From cb9bf54f65d486d8a550737224dce8232bfe0eca Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Wed, 22 Dec 2021 15:47:20 -0700 Subject: [PATCH 01/21] Abstractify purePursuit --- include/motionControl/purePursuit.hpp | 66 +++++++++++++++++++++------ include/utils/splinePath.hpp | 4 ++ src/motionControl/purePursuit.cpp | 58 ++++++----------------- 3 files changed, 69 insertions(+), 59 deletions(-) diff --git a/include/motionControl/purePursuit.hpp b/include/motionControl/purePursuit.hpp index 8025ba2c..6522ce0a 100644 --- a/include/motionControl/purePursuit.hpp +++ b/include/motionControl/purePursuit.hpp @@ -13,6 +13,30 @@ #include "chassis/omniDrivetrain.hpp" namespace Pronounce { + struct PurePursuitPointData { + Point lookaheadPoint; + Vector lookaheadVector; + Vector normalizedLookaheadVector; + double curvature; + }; + + /** + * @brief Abstract class for tracking paths, read full docstring for impelmentation details + * + * @attention PurePursuit an abstract class for tracking paths. + * It is meant to be inherited by a class that implements the + * PurePursuit::updateDrivetrain(), and PurePursuit::stop() methods. + * + * @details PurePursuit::UpdateDrivetrain() is called every loop + * iteration after setting PointData, and is responsible + * for sending inputs to the drivetrain, given a PurePursuitPointData + * struct. + * + * @details PurePursuit::Stop() is called when the drivetrain motors + * should be stopped. + * + * @authors @ad101-lab + */ class PurePursuit { private: double lookahead; @@ -20,7 +44,6 @@ namespace Pronounce { int currentPath = -1; double stopDistance; double normalizeDistance = 1; - double curvatureMultiplier = 0; PurePursuitProfile currentProfile; @@ -28,9 +51,9 @@ namespace Pronounce { double turnTarget; - OmniDrivetrain* drivetrain; Odometry* odometry; - Vector lastLookaheadVector; + + PurePursuitPointData pointData; bool enabled = false; bool following = false; @@ -40,6 +63,25 @@ namespace Pronounce { PurePursuit(OmniDrivetrain* drivetrain); PurePursuit(OmniDrivetrain* drivetrain, double lookahead); + virtual void updateDrivetrain() {} + + void updatePointData(); + + void update() { + if (!enabled) + return; + + if (paths.size() == 0 || currentPath == -1 || (paths.size() <= currentPath) || !following) { + this->stop(); + return; + } + + updatePointData(); + updateDrivetrain(); + } + + virtual void stop() {} + int addPath(Path path) { paths.emplace_back(path); return paths.size() - 1; @@ -49,6 +91,10 @@ namespace Pronounce { return this->paths; } + PurePursuitPointData getPointData() { + return this->pointData; + } + Path getPath(int index) { return paths.at(index); } @@ -87,10 +133,6 @@ namespace Pronounce { this->purePursuitProfileManager = purePursuitProfileManager; } - OmniDrivetrain* getDrivetrain() { - return drivetrain; - } - Odometry* getOdometry() { return odometry; } @@ -99,10 +141,6 @@ namespace Pronounce { this->odometry = odometry; } - void setDrivetrain(OmniDrivetrain* drivetrain) { - this->drivetrain = drivetrain; - } - bool isEnabled() { return enabled; } @@ -110,7 +148,7 @@ namespace Pronounce { void setEnabled(bool enabled) { this->enabled = enabled; if (!enabled) { - drivetrain->setDriveVectorVelocity(Vector(0.0, 0.0)); + this->stop(); } } @@ -121,13 +159,11 @@ namespace Pronounce { void setFollowing(bool following) { this->following = following; } - + bool isDone(double maxDistance) { return maxDistance > odometry->getPosition()->distance(paths.at(currentPath).getPoint(paths.at(currentPath).getPath().size() - 1)); } - void update(); - ~PurePursuit(); }; } // Pronounce \ No newline at end of file diff --git a/include/utils/splinePath.hpp b/include/utils/splinePath.hpp index 6d55480c..ef3cacba 100644 --- a/include/utils/splinePath.hpp +++ b/include/utils/splinePath.hpp @@ -5,6 +5,10 @@ #include namespace Pronounce { + /** + * @brief Smooths a list of points using splines + * + */ class SplinePath { private: std::vector points; diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index 2945841f..c3fc3dd6 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -9,27 +9,7 @@ namespace Pronounce { this->lookahead = lookahead; } - PurePursuit::PurePursuit(OmniDrivetrain* drivetrain) : PurePursuit() { - this->drivetrain = drivetrain; - this->lookahead = 0; - } - - PurePursuit::PurePursuit(OmniDrivetrain* drivetrain, double lookahead) : PurePursuit(drivetrain) { - this->lookahead = lookahead; - - } - - void PurePursuit::update() { - if (!enabled) - return; - - if (!following) { - drivetrain->setDriveVectorVelocity(Vector(0.0, 0.0)); - return; - } - - if (paths.size() == 0 || currentPath == -1 || (paths.size() <= currentPath)) - return; + void PurePursuit::updatePointData() { // Set position and path variables Path path = paths.at(currentPath); @@ -37,7 +17,7 @@ namespace Pronounce { Position* currentPosition = odometry->getPosition(); Point currentPoint = Point(currentPosition->getX(), currentPosition->getY()); - // Returns if robot is close to target to prevent + // Returns if robot is close to target to prevent little wiggles if (pathVector.at(pathVector.size() - 1).distance(currentPoint) < stopDistance) { return; } @@ -48,16 +28,8 @@ namespace Pronounce { lookaheadVector.setAngle(lookaheadVector.getAngle() + currentPosition->getTheta()); // Normalize vectors to make dot product cleaner. - Vector normalizedLastLookaheadVector = lastLookaheadVector; - normalizedLastLookaheadVector.normalize(); Vector normalizedLookaheadVector = lookaheadVector; normalizedLookaheadVector.normalize(); - - // Get the dot product of how similar the last two vectors are - double dotProduct = normalizedLookaheadVector.dot(normalizedLastLookaheadVector) - 1; - dotProduct = ((dotProduct * curvatureMultiplier) / 2) + 1; - - lastLookaheadVector = normalizedLookaheadVector; // Set the drive vector @@ -65,23 +37,21 @@ namespace Pronounce { // PID controller behaves the same for different lookahead paths double magnitude = lookaheadVector.getMagnitude(); double mappedMagnitude = std::clamp(map(magnitude, 0, lookahead, 0, normalizeDistance), 0.0, normalizeDistance); - - currentProfile.getLateralPid()->setPosition(0); - currentProfile.getLateralPid()->setTarget(mappedMagnitude); - - double lateralPower = currentProfile.getLateralPid()->update(); - Vector moveVector = Vector(lateralPower, lookaheadVector.getAngle()); - - currentProfile.getTurnPid()->setPosition(angleDifference(0, currentPosition->getTheta())); - currentProfile.getTurnPid()->setTarget(angleDifference(0, turnTarget)); + Vector normalizedLookaheadVector = Vector(mappedMagnitude, lookaheadVector.getAngle()); - // Print the turn target - printf("currentPosition: %f \n", angleDifference(0, currentPosition->getTheta())); - printf("turnTarget: %f \n", angleDifference(0, turnTarget)); + // Calculate curvature + double a = -tan(currentPosition->getTheta()); + double b = 1; + double c = tan(currentPosition->getTheta()); - double turnPower = currentProfile.getTurnPid()->update(); + double curvature = abs((a * lookaheadVector.getCartesian().getX()) + (b * lookaheadVector.getCartesian().getY()) + c) / sqrt(pow(a, 2) + pow(b, 2)); + double side = signum_c((sin(currentPosition->getTheta()) * lookaheadVector.getCartesian().getX()) - (cos(currentPosition->getTheta()) * lookaheadVector.getCartesian().getY())); + double signedCurvature = curvature * side; - drivetrain->setDriveVectorVelocity(moveVector.scale(dotProduct), turnPower); + this->pointData.lookaheadPoint = lookaheadPoint; + this->pointData.lookaheadVector = lookaheadVector; + this->pointData.normalizedLookaheadVector = normalizedLookaheadVector; + this->pointData.curvature = signedCurvature; } PurePursuit::~PurePursuit() { From acd7f205ae7d3177557b530e1eb40a0bf3f3a8e4 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Wed, 22 Dec 2021 16:19:20 -0700 Subject: [PATCH 02/21] Add OmniPurePursuit --- include/main.h | 1 + include/motionControl/omniPurePursuit.hpp | 32 +++++++++++++++ include/motionControl/purePursuit.hpp | 21 +++++++--- src/main.cpp | 2 +- src/motionControl/omniPurePursuit.cpp | 48 +++++++++++++++++++++++ src/motionControl/purePursuit.cpp | 13 +++--- 6 files changed, 105 insertions(+), 12 deletions(-) create mode 100644 include/motionControl/omniPurePursuit.hpp create mode 100644 src/motionControl/omniPurePursuit.cpp diff --git a/include/main.h b/include/main.h index 5a027de4..9c06ce88 100644 --- a/include/main.h +++ b/include/main.h @@ -68,6 +68,7 @@ // Motion control #include "motionControl/purePursuit.hpp" +#include "motionControl/omniPurePursuit.hpp" // Odometry #include "odometry/mecanumOdometry.hpp" diff --git a/include/motionControl/omniPurePursuit.hpp b/include/motionControl/omniPurePursuit.hpp new file mode 100644 index 00000000..4449b095 --- /dev/null +++ b/include/motionControl/omniPurePursuit.hpp @@ -0,0 +1,32 @@ +#pragma once + +#include "chassis/omniDrivetrain.hpp" +#include "purePursuit.hpp" +#include "utils/vector.hpp" +#include "odometry/odometry.hpp" + +namespace Pronounce { + class OmniPurePursuit : public PurePursuit { + private: + OmniDrivetrain* drivetrain; + public: + OmniPurePursuit(); + OmniPurePursuit(OmniDrivetrain* drivetrain); + OmniPurePursuit(OmniDrivetrain* drivetrain, double lookaheadDistance); + OmniPurePursuit(OmniDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance); + + void updateDrivetrain(); + + void stop(); + + OmniDrivetrain* getDrivetrain() { + return drivetrain; + } + + void setDrivetrain(OmniDrivetrain* drivetrain) { + this->drivetrain = drivetrain; + } + + ~OmniPurePursuit(); + }; +} // namespace Pronounce diff --git a/include/motionControl/purePursuit.hpp b/include/motionControl/purePursuit.hpp index 6522ce0a..d56437d2 100644 --- a/include/motionControl/purePursuit.hpp +++ b/include/motionControl/purePursuit.hpp @@ -2,6 +2,7 @@ #include #include +#include #include "pid/pid.hpp" #include "utils/path.hpp" #include "utils/position.hpp" @@ -10,9 +11,12 @@ #include "utils/purePursuitProfileManager.hpp" #include "utils/purePursuitProfile.hpp" #include "odometry/odometry.hpp" -#include "chassis/omniDrivetrain.hpp" namespace Pronounce { + /** + * @brief Struct to store the information that is used to control the robot. + * + */ struct PurePursuitPointData { Point lookaheadPoint; Vector lookaheadVector; @@ -21,7 +25,7 @@ namespace Pronounce { }; /** - * @brief Abstract class for tracking paths, read full docstring for impelmentation details + * @brief Abstract class for tracking paths. Read full docstring for impelmentation details * * @attention PurePursuit an abstract class for tracking paths. * It is meant to be inherited by a class that implements the @@ -60,8 +64,7 @@ namespace Pronounce { public: PurePursuit(); PurePursuit(double lookahead); - PurePursuit(OmniDrivetrain* drivetrain); - PurePursuit(OmniDrivetrain* drivetrain, double lookahead); + PurePursuit(Odometry* odometry, double lookahead); virtual void updateDrivetrain() {} @@ -125,6 +128,14 @@ namespace Pronounce { this->normalizeDistance = normalizeDistance; } + PurePursuitProfile getCurrentProfile() { + return this->currentProfile; + } + + void setCurrentProfile(PurePursuitProfile profile) { + this->currentProfile = profile; + } + PurePursuitProfileManager getPurePursuitProfileManager() { return purePursuitProfileManager; } @@ -166,4 +177,4 @@ namespace Pronounce { ~PurePursuit(); }; -} // Pronounce \ No newline at end of file +} // Pronounce diff --git a/src/main.cpp b/src/main.cpp index c6ccd7f8..0bda1460 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -38,7 +38,7 @@ ThreeWheelOdom odometry(&leftOdomWheel, &rightOdomWheel, &backOdomWheel); MecanumDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, &backRightMotor, &imu, &odometry); -Pronounce::PurePursuit purePursuit(&drivetrain, 10); +Pronounce::OmniPurePursuit purePursuit(&drivetrain, 10); MotorButton leftLiftButton(&master, &leftLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); MotorButton rightLiftButton(&master, &rightLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); diff --git a/src/motionControl/omniPurePursuit.cpp b/src/motionControl/omniPurePursuit.cpp new file mode 100644 index 00000000..43ab661e --- /dev/null +++ b/src/motionControl/omniPurePursuit.cpp @@ -0,0 +1,48 @@ +#include "omniPurePursuit.hpp" + +namespace Pronounce { + OmniPurePursuit::OmniPurePursuit() : PurePursuit() { + drivetrain = new OmniDrivetrain(); + } + + OmniPurePursuit::OmniPurePursuit(OmniDrivetrain* drivetrain) : PurePursuit() { + this->drivetrain = drivetrain; + } + + OmniPurePursuit::OmniPurePursuit(OmniDrivetrain* drivetrain, double lookaheadDistance) : PurePursuit(lookaheadDistance) { + this->drivetrain = drivetrain; + } + + OmniPurePursuit::OmniPurePursuit(OmniDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance) : PurePursuit(odometry, lookaheadDistance) { + this->drivetrain = drivetrain; + } + + void OmniPurePursuit::updateDrivetrain() { + // Get the lookahead vector from the pointData + Vector normalizedLookaheadVector = this->getPointData().normalizedLookaheadVector; + + // Set the lateralPid values + this->getCurrentProfile().getLateralPid()->setTarget(normalizedLookaheadVector.getMagnitude()); + this->getCurrentProfile().getLateralPid()->setPosition(0); + + // Get the lateralPid output + double lateralOutput = this->getCurrentProfile().getLateralPid()->update(); + + // Get the turn target + this->getCurrentProfile().getTurnPid()->setTarget(this->getTurnTarget()); + this->getCurrentProfile().getTurnPid()->setPosition(this->getOdometry()->getPosition()->getTheta()); + + // Get the turn output + double turnOutput = this->getCurrentProfile().getTurnPid()->update(); + + // Send values to the drivetrain + drivetrain->setDriveVectorVelocity(Vector(lateralOutput, normalizedLookaheadVector.getAngle()), turnOutput); + } + + void OmniPurePursuit::stop() { + drivetrain->setDriveVectorVelocity(Vector(0.0, 0.0)); + } + + OmniPurePursuit::~OmniPurePursuit() { + } +} // namespace Pronounce diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index c3fc3dd6..66f6128a 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -3,12 +3,19 @@ namespace Pronounce { PurePursuit::PurePursuit() { this->setPurePursuitProfileManager(PurePursuitProfileManager()); + this->odometry = new Odometry(); } PurePursuit::PurePursuit(double lookahead) : PurePursuit() { this->lookahead = lookahead; } + PurePursuit::PurePursuit(Odometry* odometry, double lookahead) { + this->setPurePursuitProfileManager(PurePursuitProfileManager()); + this->odometry = odometry; + this->lookahead = lookahead; + } + void PurePursuit::updatePointData() { // Set position and path variables @@ -27,12 +34,6 @@ namespace Pronounce { Vector lookaheadVector = Vector(¤tPoint, &lookaheadPoint); lookaheadVector.setAngle(lookaheadVector.getAngle() + currentPosition->getTheta()); - // Normalize vectors to make dot product cleaner. - Vector normalizedLookaheadVector = lookaheadVector; - normalizedLookaheadVector.normalize(); - - // Set the drive vector - // Map the magnitude to the distance from the lookahead distance to make sure that the robot's // PID controller behaves the same for different lookahead paths double magnitude = lookaheadVector.getMagnitude(); From 52ff9351442310a1f492fcc0737f751866f9ae70 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Wed, 22 Dec 2021 20:11:33 -0700 Subject: [PATCH 03/21] Change main.cpp to tank drive --- include/chassis/omniDrivetrain.hpp | 2 +- include/chassis/tankDrive.hpp | 116 +++-------------------------- src/chassis/tankDrive.cpp | 89 +++------------------- src/main.cpp | 43 ++++++----- 4 files changed, 43 insertions(+), 207 deletions(-) diff --git a/include/chassis/omniDrivetrain.hpp b/include/chassis/omniDrivetrain.hpp index 59d98db5..059e7397 100644 --- a/include/chassis/omniDrivetrain.hpp +++ b/include/chassis/omniDrivetrain.hpp @@ -10,7 +10,7 @@ namespace Pronounce * Omnidirectional drive type, used for X-Drive/Mecanum drive */ class OmniDrivetrain : public Drivetrain { - protected: + private: public: OmniDrivetrain(); diff --git a/include/chassis/tankDrive.hpp b/include/chassis/tankDrive.hpp index ce2878e4..b9b91fbb 100644 --- a/include/chassis/tankDrive.hpp +++ b/include/chassis/tankDrive.hpp @@ -1,119 +1,23 @@ #pragma once -#include -#include +#include "api.h" #include "drivetrain.hpp" -#include "odometry/tankOdom.hpp" -#include "pid/pid.hpp" -#include "okapi/api.hpp" #include "utils/utils.hpp" -#include "position/avgOdom.hpp" namespace Pronounce { - class TankDrivetrain : public Drivetrain { - private: - bool enabled = false; + class TankDrivetrain : public Drivetrain { + private: - TankOdom* tankOdom; + public: + TankDrivetrain(); + TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); - Position* targetPosition; - Position* startingPosition; + void skidSteerVelocity(double speed, double turn); - PID* turnPid; - PID* movePid; + void tankSteerVelocity(double leftSpeed, double rightSpeed); - double angle; - double prevAngle; - - double nullRotationDistance = 10.0; - double maxVoltage = 127.0; - - double speedThreshhold = 2.0; - double errorThreshhold = 0.5; - - double turnThreshhold = 2.0; - double turnErrorThreshhold = 5.0; - public: - TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); - void reset(); - - void update(); - - void waitForStop(); - - bool getStopped(); - - void setAngle(double angle) { - this->angle = angle; - } - - double getMaxVoltage() { - return this->maxVoltage; - } - - void setMaxVoltage(double maxVoltage) { - this->maxVoltage = maxVoltage; - } - - bool getEnabled() { - return enabled; - } - - void setEnabled(bool enabled) { - this->enabled = enabled; - } - - TankOdom* getTankOdom() { - return tankOdom; - } - - void setTankOdom(TankOdom* tankOdom) { - this->tankOdom = tankOdom; - } - - PID* getTurnPid() { - return turnPid; - } - - void setTurnPid(PID* turnPid) { - this->turnPid = turnPid; - } - - PID* getMovePid() { - return movePid; - } - - void setMovePid(PID* movePid) { - this->movePid = movePid; - } - - Position* getPosition() { - return this->tankOdom->getPosition(); - } - - void setStartingPosition(Position* position) { - this->tankOdom->setPosition(position); - this->startingPosition = startingPosition; - this->imu->set_rotation(position->getTheta()); - angle = NAN; - } - - void setPosition(Position* position) { - this->tankOdom->setPosition(position); - } - - Position* getTargetPosition() { - return targetPosition; - } - - void setTargetPosition(Position* targetPosition) { - this->startingPosition = this->getPosition(); - angle = NAN; - this->targetPosition = targetPosition; - } - - ~TankDrivetrain(); - }; + ~TankDrivetrain(); + }; } // namespace Pronounce diff --git a/src/chassis/tankDrive.cpp b/src/chassis/tankDrive.cpp index f9f49f92..7b43d473 100644 --- a/src/chassis/tankDrive.cpp +++ b/src/chassis/tankDrive.cpp @@ -1,90 +1,23 @@ #include "tankDrive.hpp" -std::shared_ptr visionLogger = std::make_shared( - okapi::TimeUtilFactory::createDefault().getTimer(), - "/ser/sout", // "/usd/visionLog.txt", - okapi::Logger::LogLevel::debug // Show everything - ); - namespace Pronounce { TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu) { - MotorOdom* leftPivot = new MotorOdom(frontLeft, 2); - MotorOdom* rightPivot = new MotorOdom(frontRight, 2); - AvgOdom* odomWheels = new AvgOdom(new std::list(leftPivot, rightPivot)); - this->tankOdom = new TankOdom(odomWheels, imu); - - this->targetPosition = new Position(); - this->startingPosition = new Position(); - - this->turnPid = new PID(0, 0, 0, 0, 0); - this->movePid = new PID(0, 0, 0, 0, 0); + } - void TankDrivetrain::reset() { - this->tankOdom->setPosition(startingPosition); - this->tankOdom->reset(); + void TankDrivetrain::skidSteerVelocity(double speed, double turn) { + this->frontLeft->move_velocity(speed + turn); + this->frontRight->move_velocity(speed - turn); + this->backLeft->move_velocity(speed + turn); + this->backRight->move_velocity(speed - turn); } - void TankDrivetrain::update() { - - if (!enabled) { - return; - } - - tankOdom->update(); - - Position* currentPosition = tankOdom->getPosition(); - - bool reversed = this->targetPosition->getTheta() < 0; - - double xDiff = this->targetPosition->getX() - currentPosition->getX(); - double yDiff = this->targetPosition->getY() - currentPosition->getY(); - - double angleToTarget = toDegrees(atan2(yDiff, xDiff)); - double robotAngleToTarget = fmod(angleToTarget - imu->get_heading() + 360, 360.0); - bool flipDistance = -90 < fmod(robotAngleToTarget, 360.0) < 90;// Allow the robot to reverse when it passes the target - - double distance = sqrt(pow(xDiff, 2) + pow(yDiff, 2)) * (flipDistance ? -1 : 1) * (reversed ? -1 : 1); - double linearPosition = sqrt(pow(this->targetPosition->getX() - this->startingPosition->getX(), 2) + pow(this->targetPosition->getY() - this->startingPosition->getY(), 2)) - distance; - double angle = nullRotationDistance < distance ? angleToTarget + (reversed ? 180 : 0) : prevAngle; - this->prevAngle = angle; - - this->movePid->setPosition(linearPosition); - this->movePid->setTarget(isnan(this->angle) ? distance : linearPosition); - this->turnPid->setPosition(imu->get_rotation()); - this->turnPid->setTarget(isnan(this->angle) ? angle : this->angle); - - double lateral = std::clamp(this->movePid->update(), -127.0, 127.0); - double turn = this->turnPid->update(); - - visionLogger.get()->debug("imu angle: " + std::to_string(turnPid->getPosition()) - + " robotAngleToTarget:" + std::to_string(robotAngleToTarget) - + " X:" + std::to_string(currentPosition->getX()) - + " Y:" + std::to_string(currentPosition->getY()) - + " TargetX:" + std::to_string(targetPosition->getX()) - + " targetY:" + std::to_string(targetPosition->getY()) - + " heading:" + std::to_string(imu->get_heading()));// std::clamp(lateral, -maxVoltage, maxVoltage))); - - this->getFrontLeft()->move(std::clamp(lateral + turn, -maxVoltage, maxVoltage)); - this->getBackLeft()->move(std::clamp(lateral + turn, -maxVoltage, maxVoltage)); - this->getFrontRight()->move(std::clamp(lateral - turn, -maxVoltage, maxVoltage)); - this->getBackRight()->move(std::clamp(lateral - turn, -maxVoltage, maxVoltage)); - } - - bool TankDrivetrain::getStopped() { - // Derivitive ~= speed - return abs(this->movePid->getError()) < errorThreshhold && - abs(this->turnPid->getError()) < turnErrorThreshhold; - } - - void TankDrivetrain::waitForStop() { - if (!enabled) - return; - - while (!this->getStopped()) { - pros::Task::delay(20); - } + void TankDrivetrain::tankSteerVelocity(double leftSpeed, double rightSpeed) { + this->frontLeft->move_velocity(leftSpeed); + this->frontRight->move_velocity(rightSpeed); + this->backLeft->move_velocity(leftSpeed); + this->backRight->move_velocity(rightSpeed); } TankDrivetrain::~TankDrivetrain() { diff --git a/src/main.cpp b/src/main.cpp index 0bda1460..42782dd9 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -25,6 +25,10 @@ pros::ADIDigitalIn frontGrabberBumperSwitch(2); // Inertial Measurement Unit pros::Imu imu(5); +// #define VEX_ROTATION_ODOM + +#ifdef VEX_ROTATION_ODOM + pros::Rotation leftEncoder(12); pros::Rotation rightEncoder(14); pros::Rotation backEncoder(13); @@ -34,9 +38,21 @@ Pronounce::TrackingWheel leftOdomWheel(&leftEncoder); Pronounce::TrackingWheel rightOdomWheel(&rightEncoder); Pronounce::TrackingWheel backOdomWheel(&backEncoder); +#else + +pros::ADIEncoder leftEncoder(2, 1, true); +pros::ADIEncoder rightEncoder(4, 3, true); +pros::ADIEncoder backEncoder(6, 5, false); + +Pronounce::AdiOdomWheel leftOdomWheel(&leftEncoder); +Pronounce::AdiOdomWheel rightOdomWheel(&rightEncoder); +Pronounce::AdiOdomWheel backOdomWheel(&backEncoder); + +#endif // VEX_ROTATION_ODOM + ThreeWheelOdom odometry(&leftOdomWheel, &rightOdomWheel, &backOdomWheel); -MecanumDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, &backRightMotor, &imu, &odometry); +TankDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, &backRightMotor, &imu); Pronounce::OmniPurePursuit purePursuit(&drivetrain, 10); @@ -436,9 +452,11 @@ void initDrivetrain() { backOdomWheel.setRadius(3.25/2); backOdomWheel.setTuningFactor(1); +#ifdef VEX_ROTATION_ODOM leftEncoder.set_reversed(true); rightEncoder.set_reversed(false); backEncoder.set_reversed(false); +#endif // VEX_ROTATION_ODOM odometry.setLeftOffset(3.25); odometry.setRightOffset(3.25); @@ -722,34 +740,15 @@ void opcontrol() { if (driverMode > 0) { // Filter and calculate magnitudes int leftY = filterAxis(master, ANALOG_LEFT_Y); - int leftX = filterAxis(master, ANALOG_LEFT_X); int rightX = filterAxis(master, ANALOG_RIGHT_X); - leftXAvg.add(leftX); - leftYAvg.add(leftY); - rightXAvg.add(rightX); - - leftX = leftXAvg.getAverage(); - leftY = leftYAvg.getAverage(); - rightX = rightXAvg.getAverage(); - - Vector driveVector = Vector(new Pronounce::Point(leftX, leftY)); - if (driverMode == 1) { - driveVector.setAngle(driveVector.getAngle()); - } - else { - driveVector.setAngle(driveVector.getAngle() + toRadians(imu.get_rotation())); - } - - // Send variables to motors - drivetrain.setDriveVectorVelocity(driveVector, rightX); + drivetrain.skidSteerVelocity(leftY, rightX); } else { - int leftX = filterAxis(master, ANALOG_LEFT_X); int leftY = filterAxis(master, ANALOG_LEFT_Y); int rightY = filterAxis(master, ANALOG_RIGHT_Y); - drivetrain.setDriveVectorVelocity(Vector(new Pronounce::Point(leftX, (leftY + rightY) / 2)), leftY - rightY); + drivetrain.tankSteerVelocity(leftY, rightY); } if (frontGrabberBumperSwitch.get_new_press()) { From 4c43906775b8ce2467c201c5bb01e8bc783001b5 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Wed, 22 Dec 2021 22:28:52 -0700 Subject: [PATCH 04/21] Add tank drive pure pursuit --- include/chassis/tankDrive.hpp | 11 +++++++- include/main.h | 1 + include/motionControl/tankPurePursuit.hpp | 31 +++++++++++++++++++++++ src/chassis/tankDrive.cpp | 4 +++ src/main.cpp | 4 +-- src/motionControl/tankPurePursuit.cpp | 31 +++++++++++++++++++++++ 6 files changed, 78 insertions(+), 4 deletions(-) create mode 100644 include/motionControl/tankPurePursuit.hpp create mode 100644 src/motionControl/tankPurePursuit.cpp diff --git a/include/chassis/tankDrive.hpp b/include/chassis/tankDrive.hpp index b9b91fbb..4babceb9 100644 --- a/include/chassis/tankDrive.hpp +++ b/include/chassis/tankDrive.hpp @@ -7,15 +7,24 @@ namespace Pronounce { class TankDrivetrain : public Drivetrain { private: - + double trackWidth; public: TankDrivetrain(); TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); + TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth); void skidSteerVelocity(double speed, double turn); void tankSteerVelocity(double leftSpeed, double rightSpeed); + double getTrackWidth() { + return this->trackWidth; + } + + void setTrackWidth(double trackWidth) { + this->trackWidth = trackWidth; + } + ~TankDrivetrain(); }; } // namespace Pronounce diff --git a/include/main.h b/include/main.h index 9c06ce88..d2a90f88 100644 --- a/include/main.h +++ b/include/main.h @@ -69,6 +69,7 @@ // Motion control #include "motionControl/purePursuit.hpp" #include "motionControl/omniPurePursuit.hpp" +#include "motionControl/tankPurePursuit.hpp" // Odometry #include "odometry/mecanumOdometry.hpp" diff --git a/include/motionControl/tankPurePursuit.hpp b/include/motionControl/tankPurePursuit.hpp new file mode 100644 index 00000000..7f3b8406 --- /dev/null +++ b/include/motionControl/tankPurePursuit.hpp @@ -0,0 +1,31 @@ +#pragma once + +#include "api.h" +#include "purePursuit.hpp" +#include "chassis/tankDrive.hpp" + +namespace Pronounce { + class TankPurePursuit : public PurePursuit { + private: + TankDrivetrain* drivetrain; + public: + TankPurePursuit(); + TankPurePursuit(TankDrivetrain* drivetrain); + TankPurePursuit(TankDrivetrain* drivetrain, double lookaheadDistance); + TankPurePursuit(TankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance); + + void updateDrivetrain(); + + void stop(); + + TankDrivetrain* getDrivetrain() { + return drivetrain; + } + + void setDrivetrain(TankDrivetrain* drivetrain) { + this->drivetrain = drivetrain; + } + + ~TankPurePursuit(); + }; +} // namespace Pronounce diff --git a/src/chassis/tankDrive.cpp b/src/chassis/tankDrive.cpp index 7b43d473..ab80768b 100644 --- a/src/chassis/tankDrive.cpp +++ b/src/chassis/tankDrive.cpp @@ -6,6 +6,10 @@ namespace Pronounce { } + TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu) { + this->trackWidth = trackWidth; + } + void TankDrivetrain::skidSteerVelocity(double speed, double turn) { this->frontLeft->move_velocity(speed + turn); this->frontRight->move_velocity(speed - turn); diff --git a/src/main.cpp b/src/main.cpp index 42782dd9..d6c50e20 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -54,7 +54,7 @@ ThreeWheelOdom odometry(&leftOdomWheel, &rightOdomWheel, &backOdomWheel); TankDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, &backRightMotor, &imu); -Pronounce::OmniPurePursuit purePursuit(&drivetrain, 10); +Pronounce::TankPurePursuit purePursuit(&drivetrain, &odometry, 10); MotorButton leftLiftButton(&master, &leftLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); MotorButton rightLiftButton(&master, &rightLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); @@ -464,8 +464,6 @@ void initDrivetrain() { purePursuit.setNormalizeDistance(10); - purePursuit.setOdometry(&odometry); - pros::Task purePursuitTask = pros::Task(updateDrivetrain, "Pure Pursuit"); // delay to let time for settling diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp new file mode 100644 index 00000000..d180ed66 --- /dev/null +++ b/src/motionControl/tankPurePursuit.cpp @@ -0,0 +1,31 @@ +#include "tankPurePursuit.hpp" + +namespace Pronounce { + TankPurePursuit::TankPurePursuit() : PurePursuit() { + drivetrain = new TankDrivetrain(); + } + + TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain) : PurePursuit() { + this->drivetrain = drivetrain; + } + + TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain, double lookaheadDistance) : PurePursuit(lookaheadDistance) { + this->drivetrain = drivetrain; + } + + TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance) : PurePursuit(odometry, lookaheadDistance) { + this->drivetrain = drivetrain; + } + + void TankPurePursuit::updateDrivetrain() { + double velocity = 200; + drivetrain->tankSteerVelocity(200 * (2 + this->getPointData().curvature * this->drivetrain->getTrackWidth()), 200 * (2 - this->getPointData().curvature * this->drivetrain->getTrackWidth())); + } + + void TankPurePursuit::stop() { + drivetrain->tankSteerVelocity(0, 0); + } + + TankPurePursuit::~TankPurePursuit() { + } +} // namepsace Pronounce \ No newline at end of file From 82954f89187e22ae79b393f01dd924f64730b220 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sat, 25 Dec 2021 17:06:32 -0700 Subject: [PATCH 05/21] Add stuff --- .gitignore | 3 +- firmware/libpros.a | Bin 6963476 -> 6964326 bytes include/api.h | 4 +- include/chassis/drivetrain.hpp | 92 ++++------------ include/chassis/mecanumDrivetrain.hpp | 77 +++++++++++++ include/chassis/tankDrive.hpp | 3 +- include/main.h | 1 + include/motionControl/tankPurePursuit.hpp | 1 - include/odometry/tankOdom.hpp | 58 +++++----- include/position/avgOdom.hpp | 30 +++--- include/pros/rtos.hpp | 13 +++ include/utils/motorGroup.hpp | 125 ++++++++++++++++++++++ project.pros | 2 +- src/chassis/drivetrain.cpp | 30 +++--- src/chassis/mecanumDrivetrain.cpp | 4 + src/chassis/tankDrive.cpp | 13 +-- src/main.cpp | 96 +++++------------ src/motionControl/tankPurePursuit.cpp | 4 - src/odometry/tankOdom.cpp | 6 +- src/position/avgOdom.cpp | 12 +-- src/utils/motorGroup.cpp | 30 ++++++ 21 files changed, 371 insertions(+), 233 deletions(-) create mode 100644 include/utils/motorGroup.hpp create mode 100644 src/utils/motorGroup.cpp diff --git a/.gitignore b/.gitignore index eca0e9e9..d3cf9e0f 100644 --- a/.gitignore +++ b/.gitignore @@ -5,7 +5,6 @@ # Executables *.bin *.elf -pathTest # PROS bin/ @@ -14,4 +13,4 @@ compile_commands.json temp.log temp.errors *.ini -.d/ +.d/ \ No newline at end of file diff --git a/firmware/libpros.a b/firmware/libpros.a index 3f84e8710c36c5693779951d989f03e3fbf6fca9..672ff7a41310c91fe6f5f2c9248cc8f33dd6c312 100644 GIT binary patch delta 92436 zcmeFacYGB^+de+C=Omj-3W1!2B%}ZVLLimUk_ss4l;Za`;&-?!I`}%Rtx$ZJ$=ep#e?~^8mQG74CH3vR81u}<*xg$%wz&SJL9SI`|6}oe%s7?YUjL}L z{%OS*RL}K~M*V_1N8hf0Hf=9#0Iq+?+lv~&|KtDvHUR%0|1T<%|5-aPYW+Vf$@o7h zu76VL1=ex>qfx)O0U-asxW@iLTdse|+lw0X|8Mx$wtvK|vZD>tsN5Ouq7SRsQcJSG zT;`r&w&%=k#k#7MBTr@B6o+ z%=5ooT-1Trk=`$~`0U)s{$g?cp`&m5S@z#AE_8D0!2exwy}-`>NAzYn%CU{i|9>bh z>F{_Q^Z#Eefw_;cY{ivb_;b8cV}bv+Jg&zAa}?L}ihnQX{`@KX%f;JOznatsu)P*_zMhWq`#a=|oSKu0>;xfS>e!n@D<@>wk zbbprbFO;yFMO_RZ|GGr9ZO9^KhqB1tE4jagHM70@@T(rhp* z@PbRh2#q~oT+b^=j_sHCzgh~%v}8tcnc(k#KmLFf&Q^+4`H21f;`%3*USJ*9KN|Jl zA3)sr(d_q%i=i^~MR_r3R1R?;jt^0JaBX+HD* zUa6bT(*C5l{>=D?w#!9X+TSVnCb6{NFRni_uu|s(|U%)>#QmMh~e_GPRKVUDqRL_wMqzwBneSE>)r%bqJPrFd|bRsS!PnuU9_KQAsg96j-mO07ld z>|YnxpEOd(XDa(kWpz`#m9 zPaHayf6D%9>1>_vg#S3atC{rTFuT zKahKr*~(D1jVzFBn>Lt0@eMyQ3|tkxdhvStr#t zqLZmO z4{Xpg4{Y!VxoG-Ftx0iYKAG-WsE?@```AA?^QGTBV^6rzTqlW)wh_!?>`U=LP%VJFR zB-oYd8kg&a!=B8d3Jd=Qx$x;=Yy6Gr&QG{~;lcg#OC zUJao%aTPrIt;hbEZ#@o(3(2m{yp%gI-|MDEvg248SfX(bO{d3!v(M+y1bvY^d6cOM z$ekEGxl@y%%uY@6#B?^b4Kgr;Z-0=-Z3!LSNl;aQIQv?HU6XgU%!?A7xvQmPS)5rX z(Z7l#bJQe97i02Diw2nFOwBjsoq5zszd4MBl|w6|B-l0i@T!o^!>dB`T4UiW1HoH? ze3SYbld;5AEF^R3oB58EH#?CGy>dF=yg^cvoFErX=1Vohn$D$8MxyO->ST%pyC$!> z9G1D}a`>{5IsCh|jaZj#YUIQv%#Ii%19UaTWhu1qjs&|Ve_SMg=Ep@M->V`Al`KwP zPYlVN+dI_WXrnyteU?3$eG*Qm@~zeX3_X!_qT($10DU`sArS>p3T1{w#QxaOFho+c7wZ=ryVa~K zqrGoT;mV(z8Zd!1__*+`nxeG*Gl%Aw zqu3{1lqOM4`g^WopS+Yqvtm!N&y6E6eBSbpzt}B@&l|(yPaiZj6x*2-DivSVJcp*n zyyE&qQzPl=nZHC#UsHqm4xYUJ)e@QOUriWa*3?#ta)xBqJDRYox~U<*%)+@7FD@}P znAMQXLhmF-1)G|Fr}G78b~>8aH7tkb#`VN?p*b|0wWPFgQzO@hTVzs&)Et`jO_Da2 z$f1d!m^3=g)Sxd%=HZ=5Nq#vrA;*%^b83d2dtUS9Ez~jyPw=l2l3C<2T(T=(@l4KY z1sO0n^M)h&W$QSlrf))WMe8_aRy|%P`Nxvknh_XYMrPuKjJ{fw0Ft*YcG<`zrM$jmb; z#oh9j!CY!h$|p^8)Q4m3cl)M#TYj=1Xq#FZnNECLqy}0cNkN}kes$^`V;Lk0_ylL( zyPx_=UbA&s>%2$FhykWX)(RO}a%)vnBWvB*TQas#4o$HeCA$_dHCRTD%q>1?Q>`T; z7gqDSX-D74=7ZDH<+O^{v`U`^_tM&S&*tOE3~5KpO7fhtc}Tg;%|ps38&i}dNIPj!`R$7;EH_p}k~rl^c4Y27 zQ(@8pv#wmTofcG#GuCX9pcOiKeYux1*O#kwG05mNk{0rs29>;ynH4F(C!Y*Y&pa7k zd45uMZRV7W%F91AH8P%R_*WV5N)F8zbE{;I$e~%Er)nRo7BN1#)S0T8rOs4y85}1G zc{V!pOSLk_*~QSr53X*WZ;}KtI{D6n>X~;Q)EHqgCV8GvxMt<$W}i}X^=Qqu$CV~o zvD$8Kt#bxr$&)KBs+C!3QSJ2Jri&zOiBFyJ^K)okT3u(=kETZEPy6D!)xR_}nb1UR z%Vx%jCa!*k_YKYDQ&;O}p1PVbdV%R8^KH+u4KjOSZ+27~JE6G1iR+Z2UKe4;a{qm0;hEV64M0 zM;QyY^GeO=BMBa19LK`FT|Rvw^wjyqF^qYS_2~jBGOhzYS?;!t`!WGF3p+Aj`7VIa zQ_pWYzYa0G^XaMN{Emo-b%yddQ99NcRX6ON>8R^l+9v};YknD>`j(Bilg{U6a|q?) zpG;#cu6RD+3IV=*8GD3A9B__6vFC;-i`(BG*2-bk#Hv_l@w#D)d#EOl!sCydJhfOh z`F0J)`oM8E%3KtCO!g*!5z&R6#Y==mK2uFrLok?4wj7gfl#L+76@4I^94B0boq0UX zVciuA3p-1=Dwc(@ho|rG)BXVOdHRO+OhyB_>Ud2;qrFJTRVQxGdB$4P;k%%;6T;uZ zv-}>fLi2|HjLSr=Vmzd{VKq!w%xS-cho-dQBS=4+QmuiIelw-xNvs+3e`YjlJKh9F z8#l%2!4P#ztXm(V7cWWkz_{%K7C5ftP3Ll$VgEo&d?J<q&$i|9 z{NLjGw5i5eg04X^pX;AhHpU`JSZH-FSy*I=l7_{WD0x_7i6DacFH>W|>*$J!<IO_F|UKNK6dUd6*u%#VR$GuM+l7>a2+6x+D& zdk=~rnpjEayJnlVCt_(aXLx=|=T4=?6iGUFSxyP!d@*Nv*RnxK)Kg6Qj&c2XBc)LE zo#cA&no6PQJFRBH!=UdoCF1skr0;A_`o6Gwlk|OQjYZP;6~yfHoip1~^j+Zk*xbfg zBz@m-y@QuA7D?X~ixElRRZEogeQSx5zH62!>ARuEV$pZg8mgr4mL*F1Zs(-$JJYJ@ zyT^Ur4m3t8>3hia$hL+;()T0Re+Hj4(YmDX7p~771w{}vioRdXHbLLI;?D3=lD=n3 zYtqLwb3Mq_$h9=J8s%w>T4#>^b4p-UrnG157?zn@m42FDuZ&VCT61gqHV>sxwC2_1 zs?-fygOzB~8mi@3m0@ZW7?h+n+!7_N5fHP}n%`_o(HgDkM{HaUPM5S6)b!*b##kh+ zv8na|#w8kqLZAn^-TcV`3gqCAfCYn}7Yl@~9e9M?M zNo$&>kJ)P|B&}sMJ#4F?khE6NbXz+pGBEXu)=FlZwkJigY}1v9sf+f6SlO~lwyRoJ zxmc@ZS;hSXr-OGBUWv{E{DCNu=nQem{Mtg(`*vpRB6TS9t5Z#gxj@?}(PXlHP9{5A zJxC@yS^Y~UJ6obmuU*Wh6p^m(nqKEi)wN=>r>1vAZjxh>O!l_OkxcfnM9E}dOO#CZ zvqZ_{0BdOSL^se9C6R-)qAugiAekJTlgXi`w_uPBoiUL{8Jh{v>CxTBS3U&0M9gTCQ@H&dRY$sSD;PDuR-+ zOeb_>tTfJGYMCz5^ov!LLM_u}n*J$v(&VAYeOt{@q_Ip_D$&!(zH4%lyUrShBzL_v zNJ;Jnh}oCvM%9*i^4y~7C47vr$YuJDrq9;78jB=%yTz9zH`5X&x$jw`B=>zwl;rME zW3iU$PHU)=-CdR_$=#ik+&!jMk^3>C&S8vHl6yeY@60t6lH9|Z{_6@uA;~?a>7QYj zQaXqxR-$$Zw8pusUzHMNU8)?(WS5gW^Zj4PI@sm<0atqqz z+0$IKg_LM6+E^vx3?+BGg{@BIqAg+#Ns?O>Vs>)lRArOg;x>KP31cjh+(euHF(!mY zYm?+ATfIqgQ!G)En`()Y+>(|k$t|VEVv$?g8mc6>j3r8P%i3~~Th6p9ax2<&k2qtb za?z&S^as&~LXun6rU#BS6q4K;HvQF8P-HFIT4tMAwC78ii?*K9nv1r+uN`dqvQ(u|ymq$9J(HiYXuBxUT(sS+ z$&$^7nJazyyIJJX%&!&I7$QX;{^#hA4$?FbFl)Ub=M9J$eOO(8RsK#RP zy2l!-Prtv$Ob%YRhEtH=EwDqcIk_ zI-l9}X}HHD$0Awec9|*6)u~ycWYK1cl0~~EN*3MiGI3Ze>Pj|Or-vm<7Cr4bR;RaV zRV?PR>v8jpkxCW=?E1iRhC;F!WY>3w84Af_uw6g%EfiU+GsJ8YEdE--T%F-cYqA(& zImy+T-=2MS(!?;wM3Eh6;xX$ua)e2(p_ULlGiGBefHbNSR}92EUM({tZs>t z*BX{6d97)QlGoa5EEcbItf9))S=SOJuk~{BnqgWMuZ`^bxfaGqC9h5GdfF?7Lh{C?v0K?0SX1P-I=Hwl~{U7dRc12twtRYDY_yTcysHD7Q*othx!JQY9?f9in9= zkb4*FBHT*7gY5bz6_rAfJIt;xyrL9}+>vUI%tbp&i6*(OoaBzR#vsWZXNi*B@es3< zJ3+N&k~`V1N7{|CNOGsz_1?zd)K+P_#g`;^h9ydJXIi2p_f<=jIh6NOG6i^+vBlk(GK^m~CRw z`c*a;?P{ep7wsC$NiN#8ITkI^$Q)Bdr^?`U;62p^RflGj5Jv-5gbwPo^p%&xb8!x)R?^%J{37DUUj z$VGd~qDu1msU=EYPg|no^)pM9yq;BKv3UL58me5hUs$5#^~;>Ro-?hA*9&&N6)scd ztVv!k+w~^H4Ta?OnqB|+M?)cby=B*PM?sOr>vv|G;5DSG$?JWkHFf)kdKlGk`Q-PX`h zNL~}&^kOZc$e@Ff_alxR38ovP zs55PKH@#>(rBLM7cGEZFbVnYF+FG+5DOO)hxutZ62M@y9Cc2;At$n9bc zRW91DmMF=^Gyd#1C3=`vMQ$%Q{kkzQMQ%SgJvhx6x+Hgyo8Ai-9P(Hsxx?J_5x3wG zL=!8?9ci|SMH^q!+y{?QT658kwVV<}_nLT8GYQvKUrjaXOLx}~Usei5Up04qO^i|~ z`f9q%wdpYEtEEJDgT6ZMa&007%gfXH?m5Q#N#0ft2J{(E z+S*xTmHf50M9E(VcgY`|ft5z{sQ7!?UB6k!P)PoIyXzwY4Ta>d zpS!-TIAeLJj^b~C)#DRUsF{3ut<#vP% zy;Y#r$R}qm1B{_E_c@te4`YK*tb=M@k0$_S1S4VDBe*ryGqH-&O1tK zS1UP%xFl}Zx~u#6Cb#RX;Yx1TTcYH4Lr!itnFph|-R7<@I%kYlo=~^D>pM3X3d!yJ z?)vTBhC*_?(_Jqwiq~~|be0Qqx7D4zTe!y(V2=FH^#k`hh6FDudH`&(yFPKXQYgOfsR|a~_myn%{XoeU-w%~+@%_Vd zeE(<-SMvRnB}%@3&dK*<^I#O;Pu=ya!WgaOo9lX|r-nlEZP)dDxW6KgNAj)fx^Lsf zN~6}Yr*0-bNx8QrO3Hndh`c8$&t-{{az9H<$edN*`Oxlah6fS4oi0{A8|4a%oPdn! z+0?5v=Cl_Ho-J~d z&mrx3>wA}n;C&H{5)-#2M_`fkyK-@!5*GS&xRcqS$9p zMfcBVWiSzs(mgc^d8Zk!gUWMfrS!Yu{FWE;sy(s658sfGR7%GZt zR+&5KRa#>RYgjtt(Xhpvc0M<&jn4WF+zga$RD->N<lI2 zv5`%%#OQqso)0}op{PS0`4x^j?_7PFSliSY=cOed}z-NK@N%VgX$*z*LQE`T}vL8J;*d z5RaQV!}u%_+#Cr^9!e*!AHr$rV>Eh^DiYw-45tHN0b8l{o?L(Z6Lq|g$>}hhSoG^% zVZx0)8kr~Q12!P&9sRj}CwdBxqK9>!+t7)e=-FIP7xh{= z^Lom86Feu8s?rZFHoSlhM^VIwUn=?{fW=INrip zpmxSi1Re}C$b*1%lheZjX7#`k;Z2(*9hB47-*b|4{22~glxvCTm$Ugb*B@b-)3_f{ zo$J)Kn$1^u)Ha$;(yQ6L#Pzo(D#!eo34TV7v$j~;(it1LyuGrh$-Be#_r+J}#`Qxf zcsibPpY|oq$W%9&(Z6g`deB%_>3Z%rSMH?1gQPf`W)RTbpS z;yskBy_NZHPP2+wH@ug^n~LGBocYvbM`(J<6>73e;MoiRMIMBV&R9*KAl`3<;G88c zv~q?Om(yBW)8DPc*faPoq6!3LEo1KGw5DtN4N=(X3~L~#wU(xLdZv!>0@ZO_YfUTH zqTa%G-;?xeTI*?gH!Lbrcw>&#!Kol^i1#7Hn@(qbSFXCsLrrf>P0zJSDVk9g*?wSm z5B21dIf?~9>1eC@)Wz(pJkd?lyQVWXjoiI493CLYBqzPS7DbP(Jjp009j{$fJgR1O zCshb=SvBOW_to_LjgjO1CaFEIqEDiO8$u2*#W4iY$XH;ZHyArN z7~^D~{oocB2dcSyyw}$d7V=5Il9ZgwM~Dh-o%tI-oxzw#Xm#&iAhV!vb;d%Q=9f9r z^CtW|ZAWy5Hjn-hm~$_ED5Tc<<)0Zlvksc*(s)%H#ZD5dAkFOqJ``KpI>U=esbj!T zhYja0aO`I~^UFAqFx6mpeZ6?x)*0oZ6KH5}eHfbmhMMQ^!2Lt3$~o$!VEy;u)G&_f zbFW@+Ll~f!MY<+G{w+RkQ-$l~Te)-ZPAqhYexR0NwwFPlD9Y^B!VR@Y=<`P^a}^!~ zTahe#?TxUz^f*kYY&{*O8kV`BM+D4`Yxl>@aj!$4K^Tu1y3o!U!N-Xw?Xb`3xeCf@ z`Wt9~>hbmX*lIQ4)%p?4uj&^uRB1j6)2S?T2&#p?sh``=7;(XG!E`UnOu0UEu3iw~ zA@GbH(_3@f0x48 z9^#@4O#MtVrw&==_5)eyR(-7ar9JjSM{#K%x>G+P!aF#Ft92;?X`k-cV^lwes-K$G znb#&z9C}Q@gykZMybaTR%N$jXX#G?_Erxe+=C8CE$(XOst>I76T4yF_9~qyQ=DTn`mZ zJ30&T&0)tUO~o#l4QsV1G40H#!Z3 zMst0KsMg6DPll?_ec`aSW`5>vQ7RfKmo zt!Z38DynxzUFlqg>*vJa&dwtIORmP^$T}^8jt|y6lT~Sv$ z_u%@=ViZ{~od9rgO^q7_lS(I|4N1f+$;{JoxvVPF5D^V zba#d;sbj!Q(XYEROw)&oSGzl7<>dqNT`92}K6#A9c4{eFGZWiMaj&~Gua}v~ym|=# z9?o#SMHKIWK8*ZyRn&!)$4E!M7_60!u83hhoDr_xa~Qi)8T!IikONTc9_wj=82PEB z#+A7`Om(x&Mt<6Cn!CW%Gs|q`r)^Ieqxs+yVVag@Hu6)tV6BvW1#D}x>_||QpOW_) z)jx*maF*G~PwrEV{B#+n8(C%}KTQ<^0ci9tQHQr2~`yk}O*`cxe2nJs1Q75Cw)a+NpN z2a3pE&IBuUy(L=oGM$mSrijtKOlPF7`(i^cXPnABNK)yMdv=qPj8A>`yf9p z6}$U5qjUyRR8 zSc? zqo7pjjHX7WvsbVaW}Y<4&bfS$&YCw+>1=tE=hIpKI$7zgcrgfB>Fg@D7s2bHX%2N8 z6gx@QUazCL-ajk9tr9*1uoaNGue-ibBn&{<8oRnmqQwAbc#4tbVyHiKFq9lO{^V&BTg%JK$b#i}8Rnrdjke6@E^Rdq+DeOa-%>7o z1^m`pzFzHeAtg=LpN=!kAH#ImFc;0rmy2+6pdR>TeB3bXFdO-Dy686$+1W^scf~A{ zjBMx>n@BQpUtV#7BqP-o72lC$WVR~8XOJ_WhmqNai4udHVbzQr*5eh%QfUUS)WhZv zMNOEQ!-B3GX01LLM={Js4$CKA8-%N$a$?OO>~$WBlY^WN4`VMiTHGVaNJH_$e{fbB zx*#eHc1Fb;JEui0jBU?P=s?3xOm@Np!6S1s_fx52IvVhjB9asPQtTY;EKyv_*jUY8 zY_u@}^jWG|V1kgM1RF=~i2(n?k%#mXUAThfeV)kT~{ zB`aCA70<|OCaaR7$WT*6vU(&MSt63v8)DQ@)HRdUuVVdBWT_$I>`-ST&F?o6H_Tbz z+D5%5#t%bNX1dxhHdrEZ(irjiFf?W6q+P;&IGoL#M2Si-bUQ_+7rJ}JJc;klOMgUqxqDlsmkMp4PcI)}?U}o!gR~B<%~C)tW3|vU ze+cz2DE0;IGPBUzd6hpugG%S9Vh7oQaS^#N!7x99>2a3X z$WFtBVb0x*u@Dqh+ssatF=tkG>RL^?@QUygJ4QJJ`AKnN6jFn+U;9ja2gzlmn~V*H z`vSNxvzqoY^3Oh89T5S12TXgj%tk_r>us37g6UG0+1#BWxyahT!1OH3jFeTKE+2QN z8QU{QbMS*=%!-l33f93NL(^=g!IW;AIkjkBKHe5bMrU07?afOL_;5$jagf-L87+HnZL~LN$Bn;ST!Ul6)mzmbL*9M3HD&vqAfcG1g;jv z3YRn9yi5!hU%IlAU7wRiqIw;b7E(nbpKqY!u#(*z5jzHp&rEiGMAI?Zc48yMt7Ee5 z#5Rd{;A~w)<}YA$FrX#w$%?&WoWTKVnyib+++~DgY_^PdUsM{4H8b8Gu@53|EUt}p7ExMcy7R&@4t2~-_nD|Z4w-JP=to~u#eDkuM(iJl-B}~? zXdK#;nG9Etzln(PrifkIbWsDMm$V}7@e*RdcxOQ??;RFP$=l3(o5WE|MBeKxey~LB z#X?2?2^f^Q7fTTJCZMjF|DK4U5L3(zSAP7Vo{Z0=HV7~jMGW13G^S5_A~kv!7RM)G zOj5?BWkvBTwQJ_a%c9^!h-PjaFX}_&7ev2_&iv1Bxy0g$&O9Y$5~RD(%#-4v^ZeIv zN0+De#TKHU7Bm7Yx9k%qU@ytx~} z@V1)16~{D?!fPLD96_;@#N5`t4|_XJpMt}b509?GcGtA4hexA)ahV<7QOoxZt~o}X z5ThqKtMy7cf(;XT`<<)Z2Ja2VQ#aF=bL-e(>}cd4)0Xop*%1H5zm zrP=56hKxl{jiQ4H?bsdv>QA}ATALUvi$;8!JceyXRAtyI^#C(o>v zId=+Fo2cPHYN$%?GcH4JbrEva+zDNkyp$iNo@<3H0(D^<8JEAy(7VH*{o=udS6M3k zFhh%hU=f}rQOcp%3xB|}ewbkk4x6lvQCcdi*o2=*5O=0HJzSnkFuhT&xz}QtmT?lJ z+VEUWX5y9rTH$X|4MGU$0l==X+3;x3^S65mj~<}FPa%Z0tb_09;$GiC?nOd$@q)kJ z#PeWk;VUTZgwVo!z`f6X4u^yiGk(MkU6*QMId4)Jt_9k;dwKo>m1{e;^#yvkmsn68 zm4VSqpDz(T1(STk;vJ9+mGkNa{R%!K9g9GQd7;Ywb)bs;<~;TFHYdMA)g1MIV5}y( zZx5TD08awKU<%^P)w@3erBJPiTX!&YDClr_H+{roEaY>zD ziltfXx#$}Zi%2msfyI6uGZ_>mD;WbjA9EgZc_m|H7h;}4uC8PZ?P5$W47!1mF}6!F zuRv}kWmh6b_f1SQ479Uy!0;}|d;%FyKF#@gWx+q0}Ukf=og^Tg#3O5 znnEZ5+j`H}3B};t=DC1SIqdR0R}var3TQK-U$H1WKOhuV4rm{tGUb6z5ZY4#=nFz~ zDgs^Zg8UVd`V!zBDBXF}pedv2yIBza6#;xVH{=$^cT4%5)=ey#;mqr*x&owNlI-52 z5f1$uA@P>?2c7--hpaew169zarcs%SO=di)C5Uv0PJ|NZ=}ubqjQGCQ5esf4t$R3#rPDP zTdc3)bPo;;u_{}UPTapZRBr2WPUB}Z{Zbj@EFKE4f~KcBi>pDM)AY#Z)SL@7D#D|d z>BSdNr*3pj!||uPoqHppL&H14p-)byvfm;3@(1|4?ala}2;(fvf$A`~GUle?zt>4H7eOu1DpN~Q!c%{ zFe`ab5KnZ2I-O=qnD!l9mJ2F=Df$O?P~6#AXH@nvzqzw9A0$YSZWF?Tm=& z3*!jWK`l-<>GiTr-#El@dJ_&yEGM~`R8$Q%qAGjNxQYl^#eWu+UUxcNAAX6O6FV_9 z?ltcbJ_qS^E~QB1zo9{`Cx#~Dat+_#5XxctssqM^?}nX6!J(Mxq-K2#zc?QjmmW_Q zG=EJx)`C-p>Bz?LuK8dbUr68GRyx_FQ*Ss7w4By*xe_Pix!BX!@#`CMRC4u|eR2}D zN^rLh0r<{Dja^o)s3<(%;a|AjLl)rlSL-4c;{c~KY=vW$ycL06T#jTnLNYS7oQY$_ksiS<-~uY7dxjWej-e>%<8;}@DJ5DEIA+3l$VQNi0>`XV~?% za|}B#4r6K4f$x)Ea%If4=ZV5qz!7SNH-<;s=e)Yn?7eE&7omTdsQ7UFyB=(!>1M20 z+2tI&K4reqd{R)eP$0RgKeZ7_dYm$VmZk-8`a6=JG&l%!OLOYgu^4t z2`wQFmrXm4VcFeueFwh1K)XMRI(&6nE@Lmx*YU2M2jXtNoBl>TPL*_wscq!``6>^-w?My>Z1Ujg;EXw`;ilKdmW9;XSvXv?oUYTLbeHXO z#Rcojm^X?%7lRP?N#4J?(*Pi z?%v}uJhwU6HS#L%0awzosV4#tq1_WGc9K}CwAXOgtA`tQeiOz=rh|*qtgzG{uu0{$ z-1XKt;i=H{0~?_zvK=EbWn-P(^*#%Y#!}!=(RAXaWsh<#;O`kOmxYZ+#9P7xua>H& zREH`w$Gf|9$6UkB1&^tgmu$<8EkgY{?)m@>k`A7)fWumHs!Dyi$&i`nu9wPhgv>tJ zj%3-(l|-FI?)tB_jF`I$+bzppHqCV$4(r|Z*vj~3m{4~VHFYZ9Hsf{gd9Z~+A8Xn; z9TywV-@XP5UhhAQY*Ze`x|V~SLwOQXODNsFJXi5_&^>Q$s;%P5b;v!GPDb|s*w!uq zMQMA6f@_bi-scA3Dwrk!3-oXy=v)E)5!c^gTKK!@bO&`z600E1WA&Y@3^P9i+a=S^ ze ztH7haAW*Zsp#}3dI&;m*x z!X>Xf8h=>xqS#4f${`NFV}==04v8?9GaWdM(eO&t^lK$duV(P*V0kr@UNm*xJWAm; z!O!r+m9n={aG7GcsmA0C*VgncI58`)F04}Ne9Re!Qlisb)?Rc zME&{LK8WhL>oLVG4^4->jWLFdY12!ig4WY}@gPja9=fdJUTo#o-c*N`o~ZM|Od&XfAfF6uaIT%4`v8~;O-2S%8NbJUzsCrCHuDo$cKk4}9WVmlS=XpuS=YOw&0<`%1bq#= z`xx$XcNk;QSJ8<36rPVp8E~L8gl$|O_8Vh1SQAjV9j7Rs4#c7lVd1!s=f!AEd6F@j z-Vt^eya2sTr>gJ8A1?%{>H~9B=OnUd*X&%V@*0o7ISu!vKYIq@IR5aX5pG&o?$o#H zGJu{uy5Hscf@6511NAO4d0|K_;KVO5{mk{nPBqdmEK@Z7in04d9!_&7uk&fdEbQBD zm~Ibyai2R#9dR3=vZv^Wu>?gO>DNFv7%-2rK4teixt3S z6%Gjmt{6f;au@DA1^kkOd;%x+Q;%_3*aw(EUbK@>!BKEIxDYN~rAxT1+Cx(#B@Zj>La9I|*=RVU1r?%~Znv!EEOJDZnmcmZk7#?a<>$7Pi)=+M(OKW;?%N zpe9)o|5-B+;LQ5Y#Fk(E_PQ%B(PIM|i>yYuBJ%SDv>(|LDNDm%5c+p{@zz+)so~_r z(!NA8_6Q;@QgtzsyxH10KIHG~#=|Id{lZwcqlRN*X{39*8axOHx; z6#5Nm3i2nY@KWgYtlF*h!Pl|zfGdB?h0o!?piG5R|U zuU#TVuzqAIPup&cEQk+B#mJBoD|nNM4V(7D)DB zg*@DT!-k@ehkff7#@^#a6JdUr+uD-(eO?(oMn8BHy3Rb9I`Eml9(lJ&@G;;*+`S1# z=JSdRr?L1r$3?002*FjLPkM2v(i{{;g*3N@r!YRkJ~u%}eCZJS?Xg0dUVk1`zr6xg zT?gH)C}em0@D5aTAr)UggqB1hyS}9fonnD~&S0kz-_=3K;`78GxO+%r=v{?8^w?w2 z?dk~Kq;MLX&!XGFQzB?kKD{3TFNu&N_+};WvivjxpMtZ2w?|OdKC7w%zn5S3vnvVs zP=xHK2o5p+NPgyajl50to?NAcynw|HeW-rn>n1NG{B^{}&J-bEfmSfNup%$xq1gW_x4@K2^QJ1as5 z(gv_NHEcsSYk}9=Y*6jM#)MyL2e%Sz669UnK3Odj3@73ZYzgwpx%8h<;#$yPxM3ptpg1IUkhCMAv9-eo)7_!D$ zyhqrsh1et{l=E0kj-SNCqk^Xz_=p)0DoVlbeey1Zm!#m~{SM|Jp^_AQypPk!(xu?< zeX0V4%2EjO-d_qEh6=S;{Ihlokot=55eU6HZQStwOM3f&dF+oGpNUn-V+!Yf+B9Sp|9ul+?xQ?=lNn6d(XQ@25y zruos-*6>^S4AOM17_FNOzgg2E&Co)Zqh52rRYdztEiVnFn_nbN&8tf4>$k^+#Fa2h zi9`K9p~1YS<)h>=#&7J8kY3k{G?dNY zN02=e=4sx+lkhB_zfl*`a?Lv)i;?-Q8Um@Srq;G!P3%7tdTQPaF@C$>+AUHFBFV$= z={+e$kmTd{F$HFC&4Z@Tzp0#rJ3@GF2*P{IH$Zv)s;{08lX zG)UP>`HiMY8KM>J09!e~ycHk~*K*S$f64DnF>|9cU$c{Wpd6(Ib%RSCzq+>|jZxJz z{FWk1C5+WPiSEXJE7w9=q3J$2&gQLYRVA#}a??Vp!CU`U4B{FskXBwD-n#UhP58r{ zmLg&k{`{+RU!-!{p?KI&BNCHE)lGPXE?ErR&YK%EZ zD9k+sCc{sz*rGgu1m@Qt+y8_(E@#y4_qp)e>&jC7MLp$hl-nksanbyJmxkbnx` zL8_)CcfS>){$}TB9xG04cGhswd%OwBwqRNygY`!cQf%QrK`3$q!`*=?naNq63*~Va zD5$_Dh?z>R=chY3v^hbvPxX0}L5CSco6Wua9nhuzb(G|` zntSLpJaj#d5OPHxZ-V8Cj$bYU?`~SmFL1Bsky3#F=#Tq=@bh-$1*Zj7^hEUU+>50Y zQU}g_f(F7AYm0>&>J;TOu(Za@I^xzAXK3hHOk_&Dtrgk*QxbV4B(F?mkJ#!AEnBDo z>?yWaq4F8A6u7kCC%_)|Gx$uV+`XtRjEDU$6d&6xT27z;ac=|zL z{yVsmBCtLHM^9iGTHH@yJl6eb0@uPAyG-CEkanNI#b+3n9Uw9j!zIuIi#me9lCN-@ zCy=lkD+<7+)tZlAVjxv@1X@c1@o`8D1m=H@%`E|s4tR@(K)a9eM3KN(*lb)U(C-ps zKN3g{LYTOb4?cnjJbQ$DPXy}k!}=pIJQYVzAm9MDs03VIu#F{@do50L1cE-nt5*bC zU&9R>0zWX$b`dE28q$e7z|pIC&xyc-tvFK>2swot@dO+(SiuCgqrp}Ld@;mv1U^}Y z%WeWUzQ^Pd80bPwTqZOcyRG{K-bMyuI>3&%F?$52?7-|1D21c1FF{XiYX}U$fO-+Y zJvla#KtaR?{q&2*zhP`1f!X&!qSPG2W|ctG3Anl?z-qbhsKo=Q)gdfe0yFzFR*FEE zQHUJ^og?v(oWKcO(RU`W2xoxl1O|BHPA`E=XYm>nf!H5#l|taBevJJ}AR4D2FHe9X zIMfgV%Ua`vOki{ s?SSJ6;60+Sx&9v*=Je_ZDi(0^p?O#)tcw_yc=yyF<#Mj#b; zoIfIfx1ZQ40{6f|0WW~h5e>-%IwA z1S)pI>Lkzs+mK!adZE@x0^cCpOe0X)j`$)l;w8ivf!OYdF9IKd;DZEWX5q#-fnZGj zw*-n{K&5a@+RxJvUb!g$jK?{?DXH{Ah%W;7cHu@mf$u9KDHB+Pv+P;|o$#B-cL;bo z5MKnI-9dbTQq7JQLkNt)bQUHs_X}K96Zo_+vN(b7^C7$le6s=J1>n-kV0pYrs@7ZZ zS}1{`-yyyToL`HCO`sllJw;$0rtlJh)yQ#o2{cCc>4;UWnJ40lfDRVg5$Jdy_k##@ zn1{dcB0ztLHiN*d`gnnWfUD^M#22AgmLk3a0G6U!5P_SR;TQrpaE?eKFrpP+2qv() z88(6hDkIyBB{1VE;)_7o7{nKWo7a%O2y}gb@FLI_v>qcc_dSFcffQF!Je4HW7m4f_ z0`y*Coj`!Sv4}4M)vyG55coPT;)_5HB=#v%gYXsvHiEL<1O_G`Qn0YJj}SV31iW#q z5d;zuaq$E;0+b{0I=zflo6v`=k^BkV!tkdNI5QdXMPNx|#210$4G>=hK0}KK2@J$I z&Ju`oBEAR=#wE-n0`DPP*pLLYk%|2;1;U2B~b7TUWFv^GNNHIfpK7JBY{nb%3TCXjz@eEXx9w!MZm8o!izx53J5O( zcQ8Z`6fOQ;+(&hQf33=C#22ZC;y8y9_~A#y7lDRvA-)K_9F6zO2)Hf6Z8HMi3mN;G zz;VoHL9}{Z}1$YI47D(WBdB&m${QNrNi@+2_+;{>9-$8g0 z*jx?aMc~2LcqgG9z6iA4j`$+5A6tP= z1kS&K7hnj~K>`>@zzNE>5!eByJ|b{xD8h?CgBb`f0!z{0T>`GnXz?kbN1r3U!T{PI z#bq^tjA-o7&nSk&j@P%t2;)~FG%Mo7$#^PfXfkX^;I)Thnh%W+fq#?ctY(i=~M_@9- z>K1|C2)$njT#iC~MF1o>Lwpe^xDgv_0@D$~sRVYOMR*bDw-)gy2wlf(Yby!#XpHzG zFtisoYXp9{g3TI%FVX&E0yA+`<*-t~EWlY#gma3&M+Mc~mE#1~ev*5N#!1P~CH5MKliqSpihg;wJQ z76Kjth%W+#G3ccPj+aDy5xDRb!i&I?bnMj#tOT3q33NV%__Jfav=bn&8i8_%*d_!H zBbRp~umG_$fWXIf5MKn^ypP|uAkb$&b{Pcbbf27#6s z@i_t+gYXML1k!&3_XHY@z;#&xfXxqZrA=TuoMQzz|KX2vh+bJqWzg z61kGV5agCA1pHSZmI+iZfm}(TKh9zA5~wo`sf7S#=N}1FZHtF=h)kFEUMTL918Id@ zVVw}zTpjC#K>A7iaV~);>u?21pqM8fdJ&lHgQf{IKn(69P$L=3gg`5hc$q*C>~`)G zcnwUkSb*h-%2)!Y60uAOxVqtUD50L1-N^(N5f-Cz5uz&&Gt<3+cRoM9n-DnnHu z=qaf_*aloIcfeTS>S7_xuG8b7Di>6PRL>Cisg;9v5dImfGPOpYgM>HXl#*IE=rrMP z_CVh-&qczXs9Q3RqZQ$Ha7-o3=a>5Sgeyc!ea1E5 z>Plala1EuuPXld`e-_ov>(rhc8}B^ z&(eAf78(1TL3qWY^FC)J?=L3pbLJ2GrY?LRdQc}77ooSyQ;ZMhyFl#Sho9ctFRsB+ z%k!bo_v44T=7~c4osqTI;`~|ajypZDI7ju=DBq2O_6ynbeM?*Ct#oL=l-k;Dv0_Wz z_w-wAb+b;qw%?ghw8>oj!e+ zzHA5Z4iB<#CU509Z!nMf-qnZ=G1Cl1Ts61{!cnUpIv5{|cJN51a&McffY)d-P+ukhio z!_-c;;fcuL^nu%dYiXFjiPw%ei)y@(*mcAif?v1!{D?D+hY7!4W*cD%u>wWJF@UmmVc62d>Onxd2t3;8A@H_TyyAR{6Tvbj+C& zys;iUW=M~rrU&y)6OS=0zFdSJ$5$IshQ11mmdBk%!{#EyOD~i)B39*Wvxr!79EX@7 z_8!M9IK|ggt)uu2Uz-2-BK(9iLi4#M%HzA)$6L@$OL<)Ps2L)h`3|J0cwcJ$S7&dW z(=jmLn(bi!KptxX*{z8(?5o7q6V8ftzQVFC{r~lKAJ9=$@59GuHk(EYfg}V-AOWe7 z76_e?&;!zYNdi%N2LS<*r58bpltBRnlpjj3h9ZbGl_E_96qF`KM5!W0d7o$In-DnX z|L!?6pL?HM=1$$&&F-d%Y4_BKho}YM`qYL=!2G7 z2}flkU%4PP7TGoKyj0_(WGVW{E(-iS`J*Ds2s#~ts6&E zc6*{c(ovOav3>*ONj>1|e7W^1WuN9ozzw-bR4Z*~+yU2R^HeKiXZ!*h$Q^IBvUVmg zAfT#b%GsHafKKurT(vkm6BdwhN=nMxnY;m!vn5l(&O`+SOq5K#WTb6OK)PIEt5vj% ziUbVqESXAv`Uj2@0pEK`rm~$W8L&>CoU2u_GqC|1tn}mZA;Nr%Bv##yl@9n*4$W#c z>`a*e{UTkp1UpkUV5r=mRI6!c$^}dsDVan&6BqFFF3BX>neqV*XGx}(ov9G;cZ6hW z+nM-)dUDCCR>#iBccmK*mRw8U)l;lT$K?k!idumuQVJCPZ?s`lUmLYZHe}$>f68lu zm>|8bhPd_fCL!)5xqP|0TTM^M!8y$upd7Sjok%G!?f0HYsZw#8JU=JovD*Y5mi7se zb~>oiAxRgp52H1!IY`Zsk}`sP23X}zrsRw0GfJw+nn~~%t>RpsKexJ^l;1B4vgBT- ziw@yunY;8g)+_09yJ_B(xwmX#!|3p%EU#vPfaV(wW2X6rQFB;8r?v9NPir|O6G!KW zl&#!2qJg9*=BOg+*M`Z_mblBO^BP%}78+F#eJvl@k|}Ya=~K10+;ZxaI9)QH47dEX zK&He`Bo|jf{(LS|;&9WyYK~{}W{OOS{$`H2YjVBQDe;I;T-XV@eUmBiOP{K1m-!h753^O2cB0Zg3s)f zEhS4bbLfW%Yk%wau$R1&&@uFo7K5Eu9?9Cx3hDP(YajO=X-Z_W6uy_)t&!vPzEX51 zWZ+=K&_lxfpA@amDlRlh-m0yA#dlsADf(K%hck|;XhUEH?=D$h#P3p+< z3w_o=%5VFIrbv5Zy}VqJ$zFY<(7{+K`p5U}qf!(p;X+wOIT|jIqG!SH$}0`~X}_8j zC1n+Rw+xhGx9JM-G7Vipv!j%Cd0zgLZ1CE-Oi##-jtpz06pndbq1IWcP|^&^^Eu@o zO4+*1a(mTGJ(J8Yx5`%k*8K4YsbAfUNR};ZZ>8f>*R;Q-WS>XgX*Z-oJ=1rqJi*!F zn^M7ZC$mRmwyEb{?G|S6yRD^V4jr`Ja<=)2+!598Vg{eNE3pzLL1B%)q&?NV-~1J*KqSV+2mPBay~lx-Rt! z$$8>ed!XqXE_J;%S9`GO8Y*|1Au^c@rN5;zxix2a_v9@BSc2y3)M%D#T7{C)ZP zz|8WWrR-{ExjlT3;ax6CdimJ&E&U6<7_w|1nVhBM{7!C*YA-X(>sJos6<=-n09Qr1 zIu)tC!3?QoCw7`4O(fCb$GP(QFCw6Uw4G&ksuN|_kd)EMH#{O%ij7A0hf#ISY@}x9xvc#s@ zF)!ngIYjCW^(rW__k!(R6*zpDWM+7Emx91{rzO2GkMI8 z`h@%?&2ANE)GLwMOwuKtb_Iu*H|oXOX?MX9l77`r`xt?*e=q%&@`{zl{@O!*cl~1K zB)LGXkWABFi4rLurK{tX_ivjHmh-HB2`BH#D`N|6_o_rndX3Qb+9c|ASp<3jpw zmMxXxlF|y!<_JjoNiy+v#vO1gmt-o250YAb0ViLVOr=8lrbb{ucR60`SI+Z}WI_Ty zm79V3RT?dpOjtmHAjwp%l_8nD0c(TCORieMosx@cy3m^Wll<=CXL5qqPss0#H!vpP z4>{QC*9`WO@fVTb6Or-xx$nxR_H%Et)5WErf{wwG$+TzouJd#2@crE5WnMw|jV|+r z@=xq??J+Qq4mi-e#gnA%l&7AF?Kreq1@Lb z$2v!xk6dPx%iHPt$;lPXq4LzQBtzO2Nv;z3(HD~NORgDmY>VC}9+9evd5`N+7*P2g z$t2~~L((14vw>u473?atdxG!okJG$<_T~*}ZfW!6f&;a= z(ZDD9wUF}Cpy04>gN@|Ib{(T&&jFHYVrS$_Q*u2>ZtAo)0;D>!%dmicUrVN0fQ~t; zss4~+a*Morrkkd3VWUAva+|;#S*z2QrH*|p)!IeshI0qJSywXc!)|zVsR6HkE4dE# z5OO#}=x7fiP&Z9#V18-hY??IsI*=p{I@@*JPJ=FX##ul{I$<{CP$SJNfEfFA?x?m1NR= zbzQ3jgvu^Y?&+(8O_CGgs2tXT0fi;j%WIT04X-a}cJlhr|4DiH=^T>YAZgkE;icp( zPu}PhT>3%Mo1C<@Qqr59^cdYs$wb0xjaNte?; zw>xR0l%#h!>4$ga2{idjJLBgbA}6MwyQs`7=$iN1DtptuYYK06N8W87n|r84{M;R7 zUO~_JceR3j>WBNtAR0~$oo`ooTjt^Iq9iiQj@Xs$=Ue+e!+yH=b8AC?Nqda&er~Dz zVdzP_^=H~TU!p{o*%7<-BMCZhPB_c!`jM2c3iaNm1Nu!{9Ox;L&343YQA~;$eeZZF z`ZBb3(1XMqfX(y>=spI?*E21o1)F^x-U1# zBYU|~O8AF%gZ|oJt~S`K4O(mGb^|@|?G2WFS*e}glA5XEr|h;LYulsR)=#dG*%qc3 zTzhoR9g%(ilWoL%$4Ha3@ch!q&;65j5++Gkk~Q{1O1!z<`r<-LbV0r24RPx&t)IKD z9729>{aF{eV$0lrnsx6&O5wn@b`SbBR{w2Qp^GVnbL$^!LfraAWAj!=kOzrRw&t>0G(vFCnn{j|FM=`sCTh$hmu zu6V?BFZ)K~lJs+*m6Zr#u3u>T-fYuBUVM#{zW|xt<&^()l-#e%WB5_C+(BFYc(#>fy!qDTD)I}2cCw{0PyP>*Bx71`-y?s*m-Tt}zFFvu zJoig-%$U({wUR4kM-6-A3vXd^M9HI^Oy;8UJLL~RW=FYr>cdQy7Yn|F%+}o`V4g4s z3D2ILH02pse#S^{M$P6Pm#leW5eby|(GEDTN`ElTmJ+L>Uq|$6BvpGR$bigcWhwOk(=b!J3QGb{R&jwmdE^ zw}$LfdGyi^?2*kYTg&U7*&@^kH|rsOIj>aarfC$S1x>%5h|# zH;d@8Rcg|HyQbV8@G#Grp^tSS%cMkJ$QUbR3jRPcyCtC=CzswQb9uNNBr&yAaCHg( zB!M$_uvF*0PN5FLe&`ZAe{r&ZeTu-%5yPQqD`ZD;I$%tbvV zmvtarla`*#GBcv}yQ8|6uBkG!k3~JwBF0aYS36^*LK|&3GpBr(MAS!Knao9@U$b=r zU9v%BDy8-8A=@*pBwOcS3ECU6lvIh8$=--s!}MgYXK%$?Ql2Q29E>3{OK{do&RjVb z&AJRFWSL=8LhF($;~jv=JR3k?B&yYrf3v?Q+gOcRR?X;!_E^c4Wrimw3-TdP06=##&mbgtpl! zm$$>>X_>;bMc5jd8PPw=HRU%+HFiCfx!v=CtR7aHMMv5_XsbchfHT`-@{szr7I3g=39mxf$zv1;pe)|ha`T^nLXU%7mq*k8@ zvyAj*MEl9LXtFeMZOv@A#kzG}USsN$&?}ugr|Va!%Q&m0UC%FU7~hG%$P}gx!)EDh zvCdY?%!s}$7nDCF<@#G@_V6~#Rmv!#E&BcJTS9UraV zhPAtK$Ct9d6k9?&NNq2#H$=S(glXe2y;6kfwZo{PUj+3!CP{l7`b?R5HP_CJ8X-E2 z2U6|~W0M)<(Qg_{uD^ZX>>F8$=ciK%?cw$^d1p_`^_mx^ zwT*>sJ6eBWAw`Pq z4}I7jKYDRHYFi(9M`Dbq&o^OO+lbcRT+rtg*Jm=be_SD}v1xgv3!{YAj;Sb@Pw~6V zT4CBKOrM^N=q7UCdRJ1ebh#ir|6=;{@1>WObF&KTJ6n!zIR*wA@+)q6^sY!UT{TnW z`3dx{tDM#!?kU`7v#j=XSArhq!+Xz=Gtr#sD!XI2?9HY1B{Rzvq|czeZ_JR)Y*%=D z8G)bs6`AYEb+pM_oLPmp$Y4n}qE1K)i%$mYrV$r8K%^Q|`_`_`M_Y(1ldF5_8->`8G#RzKOh3DaeS zRnl16H6&L% zD;%AFfP9unvR)l!X7_hV`ZJ>S*I|Z9$hAObFOJEsbx&%^o*F2>7L!}oO43~=9pkK& zcGlh#CT}N6LceMLVh>^3bC^eG(_|*c!Zo=7*3hr4d)<TkR~ zk#g_vvaP#OR^MFp?e7;YQGNKyWGYsUxvig>-Z*RZW zFSME_xvWO-OM@9QB`oWzRSWCOSbd{!lT3-)QD5mu?iTb0Ryx%8h<&^JEvLgkS-y

DUv=%=th@K?mT?ER`WbM$_5VBP5p}0ip|C1s$imXXFWvV6l!*3`br`5l%%Ye~3>)F~{}2z~06I)?kY&eH3x zI3zWGl3-0KtsztJHOaJ>L|d7DG4w9Z`pUq}WaC?dLm$JTES?`4=NMf8!t-DIb z=v74be?#Z4Qtv0_oiFJzNfORXl;sBN?Z8LUYLQI#ONmXA*q|A`WjG>{miDnzCp1@h8{&F1qsiTw{9629m1wOQA@~5SGpBPHXdj(%%N-u9C1mm~>)o#{jB`S~1?jhshH!h$1Z zzF2B5)Y@(J?j%VPfrcqHJyLbj_tK@_RBV(A>t(WUGlKPo^QhH;qRlIfP=hUlSRu`u?=Y6D3 zFPVb%c738G#>-SmcY;>8D&J2D_Go{LB>bUFQmC&Lx@tc<(}yg$da%A$_(CddmMK_Y zJsgw7_fCtCBnIk0yT~6# z`xw4ma!J~7%VaJpCC>~=nw%pw<-1_|%#xzV4&~#eJV8HHld0$Ixr%VZ#R%q37 z+Tm5nU(#5AkL*j|#tnPORtxZ#q)Z8Ye%4qQeG|N#Tgh!eD_P+# zI)LO{zq~MjN7)C^M%uTK$-Wu+Rr)Z>>Yw<1>*fqS;aoKtc9|2|hCNbR49jfwhuum) zGvJ%#mn_xvA>)^IeIt9LkEOxF%tnvwM*1NH-x_}JywGStRwIw>k$uu)cV;W^wbE@_ z{dj|Km0TNX6=E;yNLDLpbVC~aCX;=T=CT{<$0dB@{jR;RsDdZ6tyHkQag{@+g!JFF zYRSk&@~olXY%D92y^RY$ ze*Io(G$nhZccj4xr;#kbqPFUypD^()p-bRBty9wCf|=t7XR-FOwa~X@;2|jqE+Pd> zq>qne3X7DC(M%iHvWL)AJA1|duNQ`(U0pQw?N&Vv%;uL&`Hvh{k;f^yJ$CyzDYx$f zwK%?x%zO)n+n;V|qfPh!BX8^Ia^&G`h)$AA)23$gG#!rImiEz)-S`&t>Z=t$l-ctR z%evh+DpH1(aBh8jVOF4neDv_>t z46htUj7Jh~=X~n3QCA?s>s48zF-T@Ftw2P!6^L+Fz&@7pM(TMT?<3cD-+Yn!hjCpo z!#6+crE8E_Ti$ike&rD_letLmH-cZ)|3=bQM%z-R;CQJpQW8TnlO&ndlK7uy8cXIE zNt}@>t-WMivyHT_w(edl1gOoV;YzR>OVMKdB|Z zMI=*ttB&$z2AR^smdJ4^Q~Jo3vf)ZwOGf9ZWZm20n~)LwZ%SUX^tp^5ow*6@GxO%S4 z;d?v7uODh=u1)`7T~>qV0nH{`8%FtrW>hm%HwBoJtv>@(^9g=Isb#z;?~?sy6$(lX zmroP72(kJH?$mmbGml8K%!k{)@#`vC>1d`kBzI~# z*UTfgEph-3#0S#&sOrtsu`M^uhI+K#LF$mrTuzQ zmN6y!@C`FtNvng_d!ebdUC{@vIMW?!CH0XHEsfb*H`*F_JG7`~8(A@X@-?z%jqes< z?JihYeysC$=m6b|0oK5^!MUy7GxN06Se=YTc~bkB^0DF#{R1Mc_aZy{S)H^kQ{!FM8+lXn+Ih2SM)SzjlYs^D8{RJ6$X>t6D>Lss(cBbQ4) zjN$h6e$}c~A~n>iTp~5MdCO{4A~iDqZ7K0F-8sDTd37iwRZOqq+nrp7r$p+$klY=c z#t$4k;LVCnh7RdAJbp-epKck6RZ|x~v~nJ-QpifG7#L_JjSF&Hv$j-mXN1J1eQ8=< z%C&b}h&QP8^dKR)^FDvMXZav zazGCW#}^UdxQovS9@n4)QHkD7@(d`K&+^IX3Ulo@tR;uMlB^nAZFzR z$R$j|3yiY%9l2d1ABmNhb}!{yzLZbTo|paJKYL!~ND`b3X%p$MLD`YIUf9yh% z^2{U;UEp3Sl$CTL`4i{gFEsefz8}}R`q29J-H52w3K=Vnj@mO1Egwf-p9l*XYmDvW z^)*K!W36%5&g;_Tp$#JCW=|jWWGZB=H@cE{8pvJ6;2{IvwBlCgFP!mf-L#`V<}hpB zYiW_zzZcSc=S)AHC*$~QY2#h8Lb2X`QsJ zhL*dv-9_5zHq;040+*d^Y*ojs_;2jc*v#WRv%xhQ)Op@OH-FR(;>pkBy5Isgi8pyE zev7!=0@#nt{{JH0jsq%dM0Y4iam|uBieKhEJVp=p@bAgnWlY(igKCutz49s zX;jg;{9-~4RlaoCS9Hn!lP=pO_4E0>k5_s(pB>$u(uh@0eXGIgt75gql+(|msQ3+Iy}t_->BBd*s9E$@PZ^!U@jbOQ2+Z96X^ zTY2SedmZ(7)B3WzZT&DBi(y-Q0|(+L9FHIBXC$=4rFa~F!JGIH|HE*(hHJYhY>aI% z4g26=oQ`wQvxLOwxB>U#cX$*};m>#tAK^39&(r7tb74U&h1DEAMlu0?qhA|z#lbiR zXW$}SiCasPBMlJOS%t8|;d2;y9d*OK=_T!XtP}l&`4Et4IP@@h^OcdcJ8r zKg@+OSQcwy6Vz9V+HNT7`@@>oH-ptxK63tPLf`mRzr_9c1760vsBh(J{Sb`CGFS-{ zu>m&6&e-3V^Zy+J(^20c)dj4?ZTKyoMt$Q_>s`m&_y|pTve5Dzm>VN8R&VIELRC!0 zcGw*=>%B+*Q`~~P@BkjgU+@+_MSXKom+Q$-q9j(qBy5QKj-fW_h`n$)PR9AT95>@$ zJb@P-J@y-S+VNcq9;3VwV=piO!!QbqVm#KtmY9wMaVlE4)>iiaR|LMrW2kQ@>Ac18VtH~ah_M_@KC!F9L`kKj4HiTCg+y5)&q2OfmsSP+Y0 zScfj6}w@7dmJ0lFn2#m%OSPrXVGPc9+I20$~VqArL^oOc-lbpnJ zcm;3aQw+%I)X$G4u?jZ8wwQ)JZ~zWR&twwwaXD_ry?6pI;%$6}z9H;e%!`GvB$mf& zjvk{9ftHw#1JQ#sa0PC`!+0LA;-B~seR4Si496n2a{gB!P#asI{!vSJO-~$zBXAtf z#wEB8ci|B{hd1%Ds?Y!aa{HN&>e^31e}A*a0h;e7w`@~MpwAA-~h~zC9#T!L<4M#-Eatw!io4E z&d24r8TaA|yok5)8G3@{HIr_d0$3EwU?oh%2G|_iV>%8*56-~FxEl96dW@3=W^gVg7ac=EQ?hz z2^(Sy?5OJb|2ly_I1;Dg0$hP#;8B!+du$KnK6=X^C3IlHm*5DT0g-7rl-o(e~U(jiv*H-qw{>M-4uoBk8CfF9!um=vn;W!4T z;sRWOU*LZHLDlpB7J(<2JK7o0D_9ESF##K6C+v+Qa0*)ZKU|9$qJ92#6dVBhVy?Mfp>8ZF2fDD8;{~I_z=AdIRlKs(pU*=Vgqbj z$m2BVMqmhz$MiOS? zz(|~m3vdN~f&1|Y{)oTeHGGKr)8Bf5i$MLKkM;#mw9o%~1X|-8I2cFbc$|iFaS<-Z zHTVVY#~<)A-qoL|*O8dT*>qR}6R|mVz;x`5BX9~@_&?l&`|u?GT%7a&3V}cH0eY8k z1{RJ*u_D&RR`@y&!ZA1nXX6LB%tK-&Zo(b74^QGHyn{wbXMj1;tBjM+g$1!FCSrZ` zG$YXod*U#B2S30ixCyu85&Qvf;$6&9mVsdzM~_jFKuhd^!|)ya5SQXE+>e*=26~lq z7MKGIV@YgdEBil%Kp%Vy$KV8fAD7@~_$8jg`xqGK3?K~SuqrlI_55#5U=WVL`S=m) zKRMO2WiMX9>-YqN$~*PKu>_XG=GZ~B&;N7+LvS>{iwkfGZpI_{2f8ab3l7ARsJ~FA z1FwsXu~!Ao|3L(1;C$SKJMau%z9`#C;W@m5W@Tpq{uqTtuogDN?${rv;T%Vgv7W$IJcQ@*H~a_n@9MgSF<27g zur7AT!8iur#rd|f|Nlo|Gw#Im_&Ywu995kGAyAudz({NGLB2>yWg zFrb>Vz}y&%ao7;sVk!>BQ8*VD;wI5P|F;u3foJg!{(~Xaoq`~=C0u^I3JeBs@M`c;24~YpW}Kwf~RV5{y!z)PH+}f5fiW@zK&CI zHtxjzcn$wT{Un(lwD~XzlRYGQ<6xYNi*Oenz+3nLBNCkjL}M*%h<)%){183MNbJMI z_$U62d6S$4#9#w#hJ$bfF2ql8KOVvRjvnJFfr7Q11r)<%Y>tC*Bre6z@erQG2ly{W z*LM0Zj{50q*H({wONT%w?22#VaGZ!1F2~il4-erDyp2J1oB@PkB~{P=1OlC~C+d%# z>p?RE|A%XEKOV*_cnAN%kh)Gk5m**0iT3&5lt3HoheL2W&cRi<5f9>Vyn(kdw4O77 za#$Ig)#LncOQ1gv#rJS7uEEWC1b@I=cpoF{I}0w1b@4UqSzq?QZsLIiEc_Uc;Te2@ z|6-8_PWw{W9=qT;d>2>aX8hSh;xc+CI~@jLS*(m5Fde7hEZm6O@f==3{S^US;b8Ps zB$0rfu?J4Y*{DB^s2%LUOZYnmHgd|tuoBk9F4)u2W6UIA;WqplFXK%Ndd*otIM%?r z*d6=hEL?!wagVL+|DOn4$G`Cz1~+yV7>Y4i9+R*EcE;{F0jJ?-xK7pc|2Tm&_&0hr zaTc5dOJXfd#xB?cJvbfb;40jR2Sxk*KThBV-bTNs&H!?v{y?wp`!ZM`n_xHWixY4f z>JO7^`$Kr5Dd+$11n!`JGpAw*mcX)@jLono4!|im6TiTn_$yv*#`*8n+*x1%md9$? z2j9e5xB$PxZ}1*I!2&Iu{)=J*Y~~>`3`gS<{0tA`3A~R_@s*a&0$#-?*aqK14=&Bj ze@@~Up25fHYUOlX1WRF4Y>V&UL|lRE@Hn2uCyw$h`PR+?VzE57#uOZllkhWKkEiih zG}}1+`s1ru0o&Nh{!b+^6vyLi{189KwYUS1;LmsoAEVjU8Avo1!#b*-|BVRr#W!&_ zeuT?$AD+X@_yk?;oCW5`;#dajV-wLn|GN?BixY4feu67;4}OOi@j4pqodNh_G#0~# z*u6dHe?I~faXNmAt8gzK#LM_QdUbFXoC9CMSZsmqabyS1|FHxR1Q6VLzOS7Vg3WcpYzJ?i8p0{OGAcqAvEq zH*p>=#;@=jyn%NxZ>qC^7_5zrurCgA^ceFAe1!Y)2>yi+F<+XqfI?UYU&FyT5*Oj8 zcmTh*mHmI4z&{w$*;znAEQJ-ZE;hn;*bC?55?qCw@DQF<_58n0;9soU#Th^oY>Qp6 z7Y@czI1y*y0$h*#@Erao+UNhD1pdL0bY}oXum(26_ShBs;1GNpC*U-ki%W1tI_Lj- z0$<`@Jd7vt9A3s-_y~PocLpAc(O3)JM$`Emr^*z*6X`PNETZz@GRPPQrP( z9JkeBF@9*xCQs)Df|_0;63~oeY@*`WdG-~ z6Y_;JEQ)2ZD%Qa!*bdXN4-Q2SPQ^L67+0uz{%;_#1NY-mJd2m{7Do4QHfd$7ht04Z zPQdr^L)<9Z=l^yBr}0-bdpZm7$6{CpU&B^75QpPz`~WxLHay;w^ZzV?zwtke?BxvL z6->gW*cN-@ARLJca0zb29r#->&i{J^o?vKiXTgzJ1(PrpyWu!|7gyjqJd8i!9em^= zk*ANdz=BvA6R{n3#!)x{m*Q?bi&yX_y8AlI2|!O75*4u}cEDly4lcu$xC{5=S-gmk z(Cp_dI2;Q&dW<*%Rj~=S!TvZD-^UMd3+};R@jgDqu>Q^fqOh8+?El&Xx?oS7gfnmz zZo*@D1|Q(Rm}`Kuz#>=!>tc$k=YLlMqi_N)!cTE0?#JtR8v_SA3(SutF%IiuYfKUC z^Z!i(OK}}$;88q{5Aa`%9ONwc6->fp?2i3$8qU%0-|4f{DgvAE5T3-Fcn^ICI}6N- zB{2@0Vtee4Q*kkVI+*kSO9FfGB3?)DH=P9rVJw!%=GY#G;b_!?blQ61bJ?x0D<7k|O%Wx$g$Mg6X`oHC@U@okJNw%{8+Y{)5BXBm(!;QEd z&*2pe9PTVA3@c+IreIebtLphbmB3ouiHGn9Jdb~)djxBS`7jRaU~_DbLvfsFpa1U? z_ykwsE6P0X&75@fJS8+;2MzE{H|3 z7A9j??1Piv=KP;QU?Hx=4fs8t!oTn-29I(E&=wcqa@>GB@jE=_A@M8zf&ZZU9jD_E zjKX4A0Tb~xY=>`PKOBjZ(DOctk8mY!#;@@Rp2gqr4n9G@(awOwFa}Fu6|C*(F`5zR zggx+0^x#xnh)Zz=ZpN?idpw1=@IL0UcfHK=atu_&+Sm}ga01T7#kdvsP2>E(OF(}JM6caB zFh9m(4NS(?*b7JFWSoT`;4)l=n>{3U;sHF0XYeBaj`#2>dcWrkJQyP|21{ajtd5?# zB${Ab?2J8e5RSz0I34HVN4Nsl<2Kxbha5e|4+PHRRs0M8L30MX2179li((n9j7iuK zTVf|$+5cS$^uuB3!6`T!Kg3UPHEzLO_zfPzvv>(_s(Sw4C-5)&%yiZ?C+5XM7>gCK z2G+x-*bcj3FC2_-i}v|Hfxvq>A3w&=a070~y?7W;;V*a%Z{s6$&2m;SU>4_p7=Z#< z49j8_tc8uR6{cV}?2m8Z7@UglY$5;taHK34V?n(X)fZK0Jay;;(oe@8Dzfdf!>YKn%x% zSRBh?RjlpkF&PSO*(p8%)Cp_w5r4;f z_!Pb8J8K$@5g3Cd(Nms8b*zg`uq}4Ro;V0c;&_~n^Y9~Ff$MRbqsQ1o;1K?R=kY53 zh5w*wIct~$Loo`AVi~NAN!ZX<_J2zPovU$k zFrLC+@EYF6M+-RrT^~3D2*5BbfW@#ZR>4}>2wPzacEkSo7LLKGA8`J^PhcT_ifix- z{0hItv#trqt`-bL4g>K1+h4mbMzQh3Dm~dur;P)cN~DjaV)-zb8rzZ z$F-P&yKQCve@Ea1{*2e~A9OEb-(eJ%#;RBkTVN{o!l5`;)${*70w3UV+<-grJ3NIK z@fJQp@5RnQb7282i50PyXrKR02&CaKoQ}(ID}Ikx(EB52fkiP1yWvD!jtB7EN1Xq6 z3H*m4A3Gfu!&=x1d*e)8h#T-QUc!Gcc!|?*5$wIh;{?VKScqTXIedx*mOAxIVs%Wx zQMd><;u*Y$IhV159uf_(CyvLDaXlWubNCb^K5;rMk4>;QPR7OfIeLzgxQ`*9IvrKV zw%8YE;3_M<5--G|HDnV-O*#*Bybn=$^O%WFa~R4J#2<;@l70wGjJZR!OeICf3TJP z{|AA4=)2w-Krj}@l2{8HVmkK1u{aes;5IygKdE~D-y`q@12;GW2*X$`k2UZ$Y==E@ z2#&*daT%_}J)(X7A0%)M|3cr5&OqX@FOJ4(xE#0P0X%`f;P3bt^Kat(FT2TEP%j*f zlhMM@a2p=LlXwAd;bZjO%ofE$SY|Wle=`D|aUY(-i+Bqkq4yT2<6Kw(OJYT=g-x&n zcJq)Jgky0LevV(@Pk0UQW6>|1fmFaGY=S*-2#!V13=*H=7TkkJ@g5o(&Vq_y9KMDr z*cV6OB%FgQ96iP+0$<@FJdKy}FMNW&a^~oDA{3+XRjiD4us2S_#kR8lza{V!KE}Xp z&H{>Kdz^~<(0{vAF9zFSgD;)<8`uv=;Z#-6|2YIc!q0IN?!trkBmSh$GmJm+o+`U3 z$4)1nAB(GUaZ6BTd2P@V?el*ffjw%7d?AtiSyhho^LUx~U*zxMQ&rlTyBzbV(k?%~ zLc9c4C7!TL&wr^{mxA`{N%_fDHB$cho+=~us8Vk{&L_S?m3pi3Ys&ZI_jm$-R;B(0 zyuC}$f9d!>6`oPx{>rJCPnGflSPWya0#?Q(RTfYW+Ys-7U5WR?(H;uM;WP?n;Zowu zaXs-Zc!2mpJW2cv-Xs1Hjor=wz0p%h6S9UyF_wa4HHTreQ)L%)ru+?ji})Cvf%DZo zhVi*7{jR|;i0{B-PF()}M}_kgT*7`|9pdq*j$wbx5gAzR-ii$ z#`kPJhOwN$THK9S@h>#@I2{$o=GYgf;7+`SPq5Hlr+t4Muj=_fmw#WL6y-@v}O0GHx-_%ph`b@~gyeEMI?_24K+pau5Fw{S78!>5?* zJ83^lZdO(4r-Uj8Unz{EyuLb3F1@PMOQk&BL!vtcgUAoXk*YMb)JgIIVpTd=OZi63 zp!_W5*YGb@SMs1tGB6*^sY=`vrU`k{C`mzStc2CDjw%h3RjHp!JRN&ue|$@o`lD2- z|32~g__3qM_=Lb}RT^wirNLq1$M7tk$7`z8yMz9RBrj_ign3lyFH)6yrHGfqs&=_l zs7ZyU6tu)n*cp4NQop|{9llN6gHv!iTB_7vjT`W5%JJxP|z3JWBi| zo+p0ku%7=ifPX14k2q@-ph`SMl}%lUcu}l?l`#qHViQ%`w^XJ58^n9yAj*dwkxE)& zG6mD{16+*%!I@q74~xYseK zUYI&k{=GWJt3wT=jw+Yvrm76MCAK5}I{EIZM=JEugfyI{4wQe7qe=(MRVn`**Qx{M z=QGqk@&RL2>RnQ$-c`Iw`BSyKeE0LXQ!kGy_3~r1Xg~kQ5-5WeRB6~;O_zH=RTk8P z@;*3__}kFc$;$X6H>38oGq#h zEJ~GrVz4OX)zp@T(NL9oEmW!320NaR{jC)SXrPH)MBr3d%Gb#U6O_u*TtV+Ed zlz)Z$C_k&#k^dc|O1;~Z-^WM9-5z8%F zF|JUH8pd{Yv+Vy}PQv&G58)4Z1~1}ocvF>*N}UpAfEBS8Ho*?q4Ts@qHAeRTY)x!7 zjCuGGF2hy04!7c$cwCK<=|`DlApTeqOJjMggf-O;(x5hhM%WbFVn^(ZZ(vXCi-T~e ztrcvRE^Ou9oi@+hXsz9y77@77Fzy?&OnH6!kCiLDOq3M-DFykYAi;DBYGJav(JJ_L zT4kx#_Up6^&n)>r&Mt|H!*LY8uTC?J`M4ODVg~NOJ$L}msd9IF0k7drG`+Y}vHz=_ z?6W`#=(RcoU%}#72Fqg|Y=9jx4ZC449EqcGwikCQ^9b1gg-!;rg!~5Ff(P+?JcVcR zcl;B*+|CO5Vld{$B5qlju5k$hWmVa6HObe;hQ!;GPr?2;7$@KqoT*BGACX^%n=r#e zVwWlvkB~o(XNX@Te-rN#H@%$|@Wwz@`iUeTjm3ypBwrOhNfb0A&{7t+|J^SD7d8C53 zud`->s&pJl-v0l4QeKRBMdDR4iFh;et*|5UUgZ1X5aQ#>PZn$I(LaNN#S|>XjrawA zgNN{hy3smtAgy?Zp>p}~ldKqu5m;IsXc%!=1#4hSRqnjnVk)NFTJ^t4E1s{rTog1b zuE15c)}(LJdgPP4oOpjJ7OP{Tt(A5rS7FacP0O9lXq<>s@nf~6VSIusaV_ps8Dl65haDcpv|Dd~-FAe5ZnZPgU+WhL9hw#>nlcllK^NH6gouwG%Mb ztFiK*K*{e`-MZ$o0)DC-$NJxj?G;j!<*w1r z%N3=ZCgg;vL4_n$PB44ZN(c6)l@rq5l#=hFGD1o`7x@T`_swKQu`Rj zBJxYrfwIDCH|cP_CWguyQ(?C%FDnm|Kc>n+uao~nog}w#Y~Q@( zqg>XXC+k7;ZmmAk?@fX{FDrJ5$Y5QEV&bn-t-#@dx{_pAM@fX`~&DLIzhUfLH zU779me^ft@zt~=nz|7@Gyim^yzQ*|FwbK9D{zA6)`Ce?Fmf2qZ754wxUXSq1 zl-^cnR6NU~Ew|Dv>)fL>Kl6aq z=Fc=M$X%8dl)+TDZq02JX@&ijRw5`&;+Y#W!Ah7X@jse`<+Vorl~%<+DzlNb^DkLi zsm!`o&}~^-d{*hi+frILtMrtXHqI(-az{#2vPu`Hfc^)Lky~7zuwUrGb(Sk&S!6dhel>MrD z<^M=&jjYlFkEFD5R%yRSQrbGJ^fxW-npIlyv6S}BDqZtfN=HdH*&fEfn%$RGxycjB z9?q(~_(|F;X5gH!pN3jjMz;v@KbKYU)|0eotMQHcd95N((?ZNIt%^_6iu+&5YT4~+ zTD12*FF6OT^kMD8ti?~$a{AxTYQ9B^&BIoqhyD@PAKJlT>tE@h^wZ1^WN`Ck(yNOe zc>3>A<%G1K-39xr%ymjZ#%3)!-U)(aA zrNllL5*kT~y=~b7i?VgMHrqgFywt;P>7kx(+wjXTmH5d`W1wX|%pF$crM@?3>w81C zzN>`3IJz*)+}tW6Azs4Shjv(+my>3CL~hE~e5%yb6D#x3DJKIkb!gp|(y%8vfNwMP+Wvr*W)W z2Xllb?0Bj7x=UQf7`cKX(j8jh;7eWXTj?@xOR09T!>YP9 zJkq<$Kk|D-d1;p`khC)={@=X3>v1T~^|=_&j06?fNon9wPhF zn%(l%(CYdhe6ye3qt?3&z4O(9@0BTY;}?;7vOWVdyBL$(WzCHDDjM`=sWee|u&Xra&JBfc2-`d3>s z11&li%scsfwKp=(SL-@>e`a*-6PpBd0<8L0!h6@D!kvb6>MfUaBTPQQK z)Ke;NhWFJTWg2Bh>^jZM_53-rPDWhIp1I3p7E2}~qsy3{m(#LE@@Ay}+H+a;Y>|kJ on8;qmd%Y0pI-%FXc214n~V@8!@5y?1Gc9uyEzbOh-jQl%*er3ix3 z5u}KsfQWRZDuRgLy=L~_Aw249;d$Rbz8}{$=iIAI*>kU1dv?j;^3+w^ zQ*ZzQy$?4RT8?`yY$n1;(ia-Tp_# z^-n84r+Th`H0tNnIr?_}vuS&7191IA-k#S0{vZGUw*mP7_|9`{3Wy?xtmTlFTh04v2F8VNwHMJo7 z%VqAn%=&D((u`U4Vk_2+Ff3w`&&OH8Q@tS^^$>K7=?|nZG zU|#>_;-U_`4>o(Q#drH0_7{um4;}rgY-j)d;zB3K*Z$uX*K_PVU{o`fs~n!g0{(~M zk`9l0uz>%i5|noXd#bpe7XBQ+b(IDE+wv%d1?4KPXBGcm&inZ#_Lqz6?>PU7Z*cPz z_D_oIpHzB|bzCgp2Sff3i|hZg^C8UPno^HB{zeJ$J;t6#35z|4e`s)>KA3{e^Ok3X8c3j#Q>K6cgpQPEdBS3>yHd9qtn)$B7py>T))pU{$k0jFq-8qu4fg0 zAb%UoGXF&>(`7OH-Qv2oftC4-rL4$c|E821K8`(GT+b?=mCG+U#{O-oaB3F&gW~!l zLoR*A`6=w#QmNc%_U{Y$r$#C_9`UE8O88>-yi3(atyonTef&MuOW{;0SNLxT|+?C+F@C7kRpmrGk&!{0BiKQjCyedF=v z*xxIzKd#VZ>Jaw4O4EId+3yw?49#YFKDW|*NJ%Ek)~{G|lom^l$rYCzgiGunl_Motw<9H8^zo;qd&YhC zm&+dbQu*%W@0K13QB0O54%R~!mk!1yupa-koKIjqLvQDlNhz%7v*qkf*7NsD@!wNE zqwAI4k)doJ7n^7E=H;Kac4+!bOCn)lT!GDDx6^`5%>~c2Q1>7Uf78cQEfyUe?vi=< z9h<3YbdMKsm(9!bTrgB_s3z|*BoPps65{@Gi)FN`laiJuWHYn2S$<8BUZiStD8b=g zd(*O@mZ5StO0~}Js!QqO_Dzoh?%(EGC)CfaT6D#FvGUWZ5ciT|wvttKRi^6fW*^(3 z*Yhsm0jpnQEG%<557;8XhU|k@yZfNkqh$lLLZg&!4tJ#{9;@alReGWuoqxTHs;}L~ zSVR?6-zvd|>Ty#X4)=xazFt#wRf_v|6~AjQ>r$Hg!g0T`7H)BOIO!Mn4vnSCa>fdk#aJ3hu)#fd zLY}J*p5&hJW}bG%_~7gdd-J$2?Db!=#b`qWv`%%n7mo^vZk(fvO+mkh1Kx|*Rq0|w zxk?4HH$Mt+Z+;Y5Jj7IEI0f9l3pwLQ5 z7q_bTIozes$!W2yuj zviDpp=-zWNeCg=i6()9wSe>k^^r)=&YQ$I>l`AP2GtkDn5^Tu+x>%(9>taz`tEmc^ z31Yzb#s%D)`$c)&(N#(AT^*vEzez*bfm%^CQwJp2kX`hbXm`nT4T+m`yH8fQ2SuJBHf1*ojF0+#(3ZoQpCr8Bn)Wk5kkuAz^(xp@t<3-O=rGwLnM?iu1< zT)EU+t)x?GLV}P>uj{;0_Q{6IJs`4lrV5MHgrw{ZGfTTS%uJYDR<|d)5viwY>Qb`I zo$ji66VEL+RdN|rd^fRB0aHcG%I!Lo*sY+c0;vwS?P}txP*Wwn4q1}Y!cCP-eUVW~ z6;gFoib`sun$)r4NV@V&?W&KSb#*WEN`9(AdF(E zn4DycOIOu>^=TE(C7s=umnPp+%Regn!2(J18y)16dE zccXK>a5l>B>2Nn&m2#woUNKF2y;mvKY)WYa>NRv*<5NA1F4EjsM8#ADrY5Ah5%ud- zz(Z2O=W{ppXnwunbT`hase=uPq8jOQblS%1riwD7+xk&jks^l54b_-fLsBc@kZ<}+ zY9*v5sQfy(e)_>VGRBoA#O=J8Ufy6X!@c-+`p}+wBN?iZ0vcLP^XpD z#Ek6QcWb(D->o%UXDkutRhq;_MQc}CruU?0z~2tlZhyp7$?ezZxpltK8B4X-D>lQ=7Oy zoZ2)`MZLCuzPYilX`TJKRZV9#^SETF+#QEBUsX+)uu$J`K4X_I;apUzb$7SV$QF0w zOqHCwu%#_R-MUIYp)_mVa)CObq$XvGStS}e+yNi8T=ju*U>}Zd^=P9hlxp3ks1lOh zku6*A)DJm1K`r*j0c{%Vi#<6}W$`{O+I*vDaj4{us?U@*S$a-`N}ir>pKUYOPYo&(XwO9uIm%*` zB|2WJe=ox~Hj>i*mj1m0-*4-9rT)DN->Y@JM*m)m?{zwU2jA=6GYdHvTf}cM&PdU| zb96cP!otn~?g~B4m<@J(zQ(sU!`Eo+SUg`~tOpHC|Mxl{Jftft&AuPSSm$pKF;>9F zE4QSNBzT0~z^J&73wJab>!b1W;~4W9@7oPhRKCvmWO+L@8^8qAEbQGkmG68AeKZjt z=kyDD%IU;Q9}HL;oHm0Z{&^ufURDBVJ(u;UY>g1Q&6QZ33=+3SS_N9IYV3?-61th z9f$VG%9&O0ftUy$)7rcLH!T_SPx2d38*yUihcS?Vw>`gs+rZx0jJcwg(zHj-`w;F? z4FD}sFSTdP%DgtfXTaV-v(^?*A1i8|zCg8}{7kjF5TnfHbs4T5>F~Mq7S4ihScFx zNH?ezIPua8zJ_?qX!P!{knS0h_z2R^hLkb{(qlt%Ba8!n(;KzAn?tg4LmXBBqGpQe z4Iz5-G@1v-t^2Vu1M={q1=LYmi(rNWf=ur#;%ISaca+J4MoII z*V>cspm>vOJFDtrkt8fIJC`ghG(}0nB2$z+EH*_+#8NdDygja{SY{4YQnB0=B^7V+ zjHju1+puc;j$mM`xwZqbFGsrVV<^^ft(vEdJe2Cjv7))mtRF+o!gZbQzYr!VLF8hpLl0^*Yu%`ZJKJ(cbIGLrb?mcJI1wEwUt8A zcS6mAr%vBVC0ca)PUoiYjMIj;52tB*y}_YK!Nd+TG7 z^nGhGBI&ziijuzXOi|Kz*%T#xSJhZd`mUKnmGoUVMM>X{-1L2KSQUM@x$n#%eWa4U zdtCGGperPOKXL76@JSP`N%|ggZNwNTf}v6L{bIBU`o1XT49}4C{id`AeavF42e}%# zC0(sXdFrCpnPa^uRT|4Oq7!3>vCh=8^tWgkWt2kkn%AOj_EZYRYkrGdmYU9M0VNu| zhFWqh%Ytec7?tET+!Q6R5fGo|HPUEH@mk2Dy=&!iaB5i=wrJtQ^|44^<5UH#EXiw8 zQx+LFAMGDXR2X-lqUnP^xQuPGMI{|$ZCB(Lcft=Dc{ zA$cuh(L6Tk3dw5)i}pR3KimjYuXwF&v}wIk9P74<5;1j!ydYLJt&;BQrd6)i8aY-G zndo%zCL$xz8Oy&C?GkY^l?k@BMQfAA*m>$uCRnGM5Mzb5SE9jWr`$|-F?*0qb~XE# zOlFy)%&*;yrWBE`o)#_b3)Qt^vX4dUg5)H}BAM)Gk|UYyZ;F!10j4OK9B7J?$-(B( zQ5Nm)m-EaG00vw&KrFDsj|OlO*|a+%J`wM?lC<_H#5lCezjwkXTQ zDNHTXg%<5VHKkC?bg4z#zELR@xo@dCiqe33Cba@Ux{kmRm42Pw&22l44; z`i^SLID2liXr+DivB>oMu0_I`n6ez!W8~KbxZD^`R+BUVl+zF?oG#4ps8{t0_uepIAyfy({|7uqs|H zR&CgNeWa3CyH&f4{Tt1zTC|>4ZE_u5A$j$&YNrQ7k;AK>)tIX*f~On1qCllJcnvb0 zLPhy>an4 zSxhrU$zp~Yi^*c9IaJAF8B>%jmbK<$v7BL5ELOB?cX8sQfoYP(Dpu{QLb^h(&gxd} zF><2xkSx}+YA+mzB8SB~Mw?ijKAFbqY@oCTiw#XDxjGwJi$AqFqSl$Co#>beUM~eQ zb{Ac$tlQqIEySfODHN}rt=jZdrBJ+PS>@))UtgWwlxVEZ9_HjpUVB;P9u1?Cy!JLl z$!i~oPxIPWwPo-+z^ZlqRv(Mxb+A=?`7?bia&-<>6%a*|*I}k8c^z(wlGhQYD0v;J z#$xh1O37$T@;cfSC9h+wxi&{G!>V|lVAcHc>m!xCPPS^5+Ug3)>r_nR54u9~I?bvr zod`wF=4gh|raGs-tVB$m+#Jm`t#WfT+qBBf(JMJt(YP!Y?PsD_S&%#4gEQ~(2DwYD zTIMn)6^h)qtlE|{N}@sQsK#QFyUQG^BzLzdN^(ES zP3~U9s>t1E)!LlbM=HrZWYsF;4xSvkB==LR=KZFwkmR1QYMro(yn}Ic>XdrgXcLPz zvb?cqzf@Xd(VjJ(rdvWB(D!lQS$mT#HV?EsM<1keQedrb66x0=x*8(=}L)<(m6HF5;H^L!Co8YxrMT6IHr8RhsFr6f? zk+!FKrHNsVwPI{V@Ori`V@;t@$vEDo*$OL#;x!Q?!~!M{#cPV1o+zEyG$k6mX4-OH zsg^Z|A$cul4pQ=39^%uyR#0sjyjHep1#ypsx>oD8noS$?mOd8AYYmesxn66UqU5!f zDN0^zo1)~kt{RKUYdv$Qa=q3!MagS}+`Kk2tcusBHtplq`bZ_OEo@r!i@HMc+Qz2s zIHoHkukCGG(E(88B;!s-n<^Q1R-%!NyO^R(##yE)lW{k*Zm8&A8Oiu9F|{(t{Q~PE z+)TzpZQA=4l|qsGf=$c*Rw)#@qtzT4i*}3>4RT$%$sKQwL6SSc6eYP6AwEs+B-NHd zZnjN}vgu=yi}od()=D3o+Cfb>`I6+$Fhxo3%cdyFooR}a+}Ua@Cb_RD*;ur%nxZ6k zPHu8vH>`@>xi&5SoIX-X?tGgjis}kU?joBOQA}4za+lh)@~=RVlZ=-eZDP@uuWBsX zl}c+Y+Eu2LT(qlmEn1?HIR=SWs)E<{w;4+?dEIK$mf}7pDHN~UZCWYZ-XewK^+Pp1 z#-iP=M1$A8xq1D>9ERj|pE*d$>wbt&^LjwFW$=2~rq!LJk45tOsZARXqUBiRqCIX> zC3*eK6eX`GOi}WB(iA1Hr`1?YUOzX7Di`e;QE@)~A}lGlQ!D0vMxMagTV z8jHzml#-408f}V_*FyGOC)rrTs(6jFYoXXY(ZJLdPjS1JaYI)~UgPcB_lD%%}^AJHSJn(N2O3K z*0pPI;Jij2ip2(MGAijTHd10$rL4volQ})*u@kji&<(cCX3z7p~}_S-4rE@J#w?y z%djdI``WeR`oI*61MM15*M}}y9BS8E;#xxFxRlEu+Rn_#hRZG**e zN^7t<-gF8TqBfq%48V2OmoFLgRq@a^UsMW3UkwlK)flBv^wsu|i_oFdS4W8+I(_v# zEuBTfR+HTLyj2J+#kv>tm6Nu$71AJ4h)SN&4ET z3KLztk>szflG}2t@x{QR( z&hqhQS7l{f@z=vcyNfLm&7!CZ=i>^pcEb%Qys7XMB7|=_OU|%I7Bg$2t#}p;O{-zk}-r3N3&*rL(XAzpM zDdx|sX`V3eNm$}uExa=^r+rEAYMrORe8y{7nPObYpCWNNDaX(B>^Pn!ma4 ze9X;SG_(oDHiJ4EHLEx*EqoV7F!l+whfPcIdw3w0zm;E!ri@X$mteV0)>o;Xx9p>% z7A%&aeNQQM)=G(8&7B2HN-0bG47dNN6JDb+hH6B}wvFR`+q_<$K z*bp$$+nad}gT}E5Cv)z|$9=~jGqu@`r-+USJl_9+v2E1WMmk?$R9C{n5)EH>n0Ws~VO2;OBRWaBWaaW%fzTWe%Jdh6YPzmpqiN zT-$`x$R0F$o+=XH)C{KsV1e_g^*&r1{i!POQ-A?l3ucG>y!Q^nn6l>lnnf zckeJpia2UV&P`w{syK#mZQN3Is5O(s)mF~@K^=Q4*TA1~Ds+tH+6ufY>@4c~1Odn$ zQ@HQY6l2zBa_!0%#x_%4IzV z=z%z~Cg(D%Nw?uup*dn(YiGe&Ilp*8rzbAeXkx08|5@r<&F_0$+a`W#jp;2TqS`nM zmKxa$M}ik=Uh0gnh2JKsKtR@#lgk3-Rh2t)HJ`y zqc_tulU_~p1+Gn)tQ;dTMe5iBQ^lukoN+-jIw^~q)tg*fCOq3Z3%br{z|--B`*un* zW>v!@`@M`UqBg##LEe+S%2{QWXnNM>MMgQRJ{GO-Wi@Tbr~>(_3UXHQmdVk6%6u!g zSqaX@EuZYO2g>#xhBM(ewmd=*w z4MYR!6%FexT1!kZDISosoCQV0W{Y;Gn%L0Z84*suNYe1gLb3Yf##*1!1sO7>W5qw86i_#|>)i3YunBvifypp~JNeb#$|>3>rsK zX7AQ^)E=cx7P~uQn5l@-P?wfZT!57CZaAc7bqC>ax%Z}%5GI07-%id5S0ALLT4;sO zz{jgO&9!(NUemO(m{)0D3)7|?bItoO&(zLiVA6aDrsFwgE2`nIx<3AxF`7|+9j4nk zW=hJTb2a}D@kXt*dzHnj!zlW(cwdKofmX!EmANQPrE<(!V_{yd&3{>~16~uR`Z?yv z*I-_)eV)SDE=dYZ0}V5${#cbxLs;l0t@mjJr1W_a_BpwIyx+rBdgyj-YbD)h9qgM8 zALiYt7|eS$%P!q~7^cs1%yWN+`LK2nJxF?Qz;wqnM;9ToKhyXQv9hx>vhs^a;=D*X z#u8Cf^vHomH){mHb6T@~u-AaCv1$K?qQaX}Xy`TVqVVkEEaEvk7SfNn{7LJASfdR{ z=&#z_qC*#~V<~A|vx!M?<@3avF3t?44dPlAanp3l&$X2zu&c9(vW9YPwW!q9Swbd= z&_Y~$OAP7ij8-BxK=s8!Q!K_2g8Qj1Ws}g794Y?+Su1ePLKC?5rHIZl#1yU#5p_*5 zoonxjp;@Raoy&0TW3fETS&Z)yN9k*u_?f;w6@|JvOYzR4aW^!iVW$#WpKGVYC{t|0 zwRYkyQ*6OCyZE#l+Lg|2@Vc&eLe@z*QH8eW+B{LTyE8gjie0$2yuBW_?}GZhC^9TL zZ46cT*rjJTt`!ucyQ5ht_TpM|u?FpU9XO6=2hyCLGDU2jPKw`5@dd8c5yg6-u5=#5 zu@`UE17p~O5DA^kwLFXUFRUU&$|9PlN zmYz5d=1!KA(1npKOU8LpCPm%tHXQBP+< z%bnq3M^9&*ks=F;oAAk}r^w?=(3p`TKM)bUocXK<6li^Wpf~EOun7%d5h4t*{hvPG|;}P+8FJ#A7uPaYpv>GxHir%809iuE< zHpFYfR6ob8XUBPlxf@J6%sEZm?C*@`n#eQ2Sxn_bWXuDi z(g3t8QzSB`P4pUohK!6^N6aOwkuj@?J*J3^SyFs&ib#ui><{xQ$$*9E%s7fBQ3^@dt^1zVg(UC$QkWznwVqOQ(q}jW~ejFQ%`+eM7yDw zSbZl{ zGvAC^q_;5%^=F!G5cN6v##_`JF86W$hC7qJW$M7z?D|@!`pDV>Dv1!q&s!(T+} z7n}`MzQA^Dl-T$JT9)Yp$z{DbYl=uNy@Y)vnlh5h+ahHooQ>pS5$#P8$>o%o3Xx9| zt4BIZnMtLl_=cQ}q|!n7j50(dm0cp$6p>U$i4LQlN-B-T%Vaf@%2#45M3<3N7LC!v zuNor18H!?1MkIZ(KqK7*f2MdELQ5pa{s((4qEF=?x-BE~58WPPUKATy(^~z61oXuX zm4GUAcs2ojfIf`P);{Xb+-v<(gt0nko8N=_A&QM8Gyi-eHjH+L7tt?OKgg>))2-4f zDAJj?pc+U<;@)UyTr%C>#YJirM6i<@=9A$#%XDr;&V}`SL^Y9*MEx<&@R~;AnVDbt z^HZpFmMV6Z9q1RS*$KM&K1`2t%=$*HtJpXu=c=_TrozlWjm6hvurK?d6JsGQp>L0m zt|)r@dg9snNH>pxX=099&qQU`>E`(`EzL3Osp%bDYtd};Z7}W5G3&W1Uq4*6O8b|v zUC6N;`!ZxCX?_UPZ#iZ?d#y~@vzMb4V-YC&(Dm%)Uk`s3O;efYA(_es7r?YE$E+v4(&HGD6mEyeqc6Z-0JcJ=odO4!r{Xi0Gv3&OaiNXN*@Cqe3FDsHf{hc+ z$6<{cIkB~vG|rh|UY}-(9dOQXY_{f>)H7r??D<=Z+2fpf{bdZR?HKl7ULtV3vxJ!! zf6Wv%#y^!8&x-!zkphgoxJ1kykItotYu0*VKddE;yto=SA|$2F+9KRgBxigb1&N#o zdj%0Z0edM~0jYAIs4)S}8L4uo7z!(&BNoxu5OILM4vBjcoTW;XKck1sBqwe`ps2Pb zC#r3kC6Q7ui+U3=WFw^x6T={SOA#scMk%pmqO-7>Q#XrG$=k@ObHzhbL{4oeVkQ|@ zY}jm~{v?do*sz6)(PTAp>lLxW6p>rK#4(88(u&;rW1RS95;`_^Y{f*e$*623*TbSI ziAHkmE5<~Zo<-1F^-Uq0Zcu?%>4TZ<336AbTQ(dOgN7>A%Mz85tP zqS#1c_Brpv-qE5B!fgP0lEyE=cFVAa36K6SUbg8!&UGgwpZxw zcdn-!FCB)5cZMy~I4rsUY}|V+W5TfIz7BU-Lok5IMONSSaFFjF+^0c0tRItprPcQ= z^xdd7bB(2+Er@(a|Feo5=fHpz713_wna&NGLu0Cp_U&EiB^| zi^4OuqldTGL#SMfamf(d%cJxZx&Q@6Fa7r*x(X-xg%xl>E>h0BFZ9bfT|C+4qHqanKn*#Zd-AaeJoZBl$4q0gijR6k+TDfUP_os_|PK-;Pk`Z(zA1tzz~| z*g>3qi~+E&IC%_1sKg!dJC}vn?U2agP852N4hg2v4oNKTWFcSNdihpblUdxULbc~J z_PrESSlsDC*Q#S}NimhheO~B;8W?9cs+-2*&J-$x`SX!tI*a?FP`6r)dV{4R*0bYwqSk2gbB)d8! zVT9LX+SbL>4CR0k-iX0}X2lLD83Vi-^AmE>2_<8I-^Z+dhq14fi~;@-6Ncq>MadZ8 zt(X&#??7fDZ~qE{iPVr8Pk^ox8vYy5T|%zTh%~Rq1iRwKw3i3!giOE*!7G4JxE&~z z&^LIG%PW>p{oANqicrxzKpBLrcY&%93cLqYkI)4|EeJUg_+A|eHG2Tmi_pTKfrfN* z0iJsZIF^(T9|27z^h+|(D}?-T#`Bs_s0en9UMmQ7%mCUzh@K63eL%>g9ME1uvE_k| z5?WmW=nSE86@e}iimU{56Uc+N2%hRWmO#tks$$~|Jk)C z*nUa=CZLW$3Fpz=%rUkZwKNV#Y!F{!eMd*izT7BN{jkfd5K-=NgKo88-FBmuX?S=86*htdtQC95; z7Pz#Rge_gSQ~c$4#aT7xt+&z`9!}khsZdm1;SYI#Nz|Q&!C}1V#J5p@*LGnHNmebs zu+G_=a9CkD=}{=-E7PjEIxNP!XQ;<_!Q+tO^>h^Ck8N)tOG&5i;Beb?lANhfZEV%9 zfdT2{jakWuB9EWTL8(w}Yt@d|M^`0aOj8aNe^g12)h<@e0;*)JHiAbB^74~*89?2w z+UuGgKm%YKW!Uuzl1{y?+8e`lr`O=H*mROpt%7Wr3bNo_Iph)|;%$CW^nb zay6E{atyUfb9=o&e7jL&hgmDy2TzCi8T*&W-~2PE&zL6rxQWymw}&97$UB{PVf)#% zm!+2gc?!3G*&p9|`r>sQ6m|S%54x^ES&7@jkcxS67!q=fFSdoQI=5$y!gmem>zOu{ zpXzgadz_Xe=iOlIL-x`%@#DFi_)oR`XVt_{hG~{jou?`vgmNjykA<9Tfm8t1Dmc8G z+sVfsiq1dFM^{cZpB`f196YG1)_Xs0eDO4!&zl1nt4-$*#_e+p;?rphJnM_sB#CRk zez-5Rs&SvR1;%3MD961Q4xgG%@{LNh zRKK@ro*2AKj_Vpc?wek+sj|^WFe;l}yF&x_2HycF>hRV1xs0tmU&Fg+4Z%YIyEZnS zu`T493b(T4x}8Qe_zV^*kFW>0u_cia)f~3Arrl+qjp*Wq?Ana_y2DTyN0|=x&j-R@ z#ID_3uSdsgu)S&8%hG*vj=z-In-AX`q2Eq6dGK^>`kd6VYpK|!klJz@4wrQ&WZr!= zYI*9Opw?4A{FTjVMFm4l_@KyxQ71Zo`ylv_v^(f%ng8@1kVe@H(ka0}9t+ zDS`J>P_ZdWVu#iP*d#t3+cPyTA{jqa_Z?hay=|7ES9P*R!Fifd!91zu)Zuh4`_Dbk zIfQw&MMzqnJl(@*B8F!lcL!}(^9Vdr1!21lct4swiee*)rAm7(4=vFZt~>B+u--R3 zURH^u z5%D(g$a0x(M1#KLndqTe=IUA2WLKJzjx_~U@hNJHgetZzEVIh3a#wS=m8xXN=CQ2RXcm!Rq@p!R!&(pkv% zAN$+IU?_d{2ypG$-RJCJWGtEhEYQtGpmPN}5!XjBE&M%nx{W#}iB*v1@!E>Fbu&K& z+l4_me(Au^ke6!YiFV)cdPohR6XkP`eC)ENWF9yj8w=S}1RRQ)PBO)$65F1sJa56h zcpsdG!>hrgq3I>NqeSFlp18p{b%pNM6COiMFWKP)E_>|HwU%X6k1xYvq3Lv;nwQJh z`}8~Lb-v{_oTuf;K8DjN6uAI%)|0eJD#~sO#39K^#$^x=w%T1GX3ulxbzQ&(u4k+z zFbZdfL>aCDL+~;@>$ITW+JaZ?P9m!@W^y(Lr#I~&%l2jUh#%R^N|m&^KN9C%mZ;pgKy+MG6h@X zJ2dDkUv^THN6IODb4zsw!vGgGfH$Aded*QE+Vbkds>ZO82b3O${`;WWK`@R%v5}w- zP&qB)0oy<_sb7bEiRm+j2BXHg6hGv68|em`?XdF~$z+a8{k0f%oHH)Y)^f1~dp5qs zm;2Cu@-`AlwFYA00z^cEeQ0DSw_JJ)PkzxBFNEE5I*Lt7`g$?OX>Xek@FVUUh`d8{ z#T&!5rQy!(^x%%~;oe(5Q)A=T|+c(te z3e?z0wWM@}j?pe1@S^;V>AKS)IGi<|%#rGz$GA4op?m%aFK-;QYR>e;++!og-r-eW zN1rF~N=h+3Qi(ra95qsnS}Izz)gJyd{3)TCX-8tuAtHbo%y!K(U@T-7;=tdQ%~Jg738$6uR<3EKG^ zgd_O-l%}}zY`Rn5s>?unpy_doYf}#6*(20D$aEb;Vu4#9!t^uOUUaIFo-s{@=;x9> zCi8HbI(a96M$E!K-Hhq>w3YI`i3C%89aOdyZ8Nq8x6xoQbg?Kl68JClK_c^|DY7M0 zra`GXm9cgql)r5awBHuv3K^AN zhJCK#qyE@Q-e$HX)}({lD7V(O=6M6BAXUSECw%uB{%opzG;V98 zRl;K~G_?vY=E!xI*%#4F7yHmS+)e)kZ|NDW(6G52`zF3?xAdv_E3VtoqIo`3gJqj} z(MX&y3V3jzGUIUel|S+ANk8$8k6+MW|6s9Wsk0`(D(uUgm0V$8v_sp)(|ym4#((Eh zc`c|b6IKN^3szkYTvlOg5OBp1`a!*dHI4&Ua*$8Z0Bj?v8y2=46Ud8q^({OGE*lrX zrMq+~D695TReNVb-&^U2)CKP2%4tXbwQpD}bV2R(`Fri;G^2iYd^ORBW;Xv1&A6T! zPfj~R9@dWgYIYt`JNoRT?FXMg;kiXnyHLkhSALXQ-NLjEKA|f+Mx%Q zENrz^wL>?6jdmVlpvG_{{g-dPvXix9s5~ipcUlRdwdVX>`SCVz z&Y}uiXb6N@VQ<`Aw^k0_O`5_t9-~5~(0wGR+U>NCSFj&}D}Td<&t+zHLacB(d|Io7 z()pKr(+R`cMeCQM_jdrsFQ|e%WI~+Myn1KbT0T_%flD+ced`ddYY5E0z{h8tQG*VS zQ#IyIi9f$}yfzVePBs(^uj1snMVwsWOmKZs5+|XiP`G)3XGv`6R@rbf2=a@(;X~YM zTf-ZYy1pDQ5q`#c^!7W(Qn=(2bL z>cDsMTI{Ea6*vrBgnLxP$b4UP;WQRs!f{^eJgvAq^etHms&ofMQ4x#1+;NPLuhg44|s8e9KoR#z)K@(1it>S z0&j_+u6<`$2i_Vf`*}MFcz=ZKCoc{${$M2a<6DyO=@6;^?jZ2FP|~OQHf#ama!48K z?6tnYS3~7&U1@~()Jx@&9lVY-S!#&H)jdlsIkgiuWi4xf)i`PI&_%tJ?UG(4f9 z=WXgQMT1A92*S+ga599((IkwU#xL)K)YO}1i1BHBjhMaK8JSir9BYCnboQ(^$vEOJ zL4=vlCPY|5R}UJy%_k0wCUlFg1B<86A#r)Nvv@*SHC%srCXDoaiRv==C5#Fr%zQrk z8p3E*7n4o#7B)y!TH{Q}lMf-1uu}!TPr4Yp##tow4(axL(?m3%gU;e;<7l_6A(=+LJ# zOZY0VGX_-6=V~=r&P)F4`J~}|l5oNM29BwbkN5z>w?TIh3e9}hUxIMOcNGTG%4hXb z2-otohv4*yIRN3hocpdUi6(_=a4~Hy-V}OQtXqpecka0mKG_xrMLF|-Cl=CFOVC=3 z-R2*OwV&{!CE+H<=ILMeJfxQ_1qy?kSpOlLAx*RRQ>(T7vwwp$-BOYkQ6vA6(;>~U zgf2t9R{pao0$#S{r!n>L_dWz^rjiEuuXZ7eCCpOd2>}KZ_?#UqB20 zyQ?7fw-hahE`$BASAaA~HJad`CkxVGOa8{NrTBN)4QZ&dW%&1K4{5liaA(-c`7^3F z(jr%XC4ZOL{*E)ODM8RQ`H;!Pb&jyyv2*?ZstF0HKgSh%@@bn zsvWJegq4=Ow6JRNc9%;+TxAJj5bN=FF{0FZXL!+S^Pzp$5-=H!-?U)W(59sb_iQ)- znVztx?F2$DNeo_(zmG@~OV>MN@b$@hXBpRlCa4?BLua8yM}uaVm4u?)Q($`hWfm*W z14&^1&h2n4!Bryj-+cs9NiOHu6YaN$kEg9MJ{^aVpYkMB_F{NTQ@in547S$$bb z5j7pm_sL+G;;eCSL!IJ$IF{fZB z9N2_czr7+52lQfG5lcX=D!}xHb`e{^&zFGdB}7kKI}0v1r{SaZrmEm6!)FZCZT-tQ zRzk-tB{BSPD}ZeXcBKT0M&VHuf%px0ONYSqHn=B8pk+;5tP!Yt5tD1heJK1@IcAtt zp0LdzaMm9WSO`ph7uRG2UJu046PS(`KPJ!@N#g{8V+9$zNT4{FyhGpsQXR7ac)KxN z0?m*SA_%u_b*Y1Nn0-1ZUcnNe(#nBV^9>+ad0+tvoe*%kF zgCznF&g10`0`D)y1w4Vze!%1rXzxNyTqM*3OX?1RnY%H28o*m`VfF|N+J@O9PzYmf zC_x|my$^wQ7*JmV8GRWWO~4~=1R6%+0X%`NxHphRU@A@@(+Ldr!JTCS2T$YWC<1{$BFz!_ zW+2{8AmEGhm$w%{UL0x&f$8mVrYF#&2;#3bp-X6}2Y~^PaFdWgU;yqI5V(UDUn6iI zoA>1e*aZAFG=WIm;r@t#bp-wfkieHPf zUw=Y3D&syYfppB?83KdXA-)KVnTq%#um=He$1p8vIOhiw*wTfu7y_};Sn>q=?LvGJ zsCNqSMWFsm2rmL{5&5$S%y<#uMc^W?$lh@gYKnEdgMhUxZg3EoQw%pW31sC#eE9;< zPcD=v@BootkH8x@5MKmNy^oDCfpXyV1p*5O;B^NAU0Wc$2sFQj@FF1Z>H7iP0x$l4 z;NKFAaEKt)KIG_l0>!#wbrPtz8SzD+FGGA0I5ZydMWCt;@kJo365@+MU{Aysfwdrb z9|6BvxDii)WAeWvkQW2Wz%f}aPD6O*q5RVq8-y05x>FeOMc~UFxbaWmOhsgB0#ozh z`5u7=_@(BX1nw0;d=a>I6Y&K~Ek9tYLkNt+bQUEr@eD4{32ZOQSPcSa!Vq2r4y{9Y z0aUicVtKqqs+t?|QYnGX-y^;V>|2e5O&|lj9w)E{Q+R>EE5G566@dz3@m6Q3tNtC_ zMMB70>dnL3$^=5zBAXHz*$^)x5U7On&`$&gFF_~;0!%}#U;@`LnK1-D!|5Q2Kvr7} zj=(D|v0)?-kHj*b!0<~5B?2Df5K072xGp1A5o&xFp+ulIC_GGH;#Pzbfr#RG#7UqH za@IovpJgGGf&kXUA(RLtAliEo_#{6KB?4hs$MFQ-04PUbG@_#}fmJJ!=Lwv|@TU>@FdLyn;H72=B?6Ad2qgkLF?st4 zw8uD36UgU8C=uw0d~lz@Qag7sD;B(^TOvY<0M5KDi-2zmLWw}3-UuZEE9Nuy3W2>? z^h*fr?#|eL0>geqC?V1;Gb$mJ2-Lzf6eVyQvzSic{yBsafl7~YN+qzl71BsoLPv1) zuMu#gq2&a+Al^0;*owve5rK|p5lRFeg6RtcW~0Sh1R7pt>S-8;e98Up=p;rAd2Ttn;x7XU~{wHN|hS|Gj%{4fad zMW8GqvJruksMUdh|0%p-NuW8RVG)5oVCo$La}kw02t-XpcoC@665&;V(#S*1@O4sE ztAO|-a2jLuM6ncj4|iV)l)?~u5$KHLe1X9EpAcUJ%DsX3BG9}L-cuuRYXR=H5%>|5 zeMP{H>5K>gD6tRWMSzDRyh13AB%~m|NLA+-#20~fqZ#W-;9U%V1c8@v^s5NO#Us85 zc%rj?1YSbuoR&Ul@jC*0!OMLDlTYHtRVct4N$h3fa@(#^%0?MBM@H%%FaN15txP+ZxNV>7M~C}_c`LL zAVA$ixHKnFzYeyJ1j-?$jwNslGdzR9JE@2-0`0ILStG#>Y|9A5*T=Suz!}#!crrrh zw^4{M%%EjP55yONBa;wc1U?#q_#&`$8RCmTZ+wg)5Qec%C$Qu=;)}r8bi@~dxyWp1 z2@FJ3T_?~Aq4$u$;b??c1VA|bx=#T@{_kM(OkfydIF-PP(}*tuZIR3cf#Z1lZ3Tg5 z%@AJ%I`_rCjKKMCu`eUA2kk#1FaifvE)u|FAi|5ly1EE20-t<<@FGyAC*p4ep;<-n z`+Ni*^}~jOz#C%`Uj!01A-)K-ZiM(E@Sz*=Mc~{<#1~evrQX+gd_Z9Q1;iJDjp#Lj zK)_18QA6M^mg_47f-vYM1l(zezYT=;e~I`a@KP1*%LuFhonI4ZcpO`D%$H>=$g4r1 z2m-b_fz8O}T?tG<=nN*Xt{&oxK&|)jqZ|ZUe~b+Ufyp@f;{SYI1gHUtt6 zU_(Km8U}opK$)S8-5^l%0k|hn7P0IV3o!34E}aPsgL52#PM_gcD1mqT;~FED^3Uvh zxX6&+v+xv(z;pz`76N15!$lK;_g-Y|B!S7_;14?pbRLW!TqBS#8>gJY0Q72gTLPs( zM=t_{+aOmG=!DcVmB6EAh-CtarI9NEToz|{1T(49rXjZw*aBjHB2c;m9_=AAElWdj zbDcm?TPza-^J-$55GZ*J_tOZ_FFrMu8ZSI4Ban?f&wB*QA_n&oNJ_>sAy6G8UL@dZ zhTYB`LZd(xivyT}u#6+HEfMR4Kofk7AkYG{n@!+F9R2GAUYUfy+95FHBW#ukR7X_q zAy5}bf1kjE!wBJ`09|oV!336niru~h6n`m%dLv@15*UwV)`URF%lP{r0*zn8Qyv1J zo3#6TXL!w0w@XgzHQM&L7g9@E179w6KuDgh$o} zE*MHb;N*xhH1^d$0;fba zCHxkSDXn~@)Ym0kAxi4YTn4VG^f82MDg9X-WLo3MSyXpD;U-aZ=hHWBKPEN3Xjot9 ze2;;wj4AkA>e}XMyU3UT19O^~fU`yQRw{<)VA&P5ibK z_RDe%%gIh{ak?ob`(b{QM6-{bQFZ5p!R@988O|DR%x_UNv}a`HJEpeYgeuT}A+>dD zF9*Kk<-bVpmHE9UKK$63P`u(T7{2#tLIydlb*CVAWPIe&)6mGHWqxmqkWZYkF{7%( z`hh$SKYF_@W1A<<#s=~x!2Ax2j-TK^wtiEL`ovk;k(eKgvZ)+!%wn_i2U+6eC(ddP zCk`j2gPd4bj`hbSB4M91gug86>_bb9MAklMVcheaw$B;KSBW+IoKb%4SJa%P4lYHU z+2?Fxc^oTB?srD;&7$spXW5J?ASGp>^tii3A04NgY%FfwMVNfK7v0OtvlKQ8QTf5* zG_iBPGd~|7PVIL_;TNZWLR+N{hoV9?9xULukSY+jyg8ah&>q2!widy3-`PLzET8M#%(c}waI=<4qkrOh< zNXMWRxgGOdf@zXx&2iYulSv*weK5b{;_JiClmc%wfX58!F~aa*e$k@n5d^~wQH#E6 zi5~P7B&Htu|N6QQ_?pf?@Z;y)+(;r335ggXv5Hg)Vvi6j_Fk0)wMS8#;!>+>&!fe! zsL`rf+MuO&QL)vi+Dcnmo1*-`-*Y}U#{c#I-`DG$_w#(8ah@~pxi|ObCdEXKkwdin zLc2wt6|eW1)jE_WtCQ3ECryS|%gT62nl-Ru1lN;WR=q<>d0Y>#Sv|#w)$663ckS(Y zTf5O6X=F;V7HOMO)^=rvb@5PAyt&(oKAaShvxdCBD__>Mn=Ja0B{wiK-8yeIIV_uf zveomj?DInxrQ-$m=D6dnqlR;M~W@r2ZOUNy3h2nN5DDXi! z$;8^3kieSq{#k_*b|x%v@kuEuX=kzr`p%F{DLWGx_+YGL;v`evkiXs4ldDsO(sogS zz@&DPDdVqy$0!_l$VW0|?M#utPv=OcoSlgYoNrA#DxWa)Ss<~BcI=(N({kKYsAOk~ z1%BIAGL`L2@xXyWlBr^6VgvgQlT5swDG|75n`ElmnUaB}rc0)pohcP~F+ws4b|x;c zxLhDARJSvwjZAUrAW?c~7JDgJ%wa#t)<{G$x9 zkw3|62$|yl35i`G>J)!1L+qJi@(B@{;!kCaT@fX>+%m9a-X&GvOy-d zU0b^_?GK#V``hVli)*`7u**wGqEdS8mQvgJ$!vK@7WrfF&aHBLEK4#o>PH9@_W57x zF56MZ&{bOWb6R;MYd6a~r>j&t>Nm`k$OI{z;_cSRSihGPoep_d&Ivsf%;i$FD!n*w zUwL~q;i{jfm=x`h@Ih~pbKqn&WZxzH74q~`nqQOhzo;Y2&pWfWl;8IIudTE<*2&8b zne5d!@@|ZgqQ`!n4@*%l3Fl2O%2;Zi6uk%@P)1%&$k}IBkfN&T#lB60q}Xk`9>@!K zT|x6*DQo|-e79`ygizBHa{OI}HB1Uey{z!|8L3dj3^Bf<{4*(A>n*oe&D1lDckEUcZTPiv#L~@Y5GN+r_x2K@VmE? z$H=@vZa5O=m?iaV2lCP^VWAmPTCO?;5|)}F)$GJNGo*ne+H9XKuhSv|3(0y+H``W^ zG$SQtwDk**us>{D*Z!!fu9@7%=yfhY0|!iZjdA9Ul5#Rgu9myT1mBsG2plzB*7svi zsJ;|40xQVVRgH;u#+1M6b~0*wVrN`|o(WPi$4U)`M zpITB7RPB_c=V#L;1$B~sYb>%G1`Qr3ulVzXK9XhCbl1#lE|J@qf2C3$`9yckd?EWK zY2+Dd)XZ-uT}IGCxy02h;B!(60<>aH|C)u&fMfERfelh~NC~56VQ(u*7jc^98B)@y z8Dpp2d4@{*Z9AR82&#Wbx+vjGj-ZJ|Rk>hWI!Td`!xg#=EOC;nRH>W+|1SYYl~iff$j|}D`$*bj1biX!@al2| z)h=b)=`z)my?esT!Ysy&i;tc}Ga5YIZ#$-GNPOOQu?$8d57mo<4m$ z7>NnlwtgemY(H&YGvrcw^IESquT69P)OccIp2phTsFfkHUPu;MaGpV(`x%M#?K(!D zZha)vz|Ob=x5+gkv7yu22rMY)d}8@9XIzC3N~VIH@wfv+|B_tAFde18Gq6fown`>r zU_H5vB~}mYC(8^9>?6-IiFE>XEyDs^$-PTrqd*;VWW&z7d75O`lixJ`@)@;45?ciA zm(e*}qa{o2`9!L<%B3659hh80GOfe*dvvLR;rk@l#vVdOX9(}wLkQAMlN|IUy{{Dd zT31yXw6p8Dod)ggjITE67*tV~;Virp4eVXf*i^+R?BJ*CS}riF?DE8JemdByaw4pi z!#e0eUWs-0Ns^}FwdBlBT$gpcj4k|BMoF)iwCw-zY;u+-e&ZAzJR#`~PI~l8NpE!0 zJ#>40>!inZmGpN`dZs*WB&Is)RdP*8+~lNt&zAINC!JIK+~TDFl#5T|_fGoKUAbl@ z{$OYP-OV@X>FX==lDg(~Hp$+!Z<=Hb;MB{JQP*p=<4So_w(eunpVYr_CZdyMe+-BS0ntQ+jsA8TtLxrEkPVn^)O zXC&yn>UWmc@PAVNb=GTki#^(6T{nqrv?F$l44czO-#ku=e#n|dBL412Qn_wfE!4wZ zX0rXwV%oi)8KxfgMtGpy+tqCwUdL{cUFHGRWmdPFHnZ!#*}%vr#Yy4A>;?_B!2oUW zg*J%O&g}+z;M*JQ)nz5u94s}H!@srLdbI6YZF@u8zFe4IaP84KH$nC-&nqKdJxZFS zgg>!6*`l4?mzgWZI(#uHuF6t*={~cguDP1k@=tv(XTqF*i#agXVzalPFLNVC3>xa;;7 z>!(XetqSN@|3ci=WQ&$_>%Bt=^Q8l|g??=?pqG_!IVoRZ{dSwbTR#^Opr2n4amUH( z_}kyV3eeBj``dwl@2ts}nc@zbzEv)^DF+)xD-pt6zwvg+jBg`{^GC9g%*JvpSUOy;?(!IN*v$Exyt^jZ z7cX9Tny!~UnOUyrZw)^En;f?-B^hT9)^G7Fw3AK$oGss>m1K0&r8{L|vOX_nnt`X~ zo%JJ2j!B^ff0jEPS%=(a<6xJpdF=ucICxS5*3m2SzH5y1(yfq;z+7VHvA>O2>4|J@pM>=I zYBP`hZAyQ8XH?4lp_F!$()4c^RcP0)pW$0PoBbuDDE&6!ASw14C9{Z~@5o=*WwRSm zWhFjUyn??1XWfYc} zoI*xXT}*bZpfjy&-Y~P}mkxq;X)PttT&6O*o?639ueQ@H7aUhh!m@7-*{Aa89wsx7 zY+l(~KKINfxy>fdt9L_&`R)+uPWsh{y_^MkwtI(Z#axrmlXQ~f$o$PLpvP9xE_>{n za^JwiJZEM-tK<4eO1_fd3Ymh3N@lwxwBy7~yJap9mxClG77flN!Lt%LZ3m0S?{W%t z2=+sl82_Vm<#|tv?n~^hOu;QB6QIY0Ou-E#lV1{fWlEe*557)&S)0=Ng1?YpWht#F zlZ-xbyHn`rAnSGBbWPHww3L!oQmKVZWsb`kq7Q$a$#qfc9XE>vUy^VyDeqx-R^}I0 zOP;{kbTZ`Ns}db86+AK}W@1c%-YV`o?}SB2uz3lYnZX5QzECQDDpQ%qJG7SG6Usxk zLxw|UKv)KkoI%ZV$;=GSEc2aGb(>7JwZ=(3;_aQzsbn zU6+@t}P?rmpl1-WDc z$y7Aa>To?N%=4SKpr{06WU@D-u8e7~ktV!bv6>Xe%OuBUh|DfIt05<{9GYeg7XDU@*bIbRY=i6n~l@=k*X8zq(|>f zPa9Ez66qy1d3b@oP5&f3K_*d{$F9m(aYx8c(|r2OsLb}S}xr*g3 zY(>~#)2uXFt}s4&C9p>$-^$H*^?U2~A4&NB7aZKS-= zm8`3v%+lK#g|$j#O*w7EN-~9MB_nE(Tz%`lElHm?GD}~5=R3Ml`c3n$5_iq>7OuA{ z{`J~EJz`d4pGuV>pUFNIx5*Ty4a55CY=q7}k(m*-OqO?0Qa*ZlOJAH3rC&1EYn$uQ ztMOM>SLdrVTUYH~ry(sh(`^OOGHIqVVZZH?XY2V3l8psykS04|%}B*_8MNizjr zobck&t~J==Yap&kQhpJBHZbWsWM;SN#Xh%W_R2pFvbVxzSZZX3j{n$mU7kjLz1xF5Tj|Gzx2nf27J)S{igpZ}e)LFzqlbo6hpf zOpZSp%qU5@mdfn)f1;8;9@!zXcY3TIsej41tQYWjrlx-T<(33_dN<#^XV?#Sy>-+l55Tc$9rZ4}nWViH{ezz!nEVCb~@AlEGGNib6u`>mGq12K4}uMcf8)lwXr6 zecg>XeG}HNhyM%hOCJ6*nG166=lo_?2_qM`@A0|tA)G}CFM@uaqSyTI}wCZQ+ zGp|HnNb!F%4b`Vgt>V6+vko=&qng26B$&f38(*g2pCnUC5+!6hZ|cp8*7w!=88({H z!Q~`UN6Kn@w6@;7w39@#OwDUZ#^_!^X17k-H?w;GCvO}|k5wh%%tTpkus(ecl}3YQ zvR?^ImBeJt=u`Zcl2|U2{YpUFnmW^m_m#j-{U^@brHVZ4S2EF>vS*@RpWO$gGktD2 zC$-MXWWSQpFZJA)$$llH)lHr0!~04m#8;}yB>ir)LhdDnRVu1I=@V&;gbQm?(bckv zt4hLGXZkQ_x?-Daz3oy`L+T{h^_E%fr3cS&E!iadDn+76cF9uNL{+6>fX?(GJ@~Jb zdd;^;Nm%fYG9Mx}2Wjn=dc#mv5kRs9hKt4GRa~jmm~>SEOmVC#YpsbDZeU{ea{%I zcaQRpt?^tU!FoR#E}5({*&9ZC@X?t*%pc7H?+?>O>6R%fbz)>Pit4?x*74Puzf-Z| zajmEK%eACV4Vi-V4!XT0Qe-NlTV1PXNbh{5S;_8quoMrJNh%GpF5FKF&#kxZGbA!i zreM91|5_4XIaO9$p%3Jp1s%{%iEOu{MfFatll0)DGkut|T_LSy12k_YB}Q;vnV*xY zXSI4!y+_iDzBI z)^SbB6RfwGF;ZGsCV4a}Dzks(ptxYhNouHEMt_&3$xBApKq)OJG1o7Ws3eI%NwB%} z(&M8ueaPh}uXBJ(p9vnjV|$O;71C?et%; zTfgT1BczEwv=?*1JjvNF&6~@U*E&VKbnT}SQ3vAk}QOJCjsX*f?i)Za_+s~@W!?vVUe zjkWg3*7K`hr>kt$-z9KagDrm5SbKfnIxs+zGTG10$6hWux7kddq?^eKx7PtAhJN(g z02aPFfLLi?R3`gg;ezyG#OWX6{c2=RJ?gyc!my9M+Ny=LXyR>k({81I+4rmJfAh6P z`5k*@U5817LEc9H+Ku$10)CbJ^GY>+$ok0+sg&MGzvTP5w3zR0<-0~|#Oa3+{K|#4 zq*aLB>Vx!F(rC9d*e;WOjE35c^g|7PasHEDThz{18~q^-uE|un-k(~vNUjC)L>(+| zEM=6*-p0A5r}RTHPCrHA7aMx+wH_b6+M|Bqu((Y2#w}tGLqD70SJXfBxC~kz&Keh$ zT>2r=S{gKW8d=4k$ldx-DZOZ}k-64(W};t_pgs}{-Y2sUrT$Qv!hV#D(Mao6vlrJ; z7neU^mWJiwEKa++Wa@jMddQoNFPq(aORcxwTQ9jLMo;~WieEk-yRVbSWh2=4c3QWT ze)_;KU%36@gBIG)+Q;&`@U`AwNG?U&nvGL*Y}%uKD#kC5Psj-wLlv35>@fQXEy=DQ zhAH)nsp-OcgI((Fk0l+IB*Rv_Y)6^L+Fz&?nw=h73p)a?P%I!7-3Bet_*Id#Qky>tzV zB*=>r=~5qYGMNkX1|wJ(RYC^*j(#IF__X9&NTQKuu1aQtB=mcv!M7!|SrQv$N_i$3 z*9;@YUwUxOaNBou4Q1%gWmMmDcGgl?wwbJ~d&ZF2E_;1v443D;tLAT~<-X?2VEvDd zx*L4t-F*3Z0{wqI_RF7uFNGsGTAu1~glH;zy?Gbf3D~Og<2ptLrvB zGy$BT zYJ=e9c+-kKS0pg?hs?=Qrn%5M7b4XbS`R~#YYLS@lZy#GLz8oKUvj|Pt!TQc%3LQ| z#==)ioE!K7PDzK?N?g$r)#=SP=4&O^Em>Ty*B0l_P*s}gBu%?md9%nMJ6IL7$mlv) zJ+dUX7ItMxu9>S;n$+<=-1d#8-s(uJQda(~$+50dX;z=C$>DB^bg+7BB<-NJC~I=| z(r+wKo6+>Ok_-W_lq|GvWtFkMwgG(H*`=vYvW%iu-mv5xu1EW=N@2+fu3h`Bqf>mc zTHCt?Hn!UL42-h+PR&+OvvsYI$b5CJ>6^0@OuZPM{EN#P|5c$d>%z5y{?>&&?fk7n zB|7+96>=r7vs&fP7h)aGpD)PzcR-_{)SWq!3%gzh&625^Ba@E@WqjN4b;%$MpKF$X zk>toqe;B5(Z&u%I8O&lXmwX<=?I+(Pp~_9kXE5CveRKFE7t;ct{9DMm{H4qa{l#xh zYH&<)NJwg2h2&2kS^rB5h?Gy5mkUdMULs|?X|1^!5@tO)mpjNhf5(5Ab+dx}r;;k2 zYUHt^w{=gjs(g_%*s5B%VZPLu(kZe2;rc|a54kiLE@PgNNi1MBs+>~K%w!eM86IUl zPcTEQKP#t1Tg9rIArk%Zm&V0~e|~8kWfkimqoEf$!!=Yqm()K{B_%qviuNfF)1KBD znXGB28t1lxYDiy2YnahilBS01Y=O=$&S)Frv(0E=Ra=uQhqX^X%KuE_v!>sxYF+dT z%VM2(o5g0`zSnqe>vytPPpYPjG?%9it(H>UC)XO|FsGRw>RF7B?f=!F3-`Bn)krDc zU6Z<+1>`2y`_R086W{yLe7#rmvcp=xnwRpvu`ba2v2c4 zyTrKoTJaY~R;|ZF7gwIVR?BNFGitn1-iv&kUH+x9l)T>J=aoMwo_nLduiPfdBfC-4 zuJE5nb`_a=flBd|1f-mEm z^2Efv9*EJ6st@VVEkvHPb4HAA9DNYaEq`0lM@)Ig^!P<5ALBhPz4b2>ul};WzrGn4 zd6k01mj$}u+`kiV@J9Rwae3~vAKnH0Nxan?@teex-iZILdAYrc>F}~ZQ@L+D`Is&* zMuk-VIMwqZt)_YITwq_ z|D0Q+$mjC*sn&ZTXOt@Ed@s>unuadhCH3?X^D|24I`Ei}9COQm2+&8&cpH1U`evAs zTkc%+5i`lgF0cAWQe!p|pxDGqlA(uQA zhv@+1WtpA@u7mmnCCW{qUVdHrpBl2*3Hd50=2Yc|JfHfF+zk=elijsJUgqNmI2jk> zCX`pIcKsXp0A+94aoMPb%Of2|5qJw*Vn^(Y!*L9LhKunip2xrN5kALox#H@IM2a3w z)F;paQ?MuY!^t=c7vWd99(Un>Jd7vtSG?|$<6j5xFM${6>*I_t6!qZ;kfAA6N z`KEDy48>?ik5QaJ6>Na|Qc4@@yQAtD{0#MNQH^iJA8-$zz$}L-ym=s|3y=t6m+B+F$?Cx7}VPvt(SN{`RK~5}!<*+K&L4B`G>%WWLaYz8?{{#Ya zaT#vJU3d&Hp}uFO9pA+#DDPj`@jwj2NGynP89D!}6KIMZurE$T3)kR}xDSt@zVV_1 zyMd1|L!c86#{%|0ypoEg2qa)#Y=&)7-*wQA`{PGA0~g_1+=gj*4*x>WJrd8*El>Qq zfJ_*UdGIYPj#aP$CSgw;hO=-nZgTV(`w1Mwvv>vXqA5?tl0F#?IIq zN7%~#pG;sruEfo_4^QFm_yGUI48hI-gE0c5urS7Ac~zhP6A84!E;ta!;zIlycj9q8 zhgb0yKEuGw&H!^_5z#*X%MqxJEinbVVjmoW6L2mr!;QELkKrY}jW05D{`-ZnZ!tUO z#UfY|D`0hOiXE^odT=VPz;E%Oet=33s^19wj(_7L%n<6-3&#Rj3KOsi>K}o$-){H; z4#kgfhKIx=T#MT<4bS0U_yhyw?o}5Qia9YKzKx}@64pRZ0}@Ht6NlkMoQLc2NBjk^ z<86G5`lg` zDL7ZO&;MlvHsUTkhL`X*zQAC4$)x)>Hx|TVSO(*!)9@Vrg-6tdGqx89QTd9E2X6iVJZSevb$6N+jq19RmKjoss3hd>DhJFaeujd+dWF zaSATLrMMcu&CU70jX)Zn!@uwe>c6M9_bnE}GFTHEU`tHFuGj~Mcu0)Gi8v2e;CHwO zPv9+lidmwZ0p`b|7>AXyK6=`c=z&A=W3+HNuEA9N5%=LK{2d>lJK7moR?O$9l8Mi`0jU>U4}wXr33#sN46XX0X9 zhnsMRs^|ZH0>|(Y-o_UgoX;6xZY+uwu`ag34%h?x;fFXzw9o&^1ZLwxT!r7`0X%~@ z(9G`)EHl1^Ww9zIViRnipYy*D0sR*adU{R41^6{?!JYUs9>;Td6Q5$n0#3g0miD&F&u2rB3dBqx@@1gwY6FbR9&Fr0|< za0PycdoT?>zmPbO*YOehz2yun0t;aotclIBBlg2#I0h%-Y)6l=fWR_bjo;xOJb_p6 zE}Dhda#$GSu`#y64%ow1_Ww`nt!M=EEY` z0+X;O4#rV97H8rj{1SiAuf*!6KZ*A-sDu;OU**#B5?CJVV{`lfhvHoPAL@S{)qZy2 zMfBVt@f0(abSj2pVT{Gb*akb`033;*;5=M}8!^q%W85U*F6AsZ2#a6|tbz5hJAQyu zaV~Da@9{KV#Cx`~|9#_}1!ux&ER2cR1lwRQ9E4+WGA_c+cp7ixV^z=p@Y2oza$_u( z!xor~!|)^g99Q6OJct+Y4*rWlWjO!CB%udK99G7f*c#u%zBmLY<1*Zh=kO|;Wu4^& zU}Ra&{{jT6VIAy(y>SxG!gaU_f5zYN8a_t-^SQ2QG!`kx`Co!S4eWyba1?%mb8$It z#I5)n{)x{pV|ix)p;*L2A{HBB3+#tOaXv1=?U;rq@E!(Ma2A*aW3U8z>X2xO$v6;) z<7}Ld8*mFA!!vjXA7e;GXCM(++|gr{AFva_JlSQ+2N_i!T4Q1$%ZN?;FO$A3^i;-yDz4y=la z*aQ3FY+Qiba4+7%2cmud9}({?APTEt9qfty@iSb4yYV3YjSn$^!2d8R!KqgW^ zWw0T(!1r+gPR3dIHGbphF%A$oihtm3%v#eKKrEKUM%WU2<3OB(vvDf@5(Keu-=GD4xcL=+nSia7HYG)i4n~?MZa?25>UY!msfgJb*{> z54?^34V?jG#zI&OYdLz11_U}|FC2@La1H*9$M8?Qg8_}41&3f^ERKoT$X51$Hv)a| zW1NQH;a0qWzoSoMXMurO5-VU&?2prNo~q~nj|6_gd-xP{H*pqF5Nl&29E2lr5q^mW z@EG35XQF-n=WpsP;B9PxEpRY;a4~*`NANU0L02=U-vU?^8)D05oc|*TjKdYU7LVc? ze2PBJodv{TNom$}J7tn0sbR2+hV<~Kb$v6zrr>6J*Ig` z{ECy}U3dVm*vkI@lYmbfXTcdUKgM7a zY>mTkH2x2lV;Y{s4DUMq2jknSp8ur?yo>MQRGf>Oa64YcKQXkevw$2}5v!yAhMqnh zzmL;I`~0^EY{R{H18-xNB&UO%SP5%jPwbC#a3TJPKj9xqod0(SWKVV$5RC~~7kl9V zoQwa%J(!07p#BuJu6d3W$GliQh4a52fqpm)7vNIdi-%DE*QR#-7(?1Q`8-$@OJfbJ zi>*8)y5n42gkR$Z{27nqZTt^ww08#309#^v?2i4=Gn~XYoQm^s9qz_+cn$x?#~9MV z89)K7gpIH@c5?I>JqZlJ4{o8C-E9SK;O>JK*F&gmd2Xc z0z2bC9EWpo8GhSY_P?ILdkCDw3-|}#!~f8)i_dfbdh@eDr1=a{RzGl2Y96&qqpTiO5J2z-FUa2_tgZ}5A(hWGF( zX6@lDI2V?~s+f$ORXzVdBJc^Wz_oY~Pv9N=7qj(r7MKUiVm!9Ob~qfziuU=xn80>C zgIDn{boX)=6o|#JG&aRHI0#4J5?qPfdU?-(0%!0N{)^`O&Vs`+H7YodHB*1x *bT?yRQwt@;1N9SA@KnJ!_Yp?0t;Xztbs|` z35VlYT!2e)EAGJ?=($ZIsIRlYoLB@)U=3`JN!TA3<62C`!*~iG;D3%DBi9Gcg7afl zOvEnO8zOM#Ic~*E_z<6C!~kc3QCJykVn^&L+UNg70yA(ers7$=fiE!Y zKxaWYu_TtqmY9sga5PRE$oapFzy|ytPvHf8iavv!1xH{7tcmZU{(y--y^qB4xCB=Y z;`~2K;5YmS0|q-Cgkm|YimkCd4#gQb2fx8Bcn+_6NCXXW78HhMF&>k!6OP7-xCXc4 z&v*iV!-wb|>MYL_N+JiA!0Ol-TjN0d2tUCu@N3+Ld+`kZj<+2>#(xCd!<-Qn#1dEz zn`2uXj3eT18Lr2zxF1jA1-yxm(LKWHHv}W`Ei5J4=YKqbde{m(;`=xZ$Ky==AFjlW zxC7Jh3|_-KBRKz`67V1Cj5rLVu_%_q1Z;$Du`BjR4^G7SxENQAt6~Fu7rWvB z9F0?PKCZ+~xCf8pWps_@{11_YK27Gv7%Yn&u`iCm8MqS<;~)4Cea1QchhT1u8OQmb zLZBy(!!uU_3U!w%8p9kLR=+M_?8%#HFhooQ4bWYut=K;YqxLckl&f`q=3|7Z$;?=&4Df8Fs+F-U>Js z7vi_rbfU9>cKAMih!b%seuLW`J;osd4L)%?nu}lH54aD1!Qb#Q{*6yDc#_j!80NyF zSlU+he`5meu{(~%*|-ol;cmQ(#$;!K88IiuU?oh%=Bl3m-3g4u2{;`;#U=PPZp5v) z7Z2lUyo7(^J$xqG&;PztoRJ4(1V&>KEQuAd1~$N!*bckl2RIDJ;N&Ts|8ofZ4_Dwi z+>AT%XFP$w;qUklK1OpYy9Tpj(3XyGFK3ctbcaW|&nFL(iO;2nH|J~KK0gJwEw8jg9e5XNG8Ou%~B9FwsN_Q4@I z8b85VGdcek5Lkw5Fcr7semsW1;#Itb5Ag;1&vI5U6mw#J4~e2!8mnM!Y>aL2J?x1C za0HIWX*drT<4W{wAn^n4!9#coFXA6~7oVbgwzGzrFdIf;VJv|a96d&L0`;*4reIg> zi$n1voP@J+Auh+YxCwXQ0bAMs#|fOnYxp-lLSv4zh5?ubb728|2g_hQCSntOSJm^s zBY|Ex5J%z!oR0ci^7>q`1i!|OxE1%}VLXkO@K4b`|L+lahQ4#11q5RRMq?2yi50O1 zHo%tH4!hw8IBYKG{}=+3aSr|uSKvC_j63mXJb}OA@AwZsM$>XuFr&r!pOru)7Q|v$ z7OP?%Y>I8M6TXjw(1Rc24E)Sn@CAWY_$_Y3pYRBt!OQp;-pBti!#rnAGh=qli=G$~ zrLYp##D>@k+hcd^hacitoPu-lbNmw5J9>;Q1a{#;Jc;M=I^M>A(eo5}E z@sKEwHL(dMV|N^gqj3s;ipy|4ZpHn05-*|W7Kwk+ccC-VP|S@*uryY~2AG0_a5CyI zi|UirCOm{!9X*Ec|C|a1u_|`Pakvck;yJvF&oSh4r@yzb8aBfoIL+20Kd(SwJs!l% z_!xs1IUN_k9yki;<9B!tpJDFBPWvKQQPuN5iNJ7NfZyP0yoZ^Wu!dM0yWtr89M|Dq zJcrLj`}~ji!s)OiHozV@0T<#|co^?v$Wo`Dir5l+;Z*z@_b%o9zfQn^nbScrY=k{= z0-X8OwM=p9VNZWy!DDKCpPunDGMPaJ~d&@+?7=eP^5nDKVjQ0ri#Yy-Tev4`NH)dYtEHD8-#0fYH*WiA4gNHd^c!aY^)Ur|;yC=& z(PJzp@C|Om19%pnU}iaE^oF7ireIebj348txEwd&c3av1X#~#Vb-a(}M)oNd$9P4!eu-P~EZ#)F%}zh%usbfrKhW6X)GMvO@uf#|p&uNpV*^aW z?${qk;zXQ<|HGB|9d1#l8^$3#uF5Iv`IEpC^xG;0@+_EJm4TJU!8i?`)xScBX zJK`YX6I7`;85i5-a{e!~6Na${zrpWSX|NrS5I=zzh+oBjiT{Tgesl(s5wl_hMynoK zKtWB2r70+nHHg>26yon;PvU)XH1Tmbo%kGFPJAV95Iwr!O;k8e!702*{2H3uoi*~s zjH<*6<$iWh)0kM)Q4QgRid>_Z*R9u96@i1OOznxBhu~;9w;X)6I zH2f9KT~5P>*bxWdRlJ2yF><%lE(YsiH(ZEm=($GXZ+wP1_Bb6?##-1M2jVcCf}i0g z+<^!1IJ)=R{diYq3=)5z=N?2R>%4{#8&qIXaZm1_jnoq z!hbPjpR<4x*brOc2%LuJ@Qyl34#xdXdwwzirpk zmn!w6RjFTwcm=F}K+k^}QEdW^RcX*dl?Hu@55N&P8YihzZw{^|z8<%z(%+AiA0d7M ze>)(BTH!Jk?o#j&U!c#=Qcnh&NtOCpR9SEo@%&g6W3i$t^&4Xg>`Zxg4~c#_2)*$! zO7M{vG~I{4k!zb9haa{ycw@ctXK*3^?di2*&)XY=J^pf_NFMN4ycX zA)bQ$i4VrnPTXURr@~?imf>3B8&%oVdx-DHQ}`=h#T$4>l{I{*N_)RFX9WT=T-A?X z=G25#c$OyyZ97eU`Dw+(g9?~XjPV10E>(E`5#AxMiex|Wa97PVB#O*IO3n+eBz(um&8}& zR^mHw{~s3v?fL)+Ah&HOPSlh!?>s#1pVS@h12l@h;fsuq<3V>`!2% zDzPy*i@1gVBfbJRslyE8Cp@hVG>q%2T)OY7Yvmxsr^GWHapD<0Br>bgu(;Y+ekN9x z4(h1VK?7{6_BD(?YESuQgDUmLt5WY1oJRQ~wTt{vtt$1lP`(X4yC^tB;254#rQv8$$N}?6f{<4K?Bqz*#)YMcoOB)a5m*% zsjcK}QKjB?%6H>_%FnA!4da$7^&U|EudVFs=TyjgOe!>x-~CdhVvH(lS`153o~S0u z3l3H4wWGWvcB6cRT3udns8Vk><@0c%s;~dQB(MtCtJ3h0T19@GLX~>gDE|ZhrrhVa zl$Vz$B~|L>RAu0KFuyA0acZ2rV!{TZM*|%+APqWWUn-1Ki_6oix19|oLs z>gB|IC-wY~mRl_i$N-0TWkA{l++xnX~F1AGoAY9D>7frYg6eb8#Uq##H(mcXWre~p7x5VK#jrGSPYnWz*ocA@^6z1H z;zP&}$0=z4%$+QF9`#lb{~CY5?ReDDW7xlYCk=n6;7`1x$`&v(IBVp_aLj>4F&4|J z(ykWyy4Zwxd-9!ZWx<09e25>Z(!mV!b8rE1`*-rB-CE*1aWAG(?;QDyc%Aq|@=t7~ zBl`#RWP$b%=t(}z&spPKs>EZ++rOtL<)w+&AfAYgh^LT$54#f|LVh?-5fk)anL%I) zF2~iX3}Bl&P!3Yuk7>5n^nEFX+Vqu|-TqQd)L#o$Bk&znZmmjSIjn?D)h_b09hi(A zY^{*}a!r-{m_?cuSK!ySR^$CCT|IJp6Bi)GVnvL{7OLFVw88e+35Tgo<;D-k;Y9pg zZD1H*;7VMByTuB6`?601;$b|F_HXJ{H;h}F7w_X^TdVJZltLc4DJh##ip46JfUQ-z z*+{~U*cCrib_7sK2=9s||KpxqeP5RNe@5+Pg6jGh+ni!V+q< z9F>+Qv{8ho1=%*(9y?)A?1K|<63)cAxDXfPX55Oqai3#^ahSkyl(S3@Vk^35K!nxq zV9L*_CDT%_nMJ0{ue9ouve+1#V{1&ZO|5!3Wv6LnIhu0B^B_oCOp^PuOis%%?Rz6X zg)7&q0^|#;vR!4j*yZKa5LqJm#%ea_r{T4IH_gl4!~n{NsL}H4rsQX<1?9nbL%Q@lphmS<=B*;|F!ekRXLW6 zl8;pz$fcqZfvT#UHTE`?4(x3xXPLdtB;Q`k&=f0Fi4$ljp`jx z&FXzRrABIl6DeN>r*^rLvd`_>oz;rHk&>;#4%tlK$|O&+_Ov^z?0ZRjAF_h>&me2P z12Vm=XN~f<*In{5{(Ae#ue6sJO|R6mj(FSaPd)#?+UwyEB$F;b=(T!Q^dF30e;WG# z)qeXc?e!O-U)HnwdfSJ-7Jq&GCthhU?<~C9e!I7Q*8fj?JuJQB*F*1><%j&q_~nsm zJKoY(nhi_OuDB_c3#4bGZb@mJWSzEsZb@mS^wR5ET0gzC?B7z_JiT=7-%{Esz4V2a z_DU}u{Ew6lPcQxHA1NK1UK)Qp#R{06p1q*irRiDE9cjBUz3t&U()Ne+(%N^W^k90a zbyrGHq?cyCC#6@@OWWO((wpg}r?m80dTF8iQtB?|-BzF9m(noFI$Pr(Da{n=EtQSi z-1=u*vs~8r2PuU!74=q=cuOn(M~R=Wm?^vU_k)yj0dd|&R`G|@Wesm#%kxkcSU7^4MOX=kF(ok}#6onCrDOHZVi7Jn+G=h918JeAU$>7|df^nQA2pJ!6)F7DlgKR%Pv zAjvw1YT5s!G*YsO_MtjKvz^i_pVDlv^vZ>vr{uR1x@Ql!+C5Ln956h+-r(mcQP#)? zZ)dmGJWmO+Mt%_DZ|!}a5*;u$z3o3z#oTUXevwirV0L=L_!rV}Wk})d)}R;CFwed& z{^l$z^8qs|W`Vb<3~a7Udg|&?P)-IeXQJM<+m9nYb2pmVtiPpw-c{13utfE=oF|jF zO)=WItkGHGvsv$-&k&Ghh!gAkk==_{p3}Hpwh99zEcZ=DRl+A;8OD6AC6f+gr_>7; zePq&yzk6<@4B6h>_D1uo-c^+<3uW>)KjbXkaLKcTK7ypcyGEMVHPpw|H|mACXN`K1 zt^7srVrYKzl~FE|X5Pg-e4}}!RovAsB1>s`j?pD}mtNoQ_1zK@w%46rpS{xS7q9f% z_l@SwWpQ$+p8oI-enNUZ>)`Z?dCHG@qyL~-SNgNt@>lx*EWMr6WiKnrM@D`AjqoD( ztm)6Qy?6GFUJJa^>sPPznkUQaE3Ge)Yo?F+b?BU%8AUvJtiYrdQgJd87Sb|H@xEH2sP?6OM4`Gj{|@y3XT zWOfe_yt^VRb< z{U;$)_SAp2cK*)aES0)^Z|5)GrzEveT$h9ev@Gw8Z0(UQD|>oFsqHIu{r8iXxu3e8 z$(x?5`bXEAb-g*O{ZC!9r!Fnk?PUckq(EHu)CDcN{riqnD=yYq#D+25E~li2?D1~6 z+-*t4^w5#)MYE?4$kV-GcW)?l(S+{nTRFpyvl^B5$)4KhLid(!UyEF+&|^%%{{h!? B*ZBYd diff --git a/include/api.h b/include/api.h index 75ae773c..241b7cb7 100644 --- a/include/api.h +++ b/include/api.h @@ -41,8 +41,8 @@ #define PROS_VERSION_MAJOR 3 #define PROS_VERSION_MINOR 5 -#define PROS_VERSION_PATCH 3 -#define PROS_VERSION_STRING "3.5.3" +#define PROS_VERSION_PATCH 4 +#define PROS_VERSION_STRING "3.5.4" #define PROS_ERR (INT32_MAX) #define PROS_ERR_F (INFINITY) diff --git a/include/chassis/drivetrain.hpp b/include/chassis/drivetrain.hpp index 43061723..303cf9c8 100644 --- a/include/chassis/drivetrain.hpp +++ b/include/chassis/drivetrain.hpp @@ -2,6 +2,7 @@ #include "api.h" #include "utils/utils.hpp" +#include "utils/motorGroup.hpp" namespace Pronounce { /** @@ -9,16 +10,16 @@ namespace Pronounce { */ class Drivetrain { protected: - pros::Motor* frontLeft; - pros::Motor* frontRight; - pros::Motor* backLeft; - pros::Motor* backRight; + + MotorGroup leftMotors; + MotorGroup rightMotors; pros::Imu* imu; public: Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); + Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu); /** * Get average temperature of all the motors. @@ -30,80 +31,23 @@ namespace Pronounce { */ double getSpeed(); - virtual void update() {} + MotorGroup getLeftMotors() { + return leftMotors; + } - /** - * Get frontLeft motor - * - * @return frontLeft motor pointer - */ - pros::Motor* getFrontLeft() { - return this->frontLeft; - } + void setLeftMotors(MotorGroup leftMotors) { + this->leftMotors = leftMotors; + } - /** - * Set frontLeft motor - * - * @param frontLeft Motor pointer - */ - void setFrontLeft(pros::Motor* frontLeft) { - this->frontLeft = frontLeft; - } - - /** - * Get frontRight motor - * - * @return frontRight motor pointer - */ - pros::Motor* getFrontRight() { - return this->frontRight; - } + MotorGroup getRightMotors() { + return leftMotors; + } - /** - * Set frontRight motor - * - * @param frontRight Motor pointer - */ - void setFrontRight(pros::Motor* frontRight) { - this->frontRight = frontRight; - } - - /** - * Get backLeft motor - * - * @return backLeft motor pointer - */ - pros::Motor* getBackLeft() { - return this->backLeft; - } - - /** - * Set backLeft motor - * - * @param backLeft Motor pointer - */ - void setBackLeft(pros::Motor* backLeft) { - this->backLeft = backLeft; - } - - /** - * Get backRight motor - * - * @return backRight motor pointer - */ - pros::Motor* getBackRight() { - return this->backRight; - } - - /** - * Set backRight motor - * - * @param backRight Motor pointer - */ - void setBackRight(pros::Motor* backRight) { - this->backRight = backRight; - } + void setRightMotors(MotorGroup rightMotors) { + this->rightMotors = rightMotors; + } + virtual void update() {} }; } // namespace Pronounce diff --git a/include/chassis/mecanumDrivetrain.hpp b/include/chassis/mecanumDrivetrain.hpp index bccd50eb..15008333 100644 --- a/include/chassis/mecanumDrivetrain.hpp +++ b/include/chassis/mecanumDrivetrain.hpp @@ -8,6 +8,11 @@ namespace Pronounce { class MecanumDrivetrain : public OmniDrivetrain { private: + pros::Motor* frontLeft; + pros::Motor* frontRight; + pros::Motor* backLeft; + pros::Motor* backRight; + Odometry* odometry; public: MecanumDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); @@ -16,6 +21,78 @@ namespace Pronounce { void setDriveVectorVelocity(Vector vector); void setDriveVectorVelocity(Vector vector, double rotation); + /** + * Get frontLeft motor + * + * @return frontLeft motor pointer + */ + pros::Motor* getFrontLeft() { + return this->frontLeft; + } + + /** + * Set frontLeft motor + * + * @param frontLeft Motor pointer + */ + void setFrontLeft(pros::Motor* frontLeft) { + this->frontLeft = frontLeft; + } + + /** + * Get frontRight motor + * + * @return frontRight motor pointer + */ + pros::Motor* getFrontRight() { + return this->frontRight; + } + + /** + * Set frontRight motor + * + * @param frontRight Motor pointer + */ + void setFrontRight(pros::Motor* frontRight) { + this->frontRight = frontRight; + } + + /** + * Get backLeft motor + * + * @return backLeft motor pointer + */ + pros::Motor* getBackLeft() { + return this->backLeft; + } + + /** + * Set backLeft motor + * + * @param backLeft Motor pointer + */ + void setBackLeft(pros::Motor* backLeft) { + this->backLeft = backLeft; + } + + /** + * Get backRight motor + * + * @return backRight motor pointer + */ + pros::Motor* getBackRight() { + return this->backRight; + } + + /** + * Set backRight motor + * + * @param backRight Motor pointer + */ + void setBackRight(pros::Motor* backRight) { + this->backRight = backRight; + } + Odometry* getThreeWheelOdom() { return odometry; } diff --git a/include/chassis/tankDrive.hpp b/include/chassis/tankDrive.hpp index 4babceb9..3cb5ed73 100644 --- a/include/chassis/tankDrive.hpp +++ b/include/chassis/tankDrive.hpp @@ -2,14 +2,13 @@ #include "api.h" #include "drivetrain.hpp" -#include "utils/utils.hpp" +#include "utils/motorGroup.hpp" namespace Pronounce { class TankDrivetrain : public Drivetrain { private: double trackWidth; public: - TankDrivetrain(); TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth); diff --git a/include/main.h b/include/main.h index d2a90f88..3d046994 100644 --- a/include/main.h +++ b/include/main.h @@ -96,6 +96,7 @@ #include "utils/runningAverage.hpp" #include "utils/utils.hpp" #include "utils/vector.hpp" +#include "utils/motorGroup.hpp" // Vision #include "vision/tippingVision.hpp" diff --git a/include/motionControl/tankPurePursuit.hpp b/include/motionControl/tankPurePursuit.hpp index 7f3b8406..e781f8ff 100644 --- a/include/motionControl/tankPurePursuit.hpp +++ b/include/motionControl/tankPurePursuit.hpp @@ -9,7 +9,6 @@ namespace Pronounce { private: TankDrivetrain* drivetrain; public: - TankPurePursuit(); TankPurePursuit(TankDrivetrain* drivetrain); TankPurePursuit(TankDrivetrain* drivetrain, double lookaheadDistance); TankPurePursuit(TankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance); diff --git a/include/odometry/tankOdom.hpp b/include/odometry/tankOdom.hpp index 20f3ac71..32775647 100644 --- a/include/odometry/tankOdom.hpp +++ b/include/odometry/tankOdom.hpp @@ -2,50 +2,52 @@ #include "utils/position.hpp" #include "position/odomWheel.hpp" -#include "position/motorOdom.hpp" #include "odometry.hpp" #include "utils/utils.hpp" #include "api.h" -#include using namespace Pronounce; namespace Pronounce { - class TankOdom : public Odometry { - private: - OdomWheel* odomWheel; + class TankOdom : public Odometry { + private: + OdomWheel* odomWheel; - pros::Imu* imu; + pros::Imu* imu; - double tuningFactor = 1.0; + double tuningFactor = 1.0; - public: - TankOdom(OdomWheel* odomWheel, pros::Imu* imu); + public: + TankOdom(OdomWheel* odomWheel, pros::Imu* imu); - double getTuringFactor() { - return this->tuningFactor; - } + double getTuringFactor() { + return this->tuningFactor; + } - void setTuningFactor(double tuningFactor) { - this->tuningFactor = tuningFactor; - } + void setTuningFactor(double tuningFactor) { + this->tuningFactor = tuningFactor; + } - OdomWheel* getOdomWheel() { - return this->odomWheel; - } + OdomWheel* getOdomWheel() { + return this->odomWheel; + } - void setOdomWheel(OdomWheel* odomWheel) { - this->odomWheel = odomWheel; - } + void setOdomWheel(OdomWheel* odomWheel) { + this->odomWheel = odomWheel; + } - void update(); + void update(); - void reset(); + void reset(Position* position) { + odomWheel->reset(); + this->imu->reset(); + this->setPosition(position); + this->setResetPosition(position); + } - std::string to_string(){ - return this->getPosition()->to_string(); - } + void reset() { + } - ~TankOdom(); - }; + ~TankOdom(); + }; } // namespace Pronounce diff --git a/include/position/avgOdom.hpp b/include/position/avgOdom.hpp index 585a8251..69513f8e 100644 --- a/include/position/avgOdom.hpp +++ b/include/position/avgOdom.hpp @@ -1,7 +1,7 @@ #pragma once #include "odomWheel.hpp" -#include +#include namespace Pronounce { @@ -14,20 +14,18 @@ namespace Pronounce { */ class AvgOdom : public OdomWheel { private: - std::list odomWheels; + std::vector odomWheels; public: AvgOdom(); - AvgOdom(OdomWheel odomWheels[]); - AvgOdom(std::list odomWheels); - AvgOdom(std::list* odomWheels); + AvgOdom(std::vector odomWheels); /** * Get the distance at the current moment */ double getPosition() { double total = 0; - for (std::list::iterator it = odomWheels.begin(); it != odomWheels.end(); it++) { - total += it->getPosition(); + for (int i = 0; i < odomWheels.size(); i++) { + total += odomWheels.at(i).getPosition(); } return total / odomWheels.size(); } @@ -35,25 +33,31 @@ namespace Pronounce { * Set the distance */ void setPosition(double position) { - for (std::list::iterator it = odomWheels.begin(); it != odomWheels.end(); it++) { - it->setPosition(position); + for (int i = 0; i < odomWheels.size(); i++) { + odomWheels.at(i).setPosition(position); } } double getChange() { double total = 0; - for (std::list::iterator it = odomWheels.begin(); it != odomWheels.end(); it++) { - total += it->getChange(); + for (int i = 0; i < odomWheels.size(); i++) { + total += odomWheels.at(i).getChange(); } return total / odomWheels.size(); } void update() { - for (std::list::iterator it = odomWheels.begin(); it != odomWheels.end(); it++) { - it->update(); + for (int i = 0; i < odomWheels.size(); i++) { + odomWheels.at(i).update(); } } + void reset() { + for (int i = 0; i < odomWheels.size(); i++) { + odomWheels.at(i).reset(); + } + } + ~AvgOdom(); }; } // namespace Pronounce diff --git a/include/pros/rtos.hpp b/include/pros/rtos.hpp index 28835245..37000fa4 100644 --- a/include/pros/rtos.hpp +++ b/include/pros/rtos.hpp @@ -369,6 +369,19 @@ class Mutex { public: Mutex(void); + /** + * Takes and locks a mutex indefinetly. + * + * See + * https://pros.cs.purdue.edu/v5/tutorials/topical/multitasking.html#mutexes + * for details. + * + * \return True if the mutex was successfully taken, false otherwise. If false + * is returned, then errno is set with a hint about why the the mutex + * couldn't be taken. + */ + bool take(void); + /** * Takes and locks a mutex, waiting for up to a certain number of milliseconds * before timing out. diff --git a/include/utils/motorGroup.hpp b/include/utils/motorGroup.hpp new file mode 100644 index 00000000..aa8d768c --- /dev/null +++ b/include/utils/motorGroup.hpp @@ -0,0 +1,125 @@ +#pragma once + +#include +#include "api.h" + +namespace Pronounce { + class MotorGroup { + private: + std::vector motors; + public: + MotorGroup(); + MotorGroup(std::vector motors); + MotorGroup(pros::Motor* motors ...); + + void operator=(std::int32_t power) { + for (pros::Motor* motor : motors) { + motor->move_voltage(power); + } + } + + void move(double power) { + for (pros::Motor* motor : motors) { + motor->move(power); + } + } + + void move_absolute(double position, std::int32_t velocity) { + for (pros::Motor* motor : motors) { + motor->move_absolute(position, velocity); + } + } + + void move_relative(double position, std::int32_t velocity) { + for (pros::Motor* motor : motors) { + motor->move_relative(position, velocity); + } + } + + void move_velocity(double velocity) { + for (pros::Motor* motor : motors) { + motor->move_velocity(velocity); + } + } + + void move_voltage(std::int32_t voltage) { + for (pros::Motor* motor : motors) { + motor->move_voltage(voltage); + } + } + + void modify_profiled_velocity(double voltage) { + for (pros::Motor* motor : motors) { + motor->modify_profiled_velocity(voltage); + } + } + + double get_target_position() { + double targetPosition = 0; + for (pros::Motor* motor : motors) { + targetPosition += motor->get_target_position(); + } + return targetPosition / motors.size(); + } + + double get_target_velocity() { + double targetVelocity = 0; + for (pros::Motor* motor : motors) { + targetVelocity += motor->get_target_velocity(); + } + return targetVelocity / motors.size(); + } + + double get_actual_velocity() { + double actualVelocity = 0; + for (pros::Motor* motor : motors) { + actualVelocity += motor->get_actual_velocity(); + } + return actualVelocity / motors.size(); + } + + double get_current_draw() { + double currentDraw = 0; + for (pros::Motor* motor : motors) { + currentDraw += motor->get_current_draw(); + } + return currentDraw / motors.size(); + } + + std::int32_t get_direction() { + std::int32_t direction = 0; + for (pros::Motor* motor : motors) { + direction += motor->get_direction(); + } + return direction / motors.size(); + } + + double get_efficiency() { + double efficiency = 0; + for (pros::Motor* motor : motors) { + efficiency += motor->get_efficiency(); + } + return efficiency / motors.size(); + } + + double is_stopped() { + double stopped = 0; + for (pros::Motor* motor : motors) { + stopped += motor->is_stopped(); + } + return stopped / motors.size(); + } + + double get_temperature() { + double stopped = 0; + for (pros::Motor* motor : motors) { + stopped += motor->get_temperature(); + } + return stopped / motors.size(); + } + + + + ~MotorGroup(); + }; +} // namespace Pronounce diff --git a/project.pros b/project.pros index 244b556a..d9ce3a7e 100644 --- a/project.pros +++ b/project.pros @@ -1 +1 @@ -{"py/object": "pros.conductor.project.Project", "py/state": {"target": "v5", "templates": {"kernel": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/kernel@3.5.3", "system_files": ["include/pros/rotation.hpp", "include/display/lv_objx/lv_cont.h", "include/pros/serial.hpp", "include/display/lv_objx/lv_objx.mk", "include/pros/llemu.h", "include/display/lv_draw/lv_draw_img.h", "firmware/libm.a", "include/pros/apix.h", "include/display/lv_objx/lv_table.h", "include/display/lv_objx/lv_cb.h", "include/display/lv_misc/lv_log.h", "firmware/libc.a", "include/pros/gps.hpp", "include/pros/motors.hpp", "include/display/lv_draw/lv_draw_label.h", "include/pros/imu.hpp", "include/display/lv_objx/lv_ddlist.h", "include/display/lv_themes/lv_theme.h", "include/pros/screen.hpp", "include/display/lv_themes/lv_theme_material.h", "include/display/lv_objx/lv_arc.h", "firmware/libpros.a", "include/display/lv_objx/lv_page.h", "include/pros/rtos.h", "include/pros/adi.hpp", "firmware/v5-common.ld", "include/display/lv_core/lv_obj.h", "include/display/lv_misc/lv_fs.h", "include/display/lv_misc/lv_font.h", "include/display/lv_themes/lv_themes.mk", "include/display/lv_draw/lv_draw.h", "include/api.h", "include/display/lv_misc/lv_circ.h", "include/display/lv_objx/lv_tileview.h", "include/display/lv_fonts/lv_fonts.mk", "include/display/lv_hal/lv_hal.h", "include/pros/optical.h", "include/display/lv_misc/lv_symbol_def.h", "include/display/lv_hal/lv_hal_tick.h", "include/display/lv_themes/lv_theme_default.h", "common.mk", "include/display/lv_objx/lv_line.h", "include/pros/screen.h", "include/display/lv_objx/lv_lmeter.h", "include/display/lv_objx/lv_btn.h", "include/display/lv_objx/lv_gauge.h", "include/pros/motors.h", "include/display/lv_draw/lv_draw_arc.h", "include/display/lv_draw/lv_draw.mk", "include/pros/llemu.hpp", "include/display/lv_objx/lv_label.h", "include/display/lv_core/lv_refr.h", "include/display/lv_conf.h", "include/display/lv_objx/lv_roller.h", "include/display/lv_core/lv_lang.h", "include/pros/gps.h", "include/display/lv_misc/lv_task.h", "include/display/lv_misc/lv_gc.h", "include/display/lv_misc/lv_ufs.h", "include/display/lv_core/lv_indev.h", "include/pros/adi.h", "include/display/lv_objx/lv_btnm.h", "include/display/lv_draw/lv_draw_rbasic.h", "include/display/lv_objx/lv_tabview.h", "include/display/lv_objx/lv_led.h", "include/display/lv_themes/lv_theme_mono.h", "include/display/lv_core/lv_group.h", "include/pros/ext_adi.h", "include/display/lv_objx/lv_imgbtn.h", "include/display/lv_themes/lv_theme_night.h", "include/display/lv_objx/lv_slider.h", "firmware/v5.ld", "include/pros/colors.h", "include/display/README.md", "include/display/lv_misc/lv_anim.h", "include/pros/vision.hpp", "include/display/lv_misc/lv_mem.h", "include/display/lv_core/lv_vdb.h", "include/pros/rotation.h", "include/display/lv_version.h", "include/display/lvgl.h", "include/display/lv_conf_checker.h", "include/display/lv_draw/lv_draw_rect.h", "include/display/lv_draw/lv_draw_triangle.h", "include/display/lv_draw/lv_draw_vbasic.h", "include/display/lv_objx/lv_calendar.h", "include/display/lv_hal/lv_hal.mk", "include/display/lv_core/lv_core.mk", "include/display/lv_misc/lv_math.h", "include/display/lv_objx/lv_bar.h", "include/pros/misc.h", "include/display/lv_objx/lv_ta.h", "include/display/lv_fonts/lv_font_builtin.h", "include/display/lv_misc/lv_templ.h", "include/pros/distance.hpp", "include/display/lv_hal/lv_hal_indev.h", "include/pros/imu.h", "include/display/lv_objx/lv_sw.h", "include/display/lv_misc/lv_ll.h", "include/display/lv_themes/lv_theme_templ.h", "include/display/lv_hal/lv_hal_disp.h", "include/display/lv_misc/lv_txt.h", "include/display/lv_misc/lv_area.h", "include/display/lv_objx/lv_kb.h", "include/pros/distance.h", "include/display/lv_misc/lv_color.h", "include/pros/misc.hpp", "include/display/lv_objx/lv_win.h", "include/pros/vision.h", "include/display/lv_objx/lv_mbox.h", "include/display/lv_themes/lv_theme_zen.h", "include/display/lv_core/lv_style.h", "include/display/lv_objx/lv_objx_templ.h", "include/display/lv_misc/lv_misc.mk", "include/display/licence.txt", "include/pros/rtos.hpp", "include/display/lv_objx/lv_list.h", "include/display/lv_objx/lv_spinbox.h", "firmware/v5-hot.ld", "include/pros/api_legacy.h", "include/display/lv_themes/lv_theme_alien.h", "include/pros/serial.h", "include/display/lv_objx/lv_canvas.h", "include/display/lv_draw/lv_draw_line.h", "include/display/lv_objx/lv_preload.h", "include/display/lv_objx/lv_img.h", "include/display/lv_objx/lv_chart.h", "include/pros/optical.hpp", "include/display/lv_themes/lv_theme_nemo.h"], "user_files": ["include/main.h", ".gitignore", "include/main.hpp", "include/main.hh", "src/main.cc", "src/main.c", "Makefile", "src/main.cpp"], "name": "kernel", "version": "3.5.3", "supported_kernels": null, "target": "v5", "metadata": {"cold_addr": "58720256", "cold_output": "bin/cold.package.bin", "hot_addr": "125829120", "hot_output": "bin/hot.package.bin", "output": "bin/monolith.bin", "origin": "pros-mainline"}}, "okapilib": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/okapilib@4.2.0", "metadata": {"origin": "pros-mainline"}, "name": "okapilib", "supported_kernels": "^3.3.1", "system_files": ["include/okapi/impl/filter/velMathFactory.hpp", "include/okapi/api/odometry/twoEncoderOdometry.hpp", "include/okapi/api/control/util/pathfinderUtil.hpp", "include/okapi/impl/device/rotarysensor/adiGyro.hpp", "include/okapi/pathfinder/include/pathfinder/spline.h", "include/okapi/api/units/QAngularAcceleration.hpp", "include/okapi/pathfinder/include/pathfinder/trajectory.h", "include/okapi/api/control/iterative/iterativePosPidController.hpp", "include/okapi/pathfinder/include/pathfinder/io.h", "include/okapi/api/control/async/asyncController.hpp", "include/okapi/api/util/timeUtil.hpp", "include/okapi/api/control/async/asyncVelocityController.hpp", "include/okapi/pathfinder/include/pathfinder/fit.h", "include/okapi/api/filter/medianFilter.hpp", "include/okapi/api/chassis/model/threeEncoderSkidSteerModel.hpp", "include/okapi/api/device/motor/abstractMotor.hpp", "include/okapi/pathfinder/include/pathfinder/structs.h", "include/okapi/api/units/QAngle.hpp", "include/okapi/api/control/async/asyncPositionController.hpp", "include/okapi/pathfinder/include/pathfinder/lib.h", "include/okapi/impl/control/iterative/iterativeControllerFactory.hpp", "include/okapi/impl/device/rotarysensor/IMU.hpp", "include/okapi/pathfinder/include/pathfinder/followers/encoder.h", "include/okapi/impl/control/async/asyncVelControllerBuilder.hpp", "include/okapi/api/control/util/pidTuner.hpp", "include/okapi/api/units/QAcceleration.hpp", "include/okapi/impl/device/motor/adiMotor.hpp", "include/okapi/impl/util/rate.hpp", "include/okapi/api/filter/velMath.hpp", "include/okapi/api.hpp", "include/okapi/api/units/QJerk.hpp", "include/okapi/api/odometry/stateMode.hpp", "include/okapi/api/util/mathUtil.hpp", "include/okapi/api/control/async/asyncVelPidController.hpp", "include/okapi/impl/control/async/asyncMotionProfileControllerBuilder.hpp", "include/okapi/api/units/QLength.hpp", "include/okapi/pathfinder/include/pathfinder/followers/distance.h", "include/okapi/api/chassis/controller/defaultOdomChassisController.hpp", "include/okapi/api/util/logging.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/tank.h", "include/okapi/api/odometry/odomState.hpp", "include/okapi/api/device/rotarysensor/rotarySensor.hpp", "include/okapi/api/device/rotarysensor/continuousRotarySensor.hpp", "include/okapi/api/chassis/controller/chassisScales.hpp", "include/okapi/api/units/QTime.hpp", "include/okapi/api/control/async/asyncLinearMotionProfileController.hpp", "include/okapi/api/units/QTorque.hpp", "include/okapi/api/device/button/abstractButton.hpp", "include/okapi/impl/util/configurableTimeUtilFactory.hpp", "include/okapi/impl/device/button/adiButton.hpp", "include/okapi/api/chassis/controller/chassisControllerIntegrated.hpp", "include/okapi/api/control/iterative/iterativeMotorVelocityController.hpp", "include/okapi/api/filter/emaFilter.hpp", "include/okapi/api/util/abstractRate.hpp", "firmware/okapilib.a", "include/okapi/api/chassis/model/skidSteerModel.hpp", "include/okapi/impl/control/util/pidTunerFactory.hpp", "include/okapi/api/units/QSpeed.hpp", "include/okapi/api/units/QAngularJerk.hpp", "include/okapi/api/chassis/model/chassisModel.hpp", "include/okapi/api/control/offsettableControllerInput.hpp", "include/okapi/api/units/QArea.hpp", "include/okapi/api/filter/filteredControllerInput.hpp", "include/okapi/api/control/iterative/iterativeVelocityController.hpp", "include/okapi/impl/util/timer.hpp", "include/okapi/pathfinder/include/pathfinder/mathutil.h", "include/okapi/impl/device/distanceSensor.hpp", "include/okapi/api/coreProsAPI.hpp", "include/okapi/api/control/async/asyncPosPidController.hpp", "include/okapi/api/chassis/controller/chassisController.hpp", "include/okapi/api/control/async/asyncVelIntegratedController.hpp", "include/okapi/api/control/closedLoopController.hpp", "include/okapi/api/filter/composableFilter.hpp", "include/okapi/api/chassis/controller/chassisControllerPid.hpp", "include/okapi/impl/control/util/controllerRunnerFactory.hpp", "include/okapi/api/odometry/threeEncoderOdometry.hpp", "include/okapi/impl/device/opticalSensor.hpp", "include/okapi/api/chassis/model/readOnlyChassisModel.hpp", "include/okapi/api/units/QMass.hpp", "include/okapi/impl/device/rotarysensor/integratedEncoder.hpp", "include/okapi/api/filter/demaFilter.hpp", "include/okapi/impl/util/timeUtilFactory.hpp", "include/okapi/impl/device/motor/motor.hpp", "include/okapi/api/control/async/asyncPosIntegratedController.hpp", "include/okapi/api/odometry/odometry.hpp", "include/okapi/api/control/iterative/iterativeVelPidController.hpp", "include/okapi/impl/chassis/controller/chassisControllerBuilder.hpp", "include/okapi/api/odometry/point.hpp", "include/okapi/api/control/util/controllerRunner.hpp", "include/okapi/api/chassis/model/hDriveModel.hpp", "include/okapi/api/control/async/asyncMotionProfileController.hpp", "include/okapi/api/control/async/asyncWrapper.hpp", "include/okapi/impl/device/controller.hpp", "include/okapi/api/control/iterative/iterativeController.hpp", "include/okapi/api/units/QFrequency.hpp", "include/okapi/api/device/button/buttonBase.hpp", "include/okapi/api/control/iterative/iterativePositionController.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/swerve.h", "include/okapi/api/filter/filter.hpp", "include/okapi/api/odometry/odomMath.hpp", "include/okapi/impl/device/rotarysensor/adiEncoder.hpp", "include/okapi/api/util/abstractTimer.hpp", "include/okapi/impl/device/rotarysensor/potentiometer.hpp", "include/okapi/impl/device/button/controllerButton.hpp", "include/okapi/api/filter/ekfFilter.hpp", "include/okapi/api/util/supplier.hpp", "include/okapi/api/units/RQuantity.hpp", "include/okapi/api/units/QForce.hpp", "include/okapi/api/control/controllerOutput.hpp", "include/okapi/impl/device/adiUltrasonic.hpp", "include/okapi/api/units/QVolume.hpp", "include/okapi/pathfinder/include/pathfinder.h", "include/okapi/api/filter/passthroughFilter.hpp", "include/okapi/api/control/controllerInput.hpp", "include/okapi/impl/device/controllerUtil.hpp", "include/okapi/api/chassis/model/threeEncoderXDriveModel.hpp", "include/okapi/api/control/util/flywheelSimulator.hpp", "include/okapi/api/filter/averageFilter.hpp", "include/okapi/api/units/QPressure.hpp", "include/okapi/impl/control/async/asyncPosControllerBuilder.hpp", "include/okapi/api/units/QAngularSpeed.hpp", "include/okapi/impl/device/motor/motorGroup.hpp", "include/okapi/api/chassis/controller/odomChassisController.hpp", "include/okapi/api/chassis/model/xDriveModel.hpp", "include/okapi/api/control/util/settledUtil.hpp", "include/okapi/impl/device/rotarysensor/rotationSensor.hpp"], "target": "v5", "user_files": [], "version": "4.2.0"}}, "upload_options": {"slot": 1, "description": "VEX Team ? Code"}, "project_name": "Pronounce This"}} \ No newline at end of file +{"py/object": "pros.conductor.project.Project", "py/state": {"target": "v5", "templates": {"kernel": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/kernel@3.5.4", "system_files": ["include/display/lv_themes/lv_theme_night.h", "include/display/lv_hal/lv_hal.h", "include/display/lv_themes/lv_theme_templ.h", "include/display/lv_objx/lv_imgbtn.h", "include/display/lv_draw/lv_draw_img.h", "include/display/lv_objx/lv_cont.h", "include/display/lv_draw/lv_draw_arc.h", "include/display/lv_version.h", "include/display/lv_core/lv_style.h", "include/display/lv_objx/lv_ddlist.h", "include/display/lv_objx/lv_mbox.h", "include/display/lv_objx/lv_spinbox.h", "include/display/lv_objx/lv_objx_templ.h", "include/display/lv_objx/lv_line.h", "include/pros/adi.hpp", "include/display/lv_misc/lv_task.h", "include/pros/optical.hpp", "include/pros/serial.h", "include/pros/imu.hpp", "include/display/lv_core/lv_group.h", "include/display/lv_conf.h", "include/pros/vision.hpp", "include/pros/rtos.h", "firmware/libm.a", "firmware/v5.ld", "include/display/lv_objx/lv_bar.h", "include/pros/motors.hpp", "include/display/lv_misc/lv_fs.h", "include/display/lv_misc/lv_templ.h", "include/display/lv_draw/lv_draw_vbasic.h", "include/display/lv_objx/lv_list.h", "include/display/lv_themes/lv_theme.h", "include/display/lv_objx/lv_chart.h", "include/pros/motors.h", "include/display/lv_objx/lv_arc.h", "include/display/lv_core/lv_vdb.h", "include/display/lv_misc/lv_txt.h", "include/display/lvgl.h", "include/display/lv_misc/lv_color.h", "include/display/lv_core/lv_indev.h", "include/display/lv_objx/lv_kb.h", "include/pros/llemu.h", "firmware/v5-common.ld", "include/display/README.md", "include/pros/misc.hpp", "include/display/lv_objx/lv_tabview.h", "include/display/lv_draw/lv_draw_rbasic.h", "common.mk", "include/display/lv_misc/lv_font.h", "include/display/lv_objx/lv_led.h", "include/display/lv_core/lv_obj.h", "include/display/lv_draw/lv_draw_line.h", "include/pros/rtos.hpp", "include/pros/apix.h", "include/display/lv_objx/lv_sw.h", "include/display/lv_misc/lv_ll.h", "include/pros/vision.h", "include/display/lv_objx/lv_ta.h", "include/display/lv_draw/lv_draw_label.h", "include/display/lv_core/lv_refr.h", "include/api.h", "firmware/libpros.a", "firmware/libc.a", "include/pros/ext_adi.h", "include/display/lv_hal/lv_hal.mk", "include/pros/colors.h", "include/pros/distance.h", "include/pros/screen.hpp", "include/pros/distance.hpp", "include/display/lv_themes/lv_theme_alien.h", "include/pros/gps.h", "include/display/licence.txt", "include/display/lv_misc/lv_gc.h", "include/display/lv_objx/lv_btnm.h", "include/display/lv_objx/lv_page.h", "include/pros/gps.hpp", "include/pros/llemu.hpp", "include/display/lv_hal/lv_hal_disp.h", "include/display/lv_misc/lv_circ.h", "include/display/lv_objx/lv_btn.h", "include/display/lv_misc/lv_anim.h", "include/display/lv_draw/lv_draw.mk", "include/display/lv_core/lv_lang.h", "include/pros/api_legacy.h", "include/display/lv_themes/lv_theme_nemo.h", "include/display/lv_misc/lv_math.h", "include/display/lv_misc/lv_symbol_def.h", "include/display/lv_draw/lv_draw_rect.h", "include/display/lv_misc/lv_mem.h", "include/display/lv_conf_checker.h", "include/display/lv_fonts/lv_font_builtin.h", "include/display/lv_objx/lv_table.h", "include/pros/rotation.hpp", "include/display/lv_themes/lv_theme_default.h", "include/display/lv_core/lv_core.mk", "include/pros/screen.h", "include/display/lv_draw/lv_draw_triangle.h", "include/display/lv_objx/lv_lmeter.h", "include/display/lv_hal/lv_hal_indev.h", "include/display/lv_objx/lv_objx.mk", "include/display/lv_objx/lv_win.h", "include/display/lv_themes/lv_theme_zen.h", "include/pros/misc.h", "include/display/lv_objx/lv_img.h", "include/display/lv_themes/lv_theme_mono.h", "include/display/lv_hal/lv_hal_tick.h", "include/display/lv_fonts/lv_fonts.mk", "include/pros/optical.h", "include/display/lv_objx/lv_gauge.h", "include/display/lv_misc/lv_ufs.h", "include/display/lv_misc/lv_log.h", "include/display/lv_objx/lv_canvas.h", "include/display/lv_objx/lv_calendar.h", "include/pros/adi.h", "include/display/lv_themes/lv_theme_material.h", "include/display/lv_draw/lv_draw.h", "include/display/lv_misc/lv_misc.mk", "include/display/lv_objx/lv_slider.h", "include/display/lv_objx/lv_cb.h", "include/pros/imu.h", "include/display/lv_objx/lv_label.h", "include/display/lv_objx/lv_roller.h", "include/pros/serial.hpp", "firmware/v5-hot.ld", "include/display/lv_misc/lv_area.h", "include/pros/rotation.h", "include/display/lv_objx/lv_tileview.h", "include/display/lv_objx/lv_preload.h", "include/display/lv_themes/lv_themes.mk"], "user_files": ["Makefile", "src/main.c", "src/main.cc", "include/main.hpp", "include/main.hh", "src/main.cpp", "include/main.h", ".gitignore"], "name": "kernel", "version": "3.5.4", "supported_kernels": null, "target": "v5", "metadata": {"cold_addr": "58720256", "cold_output": "bin/cold.package.bin", "hot_addr": "125829120", "hot_output": "bin/hot.package.bin", "output": "bin/monolith.bin", "origin": "pros-mainline"}}, "okapilib": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/okapilib@4.2.0", "metadata": {"origin": "pros-mainline"}, "name": "okapilib", "supported_kernels": "^3.3.1", "system_files": ["include/okapi/impl/filter/velMathFactory.hpp", "include/okapi/api/odometry/twoEncoderOdometry.hpp", "include/okapi/api/control/util/pathfinderUtil.hpp", "include/okapi/impl/device/rotarysensor/adiGyro.hpp", "include/okapi/pathfinder/include/pathfinder/spline.h", "include/okapi/api/units/QAngularAcceleration.hpp", "include/okapi/pathfinder/include/pathfinder/trajectory.h", "include/okapi/api/control/iterative/iterativePosPidController.hpp", "include/okapi/pathfinder/include/pathfinder/io.h", "include/okapi/api/control/async/asyncController.hpp", "include/okapi/api/util/timeUtil.hpp", "include/okapi/api/control/async/asyncVelocityController.hpp", "include/okapi/pathfinder/include/pathfinder/fit.h", "include/okapi/api/filter/medianFilter.hpp", "include/okapi/api/chassis/model/threeEncoderSkidSteerModel.hpp", "include/okapi/api/device/motor/abstractMotor.hpp", "include/okapi/pathfinder/include/pathfinder/structs.h", "include/okapi/api/units/QAngle.hpp", "include/okapi/api/control/async/asyncPositionController.hpp", "include/okapi/pathfinder/include/pathfinder/lib.h", "include/okapi/impl/control/iterative/iterativeControllerFactory.hpp", "include/okapi/impl/device/rotarysensor/IMU.hpp", "include/okapi/pathfinder/include/pathfinder/followers/encoder.h", "include/okapi/impl/control/async/asyncVelControllerBuilder.hpp", "include/okapi/api/control/util/pidTuner.hpp", "include/okapi/api/units/QAcceleration.hpp", "include/okapi/impl/device/motor/adiMotor.hpp", "include/okapi/impl/util/rate.hpp", "include/okapi/api/filter/velMath.hpp", "include/okapi/api.hpp", "include/okapi/api/units/QJerk.hpp", "include/okapi/api/odometry/stateMode.hpp", "include/okapi/api/util/mathUtil.hpp", "include/okapi/api/control/async/asyncVelPidController.hpp", "include/okapi/impl/control/async/asyncMotionProfileControllerBuilder.hpp", "include/okapi/api/units/QLength.hpp", "include/okapi/pathfinder/include/pathfinder/followers/distance.h", "include/okapi/api/chassis/controller/defaultOdomChassisController.hpp", "include/okapi/api/util/logging.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/tank.h", "include/okapi/api/odometry/odomState.hpp", "include/okapi/api/device/rotarysensor/rotarySensor.hpp", "include/okapi/api/device/rotarysensor/continuousRotarySensor.hpp", "include/okapi/api/chassis/controller/chassisScales.hpp", "include/okapi/api/units/QTime.hpp", "include/okapi/api/control/async/asyncLinearMotionProfileController.hpp", "include/okapi/api/units/QTorque.hpp", "include/okapi/api/device/button/abstractButton.hpp", "include/okapi/impl/util/configurableTimeUtilFactory.hpp", "include/okapi/impl/device/button/adiButton.hpp", "include/okapi/api/chassis/controller/chassisControllerIntegrated.hpp", "include/okapi/api/control/iterative/iterativeMotorVelocityController.hpp", "include/okapi/api/filter/emaFilter.hpp", "include/okapi/api/util/abstractRate.hpp", "firmware/okapilib.a", "include/okapi/api/chassis/model/skidSteerModel.hpp", "include/okapi/impl/control/util/pidTunerFactory.hpp", "include/okapi/api/units/QSpeed.hpp", "include/okapi/api/units/QAngularJerk.hpp", "include/okapi/api/chassis/model/chassisModel.hpp", "include/okapi/api/control/offsettableControllerInput.hpp", "include/okapi/api/units/QArea.hpp", "include/okapi/api/filter/filteredControllerInput.hpp", "include/okapi/api/control/iterative/iterativeVelocityController.hpp", "include/okapi/impl/util/timer.hpp", "include/okapi/pathfinder/include/pathfinder/mathutil.h", "include/okapi/impl/device/distanceSensor.hpp", "include/okapi/api/coreProsAPI.hpp", "include/okapi/api/control/async/asyncPosPidController.hpp", "include/okapi/api/chassis/controller/chassisController.hpp", "include/okapi/api/control/async/asyncVelIntegratedController.hpp", "include/okapi/api/control/closedLoopController.hpp", "include/okapi/api/filter/composableFilter.hpp", "include/okapi/api/chassis/controller/chassisControllerPid.hpp", "include/okapi/impl/control/util/controllerRunnerFactory.hpp", "include/okapi/api/odometry/threeEncoderOdometry.hpp", "include/okapi/impl/device/opticalSensor.hpp", "include/okapi/api/chassis/model/readOnlyChassisModel.hpp", "include/okapi/api/units/QMass.hpp", "include/okapi/impl/device/rotarysensor/integratedEncoder.hpp", "include/okapi/api/filter/demaFilter.hpp", "include/okapi/impl/util/timeUtilFactory.hpp", "include/okapi/impl/device/motor/motor.hpp", "include/okapi/api/control/async/asyncPosIntegratedController.hpp", "include/okapi/api/odometry/odometry.hpp", "include/okapi/api/control/iterative/iterativeVelPidController.hpp", "include/okapi/impl/chassis/controller/chassisControllerBuilder.hpp", "include/okapi/api/odometry/point.hpp", "include/okapi/api/control/util/controllerRunner.hpp", "include/okapi/api/chassis/model/hDriveModel.hpp", "include/okapi/api/control/async/asyncMotionProfileController.hpp", "include/okapi/api/control/async/asyncWrapper.hpp", "include/okapi/impl/device/controller.hpp", "include/okapi/api/control/iterative/iterativeController.hpp", "include/okapi/api/units/QFrequency.hpp", "include/okapi/api/device/button/buttonBase.hpp", "include/okapi/api/control/iterative/iterativePositionController.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/swerve.h", "include/okapi/api/filter/filter.hpp", "include/okapi/api/odometry/odomMath.hpp", "include/okapi/impl/device/rotarysensor/adiEncoder.hpp", "include/okapi/api/util/abstractTimer.hpp", "include/okapi/impl/device/rotarysensor/potentiometer.hpp", "include/okapi/impl/device/button/controllerButton.hpp", "include/okapi/api/filter/ekfFilter.hpp", "include/okapi/api/util/supplier.hpp", "include/okapi/api/units/RQuantity.hpp", "include/okapi/api/units/QForce.hpp", "include/okapi/api/control/controllerOutput.hpp", "include/okapi/impl/device/adiUltrasonic.hpp", "include/okapi/api/units/QVolume.hpp", "include/okapi/pathfinder/include/pathfinder.h", "include/okapi/api/filter/passthroughFilter.hpp", "include/okapi/api/control/controllerInput.hpp", "include/okapi/impl/device/controllerUtil.hpp", "include/okapi/api/chassis/model/threeEncoderXDriveModel.hpp", "include/okapi/api/control/util/flywheelSimulator.hpp", "include/okapi/api/filter/averageFilter.hpp", "include/okapi/api/units/QPressure.hpp", "include/okapi/impl/control/async/asyncPosControllerBuilder.hpp", "include/okapi/api/units/QAngularSpeed.hpp", "include/okapi/impl/device/motor/motorGroup.hpp", "include/okapi/api/chassis/controller/odomChassisController.hpp", "include/okapi/api/chassis/model/xDriveModel.hpp", "include/okapi/api/control/util/settledUtil.hpp", "include/okapi/impl/device/rotarysensor/rotationSensor.hpp"], "target": "v5", "user_files": [], "version": "4.2.0"}}, "upload_options": {"slot": 1, "description": "VEX Team ? Code"}, "project_name": "Pronounce This"}} \ No newline at end of file diff --git a/src/chassis/drivetrain.cpp b/src/chassis/drivetrain.cpp index 56654dcc..57c924d5 100644 --- a/src/chassis/drivetrain.cpp +++ b/src/chassis/drivetrain.cpp @@ -2,28 +2,28 @@ namespace Pronounce { - Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu){ - this->frontLeft = frontLeft; - this->frontRight = frontRight; - this->backLeft = backLeft; - this->backRight = backRight; + Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) { + this->leftMotors = MotorGroup(frontLeft, backLeft); + this->rightMotors = MotorGroup(frontRight, backRight); this->imu = imu; } + Drivetrain::Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu) { + this->leftMotors = leftMotors; + this->rightMotors = rightMotors; + this->imu = imu; + } + double Drivetrain::getTemp() { - double total = this->frontLeft->get_temperature() + - this->frontRight->get_temperature() + - this->backLeft->get_temperature() + - this->backRight->get_temperature(); - return total / 4; + double total = this->leftMotors.get_temperature() + + this->rightMotors.get_temperature(); + return total / 2.0; } double Drivetrain::getSpeed() { - double total = this->frontLeft->get_voltage() + - this->frontRight->get_voltage() + - this->backLeft->get_voltage() + - this->backRight->get_voltage(); - return total / 4; + double total = this->leftMotors.get_actual_velocity() + + this->rightMotors.get_actual_velocity(); + return total / 2.0; } } // namespace Pronounce diff --git a/src/chassis/mecanumDrivetrain.cpp b/src/chassis/mecanumDrivetrain.cpp index 73dfb4eb..c878a209 100644 --- a/src/chassis/mecanumDrivetrain.cpp +++ b/src/chassis/mecanumDrivetrain.cpp @@ -2,6 +2,10 @@ namespace Pronounce { MecanumDrivetrain::MecanumDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : OmniDrivetrain(frontLeft, frontRight, backLeft, backRight, imu) { + this->frontLeft = frontLeft; + this->frontRight = frontRight; + this->backLeft = backLeft; + this->backRight = backRight; } MecanumDrivetrain::MecanumDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, Odometry* odometry) : OmniDrivetrain(frontLeft, frontRight, backLeft, backRight, imu) { diff --git a/src/chassis/tankDrive.cpp b/src/chassis/tankDrive.cpp index ab80768b..1443abc3 100644 --- a/src/chassis/tankDrive.cpp +++ b/src/chassis/tankDrive.cpp @@ -3,7 +3,6 @@ namespace Pronounce { TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu) { - } TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu) { @@ -11,17 +10,13 @@ namespace Pronounce { } void TankDrivetrain::skidSteerVelocity(double speed, double turn) { - this->frontLeft->move_velocity(speed + turn); - this->frontRight->move_velocity(speed - turn); - this->backLeft->move_velocity(speed + turn); - this->backRight->move_velocity(speed - turn); + this->getLeftMotors().move_velocity(speed - turn * this->trackWidth / 2); + this->getRightMotors().move_velocity(speed + turn * this->trackWidth / 2); } void TankDrivetrain::tankSteerVelocity(double leftSpeed, double rightSpeed) { - this->frontLeft->move_velocity(leftSpeed); - this->frontRight->move_velocity(rightSpeed); - this->backLeft->move_velocity(leftSpeed); - this->backRight->move_velocity(rightSpeed); + this->getLeftMotors().move_velocity(leftSpeed); + this->getRightMotors().move_velocity(rightSpeed); } TankDrivetrain::~TankDrivetrain() { diff --git a/src/main.cpp b/src/main.cpp index d6c50e20..2d594c39 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -12,23 +12,17 @@ pros::Motor frontRightMotor(2, true); pros::Motor backLeftMotor(9); pros::Motor backRightMotor(10, true); -pros::Motor rightLift(3, true); -pros::Motor leftLift(4, false); +pros::Motor lift(3, true); pros::Motor intake(11); -pros::Motor backGrabber(6); - pros::ADIDigitalOut frontGrabber(1, false); -pros::ADIDigitalIn frontGrabberBumperSwitch(2); +pros::ADIDigitalOut backGrabber(2, false); +pros::ADIDigitalIn frontGrabberBumperSwitch(3); // Inertial Measurement Unit pros::Imu imu(5); -// #define VEX_ROTATION_ODOM - -#ifdef VEX_ROTATION_ODOM - pros::Rotation leftEncoder(12); pros::Rotation rightEncoder(14); pros::Rotation backEncoder(13); @@ -38,39 +32,21 @@ Pronounce::TrackingWheel leftOdomWheel(&leftEncoder); Pronounce::TrackingWheel rightOdomWheel(&rightEncoder); Pronounce::TrackingWheel backOdomWheel(&backEncoder); -#else - -pros::ADIEncoder leftEncoder(2, 1, true); -pros::ADIEncoder rightEncoder(4, 3, true); -pros::ADIEncoder backEncoder(6, 5, false); - -Pronounce::AdiOdomWheel leftOdomWheel(&leftEncoder); -Pronounce::AdiOdomWheel rightOdomWheel(&rightEncoder); -Pronounce::AdiOdomWheel backOdomWheel(&backEncoder); - -#endif // VEX_ROTATION_ODOM - ThreeWheelOdom odometry(&leftOdomWheel, &rightOdomWheel, &backOdomWheel); TankDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, &backRightMotor, &imu); Pronounce::TankPurePursuit purePursuit(&drivetrain, &odometry, 10); -MotorButton leftLiftButton(&master, &leftLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); -MotorButton rightLiftButton(&master, &rightLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); -MotorButton backGrabberButton(&master, &backGrabber, DIGITAL_R1, DIGITAL_R1, 200, 200, 200, 0, 450 * 3); +MotorButton liftButton(&master, &lift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); MotorButton intakeButton(&master, &intake, DIGITAL_R2, DIGITAL_R2, 200, 0, 0, 0, 0); SolenoidButton frontGrabberButton(&master, DIGITAL_A, DIGITAL_B); +SolenoidButton backGrabberButton(&master, DIGITAL_R1, DIGITAL_R1); // Autonomous Selector Pronounce::AutonSelector autonomousSelector; -bool relativeMovement = false; -bool driveOdomEnabled = true; - -#define ROLL_AUTHORITY 1.0 - #define DRIFT_MIN 7.0 bool preDriverTasksDone = false; @@ -116,9 +92,8 @@ int preAutonRun() { frontGrabberButton.setAutonomous(true); backGrabberButton.setAutonomous(true); - leftLiftButton.setAutonomous(true); - rightLiftButton.setAutonomous(true); - backGrabberButton.setAutonomousButton(true); + liftButton.setAutonomous(true); + backGrabberButton.setAutonomous(true); intakeButton.setAutonomousButton(true); return 0; @@ -145,8 +120,7 @@ int rightStealRight() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(200); - leftLiftButton.setAutonomousAuthority(360); - rightLiftButton.setAutonomousAuthority(360); + liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(rightNeutralToMidNeutralIndex); purePursuit.setFollowing(true); @@ -186,8 +160,7 @@ int rightAwpRight() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(200); - leftLiftButton.setAutonomousAuthority(360); - rightLiftButton.setAutonomousAuthority(360); + liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(rightAllianceToRightHomeZoneIndex); purePursuit.setFollowing(true); @@ -217,8 +190,7 @@ int leftAwpLeft() { frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(200); - leftLiftButton.setAutonomousAuthority(360); - rightLiftButton.setAutonomousAuthority(360); + liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(leftNeutralToMidNeutralIndex); purePursuit.setFollowing(true); @@ -266,8 +238,7 @@ int skills() { purePursuit.setFollowing(true); purePursuit.setTurnTarget(0); - leftLiftButton.setAutonomousAuthority(1500); - rightLiftButton.setAutonomousAuthority(1500); + liftButton.setAutonomousAuthority(1500); // Wait until it is done while (!purePursuit.isDone(0.5)) { @@ -276,8 +247,7 @@ int skills() { frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); - leftLiftButton.setAutonomousAuthority(0); - rightLiftButton.setAutonomousAuthority(0); + liftButton.setAutonomousAuthority(0); purePursuit.setCurrentPathIndex(farPlatformToNearPlatformIndex); purePursuit.setFollowing(true); @@ -291,8 +261,7 @@ int skills() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); - leftLiftButton.setAutonomousAuthority(1500); - rightLiftButton.setAutonomousAuthority(1500); + liftButton.setAutonomousAuthority(1500); // Wait until done while (!purePursuit.isDone(0.5)) { @@ -301,8 +270,7 @@ int skills() { frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); - leftLiftButton.setAutonomousAuthority(0); - rightLiftButton.setAutonomousAuthority(0); + liftButton.setAutonomousAuthority(0); purePursuit.setCurrentPathIndex(nearPlatformViaLeftNeutralToFarPlatformIndex); purePursuit.setFollowing(true); @@ -316,8 +284,7 @@ int skills() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); - leftLiftButton.setAutonomousAuthority(1500); - rightLiftButton.setAutonomousAuthority(1500); + liftButton.setAutonomousAuthority(1500); // Wait until done while (!purePursuit.isDone(0.5)) { @@ -326,8 +293,7 @@ int skills() { frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); - leftLiftButton.setAutonomousAuthority(0); - rightLiftButton.setAutonomousAuthority(0); + liftButton.setAutonomousAuthority(0); purePursuit.setCurrentPathIndex(nearPlatformToMidIndex); purePursuit.setFollowing(true); @@ -364,8 +330,7 @@ int postAuton() { purePursuit.setEnabled(false); frontGrabberButton.setAutonomous(false); backGrabberButton.setAutonomous(false); - leftLiftButton.setAutonomous(false); - rightLiftButton.setAutonomous(false); + liftButton.setAutonomous(false); intakeButton.setAutonomous(false); return 0; @@ -408,8 +373,7 @@ void updateMotors() { while (1) { frontGrabberButton.update(); backGrabberButton.update(); - leftLiftButton.update(); - rightLiftButton.update(); + liftButton.update(); intakeButton.update(); pros::Task::delay(20); @@ -425,16 +389,14 @@ void initMotors() { frontRightMotor.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_COAST); backLeftMotor.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_COAST); backRightMotor.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_COAST); - backGrabber.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); - leftLift.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); - rightLift.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); - - backGrabberButton.setSingleToggle(true); - backGrabberButton.setGoToImmediately(true); + lift.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); frontGrabberButton.setSolenoid(&frontGrabber); frontGrabberButton.setSingleToggle(true); + frontGrabberButton.setSolenoid(&backGrabber); + frontGrabberButton.setSingleToggle(true); + intakeButton.setSingleToggle(true); pros::Task updateButtons(updateMotors, "Update buttons"); @@ -444,7 +406,6 @@ void initDrivetrain() { printf("Init drivetrain"); // odometry.setUseImu(true); - leftOdomWheel.setRadius(3.25/2); leftOdomWheel.setTuningFactor(1); rightOdomWheel.setRadius(3.25/2); @@ -452,11 +413,9 @@ void initDrivetrain() { backOdomWheel.setRadius(3.25/2); backOdomWheel.setTuningFactor(1); -#ifdef VEX_ROTATION_ODOM - leftEncoder.set_reversed(true); - rightEncoder.set_reversed(false); - backEncoder.set_reversed(false); -#endif // VEX_ROTATION_ODOM + //leftEncoder.set_reversed(true); + //rightEncoder.set_reversed(false); + //backEncoder.set_reversed(false); odometry.setLeftOffset(3.25); odometry.setRightOffset(3.25); @@ -727,11 +686,6 @@ void opcontrol() { //lv_obj_t* infoLabel = lv_label_create(lv_scr_act(), NULL); // lv_label_set_text(infoLabel, ""); - const int runningAverageLength = 1; - RunningAverage leftXAvg; - RunningAverage leftYAvg; - RunningAverage rightXAvg; - // Driver Control Loop while (true) { diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index d180ed66..4eeda71f 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -1,10 +1,6 @@ #include "tankPurePursuit.hpp" namespace Pronounce { - TankPurePursuit::TankPurePursuit() : PurePursuit() { - drivetrain = new TankDrivetrain(); - } - TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain) : PurePursuit() { this->drivetrain = drivetrain; } diff --git a/src/odometry/tankOdom.cpp b/src/odometry/tankOdom.cpp index a0ce8121..39f97c79 100644 --- a/src/odometry/tankOdom.cpp +++ b/src/odometry/tankOdom.cpp @@ -8,16 +8,12 @@ namespace Pronounce this->setPosition(new Position()); } - - void TankOdom::reset() { - this->imu->reset(); - } void TankOdom::update() { odomWheel->update(); double average = odomWheel->getChange(); - double angle = toRadians(imu->get_heading()); + double angle = toRadians(imu->get_heading()) + this->getResetPosition()->getTheta(); double magnitude = average; diff --git a/src/position/avgOdom.cpp b/src/position/avgOdom.cpp index 19405a58..5387e33f 100644 --- a/src/position/avgOdom.cpp +++ b/src/position/avgOdom.cpp @@ -1,13 +1,13 @@ #include "avgOdom.hpp" namespace Pronounce { - AvgOdom::AvgOdom(std::list odomWheels) { - this->odomWheels = odomWheels; - } + AvgOdom::AvgOdom() { - AvgOdom::AvgOdom(std::list* odomWheels) { - this->odomWheels = *odomWheels; - } + } + + AvgOdom::AvgOdom(std::vector odomWheels) { + this->odomWheels = odomWheels; + } AvgOdom::~AvgOdom() { } diff --git a/src/utils/motorGroup.cpp b/src/utils/motorGroup.cpp new file mode 100644 index 00000000..0f6ceb83 --- /dev/null +++ b/src/utils/motorGroup.cpp @@ -0,0 +1,30 @@ +#include "motorGroup.hpp" + +namespace Pronounce { + MotorGroup::MotorGroup() { + motors = std::vector(); + } + + MotorGroup::MotorGroup(std::vector motors) { + this->motors = motors; + } + + MotorGroup::MotorGroup(pros::Motor* motors ...) { + this->motors = std::vector(); + this->motors.push_back(motors); + va_list args; + va_start(args, motors); + pros::Motor* m = va_arg(args, pros::Motor*); + while (m != NULL) { + this->motors.push_back(m); + m = va_arg(args, pros::Motor*); + } + va_end(args); + } + + MotorGroup::~MotorGroup() { + for (int i = 0; i < motors.size(); i++) { + delete motors[i]; + } + } +} // namespace Pronounce From 247e2588041ea70612fde092a09b6c9354bb69d9 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sat, 25 Dec 2021 17:50:45 -0700 Subject: [PATCH 06/21] Still not working --- include/main.h | 2 -- include/utils/motorGroup.hpp | 47 ++++++++++++++++++++++++------------ 2 files changed, 31 insertions(+), 18 deletions(-) diff --git a/include/main.h b/include/main.h index 3d046994..d2e3c5eb 100644 --- a/include/main.h +++ b/include/main.h @@ -81,8 +81,6 @@ #include "pid/pid.hpp" // Position -#include "position/threeWireOdomWheel.hpp" -#include "position/avgOdom.hpp" #include "position/motorOdom.hpp" #include "position/odomWheel.hpp" #include "position/trackingWheel.hpp" diff --git a/include/utils/motorGroup.hpp b/include/utils/motorGroup.hpp index aa8d768c..f2631e2d 100644 --- a/include/utils/motorGroup.hpp +++ b/include/utils/motorGroup.hpp @@ -13,50 +13,58 @@ namespace Pronounce { MotorGroup(pros::Motor* motors ...); void operator=(std::int32_t power) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->move_voltage(power); } } void move(double power) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->move(power); } } void move_absolute(double position, std::int32_t velocity) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->move_absolute(position, velocity); } } void move_relative(double position, std::int32_t velocity) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->move_relative(position, velocity); } } void move_velocity(double velocity) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->move_velocity(velocity); } } void move_voltage(std::int32_t voltage) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->move_voltage(voltage); } } void modify_profiled_velocity(double voltage) { - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); motor->modify_profiled_velocity(voltage); } } double get_target_position() { double targetPosition = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); targetPosition += motor->get_target_position(); } return targetPosition / motors.size(); @@ -64,7 +72,8 @@ namespace Pronounce { double get_target_velocity() { double targetVelocity = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); targetVelocity += motor->get_target_velocity(); } return targetVelocity / motors.size(); @@ -72,7 +81,8 @@ namespace Pronounce { double get_actual_velocity() { double actualVelocity = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); actualVelocity += motor->get_actual_velocity(); } return actualVelocity / motors.size(); @@ -80,7 +90,8 @@ namespace Pronounce { double get_current_draw() { double currentDraw = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); currentDraw += motor->get_current_draw(); } return currentDraw / motors.size(); @@ -88,7 +99,8 @@ namespace Pronounce { std::int32_t get_direction() { std::int32_t direction = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); direction += motor->get_direction(); } return direction / motors.size(); @@ -96,7 +108,8 @@ namespace Pronounce { double get_efficiency() { double efficiency = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); efficiency += motor->get_efficiency(); } return efficiency / motors.size(); @@ -104,7 +117,8 @@ namespace Pronounce { double is_stopped() { double stopped = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); stopped += motor->is_stopped(); } return stopped / motors.size(); @@ -112,13 +126,14 @@ namespace Pronounce { double get_temperature() { double stopped = 0; - for (pros::Motor* motor : motors) { + for (int i = 0; i < motors.size(); i++) { + pros::Motor* motor = this->motors.at(i); stopped += motor->get_temperature(); } return stopped / motors.size(); } - + ~MotorGroup(); }; From a3521ceea02a4354025dc5540d2ae84a477b24bd Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sun, 26 Dec 2021 12:47:44 -0700 Subject: [PATCH 07/21] tested on robot --- .gitignore | 3 +- firmware/libpros.a | Bin 6963476 -> 6964326 bytes include/api.h | 4 +-- include/pros/rtos.hpp | 13 +++++++ project.pros | 2 +- src/main.cpp | 77 ++++++++++++++++-------------------------- 6 files changed, 47 insertions(+), 52 deletions(-) diff --git a/.gitignore b/.gitignore index eca0e9e9..d3cf9e0f 100644 --- a/.gitignore +++ b/.gitignore @@ -5,7 +5,6 @@ # Executables *.bin *.elf -pathTest # PROS bin/ @@ -14,4 +13,4 @@ compile_commands.json temp.log temp.errors *.ini -.d/ +.d/ \ No newline at end of file diff --git a/firmware/libpros.a b/firmware/libpros.a index 3f84e8710c36c5693779951d989f03e3fbf6fca9..672ff7a41310c91fe6f5f2c9248cc8f33dd6c312 100644 GIT binary patch delta 92436 zcmeFacYGB^+de+C=Omj-3W1!2B%}ZVLLimUk_ss4l;Za`;&-?!I`}%Rtx$ZJ$=ep#e?~^8mQG74CH3vR81u}<*xg$%wz&SJL9SI`|6}oe%s7?YUjL}L z{%OS*RL}K~M*V_1N8hf0Hf=9#0Iq+?+lv~&|KtDvHUR%0|1T<%|5-aPYW+Vf$@o7h zu76VL1=ex>qfx)O0U-asxW@iLTdse|+lw0X|8Mx$wtvK|vZD>tsN5Ouq7SRsQcJSG zT;`r&w&%=k#k#7MBTr@B6o+ z%=5ooT-1Trk=`$~`0U)s{$g?cp`&m5S@z#AE_8D0!2exwy}-`>NAzYn%CU{i|9>bh z>F{_Q^Z#Eefw_;cY{ivb_;b8cV}bv+Jg&zAa}?L}ihnQX{`@KX%f;JOznatsu)P*_zMhWq`#a=|oSKu0>;xfS>e!n@D<@>wk zbbprbFO;yFMO_RZ|GGr9ZO9^KhqB1tE4jagHM70@@T(rhp* z@PbRh2#q~oT+b^=j_sHCzgh~%v}8tcnc(k#KmLFf&Q^+4`H21f;`%3*USJ*9KN|Jl zA3)sr(d_q%i=i^~MR_r3R1R?;jt^0JaBX+HD* zUa6bT(*C5l{>=D?w#!9X+TSVnCb6{NFRni_uu|s(|U%)>#QmMh~e_GPRKVUDqRL_wMqzwBneSE>)r%bqJPrFd|bRsS!PnuU9_KQAsg96j-mO07ld z>|YnxpEOd(XDa(kWpz`#m9 zPaHayf6D%9>1>_vg#S3atC{rTFuT zKahKr*~(D1jVzFBn>Lt0@eMyQ3|tkxdhvStr#t zqLZmO z4{Xpg4{Y!VxoG-Ftx0iYKAG-WsE?@```AA?^QGTBV^6rzTqlW)wh_!?>`U=LP%VJFR zB-oYd8kg&a!=B8d3Jd=Qx$x;=Yy6Gr&QG{~;lcg#OC zUJao%aTPrIt;hbEZ#@o(3(2m{yp%gI-|MDEvg248SfX(bO{d3!v(M+y1bvY^d6cOM z$ekEGxl@y%%uY@6#B?^b4Kgr;Z-0=-Z3!LSNl;aQIQv?HU6XgU%!?A7xvQmPS)5rX z(Z7l#bJQe97i02Diw2nFOwBjsoq5zszd4MBl|w6|B-l0i@T!o^!>dB`T4UiW1HoH? ze3SYbld;5AEF^R3oB58EH#?CGy>dF=yg^cvoFErX=1Vohn$D$8MxyO->ST%pyC$!> z9G1D}a`>{5IsCh|jaZj#YUIQv%#Ii%19UaTWhu1qjs&|Ve_SMg=Ep@M->V`Al`KwP zPYlVN+dI_WXrnyteU?3$eG*Qm@~zeX3_X!_qT($10DU`sArS>p3T1{w#QxaOFho+c7wZ=ryVa~K zqrGoT;mV(z8Zd!1__*+`nxeG*Gl%Aw zqu3{1lqOM4`g^WopS+Yqvtm!N&y6E6eBSbpzt}B@&l|(yPaiZj6x*2-DivSVJcp*n zyyE&qQzPl=nZHC#UsHqm4xYUJ)e@QOUriWa*3?#ta)xBqJDRYox~U<*%)+@7FD@}P znAMQXLhmF-1)G|Fr}G78b~>8aH7tkb#`VN?p*b|0wWPFgQzO@hTVzs&)Et`jO_Da2 z$f1d!m^3=g)Sxd%=HZ=5Nq#vrA;*%^b83d2dtUS9Ez~jyPw=l2l3C<2T(T=(@l4KY z1sO0n^M)h&W$QSlrf))WMe8_aRy|%P`Nxvknh_XYMrPuKjJ{fw0Ft*YcG<`zrM$jmb; z#oh9j!CY!h$|p^8)Q4m3cl)M#TYj=1Xq#FZnNECLqy}0cNkN}kes$^`V;Lk0_ylL( zyPx_=UbA&s>%2$FhykWX)(RO}a%)vnBWvB*TQas#4o$HeCA$_dHCRTD%q>1?Q>`T; z7gqDSX-D74=7ZDH<+O^{v`U`^_tM&S&*tOE3~5KpO7fhtc}Tg;%|ps38&i}dNIPj!`R$7;EH_p}k~rl^c4Y27 zQ(@8pv#wmTofcG#GuCX9pcOiKeYux1*O#kwG05mNk{0rs29>;ynH4F(C!Y*Y&pa7k zd45uMZRV7W%F91AH8P%R_*WV5N)F8zbE{;I$e~%Er)nRo7BN1#)S0T8rOs4y85}1G zc{V!pOSLk_*~QSr53X*WZ;}KtI{D6n>X~;Q)EHqgCV8GvxMt<$W}i}X^=Qqu$CV~o zvD$8Kt#bxr$&)KBs+C!3QSJ2Jri&zOiBFyJ^K)okT3u(=kETZEPy6D!)xR_}nb1UR z%Vx%jCa!*k_YKYDQ&;O}p1PVbdV%R8^KH+u4KjOSZ+27~JE6G1iR+Z2UKe4;a{qm0;hEV64M0 zM;QyY^GeO=BMBa19LK`FT|Rvw^wjyqF^qYS_2~jBGOhzYS?;!t`!WGF3p+Aj`7VIa zQ_pWYzYa0G^XaMN{Emo-b%yddQ99NcRX6ON>8R^l+9v};YknD>`j(Bilg{U6a|q?) zpG;#cu6RD+3IV=*8GD3A9B__6vFC;-i`(BG*2-bk#Hv_l@w#D)d#EOl!sCydJhfOh z`F0J)`oM8E%3KtCO!g*!5z&R6#Y==mK2uFrLok?4wj7gfl#L+76@4I^94B0boq0UX zVciuA3p-1=Dwc(@ho|rG)BXVOdHRO+OhyB_>Ud2;qrFJTRVQxGdB$4P;k%%;6T;uZ zv-}>fLi2|HjLSr=Vmzd{VKq!w%xS-cho-dQBS=4+QmuiIelw-xNvs+3e`YjlJKh9F z8#l%2!4P#ztXm(V7cWWkz_{%K7C5ftP3Ll$VgEo&d?J<q&$i|9 z{NLjGw5i5eg04X^pX;AhHpU`JSZH-FSy*I=l7_{WD0x_7i6DacFH>W|>*$J!<IO_F|UKNK6dUd6*u%#VR$GuM+l7>a2+6x+D& zdk=~rnpjEayJnlVCt_(aXLx=|=T4=?6iGUFSxyP!d@*Nv*RnxK)Kg6Qj&c2XBc)LE zo#cA&no6PQJFRBH!=UdoCF1skr0;A_`o6Gwlk|OQjYZP;6~yfHoip1~^j+Zk*xbfg zBz@m-y@QuA7D?X~ixElRRZEogeQSx5zH62!>ARuEV$pZg8mgr4mL*F1Zs(-$JJYJ@ zyT^Ur4m3t8>3hia$hL+;()T0Re+Hj4(YmDX7p~771w{}vioRdXHbLLI;?D3=lD=n3 zYtqLwb3Mq_$h9=J8s%w>T4#>^b4p-UrnG157?zn@m42FDuZ&VCT61gqHV>sxwC2_1 zs?-fygOzB~8mi@3m0@ZW7?h+n+!7_N5fHP}n%`_o(HgDkM{HaUPM5S6)b!*b##kh+ zv8na|#w8kqLZAn^-TcV`3gqCAfCYn}7Yl@~9e9M?M zNo$&>kJ)P|B&}sMJ#4F?khE6NbXz+pGBEXu)=FlZwkJigY}1v9sf+f6SlO~lwyRoJ zxmc@ZS;hSXr-OGBUWv{E{DCNu=nQem{Mtg(`*vpRB6TS9t5Z#gxj@?}(PXlHP9{5A zJxC@yS^Y~UJ6obmuU*Wh6p^m(nqKEi)wN=>r>1vAZjxh>O!l_OkxcfnM9E}dOO#CZ zvqZ_{0BdOSL^se9C6R-)qAugiAekJTlgXi`w_uPBoiUL{8Jh{v>CxTBS3U&0M9gTCQ@H&dRY$sSD;PDuR-+ zOeb_>tTfJGYMCz5^ov!LLM_u}n*J$v(&VAYeOt{@q_Ip_D$&!(zH4%lyUrShBzL_v zNJ;Jnh}oCvM%9*i^4y~7C47vr$YuJDrq9;78jB=%yTz9zH`5X&x$jw`B=>zwl;rME zW3iU$PHU)=-CdR_$=#ik+&!jMk^3>C&S8vHl6yeY@60t6lH9|Z{_6@uA;~?a>7QYj zQaXqxR-$$Zw8pusUzHMNU8)?(WS5gW^Zj4PI@sm<0atqqz z+0$IKg_LM6+E^vx3?+BGg{@BIqAg+#Ns?O>Vs>)lRArOg;x>KP31cjh+(euHF(!mY zYm?+ATfIqgQ!G)En`()Y+>(|k$t|VEVv$?g8mc6>j3r8P%i3~~Th6p9ax2<&k2qtb za?z&S^as&~LXun6rU#BS6q4K;HvQF8P-HFIT4tMAwC78ii?*K9nv1r+uN`dqvQ(u|ymq$9J(HiYXuBxUT(sS+ z$&$^7nJazyyIJJX%&!&I7$QX;{^#hA4$?FbFl)Ub=M9J$eOO(8RsK#RP zy2l!-Prtv$Ob%YRhEtH=EwDqcIk_ zI-l9}X}HHD$0Awec9|*6)u~ycWYK1cl0~~EN*3MiGI3Ze>Pj|Or-vm<7Cr4bR;RaV zRV?PR>v8jpkxCW=?E1iRhC;F!WY>3w84Af_uw6g%EfiU+GsJ8YEdE--T%F-cYqA(& zImy+T-=2MS(!?;wM3Eh6;xX$ua)e2(p_ULlGiGBefHbNSR}92EUM({tZs>t z*BX{6d97)QlGoa5EEcbItf9))S=SOJuk~{BnqgWMuZ`^bxfaGqC9h5GdfF?7Lh{C?v0K?0SX1P-I=Hwl~{U7dRc12twtRYDY_yTcysHD7Q*othx!JQY9?f9in9= zkb4*FBHT*7gY5bz6_rAfJIt;xyrL9}+>vUI%tbp&i6*(OoaBzR#vsWZXNi*B@es3< zJ3+N&k~`V1N7{|CNOGsz_1?zd)K+P_#g`;^h9ydJXIi2p_f<=jIh6NOG6i^+vBlk(GK^m~CRw z`c*a;?P{ep7wsC$NiN#8ITkI^$Q)Bdr^?`U;62p^RflGj5Jv-5gbwPo^p%&xb8!x)R?^%J{37DUUj z$VGd~qDu1msU=EYPg|no^)pM9yq;BKv3UL58me5hUs$5#^~;>Ro-?hA*9&&N6)scd ztVv!k+w~^H4Ta?OnqB|+M?)cby=B*PM?sOr>vv|G;5DSG$?JWkHFf)kdKlGk`Q-PX`h zNL~}&^kOZc$e@Ff_alxR38ovP zs55PKH@#>(rBLM7cGEZFbVnYF+FG+5DOO)hxutZ62M@y9Cc2;At$n9bc zRW91DmMF=^Gyd#1C3=`vMQ$%Q{kkzQMQ%SgJvhx6x+Hgyo8Ai-9P(Hsxx?J_5x3wG zL=!8?9ci|SMH^q!+y{?QT658kwVV<}_nLT8GYQvKUrjaXOLx}~Usei5Up04qO^i|~ z`f9q%wdpYEtEEJDgT6ZMa&007%gfXH?m5Q#N#0ft2J{(E z+S*xTmHf50M9E(VcgY`|ft5z{sQ7!?UB6k!P)PoIyXzwY4Ta>d zpS!-TIAeLJj^b~C)#DRUsF{3ut<#vP% zy;Y#r$R}qm1B{_E_c@te4`YK*tb=M@k0$_S1S4VDBe*ryGqH-&O1tK zS1UP%xFl}Zx~u#6Cb#RX;Yx1TTcYH4Lr!itnFph|-R7<@I%kYlo=~^D>pM3X3d!yJ z?)vTBhC*_?(_Jqwiq~~|be0Qqx7D4zTe!y(V2=FH^#k`hh6FDudH`&(yFPKXQYgOfsR|a~_myn%{XoeU-w%~+@%_Vd zeE(<-SMvRnB}%@3&dK*<^I#O;Pu=ya!WgaOo9lX|r-nlEZP)dDxW6KgNAj)fx^Lsf zN~6}Yr*0-bNx8QrO3Hndh`c8$&t-{{az9H<$edN*`Oxlah6fS4oi0{A8|4a%oPdn! z+0?5v=Cl_Ho-J~d z&mrx3>wA}n;C&H{5)-#2M_`fkyK-@!5*GS&xRcqS$9p zMfcBVWiSzs(mgc^d8Zk!gUWMfrS!Yu{FWE;sy(s658sfGR7%GZt zR+&5KRa#>RYgjtt(Xhpvc0M<&jn4WF+zga$RD->N<lI2 zv5`%%#OQqso)0}op{PS0`4x^j?_7PFSliSY=cOed}z-NK@N%VgX$*z*LQE`T}vL8J;*d z5RaQV!}u%_+#Cr^9!e*!AHr$rV>Eh^DiYw-45tHN0b8l{o?L(Z6Lq|g$>}hhSoG^% zVZx0)8kr~Q12!P&9sRj}CwdBxqK9>!+t7)e=-FIP7xh{= z^Lom86Feu8s?rZFHoSlhM^VIwUn=?{fW=INrip zpmxSi1Re}C$b*1%lheZjX7#`k;Z2(*9hB47-*b|4{22~glxvCTm$Ugb*B@b-)3_f{ zo$J)Kn$1^u)Ha$;(yQ6L#Pzo(D#!eo34TV7v$j~;(it1LyuGrh$-Be#_r+J}#`Qxf zcsibPpY|oq$W%9&(Z6g`deB%_>3Z%rSMH?1gQPf`W)RTbpS z;yskBy_NZHPP2+wH@ug^n~LGBocYvbM`(J<6>73e;MoiRMIMBV&R9*KAl`3<;G88c zv~q?Om(yBW)8DPc*faPoq6!3LEo1KGw5DtN4N=(X3~L~#wU(xLdZv!>0@ZO_YfUTH zqTa%G-;?xeTI*?gH!Lbrcw>&#!Kol^i1#7Hn@(qbSFXCsLrrf>P0zJSDVk9g*?wSm z5B21dIf?~9>1eC@)Wz(pJkd?lyQVWXjoiI493CLYBqzPS7DbP(Jjp009j{$fJgR1O zCshb=SvBOW_to_LjgjO1CaFEIqEDiO8$u2*#W4iY$XH;ZHyArN z7~^D~{oocB2dcSyyw}$d7V=5Il9ZgwM~Dh-o%tI-oxzw#Xm#&iAhV!vb;d%Q=9f9r z^CtW|ZAWy5Hjn-hm~$_ED5Tc<<)0Zlvksc*(s)%H#ZD5dAkFOqJ``KpI>U=esbj!T zhYja0aO`I~^UFAqFx6mpeZ6?x)*0oZ6KH5}eHfbmhMMQ^!2Lt3$~o$!VEy;u)G&_f zbFW@+Ll~f!MY<+G{w+RkQ-$l~Te)-ZPAqhYexR0NwwFPlD9Y^B!VR@Y=<`P^a}^!~ zTahe#?TxUz^f*kYY&{*O8kV`BM+D4`Yxl>@aj!$4K^Tu1y3o!U!N-Xw?Xb`3xeCf@ z`Wt9~>hbmX*lIQ4)%p?4uj&^uRB1j6)2S?T2&#p?sh``=7;(XG!E`UnOu0UEu3iw~ zA@GbH(_3@f0x48 z9^#@4O#MtVrw&==_5)eyR(-7ar9JjSM{#K%x>G+P!aF#Ft92;?X`k-cV^lwes-K$G znb#&z9C}Q@gykZMybaTR%N$jXX#G?_Erxe+=C8CE$(XOst>I76T4yF_9~qyQ=DTn`mZ zJ30&T&0)tUO~o#l4QsV1G40H#!Z3 zMst0KsMg6DPll?_ec`aSW`5>vQ7RfKmo zt!Z38DynxzUFlqg>*vJa&dwtIORmP^$T}^8jt|y6lT~Sv$ z_u%@=ViZ{~od9rgO^q7_lS(I|4N1f+$;{JoxvVPF5D^V zba#d;sbj!Q(XYEROw)&oSGzl7<>dqNT`92}K6#A9c4{eFGZWiMaj&~Gua}v~ym|=# z9?o#SMHKIWK8*ZyRn&!)$4E!M7_60!u83hhoDr_xa~Qi)8T!IikONTc9_wj=82PEB z#+A7`Om(x&Mt<6Cn!CW%Gs|q`r)^Ieqxs+yVVag@Hu6)tV6BvW1#D}x>_||QpOW_) z)jx*maF*G~PwrEV{B#+n8(C%}KTQ<^0ci9tQHQr2~`yk}O*`cxe2nJs1Q75Cw)a+NpN z2a3pE&IBuUy(L=oGM$mSrijtKOlPF7`(i^cXPnABNK)yMdv=qPj8A>`yf9p z6}$U5qjUyRR8 zSc? zqo7pjjHX7WvsbVaW}Y<4&bfS$&YCw+>1=tE=hIpKI$7zgcrgfB>Fg@D7s2bHX%2N8 z6gx@QUazCL-ajk9tr9*1uoaNGue-ibBn&{<8oRnmqQwAbc#4tbVyHiKFq9lO{^V&BTg%JK$b#i}8Rnrdjke6@E^Rdq+DeOa-%>7o z1^m`pzFzHeAtg=LpN=!kAH#ImFc;0rmy2+6pdR>TeB3bXFdO-Dy686$+1W^scf~A{ zjBMx>n@BQpUtV#7BqP-o72lC$WVR~8XOJ_WhmqNai4udHVbzQr*5eh%QfUUS)WhZv zMNOEQ!-B3GX01LLM={Js4$CKA8-%N$a$?OO>~$WBlY^WN4`VMiTHGVaNJH_$e{fbB zx*#eHc1Fb;JEui0jBU?P=s?3xOm@Np!6S1s_fx52IvVhjB9asPQtTY;EKyv_*jUY8 zY_u@}^jWG|V1kgM1RF=~i2(n?k%#mXUAThfeV)kT~{ zB`aCA70<|OCaaR7$WT*6vU(&MSt63v8)DQ@)HRdUuVVdBWT_$I>`-ST&F?o6H_Tbz z+D5%5#t%bNX1dxhHdrEZ(irjiFf?W6q+P;&IGoL#M2Si-bUQ_+7rJ}JJc;klOMgUqxqDlsmkMp4PcI)}?U}o!gR~B<%~C)tW3|vU ze+cz2DE0;IGPBUzd6hpugG%S9Vh7oQaS^#N!7x99>2a3X z$WFtBVb0x*u@Dqh+ssatF=tkG>RL^?@QUygJ4QJJ`AKnN6jFn+U;9ja2gzlmn~V*H z`vSNxvzqoY^3Oh89T5S12TXgj%tk_r>us37g6UG0+1#BWxyahT!1OH3jFeTKE+2QN z8QU{QbMS*=%!-l33f93NL(^=g!IW;AIkjkBKHe5bMrU07?afOL_;5$jagf-L87+HnZL~LN$Bn;ST!Ul6)mzmbL*9M3HD&vqAfcG1g;jv z3YRn9yi5!hU%IlAU7wRiqIw;b7E(nbpKqY!u#(*z5jzHp&rEiGMAI?Zc48yMt7Ee5 z#5Rd{;A~w)<}YA$FrX#w$%?&WoWTKVnyib+++~DgY_^PdUsM{4H8b8Gu@53|EUt}p7ExMcy7R&@4t2~-_nD|Z4w-JP=to~u#eDkuM(iJl-B}~? zXdK#;nG9Etzln(PrifkIbWsDMm$V}7@e*RdcxOQ??;RFP$=l3(o5WE|MBeKxey~LB z#X?2?2^f^Q7fTTJCZMjF|DK4U5L3(zSAP7Vo{Z0=HV7~jMGW13G^S5_A~kv!7RM)G zOj5?BWkvBTwQJ_a%c9^!h-PjaFX}_&7ev2_&iv1Bxy0g$&O9Y$5~RD(%#-4v^ZeIv zN0+De#TKHU7Bm7Yx9k%qU@ytx~} z@V1)16~{D?!fPLD96_;@#N5`t4|_XJpMt}b509?GcGtA4hexA)ahV<7QOoxZt~o}X z5ThqKtMy7cf(;XT`<<)Z2Ja2VQ#aF=bL-e(>}cd4)0Xop*%1H5zm zrP=56hKxl{jiQ4H?bsdv>QA}ATALUvi$;8!JceyXRAtyI^#C(o>v zId=+Fo2cPHYN$%?GcH4JbrEva+zDNkyp$iNo@<3H0(D^<8JEAy(7VH*{o=udS6M3k zFhh%hU=f}rQOcp%3xB|}ewbkk4x6lvQCcdi*o2=*5O=0HJzSnkFuhT&xz}QtmT?lJ z+VEUWX5y9rTH$X|4MGU$0l==X+3;x3^S65mj~<}FPa%Z0tb_09;$GiC?nOd$@q)kJ z#PeWk;VUTZgwVo!z`f6X4u^yiGk(MkU6*QMId4)Jt_9k;dwKo>m1{e;^#yvkmsn68 zm4VSqpDz(T1(STk;vJ9+mGkNa{R%!K9g9GQd7;Ywb)bs;<~;TFHYdMA)g1MIV5}y( zZx5TD08awKU<%^P)w@3erBJPiTX!&YDClr_H+{roEaY>zD ziltfXx#$}Zi%2msfyI6uGZ_>mD;WbjA9EgZc_m|H7h;}4uC8PZ?P5$W47!1mF}6!F zuRv}kWmh6b_f1SQ479Uy!0;}|d;%FyKF#@gWx+q0}Ukf=og^Tg#3O5 znnEZ5+j`H}3B};t=DC1SIqdR0R}var3TQK-U$H1WKOhuV4rm{tGUb6z5ZY4#=nFz~ zDgs^Zg8UVd`V!zBDBXF}pedv2yIBza6#;xVH{=$^cT4%5)=ey#;mqr*x&owNlI-52 z5f1$uA@P>?2c7--hpaew169zarcs%SO=di)C5Uv0PJ|NZ=}ubqjQGCQ5esf4t$R3#rPDP zTdc3)bPo;;u_{}UPTapZRBr2WPUB}Z{Zbj@EFKE4f~KcBi>pDM)AY#Z)SL@7D#D|d z>BSdNr*3pj!||uPoqHppL&H14p-)byvfm;3@(1|4?ala}2;(fvf$A`~GUle?zt>4H7eOu1DpN~Q!c%{ zFe`ab5KnZ2I-O=qnD!l9mJ2F=Df$O?P~6#AXH@nvzqzw9A0$YSZWF?Tm=& z3*!jWK`l-<>GiTr-#El@dJ_&yEGM~`R8$Q%qAGjNxQYl^#eWu+UUxcNAAX6O6FV_9 z?ltcbJ_qS^E~QB1zo9{`Cx#~Dat+_#5XxctssqM^?}nX6!J(Mxq-K2#zc?QjmmW_Q zG=EJx)`C-p>Bz?LuK8dbUr68GRyx_FQ*Ss7w4By*xe_Pix!BX!@#`CMRC4u|eR2}D zN^rLh0r<{Dja^o)s3<(%;a|AjLl)rlSL-4c;{c~KY=vW$ycL06T#jTnLNYS7oQY$_ksiS<-~uY7dxjWej-e>%<8;}@DJ5DEIA+3l$VQNi0>`XV~?% za|}B#4r6K4f$x)Ea%If4=ZV5qz!7SNH-<;s=e)Yn?7eE&7omTdsQ7UFyB=(!>1M20 z+2tI&K4reqd{R)eP$0RgKeZ7_dYm$VmZk-8`a6=JG&l%!OLOYgu^4t z2`wQFmrXm4VcFeueFwh1K)XMRI(&6nE@Lmx*YU2M2jXtNoBl>TPL*_wscq!``6>^-w?My>Z1Ujg;EXw`;ilKdmW9;XSvXv?oUYTLbeHXO z#Rcojm^X?%7lRP?N#4J?(*Pi z?%v}uJhwU6HS#L%0awzosV4#tq1_WGc9K}CwAXOgtA`tQeiOz=rh|*qtgzG{uu0{$ z-1XKt;i=H{0~?_zvK=EbWn-P(^*#%Y#!}!=(RAXaWsh<#;O`kOmxYZ+#9P7xua>H& zREH`w$Gf|9$6UkB1&^tgmu$<8EkgY{?)m@>k`A7)fWumHs!Dyi$&i`nu9wPhgv>tJ zj%3-(l|-FI?)tB_jF`I$+bzppHqCV$4(r|Z*vj~3m{4~VHFYZ9Hsf{gd9Z~+A8Xn; z9TywV-@XP5UhhAQY*Ze`x|V~SLwOQXODNsFJXi5_&^>Q$s;%P5b;v!GPDb|s*w!uq zMQMA6f@_bi-scA3Dwrk!3-oXy=v)E)5!c^gTKK!@bO&`z600E1WA&Y@3^P9i+a=S^ ze ztH7haAW*Zsp#}3dI&;m*x z!X>Xf8h=>xqS#4f${`NFV}==04v8?9GaWdM(eO&t^lK$duV(P*V0kr@UNm*xJWAm; z!O!r+m9n={aG7GcsmA0C*VgncI58`)F04}Ne9Re!Qlisb)?Rc zME&{LK8WhL>oLVG4^4->jWLFdY12!ig4WY}@gPja9=fdJUTo#o-c*N`o~ZM|Od&XfAfF6uaIT%4`v8~;O-2S%8NbJUzsCrCHuDo$cKk4}9WVmlS=XpuS=YOw&0<`%1bq#= z`xx$XcNk;QSJ8<36rPVp8E~L8gl$|O_8Vh1SQAjV9j7Rs4#c7lVd1!s=f!AEd6F@j z-Vt^eya2sTr>gJ8A1?%{>H~9B=OnUd*X&%V@*0o7ISu!vKYIq@IR5aX5pG&o?$o#H zGJu{uy5Hscf@6511NAO4d0|K_;KVO5{mk{nPBqdmEK@Z7in04d9!_&7uk&fdEbQBD zm~Ibyai2R#9dR3=vZv^Wu>?gO>DNFv7%-2rK4teixt3S z6%Gjmt{6f;au@DA1^kkOd;%x+Q;%_3*aw(EUbK@>!BKEIxDYN~rAxT1+Cx(#B@Zj>La9I|*=RVU1r?%~Znv!EEOJDZnmcmZk7#?a<>$7Pi)=+M(OKW;?%N zpe9)o|5-B+;LQ5Y#Fk(E_PQ%B(PIM|i>yYuBJ%SDv>(|LDNDm%5c+p{@zz+)so~_r z(!NA8_6Q;@QgtzsyxH10KIHG~#=|Id{lZwcqlRN*X{39*8axOHx; z6#5Nm3i2nY@KWgYtlF*h!Pl|zfGdB?h0o!?piG5R|U zuU#TVuzqAIPup&cEQk+B#mJBoD|nNM4V(7D)DB zg*@DT!-k@ehkff7#@^#a6JdUr+uD-(eO?(oMn8BHy3Rb9I`Eml9(lJ&@G;;*+`S1# z=JSdRr?L1r$3?002*FjLPkM2v(i{{;g*3N@r!YRkJ~u%}eCZJS?Xg0dUVk1`zr6xg zT?gH)C}em0@D5aTAr)UggqB1hyS}9fonnD~&S0kz-_=3K;`78GxO+%r=v{?8^w?w2 z?dk~Kq;MLX&!XGFQzB?kKD{3TFNu&N_+};WvivjxpMtZ2w?|OdKC7w%zn5S3vnvVs zP=xHK2o5p+NPgyajl50to?NAcynw|HeW-rn>n1NG{B^{}&J-bEfmSfNup%$xq1gW_x4@K2^QJ1as5 z(gv_NHEcsSYk}9=Y*6jM#)MyL2e%Sz669UnK3Odj3@73ZYzgwpx%8h<;#$yPxM3ptpg1IUkhCMAv9-eo)7_!D$ zyhqrsh1et{l=E0kj-SNCqk^Xz_=p)0DoVlbeey1Zm!#m~{SM|Jp^_AQypPk!(xu?< zeX0V4%2EjO-d_qEh6=S;{Ihlokot=55eU6HZQStwOM3f&dF+oGpNUn-V+!Yf+B9Sp|9ul+?xQ?=lNn6d(XQ@25y zruos-*6>^S4AOM17_FNOzgg2E&Co)Zqh52rRYdztEiVnFn_nbN&8tf4>$k^+#Fa2h zi9`K9p~1YS<)h>=#&7J8kY3k{G?dNY zN02=e=4sx+lkhB_zfl*`a?Lv)i;?-Q8Um@Srq;G!P3%7tdTQPaF@C$>+AUHFBFV$= z={+e$kmTd{F$HFC&4Z@Tzp0#rJ3@GF2*P{IH$Zv)s;{08lX zG)UP>`HiMY8KM>J09!e~ycHk~*K*S$f64DnF>|9cU$c{Wpd6(Ib%RSCzq+>|jZxJz z{FWk1C5+WPiSEXJE7w9=q3J$2&gQLYRVA#}a??Vp!CU`U4B{FskXBwD-n#UhP58r{ zmLg&k{`{+RU!-!{p?KI&BNCHE)lGPXE?ErR&YK%EZ zD9k+sCc{sz*rGgu1m@Qt+y8_(E@#y4_qp)e>&jC7MLp$hl-nksanbyJmxkbnx` zL8_)CcfS>){$}TB9xG04cGhswd%OwBwqRNygY`!cQf%QrK`3$q!`*=?naNq63*~Va zD5$_Dh?z>R=chY3v^hbvPxX0}L5CSco6Wua9nhuzb(G|` zntSLpJaj#d5OPHxZ-V8Cj$bYU?`~SmFL1Bsky3#F=#Tq=@bh-$1*Zj7^hEUU+>50Y zQU}g_f(F7AYm0>&>J;TOu(Za@I^xzAXK3hHOk_&Dtrgk*QxbV4B(F?mkJ#!AEnBDo z>?yWaq4F8A6u7kCC%_)|Gx$uV+`XtRjEDU$6d&6xT27z;ac=|zL z{yVsmBCtLHM^9iGTHH@yJl6eb0@uPAyG-CEkanNI#b+3n9Uw9j!zIuIi#me9lCN-@ zCy=lkD+<7+)tZlAVjxv@1X@c1@o`8D1m=H@%`E|s4tR@(K)a9eM3KN(*lb)U(C-ps zKN3g{LYTOb4?cnjJbQ$DPXy}k!}=pIJQYVzAm9MDs03VIu#F{@do50L1cE-nt5*bC zU&9R>0zWX$b`dE28q$e7z|pIC&xyc-tvFK>2swot@dO+(SiuCgqrp}Ld@;mv1U^}Y z%WeWUzQ^Pd80bPwTqZOcyRG{K-bMyuI>3&%F?$52?7-|1D21c1FF{XiYX}U$fO-+Y zJvla#KtaR?{q&2*zhP`1f!X&!qSPG2W|ctG3Anl?z-qbhsKo=Q)gdfe0yFzFR*FEE zQHUJ^og?v(oWKcO(RU`W2xoxl1O|BHPA`E=XYm>nf!H5#l|taBevJJ}AR4D2FHe9X zIMfgV%Ua`vOki{ s?SSJ6;60+Sx&9v*=Je_ZDi(0^p?O#)tcw_yc=yyF<#Mj#b; zoIfIfx1ZQ40{6f|0WW~h5e>-%IwA z1S)pI>Lkzs+mK!adZE@x0^cCpOe0X)j`$)l;w8ivf!OYdF9IKd;DZEWX5q#-fnZGj zw*-n{K&5a@+RxJvUb!g$jK?{?DXH{Ah%W;7cHu@mf$u9KDHB+Pv+P;|o$#B-cL;bo z5MKnI-9dbTQq7JQLkNt)bQUHs_X}K96Zo_+vN(b7^C7$le6s=J1>n-kV0pYrs@7ZZ zS}1{`-yyyToL`HCO`sllJw;$0rtlJh)yQ#o2{cCc>4;UWnJ40lfDRVg5$Jdy_k##@ zn1{dcB0ztLHiN*d`gnnWfUD^M#22AgmLk3a0G6U!5P_SR;TQrpaE?eKFrpP+2qv() z88(6hDkIyBB{1VE;)_7o7{nKWo7a%O2y}gb@FLI_v>qcc_dSFcffQF!Je4HW7m4f_ z0`y*Coj`!Sv4}4M)vyG55coPT;)_5HB=#v%gYXsvHiEL<1O_G`Qn0YJj}SV31iW#q z5d;zuaq$E;0+b{0I=zflo6v`=k^BkV!tkdNI5QdXMPNx|#210$4G>=hK0}KK2@J$I z&Ju`oBEAR=#wE-n0`DPP*pLLYk%|2;1;U2B~b7TUWFv^GNNHIfpK7JBY{nb%3TCXjz@eEXx9w!MZm8o!izx53J5O( zcQ8Z`6fOQ;+(&hQf33=C#22ZC;y8y9_~A#y7lDRvA-)K_9F6zO2)Hf6Z8HMi3mN;G zz;VoHL9}{Z}1$YI47D(WBdB&m${QNrNi@+2_+;{>9-$8g0 z*jx?aMc~2LcqgG9z6iA4j`$+5A6tP= z1kS&K7hnj~K>`>@zzNE>5!eByJ|b{xD8h?CgBb`f0!z{0T>`GnXz?kbN1r3U!T{PI z#bq^tjA-o7&nSk&j@P%t2;)~FG%Mo7$#^PfXfkX^;I)Thnh%W+fq#?ctY(i=~M_@9- z>K1|C2)$njT#iC~MF1o>Lwpe^xDgv_0@D$~sRVYOMR*bDw-)gy2wlf(Yby!#XpHzG zFtisoYXp9{g3TI%FVX&E0yA+`<*-t~EWlY#gma3&M+Mc~mE#1~ev*5N#!1P~CH5MKliqSpihg;wJQ z76Kjth%W+#G3ccPj+aDy5xDRb!i&I?bnMj#tOT3q33NV%__Jfav=bn&8i8_%*d_!H zBbRp~umG_$fWXIf5MKn^ypP|uAkb$&b{Pcbbf27#6s z@i_t+gYXML1k!&3_XHY@z;#&xfXxqZrA=TuoMQzz|KX2vh+bJqWzg z61kGV5agCA1pHSZmI+iZfm}(TKh9zA5~wo`sf7S#=N}1FZHtF=h)kFEUMTL918Id@ zVVw}zTpjC#K>A7iaV~);>u?21pqM8fdJ&lHgQf{IKn(69P$L=3gg`5hc$q*C>~`)G zcnwUkSb*h-%2)!Y60uAOxVqtUD50L1-N^(N5f-Cz5uz&&Gt<3+cRoM9n-DnnHu z=qaf_*aloIcfeTS>S7_xuG8b7Di>6PRL>Cisg;9v5dImfGPOpYgM>HXl#*IE=rrMP z_CVh-&qczXs9Q3RqZQ$Ha7-o3=a>5Sgeyc!ea1E5 z>Plala1EuuPXld`e-_ov>(rhc8}B^ z&(eAf78(1TL3qWY^FC)J?=L3pbLJ2GrY?LRdQc}77ooSyQ;ZMhyFl#Sho9ctFRsB+ z%k!bo_v44T=7~c4osqTI;`~|ajypZDI7ju=DBq2O_6ynbeM?*Ct#oL=l-k;Dv0_Wz z_w-wAb+b;qw%?ghw8>oj!e+ zzHA5Z4iB<#CU509Z!nMf-qnZ=G1Cl1Ts61{!cnUpIv5{|cJN51a&McffY)d-P+ukhio z!_-c;;fcuL^nu%dYiXFjiPw%ei)y@(*mcAif?v1!{D?D+hY7!4W*cD%u>wWJF@UmmVc62d>Onxd2t3;8A@H_TyyAR{6Tvbj+C& zys;iUW=M~rrU&y)6OS=0zFdSJ$5$IshQ11mmdBk%!{#EyOD~i)B39*Wvxr!79EX@7 z_8!M9IK|ggt)uu2Uz-2-BK(9iLi4#M%HzA)$6L@$OL<)Ps2L)h`3|J0cwcJ$S7&dW z(=jmLn(bi!KptxX*{z8(?5o7q6V8ftzQVFC{r~lKAJ9=$@59GuHk(EYfg}V-AOWe7 z76_e?&;!zYNdi%N2LS<*r58bpltBRnlpjj3h9ZbGl_E_96qF`KM5!W0d7o$In-DnX z|L!?6pL?HM=1$$&&F-d%Y4_BKho}YM`qYL=!2G7 z2}flkU%4PP7TGoKyj0_(WGVW{E(-iS`J*Ds2s#~ts6&E zc6*{c(ovOav3>*ONj>1|e7W^1WuN9ozzw-bR4Z*~+yU2R^HeKiXZ!*h$Q^IBvUVmg zAfT#b%GsHafKKurT(vkm6BdwhN=nMxnY;m!vn5l(&O`+SOq5K#WTb6OK)PIEt5vj% ziUbVqESXAv`Uj2@0pEK`rm~$W8L&>CoU2u_GqC|1tn}mZA;Nr%Bv##yl@9n*4$W#c z>`a*e{UTkp1UpkUV5r=mRI6!c$^}dsDVan&6BqFFF3BX>neqV*XGx}(ov9G;cZ6hW z+nM-)dUDCCR>#iBccmK*mRw8U)l;lT$K?k!idumuQVJCPZ?s`lUmLYZHe}$>f68lu zm>|8bhPd_fCL!)5xqP|0TTM^M!8y$upd7Sjok%G!?f0HYsZw#8JU=JovD*Y5mi7se zb~>oiAxRgp52H1!IY`Zsk}`sP23X}zrsRw0GfJw+nn~~%t>RpsKexJ^l;1B4vgBT- ziw@yunY;8g)+_09yJ_B(xwmX#!|3p%EU#vPfaV(wW2X6rQFB;8r?v9NPir|O6G!KW zl&#!2qJg9*=BOg+*M`Z_mblBO^BP%}78+F#eJvl@k|}Ya=~K10+;ZxaI9)QH47dEX zK&He`Bo|jf{(LS|;&9WyYK~{}W{OOS{$`H2YjVBQDe;I;T-XV@eUmBiOP{K1m-!h753^O2cB0Zg3s)f zEhS4bbLfW%Yk%wau$R1&&@uFo7K5Eu9?9Cx3hDP(YajO=X-Z_W6uy_)t&!vPzEX51 zWZ+=K&_lxfpA@amDlRlh-m0yA#dlsADf(K%hck|;XhUEH?=D$h#P3p+< z3w_o=%5VFIrbv5Zy}VqJ$zFY<(7{+K`p5U}qf!(p;X+wOIT|jIqG!SH$}0`~X}_8j zC1n+Rw+xhGx9JM-G7Vipv!j%Cd0zgLZ1CE-Oi##-jtpz06pndbq1IWcP|^&^^Eu@o zO4+*1a(mTGJ(J8Yx5`%k*8K4YsbAfUNR};ZZ>8f>*R;Q-WS>XgX*Z-oJ=1rqJi*!F zn^M7ZC$mRmwyEb{?G|S6yRD^V4jr`Ja<=)2+!598Vg{eNE3pzLL1B%)q&?NV-~1J*KqSV+2mPBay~lx-Rt! z$$8>ed!XqXE_J;%S9`GO8Y*|1Au^c@rN5;zxix2a_v9@BSc2y3)M%D#T7{C)ZP zz|8WWrR-{ExjlT3;ax6CdimJ&E&U6<7_w|1nVhBM{7!C*YA-X(>sJos6<=-n09Qr1 zIu)tC!3?QoCw7`4O(fCb$GP(QFCw6Uw4G&ksuN|_kd)EMH#{O%ij7A0hf#ISY@}x9xvc#s@ zF)!ngIYjCW^(rW__k!(R6*zpDWM+7Emx91{rzO2GkMI8 z`h@%?&2ANE)GLwMOwuKtb_Iu*H|oXOX?MX9l77`r`xt?*e=q%&@`{zl{@O!*cl~1K zB)LGXkWABFi4rLurK{tX_ivjHmh-HB2`BH#D`N|6_o_rndX3Qb+9c|ASp<3jpw zmMxXxlF|y!<_JjoNiy+v#vO1gmt-o250YAb0ViLVOr=8lrbb{ucR60`SI+Z}WI_Ty zm79V3RT?dpOjtmHAjwp%l_8nD0c(TCORieMosx@cy3m^Wll<=CXL5qqPss0#H!vpP z4>{QC*9`WO@fVTb6Or-xx$nxR_H%Et)5WErf{wwG$+TzouJd#2@crE5WnMw|jV|+r z@=xq??J+Qq4mi-e#gnA%l&7AF?Kreq1@Lb z$2v!xk6dPx%iHPt$;lPXq4LzQBtzO2Nv;z3(HD~NORgDmY>VC}9+9evd5`N+7*P2g z$t2~~L((14vw>u473?atdxG!okJG$<_T~*}ZfW!6f&;a= z(ZDD9wUF}Cpy04>gN@|Ib{(T&&jFHYVrS$_Q*u2>ZtAo)0;D>!%dmicUrVN0fQ~t; zss4~+a*Morrkkd3VWUAva+|;#S*z2QrH*|p)!IeshI0qJSywXc!)|zVsR6HkE4dE# z5OO#}=x7fiP&Z9#V18-hY??IsI*=p{I@@*JPJ=FX##ul{I$<{CP$SJNfEfFA?x?m1NR= zbzQ3jgvu^Y?&+(8O_CGgs2tXT0fi;j%WIT04X-a}cJlhr|4DiH=^T>YAZgkE;icp( zPu}PhT>3%Mo1C<@Qqr59^cdYs$wb0xjaNte?; zw>xR0l%#h!>4$ga2{idjJLBgbA}6MwyQs`7=$iN1DtptuYYK06N8W87n|r84{M;R7 zUO~_JceR3j>WBNtAR0~$oo`ooTjt^Iq9iiQj@Xs$=Ue+e!+yH=b8AC?Nqda&er~Dz zVdzP_^=H~TU!p{o*%7<-BMCZhPB_c!`jM2c3iaNm1Nu!{9Ox;L&343YQA~;$eeZZF z`ZBb3(1XMqfX(y>=spI?*E21o1)F^x-U1# zBYU|~O8AF%gZ|oJt~S`K4O(mGb^|@|?G2WFS*e}glA5XEr|h;LYulsR)=#dG*%qc3 zTzhoR9g%(ilWoL%$4Ha3@ch!q&;65j5++Gkk~Q{1O1!z<`r<-LbV0r24RPx&t)IKD z9729>{aF{eV$0lrnsx6&O5wn@b`SbBR{w2Qp^GVnbL$^!LfraAWAj!=kOzrRw&t>0G(vFCnn{j|FM=`sCTh$hmu zu6V?BFZ)K~lJs+*m6Zr#u3u>T-fYuBUVM#{zW|xt<&^()l-#e%WB5_C+(BFYc(#>fy!qDTD)I}2cCw{0PyP>*Bx71`-y?s*m-Tt}zFFvu zJoig-%$U({wUR4kM-6-A3vXd^M9HI^Oy;8UJLL~RW=FYr>cdQy7Yn|F%+}o`V4g4s z3D2ILH02pse#S^{M$P6Pm#leW5eby|(GEDTN`ElTmJ+L>Uq|$6BvpGR$bigcWhwOk(=b!J3QGb{R&jwmdE^ zw}$LfdGyi^?2*kYTg&U7*&@^kH|rsOIj>aarfC$S1x>%5h|# zH;d@8Rcg|HyQbV8@G#Grp^tSS%cMkJ$QUbR3jRPcyCtC=CzswQb9uNNBr&yAaCHg( zB!M$_uvF*0PN5FLe&`ZAe{r&ZeTu-%5yPQqD`ZD;I$%tbvV zmvtarla`*#GBcv}yQ8|6uBkG!k3~JwBF0aYS36^*LK|&3GpBr(MAS!Knao9@U$b=r zU9v%BDy8-8A=@*pBwOcS3ECU6lvIh8$=--s!}MgYXK%$?Ql2Q29E>3{OK{do&RjVb z&AJRFWSL=8LhF($;~jv=JR3k?B&yYrf3v?Q+gOcRR?X;!_E^c4Wrimw3-TdP06=##&mbgtpl! zm$$>>X_>;bMc5jd8PPw=HRU%+HFiCfx!v=CtR7aHMMv5_XsbchfHT`-@{szr7I3g=39mxf$zv1;pe)|ha`T^nLXU%7mq*k8@ zvyAj*MEl9LXtFeMZOv@A#kzG}USsN$&?}ugr|Va!%Q&m0UC%FU7~hG%$P}gx!)EDh zvCdY?%!s}$7nDCF<@#G@_V6~#Rmv!#E&BcJTS9UraV zhPAtK$Ct9d6k9?&NNq2#H$=S(glXe2y;6kfwZo{PUj+3!CP{l7`b?R5HP_CJ8X-E2 z2U6|~W0M)<(Qg_{uD^ZX>>F8$=ciK%?cw$^d1p_`^_mx^ zwT*>sJ6eBWAw`Pq z4}I7jKYDRHYFi(9M`Dbq&o^OO+lbcRT+rtg*Jm=be_SD}v1xgv3!{YAj;Sb@Pw~6V zT4CBKOrM^N=q7UCdRJ1ebh#ir|6=;{@1>WObF&KTJ6n!zIR*wA@+)q6^sY!UT{TnW z`3dx{tDM#!?kU`7v#j=XSArhq!+Xz=Gtr#sD!XI2?9HY1B{Rzvq|czeZ_JR)Y*%=D z8G)bs6`AYEb+pM_oLPmp$Y4n}qE1K)i%$mYrV$r8K%^Q|`_`_`M_Y(1ldF5_8->`8G#RzKOh3DaeS zRnl16H6&L% zD;%AFfP9unvR)l!X7_hV`ZJ>S*I|Z9$hAObFOJEsbx&%^o*F2>7L!}oO43~=9pkK& zcGlh#CT}N6LceMLVh>^3bC^eG(_|*c!Zo=7*3hr4d)<TkR~ zk#g_vvaP#OR^MFp?e7;YQGNKyWGYsUxvig>-Z*RZW zFSME_xvWO-OM@9QB`oWzRSWCOSbd{!lT3-)QD5mu?iTb0Ryx%8h<&^JEvLgkS-y

DUv=%=th@K?mT?ER`WbM$_5VBP5p}0ip|C1s$imXXFWvV6l!*3`br`5l%%Ye~3>)F~{}2z~06I)?kY&eH3x zI3zWGl3-0KtsztJHOaJ>L|d7DG4w9Z`pUq}WaC?dLm$JTES?`4=NMf8!t-DIb z=v74be?#Z4Qtv0_oiFJzNfORXl;sBN?Z8LUYLQI#ONmXA*q|A`WjG>{miDnzCp1@h8{&F1qsiTw{9629m1wOQA@~5SGpBPHXdj(%%N-u9C1mm~>)o#{jB`S~1?jhshH!h$1Z zzF2B5)Y@(J?j%VPfrcqHJyLbj_tK@_RBV(A>t(WUGlKPo^QhH;qRlIfP=hUlSRu`u?=Y6D3 zFPVb%c738G#>-SmcY;>8D&J2D_Go{LB>bUFQmC&Lx@tc<(}yg$da%A$_(CddmMK_Y zJsgw7_fCtCBnIk0yT~6# z`xw4ma!J~7%VaJpCC>~=nw%pw<-1_|%#xzV4&~#eJV8HHld0$Ixr%VZ#R%q37 z+Tm5nU(#5AkL*j|#tnPORtxZ#q)Z8Ye%4qQeG|N#Tgh!eD_P+# zI)LO{zq~MjN7)C^M%uTK$-Wu+Rr)Z>>Yw<1>*fqS;aoKtc9|2|hCNbR49jfwhuum) zGvJ%#mn_xvA>)^IeIt9LkEOxF%tnvwM*1NH-x_}JywGStRwIw>k$uu)cV;W^wbE@_ z{dj|Km0TNX6=E;yNLDLpbVC~aCX;=T=CT{<$0dB@{jR;RsDdZ6tyHkQag{@+g!JFF zYRSk&@~olXY%D92y^RY$ ze*Io(G$nhZccj4xr;#kbqPFUypD^()p-bRBty9wCf|=t7XR-FOwa~X@;2|jqE+Pd> zq>qne3X7DC(M%iHvWL)AJA1|duNQ`(U0pQw?N&Vv%;uL&`Hvh{k;f^yJ$CyzDYx$f zwK%?x%zO)n+n;V|qfPh!BX8^Ia^&G`h)$AA)23$gG#!rImiEz)-S`&t>Z=t$l-ctR z%evh+DpH1(aBh8jVOF4neDv_>t z46htUj7Jh~=X~n3QCA?s>s48zF-T@Ftw2P!6^L+Fz&@7pM(TMT?<3cD-+Yn!hjCpo z!#6+crE8E_Ti$ike&rD_letLmH-cZ)|3=bQM%z-R;CQJpQW8TnlO&ndlK7uy8cXIE zNt}@>t-WMivyHT_w(edl1gOoV;YzR>OVMKdB|Z zMI=*ttB&$z2AR^smdJ4^Q~Jo3vf)ZwOGf9ZWZm20n~)LwZ%SUX^tp^5ow*6@GxO%S4 z;d?v7uODh=u1)`7T~>qV0nH{`8%FtrW>hm%HwBoJtv>@(^9g=Isb#z;?~?sy6$(lX zmroP72(kJH?$mmbGml8K%!k{)@#`vC>1d`kBzI~# z*UTfgEph-3#0S#&sOrtsu`M^uhI+K#LF$mrTuzQ zmN6y!@C`FtNvng_d!ebdUC{@vIMW?!CH0XHEsfb*H`*F_JG7`~8(A@X@-?z%jqes< z?JihYeysC$=m6b|0oK5^!MUy7GxN06Se=YTc~bkB^0DF#{R1Mc_aZy{S)H^kQ{!FM8+lXn+Ih2SM)SzjlYs^D8{RJ6$X>t6D>Lss(cBbQ4) zjN$h6e$}c~A~n>iTp~5MdCO{4A~iDqZ7K0F-8sDTd37iwRZOqq+nrp7r$p+$klY=c z#t$4k;LVCnh7RdAJbp-epKck6RZ|x~v~nJ-QpifG7#L_JjSF&Hv$j-mXN1J1eQ8=< z%C&b}h&QP8^dKR)^FDvMXZav zazGCW#}^UdxQovS9@n4)QHkD7@(d`K&+^IX3Ulo@tR;uMlB^nAZFzR z$R$j|3yiY%9l2d1ABmNhb}!{yzLZbTo|paJKYL!~ND`b3X%p$MLD`YIUf9yh% z^2{U;UEp3Sl$CTL`4i{gFEsefz8}}R`q29J-H52w3K=Vnj@mO1Egwf-p9l*XYmDvW z^)*K!W36%5&g;_Tp$#JCW=|jWWGZB=H@cE{8pvJ6;2{IvwBlCgFP!mf-L#`V<}hpB zYiW_zzZcSc=S)AHC*$~QY2#h8Lb2X`QsJ zhL*dv-9_5zHq;040+*d^Y*ojs_;2jc*v#WRv%xhQ)Op@OH-FR(;>pkBy5Isgi8pyE zev7!=0@#nt{{JH0jsq%dM0Y4iam|uBieKhEJVp=p@bAgnWlY(igKCutz49s zX;jg;{9-~4RlaoCS9Hn!lP=pO_4E0>k5_s(pB>$u(uh@0eXGIgt75gql+(|msQ3+Iy}t_->BBd*s9E$@PZ^!U@jbOQ2+Z96X^ zTY2SedmZ(7)B3WzZT&DBi(y-Q0|(+L9FHIBXC$=4rFa~F!JGIH|HE*(hHJYhY>aI% z4g26=oQ`wQvxLOwxB>U#cX$*};m>#tAK^39&(r7tb74U&h1DEAMlu0?qhA|z#lbiR zXW$}SiCasPBMlJOS%t8|;d2;y9d*OK=_T!XtP}l&`4Et4IP@@h^OcdcJ8r zKg@+OSQcwy6Vz9V+HNT7`@@>oH-ptxK63tPLf`mRzr_9c1760vsBh(J{Sb`CGFS-{ zu>m&6&e-3V^Zy+J(^20c)dj4?ZTKyoMt$Q_>s`m&_y|pTve5Dzm>VN8R&VIELRC!0 zcGw*=>%B+*Q`~~P@BkjgU+@+_MSXKom+Q$-q9j(qBy5QKj-fW_h`n$)PR9AT95>@$ zJb@P-J@y-S+VNcq9;3VwV=piO!!QbqVm#KtmY9wMaVlE4)>iiaR|LMrW2kQ@>Ac18VtH~ah_M_@KC!F9L`kKj4HiTCg+y5)&q2OfmsSP+Y0 zScfj6}w@7dmJ0lFn2#m%OSPrXVGPc9+I20$~VqArL^oOc-lbpnJ zcm;3aQw+%I)X$G4u?jZ8wwQ)JZ~zWR&twwwaXD_ry?6pI;%$6}z9H;e%!`GvB$mf& zjvk{9ftHw#1JQ#sa0PC`!+0LA;-B~seR4Si496n2a{gB!P#asI{!vSJO-~$zBXAtf z#wEB8ci|B{hd1%Ds?Y!aa{HN&>e^31e}A*a0h;e7w`@~MpwAA-~h~zC9#T!L<4M#-Eatw!io4E z&d24r8TaA|yok5)8G3@{HIr_d0$3EwU?oh%2G|_iV>%8*56-~FxEl96dW@3=W^gVg7ac=EQ?hz z2^(Sy?5OJb|2ly_I1;Dg0$hP#;8B!+du$KnK6=X^C3IlHm*5DT0g-7rl-o(e~U(jiv*H-qw{>M-4uoBk8CfF9!um=vn;W!4T z;sRWOU*LZHLDlpB7J(<2JK7o0D_9ESF##K6C+v+Qa0*)ZKU|9$qJ92#6dVBhVy?Mfp>8ZF2fDD8;{~I_z=AdIRlKs(pU*=Vgqbj z$m2BVMqmhz$MiOS? zz(|~m3vdN~f&1|Y{)oTeHGGKr)8Bf5i$MLKkM;#mw9o%~1X|-8I2cFbc$|iFaS<-Z zHTVVY#~<)A-qoL|*O8dT*>qR}6R|mVz;x`5BX9~@_&?l&`|u?GT%7a&3V}cH0eY8k z1{RJ*u_D&RR`@y&!ZA1nXX6LB%tK-&Zo(b74^QGHyn{wbXMj1;tBjM+g$1!FCSrZ` zG$YXod*U#B2S30ixCyu85&Qvf;$6&9mVsdzM~_jFKuhd^!|)ya5SQXE+>e*=26~lq z7MKGIV@YgdEBil%Kp%Vy$KV8fAD7@~_$8jg`xqGK3?K~SuqrlI_55#5U=WVL`S=m) zKRMO2WiMX9>-YqN$~*PKu>_XG=GZ~B&;N7+LvS>{iwkfGZpI_{2f8ab3l7ARsJ~FA z1FwsXu~!Ao|3L(1;C$SKJMau%z9`#C;W@m5W@Tpq{uqTtuogDN?${rv;T%Vgv7W$IJcQ@*H~a_n@9MgSF<27g zur7AT!8iur#rd|f|Nlo|Gw#Im_&Ywu995kGAyAudz({NGLB2>yWg zFrb>Vz}y&%ao7;sVk!>BQ8*VD;wI5P|F;u3foJg!{(~Xaoq`~=C0u^I3JeBs@M`c;24~YpW}Kwf~RV5{y!z)PH+}f5fiW@zK&CI zHtxjzcn$wT{Un(lwD~XzlRYGQ<6xYNi*Oenz+3nLBNCkjL}M*%h<)%){183MNbJMI z_$U62d6S$4#9#w#hJ$bfF2ql8KOVvRjvnJFfr7Q11r)<%Y>tC*Bre6z@erQG2ly{W z*LM0Zj{50q*H({wONT%w?22#VaGZ!1F2~il4-erDyp2J1oB@PkB~{P=1OlC~C+d%# z>p?RE|A%XEKOV*_cnAN%kh)Gk5m**0iT3&5lt3HoheL2W&cRi<5f9>Vyn(kdw4O77 za#$Ig)#LncOQ1gv#rJS7uEEWC1b@I=cpoF{I}0w1b@4UqSzq?QZsLIiEc_Uc;Te2@ z|6-8_PWw{W9=qT;d>2>aX8hSh;xc+CI~@jLS*(m5Fde7hEZm6O@f==3{S^US;b8Ps zB$0rfu?J4Y*{DB^s2%LUOZYnmHgd|tuoBk9F4)u2W6UIA;WqplFXK%Ndd*otIM%?r z*d6=hEL?!wagVL+|DOn4$G`Cz1~+yV7>Y4i9+R*EcE;{F0jJ?-xK7pc|2Tm&_&0hr zaTc5dOJXfd#xB?cJvbfb;40jR2Sxk*KThBV-bTNs&H!?v{y?wp`!ZM`n_xHWixY4f z>JO7^`$Kr5Dd+$11n!`JGpAw*mcX)@jLono4!|im6TiTn_$yv*#`*8n+*x1%md9$? z2j9e5xB$PxZ}1*I!2&Iu{)=J*Y~~>`3`gS<{0tA`3A~R_@s*a&0$#-?*aqK14=&Bj ze@@~Up25fHYUOlX1WRF4Y>V&UL|lRE@Hn2uCyw$h`PR+?VzE57#uOZllkhWKkEiih zG}}1+`s1ru0o&Nh{!b+^6vyLi{189KwYUS1;LmsoAEVjU8Avo1!#b*-|BVRr#W!&_ zeuT?$AD+X@_yk?;oCW5`;#dajV-wLn|GN?BixY4feu67;4}OOi@j4pqodNh_G#0~# z*u6dHe?I~faXNmAt8gzK#LM_QdUbFXoC9CMSZsmqabyS1|FHxR1Q6VLzOS7Vg3WcpYzJ?i8p0{OGAcqAvEq zH*p>=#;@=jyn%NxZ>qC^7_5zrurCgA^ceFAe1!Y)2>yi+F<+XqfI?UYU&FyT5*Oj8 zcmTh*mHmI4z&{w$*;znAEQJ-ZE;hn;*bC?55?qCw@DQF<_58n0;9soU#Th^oY>Qp6 z7Y@czI1y*y0$h*#@Erao+UNhD1pdL0bY}oXum(26_ShBs;1GNpC*U-ki%W1tI_Lj- z0$<`@Jd7vt9A3s-_y~PocLpAc(O3)JM$`Emr^*z*6X`PNETZz@GRPPQrP( z9JkeBF@9*xCQs)Df|_0;63~oeY@*`WdG-~ z6Y_;JEQ)2ZD%Qa!*bdXN4-Q2SPQ^L67+0uz{%;_#1NY-mJd2m{7Do4QHfd$7ht04Z zPQdr^L)<9Z=l^yBr}0-bdpZm7$6{CpU&B^75QpPz`~WxLHay;w^ZzV?zwtke?BxvL z6->gW*cN-@ARLJca0zb29r#->&i{J^o?vKiXTgzJ1(PrpyWu!|7gyjqJd8i!9em^= zk*ANdz=BvA6R{n3#!)x{m*Q?bi&yX_y8AlI2|!O75*4u}cEDly4lcu$xC{5=S-gmk z(Cp_dI2;Q&dW<*%Rj~=S!TvZD-^UMd3+};R@jgDqu>Q^fqOh8+?El&Xx?oS7gfnmz zZo*@D1|Q(Rm}`Kuz#>=!>tc$k=YLlMqi_N)!cTE0?#JtR8v_SA3(SutF%IiuYfKUC z^Z!i(OK}}$;88q{5Aa`%9ONwc6->fp?2i3$8qU%0-|4f{DgvAE5T3-Fcn^ICI}6N- zB{2@0Vtee4Q*kkVI+*kSO9FfGB3?)DH=P9rVJw!%=GY#G;b_!?blQ61bJ?x0D<7k|O%Wx$g$Mg6X`oHC@U@okJNw%{8+Y{)5BXBm(!;QEd z&*2pe9PTVA3@c+IreIebtLphbmB3ouiHGn9Jdb~)djxBS`7jRaU~_DbLvfsFpa1U? z_ykwsE6P0X&75@fJS8+;2MzE{H|3 z7A9j??1Piv=KP;QU?Hx=4fs8t!oTn-29I(E&=wcqa@>GB@jE=_A@M8zf&ZZU9jD_E zjKX4A0Tb~xY=>`PKOBjZ(DOctk8mY!#;@@Rp2gqr4n9G@(awOwFa}Fu6|C*(F`5zR zggx+0^x#xnh)Zz=ZpN?idpw1=@IL0UcfHK=atu_&+Sm}ga01T7#kdvsP2>E(OF(}JM6caB zFh9m(4NS(?*b7JFWSoT`;4)l=n>{3U;sHF0XYeBaj`#2>dcWrkJQyP|21{ajtd5?# zB${Ab?2J8e5RSz0I34HVN4Nsl<2Kxbha5e|4+PHRRs0M8L30MX2179li((n9j7iuK zTVf|$+5cS$^uuB3!6`T!Kg3UPHEzLO_zfPzvv>(_s(Sw4C-5)&%yiZ?C+5XM7>gCK z2G+x-*bcj3FC2_-i}v|Hfxvq>A3w&=a070~y?7W;;V*a%Z{s6$&2m;SU>4_p7=Z#< z49j8_tc8uR6{cV}?2m8Z7@UglY$5;taHK34V?n(X)fZK0Jay;;(oe@8Dzfdf!>YKn%x% zSRBh?RjlpkF&PSO*(p8%)Cp_w5r4;f z_!Pb8J8K$@5g3Cd(Nms8b*zg`uq}4Ro;V0c;&_~n^Y9~Ff$MRbqsQ1o;1K?R=kY53 zh5w*wIct~$Loo`AVi~NAN!ZX<_J2zPovU$k zFrLC+@EYF6M+-RrT^~3D2*5BbfW@#ZR>4}>2wPzacEkSo7LLKGA8`J^PhcT_ifix- z{0hItv#trqt`-bL4g>K1+h4mbMzQh3Dm~dur;P)cN~DjaV)-zb8rzZ z$F-P&yKQCve@Ea1{*2e~A9OEb-(eJ%#;RBkTVN{o!l5`;)${*70w3UV+<-grJ3NIK z@fJQp@5RnQb7282i50PyXrKR02&CaKoQ}(ID}Ikx(EB52fkiP1yWvD!jtB7EN1Xq6 z3H*m4A3Gfu!&=x1d*e)8h#T-QUc!Gcc!|?*5$wIh;{?VKScqTXIedx*mOAxIVs%Wx zQMd><;u*Y$IhV159uf_(CyvLDaXlWubNCb^K5;rMk4>;QPR7OfIeLzgxQ`*9IvrKV zw%8YE;3_M<5--G|HDnV-O*#*Bybn=$^O%WFa~R4J#2<;@l70wGjJZR!OeICf3TJP z{|AA4=)2w-Krj}@l2{8HVmkK1u{aes;5IygKdE~D-y`q@12;GW2*X$`k2UZ$Y==E@ z2#&*daT%_}J)(X7A0%)M|3cr5&OqX@FOJ4(xE#0P0X%`f;P3bt^Kat(FT2TEP%j*f zlhMM@a2p=LlXwAd;bZjO%ofE$SY|Wle=`D|aUY(-i+Bqkq4yT2<6Kw(OJYT=g-x&n zcJq)Jgky0LevV(@Pk0UQW6>|1fmFaGY=S*-2#!V13=*H=7TkkJ@g5o(&Vq_y9KMDr z*cV6OB%FgQ96iP+0$<@FJdKy}FMNW&a^~oDA{3+XRjiD4us2S_#kR8lza{V!KE}Xp z&H{>Kdz^~<(0{vAF9zFSgD;)<8`uv=;Z#-6|2YIc!q0IN?!trkBmSh$GmJm+o+`U3 z$4)1nAB(GUaZ6BTd2P@V?el*ffjw%7d?AtiSyhho^LUx~U*zxMQ&rlTyBzbV(k?%~ zLc9c4C7!TL&wr^{mxA`{N%_fDHB$cho+=~us8Vk{&L_S?m3pi3Ys&ZI_jm$-R;B(0 zyuC}$f9d!>6`oPx{>rJCPnGflSPWya0#?Q(RTfYW+Ys-7U5WR?(H;uM;WP?n;Zowu zaXs-Zc!2mpJW2cv-Xs1Hjor=wz0p%h6S9UyF_wa4HHTreQ)L%)ru+?ji})Cvf%DZo zhVi*7{jR|;i0{B-PF()}M}_kgT*7`|9pdq*j$wbx5gAzR-ii$ z#`kPJhOwN$THK9S@h>#@I2{$o=GYgf;7+`SPq5Hlr+t4Muj=_fmw#WL6y-@v}O0GHx-_%ph`b@~gyeEMI?_24K+pau5Fw{S78!>5?* zJ83^lZdO(4r-Uj8Unz{EyuLb3F1@PMOQk&BL!vtcgUAoXk*YMb)JgIIVpTd=OZi63 zp!_W5*YGb@SMs1tGB6*^sY=`vrU`k{C`mzStc2CDjw%h3RjHp!JRN&ue|$@o`lD2- z|32~g__3qM_=Lb}RT^wirNLq1$M7tk$7`z8yMz9RBrj_ign3lyFH)6yrHGfqs&=_l zs7ZyU6tu)n*cp4NQop|{9llN6gHv!iTB_7vjT`W5%JJxP|z3JWBi| zo+p0ku%7=ifPX14k2q@-ph`SMl}%lUcu}l?l`#qHViQ%`w^XJ58^n9yAj*dwkxE)& zG6mD{16+*%!I@q74~xYseK zUYI&k{=GWJt3wT=jw+Yvrm76MCAK5}I{EIZM=JEugfyI{4wQe7qe=(MRVn`**Qx{M z=QGqk@&RL2>RnQ$-c`Iw`BSyKeE0LXQ!kGy_3~r1Xg~kQ5-5WeRB6~;O_zH=RTk8P z@;*3__}kFc$;$X6H>38oGq#h zEJ~GrVz4OX)zp@T(NL9oEmW!320NaR{jC)SXrPH)MBr3d%Gb#U6O_u*TtV+Ed zlz)Z$C_k&#k^dc|O1;~Z-^WM9-5z8%F zF|JUH8pd{Yv+Vy}PQv&G58)4Z1~1}ocvF>*N}UpAfEBS8Ho*?q4Ts@qHAeRTY)x!7 zjCuGGF2hy04!7c$cwCK<=|`DlApTeqOJjMggf-O;(x5hhM%WbFVn^(ZZ(vXCi-T~e ztrcvRE^Ou9oi@+hXsz9y77@77Fzy?&OnH6!kCiLDOq3M-DFykYAi;DBYGJav(JJ_L zT4kx#_Up6^&n)>r&Mt|H!*LY8uTC?J`M4ODVg~NOJ$L}msd9IF0k7drG`+Y}vHz=_ z?6W`#=(RcoU%}#72Fqg|Y=9jx4ZC449EqcGwikCQ^9b1gg-!;rg!~5Ff(P+?JcVcR zcl;B*+|CO5Vld{$B5qlju5k$hWmVa6HObe;hQ!;GPr?2;7$@KqoT*BGACX^%n=r#e zVwWlvkB~o(XNX@Te-rN#H@%$|@Wwz@`iUeTjm3ypBwrOhNfb0A&{7t+|J^SD7d8C53 zud`->s&pJl-v0l4QeKRBMdDR4iFh;et*|5UUgZ1X5aQ#>PZn$I(LaNN#S|>XjrawA zgNN{hy3smtAgy?Zp>p}~ldKqu5m;IsXc%!=1#4hSRqnjnVk)NFTJ^t4E1s{rTog1b zuE15c)}(LJdgPP4oOpjJ7OP{Tt(A5rS7FacP0O9lXq<>s@nf~6VSIusaV_ps8Dl65haDcpv|Dd~-FAe5ZnZPgU+WhL9hw#>nlcllK^NH6gouwG%Mb ztFiK*K*{e`-MZ$o0)DC-$NJxj?G;j!<*w1r z%N3=ZCgg;vL4_n$PB44ZN(c6)l@rq5l#=hFGD1o`7x@T`_swKQu`Rj zBJxYrfwIDCH|cP_CWguyQ(?C%FDnm|Kc>n+uao~nog}w#Y~Q@( zqg>XXC+k7;ZmmAk?@fX{FDrJ5$Y5QEV&bn-t-#@dx{_pAM@fX`~&DLIzhUfLH zU779me^ft@zt~=nz|7@Gyim^yzQ*|FwbK9D{zA6)`Ce?Fmf2qZ754wxUXSq1 zl-^cnR6NU~Ew|Dv>)fL>Kl6aq z=Fc=M$X%8dl)+TDZq02JX@&ijRw5`&;+Y#W!Ah7X@jse`<+Vorl~%<+DzlNb^DkLi zsm!`o&}~^-d{*hi+frILtMrtXHqI(-az{#2vPu`Hfc^)Lky~7zuwUrGb(Sk&S!6dhel>MrD z<^M=&jjYlFkEFD5R%yRSQrbGJ^fxW-npIlyv6S}BDqZtfN=HdH*&fEfn%$RGxycjB z9?q(~_(|F;X5gH!pN3jjMz;v@KbKYU)|0eotMQHcd95N((?ZNIt%^_6iu+&5YT4~+ zTD12*FF6OT^kMD8ti?~$a{AxTYQ9B^&BIoqhyD@PAKJlT>tE@h^wZ1^WN`Ck(yNOe zc>3>A<%G1K-39xr%ymjZ#%3)!-U)(aA zrNllL5*kT~y=~b7i?VgMHrqgFywt;P>7kx(+wjXTmH5d`W1wX|%pF$crM@?3>w81C zzN>`3IJz*)+}tW6Azs4Shjv(+my>3CL~hE~e5%yb6D#x3DJKIkb!gp|(y%8vfNwMP+Wvr*W)W z2Xllb?0Bj7x=UQf7`cKX(j8jh;7eWXTj?@xOR09T!>YP9 zJkq<$Kk|D-d1;p`khC)={@=X3>v1T~^|=_&j06?fNon9wPhF zn%(l%(CYdhe6ye3qt?3&z4O(9@0BTY;}?;7vOWVdyBL$(WzCHDDjM`=sWee|u&Xra&JBfc2-`d3>s z11&li%scsfwKp=(SL-@>e`a*-6PpBd0<8L0!h6@D!kvb6>MfUaBTPQQK z)Ke;NhWFJTWg2Bh>^jZM_53-rPDWhIp1I3p7E2}~qsy3{m(#LE@@Ay}+H+a;Y>|kJ on8;qmd%Y0pI-%FXc214n~V@8!@5y?1Gc9uyEzbOh-jQl%*er3ix3 z5u}KsfQWRZDuRgLy=L~_Aw249;d$Rbz8}{$=iIAI*>kU1dv?j;^3+w^ zQ*ZzQy$?4RT8?`yY$n1;(ia-Tp_# z^-n84r+Th`H0tNnIr?_}vuS&7191IA-k#S0{vZGUw*mP7_|9`{3Wy?xtmTlFTh04v2F8VNwHMJo7 z%VqAn%=&D((u`U4Vk_2+Ff3w`&&OH8Q@tS^^$>K7=?|nZG zU|#>_;-U_`4>o(Q#drH0_7{um4;}rgY-j)d;zB3K*Z$uX*K_PVU{o`fs~n!g0{(~M zk`9l0uz>%i5|noXd#bpe7XBQ+b(IDE+wv%d1?4KPXBGcm&inZ#_Lqz6?>PU7Z*cPz z_D_oIpHzB|bzCgp2Sff3i|hZg^C8UPno^HB{zeJ$J;t6#35z|4e`s)>KA3{e^Ok3X8c3j#Q>K6cgpQPEdBS3>yHd9qtn)$B7py>T))pU{$k0jFq-8qu4fg0 zAb%UoGXF&>(`7OH-Qv2oftC4-rL4$c|E821K8`(GT+b?=mCG+U#{O-oaB3F&gW~!l zLoR*A`6=w#QmNc%_U{Y$r$#C_9`UE8O88>-yi3(atyonTef&MuOW{;0SNLxT|+?C+F@C7kRpmrGk&!{0BiKQjCyedF=v z*xxIzKd#VZ>Jaw4O4EId+3yw?49#YFKDW|*NJ%Ek)~{G|lom^l$rYCzgiGunl_Motw<9H8^zo;qd&YhC zm&+dbQu*%W@0K13QB0O54%R~!mk!1yupa-koKIjqLvQDlNhz%7v*qkf*7NsD@!wNE zqwAI4k)doJ7n^7E=H;Kac4+!bOCn)lT!GDDx6^`5%>~c2Q1>7Uf78cQEfyUe?vi=< z9h<3YbdMKsm(9!bTrgB_s3z|*BoPps65{@Gi)FN`laiJuWHYn2S$<8BUZiStD8b=g zd(*O@mZ5StO0~}Js!QqO_Dzoh?%(EGC)CfaT6D#FvGUWZ5ciT|wvttKRi^6fW*^(3 z*Yhsm0jpnQEG%<557;8XhU|k@yZfNkqh$lLLZg&!4tJ#{9;@alReGWuoqxTHs;}L~ zSVR?6-zvd|>Ty#X4)=xazFt#wRf_v|6~AjQ>r$Hg!g0T`7H)BOIO!Mn4vnSCa>fdk#aJ3hu)#fd zLY}J*p5&hJW}bG%_~7gdd-J$2?Db!=#b`qWv`%%n7mo^vZk(fvO+mkh1Kx|*Rq0|w zxk?4HH$Mt+Z+;Y5Jj7IEI0f9l3pwLQ5 z7q_bTIozes$!W2yuj zviDpp=-zWNeCg=i6()9wSe>k^^r)=&YQ$I>l`AP2GtkDn5^Tu+x>%(9>taz`tEmc^ z31Yzb#s%D)`$c)&(N#(AT^*vEzez*bfm%^CQwJp2kX`hbXm`nT4T+m`yH8fQ2SuJBHf1*ojF0+#(3ZoQpCr8Bn)Wk5kkuAz^(xp@t<3-O=rGwLnM?iu1< zT)EU+t)x?GLV}P>uj{;0_Q{6IJs`4lrV5MHgrw{ZGfTTS%uJYDR<|d)5viwY>Qb`I zo$ji66VEL+RdN|rd^fRB0aHcG%I!Lo*sY+c0;vwS?P}txP*Wwn4q1}Y!cCP-eUVW~ z6;gFoib`sun$)r4NV@V&?W&KSb#*WEN`9(AdF(E zn4DycOIOu>^=TE(C7s=umnPp+%Regn!2(J18y)16dE zccXK>a5l>B>2Nn&m2#woUNKF2y;mvKY)WYa>NRv*<5NA1F4EjsM8#ADrY5Ah5%ud- zz(Z2O=W{ppXnwunbT`hase=uPq8jOQblS%1riwD7+xk&jks^l54b_-fLsBc@kZ<}+ zY9*v5sQfy(e)_>VGRBoA#O=J8Ufy6X!@c-+`p}+wBN?iZ0vcLP^XpD z#Ek6QcWb(D->o%UXDkutRhq;_MQc}CruU?0z~2tlZhyp7$?ezZxpltK8B4X-D>lQ=7Oy zoZ2)`MZLCuzPYilX`TJKRZV9#^SETF+#QEBUsX+)uu$J`K4X_I;apUzb$7SV$QF0w zOqHCwu%#_R-MUIYp)_mVa)CObq$XvGStS}e+yNi8T=ju*U>}Zd^=P9hlxp3ks1lOh zku6*A)DJm1K`r*j0c{%Vi#<6}W$`{O+I*vDaj4{us?U@*S$a-`N}ir>pKUYOPYo&(XwO9uIm%*` zB|2WJe=ox~Hj>i*mj1m0-*4-9rT)DN->Y@JM*m)m?{zwU2jA=6GYdHvTf}cM&PdU| zb96cP!otn~?g~B4m<@J(zQ(sU!`Eo+SUg`~tOpHC|Mxl{Jftft&AuPSSm$pKF;>9F zE4QSNBzT0~z^J&73wJab>!b1W;~4W9@7oPhRKCvmWO+L@8^8qAEbQGkmG68AeKZjt z=kyDD%IU;Q9}HL;oHm0Z{&^ufURDBVJ(u;UY>g1Q&6QZ33=+3SS_N9IYV3?-61th z9f$VG%9&O0ftUy$)7rcLH!T_SPx2d38*yUihcS?Vw>`gs+rZx0jJcwg(zHj-`w;F? z4FD}sFSTdP%DgtfXTaV-v(^?*A1i8|zCg8}{7kjF5TnfHbs4T5>F~Mq7S4ihScFx zNH?ezIPua8zJ_?qX!P!{knS0h_z2R^hLkb{(qlt%Ba8!n(;KzAn?tg4LmXBBqGpQe z4Iz5-G@1v-t^2Vu1M={q1=LYmi(rNWf=ur#;%ISaca+J4MoII z*V>cspm>vOJFDtrkt8fIJC`ghG(}0nB2$z+EH*_+#8NdDygja{SY{4YQnB0=B^7V+ zjHju1+puc;j$mM`xwZqbFGsrVV<^^ft(vEdJe2Cjv7))mtRF+o!gZbQzYr!VLF8hpLl0^*Yu%`ZJKJ(cbIGLrb?mcJI1wEwUt8A zcS6mAr%vBVC0ca)PUoiYjMIj;52tB*y}_YK!Nd+TG7 z^nGhGBI&ziijuzXOi|Kz*%T#xSJhZd`mUKnmGoUVMM>X{-1L2KSQUM@x$n#%eWa4U zdtCGGperPOKXL76@JSP`N%|ggZNwNTf}v6L{bIBU`o1XT49}4C{id`AeavF42e}%# zC0(sXdFrCpnPa^uRT|4Oq7!3>vCh=8^tWgkWt2kkn%AOj_EZYRYkrGdmYU9M0VNu| zhFWqh%Ytec7?tET+!Q6R5fGo|HPUEH@mk2Dy=&!iaB5i=wrJtQ^|44^<5UH#EXiw8 zQx+LFAMGDXR2X-lqUnP^xQuPGMI{|$ZCB(Lcft=Dc{ zA$cuh(L6Tk3dw5)i}pR3KimjYuXwF&v}wIk9P74<5;1j!ydYLJt&;BQrd6)i8aY-G zndo%zCL$xz8Oy&C?GkY^l?k@BMQfAA*m>$uCRnGM5Mzb5SE9jWr`$|-F?*0qb~XE# zOlFy)%&*;yrWBE`o)#_b3)Qt^vX4dUg5)H}BAM)Gk|UYyZ;F!10j4OK9B7J?$-(B( zQ5Nm)m-EaG00vw&KrFDsj|OlO*|a+%J`wM?lC<_H#5lCezjwkXTQ zDNHTXg%<5VHKkC?bg4z#zELR@xo@dCiqe33Cba@Ux{kmRm42Pw&22l44; z`i^SLID2liXr+DivB>oMu0_I`n6ez!W8~KbxZD^`R+BUVl+zF?oG#4ps8{t0_uepIAyfy({|7uqs|H zR&CgNeWa3CyH&f4{Tt1zTC|>4ZE_u5A$j$&YNrQ7k;AK>)tIX*f~On1qCllJcnvb0 zLPhy>an4 zSxhrU$zp~Yi^*c9IaJAF8B>%jmbK<$v7BL5ELOB?cX8sQfoYP(Dpu{QLb^h(&gxd} zF><2xkSx}+YA+mzB8SB~Mw?ijKAFbqY@oCTiw#XDxjGwJi$AqFqSl$Co#>beUM~eQ zb{Ac$tlQqIEySfODHN}rt=jZdrBJ+PS>@))UtgWwlxVEZ9_HjpUVB;P9u1?Cy!JLl z$!i~oPxIPWwPo-+z^ZlqRv(Mxb+A=?`7?bia&-<>6%a*|*I}k8c^z(wlGhQYD0v;J z#$xh1O37$T@;cfSC9h+wxi&{G!>V|lVAcHc>m!xCPPS^5+Ug3)>r_nR54u9~I?bvr zod`wF=4gh|raGs-tVB$m+#Jm`t#WfT+qBBf(JMJt(YP!Y?PsD_S&%#4gEQ~(2DwYD zTIMn)6^h)qtlE|{N}@sQsK#QFyUQG^BzLzdN^(ES zP3~U9s>t1E)!LlbM=HrZWYsF;4xSvkB==LR=KZFwkmR1QYMro(yn}Ic>XdrgXcLPz zvb?cqzf@Xd(VjJ(rdvWB(D!lQS$mT#HV?EsM<1keQedrb66x0=x*8(=}L)<(m6HF5;H^L!Co8YxrMT6IHr8RhsFr6f? zk+!FKrHNsVwPI{V@Ori`V@;t@$vEDo*$OL#;x!Q?!~!M{#cPV1o+zEyG$k6mX4-OH zsg^Z|A$cul4pQ=39^%uyR#0sjyjHep1#ypsx>oD8noS$?mOd8AYYmesxn66UqU5!f zDN0^zo1)~kt{RKUYdv$Qa=q3!MagS}+`Kk2tcusBHtplq`bZ_OEo@r!i@HMc+Qz2s zIHoHkukCGG(E(88B;!s-n<^Q1R-%!NyO^R(##yE)lW{k*Zm8&A8Oiu9F|{(t{Q~PE z+)TzpZQA=4l|qsGf=$c*Rw)#@qtzT4i*}3>4RT$%$sKQwL6SSc6eYP6AwEs+B-NHd zZnjN}vgu=yi}od()=D3o+Cfb>`I6+$Fhxo3%cdyFooR}a+}Ua@Cb_RD*;ur%nxZ6k zPHu8vH>`@>xi&5SoIX-X?tGgjis}kU?joBOQA}4za+lh)@~=RVlZ=-eZDP@uuWBsX zl}c+Y+Eu2LT(qlmEn1?HIR=SWs)E<{w;4+?dEIK$mf}7pDHN~UZCWYZ-XewK^+Pp1 z#-iP=M1$A8xq1D>9ERj|pE*d$>wbt&^LjwFW$=2~rq!LJk45tOsZARXqUBiRqCIX> zC3*eK6eX`GOi}WB(iA1Hr`1?YUOzX7Di`e;QE@)~A}lGlQ!D0vMxMagTV z8jHzml#-408f}V_*FyGOC)rrTs(6jFYoXXY(ZJLdPjS1JaYI)~UgPcB_lD%%}^AJHSJn(N2O3K z*0pPI;Jij2ip2(MGAijTHd10$rL4volQ})*u@kji&<(cCX3z7p~}_S-4rE@J#w?y z%djdI``WeR`oI*61MM15*M}}y9BS8E;#xxFxRlEu+Rn_#hRZG**e zN^7t<-gF8TqBfq%48V2OmoFLgRq@a^UsMW3UkwlK)flBv^wsu|i_oFdS4W8+I(_v# zEuBTfR+HTLyj2J+#kv>tm6Nu$71AJ4h)SN&4ET z3KLztk>szflG}2t@x{QR( z&hqhQS7l{f@z=vcyNfLm&7!CZ=i>^pcEb%Qys7XMB7|=_OU|%I7Bg$2t#}p;O{-zk}-r3N3&*rL(XAzpM zDdx|sX`V3eNm$}uExa=^r+rEAYMrORe8y{7nPObYpCWNNDaX(B>^Pn!ma4 ze9X;SG_(oDHiJ4EHLEx*EqoV7F!l+whfPcIdw3w0zm;E!ri@X$mteV0)>o;Xx9p>% z7A%&aeNQQM)=G(8&7B2HN-0bG47dNN6JDb+hH6B}wvFR`+q_<$K z*bp$$+nad}gT}E5Cv)z|$9=~jGqu@`r-+USJl_9+v2E1WMmk?$R9C{n5)EH>n0Ws~VO2;OBRWaBWaaW%fzTWe%Jdh6YPzmpqiN zT-$`x$R0F$o+=XH)C{KsV1e_g^*&r1{i!POQ-A?l3ucG>y!Q^nn6l>lnnf zckeJpia2UV&P`w{syK#mZQN3Is5O(s)mF~@K^=Q4*TA1~Ds+tH+6ufY>@4c~1Odn$ zQ@HQY6l2zBa_!0%#x_%4IzV z=z%z~Cg(D%Nw?uup*dn(YiGe&Ilp*8rzbAeXkx08|5@r<&F_0$+a`W#jp;2TqS`nM zmKxa$M}ik=Uh0gnh2JKsKtR@#lgk3-Rh2t)HJ`y zqc_tulU_~p1+Gn)tQ;dTMe5iBQ^lukoN+-jIw^~q)tg*fCOq3Z3%br{z|--B`*un* zW>v!@`@M`UqBg##LEe+S%2{QWXnNM>MMgQRJ{GO-Wi@Tbr~>(_3UXHQmdVk6%6u!g zSqaX@EuZYO2g>#xhBM(ewmd=*w z4MYR!6%FexT1!kZDISosoCQV0W{Y;Gn%L0Z84*suNYe1gLb3Yf##*1!1sO7>W5qw86i_#|>)i3YunBvifypp~JNeb#$|>3>rsK zX7AQ^)E=cx7P~uQn5l@-P?wfZT!57CZaAc7bqC>ax%Z}%5GI07-%id5S0ALLT4;sO zz{jgO&9!(NUemO(m{)0D3)7|?bItoO&(zLiVA6aDrsFwgE2`nIx<3AxF`7|+9j4nk zW=hJTb2a}D@kXt*dzHnj!zlW(cwdKofmX!EmANQPrE<(!V_{yd&3{>~16~uR`Z?yv z*I-_)eV)SDE=dYZ0}V5${#cbxLs;l0t@mjJr1W_a_BpwIyx+rBdgyj-YbD)h9qgM8 zALiYt7|eS$%P!q~7^cs1%yWN+`LK2nJxF?Qz;wqnM;9ToKhyXQv9hx>vhs^a;=D*X z#u8Cf^vHomH){mHb6T@~u-AaCv1$K?qQaX}Xy`TVqVVkEEaEvk7SfNn{7LJASfdR{ z=&#z_qC*#~V<~A|vx!M?<@3avF3t?44dPlAanp3l&$X2zu&c9(vW9YPwW!q9Swbd= z&_Y~$OAP7ij8-BxK=s8!Q!K_2g8Qj1Ws}g794Y?+Su1ePLKC?5rHIZl#1yU#5p_*5 zoonxjp;@Raoy&0TW3fETS&Z)yN9k*u_?f;w6@|JvOYzR4aW^!iVW$#WpKGVYC{t|0 zwRYkyQ*6OCyZE#l+Lg|2@Vc&eLe@z*QH8eW+B{LTyE8gjie0$2yuBW_?}GZhC^9TL zZ46cT*rjJTt`!ucyQ5ht_TpM|u?FpU9XO6=2hyCLGDU2jPKw`5@dd8c5yg6-u5=#5 zu@`UE17p~O5DA^kwLFXUFRUU&$|9PlN zmYz5d=1!KA(1npKOU8LpCPm%tHXQBP+< z%bnq3M^9&*ks=F;oAAk}r^w?=(3p`TKM)bUocXK<6li^Wpf~EOun7%d5h4t*{hvPG|;}P+8FJ#A7uPaYpv>GxHir%809iuE< zHpFYfR6ob8XUBPlxf@J6%sEZm?C*@`n#eQ2Sxn_bWXuDi z(g3t8QzSB`P4pUohK!6^N6aOwkuj@?J*J3^SyFs&ib#ui><{xQ$$*9E%s7fBQ3^@dt^1zVg(UC$QkWznwVqOQ(q}jW~ejFQ%`+eM7yDw zSbZl{ zGvAC^q_;5%^=F!G5cN6v##_`JF86W$hC7qJW$M7z?D|@!`pDV>Dv1!q&s!(T+} z7n}`MzQA^Dl-T$JT9)Yp$z{DbYl=uNy@Y)vnlh5h+ahHooQ>pS5$#P8$>o%o3Xx9| zt4BIZnMtLl_=cQ}q|!n7j50(dm0cp$6p>U$i4LQlN-B-T%Vaf@%2#45M3<3N7LC!v zuNor18H!?1MkIZ(KqK7*f2MdELQ5pa{s((4qEF=?x-BE~58WPPUKATy(^~z61oXuX zm4GUAcs2ojfIf`P);{Xb+-v<(gt0nko8N=_A&QM8Gyi-eHjH+L7tt?OKgg>))2-4f zDAJj?pc+U<;@)UyTr%C>#YJirM6i<@=9A$#%XDr;&V}`SL^Y9*MEx<&@R~;AnVDbt z^HZpFmMV6Z9q1RS*$KM&K1`2t%=$*HtJpXu=c=_TrozlWjm6hvurK?d6JsGQp>L0m zt|)r@dg9snNH>pxX=099&qQU`>E`(`EzL3Osp%bDYtd};Z7}W5G3&W1Uq4*6O8b|v zUC6N;`!ZxCX?_UPZ#iZ?d#y~@vzMb4V-YC&(Dm%)Uk`s3O;efYA(_es7r?YE$E+v4(&HGD6mEyeqc6Z-0JcJ=odO4!r{Xi0Gv3&OaiNXN*@Cqe3FDsHf{hc+ z$6<{cIkB~vG|rh|UY}-(9dOQXY_{f>)H7r??D<=Z+2fpf{bdZR?HKl7ULtV3vxJ!! zf6Wv%#y^!8&x-!zkphgoxJ1kykItotYu0*VKddE;yto=SA|$2F+9KRgBxigb1&N#o zdj%0Z0edM~0jYAIs4)S}8L4uo7z!(&BNoxu5OILM4vBjcoTW;XKck1sBqwe`ps2Pb zC#r3kC6Q7ui+U3=WFw^x6T={SOA#scMk%pmqO-7>Q#XrG$=k@ObHzhbL{4oeVkQ|@ zY}jm~{v?do*sz6)(PTAp>lLxW6p>rK#4(88(u&;rW1RS95;`_^Y{f*e$*623*TbSI ziAHkmE5<~Zo<-1F^-Uq0Zcu?%>4TZ<336AbTQ(dOgN7>A%Mz85tP zqS#1c_Brpv-qE5B!fgP0lEyE=cFVAa36K6SUbg8!&UGgwpZxw zcdn-!FCB)5cZMy~I4rsUY}|V+W5TfIz7BU-Lok5IMONSSaFFjF+^0c0tRItprPcQ= z^xdd7bB(2+Er@(a|Feo5=fHpz713_wna&NGLu0Cp_U&EiB^| zi^4OuqldTGL#SMfamf(d%cJxZx&Q@6Fa7r*x(X-xg%xl>E>h0BFZ9bfT|C+4qHqanKn*#Zd-AaeJoZBl$4q0gijR6k+TDfUP_os_|PK-;Pk`Z(zA1tzz~| z*g>3qi~+E&IC%_1sKg!dJC}vn?U2agP852N4hg2v4oNKTWFcSNdihpblUdxULbc~J z_PrESSlsDC*Q#S}NimhheO~B;8W?9cs+-2*&J-$x`SX!tI*a?FP`6r)dV{4R*0bYwqSk2gbB)d8! zVT9LX+SbL>4CR0k-iX0}X2lLD83Vi-^AmE>2_<8I-^Z+dhq14fi~;@-6Ncq>MadZ8 zt(X&#??7fDZ~qE{iPVr8Pk^ox8vYy5T|%zTh%~Rq1iRwKw3i3!giOE*!7G4JxE&~z z&^LIG%PW>p{oANqicrxzKpBLrcY&%93cLqYkI)4|EeJUg_+A|eHG2Tmi_pTKfrfN* z0iJsZIF^(T9|27z^h+|(D}?-T#`Bs_s0en9UMmQ7%mCUzh@K63eL%>g9ME1uvE_k| z5?WmW=nSE86@e}iimU{56Uc+N2%hRWmO#tks$$~|Jk)C z*nUa=CZLW$3Fpz=%rUkZwKNV#Y!F{!eMd*izT7BN{jkfd5K-=NgKo88-FBmuX?S=86*htdtQC95; z7Pz#Rge_gSQ~c$4#aT7xt+&z`9!}khsZdm1;SYI#Nz|Q&!C}1V#J5p@*LGnHNmebs zu+G_=a9CkD=}{=-E7PjEIxNP!XQ;<_!Q+tO^>h^Ck8N)tOG&5i;Beb?lANhfZEV%9 zfdT2{jakWuB9EWTL8(w}Yt@d|M^`0aOj8aNe^g12)h<@e0;*)JHiAbB^74~*89?2w z+UuGgKm%YKW!Uuzl1{y?+8e`lr`O=H*mROpt%7Wr3bNo_Iph)|;%$CW^nb zay6E{atyUfb9=o&e7jL&hgmDy2TzCi8T*&W-~2PE&zL6rxQWymw}&97$UB{PVf)#% zm!+2gc?!3G*&p9|`r>sQ6m|S%54x^ES&7@jkcxS67!q=fFSdoQI=5$y!gmem>zOu{ zpXzgadz_Xe=iOlIL-x`%@#DFi_)oR`XVt_{hG~{jou?`vgmNjykA<9Tfm8t1Dmc8G z+sVfsiq1dFM^{cZpB`f196YG1)_Xs0eDO4!&zl1nt4-$*#_e+p;?rphJnM_sB#CRk zez-5Rs&SvR1;%3MD961Q4xgG%@{LNh zRKK@ro*2AKj_Vpc?wek+sj|^WFe;l}yF&x_2HycF>hRV1xs0tmU&Fg+4Z%YIyEZnS zu`T493b(T4x}8Qe_zV^*kFW>0u_cia)f~3Arrl+qjp*Wq?Ana_y2DTyN0|=x&j-R@ z#ID_3uSdsgu)S&8%hG*vj=z-In-AX`q2Eq6dGK^>`kd6VYpK|!klJz@4wrQ&WZr!= zYI*9Opw?4A{FTjVMFm4l_@KyxQ71Zo`ylv_v^(f%ng8@1kVe@H(ka0}9t+ zDS`J>P_ZdWVu#iP*d#t3+cPyTA{jqa_Z?hay=|7ES9P*R!Fifd!91zu)Zuh4`_Dbk zIfQw&MMzqnJl(@*B8F!lcL!}(^9Vdr1!21lct4swiee*)rAm7(4=vFZt~>B+u--R3 zURH^u z5%D(g$a0x(M1#KLndqTe=IUA2WLKJzjx_~U@hNJHgetZzEVIh3a#wS=m8xXN=CQ2RXcm!Rq@p!R!&(pkv% zAN$+IU?_d{2ypG$-RJCJWGtEhEYQtGpmPN}5!XjBE&M%nx{W#}iB*v1@!E>Fbu&K& z+l4_me(Au^ke6!YiFV)cdPohR6XkP`eC)ENWF9yj8w=S}1RRQ)PBO)$65F1sJa56h zcpsdG!>hrgq3I>NqeSFlp18p{b%pNM6COiMFWKP)E_>|HwU%X6k1xYvq3Lv;nwQJh z`}8~Lb-v{_oTuf;K8DjN6uAI%)|0eJD#~sO#39K^#$^x=w%T1GX3ulxbzQ&(u4k+z zFbZdfL>aCDL+~;@>$ITW+JaZ?P9m!@W^y(Lr#I~&%l2jUh#%R^N|m&^KN9C%mZ;pgKy+MG6h@X zJ2dDkUv^THN6IODb4zsw!vGgGfH$Aded*QE+Vbkds>ZO82b3O${`;WWK`@R%v5}w- zP&qB)0oy<_sb7bEiRm+j2BXHg6hGv68|em`?XdF~$z+a8{k0f%oHH)Y)^f1~dp5qs zm;2Cu@-`AlwFYA00z^cEeQ0DSw_JJ)PkzxBFNEE5I*Lt7`g$?OX>Xek@FVUUh`d8{ z#T&!5rQy!(^x%%~;oe(5Q)A=T|+c(te z3e?z0wWM@}j?pe1@S^;V>AKS)IGi<|%#rGz$GA4op?m%aFK-;QYR>e;++!og-r-eW zN1rF~N=h+3Qi(ra95qsnS}Izz)gJyd{3)TCX-8tuAtHbo%y!K(U@T-7;=tdQ%~Jg738$6uR<3EKG^ zgd_O-l%}}zY`Rn5s>?unpy_doYf}#6*(20D$aEb;Vu4#9!t^uOUUaIFo-s{@=;x9> zCi8HbI(a96M$E!K-Hhq>w3YI`i3C%89aOdyZ8Nq8x6xoQbg?Kl68JClK_c^|DY7M0 zra`GXm9cgql)r5awBHuv3K^AN zhJCK#qyE@Q-e$HX)}({lD7V(O=6M6BAXUSECw%uB{%opzG;V98 zRl;K~G_?vY=E!xI*%#4F7yHmS+)e)kZ|NDW(6G52`zF3?xAdv_E3VtoqIo`3gJqj} z(MX&y3V3jzGUIUel|S+ANk8$8k6+MW|6s9Wsk0`(D(uUgm0V$8v_sp)(|ym4#((Eh zc`c|b6IKN^3szkYTvlOg5OBp1`a!*dHI4&Ua*$8Z0Bj?v8y2=46Ud8q^({OGE*lrX zrMq+~D695TReNVb-&^U2)CKP2%4tXbwQpD}bV2R(`Fri;G^2iYd^ORBW;Xv1&A6T! zPfj~R9@dWgYIYt`JNoRT?FXMg;kiXnyHLkhSALXQ-NLjEKA|f+Mx%Q zENrz^wL>?6jdmVlpvG_{{g-dPvXix9s5~ipcUlRdwdVX>`SCVz z&Y}uiXb6N@VQ<`Aw^k0_O`5_t9-~5~(0wGR+U>NCSFj&}D}Td<&t+zHLacB(d|Io7 z()pKr(+R`cMeCQM_jdrsFQ|e%WI~+Myn1KbT0T_%flD+ced`ddYY5E0z{h8tQG*VS zQ#IyIi9f$}yfzVePBs(^uj1snMVwsWOmKZs5+|XiP`G)3XGv`6R@rbf2=a@(;X~YM zTf-ZYy1pDQ5q`#c^!7W(Qn=(2bL z>cDsMTI{Ea6*vrBgnLxP$b4UP;WQRs!f{^eJgvAq^etHms&ofMQ4x#1+;NPLuhg44|s8e9KoR#z)K@(1it>S z0&j_+u6<`$2i_Vf`*}MFcz=ZKCoc{${$M2a<6DyO=@6;^?jZ2FP|~OQHf#ama!48K z?6tnYS3~7&U1@~()Jx@&9lVY-S!#&H)jdlsIkgiuWi4xf)i`PI&_%tJ?UG(4f9 z=WXgQMT1A92*S+ga599((IkwU#xL)K)YO}1i1BHBjhMaK8JSir9BYCnboQ(^$vEOJ zL4=vlCPY|5R}UJy%_k0wCUlFg1B<86A#r)Nvv@*SHC%srCXDoaiRv==C5#Fr%zQrk z8p3E*7n4o#7B)y!TH{Q}lMf-1uu}!TPr4Yp##tow4(axL(?m3%gU;e;<7l_6A(=+LJ# zOZY0VGX_-6=V~=r&P)F4`J~}|l5oNM29BwbkN5z>w?TIh3e9}hUxIMOcNGTG%4hXb z2-otohv4*yIRN3hocpdUi6(_=a4~Hy-V}OQtXqpecka0mKG_xrMLF|-Cl=CFOVC=3 z-R2*OwV&{!CE+H<=ILMeJfxQ_1qy?kSpOlLAx*RRQ>(T7vwwp$-BOYkQ6vA6(;>~U zgf2t9R{pao0$#S{r!n>L_dWz^rjiEuuXZ7eCCpOd2>}KZ_?#UqB20 zyQ?7fw-hahE`$BASAaA~HJad`CkxVGOa8{NrTBN)4QZ&dW%&1K4{5liaA(-c`7^3F z(jr%XC4ZOL{*E)ODM8RQ`H;!Pb&jyyv2*?ZstF0HKgSh%@@bn zsvWJegq4=Ow6JRNc9%;+TxAJj5bN=FF{0FZXL!+S^Pzp$5-=H!-?U)W(59sb_iQ)- znVztx?F2$DNeo_(zmG@~OV>MN@b$@hXBpRlCa4?BLua8yM}uaVm4u?)Q($`hWfm*W z14&^1&h2n4!Bryj-+cs9NiOHu6YaN$kEg9MJ{^aVpYkMB_F{NTQ@in547S$$bb z5j7pm_sL+G;;eCSL!IJ$IF{fZB z9N2_czr7+52lQfG5lcX=D!}xHb`e{^&zFGdB}7kKI}0v1r{SaZrmEm6!)FZCZT-tQ zRzk-tB{BSPD}ZeXcBKT0M&VHuf%px0ONYSqHn=B8pk+;5tP!Yt5tD1heJK1@IcAtt zp0LdzaMm9WSO`ph7uRG2UJu046PS(`KPJ!@N#g{8V+9$zNT4{FyhGpsQXR7ac)KxN z0?m*SA_%u_b*Y1Nn0-1ZUcnNe(#nBV^9>+ad0+tvoe*%kF zgCznF&g10`0`D)y1w4Vze!%1rXzxNyTqM*3OX?1RnY%H28o*m`VfF|N+J@O9PzYmf zC_x|my$^wQ7*JmV8GRWWO~4~=1R6%+0X%`NxHphRU@A@@(+Ldr!JTCS2T$YWC<1{$BFz!_ zW+2{8AmEGhm$w%{UL0x&f$8mVrYF#&2;#3bp-X6}2Y~^PaFdWgU;yqI5V(UDUn6iI zoA>1e*aZAFG=WIm;r@t#bp-wfkieHPf zUw=Y3D&syYfppB?83KdXA-)KVnTq%#um=He$1p8vIOhiw*wTfu7y_};Sn>q=?LvGJ zsCNqSMWFsm2rmL{5&5$S%y<#uMc^W?$lh@gYKnEdgMhUxZg3EoQw%pW31sC#eE9;< zPcD=v@BootkH8x@5MKmNy^oDCfpXyV1p*5O;B^NAU0Wc$2sFQj@FF1Z>H7iP0x$l4 z;NKFAaEKt)KIG_l0>!#wbrPtz8SzD+FGGA0I5ZydMWCt;@kJo365@+MU{Aysfwdrb z9|6BvxDii)WAeWvkQW2Wz%f}aPD6O*q5RVq8-y05x>FeOMc~UFxbaWmOhsgB0#ozh z`5u7=_@(BX1nw0;d=a>I6Y&K~Ek9tYLkNt+bQUEr@eD4{32ZOQSPcSa!Vq2r4y{9Y z0aUicVtKqqs+t?|QYnGX-y^;V>|2e5O&|lj9w)E{Q+R>EE5G566@dz3@m6Q3tNtC_ zMMB70>dnL3$^=5zBAXHz*$^)x5U7On&`$&gFF_~;0!%}#U;@`LnK1-D!|5Q2Kvr7} zj=(D|v0)?-kHj*b!0<~5B?2Df5K072xGp1A5o&xFp+ulIC_GGH;#Pzbfr#RG#7UqH za@IovpJgGGf&kXUA(RLtAliEo_#{6KB?4hs$MFQ-04PUbG@_#}fmJJ!=Lwv|@TU>@FdLyn;H72=B?6Ad2qgkLF?st4 zw8uD36UgU8C=uw0d~lz@Qag7sD;B(^TOvY<0M5KDi-2zmLWw}3-UuZEE9Nuy3W2>? z^h*fr?#|eL0>geqC?V1;Gb$mJ2-Lzf6eVyQvzSic{yBsafl7~YN+qzl71BsoLPv1) zuMu#gq2&a+Al^0;*owve5rK|p5lRFeg6RtcW~0Sh1R7pt>S-8;e98Up=p;rAd2Ttn;x7XU~{wHN|hS|Gj%{4fad zMW8GqvJruksMUdh|0%p-NuW8RVG)5oVCo$La}kw02t-XpcoC@665&;V(#S*1@O4sE ztAO|-a2jLuM6ncj4|iV)l)?~u5$KHLe1X9EpAcUJ%DsX3BG9}L-cuuRYXR=H5%>|5 zeMP{H>5K>gD6tRWMSzDRyh13AB%~m|NLA+-#20~fqZ#W-;9U%V1c8@v^s5NO#Us85 zc%rj?1YSbuoR&Ul@jC*0!OMLDlTYHtRVct4N$h3fa@(#^%0?MBM@H%%FaN15txP+ZxNV>7M~C}_c`LL zAVA$ixHKnFzYeyJ1j-?$jwNslGdzR9JE@2-0`0ILStG#>Y|9A5*T=Suz!}#!crrrh zw^4{M%%EjP55yONBa;wc1U?#q_#&`$8RCmTZ+wg)5Qec%C$Qu=;)}r8bi@~dxyWp1 z2@FJ3T_?~Aq4$u$;b??c1VA|bx=#T@{_kM(OkfydIF-PP(}*tuZIR3cf#Z1lZ3Tg5 z%@AJ%I`_rCjKKMCu`eUA2kk#1FaifvE)u|FAi|5ly1EE20-t<<@FGyAC*p4ep;<-n z`+Ni*^}~jOz#C%`Uj!01A-)K-ZiM(E@Sz*=Mc~{<#1~evrQX+gd_Z9Q1;iJDjp#Lj zK)_18QA6M^mg_47f-vYM1l(zezYT=;e~I`a@KP1*%LuFhonI4ZcpO`D%$H>=$g4r1 z2m-b_fz8O}T?tG<=nN*Xt{&oxK&|)jqZ|ZUe~b+Ufyp@f;{SYI1gHUtt6 zU_(Km8U}opK$)S8-5^l%0k|hn7P0IV3o!34E}aPsgL52#PM_gcD1mqT;~FED^3Uvh zxX6&+v+xv(z;pz`76N15!$lK;_g-Y|B!S7_;14?pbRLW!TqBS#8>gJY0Q72gTLPs( zM=t_{+aOmG=!DcVmB6EAh-CtarI9NEToz|{1T(49rXjZw*aBjHB2c;m9_=AAElWdj zbDcm?TPza-^J-$55GZ*J_tOZ_FFrMu8ZSI4Ban?f&wB*QA_n&oNJ_>sAy6G8UL@dZ zhTYB`LZd(xivyT}u#6+HEfMR4Kofk7AkYG{n@!+F9R2GAUYUfy+95FHBW#ukR7X_q zAy5}bf1kjE!wBJ`09|oV!336niru~h6n`m%dLv@15*UwV)`URF%lP{r0*zn8Qyv1J zo3#6TXL!w0w@XgzHQM&L7g9@E179w6KuDgh$o} zE*MHb;N*xhH1^d$0;fba zCHxkSDXn~@)Ym0kAxi4YTn4VG^f82MDg9X-WLo3MSyXpD;U-aZ=hHWBKPEN3Xjot9 ze2;;wj4AkA>e}XMyU3UT19O^~fU`yQRw{<)VA&P5ibK z_RDe%%gIh{ak?ob`(b{QM6-{bQFZ5p!R@988O|DR%x_UNv}a`HJEpeYgeuT}A+>dD zF9*Kk<-bVpmHE9UKK$63P`u(T7{2#tLIydlb*CVAWPIe&)6mGHWqxmqkWZYkF{7%( z`hh$SKYF_@W1A<<#s=~x!2Ax2j-TK^wtiEL`ovk;k(eKgvZ)+!%wn_i2U+6eC(ddP zCk`j2gPd4bj`hbSB4M91gug86>_bb9MAklMVcheaw$B;KSBW+IoKb%4SJa%P4lYHU z+2?Fxc^oTB?srD;&7$spXW5J?ASGp>^tii3A04NgY%FfwMVNfK7v0OtvlKQ8QTf5* zG_iBPGd~|7PVIL_;TNZWLR+N{hoV9?9xULukSY+jyg8ah&>q2!widy3-`PLzET8M#%(c}waI=<4qkrOh< zNXMWRxgGOdf@zXx&2iYulSv*weK5b{;_JiClmc%wfX58!F~aa*e$k@n5d^~wQH#E6 zi5~P7B&Htu|N6QQ_?pf?@Z;y)+(;r335ggXv5Hg)Vvi6j_Fk0)wMS8#;!>+>&!fe! zsL`rf+MuO&QL)vi+Dcnmo1*-`-*Y}U#{c#I-`DG$_w#(8ah@~pxi|ObCdEXKkwdin zLc2wt6|eW1)jE_WtCQ3ECryS|%gT62nl-Ru1lN;WR=q<>d0Y>#Sv|#w)$663ckS(Y zTf5O6X=F;V7HOMO)^=rvb@5PAyt&(oKAaShvxdCBD__>Mn=Ja0B{wiK-8yeIIV_uf zveomj?DInxrQ-$m=D6dnqlR;M~W@r2ZOUNy3h2nN5DDXi! z$;8^3kieSq{#k_*b|x%v@kuEuX=kzr`p%F{DLWGx_+YGL;v`evkiXs4ldDsO(sogS zz@&DPDdVqy$0!_l$VW0|?M#utPv=OcoSlgYoNrA#DxWa)Ss<~BcI=(N({kKYsAOk~ z1%BIAGL`L2@xXyWlBr^6VgvgQlT5swDG|75n`ElmnUaB}rc0)pohcP~F+ws4b|x;c zxLhDARJSvwjZAUrAW?c~7JDgJ%wa#t)<{G$x9 zkw3|62$|yl35i`G>J)!1L+qJi@(B@{;!kCaT@fX>+%m9a-X&GvOy-d zU0b^_?GK#V``hVli)*`7u**wGqEdS8mQvgJ$!vK@7WrfF&aHBLEK4#o>PH9@_W57x zF56MZ&{bOWb6R;MYd6a~r>j&t>Nm`k$OI{z;_cSRSihGPoep_d&Ivsf%;i$FD!n*w zUwL~q;i{jfm=x`h@Ih~pbKqn&WZxzH74q~`nqQOhzo;Y2&pWfWl;8IIudTE<*2&8b zne5d!@@|ZgqQ`!n4@*%l3Fl2O%2;Zi6uk%@P)1%&$k}IBkfN&T#lB60q}Xk`9>@!K zT|x6*DQo|-e79`ygizBHa{OI}HB1Uey{z!|8L3dj3^Bf<{4*(A>n*oe&D1lDckEUcZTPiv#L~@Y5GN+r_x2K@VmE? z$H=@vZa5O=m?iaV2lCP^VWAmPTCO?;5|)}F)$GJNGo*ne+H9XKuhSv|3(0y+H``W^ zG$SQtwDk**us>{D*Z!!fu9@7%=yfhY0|!iZjdA9Ul5#Rgu9myT1mBsG2plzB*7svi zsJ;|40xQVVRgH;u#+1M6b~0*wVrN`|o(WPi$4U)`M zpITB7RPB_c=V#L;1$B~sYb>%G1`Qr3ulVzXK9XhCbl1#lE|J@qf2C3$`9yckd?EWK zY2+Dd)XZ-uT}IGCxy02h;B!(60<>aH|C)u&fMfERfelh~NC~56VQ(u*7jc^98B)@y z8Dpp2d4@{*Z9AR82&#Wbx+vjGj-ZJ|Rk>hWI!Td`!xg#=EOC;nRH>W+|1SYYl~iff$j|}D`$*bj1biX!@al2| z)h=b)=`z)my?esT!Ysy&i;tc}Ga5YIZ#$-GNPOOQu?$8d57mo<4m$ z7>NnlwtgemY(H&YGvrcw^IESquT69P)OccIp2phTsFfkHUPu;MaGpV(`x%M#?K(!D zZha)vz|Ob=x5+gkv7yu22rMY)d}8@9XIzC3N~VIH@wfv+|B_tAFde18Gq6fown`>r zU_H5vB~}mYC(8^9>?6-IiFE>XEyDs^$-PTrqd*;VWW&z7d75O`lixJ`@)@;45?ciA zm(e*}qa{o2`9!L<%B3659hh80GOfe*dvvLR;rk@l#vVdOX9(}wLkQAMlN|IUy{{Dd zT31yXw6p8Dod)ggjITE67*tV~;Virp4eVXf*i^+R?BJ*CS}riF?DE8JemdByaw4pi z!#e0eUWs-0Ns^}FwdBlBT$gpcj4k|BMoF)iwCw-zY;u+-e&ZAzJR#`~PI~l8NpE!0 zJ#>40>!inZmGpN`dZs*WB&Is)RdP*8+~lNt&zAINC!JIK+~TDFl#5T|_fGoKUAbl@ z{$OYP-OV@X>FX==lDg(~Hp$+!Z<=Hb;MB{JQP*p=<4So_w(eunpVYr_CZdyMe+-BS0ntQ+jsA8TtLxrEkPVn^)O zXC&yn>UWmc@PAVNb=GTki#^(6T{nqrv?F$l44czO-#ku=e#n|dBL412Qn_wfE!4wZ zX0rXwV%oi)8KxfgMtGpy+tqCwUdL{cUFHGRWmdPFHnZ!#*}%vr#Yy4A>;?_B!2oUW zg*J%O&g}+z;M*JQ)nz5u94s}H!@srLdbI6YZF@u8zFe4IaP84KH$nC-&nqKdJxZFS zgg>!6*`l4?mzgWZI(#uHuF6t*={~cguDP1k@=tv(XTqF*i#agXVzalPFLNVC3>xa;;7 z>!(XetqSN@|3ci=WQ&$_>%Bt=^Q8l|g??=?pqG_!IVoRZ{dSwbTR#^Opr2n4amUH( z_}kyV3eeBj``dwl@2ts}nc@zbzEv)^DF+)xD-pt6zwvg+jBg`{^GC9g%*JvpSUOy;?(!IN*v$Exyt^jZ z7cX9Tny!~UnOUyrZw)^En;f?-B^hT9)^G7Fw3AK$oGss>m1K0&r8{L|vOX_nnt`X~ zo%JJ2j!B^ff0jEPS%=(a<6xJpdF=ucICxS5*3m2SzH5y1(yfq;z+7VHvA>O2>4|J@pM>=I zYBP`hZAyQ8XH?4lp_F!$()4c^RcP0)pW$0PoBbuDDE&6!ASw14C9{Z~@5o=*WwRSm zWhFjUyn??1XWfYc} zoI*xXT}*bZpfjy&-Y~P}mkxq;X)PttT&6O*o?639ueQ@H7aUhh!m@7-*{Aa89wsx7 zY+l(~KKINfxy>fdt9L_&`R)+uPWsh{y_^MkwtI(Z#axrmlXQ~f$o$PLpvP9xE_>{n za^JwiJZEM-tK<4eO1_fd3Ymh3N@lwxwBy7~yJap9mxClG77flN!Lt%LZ3m0S?{W%t z2=+sl82_Vm<#|tv?n~^hOu;QB6QIY0Ou-E#lV1{fWlEe*557)&S)0=Ng1?YpWht#F zlZ-xbyHn`rAnSGBbWPHww3L!oQmKVZWsb`kq7Q$a$#qfc9XE>vUy^VyDeqx-R^}I0 zOP;{kbTZ`Ns}db86+AK}W@1c%-YV`o?}SB2uz3lYnZX5QzECQDDpQ%qJG7SG6Usxk zLxw|UKv)KkoI%ZV$;=GSEc2aGb(>7JwZ=(3;_aQzsbn zU6+@t}P?rmpl1-WDc z$y7Aa>To?N%=4SKpr{06WU@D-u8e7~ktV!bv6>Xe%OuBUh|DfIt05<{9GYeg7XDU@*bIbRY=i6n~l@=k*X8zq(|>f zPa9Ez66qy1d3b@oP5&f3K_*d{$F9m(aYx8c(|r2OsLb}S}xr*g3 zY(>~#)2uXFt}s4&C9p>$-^$H*^?U2~A4&NB7aZKS-= zm8`3v%+lK#g|$j#O*w7EN-~9MB_nE(Tz%`lElHm?GD}~5=R3Ml`c3n$5_iq>7OuA{ z{`J~EJz`d4pGuV>pUFNIx5*Ty4a55CY=q7}k(m*-OqO?0Qa*ZlOJAH3rC&1EYn$uQ ztMOM>SLdrVTUYH~ry(sh(`^OOGHIqVVZZH?XY2V3l8psykS04|%}B*_8MNizjr zobck&t~J==Yap&kQhpJBHZbWsWM;SN#Xh%W_R2pFvbVxzSZZX3j{n$mU7kjLz1xF5Tj|Gzx2nf27J)S{igpZ}e)LFzqlbo6hpf zOpZSp%qU5@mdfn)f1;8;9@!zXcY3TIsej41tQYWjrlx-T<(33_dN<#^XV?#Sy>-+l55Tc$9rZ4}nWViH{ezz!nEVCb~@AlEGGNib6u`>mGq12K4}uMcf8)lwXr6 zecg>XeG}HNhyM%hOCJ6*nG166=lo_?2_qM`@A0|tA)G}CFM@uaqSyTI}wCZQ+ zGp|HnNb!F%4b`Vgt>V6+vko=&qng26B$&f38(*g2pCnUC5+!6hZ|cp8*7w!=88({H z!Q~`UN6Kn@w6@;7w39@#OwDUZ#^_!^X17k-H?w;GCvO}|k5wh%%tTpkus(ecl}3YQ zvR?^ImBeJt=u`Zcl2|U2{YpUFnmW^m_m#j-{U^@brHVZ4S2EF>vS*@RpWO$gGktD2 zC$-MXWWSQpFZJA)$$llH)lHr0!~04m#8;}yB>ir)LhdDnRVu1I=@V&;gbQm?(bckv zt4hLGXZkQ_x?-Daz3oy`L+T{h^_E%fr3cS&E!iadDn+76cF9uNL{+6>fX?(GJ@~Jb zdd;^;Nm%fYG9Mx}2Wjn=dc#mv5kRs9hKt4GRa~jmm~>SEOmVC#YpsbDZeU{ea{%I zcaQRpt?^tU!FoR#E}5({*&9ZC@X?t*%pc7H?+?>O>6R%fbz)>Pit4?x*74Puzf-Z| zajmEK%eACV4Vi-V4!XT0Qe-NlTV1PXNbh{5S;_8quoMrJNh%GpF5FKF&#kxZGbA!i zreM91|5_4XIaO9$p%3Jp1s%{%iEOu{MfFatll0)DGkut|T_LSy12k_YB}Q;vnV*xY zXSI4!y+_iDzBI z)^SbB6RfwGF;ZGsCV4a}Dzks(ptxYhNouHEMt_&3$xBApKq)OJG1o7Ws3eI%NwB%} z(&M8ueaPh}uXBJ(p9vnjV|$O;71C?et%; zTfgT1BczEwv=?*1JjvNF&6~@U*E&VKbnT}SQ3vAk}QOJCjsX*f?i)Za_+s~@W!?vVUe zjkWg3*7K`hr>kt$-z9KagDrm5SbKfnIxs+zGTG10$6hWux7kddq?^eKx7PtAhJN(g z02aPFfLLi?R3`gg;ezyG#OWX6{c2=RJ?gyc!my9M+Ny=LXyR>k({81I+4rmJfAh6P z`5k*@U5817LEc9H+Ku$10)CbJ^GY>+$ok0+sg&MGzvTP5w3zR0<-0~|#Oa3+{K|#4 zq*aLB>Vx!F(rC9d*e;WOjE35c^g|7PasHEDThz{18~q^-uE|un-k(~vNUjC)L>(+| zEM=6*-p0A5r}RTHPCrHA7aMx+wH_b6+M|Bqu((Y2#w}tGLqD70SJXfBxC~kz&Keh$ zT>2r=S{gKW8d=4k$ldx-DZOZ}k-64(W};t_pgs}{-Y2sUrT$Qv!hV#D(Mao6vlrJ; z7neU^mWJiwEKa++Wa@jMddQoNFPq(aORcxwTQ9jLMo;~WieEk-yRVbSWh2=4c3QWT ze)_;KU%36@gBIG)+Q;&`@U`AwNG?U&nvGL*Y}%uKD#kC5Psj-wLlv35>@fQXEy=DQ zhAH)nsp-OcgI((Fk0l+IB*Rv_Y)6^L+Fz&?nw=h73p)a?P%I!7-3Bet_*Id#Qky>tzV zB*=>r=~5qYGMNkX1|wJ(RYC^*j(#IF__X9&NTQKuu1aQtB=mcv!M7!|SrQv$N_i$3 z*9;@YUwUxOaNBou4Q1%gWmMmDcGgl?wwbJ~d&ZF2E_;1v443D;tLAT~<-X?2VEvDd zx*L4t-F*3Z0{wqI_RF7uFNGsGTAu1~glH;zy?Gbf3D~Og<2ptLrvB zGy$BT zYJ=e9c+-kKS0pg?hs?=Qrn%5M7b4XbS`R~#YYLS@lZy#GLz8oKUvj|Pt!TQc%3LQ| z#==)ioE!K7PDzK?N?g$r)#=SP=4&O^Em>Ty*B0l_P*s}gBu%?md9%nMJ6IL7$mlv) zJ+dUX7ItMxu9>S;n$+<=-1d#8-s(uJQda(~$+50dX;z=C$>DB^bg+7BB<-NJC~I=| z(r+wKo6+>Ok_-W_lq|GvWtFkMwgG(H*`=vYvW%iu-mv5xu1EW=N@2+fu3h`Bqf>mc zTHCt?Hn!UL42-h+PR&+OvvsYI$b5CJ>6^0@OuZPM{EN#P|5c$d>%z5y{?>&&?fk7n zB|7+96>=r7vs&fP7h)aGpD)PzcR-_{)SWq!3%gzh&625^Ba@E@WqjN4b;%$MpKF$X zk>toqe;B5(Z&u%I8O&lXmwX<=?I+(Pp~_9kXE5CveRKFE7t;ct{9DMm{H4qa{l#xh zYH&<)NJwg2h2&2kS^rB5h?Gy5mkUdMULs|?X|1^!5@tO)mpjNhf5(5Ab+dx}r;;k2 zYUHt^w{=gjs(g_%*s5B%VZPLu(kZe2;rc|a54kiLE@PgNNi1MBs+>~K%w!eM86IUl zPcTEQKP#t1Tg9rIArk%Zm&V0~e|~8kWfkimqoEf$!!=Yqm()K{B_%qviuNfF)1KBD znXGB28t1lxYDiy2YnahilBS01Y=O=$&S)Frv(0E=Ra=uQhqX^X%KuE_v!>sxYF+dT z%VM2(o5g0`zSnqe>vytPPpYPjG?%9it(H>UC)XO|FsGRw>RF7B?f=!F3-`Bn)krDc zU6Z<+1>`2y`_R086W{yLe7#rmvcp=xnwRpvu`ba2v2c4 zyTrKoTJaY~R;|ZF7gwIVR?BNFGitn1-iv&kUH+x9l)T>J=aoMwo_nLduiPfdBfC-4 zuJE5nb`_a=flBd|1f-mEm z^2Efv9*EJ6st@VVEkvHPb4HAA9DNYaEq`0lM@)Ig^!P<5ALBhPz4b2>ul};WzrGn4 zd6k01mj$}u+`kiV@J9Rwae3~vAKnH0Nxan?@teex-iZILdAYrc>F}~ZQ@L+D`Is&* zMuk-VIMwqZt)_YITwq_ z|D0Q+$mjC*sn&ZTXOt@Ed@s>unuadhCH3?X^D|24I`Ei}9COQm2+&8&cpH1U`evAs zTkc%+5i`lgF0cAWQe!p|pxDGqlA(uQA zhv@+1WtpA@u7mmnCCW{qUVdHrpBl2*3Hd50=2Yc|JfHfF+zk=elijsJUgqNmI2jk> zCX`pIcKsXp0A+94aoMPb%Of2|5qJw*Vn^(Y!*L9LhKunip2xrN5kALox#H@IM2a3w z)F;paQ?MuY!^t=c7vWd99(Un>Jd7vtSG?|$<6j5xFM${6>*I_t6!qZ;kfAA6N z`KEDy48>?ik5QaJ6>Na|Qc4@@yQAtD{0#MNQH^iJA8-$zz$}L-ym=s|3y=t6m+B+F$?Cx7}VPvt(SN{`RK~5}!<*+K&L4B`G>%WWLaYz8?{{#Ya zaT#vJU3d&Hp}uFO9pA+#DDPj`@jwj2NGynP89D!}6KIMZurE$T3)kR}xDSt@zVV_1 zyMd1|L!c86#{%|0ypoEg2qa)#Y=&)7-*wQA`{PGA0~g_1+=gj*4*x>WJrd8*El>Qq zfJ_*UdGIYPj#aP$CSgw;hO=-nZgTV(`w1Mwvv>vXqA5?tl0F#?IIq zN7%~#pG;sruEfo_4^QFm_yGUI48hI-gE0c5urS7Ac~zhP6A84!E;ta!;zIlycj9q8 zhgb0yKEuGw&H!^_5z#*X%MqxJEinbVVjmoW6L2mr!;QELkKrY}jW05D{`-ZnZ!tUO z#UfY|D`0hOiXE^odT=VPz;E%Oet=33s^19wj(_7L%n<6-3&#Rj3KOsi>K}o$-){H; z4#kgfhKIx=T#MT<4bS0U_yhyw?o}5Qia9YKzKx}@64pRZ0}@Ht6NlkMoQLc2NBjk^ z<86G5`lg` zDL7ZO&;MlvHsUTkhL`X*zQAC4$)x)>Hx|TVSO(*!)9@Vrg-6tdGqx89QTd9E2X6iVJZSevb$6N+jq19RmKjoss3hd>DhJFaeujd+dWF zaSATLrMMcu&CU70jX)Zn!@uwe>c6M9_bnE}GFTHEU`tHFuGj~Mcu0)Gi8v2e;CHwO zPv9+lidmwZ0p`b|7>AXyK6=`c=z&A=W3+HNuEA9N5%=LK{2d>lJK7moR?O$9l8Mi`0jU>U4}wXr33#sN46XX0X9 zhnsMRs^|ZH0>|(Y-o_UgoX;6xZY+uwu`ag34%h?x;fFXzw9o&^1ZLwxT!r7`0X%~@ z(9G`)EHl1^Ww9zIViRnipYy*D0sR*adU{R41^6{?!JYUs9>;Td6Q5$n0#3g0miD&F&u2rB3dBqx@@1gwY6FbR9&Fr0|< za0PycdoT?>zmPbO*YOehz2yun0t;aotclIBBlg2#I0h%-Y)6l=fWR_bjo;xOJb_p6 zE}Dhda#$GSu`#y64%ow1_Ww`nt!M=EEY` z0+X;O4#rV97H8rj{1SiAuf*!6KZ*A-sDu;OU**#B5?CJVV{`lfhvHoPAL@S{)qZy2 zMfBVt@f0(abSj2pVT{Gb*akb`033;*;5=M}8!^q%W85U*F6AsZ2#a6|tbz5hJAQyu zaV~Da@9{KV#Cx`~|9#_}1!ux&ER2cR1lwRQ9E4+WGA_c+cp7ixV^z=p@Y2oza$_u( z!xor~!|)^g99Q6OJct+Y4*rWlWjO!CB%udK99G7f*c#u%zBmLY<1*Zh=kO|;Wu4^& zU}Ra&{{jT6VIAy(y>SxG!gaU_f5zYN8a_t-^SQ2QG!`kx`Co!S4eWyba1?%mb8$It z#I5)n{)x{pV|ix)p;*L2A{HBB3+#tOaXv1=?U;rq@E!(Ma2A*aW3U8z>X2xO$v6;) z<7}Ld8*mFA!!vjXA7e;GXCM(++|gr{AFva_JlSQ+2N_i!T4Q1$%ZN?;FO$A3^i;-yDz4y=la z*aQ3FY+Qiba4+7%2cmud9}({?APTEt9qfty@iSb4yYV3YjSn$^!2d8R!KqgW^ zWw0T(!1r+gPR3dIHGbphF%A$oihtm3%v#eKKrEKUM%WU2<3OB(vvDf@5(Keu-=GD4xcL=+nSia7HYG)i4n~?MZa?25>UY!msfgJb*{> z54?^34V?jG#zI&OYdLz11_U}|FC2@La1H*9$M8?Qg8_}41&3f^ERKoT$X51$Hv)a| zW1NQH;a0qWzoSoMXMurO5-VU&?2prNo~q~nj|6_gd-xP{H*pqF5Nl&29E2lr5q^mW z@EG35XQF-n=WpsP;B9PxEpRY;a4~*`NANU0L02=U-vU?^8)D05oc|*TjKdYU7LVc? ze2PBJodv{TNom$}J7tn0sbR2+hV<~Kb$v6zrr>6J*Ig` z{ECy}U3dVm*vkI@lYmbfXTcdUKgM7a zY>mTkH2x2lV;Y{s4DUMq2jknSp8ur?yo>MQRGf>Oa64YcKQXkevw$2}5v!yAhMqnh zzmL;I`~0^EY{R{H18-xNB&UO%SP5%jPwbC#a3TJPKj9xqod0(SWKVV$5RC~~7kl9V zoQwa%J(!07p#BuJu6d3W$GliQh4a52fqpm)7vNIdi-%DE*QR#-7(?1Q`8-$@OJfbJ zi>*8)y5n42gkR$Z{27nqZTt^ww08#309#^v?2i4=Gn~XYoQm^s9qz_+cn$x?#~9MV z89)K7gpIH@c5?I>JqZlJ4{o8C-E9SK;O>JK*F&gmd2Xc z0z2bC9EWpo8GhSY_P?ILdkCDw3-|}#!~f8)i_dfbdh@eDr1=a{RzGl2Y96&qqpTiO5J2z-FUa2_tgZ}5A(hWGF( zX6@lDI2V?~s+f$ORXzVdBJc^Wz_oY~Pv9N=7qj(r7MKUiVm!9Ob~qfziuU=xn80>C zgIDn{boX)=6o|#JG&aRHI0#4J5?qPfdU?-(0%!0N{)^`O&Vs`+H7YodHB*1x *bT?yRQwt@;1N9SA@KnJ!_Yp?0t;Xztbs|` z35VlYT!2e)EAGJ?=($ZIsIRlYoLB@)U=3`JN!TA3<62C`!*~iG;D3%DBi9Gcg7afl zOvEnO8zOM#Ic~*E_z<6C!~kc3QCJykVn^&L+UNg70yA(ers7$=fiE!Y zKxaWYu_TtqmY9sga5PRE$oapFzy|ytPvHf8iavv!1xH{7tcmZU{(y--y^qB4xCB=Y z;`~2K;5YmS0|q-Cgkm|YimkCd4#gQb2fx8Bcn+_6NCXXW78HhMF&>k!6OP7-xCXc4 z&v*iV!-wb|>MYL_N+JiA!0Ol-TjN0d2tUCu@N3+Ld+`kZj<+2>#(xCd!<-Qn#1dEz zn`2uXj3eT18Lr2zxF1jA1-yxm(LKWHHv}W`Ei5J4=YKqbde{m(;`=xZ$Ky==AFjlW zxC7Jh3|_-KBRKz`67V1Cj5rLVu_%_q1Z;$Du`BjR4^G7SxENQAt6~Fu7rWvB z9F0?PKCZ+~xCf8pWps_@{11_YK27Gv7%Yn&u`iCm8MqS<;~)4Cea1QchhT1u8OQmb zLZBy(!!uU_3U!w%8p9kLR=+M_?8%#HFhooQ4bWYut=K;YqxLckl&f`q=3|7Z$;?=&4Df8Fs+F-U>Js z7vi_rbfU9>cKAMih!b%seuLW`J;osd4L)%?nu}lH54aD1!Qb#Q{*6yDc#_j!80NyF zSlU+he`5meu{(~%*|-ol;cmQ(#$;!K88IiuU?oh%=Bl3m-3g4u2{;`;#U=PPZp5v) z7Z2lUyo7(^J$xqG&;PztoRJ4(1V&>KEQuAd1~$N!*bckl2RIDJ;N&Ts|8ofZ4_Dwi z+>AT%XFP$w;qUklK1OpYy9Tpj(3XyGFK3ctbcaW|&nFL(iO;2nH|J~KK0gJwEw8jg9e5XNG8Ou%~B9FwsN_Q4@I z8b85VGdcek5Lkw5Fcr7semsW1;#Itb5Ag;1&vI5U6mw#J4~e2!8mnM!Y>aL2J?x1C za0HIWX*drT<4W{wAn^n4!9#coFXA6~7oVbgwzGzrFdIf;VJv|a96d&L0`;*4reIg> zi$n1voP@J+Auh+YxCwXQ0bAMs#|fOnYxp-lLSv4zh5?ubb728|2g_hQCSntOSJm^s zBY|Ex5J%z!oR0ci^7>q`1i!|OxE1%}VLXkO@K4b`|L+lahQ4#11q5RRMq?2yi50O1 zHo%tH4!hw8IBYKG{}=+3aSr|uSKvC_j63mXJb}OA@AwZsM$>XuFr&r!pOru)7Q|v$ z7OP?%Y>I8M6TXjw(1Rc24E)Sn@CAWY_$_Y3pYRBt!OQp;-pBti!#rnAGh=qli=G$~ zrLYp##D>@k+hcd^hacitoPu-lbNmw5J9>;Q1a{#;Jc;M=I^M>A(eo5}E z@sKEwHL(dMV|N^gqj3s;ipy|4ZpHn05-*|W7Kwk+ccC-VP|S@*uryY~2AG0_a5CyI zi|UirCOm{!9X*Ec|C|a1u_|`Pakvck;yJvF&oSh4r@yzb8aBfoIL+20Kd(SwJs!l% z_!xs1IUN_k9yki;<9B!tpJDFBPWvKQQPuN5iNJ7NfZyP0yoZ^Wu!dM0yWtr89M|Dq zJcrLj`}~ji!s)OiHozV@0T<#|co^?v$Wo`Dir5l+;Z*z@_b%o9zfQn^nbScrY=k{= z0-X8OwM=p9VNZWy!DDKCpPunDGMPaJ~d&@+?7=eP^5nDKVjQ0ri#Yy-Tev4`NH)dYtEHD8-#0fYH*WiA4gNHd^c!aY^)Ur|;yC=& z(PJzp@C|Om19%pnU}iaE^oF7ireIebj348txEwd&c3av1X#~#Vb-a(}M)oNd$9P4!eu-P~EZ#)F%}zh%usbfrKhW6X)GMvO@uf#|p&uNpV*^aW z?${qk;zXQ<|HGB|9d1#l8^$3#uF5Iv`IEpC^xG;0@+_EJm4TJU!8i?`)xScBX zJK`YX6I7`;85i5-a{e!~6Na${zrpWSX|NrS5I=zzh+oBjiT{Tgesl(s5wl_hMynoK zKtWB2r70+nHHg>26yon;PvU)XH1Tmbo%kGFPJAV95Iwr!O;k8e!702*{2H3uoi*~s zjH<*6<$iWh)0kM)Q4QgRid>_Z*R9u96@i1OOznxBhu~;9w;X)6I zH2f9KT~5P>*bxWdRlJ2yF><%lE(YsiH(ZEm=($GXZ+wP1_Bb6?##-1M2jVcCf}i0g z+<^!1IJ)=R{diYq3=)5z=N?2R>%4{#8&qIXaZm1_jnoq z!hbPjpR<4x*brOc2%LuJ@Qyl34#xdXdwwzirpk zmn!w6RjFTwcm=F}K+k^}QEdW^RcX*dl?Hu@55N&P8YihzZw{^|z8<%z(%+AiA0d7M ze>)(BTH!Jk?o#j&U!c#=Qcnh&NtOCpR9SEo@%&g6W3i$t^&4Xg>`Zxg4~c#_2)*$! zO7M{vG~I{4k!zb9haa{ycw@ctXK*3^?di2*&)XY=J^pf_NFMN4ycX zA)bQ$i4VrnPTXURr@~?imf>3B8&%oVdx-DHQ}`=h#T$4>l{I{*N_)RFX9WT=T-A?X z=G25#c$OyyZ97eU`Dw+(g9?~XjPV10E>(E`5#AxMiex|Wa97PVB#O*IO3n+eBz(um&8}& zR^mHw{~s3v?fL)+Ah&HOPSlh!?>s#1pVS@h12l@h;fsuq<3V>`!2% zDzPy*i@1gVBfbJRslyE8Cp@hVG>q%2T)OY7Yvmxsr^GWHapD<0Br>bgu(;Y+ekN9x z4(h1VK?7{6_BD(?YESuQgDUmLt5WY1oJRQ~wTt{vtt$1lP`(X4yC^tB;254#rQv8$$N}?6f{<4K?Bqz*#)YMcoOB)a5m*% zsjcK}QKjB?%6H>_%FnA!4da$7^&U|EudVFs=TyjgOe!>x-~CdhVvH(lS`153o~S0u z3l3H4wWGWvcB6cRT3udns8Vk><@0c%s;~dQB(MtCtJ3h0T19@GLX~>gDE|ZhrrhVa zl$Vz$B~|L>RAu0KFuyA0acZ2rV!{TZM*|%+APqWWUn-1Ki_6oix19|oLs z>gB|IC-wY~mRl_i$N-0TWkA{l++xnX~F1AGoAY9D>7frYg6eb8#Uq##H(mcXWre~p7x5VK#jrGSPYnWz*ocA@^6z1H z;zP&}$0=z4%$+QF9`#lb{~CY5?ReDDW7xlYCk=n6;7`1x$`&v(IBVp_aLj>4F&4|J z(ykWyy4Zwxd-9!ZWx<09e25>Z(!mV!b8rE1`*-rB-CE*1aWAG(?;QDyc%Aq|@=t7~ zBl`#RWP$b%=t(}z&spPKs>EZ++rOtL<)w+&AfAYgh^LT$54#f|LVh?-5fk)anL%I) zF2~iX3}Bl&P!3Yuk7>5n^nEFX+Vqu|-TqQd)L#o$Bk&znZmmjSIjn?D)h_b09hi(A zY^{*}a!r-{m_?cuSK!ySR^$CCT|IJp6Bi)GVnvL{7OLFVw88e+35Tgo<;D-k;Y9pg zZD1H*;7VMByTuB6`?601;$b|F_HXJ{H;h}F7w_X^TdVJZltLc4DJh##ip46JfUQ-z z*+{~U*cCrib_7sK2=9s||KpxqeP5RNe@5+Pg6jGh+ni!V+q< z9F>+Qv{8ho1=%*(9y?)A?1K|<63)cAxDXfPX55Oqai3#^ahSkyl(S3@Vk^35K!nxq zV9L*_CDT%_nMJ0{ue9ouve+1#V{1&ZO|5!3Wv6LnIhu0B^B_oCOp^PuOis%%?Rz6X zg)7&q0^|#;vR!4j*yZKa5LqJm#%ea_r{T4IH_gl4!~n{NsL}H4rsQX<1?9nbL%Q@lphmS<=B*;|F!ekRXLW6 zl8;pz$fcqZfvT#UHTE`?4(x3xXPLdtB;Q`k&=f0Fi4$ljp`jx z&FXzRrABIl6DeN>r*^rLvd`_>oz;rHk&>;#4%tlK$|O&+_Ov^z?0ZRjAF_h>&me2P z12Vm=XN~f<*In{5{(Ae#ue6sJO|R6mj(FSaPd)#?+UwyEB$F;b=(T!Q^dF30e;WG# z)qeXc?e!O-U)HnwdfSJ-7Jq&GCthhU?<~C9e!I7Q*8fj?JuJQB*F*1><%j&q_~nsm zJKoY(nhi_OuDB_c3#4bGZb@mJWSzEsZb@mS^wR5ET0gzC?B7z_JiT=7-%{Esz4V2a z_DU}u{Ew6lPcQxHA1NK1UK)Qp#R{06p1q*irRiDE9cjBUz3t&U()Ne+(%N^W^k90a zbyrGHq?cyCC#6@@OWWO((wpg}r?m80dTF8iQtB?|-BzF9m(noFI$Pr(Da{n=EtQSi z-1=u*vs~8r2PuU!74=q=cuOn(M~R=Wm?^vU_k)yj0dd|&R`G|@Wesm#%kxkcSU7^4MOX=kF(ok}#6onCrDOHZVi7Jn+G=h918JeAU$>7|df^nQA2pJ!6)F7DlgKR%Pv zAjvw1YT5s!G*YsO_MtjKvz^i_pVDlv^vZ>vr{uR1x@Ql!+C5Ln956h+-r(mcQP#)? zZ)dmGJWmO+Mt%_DZ|!}a5*;u$z3o3z#oTUXevwirV0L=L_!rV}Wk})d)}R;CFwed& z{^l$z^8qs|W`Vb<3~a7Udg|&?P)-IeXQJM<+m9nYb2pmVtiPpw-c{13utfE=oF|jF zO)=WItkGHGvsv$-&k&Ghh!gAkk==_{p3}Hpwh99zEcZ=DRl+A;8OD6AC6f+gr_>7; zePq&yzk6<@4B6h>_D1uo-c^+<3uW>)KjbXkaLKcTK7ypcyGEMVHPpw|H|mACXN`K1 zt^7srVrYKzl~FE|X5Pg-e4}}!RovAsB1>s`j?pD}mtNoQ_1zK@w%46rpS{xS7q9f% z_l@SwWpQ$+p8oI-enNUZ>)`Z?dCHG@qyL~-SNgNt@>lx*EWMr6WiKnrM@D`AjqoD( ztm)6Qy?6GFUJJa^>sPPznkUQaE3Ge)Yo?F+b?BU%8AUvJtiYrdQgJd87Sb|H@xEH2sP?6OM4`Gj{|@y3XT zWOfe_yt^VRb< z{U;$)_SAp2cK*)aES0)^Z|5)GrzEveT$h9ev@Gw8Z0(UQD|>oFsqHIu{r8iXxu3e8 z$(x?5`bXEAb-g*O{ZC!9r!Fnk?PUckq(EHu)CDcN{riqnD=yYq#D+25E~li2?D1~6 z+-*t4^w5#)MYE?4$kV-GcW)?l(S+{nTRFpyvl^B5$)4KhLid(!UyEF+&|^%%{{h!? B*ZBYd diff --git a/include/api.h b/include/api.h index 75ae773c..241b7cb7 100644 --- a/include/api.h +++ b/include/api.h @@ -41,8 +41,8 @@ #define PROS_VERSION_MAJOR 3 #define PROS_VERSION_MINOR 5 -#define PROS_VERSION_PATCH 3 -#define PROS_VERSION_STRING "3.5.3" +#define PROS_VERSION_PATCH 4 +#define PROS_VERSION_STRING "3.5.4" #define PROS_ERR (INT32_MAX) #define PROS_ERR_F (INFINITY) diff --git a/include/pros/rtos.hpp b/include/pros/rtos.hpp index 28835245..37000fa4 100644 --- a/include/pros/rtos.hpp +++ b/include/pros/rtos.hpp @@ -369,6 +369,19 @@ class Mutex { public: Mutex(void); + /** + * Takes and locks a mutex indefinetly. + * + * See + * https://pros.cs.purdue.edu/v5/tutorials/topical/multitasking.html#mutexes + * for details. + * + * \return True if the mutex was successfully taken, false otherwise. If false + * is returned, then errno is set with a hint about why the the mutex + * couldn't be taken. + */ + bool take(void); + /** * Takes and locks a mutex, waiting for up to a certain number of milliseconds * before timing out. diff --git a/project.pros b/project.pros index 244b556a..d9ce3a7e 100644 --- a/project.pros +++ b/project.pros @@ -1 +1 @@ -{"py/object": "pros.conductor.project.Project", "py/state": {"target": "v5", "templates": {"kernel": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/kernel@3.5.3", "system_files": ["include/pros/rotation.hpp", "include/display/lv_objx/lv_cont.h", "include/pros/serial.hpp", "include/display/lv_objx/lv_objx.mk", "include/pros/llemu.h", "include/display/lv_draw/lv_draw_img.h", "firmware/libm.a", "include/pros/apix.h", "include/display/lv_objx/lv_table.h", "include/display/lv_objx/lv_cb.h", "include/display/lv_misc/lv_log.h", "firmware/libc.a", "include/pros/gps.hpp", "include/pros/motors.hpp", "include/display/lv_draw/lv_draw_label.h", "include/pros/imu.hpp", "include/display/lv_objx/lv_ddlist.h", "include/display/lv_themes/lv_theme.h", "include/pros/screen.hpp", "include/display/lv_themes/lv_theme_material.h", "include/display/lv_objx/lv_arc.h", "firmware/libpros.a", "include/display/lv_objx/lv_page.h", "include/pros/rtos.h", "include/pros/adi.hpp", "firmware/v5-common.ld", "include/display/lv_core/lv_obj.h", "include/display/lv_misc/lv_fs.h", "include/display/lv_misc/lv_font.h", "include/display/lv_themes/lv_themes.mk", "include/display/lv_draw/lv_draw.h", "include/api.h", "include/display/lv_misc/lv_circ.h", "include/display/lv_objx/lv_tileview.h", "include/display/lv_fonts/lv_fonts.mk", "include/display/lv_hal/lv_hal.h", "include/pros/optical.h", "include/display/lv_misc/lv_symbol_def.h", "include/display/lv_hal/lv_hal_tick.h", "include/display/lv_themes/lv_theme_default.h", "common.mk", "include/display/lv_objx/lv_line.h", "include/pros/screen.h", "include/display/lv_objx/lv_lmeter.h", "include/display/lv_objx/lv_btn.h", "include/display/lv_objx/lv_gauge.h", "include/pros/motors.h", "include/display/lv_draw/lv_draw_arc.h", "include/display/lv_draw/lv_draw.mk", "include/pros/llemu.hpp", "include/display/lv_objx/lv_label.h", "include/display/lv_core/lv_refr.h", "include/display/lv_conf.h", "include/display/lv_objx/lv_roller.h", "include/display/lv_core/lv_lang.h", "include/pros/gps.h", "include/display/lv_misc/lv_task.h", "include/display/lv_misc/lv_gc.h", "include/display/lv_misc/lv_ufs.h", "include/display/lv_core/lv_indev.h", "include/pros/adi.h", "include/display/lv_objx/lv_btnm.h", "include/display/lv_draw/lv_draw_rbasic.h", "include/display/lv_objx/lv_tabview.h", "include/display/lv_objx/lv_led.h", "include/display/lv_themes/lv_theme_mono.h", "include/display/lv_core/lv_group.h", "include/pros/ext_adi.h", "include/display/lv_objx/lv_imgbtn.h", "include/display/lv_themes/lv_theme_night.h", "include/display/lv_objx/lv_slider.h", "firmware/v5.ld", "include/pros/colors.h", "include/display/README.md", "include/display/lv_misc/lv_anim.h", "include/pros/vision.hpp", "include/display/lv_misc/lv_mem.h", "include/display/lv_core/lv_vdb.h", "include/pros/rotation.h", "include/display/lv_version.h", "include/display/lvgl.h", "include/display/lv_conf_checker.h", "include/display/lv_draw/lv_draw_rect.h", "include/display/lv_draw/lv_draw_triangle.h", "include/display/lv_draw/lv_draw_vbasic.h", "include/display/lv_objx/lv_calendar.h", "include/display/lv_hal/lv_hal.mk", "include/display/lv_core/lv_core.mk", "include/display/lv_misc/lv_math.h", "include/display/lv_objx/lv_bar.h", "include/pros/misc.h", "include/display/lv_objx/lv_ta.h", "include/display/lv_fonts/lv_font_builtin.h", "include/display/lv_misc/lv_templ.h", "include/pros/distance.hpp", "include/display/lv_hal/lv_hal_indev.h", "include/pros/imu.h", "include/display/lv_objx/lv_sw.h", "include/display/lv_misc/lv_ll.h", "include/display/lv_themes/lv_theme_templ.h", "include/display/lv_hal/lv_hal_disp.h", "include/display/lv_misc/lv_txt.h", "include/display/lv_misc/lv_area.h", "include/display/lv_objx/lv_kb.h", "include/pros/distance.h", "include/display/lv_misc/lv_color.h", "include/pros/misc.hpp", "include/display/lv_objx/lv_win.h", "include/pros/vision.h", "include/display/lv_objx/lv_mbox.h", "include/display/lv_themes/lv_theme_zen.h", "include/display/lv_core/lv_style.h", "include/display/lv_objx/lv_objx_templ.h", "include/display/lv_misc/lv_misc.mk", "include/display/licence.txt", "include/pros/rtos.hpp", "include/display/lv_objx/lv_list.h", "include/display/lv_objx/lv_spinbox.h", "firmware/v5-hot.ld", "include/pros/api_legacy.h", "include/display/lv_themes/lv_theme_alien.h", "include/pros/serial.h", "include/display/lv_objx/lv_canvas.h", "include/display/lv_draw/lv_draw_line.h", "include/display/lv_objx/lv_preload.h", "include/display/lv_objx/lv_img.h", "include/display/lv_objx/lv_chart.h", "include/pros/optical.hpp", "include/display/lv_themes/lv_theme_nemo.h"], "user_files": ["include/main.h", ".gitignore", "include/main.hpp", "include/main.hh", "src/main.cc", "src/main.c", "Makefile", "src/main.cpp"], "name": "kernel", "version": "3.5.3", "supported_kernels": null, "target": "v5", "metadata": {"cold_addr": "58720256", "cold_output": "bin/cold.package.bin", "hot_addr": "125829120", "hot_output": "bin/hot.package.bin", "output": "bin/monolith.bin", "origin": "pros-mainline"}}, "okapilib": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/okapilib@4.2.0", "metadata": {"origin": "pros-mainline"}, "name": "okapilib", "supported_kernels": "^3.3.1", "system_files": ["include/okapi/impl/filter/velMathFactory.hpp", "include/okapi/api/odometry/twoEncoderOdometry.hpp", "include/okapi/api/control/util/pathfinderUtil.hpp", "include/okapi/impl/device/rotarysensor/adiGyro.hpp", "include/okapi/pathfinder/include/pathfinder/spline.h", "include/okapi/api/units/QAngularAcceleration.hpp", "include/okapi/pathfinder/include/pathfinder/trajectory.h", "include/okapi/api/control/iterative/iterativePosPidController.hpp", "include/okapi/pathfinder/include/pathfinder/io.h", "include/okapi/api/control/async/asyncController.hpp", "include/okapi/api/util/timeUtil.hpp", "include/okapi/api/control/async/asyncVelocityController.hpp", "include/okapi/pathfinder/include/pathfinder/fit.h", "include/okapi/api/filter/medianFilter.hpp", "include/okapi/api/chassis/model/threeEncoderSkidSteerModel.hpp", "include/okapi/api/device/motor/abstractMotor.hpp", "include/okapi/pathfinder/include/pathfinder/structs.h", "include/okapi/api/units/QAngle.hpp", "include/okapi/api/control/async/asyncPositionController.hpp", "include/okapi/pathfinder/include/pathfinder/lib.h", "include/okapi/impl/control/iterative/iterativeControllerFactory.hpp", "include/okapi/impl/device/rotarysensor/IMU.hpp", "include/okapi/pathfinder/include/pathfinder/followers/encoder.h", "include/okapi/impl/control/async/asyncVelControllerBuilder.hpp", "include/okapi/api/control/util/pidTuner.hpp", "include/okapi/api/units/QAcceleration.hpp", "include/okapi/impl/device/motor/adiMotor.hpp", "include/okapi/impl/util/rate.hpp", "include/okapi/api/filter/velMath.hpp", "include/okapi/api.hpp", "include/okapi/api/units/QJerk.hpp", "include/okapi/api/odometry/stateMode.hpp", "include/okapi/api/util/mathUtil.hpp", "include/okapi/api/control/async/asyncVelPidController.hpp", "include/okapi/impl/control/async/asyncMotionProfileControllerBuilder.hpp", "include/okapi/api/units/QLength.hpp", "include/okapi/pathfinder/include/pathfinder/followers/distance.h", "include/okapi/api/chassis/controller/defaultOdomChassisController.hpp", "include/okapi/api/util/logging.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/tank.h", "include/okapi/api/odometry/odomState.hpp", "include/okapi/api/device/rotarysensor/rotarySensor.hpp", "include/okapi/api/device/rotarysensor/continuousRotarySensor.hpp", "include/okapi/api/chassis/controller/chassisScales.hpp", "include/okapi/api/units/QTime.hpp", "include/okapi/api/control/async/asyncLinearMotionProfileController.hpp", "include/okapi/api/units/QTorque.hpp", "include/okapi/api/device/button/abstractButton.hpp", "include/okapi/impl/util/configurableTimeUtilFactory.hpp", "include/okapi/impl/device/button/adiButton.hpp", "include/okapi/api/chassis/controller/chassisControllerIntegrated.hpp", "include/okapi/api/control/iterative/iterativeMotorVelocityController.hpp", "include/okapi/api/filter/emaFilter.hpp", "include/okapi/api/util/abstractRate.hpp", "firmware/okapilib.a", "include/okapi/api/chassis/model/skidSteerModel.hpp", "include/okapi/impl/control/util/pidTunerFactory.hpp", "include/okapi/api/units/QSpeed.hpp", "include/okapi/api/units/QAngularJerk.hpp", "include/okapi/api/chassis/model/chassisModel.hpp", "include/okapi/api/control/offsettableControllerInput.hpp", "include/okapi/api/units/QArea.hpp", "include/okapi/api/filter/filteredControllerInput.hpp", "include/okapi/api/control/iterative/iterativeVelocityController.hpp", "include/okapi/impl/util/timer.hpp", "include/okapi/pathfinder/include/pathfinder/mathutil.h", "include/okapi/impl/device/distanceSensor.hpp", "include/okapi/api/coreProsAPI.hpp", "include/okapi/api/control/async/asyncPosPidController.hpp", "include/okapi/api/chassis/controller/chassisController.hpp", "include/okapi/api/control/async/asyncVelIntegratedController.hpp", "include/okapi/api/control/closedLoopController.hpp", "include/okapi/api/filter/composableFilter.hpp", "include/okapi/api/chassis/controller/chassisControllerPid.hpp", "include/okapi/impl/control/util/controllerRunnerFactory.hpp", "include/okapi/api/odometry/threeEncoderOdometry.hpp", "include/okapi/impl/device/opticalSensor.hpp", "include/okapi/api/chassis/model/readOnlyChassisModel.hpp", "include/okapi/api/units/QMass.hpp", "include/okapi/impl/device/rotarysensor/integratedEncoder.hpp", "include/okapi/api/filter/demaFilter.hpp", "include/okapi/impl/util/timeUtilFactory.hpp", "include/okapi/impl/device/motor/motor.hpp", "include/okapi/api/control/async/asyncPosIntegratedController.hpp", "include/okapi/api/odometry/odometry.hpp", "include/okapi/api/control/iterative/iterativeVelPidController.hpp", "include/okapi/impl/chassis/controller/chassisControllerBuilder.hpp", "include/okapi/api/odometry/point.hpp", "include/okapi/api/control/util/controllerRunner.hpp", "include/okapi/api/chassis/model/hDriveModel.hpp", "include/okapi/api/control/async/asyncMotionProfileController.hpp", "include/okapi/api/control/async/asyncWrapper.hpp", "include/okapi/impl/device/controller.hpp", "include/okapi/api/control/iterative/iterativeController.hpp", "include/okapi/api/units/QFrequency.hpp", "include/okapi/api/device/button/buttonBase.hpp", "include/okapi/api/control/iterative/iterativePositionController.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/swerve.h", "include/okapi/api/filter/filter.hpp", "include/okapi/api/odometry/odomMath.hpp", "include/okapi/impl/device/rotarysensor/adiEncoder.hpp", "include/okapi/api/util/abstractTimer.hpp", "include/okapi/impl/device/rotarysensor/potentiometer.hpp", "include/okapi/impl/device/button/controllerButton.hpp", "include/okapi/api/filter/ekfFilter.hpp", "include/okapi/api/util/supplier.hpp", "include/okapi/api/units/RQuantity.hpp", "include/okapi/api/units/QForce.hpp", "include/okapi/api/control/controllerOutput.hpp", "include/okapi/impl/device/adiUltrasonic.hpp", "include/okapi/api/units/QVolume.hpp", "include/okapi/pathfinder/include/pathfinder.h", "include/okapi/api/filter/passthroughFilter.hpp", "include/okapi/api/control/controllerInput.hpp", "include/okapi/impl/device/controllerUtil.hpp", "include/okapi/api/chassis/model/threeEncoderXDriveModel.hpp", "include/okapi/api/control/util/flywheelSimulator.hpp", "include/okapi/api/filter/averageFilter.hpp", "include/okapi/api/units/QPressure.hpp", "include/okapi/impl/control/async/asyncPosControllerBuilder.hpp", "include/okapi/api/units/QAngularSpeed.hpp", "include/okapi/impl/device/motor/motorGroup.hpp", "include/okapi/api/chassis/controller/odomChassisController.hpp", "include/okapi/api/chassis/model/xDriveModel.hpp", "include/okapi/api/control/util/settledUtil.hpp", "include/okapi/impl/device/rotarysensor/rotationSensor.hpp"], "target": "v5", "user_files": [], "version": "4.2.0"}}, "upload_options": {"slot": 1, "description": "VEX Team ? Code"}, "project_name": "Pronounce This"}} \ No newline at end of file +{"py/object": "pros.conductor.project.Project", "py/state": {"target": "v5", "templates": {"kernel": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/kernel@3.5.4", "system_files": ["include/display/lv_themes/lv_theme_night.h", "include/display/lv_hal/lv_hal.h", "include/display/lv_themes/lv_theme_templ.h", "include/display/lv_objx/lv_imgbtn.h", "include/display/lv_draw/lv_draw_img.h", "include/display/lv_objx/lv_cont.h", "include/display/lv_draw/lv_draw_arc.h", "include/display/lv_version.h", "include/display/lv_core/lv_style.h", "include/display/lv_objx/lv_ddlist.h", "include/display/lv_objx/lv_mbox.h", "include/display/lv_objx/lv_spinbox.h", "include/display/lv_objx/lv_objx_templ.h", "include/display/lv_objx/lv_line.h", "include/pros/adi.hpp", "include/display/lv_misc/lv_task.h", "include/pros/optical.hpp", "include/pros/serial.h", "include/pros/imu.hpp", "include/display/lv_core/lv_group.h", "include/display/lv_conf.h", "include/pros/vision.hpp", "include/pros/rtos.h", "firmware/libm.a", "firmware/v5.ld", "include/display/lv_objx/lv_bar.h", "include/pros/motors.hpp", "include/display/lv_misc/lv_fs.h", "include/display/lv_misc/lv_templ.h", "include/display/lv_draw/lv_draw_vbasic.h", "include/display/lv_objx/lv_list.h", "include/display/lv_themes/lv_theme.h", "include/display/lv_objx/lv_chart.h", "include/pros/motors.h", "include/display/lv_objx/lv_arc.h", "include/display/lv_core/lv_vdb.h", "include/display/lv_misc/lv_txt.h", "include/display/lvgl.h", "include/display/lv_misc/lv_color.h", "include/display/lv_core/lv_indev.h", "include/display/lv_objx/lv_kb.h", "include/pros/llemu.h", "firmware/v5-common.ld", "include/display/README.md", "include/pros/misc.hpp", "include/display/lv_objx/lv_tabview.h", "include/display/lv_draw/lv_draw_rbasic.h", "common.mk", "include/display/lv_misc/lv_font.h", "include/display/lv_objx/lv_led.h", "include/display/lv_core/lv_obj.h", "include/display/lv_draw/lv_draw_line.h", "include/pros/rtos.hpp", "include/pros/apix.h", "include/display/lv_objx/lv_sw.h", "include/display/lv_misc/lv_ll.h", "include/pros/vision.h", "include/display/lv_objx/lv_ta.h", "include/display/lv_draw/lv_draw_label.h", "include/display/lv_core/lv_refr.h", "include/api.h", "firmware/libpros.a", "firmware/libc.a", "include/pros/ext_adi.h", "include/display/lv_hal/lv_hal.mk", "include/pros/colors.h", "include/pros/distance.h", "include/pros/screen.hpp", "include/pros/distance.hpp", "include/display/lv_themes/lv_theme_alien.h", "include/pros/gps.h", "include/display/licence.txt", "include/display/lv_misc/lv_gc.h", "include/display/lv_objx/lv_btnm.h", "include/display/lv_objx/lv_page.h", "include/pros/gps.hpp", "include/pros/llemu.hpp", "include/display/lv_hal/lv_hal_disp.h", "include/display/lv_misc/lv_circ.h", "include/display/lv_objx/lv_btn.h", "include/display/lv_misc/lv_anim.h", "include/display/lv_draw/lv_draw.mk", "include/display/lv_core/lv_lang.h", "include/pros/api_legacy.h", "include/display/lv_themes/lv_theme_nemo.h", "include/display/lv_misc/lv_math.h", "include/display/lv_misc/lv_symbol_def.h", "include/display/lv_draw/lv_draw_rect.h", "include/display/lv_misc/lv_mem.h", "include/display/lv_conf_checker.h", "include/display/lv_fonts/lv_font_builtin.h", "include/display/lv_objx/lv_table.h", "include/pros/rotation.hpp", "include/display/lv_themes/lv_theme_default.h", "include/display/lv_core/lv_core.mk", "include/pros/screen.h", "include/display/lv_draw/lv_draw_triangle.h", "include/display/lv_objx/lv_lmeter.h", "include/display/lv_hal/lv_hal_indev.h", "include/display/lv_objx/lv_objx.mk", "include/display/lv_objx/lv_win.h", "include/display/lv_themes/lv_theme_zen.h", "include/pros/misc.h", "include/display/lv_objx/lv_img.h", "include/display/lv_themes/lv_theme_mono.h", "include/display/lv_hal/lv_hal_tick.h", "include/display/lv_fonts/lv_fonts.mk", "include/pros/optical.h", "include/display/lv_objx/lv_gauge.h", "include/display/lv_misc/lv_ufs.h", "include/display/lv_misc/lv_log.h", "include/display/lv_objx/lv_canvas.h", "include/display/lv_objx/lv_calendar.h", "include/pros/adi.h", "include/display/lv_themes/lv_theme_material.h", "include/display/lv_draw/lv_draw.h", "include/display/lv_misc/lv_misc.mk", "include/display/lv_objx/lv_slider.h", "include/display/lv_objx/lv_cb.h", "include/pros/imu.h", "include/display/lv_objx/lv_label.h", "include/display/lv_objx/lv_roller.h", "include/pros/serial.hpp", "firmware/v5-hot.ld", "include/display/lv_misc/lv_area.h", "include/pros/rotation.h", "include/display/lv_objx/lv_tileview.h", "include/display/lv_objx/lv_preload.h", "include/display/lv_themes/lv_themes.mk"], "user_files": ["Makefile", "src/main.c", "src/main.cc", "include/main.hpp", "include/main.hh", "src/main.cpp", "include/main.h", ".gitignore"], "name": "kernel", "version": "3.5.4", "supported_kernels": null, "target": "v5", "metadata": {"cold_addr": "58720256", "cold_output": "bin/cold.package.bin", "hot_addr": "125829120", "hot_output": "bin/hot.package.bin", "output": "bin/monolith.bin", "origin": "pros-mainline"}}, "okapilib": {"py/object": "pros.conductor.templates.local_template.LocalTemplate", "location": "/home/alex/.config/pros/templates/okapilib@4.2.0", "metadata": {"origin": "pros-mainline"}, "name": "okapilib", "supported_kernels": "^3.3.1", "system_files": ["include/okapi/impl/filter/velMathFactory.hpp", "include/okapi/api/odometry/twoEncoderOdometry.hpp", "include/okapi/api/control/util/pathfinderUtil.hpp", "include/okapi/impl/device/rotarysensor/adiGyro.hpp", "include/okapi/pathfinder/include/pathfinder/spline.h", "include/okapi/api/units/QAngularAcceleration.hpp", "include/okapi/pathfinder/include/pathfinder/trajectory.h", "include/okapi/api/control/iterative/iterativePosPidController.hpp", "include/okapi/pathfinder/include/pathfinder/io.h", "include/okapi/api/control/async/asyncController.hpp", "include/okapi/api/util/timeUtil.hpp", "include/okapi/api/control/async/asyncVelocityController.hpp", "include/okapi/pathfinder/include/pathfinder/fit.h", "include/okapi/api/filter/medianFilter.hpp", "include/okapi/api/chassis/model/threeEncoderSkidSteerModel.hpp", "include/okapi/api/device/motor/abstractMotor.hpp", "include/okapi/pathfinder/include/pathfinder/structs.h", "include/okapi/api/units/QAngle.hpp", "include/okapi/api/control/async/asyncPositionController.hpp", "include/okapi/pathfinder/include/pathfinder/lib.h", "include/okapi/impl/control/iterative/iterativeControllerFactory.hpp", "include/okapi/impl/device/rotarysensor/IMU.hpp", "include/okapi/pathfinder/include/pathfinder/followers/encoder.h", "include/okapi/impl/control/async/asyncVelControllerBuilder.hpp", "include/okapi/api/control/util/pidTuner.hpp", "include/okapi/api/units/QAcceleration.hpp", "include/okapi/impl/device/motor/adiMotor.hpp", "include/okapi/impl/util/rate.hpp", "include/okapi/api/filter/velMath.hpp", "include/okapi/api.hpp", "include/okapi/api/units/QJerk.hpp", "include/okapi/api/odometry/stateMode.hpp", "include/okapi/api/util/mathUtil.hpp", "include/okapi/api/control/async/asyncVelPidController.hpp", "include/okapi/impl/control/async/asyncMotionProfileControllerBuilder.hpp", "include/okapi/api/units/QLength.hpp", "include/okapi/pathfinder/include/pathfinder/followers/distance.h", "include/okapi/api/chassis/controller/defaultOdomChassisController.hpp", "include/okapi/api/util/logging.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/tank.h", "include/okapi/api/odometry/odomState.hpp", "include/okapi/api/device/rotarysensor/rotarySensor.hpp", "include/okapi/api/device/rotarysensor/continuousRotarySensor.hpp", "include/okapi/api/chassis/controller/chassisScales.hpp", "include/okapi/api/units/QTime.hpp", "include/okapi/api/control/async/asyncLinearMotionProfileController.hpp", "include/okapi/api/units/QTorque.hpp", "include/okapi/api/device/button/abstractButton.hpp", "include/okapi/impl/util/configurableTimeUtilFactory.hpp", "include/okapi/impl/device/button/adiButton.hpp", "include/okapi/api/chassis/controller/chassisControllerIntegrated.hpp", "include/okapi/api/control/iterative/iterativeMotorVelocityController.hpp", "include/okapi/api/filter/emaFilter.hpp", "include/okapi/api/util/abstractRate.hpp", "firmware/okapilib.a", "include/okapi/api/chassis/model/skidSteerModel.hpp", "include/okapi/impl/control/util/pidTunerFactory.hpp", "include/okapi/api/units/QSpeed.hpp", "include/okapi/api/units/QAngularJerk.hpp", "include/okapi/api/chassis/model/chassisModel.hpp", "include/okapi/api/control/offsettableControllerInput.hpp", "include/okapi/api/units/QArea.hpp", "include/okapi/api/filter/filteredControllerInput.hpp", "include/okapi/api/control/iterative/iterativeVelocityController.hpp", "include/okapi/impl/util/timer.hpp", "include/okapi/pathfinder/include/pathfinder/mathutil.h", "include/okapi/impl/device/distanceSensor.hpp", "include/okapi/api/coreProsAPI.hpp", "include/okapi/api/control/async/asyncPosPidController.hpp", "include/okapi/api/chassis/controller/chassisController.hpp", "include/okapi/api/control/async/asyncVelIntegratedController.hpp", "include/okapi/api/control/closedLoopController.hpp", "include/okapi/api/filter/composableFilter.hpp", "include/okapi/api/chassis/controller/chassisControllerPid.hpp", "include/okapi/impl/control/util/controllerRunnerFactory.hpp", "include/okapi/api/odometry/threeEncoderOdometry.hpp", "include/okapi/impl/device/opticalSensor.hpp", "include/okapi/api/chassis/model/readOnlyChassisModel.hpp", "include/okapi/api/units/QMass.hpp", "include/okapi/impl/device/rotarysensor/integratedEncoder.hpp", "include/okapi/api/filter/demaFilter.hpp", "include/okapi/impl/util/timeUtilFactory.hpp", "include/okapi/impl/device/motor/motor.hpp", "include/okapi/api/control/async/asyncPosIntegratedController.hpp", "include/okapi/api/odometry/odometry.hpp", "include/okapi/api/control/iterative/iterativeVelPidController.hpp", "include/okapi/impl/chassis/controller/chassisControllerBuilder.hpp", "include/okapi/api/odometry/point.hpp", "include/okapi/api/control/util/controllerRunner.hpp", "include/okapi/api/chassis/model/hDriveModel.hpp", "include/okapi/api/control/async/asyncMotionProfileController.hpp", "include/okapi/api/control/async/asyncWrapper.hpp", "include/okapi/impl/device/controller.hpp", "include/okapi/api/control/iterative/iterativeController.hpp", "include/okapi/api/units/QFrequency.hpp", "include/okapi/api/device/button/buttonBase.hpp", "include/okapi/api/control/iterative/iterativePositionController.hpp", "include/okapi/pathfinder/include/pathfinder/modifiers/swerve.h", "include/okapi/api/filter/filter.hpp", "include/okapi/api/odometry/odomMath.hpp", "include/okapi/impl/device/rotarysensor/adiEncoder.hpp", "include/okapi/api/util/abstractTimer.hpp", "include/okapi/impl/device/rotarysensor/potentiometer.hpp", "include/okapi/impl/device/button/controllerButton.hpp", "include/okapi/api/filter/ekfFilter.hpp", "include/okapi/api/util/supplier.hpp", "include/okapi/api/units/RQuantity.hpp", "include/okapi/api/units/QForce.hpp", "include/okapi/api/control/controllerOutput.hpp", "include/okapi/impl/device/adiUltrasonic.hpp", "include/okapi/api/units/QVolume.hpp", "include/okapi/pathfinder/include/pathfinder.h", "include/okapi/api/filter/passthroughFilter.hpp", "include/okapi/api/control/controllerInput.hpp", "include/okapi/impl/device/controllerUtil.hpp", "include/okapi/api/chassis/model/threeEncoderXDriveModel.hpp", "include/okapi/api/control/util/flywheelSimulator.hpp", "include/okapi/api/filter/averageFilter.hpp", "include/okapi/api/units/QPressure.hpp", "include/okapi/impl/control/async/asyncPosControllerBuilder.hpp", "include/okapi/api/units/QAngularSpeed.hpp", "include/okapi/impl/device/motor/motorGroup.hpp", "include/okapi/api/chassis/controller/odomChassisController.hpp", "include/okapi/api/chassis/model/xDriveModel.hpp", "include/okapi/api/control/util/settledUtil.hpp", "include/okapi/impl/device/rotarysensor/rotationSensor.hpp"], "target": "v5", "user_files": [], "version": "4.2.0"}}, "upload_options": {"slot": 1, "description": "VEX Team ? Code"}, "project_name": "Pronounce This"}} \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index c6ccd7f8..f1e80a0b 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -7,20 +7,18 @@ Pronounce::Controller master(pros::E_CONTROLLER_MASTER); // Motors // Drive Motors -pros::Motor frontLeftMotor(1); -pros::Motor frontRightMotor(2, true); -pros::Motor backLeftMotor(9); -pros::Motor backRightMotor(10, true); +pros::Motor frontLeftMotor(1, true); +pros::Motor frontRightMotor(2); +pros::Motor backLeftMotor(9, true); +pros::Motor backRightMotor(10); -pros::Motor rightLift(3, true); -pros::Motor leftLift(4, false); +pros::Motor lift(3, false); -pros::Motor intake(11); - -pros::Motor backGrabber(6); +pros::Motor intake(11, true); pros::ADIDigitalOut frontGrabber(1, false); -pros::ADIDigitalIn frontGrabberBumperSwitch(2); +pros::ADIDigitalOut backGrabber(2, false); +pros::ADIDigitalIn frontGrabberBumperSwitch(3); // Inertial Measurement Unit pros::Imu imu(5); @@ -40,11 +38,10 @@ MecanumDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, Pronounce::PurePursuit purePursuit(&drivetrain, 10); -MotorButton leftLiftButton(&master, &leftLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); -MotorButton rightLiftButton(&master, &rightLift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); -MotorButton backGrabberButton(&master, &backGrabber, DIGITAL_R1, DIGITAL_R1, 200, 200, 200, 0, 450 * 3); +MotorButton liftButton(&master, &lift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); MotorButton intakeButton(&master, &intake, DIGITAL_R2, DIGITAL_R2, 200, 0, 0, 0, 0); +SolenoidButton backGrabberButton(&master, DIGITAL_R1, DIGITAL_R1); SolenoidButton frontGrabberButton(&master, DIGITAL_A, DIGITAL_B); // Autonomous Selector @@ -100,10 +97,9 @@ int preAutonRun() { frontGrabberButton.setAutonomous(true); backGrabberButton.setAutonomous(true); - leftLiftButton.setAutonomous(true); - rightLiftButton.setAutonomous(true); - backGrabberButton.setAutonomousButton(true); - intakeButton.setAutonomousButton(true); + liftButton.setAutonomous(true); + backGrabberButton.setAutonomous(true); + intakeButton.setAutonomous(true); return 0; } @@ -129,8 +125,7 @@ int rightStealRight() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(200); - leftLiftButton.setAutonomousAuthority(360); - rightLiftButton.setAutonomousAuthority(360); + liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(rightNeutralToMidNeutralIndex); purePursuit.setFollowing(true); @@ -170,8 +165,7 @@ int rightAwpRight() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(200); - leftLiftButton.setAutonomousAuthority(360); - rightLiftButton.setAutonomousAuthority(360); + liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(rightAllianceToRightHomeZoneIndex); purePursuit.setFollowing(true); @@ -201,8 +195,7 @@ int leftAwpLeft() { frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(200); - leftLiftButton.setAutonomousAuthority(360); - rightLiftButton.setAutonomousAuthority(360); + liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(leftNeutralToMidNeutralIndex); purePursuit.setFollowing(true); @@ -250,8 +243,7 @@ int skills() { purePursuit.setFollowing(true); purePursuit.setTurnTarget(0); - leftLiftButton.setAutonomousAuthority(1500); - rightLiftButton.setAutonomousAuthority(1500); + liftButton.setAutonomousAuthority(1500); // Wait until it is done while (!purePursuit.isDone(0.5)) { @@ -260,8 +252,7 @@ int skills() { frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); - leftLiftButton.setAutonomousAuthority(0); - rightLiftButton.setAutonomousAuthority(0); + liftButton.setAutonomousAuthority(0); purePursuit.setCurrentPathIndex(farPlatformToNearPlatformIndex); purePursuit.setFollowing(true); @@ -275,8 +266,7 @@ int skills() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); - leftLiftButton.setAutonomousAuthority(1500); - rightLiftButton.setAutonomousAuthority(1500); + liftButton.setAutonomousAuthority(1500); // Wait until done while (!purePursuit.isDone(0.5)) { @@ -285,8 +275,7 @@ int skills() { frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); - leftLiftButton.setAutonomousAuthority(0); - rightLiftButton.setAutonomousAuthority(0); + liftButton.setAutonomousAuthority(0); purePursuit.setCurrentPathIndex(nearPlatformViaLeftNeutralToFarPlatformIndex); purePursuit.setFollowing(true); @@ -300,8 +289,7 @@ int skills() { // Collect front goal frontGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); - leftLiftButton.setAutonomousAuthority(1500); - rightLiftButton.setAutonomousAuthority(1500); + liftButton.setAutonomousAuthority(1500); // Wait until done while (!purePursuit.isDone(0.5)) { @@ -310,8 +298,7 @@ int skills() { frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); - leftLiftButton.setAutonomousAuthority(0); - rightLiftButton.setAutonomousAuthority(0); + liftButton.setAutonomousAuthority(0); purePursuit.setCurrentPathIndex(nearPlatformToMidIndex); purePursuit.setFollowing(true); @@ -348,8 +335,7 @@ int postAuton() { purePursuit.setEnabled(false); frontGrabberButton.setAutonomous(false); backGrabberButton.setAutonomous(false); - leftLiftButton.setAutonomous(false); - rightLiftButton.setAutonomous(false); + liftButton.setAutonomous(false); intakeButton.setAutonomous(false); return 0; @@ -392,8 +378,7 @@ void updateMotors() { while (1) { frontGrabberButton.update(); backGrabberButton.update(); - leftLiftButton.update(); - rightLiftButton.update(); + liftButton.update(); intakeButton.update(); pros::Task::delay(20); @@ -409,16 +394,14 @@ void initMotors() { frontRightMotor.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_COAST); backLeftMotor.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_COAST); backRightMotor.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_COAST); - backGrabber.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); - leftLift.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); - rightLift.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); - - backGrabberButton.setSingleToggle(true); - backGrabberButton.setGoToImmediately(true); + lift.set_brake_mode(pros::motor_brake_mode_e::E_MOTOR_BRAKE_HOLD); frontGrabberButton.setSolenoid(&frontGrabber); frontGrabberButton.setSingleToggle(true); + backGrabberButton.setSolenoid(&backGrabber); + backGrabberButton.setSingleToggle(true); + intakeButton.setSingleToggle(true); pros::Task updateButtons(updateMotors, "Update buttons"); @@ -733,7 +716,7 @@ void opcontrol() { leftY = leftYAvg.getAverage(); rightX = rightXAvg.getAverage(); - Vector driveVector = Vector(new Pronounce::Point(leftX, leftY)); + Vector driveVector = Vector(new Pronounce::Point(0, leftY)); if (driverMode == 1) { driveVector.setAngle(driveVector.getAngle()); } @@ -749,7 +732,7 @@ void opcontrol() { int leftY = filterAxis(master, ANALOG_LEFT_Y); int rightY = filterAxis(master, ANALOG_RIGHT_Y); - drivetrain.setDriveVectorVelocity(Vector(new Pronounce::Point(leftX, (leftY + rightY) / 2)), leftY - rightY); + drivetrain.setDriveVectorVelocity(Vector(new Pronounce::Point(0, (leftY + rightY) / 2)), leftY - rightY); } if (frontGrabberBumperSwitch.get_new_press()) { From 5172096757e456a155d6f073515099bf1f23324e Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Mon, 27 Dec 2021 13:30:10 -0700 Subject: [PATCH 08/21] Add new robot controls --- src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main.cpp b/src/main.cpp index f1e80a0b..9d169ed8 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -732,7 +732,7 @@ void opcontrol() { int leftY = filterAxis(master, ANALOG_LEFT_Y); int rightY = filterAxis(master, ANALOG_RIGHT_Y); - drivetrain.setDriveVectorVelocity(Vector(new Pronounce::Point(0, (leftY + rightY) / 2)), leftY - rightY); + drivetrain.setDriveVectorVelocity(Vector(new Pronounce::Point(0, (leftY + rightY))), leftY - rightY); } if (frontGrabberBumperSwitch.get_new_press()) { From 3da48804bb99dd6a1ec65392742f707a2d9ebe4a Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Mon, 27 Dec 2021 14:28:03 -0700 Subject: [PATCH 09/21] Working --- include/chassis/drivetrain.hpp | 2 +- include/chassis/tankDrive.hpp | 11 +++++++++-- include/utils/motorGroup.hpp | 1 - src/chassis/drivetrain.cpp | 10 ++++++++-- src/chassis/tankDrive.cpp | 10 ---------- src/main.cpp | 2 ++ src/utils/motorGroup.cpp | 17 +---------------- 7 files changed, 21 insertions(+), 32 deletions(-) diff --git a/include/chassis/drivetrain.hpp b/include/chassis/drivetrain.hpp index 303cf9c8..9b389e9b 100644 --- a/include/chassis/drivetrain.hpp +++ b/include/chassis/drivetrain.hpp @@ -40,7 +40,7 @@ namespace Pronounce { } MotorGroup getRightMotors() { - return leftMotors; + return rightMotors; } void setRightMotors(MotorGroup rightMotors) { diff --git a/include/chassis/tankDrive.hpp b/include/chassis/tankDrive.hpp index 3cb5ed73..fed9a193 100644 --- a/include/chassis/tankDrive.hpp +++ b/include/chassis/tankDrive.hpp @@ -12,9 +12,16 @@ namespace Pronounce { TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth); - void skidSteerVelocity(double speed, double turn); + void skidSteerVelocity(double speed, double turn) { + this->getLeftMotors().move_velocity(speed - turn * this->trackWidth / 2); + this->getRightMotors().move_velocity(speed + turn * this->trackWidth / 2); + } - void tankSteerVelocity(double leftSpeed, double rightSpeed); + void tankSteerVelocity(double leftSpeed, double rightSpeed) { + printf("leftSpeed: %f, leftSpeed: %f \n", leftSpeed, rightSpeed); + this->getLeftMotors().move_velocity(leftSpeed); + this->getRightMotors().move_velocity(rightSpeed); + } double getTrackWidth() { return this->trackWidth; diff --git a/include/utils/motorGroup.hpp b/include/utils/motorGroup.hpp index f2631e2d..9b2d6018 100644 --- a/include/utils/motorGroup.hpp +++ b/include/utils/motorGroup.hpp @@ -10,7 +10,6 @@ namespace Pronounce { public: MotorGroup(); MotorGroup(std::vector motors); - MotorGroup(pros::Motor* motors ...); void operator=(std::int32_t power) { for (int i = 0; i < motors.size(); i++) { diff --git a/src/chassis/drivetrain.cpp b/src/chassis/drivetrain.cpp index 57c924d5..1e4c5284 100644 --- a/src/chassis/drivetrain.cpp +++ b/src/chassis/drivetrain.cpp @@ -3,8 +3,14 @@ namespace Pronounce { Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) { - this->leftMotors = MotorGroup(frontLeft, backLeft); - this->rightMotors = MotorGroup(frontRight, backRight); + std::vector leftMotors; + std::vector rightMotors; + leftMotors.emplace_back(frontLeft); + leftMotors.emplace_back(backLeft); + rightMotors.emplace_back(frontRight); + rightMotors.emplace_back(backRight); + this->leftMotors = MotorGroup(leftMotors); + this->rightMotors = MotorGroup(rightMotors); this->imu = imu; } diff --git a/src/chassis/tankDrive.cpp b/src/chassis/tankDrive.cpp index 1443abc3..bf3bfec3 100644 --- a/src/chassis/tankDrive.cpp +++ b/src/chassis/tankDrive.cpp @@ -9,16 +9,6 @@ namespace Pronounce { this->trackWidth = trackWidth; } - void TankDrivetrain::skidSteerVelocity(double speed, double turn) { - this->getLeftMotors().move_velocity(speed - turn * this->trackWidth / 2); - this->getRightMotors().move_velocity(speed + turn * this->trackWidth / 2); - } - - void TankDrivetrain::tankSteerVelocity(double leftSpeed, double rightSpeed) { - this->getLeftMotors().move_velocity(leftSpeed); - this->getRightMotors().move_velocity(rightSpeed); - } - TankDrivetrain::~TankDrivetrain() { } } // namespace Pronounce diff --git a/src/main.cpp b/src/main.cpp index 2d594c39..0e483d74 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -700,6 +700,8 @@ void opcontrol() { int leftY = filterAxis(master, ANALOG_LEFT_Y); int rightY = filterAxis(master, ANALOG_RIGHT_Y); + printf("leftY: %d, rightY: %d \n", leftY, rightY); + drivetrain.tankSteerVelocity(leftY, rightY); } diff --git a/src/utils/motorGroup.cpp b/src/utils/motorGroup.cpp index 0f6ceb83..67ad6289 100644 --- a/src/utils/motorGroup.cpp +++ b/src/utils/motorGroup.cpp @@ -8,23 +8,8 @@ namespace Pronounce { MotorGroup::MotorGroup(std::vector motors) { this->motors = motors; } - - MotorGroup::MotorGroup(pros::Motor* motors ...) { - this->motors = std::vector(); - this->motors.push_back(motors); - va_list args; - va_start(args, motors); - pros::Motor* m = va_arg(args, pros::Motor*); - while (m != NULL) { - this->motors.push_back(m); - m = va_arg(args, pros::Motor*); - } - va_end(args); - } MotorGroup::~MotorGroup() { - for (int i = 0; i < motors.size(); i++) { - delete motors[i]; - } + } } // namespace Pronounce From 6004fadab8c42a3e45bee980d2df83db3c792ce5 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Tue, 28 Dec 2021 14:57:45 -0700 Subject: [PATCH 10/21] Add autoPaths file to reduce cluter in main.cpp --- include/autoPaths.hpp | 157 +++++++++++++++++++++++++++++++++++++++ include/main.h | 1 + src/main.cpp | 166 +++++------------------------------------- 3 files changed, 178 insertions(+), 146 deletions(-) create mode 100644 include/autoPaths.hpp diff --git a/include/autoPaths.hpp b/include/autoPaths.hpp new file mode 100644 index 00000000..52ec17a6 --- /dev/null +++ b/include/autoPaths.hpp @@ -0,0 +1,157 @@ +#pragma once + +#include "utils/pointUtil.hpp" +#include "utils/path.hpp" +#include "utils/splinePath.hpp" +#include "motionControl/purePursuit.hpp" +#include "utils/purePursuitProfile.hpp" +#include "utils/purePursuitProfileManager.hpp" + +namespace Pronounce { + + // Test path + int testPathIndex; + + // Right steal right + int rightHomeToGoalNeutralIndex; + int rightNeutralToMidNeutralIndex; + int midNeutralToRightAllianceIndex; + int midNeutralToMidHomeZoneIndex; + int rightNeutralToRightHomeIndex; + + // Right awp right + int farRightHomeZoneToRightAllianceIndex; + int rightAllianceToRightHomeZoneIndex; + + // Left steal left + int leftAllianceToLeftNeutralIndex; + int leftNeutralToMidNeutralIndex; + int midNeutralToLeftHomeZoneIndex; + + // Skills + int rightNeutralToFarPlatformIndex; + int farPlatformToNearPlatformIndex; + int nearPlatformViaLeftNeutralToFarPlatformIndex; + int nearPlatformToMidIndex; + + void autoPaths(PurePursuit purePursuit) { + // Default pure pursuit profile + PurePursuitProfile defaultProfile(new PID(20, 0.0, 2.0), new PID(60.0, 0.0, 5.0), 10.0); + purePursuit.getPurePursuitProfileManager().setDefaultProfile(defaultProfile); + + // Test path + Path testPath = Path(); + + testPath.addPoint(0, 0); + testPath.addPoint(24, 0); + testPath.addPoint(24, 24); + testPath.addPoint(24, 48); + testPath.addPoint(-24, 48); + testPath.addPoint(0, 24); + + testPathIndex = purePursuit.addPath(testPath); + + Path rightNeutralToRightHomeZone; + + rightNeutralToRightHomeZone.addPoint(105.7, 60); + rightNeutralToRightHomeZone.addPoint(105.7, 16); + + rightNeutralToRightHomeIndex = purePursuit.addPath(rightNeutralToRightHomeZone); + + // Right Steal Right + Path rightHomeToGoalNeutral; + + rightHomeToGoalNeutral.addPoint(105.7, 16); + rightHomeToGoalNeutral.addPoint(105.7, 61); + + rightHomeToGoalNeutralIndex = purePursuit.addPath(rightHomeToGoalNeutral); + + Path rightNeutralToMidNeutral; + + rightNeutralToMidNeutral.addPoint(105.7, 62); + rightNeutralToMidNeutral.addPoint(75.3, 40); + rightNeutralToMidNeutral.addPoint(60.3, 65); + + rightNeutralToMidNeutralIndex = purePursuit.addPath(rightNeutralToMidNeutral); + + Path midNeutralToRightAlliance; + + midNeutralToRightAlliance.addPoint(70.3, 65); + midNeutralToRightAlliance.addPoint(120.1, 28); + + midNeutralToRightAllianceIndex = purePursuit.addPath(midNeutralToRightAlliance); + + Path midNeutralToMidHomeZone; + + midNeutralToMidHomeZone.addPoint(70.3, 70.3); + midNeutralToMidHomeZone.addPoint(70.3, 36); + + midNeutralToMidHomeZoneIndex = purePursuit.addPath(midNeutralToMidHomeZone); + + Path farRightHomeZoneToRightAlliance; + + farRightHomeZoneToRightAlliance.addPoint(127.9, 16); + farRightHomeZoneToRightAlliance.addPoint(127.9, 24); + + farRightHomeZoneToRightAllianceIndex = purePursuit.addPath(farRightHomeZoneToRightAlliance); + + Path rightAllianceToRightHomeZone; + + rightAllianceToRightHomeZone.addPoint(127.9, 24); + rightAllianceToRightHomeZone.addPoint(105.7, 16); + + rightAllianceToRightHomeZoneIndex = purePursuit.addPath(rightAllianceToRightHomeZone); + + Path leftAllianceToLeftNeutral; + + leftAllianceToLeftNeutral.addPoint(29, 11.4); + leftAllianceToLeftNeutral.addPoint(32, 67); + + leftAllianceToLeftNeutralIndex = purePursuit.addPath(leftAllianceToLeftNeutral); + + Path leftNeutralToMidNeutral; + + leftNeutralToMidNeutral.addPoint(32, 67); + leftNeutralToMidNeutral.addPoint(65.3, 40); + leftNeutralToMidNeutral.addPoint(70.3, 65); + + leftNeutralToMidNeutralIndex = purePursuit.addPath(leftNeutralToMidNeutral); + + // mid neutral to mid home zone + + Path rightNeutralToFarPlatform; + + rightNeutralToFarPlatform.addPoint(105.7, 61); + rightNeutralToFarPlatform.addPoint(75, 76.5); + rightNeutralToFarPlatform.addPoint(75, 100); + rightNeutralToFarPlatform.addPoint(60.3, 115); + + rightNeutralToFarPlatformIndex = purePursuit.addPath(rightNeutralToFarPlatform); + + Path farPlatformToNearPlatform; + + farPlatformToNearPlatform.addPoint(70.3, 107); + farPlatformToNearPlatform.addPoint(60, 70.3); + farPlatformToNearPlatform.addPoint(58.6, 64.1); + farPlatformToNearPlatform.addPoint(58.6, 45); + farPlatformToNearPlatform.addPoint(70.3, 30.7); + + farPlatformToNearPlatformIndex = purePursuit.addPath(farPlatformToNearPlatform); + + Path nearPlatformViaLeftNeutralToFarPlatform; + + nearPlatformViaLeftNeutralToFarPlatform.addPoint(70.3, 30.7); + nearPlatformViaLeftNeutralToFarPlatform.addPoint(35, 61); + nearPlatformViaLeftNeutralToFarPlatform.addPoint(70.3, 115); + + nearPlatformViaLeftNeutralToFarPlatformIndex = purePursuit.addPath(nearPlatformViaLeftNeutralToFarPlatform); + + Path nearPlatformToMid; + + nearPlatformToMid.addPoint(70.3, 115); + nearPlatformToMid.addPoint(70.3, 70.3); + + nearPlatformToMidIndex = purePursuit.addPath(nearPlatformToMid); + } + +} // Namespace Prononce diff --git a/include/main.h b/include/main.h index d2e3c5eb..47978fd9 100644 --- a/include/main.h +++ b/include/main.h @@ -47,6 +47,7 @@ * User defined imports */ +#include "autoPaths.hpp" #include "defines.h" // Auton diff --git a/src/main.cpp b/src/main.cpp index 70f7020c..ff184692 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -53,30 +53,7 @@ bool preDriverTasksDone = false; int driverMode = 0; -// Test path -int testPathIndex; - -// Right steal right -int rightHomeToGoalNeutralIndex; -int rightNeutralToMidNeutralIndex; -int midNeutralToRightAllianceIndex; -int midNeutralToMidHomeZoneIndex; -int rightNeutralToRightHomeIndex; - -// Right awp right -int farRightHomeZoneToRightAllianceIndex; -int rightAllianceToRightHomeZoneIndex; - -// Left steal left -int leftAllianceToLeftNeutralIndex; -int leftNeutralToMidNeutralIndex; -int midNeutralToLeftHomeZoneIndex; - -// Skills -int rightNeutralToFarPlatformIndex; -int farPlatformToNearPlatformIndex; -int nearPlatformViaLeftNeutralToFarPlatformIndex; -int nearPlatformToMidIndex; +// SECTION Auton /** * @brief Runs during auton period before auton @@ -336,7 +313,9 @@ int postAuton() { return 0; } +// !SECTION +// SECTION INIT /** * Render thread to update items on the controller */ @@ -466,6 +445,7 @@ void initSelector() { * Initialize the logger for data collection after the match */ void initLogger() { + Logger::setDefaultLogger( std::make_shared( TimeUtilFactory::createDefault().getTimer(), @@ -476,127 +456,6 @@ void initLogger() { Logger::getDefaultLogger()->debug("LOGGER: Logger initialized"); } -void autoPaths() { - // Default pure pursuit profile - PurePursuitProfile defaultProfile(new PID(20, 0.0, 2.0), new PID(60.0, 0.0, 5.0), 10.0); - purePursuit.getPurePursuitProfileManager().setDefaultProfile(defaultProfile); - - // Test path - Path testPath = Path(); - - testPath.addPoint(0, 0); - testPath.addPoint(24, 0); - testPath.addPoint(24, 24); - testPath.addPoint(24, 48); - testPath.addPoint(-24, 48); - testPath.addPoint(0, 24); - - testPathIndex = purePursuit.addPath(testPath); - - Path rightNeutralToRightHomeZone; - - rightNeutralToRightHomeZone.addPoint(105.7, 60); - rightNeutralToRightHomeZone.addPoint(105.7, 16); - - rightNeutralToRightHomeIndex = purePursuit.addPath(rightNeutralToRightHomeZone); - - // Right Steal Right - Path rightHomeToGoalNeutral; - - rightHomeToGoalNeutral.addPoint(105.7, 16); - rightHomeToGoalNeutral.addPoint(105.7, 61); - - rightHomeToGoalNeutralIndex = purePursuit.addPath(rightHomeToGoalNeutral); - - Path rightNeutralToMidNeutral; - - rightNeutralToMidNeutral.addPoint(105.7, 62); - rightNeutralToMidNeutral.addPoint(75.3, 40); - rightNeutralToMidNeutral.addPoint(60.3, 65); - - rightNeutralToMidNeutralIndex = purePursuit.addPath(rightNeutralToMidNeutral); - - Path midNeutralToRightAlliance; - - midNeutralToRightAlliance.addPoint(70.3, 65); - midNeutralToRightAlliance.addPoint(120.1, 28); - - midNeutralToRightAllianceIndex = purePursuit.addPath(midNeutralToRightAlliance); - - Path midNeutralToMidHomeZone; - - midNeutralToMidHomeZone.addPoint(70.3, 70.3); - midNeutralToMidHomeZone.addPoint(70.3, 36); - - midNeutralToMidHomeZoneIndex = purePursuit.addPath(midNeutralToMidHomeZone); - - Path farRightHomeZoneToRightAlliance; - - farRightHomeZoneToRightAlliance.addPoint(127.9, 16); - farRightHomeZoneToRightAlliance.addPoint(127.9, 24); - - farRightHomeZoneToRightAllianceIndex = purePursuit.addPath(farRightHomeZoneToRightAlliance); - - Path rightAllianceToRightHomeZone; - - rightAllianceToRightHomeZone.addPoint(127.9, 24); - rightAllianceToRightHomeZone.addPoint(105.7, 16); - - rightAllianceToRightHomeZoneIndex = purePursuit.addPath(rightAllianceToRightHomeZone); - - Path leftAllianceToLeftNeutral; - - leftAllianceToLeftNeutral.addPoint(29, 11.4); - leftAllianceToLeftNeutral.addPoint(32, 67); - - leftAllianceToLeftNeutralIndex = purePursuit.addPath(leftAllianceToLeftNeutral); - - Path leftNeutralToMidNeutral; - - leftNeutralToMidNeutral.addPoint(32, 67); - leftNeutralToMidNeutral.addPoint(65.3, 40); - leftNeutralToMidNeutral.addPoint(70.3, 65); - - leftNeutralToMidNeutralIndex = purePursuit.addPath(leftNeutralToMidNeutral); - - // mid neutral to mid home zone - - Path rightNeutralToFarPlatform; - - rightNeutralToFarPlatform.addPoint(105.7, 61); - rightNeutralToFarPlatform.addPoint(75, 76.5); - rightNeutralToFarPlatform.addPoint(75, 100); - rightNeutralToFarPlatform.addPoint(60.3, 115); - - rightNeutralToFarPlatformIndex = purePursuit.addPath(rightNeutralToFarPlatform); - - Path farPlatformToNearPlatform; - - farPlatformToNearPlatform.addPoint(70.3, 107); - farPlatformToNearPlatform.addPoint(60, 70.3); - farPlatformToNearPlatform.addPoint(58.6, 64.1); - farPlatformToNearPlatform.addPoint(58.6, 45); - farPlatformToNearPlatform.addPoint(70.3, 30.7); - - farPlatformToNearPlatformIndex = purePursuit.addPath(farPlatformToNearPlatform); - - Path nearPlatformViaLeftNeutralToFarPlatform; - - nearPlatformViaLeftNeutralToFarPlatform.addPoint(70.3, 30.7); - nearPlatformViaLeftNeutralToFarPlatform.addPoint(35, 61); - nearPlatformViaLeftNeutralToFarPlatform.addPoint(70.3, 115); - - nearPlatformViaLeftNeutralToFarPlatformIndex = purePursuit.addPath(nearPlatformViaLeftNeutralToFarPlatform); - - Path nearPlatformToMid; - - nearPlatformToMid.addPoint(70.3, 115); - nearPlatformToMid.addPoint(70.3, 70.3); - - nearPlatformToMidIndex = purePursuit.addPath(nearPlatformToMid); - -} - /** * Filter and apply the quadratic function. */ @@ -628,12 +487,14 @@ void initialize() { initSensors(); initMotors(); initDrivetrain(); - autoPaths(); + autoPaths(purePursuit); initController(); initLogger(); // initSelector(); } +// !SECTION +// SECTION Disabled /** * Runs while the robot is disabled i.e. before and after match, between auton * and teleop period @@ -654,6 +515,10 @@ void disabled() { } +// !SECTION + +// SECTION Competition Initialize + /** * Starts when connected to the field */ @@ -662,6 +527,10 @@ void competition_initialize() { } +// !SECTION + +// SECTION Auton + /** * Runs during the autonomous. NO user control */ @@ -674,6 +543,9 @@ void autonomous() { postAuton(); } +// !SECTION + +// SECTION Operator Control /** * Runs during operator/teleop control @@ -725,3 +597,5 @@ void opcontrol() { pros::delay(10); } } + +// !SECTION From dc82704c240192687acdacfb43d99aa76d5a60a9 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sat, 1 Jan 2022 12:11:31 -0700 Subject: [PATCH 11/21] Close to working. Just need to work out backwards and tune distances --- include/chassis/drivetrain.hpp | 18 +++++++- include/chassis/tankDrive.hpp | 3 +- include/motionControl/purePursuit.hpp | 10 +++++ include/motionControl/tankPurePursuit.hpp | 20 +++++++++ include/odometry/threeWheelOdom.hpp | 10 +++++ include/utils/motorGroup.hpp | 4 ++ src/chassis/drivetrain.cpp | 4 ++ src/chassis/tankDrive.cpp | 29 +++++++++++++ src/driver/motorButton.cpp | 1 - src/main.cpp | 53 +++++++++++++---------- src/motionControl/purePursuit.cpp | 13 +++--- src/motionControl/tankPurePursuit.cpp | 14 +++++- src/odometry/threeWheelOdom.cpp | 7 +++ src/utils/pointUtil.cpp | 4 +- 14 files changed, 154 insertions(+), 36 deletions(-) diff --git a/include/chassis/drivetrain.hpp b/include/chassis/drivetrain.hpp index 9b389e9b..a77271cb 100644 --- a/include/chassis/drivetrain.hpp +++ b/include/chassis/drivetrain.hpp @@ -17,7 +17,7 @@ namespace Pronounce { pros::Imu* imu; public: - + Drivetrain(); Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu); @@ -31,6 +31,14 @@ namespace Pronounce { */ double getSpeed(); + pros::Imu* getImu() { + return imu; + } + + void setImu(pros::Imu* imu) { + this->imu = imu; + } + MotorGroup getLeftMotors() { return leftMotors; } @@ -39,6 +47,10 @@ namespace Pronounce { this->leftMotors = leftMotors; } + void addLeftMotor(pros::Motor* motor) { + this->leftMotors.addMotor(motor); + } + MotorGroup getRightMotors() { return rightMotors; } @@ -47,6 +59,10 @@ namespace Pronounce { this->rightMotors = rightMotors; } + void addRightMotor(pros::Motor* motor) { + this->rightMotors.addMotor(motor); + } + virtual void update() {} }; } // namespace Pronounce diff --git a/include/chassis/tankDrive.hpp b/include/chassis/tankDrive.hpp index 500348e4..20b2d1fb 100644 --- a/include/chassis/tankDrive.hpp +++ b/include/chassis/tankDrive.hpp @@ -11,6 +11,8 @@ namespace Pronounce { public: TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth); + TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); + TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth); void skidSteerVelocity(double speed, double turn) { this->getLeftMotors().move_velocity(speed + turn); @@ -18,7 +20,6 @@ namespace Pronounce { } void tankSteerVelocity(double leftSpeed, double rightSpeed) { - printf("leftSpeed: %f, leftSpeed: %f \n", leftSpeed, rightSpeed); this->getLeftMotors().move_velocity(leftSpeed); this->getRightMotors().move_velocity(rightSpeed); } diff --git a/include/motionControl/purePursuit.hpp b/include/motionControl/purePursuit.hpp index d56437d2..1dab5b11 100644 --- a/include/motionControl/purePursuit.hpp +++ b/include/motionControl/purePursuit.hpp @@ -61,6 +61,8 @@ namespace Pronounce { bool enabled = false; bool following = false; + + bool atPoint = false; public: PurePursuit(); PurePursuit(double lookahead); @@ -175,6 +177,14 @@ namespace Pronounce { return maxDistance > odometry->getPosition()->distance(paths.at(currentPath).getPoint(paths.at(currentPath).getPath().size() - 1)); } + double getStopDistance() { + return stopDistance; + } + + void setStopDistance(double stopDistance) { + this->stopDistance = stopDistance; + } + ~PurePursuit(); }; } // Pronounce diff --git a/include/motionControl/tankPurePursuit.hpp b/include/motionControl/tankPurePursuit.hpp index e781f8ff..5eadd620 100644 --- a/include/motionControl/tankPurePursuit.hpp +++ b/include/motionControl/tankPurePursuit.hpp @@ -3,11 +3,15 @@ #include "api.h" #include "purePursuit.hpp" #include "chassis/tankDrive.hpp" +#include namespace Pronounce { class TankPurePursuit : public PurePursuit { private: TankDrivetrain* drivetrain; + + double speed = 100; + bool inverted = false; public: TankPurePursuit(TankDrivetrain* drivetrain); TankPurePursuit(TankDrivetrain* drivetrain, double lookaheadDistance); @@ -25,6 +29,22 @@ namespace Pronounce { this->drivetrain = drivetrain; } + double getSpeed() { + return speed; + } + + void setSpeed(double speed) { + this->speed = speed; + } + + bool getInverted() { + return inverted; + } + + void setInverted(bool inverted) { + this->inverted = inverted; + } + ~TankPurePursuit(); }; } // namespace Pronounce diff --git a/include/odometry/threeWheelOdom.hpp b/include/odometry/threeWheelOdom.hpp index fa7ea399..09f0313a 100644 --- a/include/odometry/threeWheelOdom.hpp +++ b/include/odometry/threeWheelOdom.hpp @@ -11,6 +11,8 @@ namespace Pronounce private: OdomWheel* leftWheel, * rightWheel, * backWheel; double leftOffset, rightOffset, backOffset; + + double maxMovement = 100; public: ThreeWheelOdom(); ThreeWheelOdom(OdomWheel* leftWheel, OdomWheel* rightWheel, OdomWheel* backWheel); @@ -25,6 +27,14 @@ namespace Pronounce this->backWheel->reset(); } + double getMaxMovement() { + return maxMovement; + } + + void setMaxMovement(double maxMovement) { + this->maxMovement = maxMovement; + } + double getLeftOffset() { return leftOffset; } diff --git a/include/utils/motorGroup.hpp b/include/utils/motorGroup.hpp index 9b2d6018..1118ecd4 100644 --- a/include/utils/motorGroup.hpp +++ b/include/utils/motorGroup.hpp @@ -18,6 +18,10 @@ namespace Pronounce { } } + void addMotor(pros::Motor* motor) { + this->motors.emplace_back(motor); + } + void move(double power) { for (int i = 0; i < motors.size(); i++) { pros::Motor* motor = this->motors.at(i); diff --git a/src/chassis/drivetrain.cpp b/src/chassis/drivetrain.cpp index 1e4c5284..2258e08b 100644 --- a/src/chassis/drivetrain.cpp +++ b/src/chassis/drivetrain.cpp @@ -2,6 +2,10 @@ namespace Pronounce { + Drivetrain::Drivetrain() { + + } + Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) { std::vector leftMotors; std::vector rightMotors; diff --git a/src/chassis/tankDrive.cpp b/src/chassis/tankDrive.cpp index bf3bfec3..d270c3ed 100644 --- a/src/chassis/tankDrive.cpp +++ b/src/chassis/tankDrive.cpp @@ -9,6 +9,35 @@ namespace Pronounce { this->trackWidth = trackWidth; } + TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) { + std::vector leftMotors; + std::vector rightMotors; + leftMotors.emplace_back(frontLeft); + leftMotors.emplace_back(midLeft); + leftMotors.emplace_back(backLeft); + rightMotors.emplace_back(frontRight); + rightMotors.emplace_back(midRight); + rightMotors.emplace_back(backRight); + this->setLeftMotors(MotorGroup(leftMotors)); + this->setRightMotors(MotorGroup(rightMotors)); + this->setImu(imu); + } + + TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) { + std::vector leftMotors; + std::vector rightMotors; + leftMotors.emplace_back(frontLeft); + leftMotors.emplace_back(midLeft); + leftMotors.emplace_back(backLeft); + rightMotors.emplace_back(frontRight); + rightMotors.emplace_back(midRight); + rightMotors.emplace_back(backRight); + this->setLeftMotors(MotorGroup(leftMotors)); + this->setRightMotors(MotorGroup(rightMotors)); + this->setImu(imu); + this->trackWidth = trackWidth; + } + TankDrivetrain::~TankDrivetrain() { } } // namespace Pronounce diff --git a/src/driver/motorButton.cpp b/src/driver/motorButton.cpp index c6bb8ff2..7d138e7f 100644 --- a/src/driver/motorButton.cpp +++ b/src/driver/motorButton.cpp @@ -27,7 +27,6 @@ namespace Pronounce { if (this->getAutonomous() && !this->autonomousButton) { this->motor->move_absolute(this->autonomousAuthority, abs(this->positiveAuthority)); - printf("MotorButton: autonomous authority: %d\n", this->autonomousAuthority); return; } diff --git a/src/main.cpp b/src/main.cpp index 70f7020c..d6a607bf 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -8,9 +8,11 @@ Pronounce::Controller master(pros::E_CONTROLLER_MASTER); // Drive Motors pros::Motor frontLeftMotor(1, true); -pros::Motor frontRightMotor(2); +pros::Motor frontRightMotor(2, false); +pros::Motor midLeftMotor(15, false); +pros::Motor midRightMotor(16, true); pros::Motor backLeftMotor(9, true); -pros::Motor backRightMotor(10); +pros::Motor backRightMotor(10, false); pros::Motor lift(3, false); @@ -34,7 +36,7 @@ Pronounce::TrackingWheel backOdomWheel(&backEncoder); ThreeWheelOdom odometry(&leftOdomWheel, &rightOdomWheel, &backOdomWheel); -TankDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &backLeftMotor, &backRightMotor, &imu); +TankDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &midLeftMotor, &midRightMotor, &backLeftMotor, &backRightMotor, &imu, 15.0); Pronounce::TankPurePursuit purePursuit(&drivetrain, &odometry, 10); @@ -78,16 +80,20 @@ int farPlatformToNearPlatformIndex; int nearPlatformViaLeftNeutralToFarPlatformIndex; int nearPlatformToMidIndex; +void flipOut() { + intakeButton.setButtonStatus(ButtonStatus::NEGATIVE); + + pros::Task::delay(1000); + + intakeButton.setButtonStatus(ButtonStatus::NEUTRAL); +} + /** * @brief Runs during auton period before auton * */ int preAutonRun() { - while (imu.is_calibrating()) { - pros::Task::delay(50); - } - purePursuit.setEnabled(true); frontGrabberButton.setAutonomous(true); @@ -96,6 +102,8 @@ int preAutonRun() { backGrabberButton.setAutonomous(true); intakeButton.setAutonomous(true); + pros::Task flipOutTask(flipOut); + return 0; } @@ -106,10 +114,11 @@ int preAutonRun() { int rightStealRight() { odometry.reset(new Position(105.7, 16)); - backGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); + backGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); frontGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); purePursuit.setCurrentPathIndex(rightHomeToGoalNeutralIndex); + purePursuit.setInverted(false); purePursuit.setFollowing(true); // Wait until it is done @@ -123,8 +132,8 @@ int rightStealRight() { liftButton.setAutonomousAuthority(360); purePursuit.setCurrentPathIndex(rightNeutralToMidNeutralIndex); + purePursuit.setInverted(true); purePursuit.setFollowing(true); - purePursuit.setTurnTarget(3.14); // Wait until it is done while (!purePursuit.isDone(0.5)) { @@ -135,8 +144,8 @@ int rightStealRight() { pros::Task::delay(500); purePursuit.setCurrentPathIndex(midNeutralToMidHomeZoneIndex); + purePursuit.setInverted(true); purePursuit.setFollowing(true); - purePursuit.setTurnTarget(-M_PI_2); // Wait until it is done while (!purePursuit.isDone(0.5)) { @@ -347,6 +356,7 @@ void renderThread() { void updateDrivetrain() { lv_obj_t* infoLabel = lv_label_create(lv_scr_act(), NULL); lv_label_set_text(infoLabel, "drivetrain"); + while (1) { uint32_t startTime = pros::millis(); odometry.update(); @@ -412,24 +422,23 @@ void initDrivetrain() { leftOdomWheel.setTuningFactor(1); rightOdomWheel.setRadius(3.25/2); rightOdomWheel.setTuningFactor(1); - backOdomWheel.setRadius(3.25/2); + backOdomWheel.setRadius(1.25); backOdomWheel.setTuningFactor(1); - //leftEncoder.set_reversed(true); - //rightEncoder.set_reversed(false); - //backEncoder.set_reversed(false); + leftEncoder.set_reversed(true); + rightEncoder.set_reversed(true); + backEncoder.set_reversed(false); - odometry.setLeftOffset(3.25); - odometry.setRightOffset(3.25); - odometry.setBackOffset(2); + odometry.setLeftOffset(4.5); + odometry.setRightOffset(4.5); + odometry.setBackOffset(1.5); + + odometry.setMaxMovement(1); purePursuit.setNormalizeDistance(10); pros::Task purePursuitTask = pros::Task(updateDrivetrain, "Pure Pursuit"); - // delay to let time for settling - pros::Task::delay(200); - odometry.reset(new Position()); printf("Init done"); @@ -667,10 +676,10 @@ void competition_initialize() { */ void autonomous() { // This calls the user selection, all the functions prototypes are in - // autonRoutines.hpp and the implementation is autonRoutines.cp + // autonRoutines.hpp and the implementation is autonRoutines.cpp // autonomousSelector.run(); preAutonRun(); - leftAwpLeft(); + rightStealRight(); postAuton(); } diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index 66f6128a..a20c1cdb 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -26,6 +26,7 @@ namespace Pronounce { // Returns if robot is close to target to prevent little wiggles if (pathVector.at(pathVector.size() - 1).distance(currentPoint) < stopDistance) { + this->atPoint = true; return; } @@ -40,14 +41,12 @@ namespace Pronounce { double mappedMagnitude = std::clamp(map(magnitude, 0, lookahead, 0, normalizeDistance), 0.0, normalizeDistance); Vector normalizedLookaheadVector = Vector(mappedMagnitude, lookaheadVector.getAngle()); - // Calculate curvature - double a = -tan(currentPosition->getTheta()); - double b = 1; - double c = tan(currentPosition->getTheta()); + Vector robotRelativeLookaheadVector = lookaheadVector; + + robotRelativeLookaheadVector.rotate(-currentPosition->getTheta()); - double curvature = abs((a * lookaheadVector.getCartesian().getX()) + (b * lookaheadVector.getCartesian().getY()) + c) / sqrt(pow(a, 2) + pow(b, 2)); - double side = signum_c((sin(currentPosition->getTheta()) * lookaheadVector.getCartesian().getX()) - (cos(currentPosition->getTheta()) * lookaheadVector.getCartesian().getY())); - double signedCurvature = curvature * side; + double xDistance = robotRelativeLookaheadVector.getCartesian().getX(); + double signedCurvature = (2 * xDistance) / pow(lookahead, 2); this->pointData.lookaheadPoint = lookaheadPoint; this->pointData.lookaheadVector = lookaheadVector; diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index 4eeda71f..cd1f8457 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -14,8 +14,18 @@ namespace Pronounce { } void TankPurePursuit::updateDrivetrain() { - double velocity = 200; - drivetrain->tankSteerVelocity(200 * (2 + this->getPointData().curvature * this->drivetrain->getTrackWidth()), 200 * (2 - this->getPointData().curvature * this->drivetrain->getTrackWidth())); + + if (isDone(this->getStopDistance())) { + return; + } + + PurePursuitPointData pointData = this->getPointData(); + printf("Curvature pointdata: %f\n", this->getPointData().curvature); + if (inverted) { + drivetrain->tankSteerVelocity(-speed * ((2 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2), -speed * ((2 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2)); + } else { + drivetrain->tankSteerVelocity(speed * ((2 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2), speed * ((2 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2)); + } } void TankPurePursuit::stop() { diff --git a/src/odometry/threeWheelOdom.cpp b/src/odometry/threeWheelOdom.cpp index b8f0abe5..645be896 100644 --- a/src/odometry/threeWheelOdom.cpp +++ b/src/odometry/threeWheelOdom.cpp @@ -2,12 +2,14 @@ namespace Pronounce { ThreeWheelOdom::ThreeWheelOdom(/* args */) : Odometry() { + this->reset(new Position()); } ThreeWheelOdom::ThreeWheelOdom(OdomWheel* leftWheel, OdomWheel* rightWheel, OdomWheel* backWheel) : Odometry() { this->leftWheel = leftWheel; this->rightWheel = rightWheel; this->backWheel = backWheel; + this->reset(new Position()); } void ThreeWheelOdom::update() { @@ -40,7 +42,12 @@ namespace Pronounce { lastPosition->add(localOffset.getCartesian()); lastPosition->setTheta(fmod(currentAngle + M_PI * 2, M_PI * 2)); + if (localOffset.getMagnitude() > maxMovement) { + return; + } + // Print last position + printf("Left Change: %f, Right change: %f, Back change %f\n", deltaLeft, deltaRight, deltaBack); printf("Last position: %f, %f, %f\n", lastPosition->getX(), lastPosition->getY(), lastPosition->getTheta()); // Update the position diff --git a/src/utils/pointUtil.cpp b/src/utils/pointUtil.cpp index 053e4562..0a290dc1 100644 --- a/src/utils/pointUtil.cpp +++ b/src/utils/pointUtil.cpp @@ -2,8 +2,8 @@ namespace Pronounce { Point::Point() { - this->x = 0; - this->y = 0; + this->x = 0.0; + this->y = 0.0; } Point::Point(double x, double y) { From d5afc6955ece5c75b26d70c127729153dbaebc5b Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sun, 2 Jan 2022 17:33:25 -0700 Subject: [PATCH 12/21] Add all abstract and sim classes for tank drive --- include/chassis/abstractDrivetrain.hpp | 17 ++++++++ include/chassis/abstractTankDrivetrain.hpp | 28 ++++++++++++ include/chassis/drivetrain.hpp | 10 +++-- include/chassis/simDrivetrain.hpp | 30 +++++++++++++ include/chassis/simTankDrivetrain.hpp | 35 +++++++++++++++ include/chassis/tankDrive.hpp | 13 ++---- include/main.h | 1 + include/motionControl/tankPurePursuit.hpp | 14 +++--- include/odometry/simOdometry.hpp | 50 ++++++++++++++++++++++ pathTest.cpp | 3 ++ src/chassis/abstractDrivetrain.cpp | 9 ++++ src/chassis/abstractTankDrivetrain.cpp | 13 ++++++ src/chassis/drivetrain.cpp | 44 ++++++++++++------- src/chassis/simDrivetrain.cpp | 15 +++++++ src/chassis/simTankDrivetrain.cpp | 41 ++++++++++++++++++ src/chassis/tankDrive.cpp | 33 +++----------- src/motionControl/tankPurePursuit.cpp | 6 +-- 17 files changed, 297 insertions(+), 65 deletions(-) create mode 100644 include/chassis/abstractDrivetrain.hpp create mode 100644 include/chassis/abstractTankDrivetrain.hpp create mode 100644 include/chassis/simDrivetrain.hpp create mode 100644 include/chassis/simTankDrivetrain.hpp create mode 100644 include/odometry/simOdometry.hpp create mode 100644 src/chassis/abstractDrivetrain.cpp create mode 100644 src/chassis/abstractTankDrivetrain.cpp create mode 100644 src/chassis/simDrivetrain.cpp create mode 100644 src/chassis/simTankDrivetrain.cpp diff --git a/include/chassis/abstractDrivetrain.hpp b/include/chassis/abstractDrivetrain.hpp new file mode 100644 index 00000000..921fb6eb --- /dev/null +++ b/include/chassis/abstractDrivetrain.hpp @@ -0,0 +1,17 @@ +#pragma once + +namespace Pronounce { + /** + * @brief Abstract class to be used in both the pure pursuit simulator and on the robot. + * + */ + class AbstractDrivetrain { + private: + + public: + AbstractDrivetrain(); + + ~AbstractDrivetrain(); + }; + +} // namespace Pronounce diff --git a/include/chassis/abstractTankDrivetrain.hpp b/include/chassis/abstractTankDrivetrain.hpp new file mode 100644 index 00000000..b816a0a9 --- /dev/null +++ b/include/chassis/abstractTankDrivetrain.hpp @@ -0,0 +1,28 @@ +#pragma once + +#include "abstractDrivetrain.hpp" + +namespace Pronounce { + class AbstractTankDrivetrain : public AbstractDrivetrain { + private: + double trackWidth; + public: + AbstractTankDrivetrain(); + AbstractTankDrivetrain(double trackWidth); + + double getTrackWidth() { + return trackWidth; + } + + void setTrackWidth(double trackWidth) { + this->trackWidth = trackWidth; + } + + virtual void skidSteerVelocity(double speed, double turn) {} + + virtual void tankSteerVelocity(double leftSpeed, double rightSpeed) {} + + ~AbstractTankDrivetrain(); + }; +} // namespace Pronounce + diff --git a/include/chassis/drivetrain.hpp b/include/chassis/drivetrain.hpp index a77271cb..58ddf604 100644 --- a/include/chassis/drivetrain.hpp +++ b/include/chassis/drivetrain.hpp @@ -3,12 +3,13 @@ #include "api.h" #include "utils/utils.hpp" #include "utils/motorGroup.hpp" +#include "abstractDrivetrain.hpp" namespace Pronounce { /** * Abstract class as a structure for different drivetrains assuming there are 4 motors */ - class Drivetrain { + class Drivetrain : public AbstractDrivetrain { protected: MotorGroup leftMotors; @@ -19,9 +20,10 @@ namespace Pronounce { public: Drivetrain(); Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); + Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu); - /** + /** * Get average temperature of all the motors. */ double getTemp(); @@ -63,7 +65,9 @@ namespace Pronounce { this->rightMotors.addMotor(motor); } - virtual void update() {} + ~Drivetrain() { + + } }; } // namespace Pronounce diff --git a/include/chassis/simDrivetrain.hpp b/include/chassis/simDrivetrain.hpp new file mode 100644 index 00000000..c1a96e01 --- /dev/null +++ b/include/chassis/simDrivetrain.hpp @@ -0,0 +1,30 @@ +#pragma once + +#include "abstractDrivetrain.hpp" +#include "utils/position.hpp" + +namespace Pronounce { + /** + * @brief A class for all simulator drivetrains + * + */ + class SimDrivetrain { + private: + Position* position; + public: + SimDrivetrain(); + SimDrivetrain(Position* position); + + Position* getPosition() { + return position; + } + + void setPosition(Position* position) { + this->position = position; + } + + virtual void update() {} + + ~SimDrivetrain(); + }; +} // namespace Pronounce diff --git a/include/chassis/simTankDrivetrain.hpp b/include/chassis/simTankDrivetrain.hpp new file mode 100644 index 00000000..b800da96 --- /dev/null +++ b/include/chassis/simTankDrivetrain.hpp @@ -0,0 +1,35 @@ +#pragma once + +#include "abstractTankDrivetrain.hpp" +#include "simDrivetrain.hpp" +#include "utils/vector.hpp" +#include + +namespace Pronounce { + class SimTankDrivetrain : public AbstractTankDrivetrain, public SimDrivetrain { + private: + double maxAcceleration; + double maxSpeed; + double leftVelocity = 0.0, rightVelocity = 0.0; + double leftVelocityTarget = 0.0, rightVelocityTarget = 0.0; + public: + SimTankDrivetrain(); + SimTankDrivetrain(double trackWidth); + SimTankDrivetrain(double trackWidth, double maxAcceleration, double maxSpeed); + SimTankDrivetrain(double trackWidth, double maxAcceleration, double maxSpeed, Position* position); + + void update(); + + void skidSteerVelocity(double speed, double turn) { + leftVelocityTarget = speed - turn; + rightVelocityTarget = speed + turn; + } + + void tankSteerVelocity(double leftSpeed, double rightSpeed) { + leftVelocityTarget = leftSpeed; + rightVelocityTarget = rightSpeed; + } + + ~SimTankDrivetrain(); + }; +} // namespace Pronounce diff --git a/include/chassis/tankDrive.hpp b/include/chassis/tankDrive.hpp index 20b2d1fb..a2e7008e 100644 --- a/include/chassis/tankDrive.hpp +++ b/include/chassis/tankDrive.hpp @@ -2,12 +2,13 @@ #include "api.h" #include "drivetrain.hpp" +#include "abstractTankDrivetrain.hpp" #include "utils/motorGroup.hpp" namespace Pronounce { - class TankDrivetrain : public Drivetrain { + class TankDrivetrain : public AbstractTankDrivetrain, public Drivetrain { private: - double trackWidth; + public: TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu); TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth); @@ -24,14 +25,6 @@ namespace Pronounce { this->getRightMotors().move_velocity(rightSpeed); } - double getTrackWidth() { - return this->trackWidth; - } - - void setTrackWidth(double trackWidth) { - this->trackWidth = trackWidth; - } - ~TankDrivetrain(); }; } // namespace Pronounce diff --git a/include/main.h b/include/main.h index d2e3c5eb..1eba9dc1 100644 --- a/include/main.h +++ b/include/main.h @@ -54,6 +54,7 @@ #include "auton/autonSelector.hpp" // Chassis +#include "chassis/abstractDrivetrain.hpp" #include "chassis/drivetrain.hpp" #include "chassis/mecanumDrivetrain.hpp" #include "chassis/omniDrivetrain.hpp" diff --git a/include/motionControl/tankPurePursuit.hpp b/include/motionControl/tankPurePursuit.hpp index 5eadd620..8267b84a 100644 --- a/include/motionControl/tankPurePursuit.hpp +++ b/include/motionControl/tankPurePursuit.hpp @@ -2,30 +2,30 @@ #include "api.h" #include "purePursuit.hpp" -#include "chassis/tankDrive.hpp" +#include "chassis/abstractTankDrivetrain.hpp" #include namespace Pronounce { class TankPurePursuit : public PurePursuit { private: - TankDrivetrain* drivetrain; + AbstractTankDrivetrain* drivetrain; double speed = 100; bool inverted = false; public: - TankPurePursuit(TankDrivetrain* drivetrain); - TankPurePursuit(TankDrivetrain* drivetrain, double lookaheadDistance); - TankPurePursuit(TankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance); + TankPurePursuit(AbstractTankDrivetrain* drivetrain); + TankPurePursuit(AbstractTankDrivetrain* drivetrain, double lookaheadDistance); + TankPurePursuit(AbstractTankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance); void updateDrivetrain(); void stop(); - TankDrivetrain* getDrivetrain() { + AbstractTankDrivetrain* getDrivetrain() { return drivetrain; } - void setDrivetrain(TankDrivetrain* drivetrain) { + void setDrivetrain(AbstractTankDrivetrain* drivetrain) { this->drivetrain = drivetrain; } diff --git a/include/odometry/simOdometry.hpp b/include/odometry/simOdometry.hpp new file mode 100644 index 00000000..140b7845 --- /dev/null +++ b/include/odometry/simOdometry.hpp @@ -0,0 +1,50 @@ +#pragma once + +#include "chassis/simDrivetrain.hpp" +#include "odometry.hpp" + +namespace Pronounce { + class SimOdometry : public Odometry { + private: + SimDrivetrain* drivetrain; + public: + SimOdometry(); + SimOdometry(SimDrivetrain* drivetrain); + + void update(); + + void reset(Position* position) { + this->drivetrain->setPosition(position); + this->getPosition()->operator=(position); + this->getResetPosition()->operator=(position); + } + + SimDrivetrain* getDrivetrain() { + return drivetrain; + } + + void setDrivetrain(SimDrivetrain* drivetrain) { + this->drivetrain = drivetrain; + } + + ~SimOdometry(); + }; + + SimOdometry::SimOdometry() { + this->drivetrain = new SimDrivetrain(); + this->reset(new Position()); + } + + SimOdometry::SimOdometry(SimDrivetrain* drivetrain) { + this->drivetrain = drivetrain; + this->reset(new Position()); + } + + void SimOdometry::update() { + this->getPosition()->operator=(this->getDrivetrain()->getPosition()); + } + + SimOdometry::~SimOdometry() { + } + +} // namespace Pronounce diff --git a/pathTest.cpp b/pathTest.cpp index 0d27de31..77b82880 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -18,6 +18,9 @@ #include "src/utils/runningAverage.cpp" #include "include/utils/utils.hpp" #include "src/utils/utils.cpp" +#include "include/utils/position.hpp" +#include "src/utils/position.cpp" + using namespace Pronounce; diff --git a/src/chassis/abstractDrivetrain.cpp b/src/chassis/abstractDrivetrain.cpp new file mode 100644 index 00000000..8518a9fc --- /dev/null +++ b/src/chassis/abstractDrivetrain.cpp @@ -0,0 +1,9 @@ +#include "abstractDrivetrain.hpp" + +namespace Pronounce { + AbstractDrivetrain::AbstractDrivetrain() { + } + + AbstractDrivetrain::~AbstractDrivetrain() { + } +} // namespace Pronounce diff --git a/src/chassis/abstractTankDrivetrain.cpp b/src/chassis/abstractTankDrivetrain.cpp new file mode 100644 index 00000000..abf38909 --- /dev/null +++ b/src/chassis/abstractTankDrivetrain.cpp @@ -0,0 +1,13 @@ +#include "abstractTankDrivetrain.hpp" + +namespace Pronounce { + AbstractTankDrivetrain::AbstractTankDrivetrain() { + } + + AbstractTankDrivetrain::AbstractTankDrivetrain(double trackWidth) { + this->trackWidth = trackWidth; + } + + AbstractTankDrivetrain::~AbstractTankDrivetrain() { + } +} // namespace Pronounce diff --git a/src/chassis/drivetrain.cpp b/src/chassis/drivetrain.cpp index 2258e08b..05e9d6b6 100644 --- a/src/chassis/drivetrain.cpp +++ b/src/chassis/drivetrain.cpp @@ -2,39 +2,53 @@ namespace Pronounce { - Drivetrain::Drivetrain() { - + Drivetrain::Drivetrain() : AbstractDrivetrain() { + + } + + Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : AbstractDrivetrain() { + std::vector leftMotors; + std::vector rightMotors; + leftMotors.emplace_back(frontLeft); + leftMotors.emplace_back(backLeft); + rightMotors.emplace_back(frontRight); + rightMotors.emplace_back(backRight); + this->leftMotors = MotorGroup(leftMotors); + this->rightMotors = MotorGroup(rightMotors); + this->imu = imu; } - Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) { + Drivetrain::Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : AbstractDrivetrain() { std::vector leftMotors; std::vector rightMotors; leftMotors.emplace_back(frontLeft); + leftMotors.emplace_back(midLeft); leftMotors.emplace_back(backLeft); rightMotors.emplace_back(frontRight); + rightMotors.emplace_back(midRight); rightMotors.emplace_back(backRight); this->leftMotors = MotorGroup(leftMotors); this->rightMotors = MotorGroup(rightMotors); - this->imu = imu; - } + this->imu = imu; + } - Drivetrain::Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu) { + Drivetrain::Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu) : AbstractDrivetrain() { this->leftMotors = leftMotors; this->rightMotors = rightMotors; this->imu = imu; } - double Drivetrain::getTemp() { - double total = this->leftMotors.get_temperature() + + double Drivetrain::getTemp() { + double total = this->leftMotors.get_temperature() + this->rightMotors.get_temperature(); - return total / 2.0; - } - - double Drivetrain::getSpeed() { - double total = this->leftMotors.get_actual_velocity() + + return total / 2.0; + } + + double Drivetrain::getSpeed() { + double total = this->leftMotors.get_actual_velocity() + this->rightMotors.get_actual_velocity(); - return total / 2.0; - } + return total / 2.0; + } } // namespace Pronounce diff --git a/src/chassis/simDrivetrain.cpp b/src/chassis/simDrivetrain.cpp new file mode 100644 index 00000000..9128946e --- /dev/null +++ b/src/chassis/simDrivetrain.cpp @@ -0,0 +1,15 @@ +#include "simDrivetrain.hpp" + +namespace Pronounce { + + SimDrivetrain::SimDrivetrain() { + this->position = new Position(); + } + + SimDrivetrain::SimDrivetrain(Position* position) { + this->position = position; + } + + SimDrivetrain::~SimDrivetrain() { + } +} // namespace Pronounce diff --git a/src/chassis/simTankDrivetrain.cpp b/src/chassis/simTankDrivetrain.cpp new file mode 100644 index 00000000..38b44596 --- /dev/null +++ b/src/chassis/simTankDrivetrain.cpp @@ -0,0 +1,41 @@ +#include "simTankDrivetrain.hpp" + +namespace Pronounce { + + SimTankDrivetrain::SimTankDrivetrain() : SimTankDrivetrain(0.0, 0.0, 0.0) {} + + SimTankDrivetrain::SimTankDrivetrain(double trackWidth) : SimTankDrivetrain(trackWidth, 0.0, 0.0) {} + + SimTankDrivetrain::SimTankDrivetrain(double trackWidth, double maxAcceleration, double maxSpeed) : SimTankDrivetrain(trackWidth, maxAcceleration, maxSpeed, new Position(0.0, 0.0, 0.0)) {} + + SimTankDrivetrain::SimTankDrivetrain(double trackWidth, double maxAcceleration, double maxSpeed, Position* position) : SimDrivetrain(position), AbstractTankDrivetrain(trackWidth) { + this->maxAcceleration = maxAcceleration; + this->maxSpeed = maxSpeed; + } + + void SimTankDrivetrain::update() { + SimDrivetrain::update(); + + // Update the wheel velocities + double leftChange = std::clamp(leftVelocityTarget - leftVelocity, -maxAcceleration, maxAcceleration); + double rightChange = std::clamp(rightVelocityTarget - rightVelocity, -maxAcceleration, maxAcceleration); + + leftVelocity = std::clamp(leftVelocity + leftChange, -maxSpeed, maxSpeed); + rightVelocity = std::clamp(rightVelocity + rightChange, -maxSpeed, maxSpeed); + + // Calculate the local offset + double offset = (leftVelocity + rightVelocity) / 2; + double angle = (rightVelocity - leftVelocity) / this->getTrackWidth(); + + // Calculate a vector + Vector localOffset(offset, angle); + + // Update the position + this->getPosition()->add(localOffset.getCartesian()); + + this->getPosition()->setTheta(this->getPosition()->getTheta() + angle); + } + + SimTankDrivetrain::~SimTankDrivetrain() { + } +} // namespace Pronounce diff --git a/src/chassis/tankDrive.cpp b/src/chassis/tankDrive.cpp index d270c3ed..c605427d 100644 --- a/src/chassis/tankDrive.cpp +++ b/src/chassis/tankDrive.cpp @@ -5,37 +5,16 @@ namespace Pronounce { TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu) { } - TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu) { - this->trackWidth = trackWidth; + TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) : Drivetrain(frontLeft, frontRight, backLeft, backRight, imu), AbstractTankDrivetrain(trackWidth) { + } - TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) { - std::vector leftMotors; - std::vector rightMotors; - leftMotors.emplace_back(frontLeft); - leftMotors.emplace_back(midLeft); - leftMotors.emplace_back(backLeft); - rightMotors.emplace_back(frontRight); - rightMotors.emplace_back(midRight); - rightMotors.emplace_back(backRight); - this->setLeftMotors(MotorGroup(leftMotors)); - this->setRightMotors(MotorGroup(rightMotors)); - this->setImu(imu); + TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu) : Drivetrain(frontLeft, frontRight, midLeft, midRight, backLeft, backRight, imu) { + } - TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) { - std::vector leftMotors; - std::vector rightMotors; - leftMotors.emplace_back(frontLeft); - leftMotors.emplace_back(midLeft); - leftMotors.emplace_back(backLeft); - rightMotors.emplace_back(frontRight); - rightMotors.emplace_back(midRight); - rightMotors.emplace_back(backRight); - this->setLeftMotors(MotorGroup(leftMotors)); - this->setRightMotors(MotorGroup(rightMotors)); - this->setImu(imu); - this->trackWidth = trackWidth; + TankDrivetrain::TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth) : Drivetrain(frontLeft, frontRight, midLeft, midRight, backLeft, backRight, imu), AbstractTankDrivetrain(trackWidth) { + } TankDrivetrain::~TankDrivetrain() { diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index cd1f8457..59380db6 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -1,15 +1,15 @@ #include "tankPurePursuit.hpp" namespace Pronounce { - TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain) : PurePursuit() { + TankPurePursuit::TankPurePursuit(AbstractTankDrivetrain* drivetrain) : PurePursuit() { this->drivetrain = drivetrain; } - TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain, double lookaheadDistance) : PurePursuit(lookaheadDistance) { + TankPurePursuit::TankPurePursuit(AbstractTankDrivetrain* drivetrain, double lookaheadDistance) : PurePursuit(lookaheadDistance) { this->drivetrain = drivetrain; } - TankPurePursuit::TankPurePursuit(TankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance) : PurePursuit(odometry, lookaheadDistance) { + TankPurePursuit::TankPurePursuit(AbstractTankDrivetrain* drivetrain, Odometry* odometry, double lookaheadDistance) : PurePursuit(odometry, lookaheadDistance) { this->drivetrain = drivetrain; } From 362dde8d840d4dbf948a3a2f29ed9142f47e5040 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sun, 2 Jan 2022 18:10:22 -0700 Subject: [PATCH 13/21] Add inverted and fix curvature calculations --- src/motionControl/purePursuit.cpp | 2 +- src/motionControl/tankPurePursuit.cpp | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index a20c1cdb..05db9521 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -46,7 +46,7 @@ namespace Pronounce { robotRelativeLookaheadVector.rotate(-currentPosition->getTheta()); double xDistance = robotRelativeLookaheadVector.getCartesian().getX(); - double signedCurvature = (2 * xDistance) / pow(lookahead, 2); + double signedCurvature = (2 * xDistance) / pow(lookaheadVector.getMagnitude(), 2); this->pointData.lookaheadPoint = lookaheadPoint; this->pointData.lookaheadVector = lookaheadVector; diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index cd1f8457..6ed2e784 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -21,7 +21,10 @@ namespace Pronounce { PurePursuitPointData pointData = this->getPointData(); printf("Curvature pointdata: %f\n", this->getPointData().curvature); + + // Drive backwards if (inverted) { + pointData.curvature = -pointData.curvature; drivetrain->tankSteerVelocity(-speed * ((2 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2), -speed * ((2 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2)); } else { drivetrain->tankSteerVelocity(speed * ((2 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2), speed * ((2 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2)); From efc0981138edcc4a2e0d97cf3511cd869fe8251e Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sun, 2 Jan 2022 18:52:25 -0700 Subject: [PATCH 14/21] Add a dot product to allow the robot to drive backwards once it has passes a point. --- include/motionControl/purePursuit.hpp | 1 + pathTest.cpp | 4 ++++ src/motionControl/purePursuit.cpp | 1 + src/motionControl/tankPurePursuit.cpp | 6 ++++++ 4 files changed, 12 insertions(+) diff --git a/include/motionControl/purePursuit.hpp b/include/motionControl/purePursuit.hpp index 1dab5b11..39776607 100644 --- a/include/motionControl/purePursuit.hpp +++ b/include/motionControl/purePursuit.hpp @@ -20,6 +20,7 @@ namespace Pronounce { struct PurePursuitPointData { Point lookaheadPoint; Vector lookaheadVector; + Vector localLookaheadVector; Vector normalizedLookaheadVector; double curvature; }; diff --git a/pathTest.cpp b/pathTest.cpp index 77b82880..3faf3169 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -214,6 +214,10 @@ int main() { int loopcount = 0; + Vector vector(1, 0); + + printf("%f\n", vector.getCartesian().getX()); + // Create path std::vector paths = std::vector(); diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index 05db9521..8732a789 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -50,6 +50,7 @@ namespace Pronounce { this->pointData.lookaheadPoint = lookaheadPoint; this->pointData.lookaheadVector = lookaheadVector; + this->pointData.localLookaheadVector = robotRelativeLookaheadVector; this->pointData.normalizedLookaheadVector = normalizedLookaheadVector; this->pointData.curvature = signedCurvature; } diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index b6a7781b..2bf06474 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -22,6 +22,12 @@ namespace Pronounce { PurePursuitPointData pointData = this->getPointData(); printf("Curvature pointdata: %f\n", this->getPointData().curvature); + pointData.localLookaheadVector.normalize(); + + double dotProduct = pointData.localLookaheadVector.dot(Vector(1, 0)); + + double speed = this->getSpeed() * dotProduct; + // Drive backwards if (inverted) { pointData.curvature = -pointData.curvature; From d339e049813f3768d26619caadff9d640eb12ee6 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Tue, 4 Jan 2022 10:12:33 -0700 Subject: [PATCH 15/21] trying to get sim to work --- .vscode/settings.json | 195 ++++++++++++---------- include/chassis/simTankDrivetrain.hpp | 2 + include/motionControl/tankPurePursuit.hpp | 3 +- include/odometry/simOdometry.hpp | 20 +-- include/utils/pointUtil.hpp | 5 + include/utils/utils.hpp | 54 +++--- pathTest.cpp | 167 +++++++++--------- runPathTest.sh | 2 +- src/chassis/simTankDrivetrain.cpp | 23 ++- src/motionControl/tankPurePursuit.cpp | 6 +- src/odometry/threeWheelOdom.cpp | 4 +- 11 files changed, 242 insertions(+), 239 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index bbd0bdb7..e12f2d29 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -1,95 +1,106 @@ { "files.associations": { - "ios": "cpp", - "type_traits": "cpp", - "cmath": "cpp", - "valarray": "cpp", - "hash_map": "cpp", - "deque": "cpp", - "forward_list": "cpp", - "list": "cpp", - "string": "cpp", - "unordered_map": "cpp", - "unordered_set": "cpp", - "vector": "cpp", - "system_error": "cpp", - "__hash_table": "cpp", - "__split_buffer": "cpp", - "__tree": "cpp", - "filesystem": "cpp", - "map": "cpp", - "pros": "json", - "set": "cpp", - "array": "cpp", - "atomic": "cpp", - "bit": "cpp", - "*.tcc": "cpp", - "bitset": "cpp", - "cctype": "cpp", - "compare": "cpp", - "cstdarg": "cpp", - "cstddef": "cpp", - "cstdint": "cpp", - "cstdio": "cpp", - "cstdlib": "cpp", - "cstring": "cpp", - "ctime": "cpp", - "cwchar": "cpp", - "cwctype": "cpp", - "exception": "cpp", - "algorithm": "cpp", - "functional": "cpp", - "iterator": "cpp", - "memory": "cpp", - "memory_resource": "cpp", - "random": "cpp", - "string_view": "cpp", - "tuple": "cpp", - "utility": "cpp", - "fstream": "cpp", - "initializer_list": "cpp", - "iosfwd": "cpp", - "iostream": "cpp", - "istream": "cpp", - "limits": "cpp", - "new": "cpp", - "ostream": "cpp", - "sstream": "cpp", - "stdexcept": "cpp", - "streambuf": "cpp", - "cinttypes": "cpp", - "typeindex": "cpp", - "typeinfo": "cpp", - "chrono": "cpp", - "clocale": "cpp", - "codecvt": "cpp", - "concepts": "cpp", - "condition_variable": "cpp", - "numeric": "cpp", - "optional": "cpp", - "ratio": "cpp", - "iomanip": "cpp", - "mutex": "cpp", - "numbers": "cpp", - "semaphore": "cpp", - "stop_token": "cpp", - "thread": "cpp", - "variant": "cpp", - "__bit_reference": "cpp", - "__bits": "cpp", - "__config": "cpp", - "__debug": "cpp", - "__errc": "cpp", - "__functional_base": "cpp", - "__locale": "cpp", - "__mutex_base": "cpp", - "__node_handle": "cpp", - "__nullptr": "cpp", - "__string": "cpp", - "__threading_support": "cpp", - "__tuple": "cpp", - "locale": "cpp", - "queue": "cpp", - "stack": "cpp" - } + "ios": "cpp", + "type_traits": "cpp", + "cmath": "cpp", + "valarray": "cpp", + "hash_map": "cpp", + "deque": "cpp", + "forward_list": "cpp", + "list": "cpp", + "string": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "vector": "cpp", + "system_error": "cpp", + "__hash_table": "cpp", + "__split_buffer": "cpp", + "__tree": "cpp", + "filesystem": "cpp", + "map": "cpp", + "pros": "json", + "set": "cpp", + "array": "cpp", + "atomic": "cpp", + "bit": "cpp", + "*.tcc": "cpp", + "bitset": "cpp", + "cctype": "cpp", + "compare": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "random": "cpp", + "string_view": "cpp", + "tuple": "cpp", + "utility": "cpp", + "fstream": "cpp", + "initializer_list": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "new": "cpp", + "ostream": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "cinttypes": "cpp", + "typeindex": "cpp", + "typeinfo": "cpp", + "chrono": "cpp", + "clocale": "cpp", + "codecvt": "cpp", + "concepts": "cpp", + "condition_variable": "cpp", + "numeric": "cpp", + "optional": "cpp", + "ratio": "cpp", + "iomanip": "cpp", + "mutex": "cpp", + "numbers": "cpp", + "semaphore": "cpp", + "stop_token": "cpp", + "thread": "cpp", + "variant": "cpp", + "__bit_reference": "cpp", + "__bits": "cpp", + "__config": "cpp", + "__debug": "cpp", + "__errc": "cpp", + "__functional_base": "cpp", + "__locale": "cpp", + "__mutex_base": "cpp", + "__node_handle": "cpp", + "__nullptr": "cpp", + "__string": "cpp", + "__threading_support": "cpp", + "__tuple": "cpp", + "locale": "cpp", + "queue": "cpp", + "stack": "cpp", + "any": "cpp", + "cfenv": "cpp", + "charconv": "cpp", + "complex": "cpp", + "csetjmp": "cpp", + "csignal": "cpp", + "cuchar": "cpp", + "regex": "cpp", + "future": "cpp", + "scoped_allocator": "cpp", + "shared_mutex": "cpp" + } } \ No newline at end of file diff --git a/include/chassis/simTankDrivetrain.hpp b/include/chassis/simTankDrivetrain.hpp index b800da96..f446d537 100644 --- a/include/chassis/simTankDrivetrain.hpp +++ b/include/chassis/simTankDrivetrain.hpp @@ -3,6 +3,7 @@ #include "abstractTankDrivetrain.hpp" #include "simDrivetrain.hpp" #include "utils/vector.hpp" +#include "utils/utils.hpp" #include namespace Pronounce { @@ -12,6 +13,7 @@ namespace Pronounce { double maxSpeed; double leftVelocity = 0.0, rightVelocity = 0.0; double leftVelocityTarget = 0.0, rightVelocityTarget = 0.0; + double leftDistance = 0.0, rightDistance = 0.0; public: SimTankDrivetrain(); SimTankDrivetrain(double trackWidth); diff --git a/include/motionControl/tankPurePursuit.hpp b/include/motionControl/tankPurePursuit.hpp index 8267b84a..19ef9af5 100644 --- a/include/motionControl/tankPurePursuit.hpp +++ b/include/motionControl/tankPurePursuit.hpp @@ -1,9 +1,8 @@ #pragma once -#include "api.h" #include "purePursuit.hpp" #include "chassis/abstractTankDrivetrain.hpp" -#include +#include namespace Pronounce { class TankPurePursuit : public PurePursuit { diff --git a/include/odometry/simOdometry.hpp b/include/odometry/simOdometry.hpp index 140b7845..f0206f58 100644 --- a/include/odometry/simOdometry.hpp +++ b/include/odometry/simOdometry.hpp @@ -28,23 +28,5 @@ namespace Pronounce { } ~SimOdometry(); - }; - - SimOdometry::SimOdometry() { - this->drivetrain = new SimDrivetrain(); - this->reset(new Position()); - } - - SimOdometry::SimOdometry(SimDrivetrain* drivetrain) { - this->drivetrain = drivetrain; - this->reset(new Position()); - } - - void SimOdometry::update() { - this->getPosition()->operator=(this->getDrivetrain()->getPosition()); - } - - SimOdometry::~SimOdometry() { - } - + }; } // namespace Pronounce diff --git a/include/utils/pointUtil.hpp b/include/utils/pointUtil.hpp index d5ea4ffe..e0d6c5d7 100644 --- a/include/utils/pointUtil.hpp +++ b/include/utils/pointUtil.hpp @@ -83,6 +83,11 @@ namespace Pronounce { this->setY(this->getY() + point.getY()); } + void operator+=(Point* point) { + this->setX(this->getX() + point->getX()); + this->setY(this->getY() + point->getY()); + } + std::string to_string() { return "X: " + std::to_string(x) + ", Y: " + std::to_string(y); } diff --git a/include/utils/utils.hpp b/include/utils/utils.hpp index 7bc1f786..6988775f 100644 --- a/include/utils/utils.hpp +++ b/include/utils/utils.hpp @@ -7,32 +7,38 @@ namespace Pronounce { - double toRadians(double degrees); - double toDegrees(double radians); - double angleDifference(double angle1, double angle2); - double signnum_c(double x); + double toRadians(double degrees); + double toDegrees(double radians); + double angleDifference(double angle1, double angle2); + double signnum_c(double x); - /** - * @brief A function like processing's map function. Maps a value from one range to another. - * - * @param value Value to map - * @param start1 Start of input range - * @param stop1 End of input range - * @param start2 Start of output range - * @param stop2 End of output range - * @return double Mapped value - */ - double map(double value, double start1, double stop1, double start2, double stop2); + /** + * @brief A function like processing's map function. Maps a value from one range to another. + * + * @param value Value to map + * @param start1 Start of input range + * @param stop1 End of input range + * @param start2 Start of output range + * @param stop2 End of output range + * @return double Mapped value + */ + double map(double value, double start1, double stop1, double start2, double stop2); - template - std::string string_format(const std::string& format, Args ... args) { - int size_s = std::snprintf(nullptr, 0, format.c_str(), args ...) + 1; // Extra space for '\0' - if (size_s <= 0) { throw std::runtime_error("Error during formatting."); } - auto size = static_cast(size_s); - auto buf = std::make_unique(size); - std::snprintf(buf.get(), size, format.c_str(), args ...); - return std::string(buf.get(), buf.get() + size - 1); // We don't want the '\0' inside - } +#ifdef SIM + double clamp(double value, double min, double max) { + return std::min(std::max(value, min), max); + } +#endif // SIM + + template + std::string string_format(const std::string& format, Args ... args) { + int size_s = std::snprintf(nullptr, 0, format.c_str(), args ...) + 1; // Extra space for '\0' + if (size_s <= 0) { throw std::runtime_error("Error during formatting."); } + auto size = static_cast(size_s); + auto buf = std::make_unique(size); + std::snprintf(buf.get(), size, format.c_str(), args ...); + return std::string(buf.get(), buf.get() + size - 1); // We don't want the '\0' inside + } } // namespace Pronounce diff --git a/pathTest.cpp b/pathTest.cpp index 3faf3169..9a06841d 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -20,19 +20,44 @@ #include "src/utils/utils.cpp" #include "include/utils/position.hpp" #include "src/utils/position.cpp" - +#include "include/utils/purePursuitProfile.hpp" +#include "src/utils/purePursuitProfile.cpp" +#include "include/utils/purePursuitProfileManager.hpp" +#include "src/utils/purePursuitProfileManager.cpp" +#include "include/pid/pid.hpp" +#include "src/pid/pid.cpp" +#include "include/chassis/abstractDrivetrain.hpp" +#include "src/chassis/abstractDrivetrain.cpp" +#include "include/chassis/abstractTankDrivetrain.hpp" +#include "src/chassis/abstractTankDrivetrain.cpp" +#include "include/chassis/simDrivetrain.hpp" +#include "src/chassis/simDrivetrain.cpp" +#include "include/chassis/simTankDrivetrain.hpp" +#include "src/chassis/simTankDrivetrain.cpp" +#include "include/odometry/odometry.hpp" +#include "src/odometry/odometry.cpp" +#include "include/odometry/simOdometry.hpp" +#include "src/odometry/simOdometry.cpp" +#include "include/motionControl/purePursuit.hpp" +#include "src/motionControl/purePursuit.cpp" +#include "include/motionControl/tankPurePursuit.hpp" +#include "src/motionControl/tankPurePursuit.cpp" using namespace Pronounce; -#define xOffset 0 -#define yOffset 0 +int testPathIndex; + +int fps = 60; + +#define xOffset 30 +#define yOffset 30 #define multiplier 3 #define lookahead 10 #define starting_point_random 1 -#define PRINT_LIVE false +#define PRINT_LIVE true #define GRAPH true #define FIELD_WIDTH 140.6 @@ -46,6 +71,21 @@ void printRobotWithLookahead(Point point) { circle(point.getY() * multiplier, point.getX() * multiplier, lookahead * multiplier); } +void printRobot(Odometry odometry, double trackWidth) { + trackWidth /= 2; + + Position* point = odometry.getPosition(); + circle(point->getY() * multiplier, point->getX() * multiplier, 1); + circle(point->getY() * multiplier, point->getX() * multiplier, lookahead * multiplier); + + Vector forwardVector(20, point->getTheta()); + + Point forwardPoint; + forwardPoint.add(Point(forwardVector.getCartesian().getX(), forwardVector.getCartesian().getY())); + + line(point->getY() * multiplier, point->getX() * multiplier, forwardPoint.getY() * multiplier, forwardPoint.getX() * multiplier); +} + void printPath(Path path) { if (path.getPath().size() < 2) { @@ -214,56 +254,19 @@ int main() { int loopcount = 0; - Vector vector(1, 0); - - printf("%f\n", vector.getCartesian().getX()); - - // Create path - std::vector paths = std::vector(); - - - // Right Steal Right - Path rightHomeToGoalNeutral; - - rightHomeToGoalNeutral.addPoint(105.7, 8); - rightHomeToGoalNeutral.addPoint(105.7, 60); - - paths.emplace_back(rightHomeToGoalNeutral); + SimTankDrivetrain drivetrain(15.0, 15.0/fps, 60.0/fps); + SimOdometry odometry(&drivetrain); - SplinePath rightNeutralToMidNeutral; + TankPurePursuit purePursuit(&drivetrain, &odometry, 10); - rightNeutralToMidNeutral.addPoint(105.7, 60); - rightNeutralToMidNeutral.addPoint(82.3, 40); - rightNeutralToMidNeutral.addPoint(70.3, 60); + // Test path + Path testPath = Path(); - paths.emplace_back(rightNeutralToMidNeutral.getPath(0.1)); + testPath.addPoint(0, 0); + testPath.addPoint(0, 24); + testPath.addPoint(24, 24); - Path midNeutralToRightAlliance; - - midNeutralToRightAlliance.addPoint(70.3, 60); - midNeutralToRightAlliance.addPoint(120.1, 36); - - paths.emplace_back(midNeutralToRightAlliance); - - SplinePath rightAllianceToRightRing; - - // Turn to negative 90 degrees - - rightAllianceToRightRing.addPoint(120.1, 36); - rightAllianceToRightRing.addPoint(117.5, 46.8); - rightAllianceToRightRing.addPoint(117.5, 70.3); - rightAllianceToRightRing.addPoint(117.5, 70.3); - - paths.emplace_back(rightAllianceToRightRing.getPath(0.1)); - - QuadraticSplinePath rightRingToLeftHomeZone; - - rightRingToLeftHomeZone.addPoint(SplinePoint(Point(117.5, 70.3), Vector(50, M_PI_2))); - rightRingToLeftHomeZone.addPoint(SplinePoint(Point(70.3, 35), Vector(50, M_PI_2))); - - paths.emplace_back(rightRingToLeftHomeZone.getPath(0.1)); - - srand(std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count()); + testPathIndex = purePursuit.addPath(testPath); #if GRAPH int gd = DETECT, gm; @@ -276,47 +279,31 @@ int main() { //printPath(path); #endif // Set random robot starting position - Point firstPosition = paths.at(0).getPath().at(0); - - firstPosition.setX(firstPosition.getX() + ((rand() / 1073741823) - 1) * starting_point_random); - firstPosition.setY(firstPosition.getY() + ((rand() / 1073741823) - 1) * starting_point_random); - Point robot = firstPosition; - Vector robotMovement = Vector(); + Position startingPosition(0, 0, -M_PI_2); #if GRAPH std::vector robotPositions; - robotPositions.emplace_back(paths.at(0).getPath().at(0)); + robotPositions.emplace_back(startingPosition); #endif - // Use a running average to estimate momentum - const int runningAverageLength = 10; - - RunningAverage runningAverageX; - RunningAverage runningAverageY; + purePursuit.setEnabled(true); // Loop through paths - for (int i = 0; i < paths.size(); i++) { + for (int i = 0; i < purePursuit.getPaths().size(); i++) { - std::vector pathVector = paths.at(i).getPath(); - Path path = paths.at(i); + std::vector pathVector = purePursuit.getPath(i).getPath(); + Path path = purePursuit.getPath(i); + + purePursuit.setCurrentPathIndex(i); + purePursuit.setFollowing(true); // Loop until you get to the last point - while (pathVector.at(pathVector.size() - 1).distance(robot) > 1) { + while (!purePursuit.isDone(1)) { loopcount++; - // Get the lookahead point - Point lookaheadPoint = path.getLookAheadPoint(robot, lookahead); - robotMovement = Vector(&robot, &lookaheadPoint); - if (robotMovement.getMagnitude() > 1) { - robotMovement.normalize(); - } - robotMovement = robotMovement.scale(1); - runningAverageX.add(robotMovement.getCartesian().getX()); - runningAverageY.add(robotMovement.getCartesian().getY()); - - // Move robot - Point runningAveragePosition(runningAverageX.getAverage(), runningAverageY.getAverage()); - robot += runningAveragePosition; + odometry.update(); + purePursuit.update(); + drivetrain.update(); #if GRAPH #if PRINT_LIVE @@ -327,24 +314,24 @@ int main() { printPath(robotPositions); - robotPositions.emplace_back(robot); + robotPositions.emplace_back(Point(odometry.getPosition()->getX(), odometry.getPosition()->getY())); setlinestyle(DASHED_LINE, 5, 2); - for (int i = 0; i < paths.size(); i++) { - printPath(paths.at(i).getPath()); + for (int i = 0; i < purePursuit.getPaths().size(); i++) { + printPath(purePursuit.getPath(i).getPath()); } setcolor(LIGHTGRAY); setlinestyle(SOLID_LINE, 5, 2); - line(robot.getY() * multiplier, robot.getX() * multiplier, lookaheadPoint.getY() * multiplier, lookaheadPoint.getX() * multiplier); - printRobotWithLookahead(robot); + line(odometry.getPosition()->getY() * multiplier, odometry.getPosition()->getX() * multiplier, purePursuit.getPointData().lookaheadPoint.getY() * multiplier, purePursuit.getPointData().lookaheadPoint.getX() * multiplier); + printRobot(odometry, 15); - delay(3); + delay(1000/fps); #endif // PRINT_LIVE - robotPositions.emplace_back(robot); + robotPositions.emplace_back(Point(odometry.getPosition()->getX(), odometry.getPosition()->getY())); #endif - if (loopcount > 1000*paths.size()) { + if (loopcount > 2*fps * purePursuit.getPaths().size()) { break; } } @@ -358,11 +345,11 @@ int main() { setlinestyle(DASHED_LINE, 5, 2); // Print all paths in the vector paths - for (int i = 0; i < paths.size(); i++) { - printPath(paths.at(i).getPath()); + for (int i = 0; i < purePursuit.getPaths().size(); i++) { + printPath(purePursuit.getPaths().at(i).getPath()); } - robotPositions.emplace_back(robot); + robotPositions.emplace_back(Point(odometry.getPosition()->getX(), odometry.getPosition()->getY())); setlinestyle(SOLID_LINE, 5, 2); diff --git a/runPathTest.sh b/runPathTest.sh index 828be293..c1aa1044 100755 --- a/runPathTest.sh +++ b/runPathTest.sh @@ -1,2 +1,2 @@ -g++ pathTest.cpp -opathTest -lgraph -Iinclude/utils/ +g++ pathTest.cpp -opathTest -lgraph -Iinclude/ -Iinclude/utils/ -Iinclude/chassis/ -Iinclude/odometry/ -Iinclude/motionControl/ -Iinclude/pid/ ./pathTest \ No newline at end of file diff --git a/src/chassis/simTankDrivetrain.cpp b/src/chassis/simTankDrivetrain.cpp index 38b44596..2a700c38 100644 --- a/src/chassis/simTankDrivetrain.cpp +++ b/src/chassis/simTankDrivetrain.cpp @@ -14,7 +14,8 @@ namespace Pronounce { } void SimTankDrivetrain::update() { - SimDrivetrain::update(); + + Position* oldPosition = this->getPosition(); // Update the wheel velocities double leftChange = std::clamp(leftVelocityTarget - leftVelocity, -maxAcceleration, maxAcceleration); @@ -24,16 +25,24 @@ namespace Pronounce { rightVelocity = std::clamp(rightVelocity + rightChange, -maxSpeed, maxSpeed); // Calculate the local offset - double offset = (leftVelocity + rightVelocity) / 2; - double angle = (rightVelocity - leftVelocity) / this->getTrackWidth(); + double offset = (leftVelocity + rightVelocity) / 2.0; + double angle = (leftVelocity - rightVelocity) / this->getTrackWidth(); + + leftDistance += leftVelocity; + rightDistance += rightVelocity; + + double relativeAngle = (leftDistance - rightDistance) / this->getTrackWidth(); // Calculate a vector - Vector localOffset(offset, angle); + Vector localOffset(offset, relativeAngle); - // Update the position - this->getPosition()->add(localOffset.getCartesian()); + Position* newPosition = new Position(); + newPosition->operator=(oldPosition); + + newPosition->add(localOffset.getCartesian()); + newPosition->setTheta(relativeAngle); - this->getPosition()->setTheta(this->getPosition()->getTheta() + angle); + this->setPosition(newPosition); } SimTankDrivetrain::~SimTankDrivetrain() { diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index 2bf06474..47827cce 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -20,13 +20,15 @@ namespace Pronounce { } PurePursuitPointData pointData = this->getPointData(); - printf("Curvature pointdata: %f\n", this->getPointData().curvature); + std::cout << "Curvature pointdata: " << this->getPointData().curvature << std::endl; pointData.localLookaheadVector.normalize(); double dotProduct = pointData.localLookaheadVector.dot(Vector(1, 0)); - double speed = this->getSpeed() * dotProduct; + double speed = this->getSpeed();// * dotProduct; + + bool inverted = signum_c(speed); // Drive backwards if (inverted) { diff --git a/src/odometry/threeWheelOdom.cpp b/src/odometry/threeWheelOdom.cpp index 645be896..aee36336 100644 --- a/src/odometry/threeWheelOdom.cpp +++ b/src/odometry/threeWheelOdom.cpp @@ -28,8 +28,8 @@ namespace Pronounce { // Calculate the change in orientation double lastAngle = lastPosition->getTheta(); - double currentAngle = this->getResetPosition()->getTheta() + (leftWheel->getPosition() - rightWheel->getPosition()) / (rightOffset + rightOffset); - double angleChange = angleDifference(currentAngle, lastAngle); // fmod(currentAngle + M_PI * 2, M_PI * 2) - fmod(lastAngle + M_PI * 2, M_PI * 2); + double currentAngle = this->getResetPosition()->getTheta() + (leftWheel->getPosition() - rightWheel->getPosition()) / (leftOffset + rightOffset); + double angleChange = angleDifference(currentAngle, lastAngle); double averageOrientation = lastAngle + (angleChange / 2); // Calculate the local offset then translate it to the global offset From f094a9d31250b5754f5ae2b70dbd8c0648f57e4e Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Tue, 4 Jan 2022 11:01:31 -0700 Subject: [PATCH 16/21] stuff --- pathTest | Bin 0 -> 168360 bytes src/motionControl/purePursuit.cpp | 2 ++ src/motionControl/tankPurePursuit.cpp | 2 +- src/odometry/simOdometry.cpp | 23 +++++++++++++++++++++++ 4 files changed, 26 insertions(+), 1 deletion(-) create mode 100755 pathTest create mode 100644 src/odometry/simOdometry.cpp diff --git a/pathTest b/pathTest new file mode 100755 index 0000000000000000000000000000000000000000..48924c126206768e59f90e57b1d5bf63e05339de GIT binary patch literal 168360 zcmeFaeOy&l_CJ15DQa}MmKLRB*TxJ>4NVPG3sdS^P?S-sgdvQ`0W&6ceKvKb^JnG)hhDCvs9`!R$aMd8KJ7TC&y+zx!%l?I`4S z!T%Il>cj@w%)mHVuQQO^CD4Tn_7>Tifd+?!)GpdjLV_qUQ1gg1wTq=oFa5%gmw%i1 ztS-_9s_nQx4^hC61E=MSYy;JHB%3u0M7uS&*|Ch7(X@l;XY(9gtA{WE?|e;Kmfj^o9+oVflt zLEk{5zsu2%LYk_vz+`*TR@@zTI zph1079r~g6a*8?K9lr<4yrY5Zyq=?`X)(V`{6lKzV^7e=Qza@Ng#StSKMene<3If* z3*g@)<@LG1QA$2t&bj%4g;~MXE7DFVyf5`|cCTdx!4tbweSWCn`mEj`b-#Pz3!mJz zFyol3UP&&wTFWoJS{s-8*8b-o89#eZ-tM_e-ne>hj}=|V{b@&!=N)8i$-@|woLXD{ zoGAGNqU2XVSZ;J^8F_7#MPetwt^S@U^hbd{$=vz#A~M|QJQ5}UswnwSM#;Yg6YoYp zJxc!aC~}w>rT$e>@;gHgZsR=@e0uTU`EwWDcoEjBD3iBrAOfSgOva@H+ zEh@||@#hr#v$I82*NWpZwEV(+Ka7nU@ST@a zJR@&@J~$}JEzZj;BvF<4XXKuFCdq1qmVM2nD=!_Al%1VhR+ck8fBul6L$b5y&&|)y zMZYE4{u}4zf%eRzRMed4ABu|p*~LXSWEbQW&hpRB&MPi1D$ckB%w031AY=Yq;H49b z3QAIEm{D#LP71TKkv%!Ong+AvorLdo^Tel54CM9YDm4%Oxr-Jq4^v%1X6&CM>6 zD=V|`hI}->BCn)$E~(!1T&YI1qH^bC=gyv!Ju@f2Kz5Yl&nwF}dYze1f>{7%g_2GO zOy*LzKm6(f=KVvM%^9eyHBHY)duGi>!?PH~vmTAO9BJqO_BC zt}G{p19#qw?Zq+LM>4PUaYnA(%SIT^!BR@{=zcU>9pI3=~vmE(n zNIKIT`N ze)VxePwE``^)lVy$X_Sx>yG?-ncw2bZ&W)Vs6zwQpo5oc4vs&i7SSMq6(VEi;F`NtcXz(ytCINPIQ zUCHmS)NfJpPgn9=mHYupeu9)gacji>RBXh%#QSK5*!-zi z@}+CwvIZqznrzN*RPy0q%pYCJr@oD!79}4J$oy$l^2t-0KT-}v0}jUgiBs~8y#f__ zl>BaHZOBT=|Gkp$Rq~CaN-9oN@(mrK{3In`-M=O)`E)L3{G=%PJ&jDDPsu+)$C#F{Ao)5$x8lgCBK)FKTpa3gOXpSDVizE{bwR`UBQ`74xs zbw5|5f zQCnMEHK!?XKG3wsOjE#oplPd_ra<{X(?85K1;_`Q9x~Gulpkoi(@ayKe4uHunWo_O zK-2YRnl>f}nsUrE10q}vQ z7&A?Q?}4VTe>TQT0WZdHrYX?H_{}tJ%rJg4O&cJL-%L{gjPaXk3VbnsGfe?6#&4!6 z(8c)8G;M4!eltx0FUD`CDbU6E%`^qL7{8gOjTgpmrYX?H_{}s0xEQ~groa~CKWvQO z%ju7dG_<2~E@{Vjjr9ZRyaIcAiX)xrNT)l}sgCp*M|!v;J;;$h&5{0tBi+-H?&e6x zI?{*d*vIp&BmIRV{i!4Uz9apXBmJ5q{gNa7q9gsRBmJZ!{iq}TS4VoeBVFZ4S31&* z9O+U=dafg#r>2K|F(I&LsxR=duVPj7{^d|&ksxH^Gww~9Z$-!zQ z1Gw;2#oj_Nven-crl}8I!!#Y!));?EIkZpPE)n&w=K900AQETB*{||3q;6X2nVG(dF&nSLr7!TQzpF1e=08a2Cqd8k z888MrV@Zu-rl76aKecbV!LSsWXb5ZSJrLhLwH3e8TktDW_f=)K_^MJ{eSx=qfv}!4 zk9ydK9Nib#=?lE0FGkLRc#rn-cB02r0*hLG!PM57@n3~NLsPC(;;N_E>QQghQMyjG zK!;P@gc3T6>}@Lcr}zSk8hnA$`We1pm(ysY=nJH_4hey$Mq+UeOf-4)1wY4eDFNmuqW@q@$7Tx<} z^&HfAc{_U)DaQnemC+A?);!{`a4bG|)2CP-ePfe-g$C zRVZzY93!&B`ulLG=(Q0Y#DS;u21@vXDRB^JVMxz{;10xJol4nU|Fdh&`W_mCqkb~_ zx7Gg|^&_U^jUU_Eh@g$rY2dULoUU_nS_Sb1Gf~7E?!|&&{Rn2RlUdzF77KX@`Xi~Y zF?7g_3`npJT&1s}5mE_PJx^AxF{%#YjH^>?4#a1rQr%Rv^5o%H_dJtc90^QPIE3{~ z%U}%#W7D^pfu|HoUMo4V)IOZb*BZNw2 zWrFqYnN-46`^l;+jH<_TMpi0iG?Gr$5Jh@MQ?5uu$^$X)FqmS+_T+NW*)igp$sfkr zj+oo;T6u13ZF8GsXdwx;!8!aOTNh}ZTyinKz~xwcLg7A;lVWP%C&-BCwOsV7Y80#- zjG49O|1Yhcqpyj+#rs>?@V%Hox*2%Z!>~LK01;GbKvfDlna9d$Tq&$i0Pd_j6Th)E z|H@5+m4ZT8e;AL0_$qYB2dV65a%xubd5kaj4Y{5_qq;^1mGe;S3oI`q5cEV7tNwFp{nT=d zd@0nq+*eh_ZL3nNeSzJi=!dW@eO1djH(132t4hTZ;KC27Fo?Rr%oQ;EQh=HD5EI(7 z?YY#nzk$jm;zzE)rEud>nu0nvJ)R9?R)}UlS!tRsn%1D#HI815rVX%`!h(5NabU?n zW^x_!wi3A%h1}0Q1kY%DvGRl*yNE*@V zXUQ^Z2Nquji(BJw`2b3W7O^jUOg*1fNu}|()QQ|mYGc)XM%KMU)}_+;TUN@tg6>(| zCjQo1=&o3IF__tPP<1MYDpivdw#u124KoQvoJU1Lp_TzMx0!XU4ppWdpWn)jNr6zz zTCg<}nk|)P3)7+S04;6$CJh0%_!pk?GFnto3u)RHi|ciy*2mzQBq&BM<>4|KDtC_N zDt5&k7|ojRBS!O$!rRxvr5|B5u}X_A)IyHtpW>QFGYZ!<8ZkG1jsc!lF`9U5cbiPnt0#|B3@VI+9k7xxyOb_tdkT$7XTOV=NKZuwr3-mbk8_>ubez zIbFZN*V4p?^|eS=2shI792kk;z+SMTC1y#;KNiD_<3(pg=Jo93f|UtEuj{d3J#;DT z`RmXa@P$fYeIf`q_cnc(SYW~Bv$?hiH!SztpO`}QVQnBXn=hr!lP>_DX)@b}1<~Bw z%oiPfPMJrWnWjsBgH}(Vfp{rx!Je=FE9ygVzIX@43fHQ!O2vK;BBoYw(MnBrLkX*u z{R_nxbu_%di)2X=U$74dEKf$t8CL|^ViTFKq29EH9(kYEQg^l&;mS#919J$kO;^He z3vyw7_zZMndhH_K-LSt2E~m;iuRVn7M)BH2Pc*T-c8prz@Y=#RSEa*wn_m0E17OSa z+B8HILao?q51>NJYlnm##@33funAr94Gp`y@Yq&Wp*>CAA&SV&b{`Ebxfu4w+3m#Y+=bdIflHic}TFGRidNJ zb*jTze~^o@Vlgb?M|!bHXc0?w(5(Lm4_ItQ)sum0~+hDX?@q5hZ z*7?IA%5pfQr4EP0&Q5fF!KGFwhd`|PLL+t{-sdO#oJI&jqe#@r?2qXd9Ufs^Y% zsR5We$Q5bemCp(SmAroCfaif1nu;u*inF+EzK?RKmZ9$LaA&L&7Ug7xyAy=?pmAaS zK`01BTus+^iR*H@KET(eZTJMq3bC@9Rv{#_41$nkSl@~omZ32E4(pE-Az>)e_R}8B zW{6_-`5X7{FSv0+mT>S@h=43WqqkgHKij(ZY@s6YKV##yl= zSs5L1mtbrpNiHP#f0EAAbr2^?qVIzsrPAkmKTI|09~7h$+OxR3P+hgS=sF2qM{Zql zG6F8{qZJ&)bwvmQ4(oSf>L4U=6xRP_l+l@&;P7WWfoBxgip9@Wuc2l{rYgfD%J~Sd z1S)S-{{yO%QrM0gZfSCy`lJxAbOuM}P@PCRhocU_*C+5pD$nn;X3@kN{uMmoaJoK zt<-S=kx=}kQ{TN%RJGhyqkf{LZ`Y^?;Hn}tYH=>=iIw^=xP-E{t5H{=I{G%2Dhv{z zr>4`PYHZ)P$zxoN?U<+AANYFeR%=mGi~s@ufZ&bm4pq&I>VozG6DgC5aW>@HNt zhAFl6hEB~1C>Nb?Vj@|z7ffw!euvuOZ1}9$WyqgT)tJ$4%efkF8By)uoFB;}A1m`d zZT_*S5_=+AHJ>b9L~5(Zyn-@g9TYHGDa3-oJ1TmRsPLb(&6gtA%#X=Hl_U-?P_F2gI;6!2^pVg4pQ_ zSEL3`u54o-jLPn-1FM0=#ss#&r)YX;ALN5@7$;B_92Jr^P7r0Qtg=~VSr!iEohyV^ za-g(DS{X~$EK|tE7x2hS5YM1n6V_>-^kiVknuBq0^oA_l=742q^hhlsIWlnRauzwD zoT?BpMP~I2o>e|fkEt42I?a=AEy-|=6(MLqSg$e8c5!_VU&Cc`T@E{57M31nJFEx5 zNHxk7w>hyn&2XDC>Y;l_N*Do~D?7R*q5veogv$zF_K(#e`5q`gH0rWkvR zL=r{dSuex#42CL-uhIe>I;I7xD7M0?`eXb6j(y?>q?gAJ$gGYZFr_AbK;F9e0dqs~ z14`@T2P}fDD+R%@z8NDASB^$obcBruUHMk{Dq2sxVVqGdxLowhayfgtrd4pYnC5yz z1Qxw|=C^^Qb|QvU?OVKqhTw=DlCgB^+KFtI7;a07@E`&=C;#uvnav~flg9P7a~ z#zPTLMglxD=8GNmZ4)3jIWxQH7Pfu*BBP#OmJgZwF(%~skIV@%9ED+RK&sW4+(L0^ zh}9F;8z35W)f)cMSg;Ay&`2bzi6k|FxSfqi?B>^bbC}{YGM<$g8A^3cxlV~w6CO2T z>)WfY8y72v1v!N*eqMc45*=W_ZMTE{?_>tEZ&+vMpG_t@6a%1?Snt$5rHGjn9s;G{ zQ@W?v$Dl;hs9{$1dEt<7B2QGhr!db{Y+U$~)#4PYhx=`b!b_E&4-FFi`+RW1b@BJ% zz}(;0$V-wJDT(CbM5232Qgb)DG-jDAfo77R*;k>N0h(LqGdZh5aw{o1589VOVMy~a zMmMrQbYWC5hM}Qioy^SOQP3bg!UboUB}TiHI9Xycon`cqrTSrqeI-3{>WwW;&liy& zAt_=t>>x{0)pNi_xM9y(eM$` zMzuF9x~%G1E~@KrX5vr+myi`yKwUOM zXrM()3-Oh~??J&^`ztrv3}x9#Me5~ z(sfutH9nm0BiGucG`!c=CRX)^2Gfu|O{bE9DYa;^6lz^7PdmD>|3NlIMpfpi(N$yt zjo9f!eJD(jNQU)QjVPk0A3(%hyni_l6{Il5`b7u4e$&A}nnF{<`r!}T3%g{c22_%9 z@MmCOzktTDcn2*u88iASzVbAc90D!V5*wbTs%J@xYACAAlrR*=ikv0x7O`7;0XH)g zKcaeuqeOGdGvvKP%<~%Vm z&?4lX%M5-o*5#Op_BxV}Khe;{ zCfJZEaghv}*$(OWX%N~}g!RdyhdR1$1$jbW3L!n?hbp{1dUzCaiW33Giz{2__ zcwN=62~EjBgEdZ{R@L*l(cFHGP}DWXV%kjZEtt9{oI-m@QqeUqPO;B#6VX1*Hmqnx zD23!RTF8vjS(MHYYP7}|yMlEltXE5FJIfo9!-RL1e`H;L%$M{C0GfBF=5$w|x)Ad2 z2SW}Saq%P=J)ya4|AmS|F^-4j5cOA7gO*)}@k<^=Uei7JMQT7zB&|5mYKE&88cuN{ z&B!p&b!fOUmJFIgF?t^D4wwaXF_>Z*39&c}JT$;JucUq&=+%lYLfy=Go`zWyE4Ndj{Nv%WEeJVA#Pxo*b9%G8~3}qs(7^tS%B}U0pt`Gu1(poR^OKw4p z=07&H&xOfsx!A3l!#U_OZLH?`7`L5{Z(u%W?7@gCcFb0zW{NF! z)-QfS%{ei~J$3SEe3Kd*R2!o2N7;%F;Sk7XC zzDyWRO~pA-&^!)$b_h?acvj5Ho{4N<6+Z_8@yc8KxR+1PS{kV3sZ=FHrkR(&Qx-oE zm%)Z&c@{f@)EXQ!u0cB>?A+^mMiS}?20`7IBsSZ$6j39r_eC#wC@w)(*;!6DA?5}A z(wZjmsiqv;yf{>G?MmJ?rsyf1Z|I_5K4N@}{E_VEdA?pw_fGM=8q+cE>2lo(WK@it zupW1|tEgrTr|c{tL96zGp%|l;ycaoz*s<~a6`e6~JP=N-p#B0#zNB~Uq|r(_4cfrXTsQ`@{=@B>;jBPSv+A86ccVdRzl>VadHh*RkQP9 zW;kg5aj=HD5j?CXm+Bn1qxl;2FY0siY*Js@{1|RdyEJ}s(b2Hh-mt&Yu>MWzH?^Dt z_5kssGK`&$+T#}xpwZ)f+|bYt`AA^*@&?g@r^8QGFu^o6v-#RofvZK5bsnV~kbEJA zn~H^myoZrj@l%ZdXkKy6v9eqQMT0O4ZiVZpuNLebP>5k!R@gta`6|l-W0+xmEIP2P zr?4`VKY)1?{k)U{(``M>Bm8|e=u2<;#H+BbN8uOt4rEM~^JW$yP=9!oRWwlaHrh z9^R!08FASL>{#(IbLAX%2hyTR4Q5vqn~aK8!{c;P2&7bJ#&&oqEgMy~sB z5u`V=K_%*&x#l)sFm}}lh?kt!J9-mk%2j_AwUCNi5%Q9T+%*tc!JdzBhp9D&f##d? z{Yg)$X_dH>Q?U(Am}uE<%UG+H@tJzGu!j8vhK;F}j}Ftl>h6Z!BLT&4V1=TmyN6>j zqh=~%$D6wK2Q&0|Fli7hlzhl%1u2`EDi)332k_>DI#6Q|XAS5#^7PPXjfHR=4w%ZUrq*DRnDu zhDCInFS_MYkfl4iyQ%BN+?_Z%DwSQMoP8OwN!??z$F{xM^nognBZ+4b@$w?Kj^O2e zj-~`{Lj*rOYl+|szUG_dhT%3On@MDsyG!;~L6%EF7T!M*Pm+6LA7pZ3h<8PhR)=UP zE2il$@Zn-BFLpmz1!4VG%CyX_=?e-elob1ukztn&>5`og;^G~&gl#)~(+0EIk~)?N z3wD=Kx8r;j+Yr|r$IC>VgSWk*>|f0GRXt+{+bkS$dmN5;l*-m|f;>uC)1Ni5+wJQK zX}Jt+fH~8t?G9O1Y?XyJk_QZYfYMbj(I6ww2@+t8$p$lt36jKF773Glo-8}wDpSa( zg1kYcv#igIvkZ#o`XGsuDOL&aIVWsI884Qwe(7mKvcoLKFm$tcmMrdR6)U5^2z)D* zJITuWGpYbgTD@fP%T}=>gP*qBXnj0@Oj^%JQP<~;Y}b&E%0TtHSNM7z0@ZS9{V%DL zSs3(V{fHIubS|2}V4KzYiE1^ZLq1ePF^Q7z$x~i3Q^pA^_r!kXJz0&4(?!SJe5}C) z@`sCS4%@!|qY&;p|BwP1A3snxIPc1=dAe;>3gMegajln)A27;U=gs2RWbvP@;?Vd& z)A+#0toL0>oKi*)3r7d}g!MCU4bMUEjTvur4rxBaiszW`>y-vSybMCZV8nr@p1Td{ z#XCqXVIam%u?_)+#)@N#r4AhhD^t_MwO!ei*a26IXB&lBPdH3c--BHX*vH} zBTBy-1~;QTx6kYk1v$m{2)6$~{RuiDu;I|bSp9dz8y&2;D^(Wkwe83Yh7W3tW0bJI z7fc8ZqW9q{al0B?vlhQG$7}f+d{J*b)iWQ!?~4j3mpZ_tSO+#xEmH@00+~#`=#J~$ zWvc@@@%u_FufwN^iT&hB`^0i#f>#voR0?TgS!~;7%g2pEF|l0sp)9Mi%G8PNvxO&? z`&cimBR3;USpiWreG@sc%TT7y5;wSk8jD#v88jniDQ`2+QkG+uU}EVGtS9#HS{mSF zz8x!W%(hwv0x>`mrm+EgED~lt&E0M|L3y~rPXTe}*GeXnT`kErQb#S+(LIqJ!M?PR zWwV`v6blF4V4b8=B(fzQ%Asey*w(g@jv_Y4;@1}Z*Ysf+;Pa0{H8#?(&6Fn!MxpYS zII7aurP*QRA@qR*k^CKefZK0PnCe zLy%A+NGnkzCN{;5H#E;|BpSqmcvJ-{@-F_HPeg?DUK9`EZGGM{>irJ$PKKVKz|)$1 zEZ1FTk>>J45FuT>A1c10ARmlvKEzU_XRkc`Xf3{|5W?ECv*{{AgTvUzA9oSbJyxbA zq?@fwOGwvQnIxo&jn3X(g|wv$srH4aOq?H4TxUUCTgbxd$D@fQxMqHP60fCOf@_dj zir`+7S#_u-1@{bRd2E8)Wfz>eD{!h1g?nKMAMOV-OK&qdA|*>}|pNP9TZBEY7H7EJ7UR;J`_H%2uNRB1J`DePrcvDzJFWlCv9ap%LhuBIuoV*W@)Swszl zqIfY5hoWRF=8xjG@-G(xQL(s3>l$ANPkMUrYhYY zldZv&QYDBg4zVf^B})eTzi5i}Bj5@QK*+&kCVhJE=i(Wu)EqERd%Dwm1M|3)Xu z{kUydVWcP1xl+$u0tnAg6+RE{`hq3V&=1yiBJ!#22+{T&x3=}|#>bvCTI@xxqXd7^Adz{ji zUJN%zG8p+=IurK?{vkNHKv22FjmoQVI7Z7Cf3&W3W{ zMU8?z-*am_Nokv^w4Ep0-Y(ic=GKW!Pk(dad2g*X#@BwZu3M2$ z<2^yNJ;$xz8l~->O507c?Yq=ruxDqtwlkErnM&Jo+4gPG_Bl766P30nDQ(BgwhxQ8 ze{yTPA0EY+-}hUs>p0oAP_#YYt?fFc?L$i2SCLP$I#;yq?AF$=w9Ql6R?D_iA7oi& z6FAp2d2@s3%a!?^B-@@U+Rkxndx%`3)Qz4>+XS=~H^28j<+Qc&OZs=h^ANr9%i(-K zCThauRz4kJa(7szvm#4ZTcr~sOP5-uXGWG@XO(t~EKRdYzrtV~JP)=?_e7R@tkQo* zmL4D^oGdN4OZ#Zk)JUaNF_ zWN9a>^wG%DedIQUH2#cI{o}Pri|6)9=6u^#-YZCi!BxE}&d9=*jfdo$VX<{5;R~_x zXK>WhbtOAf>?Nn}3C2F9l>GP?a=TOUtaQ(>aOuM%FNhax?(XW>!Gg#aZ&z2YLo6iE zQ1!QP865rsw_VN!_;wVB9F_G%2`(77O8J4DGlWbxxv9PIh9qZYbjAAJC4KDb}YeN|O@i6L?5`###EfOD#tMOjdf zy+VX13euBMSCv5G@ML#zUiD4N9ktfPlNbOe#zI^d?A~p6)sWD%vT62=!+U^coBl)Be+a zW)W!^Pk9cC_`54mi?v-^yn~dT- zS^OA^B@yUM71u(md)6@z+?AmxtPxlBHR}`g8q`xxO*k&Q_;FHX-Bb{|5(-i+CQnF( z$sHvG!v!Gs!vIh>6vW7U_e@d{|Mg(Ao@bQ_+LU9vAS2jaPPL>0?)#mM-8Ony$69i? z34x0G_~y|j9BMP;F-@s-4n?1x)`O4PhR7>#)*6dWm8$TyJ#GC>z_~8O+U=}+32}Q_ z+^6GlV2Tw%+$3{-9|k=+Bd7+EUWz>t375_ zQ&0JmF+?d{BKipFh9#wYI4KRTYTvHLK@1kisTiEBZZ42Jg#9&CH5+z4*zKX?W3*Zw zI&%N_KYSB^Mo6C~`ZWf%r@I)`CCqJv%045D4<2Rqr>ZP@N6XqKSvs()k6E8a_XX+& zdBH*{gRxz~R7@x>m!!+mw@u4ToZ=Y;XnXbPnl>T+=^dn__mL6f7AP12#a;4VX>8Lg zIBu*)!8|!pM{i`&X2@g$84fm?F-=<$zv-8JZPPAZK*y}61+?E>Ky)P*kfGpgM|c6f zL^Ev7Rc(JHjRj;#|NcZ_VQ(P|?l#JD5D9XJe9KXeis?U!w)_~eI`OwdJC#l!-^XJ# zx*JAnVTq;}C{!@3344G2i2_sOqPJCPXE4 zOFXpoG!YNb<6)JkA)n;hg?i+ykG&h#WeO6y55Ha@zQ6%9g8se~-Fu|seDNZ8Zv-@A z?;>N0Fu!eww(Df&V|R09!`*y{yY7hdg6VW`zAJz1IetkG+7leB?g``!^BOZnnTTsol+!WT#Pg>QhZJe>NOT^Q=fZ8I-ToH`t>)_ip@@ zQNJ$y#5w3B$$ndeJMhTlS2*rbyED|_aSHIU)MQ+tziY3yPB#A$kB+F#4aL}L-8!#) z2zuC919FRZP_*y34@+m?fklS`rL7f<4#kuXUAzdJUVJfq0F?i!6QTT{qCFmI-O!C< z+Tnje7L>l6Qqbi!C{)g`H&at_(_$suta2Zh-cF+TsBtGOG8gZ$(L~U`L>|NAn>Y0I z;RLAG%=k$z-{PUS?FXl}#y=2>-w>({#V-%pzfO|kylcDyN=n4(m>9Q{@f~N*z}YSi zdFv2H^AnQvd>7vYdB|D4T2#-Z>U5Gv-=*U_gF5fd#T~z$Ftzo6wN-sTo}`5PTgcZekzgdq5uI@p+=u9{sqg+#4cRUwPL+dOOXv6EJ=|K( z4GE?YGe^|ux=dWR(Dm&~{sXwiysK{~c@;X`wm<3+-y~Be(33N=ID>1PtWYEeVyk_M zvo_H?QlHOYz1XNc#2HGTt7%2a(QR_pe!^Ls=pCs~`d+xL&p}QqLy=+h>2uaT$61@` zIr@y4qjG4YL2;S5W)UYT`RC%=M#s{USS`qk8cmD-UumC1Kj|YCS>kp(1j>r4YM3Gg z@j(Q+6<9>k1g12aK8mlX!S>)|Lt;}HO95vv9g8L-j{nMl_y(z+hH*0vD;|GE0Kd|m z_jG;1DJb;NZ6|){&wj#x2FD*{PH=Ydq5eGwoWi<{Ly_aQN#uQ?J{)4Ot=jq**zn%? zC2xjAN=0gPF}#ay&c!RiY#nF~_di1Uj>t8pNS$9lfSz#_bu@P8=*lqMwFn)cHc>gd z5dN?|&VKx*oLSnO;!*o`=#=p_Fw34=x1{Oa?BEo#PmLs;QiSa^Qx$|t{&JcBDCf(% z5ER<+&FIA>G|Y_q_vaML>W7HnDERMezyNjv0Z22f7u)kMfKG~n>m3CiqhOw+z-JT` zISMjtGPh*rSm9_+t|h{I82L^K8~Hwm3@|O0=kz#QxoEUx*pWcC+G&I-9rSYrdB)$_-h#pEC1DSh+ zse5U!CRy7|Q9Slzcgybs(KqEtoi4=KuJrl>(xO}l3S&LZL#bIX69kNp>~Em<^qyoX z8sc@S%j0~3qkMrYG4`=oau?E6>yATP%fpiCqG-ysH?+hfbfzq59LZ=}hjB!HRrHs9 zU+WB-1LIB~?l7XG5a};@Nra0}RA?HT0loXZvLb(5oy|ouEg0GM7E%8Zv;IfRt-|gg zd_>#0A9o1l3HPJuOV_AF@lw1wZi;M;xg{>w9>D@lJ3@JcZM0TX#JVAuL19|DUaiao zaTC3Srp-k&h5bMYd|n{(dqdIblV<`Cc(Rfxqu-PinI*#^%JM~TFIvgZDW(`H-L+K| z-o=QpsMNJ)>(Q7abCmR|D~*(uW`eM|Bo?d(GkYkqZFVh^N`g}TNntuTQlNgNsK~8&W|V!qg3&7ralEz5;`y{ki~mhjWAc@Ot})bP!M>aGx@Ig$8-XR zzkW4_GVzjkMQfXXh+1JQRS0Ib2CqmY+cC0!{&7?csvj9t{YUenYmTi&4&I3KpTq?4 z$CL0nmoG?$ga+64M)RriQZL;q$Bas9g&3Pup{?!CmG}ybA;-&@Q)_5PBaJ7etq8$f zkA_DS?ZF$*^^>x_J&J=>6nh&CCW)qK<^7U%`Oe)kEA653g+?0JdvUFfXd;M#U9z|o zWg;95-bVXEU+{q%f&h9W=X2W{k-3gDeW05KeY%b0i>e`!3mc!6h}=4nTQ73KV^%U= zacbaXMhf+$JPrpLpqXZH2#|&vk}3L54B0Lj^t7lUQ2M5N z_fCFZIGFinfIh^O+5nY;mRF6r>L!?Gu%zkptC<*{|Mz8a4OHYWCG)))?FXY2taCQ6 zks;zncq0k;dfbE}``l_h8WyXUgQ{(&nLCI&;;)be`GcDca?%&@q^H-z=|RGmLpJ32 zX=27E;u@2L&ARx=Bl4M-N52P)%vxCglnx513SxQl1Pp&~?CU$6fBy+{D5OrDgCdQ+ zMN*_Y0_qx<)+ErfH1!}=kKd4aaA|cTq!+&-^`Q7`2q!X~$TgXih-t0Q`gp@KSUr4s2OZb)EmWZTS%|lA#=x((x)*QYV%t}14zM8W zX;NRs!4Qa&U_sPq68K8~cv!NhT- zKXPC5C5|Sg?{31Gf<7L<;JZ_BFy-)-Bx8!olGJ>|*3&!^=SSE#lpmoy!mAtK(vkE> zQ)oih(qfMg>xa@_>c790hR%oe6OdMI4(pv52fzDm&AzFTRXrDf3z2Y#9ssnSwxu*a zMoLpYrRkebhWeNU1bJ!#fA7JG8NM-j6s4NGP&3ySRFgY7LJNqSbh9c9|G3U@K3nX5{DN7{l@DMyy#D@4!{`nCj0abp(7 z=|er2DsWC%574b5`N^dm1a1=oFL9E$7Tm!%s4bQYCzm0a7HIMX-c1YqhZq=xR`3CJ z*gxRg$S@+7Jsa0Nnq(~AjRga^zfIkVCn|C-li;$ypatw~?v!{6X3HB`*r%Ty=suTuy#0Ep?Dzc|srmCL!!6+5vt` zg1ar?Mx;9!AnOhgHQ0^cONCtW3&gNj1YjV87ZUhm8BCEJ_STQP_+ms~FhNcH2Mgu6 z?xH&pG_HGTBb;vx_caVctUl&;AFpR~MgvGrfIFA-?c>U{fLQ<^;dCx7a3C%4B@O&u z3_J~gU{)wV15!Py6r;TY;Ei^p{gsHz7UJ#T`84aVtSaNL1veAX~Ai6 zqAnjigwldZ2DxYH{w&C)#k9b7SX|T_lpyg4`4F)>I5aOW|FKgo^XqaF!UkUF{msa2 z{?TaKNP}KQ9Rx_?DC61H1IRAnfz( zA>3day-3MnWS?@=1Y_K9bCM5bmWLpJI*v2PX4*jtb3AAQXUgDON3mw+u0@*STLiyo z4%Ni9&DX1T8Rcu*D>r<)YLQK6KstmjcrlOX!)i)~^)8<~q6;}^bVTKtx1Fiq<5)?k z#9(4NAk;}r<5^-DP$Rq8pIc&&oK3m0qQXsC{v);>Dcwq1!X3JJwsk^1A`MqmV*YY@jMXDXYmnIxltgGL< zgG4CZ^%v+v#>(yZy~B9c34Slu>Gzf!luW;;$cI+Zf9v=1sRL=K?0zptbgfIjM^@kA z_XcrW)9=mYq{HuhiOdMU*N%d$?gbm&h4$=(rL7`vTBW4EI^V#lsG z?Gzz7YuEcZJ;Nvi-#2;B;Mnz^NloOg_d|M;TCU^)UUMb;tX=O5sIBaJCn0Iu^~RzV zJBdICcD?hcJF)9Me^JD)x7aG}i&A~zLKqEt%RqdNBkHbqo|FMaIAV@~=!b)y2dGen zTHVos;(kpnj9hPbb1U0=dmCBSdaFg4q1^J6uG{eB?RxIPIMmYdLIv+wKLQzjL!{@v zm&au8Z(d>B!@jWu0(bG;rN%T~hjPAl-LVGt__qGg*|$-#K-kGfx^gddNQ%)hSN<6( zo#mE#TkLib?1adbzejgplr8LVDzjX9gT{SwRm~hfC+}zaaMCtcK8V^YuKZCmDy@s$ z!aiVmWt2K2nvTjP&Z1)Z_Bbp6oO;&#VnV(cY;GGn`>J|StXxM2Y)yEvMaU8&XrS}( zNH5=vI79LBov@iy#MuO4C|-Ua9^V%(mu0gENz2P01DRM}{t~2`?iX^!sL9D;JL(mz z;rkxM4eYMUx~s<@LXwtt;(X?nPsiHv_+QZpzk{^X`=4o04Yn&m6h?^y%oQvbxJMA= zjX*zKx99anv{(M?z1~-(xRRaw?csjMz0N1B{cgMU_XK%8`fmL(Zfkm-7g}f@9A4)Q z)Ny(p$kGdkgBU1c=ZEp2!^}pxV_$lz7@~E)8LQXNM>nWuSxC@=8CDOAY5e5VxC`8r zX^?cWkoY8ED$_+b9Eow(Vq``9p~j5&Xh>*{`-^Dk1n1`Nf7z3~0v#CG4j^t2 z!-+V6I9zJqxwc0aM<Kb&s`=?D6LgPf*x{i>fCfe2FbK-PT);>3 z#0&kv;{=KZ*y33ci>}9#fcAE zR$($N5D2jz>Qx8z3V}3MBRMf%b_viHR%pt`^k?uM97cpjQ%bebDy&~Z*scZFv)Qv4%MFoyQ1E9{d!!>B|L&I?SFp4%}_w!!umVRmucJTI7zk*T*8YX zK6+h$i83Qh0?E16Tu}D45o4c~sJ(YaJ>ivkO&oOVoj#j)q~6_^^J$=rzFr zoq4CO;eZ;m&X;WM>iHVgy5R^B)#&q=_@4^utV7itvhn=|w8rDCBKt*=-H6tWXjKbb zL7jCrhJhA1AQvvH(HBFr3#QrDd`;V#a4Ii9{ZyP#AP&CXU}G%@mvkE$9EA0gI)V9M zl3Yi1@}|dp(R;10BDI!Q2`J-fNqfr=F@9lKz#J_RzFjg}wrnmknvJqITf@zq9Zq%Y zFvi}p(6z&UvZX!}XD8x*)~QC<{C$rA%q2bOKx8-nw!d-2M!^=Nke@JeNjFZQNJ)K8#;~&HzNl5XwMW-{ zYtM00-I2s_ozGMH&?%;&H1d%R{&wfP>hI<(xd)tfjg6*chY*=Ibxkf-@~ zJHk{CzY~JA&5cv?Ne}|=nmg_mkqOb*8`so+bUv0ogw`J)itKgZ4A zwqv2)4gCm^R}6iGS+|MpJXBUA1~afREjwiHh1@!DXRLRWarLl|%drBk5FA+j{n`~^ zQE(19YP|F*42E;`uJM<(W{q{u2B*Q%UWy9q%z1N5`UzdGv(7YVTBfGigTn96cbk8o z%U)5vlhu)UYZXobS;J+#wZc8#x;rA?dU-Z4c&re_ZdSZ?7sXp+uCuIV46dcM+=)@h zc*{8>kve4CDD4#|o)HV~O)z08bky)^8xPV9-uTs9-k3I6!P`2j^NWJF{d9oZf!@Eg z_x>R#9iiji4)pH6rae$JiwVPlv|}3NzREp#``$jLj<4_pumP=&n4zJw)EOcx?Xa@0 zd!a)!)mF~ClO2pG|1n94C?8;{A2Fi*p(`&3XGEDsqZ7w{YD5_n*^L-@qZ&~b^5Hk0 z38A}i>e(CxPN-VdwG$Abi1FCYWomf&IudGlIe{K%grk(<B&?4tMQvh+Bsb+FSlaq=3TTsI3UJl(-{putlKPTRewQ1im>i{XMevrWuw^eG=EwrWWH; ze~p>3N1%o;6;Ws_g;;NYf@YB?AX_M#HM2#WfDFFeI01QcdV41zaTqz8sDg~CYv)Od za#->INkr@P9vEFI7=g=(>d%jl(sz4?(iRSN5d_+eBE4*W4PM$cw2k=2hD{b7kENpc z!nz#QW_Hxl-eqegkC#mOcF@vZghyY@z59b08J0H`m=+&h)``oMI9%5owrLg(BXaM) zQe-2n;H4XqQPF!MyAj!qXa#d3_U?0ksinQNJxlwL-Clmjl6G3!KMPjumUfoC9VC|X_M^DDqTBV?AGCTc1wGSYlj!fmTs2zSyxN@pI>2VZ#Wt=DW(f^^FOz= z)29AHOZzw!(6Y3zxmwzv-7W1}JpHWSoNZa!ak!S2HV&71E;Hk_v|ic;xrX+(yBFuu z%5X&X#}PqTiuOV{x42dpUWZ+apliE(F@cUN;9bN{k~>eXg**-KvH~ z=e&DCeSmZeJQZzLh$K5{2-8Cfh8Wxgj-evU7Lm z9x?C4V{wYOosH}#w7a7{iKqBg{e8$a(y#8JY}K#6J;Cs+3$OjJ{Hoi?qs!QB?)r*H z10&|H0*w7vb61z(t`ui5;a@mYD?v<|DH=A!E}fJ@%VTVN%(FIL7k8n#vOzO8Gp-BO zwt99`L+47JeT|#;x$VItpHi}-3|h;{v>d=ieUy73!{{klT5obs?&G7ehPWwk&MwIeqzGhlNWN*u`8ZKnZIaH{uo*)Qy#VV$L+oI6B^DFf%`hpySs&X1ugBX z$kI>@{bRwTWg-6`o@k->_#jhXqy!;cIm*qo&&V5jC(yJKDKYhLyg3SxfvgX zrwb$R_1q?Ux8Liz)!ybR4uhHsf!8NMm(w#$$=B2=@@*U*UGIX9{S^Dv-WMUe^AX_j<0H1gagl z*YhG2%8LKu%|Xzn0qpRWI)!qLErzwzUWKvgH)mRwavZLW_z#zQF7x1w|HSI%h`_dI z%w~~0zvdII_7GW{tmD!D;Q+y0rncR@t&h(*lEvSm4A7ZUtLXu)mmDadG2ePZJ=|8a z?6bMlIgq2NLJixSnIe2c09gv*Wj5?gZHs~S!N<^}Arx4$Kp)0yS_;+Z{C{7|zCd-cWM$K}oP@=w!YNP{P~08f!ta@Bz8GXcO=RVpsq)Cw#$x(Z0aLr4>LF+T z?~R;nEc}Pj~dHPywpyV#dL`W$G|lH_7BL3$0m8o8ttRpgQWE+ zWGoF0qvY{&WSU4h;h1W17@zCHX75hB^Q$`S1n&IzAbGp5-tc-umviL~n(4IFGoehor?$042F zBUTruS%&<*0#o5R>k-nID)!;^lCNs&iuhD-{C$(IE;Om;tc(#Wmx-Z>=`V33w%Sh2 zS^<^>jll1}^ahFOKAL=O-s?}qr&2Ro{}zYp9J|`S86aueKC2y3wk;X57wYOivI$8R z%vv->6JZ<3S_W~PaVE5QYb)N)f*#qQWE{is7^xy^+MZ;*PJ~oswy*^3Pcll0sGLR& zrJdFPD)y3!om$CTOLO&CA!)7ttz4+useP353+&W)sPCLko6y_g^f*XY;j}Z7!fQjm zVf~}KG&g$% z%h3W2z<&>^qlmRkjp}GL^dOI)rm>EMbNFR&(M~ip=3kdRiFF~+MG_-+}Rx}iOx&ornzgOsLBbLC) zm^MOj12%2xV0<(aw0uE(d^Fl;GusghHd4owi0Kj{$TP&6Kbn&+5mONrI6R_i9qk91 zH=wp-X{t8m$ky)~2Z88aT_tLoTCKiS#;%jky`(-qv5!6lgm*foz!841g;&*`tNHUl z_-X=uu4mL*d>HxMo(tz?237|X4~|AUn~6`yMTU#;8}&~mQaTgI!Sq!O$S+9|6bbyvZ6;9 z7Z({$4mA$8BErct#NpQeML0PcLr{XWu1G2he;5L`!pR|AsD_i1D90s8L$o9hoE<(3 z^;OM}SdHz3lXs)7!s!xb#teK*k+e9ykqgyr?@G#X;nWr&M49IKXse$7gX>@BX{$j1 z!#4eAq|K2xhDOloGuxX+bLX7-H_AK0&Y37CL+B1~3{9%Sxr`N64+1ARRvRg@@E4az zES7;Q;Uqt^eFt4~L;NLRx~@poJ?%Tt_?TvuDzKtCdZ1(_ulbGKiq-BgkJ_ad|PN52|tcuwi_%_cOA}g%_6KNXTowN@E z{!A!`Q-ZSQEvi5w>=Go|kpW(0XU|gG7VBisNecSWz=sR8vPPvg`p+LZT8xRVwv-isw)acrRYt`aoPd*CrSL=NhIfDeX;~E#^Ih#f|3&@ z=Ip3x9fjUh)A|t7ifJw9B%9WibSX`1DqUj*BnZ>mJc=Yp;$JCYgnST~y)5z$#hh~&1pRPDJQouu8K560P( zYR@b9m<+EO$e5{7iJ8XHIo1CpW*Q1g%7~3+2a{!6TsGlB0i(oBXGGZZTWJ)e&BAcF z#7uVEEB*Jzp*H(O%9miypFAEL&kt88fSX2A+u@wVzGOT8%@3>G6~JlA)bMu zcl+^02_|D$3AYmjaTd=Uo^;UoP(4fSSR_rU;jc`8LrEO)(JRqg#d(5$9QAJ;9a!92 ziYnvmU-6L5AdpriAZOc}YDhl=(ucK;e3*tG@4&M%XTlhZPpvfI24#bG(>U;7hqyhC zWN!S?0&#D;R?f(ZY7A7~;JyN$7;B@BHWm1iLB-sLnC1;2QR|$qbIx+k7i)&wy>rqB zns6LGh!3i;me^mqt_h)Em&l}kup=`0Kas$_cUTh0fdA@{1cuvKb6tl!o(C<*I=rij z@{Y6)BPQQTAImAM59Y_iOq+8GCp%QtI)pI(# zQt4TDZt>!XMPH4N%twrsZ=ePzCeTe(U*Pftx{=zR4LTi%_V(b=)iP|PjfP?wP8f*3 zg=N5=27ezJX@_gEk6qd}cMYz0E+JBCT1LXCWzwX|B^1wr5xonQftkT~AB|PVO|XIH zdi*Csw%u+uD>$3^ZE!BM-DlePcAPz6gpFAAy6vfioBGMX3|5Y9ZUSsGbegv@4PLD3 z)|lqE(6m9dH|>reY#A#UUsA1iS-~fK!2IKkz<#{-dmH~w)nPRr&P^dK;X3NUFfeAlSZde9TD7zhocJ4;K(^5UJR=?qn)+zc`@7{pghOI@4#Y6 za`m{G;)fnZF+J|<_)`E#J3a1+@&=@1VoC=%Ex4DZOS=zoJ_rL5)>jZwWnFDfqwV)}o9o?Zf9iO9W_cpXr*Er_rWHfV~qajSs6rRJFM7ibB z!zLc5zViycgBY-$aV_U$M^-Q``d{sbj7JaPO61KB`A3nDL;vEj16V-$*ulxSs*fG) z2u413@O#vdj~)Eb9|9z|Bt8+V2+X4@!dm;eo~vlq(Y*#sG!JpoE*g6rDZDMLTl=!H zSvP0TY=rvIy0?rFKYY=nk`|hq5t5HIx$aYJOCbXis5^2D>b4Vw&*Y%=66iUC(irjA zB+2U2IRb?PY`hww6t&WIWm5n~xqEIG^|3;aJqPMid@Zjy{I8X4&>|@Esko0K)>8)Z+{1CyqwZx{VF?v6-BX1({ zx;qxD!oGnOs?7EVAuC%XuK6rB@OVv6-IZDUZ$t#bFh$$7A2}lU?g`?}+@s@3PEGH$ zi1HkE)n!laWwBYC0~W_vI&p{)#~40`5aL+Phia-g2EEl$aSS!Y;WX=HoB#Xx$ivK= z(%|^$;GbNip+53$JE<`3m%*UZo3YZ<<0eAtjif?PP!h+&_k=jY{DoS`6t858q=iy@ zSPN$(SJ5+9Ug%Rt3NLs30$walRNl&=P7O&fdVguvTlGbaST9Xn}k;83QoYS0X1 zPfQzd7_7zVe>)Le;!i0j65^xw;{%_KZR_!&uVQpJOuOuAM^h z{@AHwv$xN*x}?e7j&^Kt=zttGDgE2eZxZ-T0>4S%HwpYEf!`$X>m?AQA*gozs5#^F zX6BR@_`UOri)Q8*Ip=z{w4$PUxkaUgeq8g<{JdO$QSrIw zW~XNt=M>J$%g&vhmpkWNZ+3Q}H}Qtq`MI;b`6b@d7L*R~o;SwppPgSa=)98r1$l`B z9L1VSDKDp>peQ#xzpx~)*l!y>A}9K}*_NrboG;Rz6q#Qx5fDQ4563198b9f$zCWBV z@R$@XFQ1tr(;rJT(_|C01IS$?&|IElkVy}NT#zWNeBh3BNqLX_EfsqF%u@lCKkGKSN~t98sQju}r56 zI^K!0{UlNUs4G(*xF0_^UM2g#RN`QX{eTO`Yxt3J+oJV5=%e(dBQuJN3ZVhHc|(Rz z$|;dLySP$%q8*nYa^MD?FK=xK( z67Wr62Jj$oJwC)c>5R5E{^B^W73poj1bj$54tG|QfeFBVr(pa*`n!Fhfo*Mm;DSMr z7x3@EO~4F1u&@`{1CMST0?tl?yu6xL1{@7s3Y-jF0o)7R2|NTmY6$A})wE&2mB2FK zCg5t|Uf>Sk=u+)0s3)gI|Mv90w*`XPUnCw@KWH)KWf@KU@{=X^#On0YgCgw#VDR$-pMy zLf|n)s0SPj+zb2<@DT72uy+s0a~|3OM*t@Svw#bMHNcg?9@m3Da4B#v@DT72aC|Y^ zW4+D*js`9OP6n<7E(ERzt^~df+yv}Yf^w|GB;Z1zAGisa;K%yF`b!251ZDx#fMvip zfe!YSr888jF7WfQs9@fu=^C55GWZ*iWA6O4u z25bSY0@4T8HvyA?NjJ2$O#)sB^aCdY?*aOOSy*RBm4ScYXy8iVup6N_z)8S;KtHex z*3~`0g;+Ohfh%bp0XG2~fupfrz5`AMo`BtHFcAMin71Mn$eE6~3X_TeN+S=-XDL|ddfpLSOr@%zuYM>9e6F3`~a2xaoSO#1RtO33X z)PXI)9zp2IS(tBN60j0D33w0C4_pPj2e|om@C}@N2i7T-1GOaBC7>602$%xwUES6; z4R{l932-NH4e)1R9dPBH@E^cUcVQlJpQ_8<7%wmdI2m{ua3OFia3yf(y_g5!0pLF1 zara>!hC&a3iNNDlK+eGFzyit#E(5*`Tn`+2Kh_)YHsC?vN??z(HEj=Y7*Klv;|0zD zmH{^cR{%c%)&g6A4Z!|?f&Kx90~3Z}Jpz+~mB1|E8^AK)kH8hczpjK{0KWk41NQnW z_#UolbAXA!8lVsO3~)BE1-KNruLkQGc+^8!&%gv=3osez83FwRCIN2*W&oD~=K-&L z82tjvfwjQ9fDORUfvvy`9s%FyU_AqqfdOC^@Ht=^a2Id|@Z?o!4?Gvx04xBu0v7@k zk~QsFU^4JkU>5LOU>Wd&N6{X59k3So`_<4B;59&PB>V!fAFu&99+>zT#tobTTna1# zt^uwE)&UOzb>Pr7(C>3WAD9T7`2@xd+ytBl{2W*fJa#SQ1{@8n2c`jAfVToYqu}>} zNx+@J3}6Fr9`J-G(H=MxxDL1ySPxtaYysAO8-aHKwJ}&XKrgVzKe0Z57XYULCjrZWYk@VuF6+@AI1<CZon^rYk=o%z`6z&0QUno0X^qq-2jt-$32H}1IGjB0Ve^gfmOhDz`p_O zfqQ{1!1|3CcMAFgCIg4PfN=wF2bKY!2Ce|^1J(k6zX|#R{26!%c)^RXXJf%Xa5V4@ z;AG$#n=x+SBw!8jR$vHtKd=$_1W>y`(@xp~eF2UGjt6D}X8^YYmjYXXYk(JHd-y8w z8sL85UBIs6Fn-`b;Ha&z55T3s0^myEGT@8AwZH?wSAo5^p*`?CVAt`QHXk?;xD=QM zybo9a+yz_)9K0QJ1C9mO11ADofLnn*Qt`?Fa2W6~a1wCN4#*8y16%?85x5E1`z81R zVAq`(_l2-yz<$8{f#ZP(fHQzy!my{n$-p(hTY+`J^k%dybb6F zE_fOJ0(SyyfxUO3U*JUGA>dkIZy)p(I2w4uE6_7w3a}hl2&@6F0EU3OfsMeSuY&Ih zpab**mjY9O&j6aLVMs@z)8T{fPUb5;61=^ zf$M<@Z=yZ$9$+i59++?`)(tQjc-mW7XTS@AWx!d$6~L9iTHpu32H=Rd(H`gnCR_%& z0+WGv1G9i%0?U9s-a&id1;AQh8L$Dk1K0}u5txvHxT^u}fvLbOAiY^u23!MN0el-+ z3p@yH03P*kv#0{a1< z0*(hBwHNvhOaLwcrUO?2bAda6n}Pd)p8~r~1fBQM9(XZuJa95_2Jm{|65tl#|Ht0D z$5&BZ@57VJ0Yrp|sEAaLh)OLY3AdoA0TKiZ5J`ln=;4qYNHjN-!_6Y%rHY7374K-N zqNR#TTdJs3(R!hlwrEk&VnvIJ7A;z|R4MsAYp=Cu_RQIHPEfz^U+;WAuydYg&AzU^ z_S%=3S&8uP2sa=c{de>igf}AWPyxRYVPAyZ-bFu0I2K_Y!YK$BBiw^<6~YU*LGKX$ z7vWBXXTAr$JI8U(Mc5zVT?oq%K7+6c;UQ-VFo`g_9eP7J!Zir5Mz|T_od|a$`~qRO$rvX-K)oY;3SlL}13pB%A#6gp z4B?Fk*CG5p!mS8jN4OW^ZiGE6QLc~B-w{57a0)aoSJX;wW=El#6{^P@oy^ObiZ7b)?)ml?*<%3SV`x+YqCck z)NULygrCH(!oOzlhahzMu^zt>Z~}bPTf6bJn+5D`;GeRlmq`4{Etk2nwP)6;CDc8`^z7Blu-hHhPn0)p!C7|>l{37r>eEhpEzY6?B=;uQ|{^u^g5&Ty0 z@A&x5F257}UHkU6?(^|qx_qZxjQg$oT4(wAdYA7D{?FjMnEWV3tNvLE{u%IL^-~A_ zCGcVOvl#r_Y2sf6{$A+sNoM-hUiursuL3{P2mE$3qQv4f%e4fz(a+3|Y(O2c<^y{DmsXeDez@tBe>HEA4 z{IU%EI`Ch&v&T>Q+>L+4ch5yWUO}(aHiPonKG)4>Zad76JKE!+a`Xnj4E1s%{&wSt zd-Ylj{*^TMSA)L>_uKS_^0^Fl=^@;IFaFLQV&s$ReTi4^FF-DOU~4OeXD7F3K+YH^ zHY2?X$c5GWZsBP>am$l^zgr*O+QSdQ{crpDS6zM}_`5o_^0=t$bh=j`72qE{FFgHZ z27YM%iZ8Zn(YQ3jQ|mHhUjM zoO{9F0X|{IPjzJY4ABEHCq*8@>YxaGH}C~!9JO8 zINM934`h;%In|VD_W04@mw*q`gBtMnfiE%dpXc4b5c~%4HX9kmJuAU?Lm6&1@25Oo z?ZvSXGFL)okSSBgJlTa@^mo$t|IpvNhkN=)@qFyX)2$Qy_B8fuUcJ4OR$r~isV8~(o%6`$4+X}g2^pU4X?p#BT%C*WX*G}Z?4alka zjJAn}-KKXvehB^n#N*mb!$0c_zOHj?>+gO1Qz`-Ki>2W6y0o^IXBqeBjLjke;_JW{ z=h@qs_{HD{rr}qC@12IWqELG<;w1Yf!$E%=-=h zs}%h6;EPOtwiiFWQRe+L_b&#&tTMbGuL6HF_%K_zQFvP)QsoD~1nC!>`GbzkLKcbd zgd5Y9uP=Bi-w(|DE4=cRg71a=oni76Iet_8b>K&UxAjlr7lU7b_K9;M(`Ej zZ8kQFTXuqf2>FYf_mhn%=Qbjlyn`{vgG@zG#z=?0Ue_IE57UDR@LiFQi_AE(*Ey_rYOaS^~qZHC;1$j3D#cc&poWt!uaiN0~L z4stI+&TSWxS<5n%rw&~a*P-Eko4$AP%%t$T9}WId@GqKaWUo^RQ2aIEscpjAZXx($ z@I~hRhV57hp4vX&7raIc;yk91Be7ya{0Q^r_7 z=?lIuc$%lU^(YfVy1x|sL*Q@n@z=O@PzSyT>}x-hH~gH%;QN3N^A%TtF9UD$XGtHn z!@f-feCp&;cacD^q-Uj z`cF@Syl@j&-;ZcxLr>PJ0c7rGsW zeW(cJo-yRe=1qvW?bjC$Xz7uytyN}v+2^@@Dfq`x|2<6J@FDBKH{pJtpP9`IVAL*) z!LJ5iZ{DBH11#~Y!0!WZn@_3sM>!_-#JrVkcQ>OPW65shyiC?xwLjwN5Do8Z-QY;~ z0dE`UqsYfV@Pokn%0c!-%1SbokZFR9&zB;Z+f{WreITbjuF|Bp6pJ@E{N`gHAwi zia4JB)??NMoJZoL;G^Kl#=3kqFA5W11pXTEry(tu&l#u^Abu+N`}<(80e`!E_AM#_ z;unBF`iHHpzwq(*y8LqR4}zcX<7c}3dhod?wzfX)x$x{^J%aDD7;OnJY|rX)VHBGHv2?% zH4pqDY4~N}j{|S(hm@Di$V&ludgWDa)Mz)|Cl2!3&Ox6)9^>C=+?U(QkTupKI>B&_ zh0G5j1ZW6lk^iz8RH%V|gUD++22r2~n2%*y7CtSIoEkof{Ks@>@DqLwk*Z4c5pY^uE+6i4@?aCQlNSRW(%Qvv(5 z5;DsEY=V{3=~(Q~0?00lOPo^Z}m-9wWXNKW~kyem@%g@!-RB zvj+U3;9>5(`;EQ*h2T4ZA8PVV+?JI8mEey9KhET{i`_QZ0DdBPn=Myk6#Dyl;P1!% zxsy-!@<6&Edz(>kdA;D{LC&XhBs0Rx%RtCv)r7ZK1^6!D)5S3dGN(c&OegLDUj{y` zJ=TIB0sb_zK9ZbAD(^0ocPjYZ*(mR|&@646P?nqzd9Fb9>KqHd=Hl=(1yS(*z=!3d z2z(Sgx}ukcai(Fa@C7Ds><=vfUx53=^kzBuV?xrWa&Cc5>jwT6{GIzUJVm3Nvizd- za|hyi9C9a``G|XM+5wTR4@rmWsSo&HgAcP2qrrayKFmhcfbUfoUXKgGcLN`$4=cg{ z5WLMsQ2sW6ACe~i9pFy{@6$=c-|KK3`Um*1cI+d3SUZjeUx)j{+OY=w6!2mFdm;Fl z;KS_0N{K(rH{T%lhuMc6;O|5HVfG;k`|%L?`$>3m7}xV9dA zF?ib?k;<_R{6z3!dQA&4#E0p16nr&!TRABHBJdU9!}NM8_y+J{?XUp+RPZ)kp!k<( zxPQIeAJ&fBz|TkgK7BOW(LslL6nxmY9tHmbcw70Y9V_wQ8t|$eZ$V-q?O20&Rwu*r zu@L+=@V0uQbk^fPdiHNR{?0A;r(^nZ^ekrH%y2tR&uESYA7-cXpo$B?+wwu}(I0#> z_^^Ig2L4*`VeQ!j{xJJh^m#S-x50sJAAF&CzsxU54>rJV-3DIS>B;zE z=$rQAsGYVTp02aQ?ere-r-S$Pi-4W(*%xbOkg>I86ln|tKPN*RQz5egGGX<(0Q^(n z!|c;?;R}$STUNt=S`U6B?zi<%s)udh*MSeSPYx9Ab?{;O6b1h>c$HngL(l%$Q-w?yQ^wc_9|nFpc$=-Fa!vt1AADFj=Yd}c{&F+^Y(6kS z_b&tg5%_UF-kbBT1K(|acw21+-vK;aTdysRb&tK^4*(z5CwgMZgKLWf>msI(|4+I}p|LedX3*M&7Q51PMY~Nt;)%ZKN1&Fpy#=41vn`c2L zOy8s6Yr%I#9Pa(H#)KH1BJk&fPp9wIka++yVfA=5_{Y+uu>$>%mI8t~VE?~1?Od>C!A8T=gZ>FgvuqrM6_JtbyL=kv#Y#uVFlvqbVYc(ya2v4_^@`N zI@Vs-O84j;0WYPwKMxMbCh%c?NPiF?f+w5e)uXo#TL%8b ztL$w>?a&1NN8phS?|x$~cnSC-@L}a!4SsBz_&0$+D^OJC$r}t4D z0p4aiNMGnZ6(!)qbh;Y+dEl`G>!r`fhE$)t8vKReu~g&n#=iOr@Cop?af#A@0sQnd z{C4m&z=!28_Y|B(06)S^-*^tAH~4$OSDJjbvHt`94e+-9K>4c%zadTfSA%~C{9$JN z#&aqw!2cEec_weneO>@h-z^F2OWVPB2S41rU(R$;{&G*n`!vAY+9wLWH~3-T=b87D zo*Ozm8Zt{EGt87RbhrlmYVct?xDfm^;KOuaCHNP?hv~ou@Gqs|cYuExe3%Y&K*qO% z57U7@;P-(K(}B_82VWbm12y3LfDcQ5A^6k4hv~pd@B_ey>A(i?4dBCU#18OD@L~1e z0TcWy!DIOF`k=AD*9ZI^;KOXdXz(w94=Y~{__x8^bgU3TK>~<9soSHlf3xP@oZ=x@ZG?N_3_c*+kp=)Klq;DL(3073f?y6 zVpYXi4;yv}_$Tpq?$eOc<2LofhrN7mLOd%VXRD_u?%f4`J@|R}+ZTt?m%E(-dvRTO zUmFPih%|f!_#WWH>LLmLWbox?9%K=NbYUs@Y2d^9+8Xe8fe&ko&EOZONq;x^pMwwU zYu$=)rVe~qUmFPiHSl4&S^@qo@CbZ$tj|s*L3|CK+SP3XyF(qSab$oYsQhy3%S%rh2Sf}k1~0AS3ne4 zCHVQ^XP7*%1F5GADUNxNp|1xWWy%v>PXZHH`jtcdT4!C(=1+x=1S!@x%tr?2O!kU1GLVR>8t{uuB@h|kRf+Dhxn za_}R-hv~|C@T1bizYTmL_%K~@M&ex{;4ciMFUyX~KkE&d8IU>Jlri@Bi@{F^Z_@>; z$7=A4!H3ns)!^rYf6$CS`yRKQR)EjFA$(r>0{GLxPxsyLwc~d1SA#Dyd83YVi(xat zht+X!@GHUF>X6D;4E`SQ=bG^w>$cV4-vFPkju%2E@5b={wi5h#;3xRf;Kj%&unpj^ z1D~$H?S#xm$b|K`P9=Db6nt2J>kIx}@L}y(3jS5_VR}*reiQgGo3a>ukDKgeqD!v@jNjlejfP0fG;w6qm0YI?*boI z#&zI#gSVBD;@=AXWAL{8MZxa{f7wsd*FkhN)@C6SRtH7ke-1vZPfZ2?Gw@+^^9A4^ z1>fDQ1D;wsl*i@Z9|S+kR(9r_Y?GBjO&P#KDAMg#q z`{leP-9H-q^+DcyQ33%U}g!;F!f3p!XFNMTGdE5#9@y_A< ziJh>~_z&<$n03V4&knk!(--_g#GfF3ROh^#vd47peq&Ba=jaW&C7t^$judz9e@(m5 zoeQsOe`e>RhR%hYT{e2RIu$%FV+O&WzmA z-uYQpkE_}{iz6Rq;l~=O!@P&H&V~}@M!w8-?uzg&y$XJk1;;Qe@|PTEPgdmiT<3=D z$fr5ZFLNSS<~loa(3&XIp>rX9PgZ0{w)04K4C&s(w!7#Vk}iLkCtzuF7_<&$bVr;-?Ab<>*(B`9r;~HN)bz_ zP?V0&ojH;Jc646PiQImm^H0jc-MNw99_YN88~N*j&MlG1=Lb4}i9~Mdrw;k^MJv*}V5a;fkkxl6MCb(r&TByw#x z=dDQOKZiQIpil1}>a1uVxv!gZXNSn|x;g7Q%mK3DfXJ?H&YK5Bwsdo@?|1}|&kl?% zJk(j=De~B%&WD{MKsFu}dHGOhVQ2dLQ5CM)uJma{YKScMa3`6CvbvlbnVt31td4jt`w_E(C=VkdW1Kk2lHAE5a%s6kvkoeb zoS!wb))H?w=RdqcLn64hqztX$%c?lpZ=yx=QEoe3gap= z?jv}r{H~GwYtiL`>r{eaUja0JN)F$tf1e-tJx6|b(g{TQkAvj*$_{*|@~wcaT*SYR z6kZpjhx}eEJo#;OVTPivFZc0udby+rQ=u+;PZ?e9IB?1^O3@{-Ge~|P$grd4Mfh9! zn}Sgw(K;*P4bi3RySotG6zVwbC4{fRmqeuTm0cLt`L2|VVn(MfoxYk&0?~5c$Z`Qv zSI|EBy`?kX2kmX7zoa;%&+7Li;r}bY`>^=;{{NhS9_a-7NBOTJ3Ckp$Dq)j^3nW}3 z;c^LAOSoRbO%iUCaF>M6F^;U zNw`Zwrx&M3&&kmhm9W2rjDGw7)ytQ0`>;S1XO0|sO0>^8)9^{YnbD#B2K4KHQvQ&c z>SzA^g8u#b5Bwp+f%|MfbKo9meKz?VXnUdV00xnRUQubqbDeosJmTp7X+(oq+PVGG zkGFSp|MlY?9Ie-W`~XMy2S47?(f!Vkqt^#JIs|eYSgWWh$$#fK2RTtI-q|U#v~!Nr z#VNDmdCt_{w)hWrv^_N090#*^`XG1U%5e^HUI^HA63M|!E#@3=lSg5bHvBNx?wU#D zIEOph-um(G*nhIcbA)5F1369)*KYdbft9D1iU+P7tg;qa@gD>v*`dvKK5q>YG~Q%m zR=p%p&twh>r{`wO>lneEfZu|nQ0NssowA>DK6P%fObk4=e(EJ2?GNFny5{2lEGM;| z?*MMg{{u?CtCJ_~uG3ww@Se`@JN^0ji^z8qc|8t%C3yEhJO|?TEa=q{0lYhKs-L5- z#ErPdao~&=T>E!=yrx{(@_(UD`;!o{I&jas;dYJVqPEoCo;m<>}8NY}YNO7rs3WNg$UnBDL+y`AN z1n(?);}<{bg}4oaY6< z;B6K>SLC}vF`!k>>BAW~S@7Y4e<2y6cUaTa0-W-5-{<_hmILQek-r@EO4l+DoM%OT z_caWR6#N~*``yaG1i@*7OZgcq6+B+>UV`6s3Il456@Sv=6XmCmBv>l)cMJa7?F{@- z@IL}S82xv>^cU@4y)N>@7P6qO|6PK&dxCMbZi+uoYsdLKR4vlu`2aF7xJCd!1|`sb zc~qfTP5@5%%)5?(gy2_8JbK=-0PRHAqk?zEdMsUW4xB$ITz(kAUWtF(>kJ+v+$1=f zRG)ME^loX&Pod0DH2$cPXIbi8|rF$de zhjHKx61?}P45)KO__H3kj#ETcaEr(<&V@n1rSur29v+fYo$(0Ww{oa{-H_yaI&>N;2Ck9nGZYh8K-IOV^aDE{w7{$-J`+`)kM z>pNq@OX;5S0prJt{Mmw^{{{oPT=xooy6B=60RVuy9T9da<|(-FNA zGw1XdymudtMbyX{2b}WhY-jvz=|{`Uc=epDm<2*ZK84uqkmc!Kt=H}GB}V+KVcUoe1C ztq+rdlfR_b$GXc+3sgK9rygQJ_m}m8pZ+1^THgjA&h>Cb4%;i;zDdESUc>VEsjj8? zgVK%4dSq1aM}bqh-VfOAmn5Di*RtR^k}36L8A^*uOEL`}J=GZ@!uF zn?!!Q;Oj)6rwcytNRDUi*9_DO-XQp{PZ`j5`w_u6y~X%BB7ag(jz@jO3fO-Hzf$mD zOFz~1&?@*tSFs?}Qe8bza4J`F8UNPuqXpkAc0l**O9gNF3(ISL_zXDJXK*~~0L7;G z7p-S`-A~5>&vQ_?z<7NgaEhlvDu&(>O4pSVPlrG9Z(aY7i#(l2pbObh*Q+A`#T)z^ z=1yJxph%RTbHx7i6TDvV_Fple_3bXfPusw_?nmzer+gk?$@mv~#J7C(qd``FU0FUjWZTd4vAgZzP_5 zPq3hlADLA7{7S~ni4xBg!8g3jfY!H9fs;Kf5_?!A@(07Qq4NGj{2U~wt~rAD7kj1k z{5QaD_3%59pT3aq*ZOuqZ;t;@|7BdvgnBOvwc|BX4`NoFMI!%YE6Y#f!1)t!l3y{5 zfxd#%d!q<{rI-P&KV6UGbo+kB_&kw+MDPQ4G9b}8-vFn0^nO^8$RBgOy}W%w@M7Rp zpF5x82z34579#&kkze{}me=`jcLL|a zI|6>f*Ah=~USENVwdw!Gz^Pp-rQUS8?i1W;&lRli{kP!3@^(kY$nGr{e=M&97vMPH z6o1nl{JTdEhvx{s{(k+K4`+dauRnpIuv1b;~EQg^}sEBGGK!}A0`4IPcrz34Uu z=v|_8)eC<3-}(2s95|~5e{L@WMS>p%#in}J`>U{1HeESQG>+;S)zG(c~BjdG1@AS*(`0tR8 zsP%J<;0?oB@&UOa2At~WlU)qJysPUm;8FS844#pA@}!~Yn*?;dBk`P)&4AYPJ_Q_q zaNT$maH@yCGLCfNXq+h`f7^!)=<;4Cc=gqcYd_=x6_4C(1P_V))mJj8?e?z)-+B+@ zF}deG!QXg@0cn2ckO7?kAAHGpk;q>v`12bW5Od({1y1FH2x_=URConGj zQ{?x4z=9)0p57@y^}Kcp128Y@nhl)l=f02mcctLFMLxLResCenH@)naA20ame=t5z z;`y84Z@j_))J9#=p&ZW@uk&wIm%8p2yvO7GTesuy1n=|`<6Sv$vQOc7dWqebAb64B zPi|*G%$#!vaHVeu>C*lES&`p*tsi$z<@nzaJFnZTm*Bzmz>5U$DC3LH=WT*NzK7$# zkOSv6!3(cv;AX)O7{=*-C3YUemb%6Ze&^TxTj&2u;8d;$>lml+9?tNVH(uV~PvYgiQVS<;w!ML_Ra|C~83**Od;JhVxaNlIN;Ez7bf;#`v z(>eb^JA5i|%FnvLviwAe|9Ziz?`1&e^BEP72pIuA*Guty_9}x~uMRtd@kyKg_$a~0 zf8@t66MV}jjAIy8*DHdr{EUC=dN`wq%N3kY)d8pcIG?iou^c#$iu|LJL6|jly)5|6 z$Mf$U95|l}9^9wvF`U!Aa1;x^CGr!1Q@TZK89=vE*Igp7&&^3UbDj}=$#E>#N95m> zct)&XK-d4lFgRpCx5zl#N#u_MPU$WZd6)%tRS3R7>i=@Ve<}DRu>+F@e^2l&UofEU zM*ool}q+ekyvR+ofLcCTZBW z<<{lEss4k0I6d=6`3d?J?`!#=a0F*cJpU8??Y}c1$vY#UXB2;X>8Co+jeZwUUCBv>iw;#e}q_pXjUU)fXefjOBQ)ypI7fm(C=?XDwu0>+`*WfAucox}HB5 z{EdehFXO-&c^1dt^J)fAz3RFExLVJV^M0^&>bgwiUwDLnR}22M;E!C%KveJ-f!peb z_Gzeo7Cg&>x?e|28E<-;ah=a8g8!;rmLhbVKNEcZtt{Vz1LqIGNgsmy?At}Yr}*th ziF`g3L&qtQ3Z?+3eBSs3qdGr7Rr2u1j$>Tg`G-Y*&Ml1h;=p-B`c>4()&(bd$(DE_C2T1*k znRA{4PWrGd;NQLroa%Y^B#x&_;@_v_yE^)uvDU+5QGt|yeXjc=kuMkg)<+oVC-}93 zFa9Y5T0d6_UL*VUx_-V8T%X_WBJp%To6`;M_gw^>@*lJ_*NObBZ5)Bl|33u}p07A= zBF8^P`knUEY6TDOL;X_lO9T1eCwR8#kFJNwXgI33&$Imc|A64Z{qa`>5AIiXsNi^_ z*K@hF-#9{WeV!h}gt{7lca^`*;F=Kp7K!KApRn}ta?|UAU-$t7CkWpC9IpRi7(eOK z?RC1s88iQ{68Ydd?R?TUk}9Lpey?2m%q_b3Cpj0Z!HNq&v2+nguz zje_64jR76c=YqFe$GG+%E`h^CdiB?O#=qgfxfeLaf9n4j!0qaKU*v=5Y8(teBtLo& z%N;86lYvwGFQK2&RltEWOXSb~BLliz&jP3MOFw_0?c_TWPjLSt=Uh&A(FTsEP~tBU z{FOES`0o(>ELr!{>Aov?`AaOX^|>o5mde%P8piebH2^r3t2Cew=Zbv8Q~r2f5xnCf z#t-Ab*)I6h2PA&(HqIgEbNs_kWxTJ*p9GxpGj}Zmx?fBZ`8CoZbi4mp;9B7jQl|V%|fS?iWLWQ$EN1%#Yt8`1+?AAIyRC zp5WL1l>wd4A6&@s& zzhS($$Ui9f8tIR2{sj-t>w8V*c&6UL5$O846u3@HqE^8*z^UGfA7@m{Y!*B?f6R@u z{Doh#yw2zOf_Hy{ab2Gu04MvC49rJ96Zx&uUykP6oKDlYeHV$I7YRNXIOX#XqF2WV z{*cH&EdGO3pYxi?A1L|MvPDxYB>MFbjyKL{`-r4)AfIo;7{Ga5o`V2Ab8OKIS~~|@l?FW@><`P2_8HT zun9Q%jrzH`JjwrO!1cWXsh}eqLW)0Se;hcq%S&Tf8g9J0YDIqjfA}}5U0v%151vEb zq2duCBlx$%Q_npPL4TukgZ}L#;FQnPe#?>QvQYmdJh<-kzKX|4Q2yK@^1*YV!|FJm z;Q5xz1%FiRSf#}CTfw8BGjOQj?cjes|8N&rJv*MF7nrl{Cw%Z zy#;?l@TspepzT9fbU;e?>yH`N^)m{%{#&9@!BmB(p8vT*;wgBSrB9Tb?i2jqA2NX9 zUS0nY{J{_Sx6aQ6joglFCo_(0tLq-%l+US;@NeB8qfLyzEb(akLg1tidx}|J0_SqU zgX8rB5>H2|2c4g;mvH=#Kg99qes^*RUJ9Jj%|4CgM|0rRi2Otu$7c!tq~It2iUFPf z+-6R!x?G);obFR!u-s81f4bm7zh$=I-DJM3%lm-f&;OYt(0<4# zz{!7JBG2jS_&d$ybdO)f^16)Wz^Q&NgI%HP0S@r(9F}jsiGdddzfJJ5uQ70l;5!8m zj*rKpp_Lv^V8OeyI4lEB^?&+1{JT`*xm@sGyG35`k0hSp`M`FwIi7a^WWm8AKO49$ z-4!AqTzC49;HBF*0^NU)p2P94mGhSONc=N_Q~beom77HVUYVC2D)P@MdHG=ke-rt< z#~2(c+|hG6{^0uRMBr3!3tnNtK_dS!aBBCd^8DR#f^U|1g8R##NIYe~WkHF~8F?wk z-ze=1Go`NQ1rI)7@TK6-?_jwTME;B)bN){dM|+;&lYvwIH@wY2rQqvCK6w@c6@qUU z`Ji8#jR+~8;CZkKz^Pq^m2d&*8;ISgVQt)BYk92?Rynyo)+|SJy{O+k7!8zjJP5@5rqTidK z^D`ef>8E~wfUeIwME;jway%Du;JhyQGm;;j&*QJ)`2Tbz3u=25SFYE?R?fBIxEO@lYA9)qy z!E<^gz{#J{?|Uc|`C8zVpK(tx&`JdNTeCp?IqY}@lz$u@9ewKj(!EX}0+Xe=HDEOZQ5ALfv*Kj=g z{S`-u{4l{EU&w&2&ql!ymUh>A^_bv&9%cD+B%V(MzvEU0h6{ecwbU-DR}bJ+t}9<+ zPRCQBp48_%`d-I+7+lYs2%PdW2lYf(FAkh$;M9Lti(k=0@FgPuzVy=* z1buus9jz4cb<3mM$h2X>AV?g^A9j<5j({5v2+w=Q@Q~wI?7q1if;5tB; z#T-xPe{(##ZmR?jo-Oz@Q-viu;4X95%~YB`60x5!`lB@60${)^ya*Zc8ff6D0wpC4%!{A<`V zy0jkNAov`qf8BroA$ZUa?|n1Jf7@dmkJish;5u*2@c+w0@D~-H+Fl)Rp?XNYdIP6+ zyyP3^biKua)ANS<{Tces29aO*Prv-zg7^C^EcY z%z(B(8w7vhAB<}~?{F*YXK>x@WZ=qP!LHDy?eJ`oUn>J?jA`c{k-zO#1}X*LE%<4I zpDTDF`Z>k_XXJ}69seBQ)L%v<7(XqG!^I-MbO-`EkAMeu^{H`k*I7IL!;FO=>y69bk2cJ9pt;EwG?Mc^Y4xGOWuHO@-+jpPf zFNq!2cJD~oBT6@TK4-Y#L4TtLIMwI#n>fK@N%w8RyZ?~^ZHIqwC(8%N$6d2+uzOc{86P#b1EBNEDv!Kq;b%GCXWqggq zLod>${G2cIj!A+KznAgf%ebTK{~E!2{elH+ayWcJ@W==JTlb@0KjU~_!8lBp#-|G2 z=@UPGzu-T9g7K~#IJ%b}-7a`3{7t%AIBd2Uzs}FVpEKT3%5|8;Qw^N*IrcaPMhQMo~59M@)u zd~jZWtH>{t_)n8`cPM%JVFdq{c!K-UT_2G8{ECGilzRpV9vpu!0#5B7JQsJR;8Th@ z0e^l_@q9;23_avU+K6v|;98d5Z??~X3?rjqB@e==d zkze^222K=ww#aAykb!-I-wFI+#H8Otl`Hs4iRZtMGNAj>D-uuTWX5A6f50y}pI3d( zfVMLy3m!ZlezxG%(jRsIS}pi1J2@V0_x1v(@_sPIpY9JH;&jWTK6O4v0w?*UXS4j& z2#1%5{NCI7_X!+0KNoyLU>)N_i6{7;fyl$0?v|@L0^Q$_7Cg9~TrGIJmswux;gf>D zyPEMb$P=DqDr~DlMHb*c-;@Kd0<?YjXur5oJG*)DkSoO8~vIQ}}ZpE{lk1rP3vT@IY$5AIJb7y01(Qa%(s z_@11je$D9y-!~EiPVoor@O6S;dJ0#V?(eGw|KL={M@W7C0XVJ8>Gz=K3H}e@RG*PI z8R#nb_}_54!ROr;2wqgff=`S5y}&7+;5yqIf1Z zzbdCX(VUo3+mcK)$CCB2s=CI8M2i!PRX4_F)HP0v*Tt%njm<5wIQCSk8ta?t63Ik$ zzry~5``d+L(`y@QWAWzZ_}o~cA=y0Fncf_)PsFNc*4NL)Eyk}HB$GbTrg*ZZBGHoU zSJl+y#Lg>EmgWy_s!dcSX4kePVpWX|Ey?DYRY|4_W3k#siUL2!4~@lUG|Y@u&6!hL zkdNFarpIU2C1Z7sRTsya8tZDS=9Wl=1LAc+<0ur8p26VY+8GUv%?bP%h?`rI@nmh4 z%3W=|uJ%&=YHWzb8>$g4XMle9udQ`rXO>PFF}xJF%$yb*6KknzP9z#o$WarAk1L6l zj4zJG@XJ@sYCnLqno$6WXTqpaC`9oskV$BJaFBH5b(VQHklQS9# zVlmWsJ=Cifnn$fMrVJ634?xB!KPo$Cp@;+O8)qd9A)|Epg=I6F6ZqFMvo?t`Pp_>@ zl#~pd7H>(Y43{ShW5v{BjdPJ>S3#_48_`Ool_zy+ktr%3WsPdBB33?BWzUFmKtp17 z%xw%y{gf06n<%L-JBzBbVv><&e!fu@($p|+U`w*GDNS=&>%?swR4^JxsehtG)%U#rd4Pr)2}n&~5XF%t$0l8yhbkUXzGdv)+v_k4a@h z>q%jCjT)uXwXOAsvREIV6KkoxG*L3~EY8``re^4IMZ76djmw`^m3ko(=QQj6Y(ams zAk-U*g=LK`wbai+r6iF*^z51OYG`R~Re4igZ9{?z3_+tn<+1#H;Z&ES zDldS-w6)xWrojj|q-oedJq@a=OT?Q=zAoNEMzqRbZdEHI^Qi`HYj8)UR9N7X>rG?STa7N1P%({Gp6h;vvz%kqKxuh zf_$s|mlu*6AwASry{a$OSIa_gr((0}VX(BAS9?>6u^p(4EVYmkzuUp`^OaF$vzVen z;Uk_hJtbzhKzX2X+()OytJ#{&^7TwEHQG%NPqD^n7r|P^Y#s?Y3Q~kw@L$SMdlM`2 zRR>g67h>jgTg$DwSB9!ChA%D)RZzN!(^j(BsZ0)tsUbR}ZiA+pn}Mt+1L|uV##F<~ zLk(b(g2VV=t_c~kQG~*o4djg~w>D9&)H7peG;_xF;c1%BH7X+)i8Xm-tb9bq_K?V= zInc$%>2U^5lGOS4+3#%bqOJRxO%<-@(nuw4`?_9t8s`bZ&?>9Gs9xwfsTkDQiMBfS z))-3A{v`!N;6ODsH#Ws*VDyY(qM~e2yrl(m9My}f>&j-;n?p#yp_pM*j2o#ZET%OO z4MM)lJa105jjv<+t#pa*TIo8CR&w3^L$r5Ni%Dh-Lw}q{k1-YFFz?cHRAiH8s1@;P zbu?W|-z|NHR$C0u4Wfi}>(Nvr)ISPlbpUxquD4H>I(oQY~4*PKw(oaV%IloS&;HQN}NoZFNLxKRVj#uTGo$PE^s8rhaf4$aZk z*i-^Ls-~)#_@o&+)Kq4W>ZZnknOWn9=(tJWO2`6BOJtgk2DGFkzkfB)6v@w1lTlc9 z-SgYr8m^#fPx3fsG^_c-bk3G#RPdf8sp;^CzMYStDTMsabiwYqABTm5vGsMSuQ(^X4$Z@Qt95<#fcSGV9hSVN8I9Qkg9+L1)e7hy zkJ=5hVUvxi3N?*UYSXC>Ogs%W;~8hHu69~gtg2nP+)&0J`m%`hbgt zrv4s16KO%aFXFltZh_FTsOPE?D|D7%t6!NcjB0F1V#Ts~Iy#(R&9uL$rq*iKiPcANp%nD>=mZTDkvB}4XbbQDy-b3tPG?ZZ-d6c^b9NXj3#dJ+)^>cK;_B<>as=YGUW+g~uzm2Ik z{}>!AXU7If8`UmtqjkuzuV$Iu6;5x22zQDkN}nrJ29qvsOh)I!99q5l39is-4Haiu z_qIvn^ZR3wVa}ZRwAxwuwDB>kz7~5p@b+WmJYofYdSi*{>npo4kfsD_JVWy9cpf*9 zR~O(1HPpeg@OS+D0T_zC1wW~_`~k}ODyxep;Rx4jN7WdC!Yk9NJ+zV#SffZY!@}~S zyXJY8k?4M#0Aq!(sjj4siryAa#=3sZ)0DQl>Dq#j*$KMm^|k(Xvzd7>n`lVtd*l|B zsEMbg7O>saKUR`IsM>W5mFiF}4v&==^Yp+SgwoV}{*abLvY0pCAg^{~(oA;CldOiB z?6kT3VAT(!xaOMRc=(XmQvy^-#bkn?n9U_=w_r>|bz)8lb_{9Qw%NP=sRo@HZ@e-KZd-=&a;YYeYL7#?{~^;=QNgy& zPt|0dc1>v~^St~as{fCxZEnVvYW10o@jAl-OV*Vk*$?yTnq*fI-SN>FM%1n~ubS-V zXoyA`g1w={jAraes=d;9LvqYCTI5yZFZfL3zLc!Q*y*DwEsX>IjYzi$fw5U8(nu=P zm~QLzfuY@N@ccpKeHp5W!GqRvLcKF0-P+~Juh+$lreqz_V|(o!tl1^8+v;jN3eNj> zAu50lq8Ck!SZ!S#IcA4<09M8PE10}HY|NeGKKm$nWHU%}N;U&<@38CHh9zTv6X~)l zZEVKsw3<;T|Kvwg{Fs{O!bxko&dPY|{i|%atrU#x~xSS9adN`aBUVT9~@8 z&#|^_HIfXvox4ZHdoJd{lWK9jEeOo2G8pgjA!>}}WGv2?tv?5SFj}^Ub!w_XUd`mv zuM_JAq}X6q%CTxWJ3hB1mbheQyiN^wTyA&Q#ovAGO^~)XdD?Be8EQ@Dg$5y7_mF99 z|JX=M0B1T?ZFxyGe}Lxpf7irX5YMK< z$s66sxw+$mN4Pns_BK>QL$pwP~asY3k@iHn}^;3a6#*6*H8`r4M`kB zz?QSJJ?;T0obe#vR&A99d=>iv6Pc^4rLA%C8R&;It9in%mhRnsfY^TQ)RcH@=rk(n zlUS;6yRD-JuhhwpZ;yX)ZA&rsLxOA6fvK5gE7wy$qxWbtC)3Q}x?1?EEZ?ZTw6?^Z zItM4CkWYU2I4rn{FD4$jZxZhxll6Ko)C4_LHMQ~y;;P%G-FQdMV}L+cEBBTQT$kFY z6@P--3Ghzfs9mTw>!>-F;wT=*(%@QU%CS7drlzh|dTRlmSg3Co7(6V~!8ASBtsCmY zdRmF(-SwpM#=4f0+BD19Vfo6Z9kmLq6ka^JwmMlO1Jgit*rE-)XsREkY@t=eN_Yot z0_+SG9C;3HRbFHuwQI(LC#{gGJKQ20HwHQhFF42!fIkJ>xbE(a+V@@Tx>i^fZ;Dsd zCg*a0FxNH07gO}u?=3{CRTMRrwC#ihPHl{f;Y=%SB;(v+Gmii1jd{zuR-j&diealq z|NH^#>FLiVy8dcIB5H?}8z=GONu2GkRw?>BLa=X2mfi0EZ91b-Q{sxrEW%JAZ|Ea0 zVi4NutYWd1>FiygMnev~`nsIkN%geBpR|m|rfsk(bo#laF}(8m%Giv0c(iIEfSxGu znE-S9RXdAje@bJTY+cFNx8mW#H>63GmuOGVUwCgRE-;lgno!38?>~5CmZ<^p>S}d* zfeu=utk@XG>&Q^%w)7ng#uFsowzs?6lHo&)xjkgAK^QI7*0IH2jDvBvlwU81!|3?bOg@%a}1^vnZ7lv;`=XX-bGI_TE$1~5~ZFt4B^72dIP*Jnss zbk_z`WhUK9&VFPr(DGg$&GjT+_zCuVcNBw)%1J_dw@qu8yj?IX`TifRou#&bS-SAm zvXB{0zzl`1kE5Nw>n>er^O!1R+pI(1PgOxVPoMded!U4Ad>YTdhWiN82~(b4!`{Yz z9ba^tG38W;T2#U!3>I{0l=sG_u&1u}dlu_EAnFeGZeMl#0-eU;X;;Q10&VNAm-$XA zxeveKTn3z)W;`I$INfYosa%wttQwoDkcpK)!3>MwY4(-!`=gL3y4s!R?P&7Z&1$!e zrsUk9O9W2jV1)%+8!F%Cla_AHT8)Q3Fq}V7?GsO|ZJ2RpbK}e=BMYJ|qz=|0FQDSI zuQ3y|5_cv<%~zgmNFdL?u4K=TxGil+$<>{<^c;VS>1E3OG4Hm9@N#KRrOdS!uLG%S zV#@Y-ue~o>W;zw=Na2_($Xp<+#fg8fTEmLOgtz)bok;&l01?e^}t`d2%MgNRDe2F$bRm)@uX4Csm}Gygrd8w{GutHQ%yT ztP-wPMTf!=^Qopc-baUZDhxLC{Vc#}F$gy%tc z)!v>5dz~5w$I&1*2M%yx5HrU_X9)L&jpF(yZx}bL-fTkFu<6)bupNBy zE#$~4jdW_|Zw9^eV^sjZDC$1-9S!=Ci%bKQUQ^Hq>i<8Ovr}vETNl(;F-|LzXJB*_ z%Rs5C!x*d5pOmon5%ol!{oDjSMVB(8_wpoWD&-J@Pj8V)>_&+G;4kURY*5>C=mAtILy#MDrwi!v$@Y$qC0yn-v(%)h0YTuWtdSYk*EfBR#Kz1<%IvF1Y1zY|1(YRF=vXwvnqy z|KUM2eTMUlT3P%LCm209vzMv6yM3^b1hl8)E?f9tVUfB{Ri3QF8+Bm$t7_tSI}*QP zr>X=)6Gjmn62nV^8u5TjB3?hHisnLtVpzvaF$xfNXQ07z{V9eyI4DZN5J$+wkYgB| zL5G!8Ats^xk`(rxJmoOEp~aY%=$Z>22+@Ov9t_~hhnLl-_ePYaBjEaAp2wJJ`$VeH zTm3TD0VeD$8T$nWCn--f;)7OY<$Ref4i2r|Ok`#uL!e(Cs!X zy~L-rU_m%GW6qpdQ=+-0k)F{?&W+9LA9&Qmo{-&Ah&!mx@rF&j)86TJE39{?oZQfr zI)PMVaOSfbUfrgcAX=s=Z%QQOiBwP0wL97xP*UISc$Rl&LQnO0g_GZ5fh~&}$r|j1 z;)J`s$J_Q+{o|Wdw_9mO7xY~E;2g)l_FjM?X;dTLW;PpZC?(V26!AtgEve9*33`ZL zErkSUh(==8CZ$zv_nFpE<7MyAdeUcEFS5DXa+FRP4s*LH)6kcx2%d5CjeM9?_?GO= zozhH}CQx3h#rf_h1B2(olyBmm5Of_Bzl||x8A0#ZoL7i%=pXn(&$qa4B}(p1L~>0%f#rsggi0hy;8ySc-Zonq&c*L#&!>_ zmpkTz1rxRg-=tz)xQ56zL!>k3Bht^Hn)^Ez+ohI1*t z*fDR|m$zzYyP4J{NE?SCSS{!v^kq-kMKzJJP(bOW=X?dPf(APr7@di0c{u1Tm9nnRzKe+uaPl#;0-Yi z=QLo1s*X)ew9KrhC&@>S#LL+FJE-e6tTx%Q<$90aIIXs9jJ}k4&R~CJ*Jv|~UGzFe zVQpiJdXe71F*p%UZIR;mdr`Sd=xT5rS;m91ZGFl#oc5B_#8|y8OwWr=oiiH6^|-LR zWOuq~GH94b&+vuUoi$5sSmTF|+De;gkoR?=493r#-&%K7T{~%1lC?bA3VyHaWCaDj z$0E~jd!f2QrhC>5XPW()?;>>FGo!EA#vQYg{GO{@kFX$ARkTiDqWvCE=Y75^QsrlT zJY#Mo;C7F+meJH!zXM}>CqeJWqBZEm>Nt&kvA|lxS|!pP#LiHOdUj{6J@2Hd*_lo4 zZ$oc3ot-dWOa|Nxu9!?fhVmPF=|!w;T|Ix$Vj5*QGE>gfy$u!c50IY6;&Hs0~dv7UNmqM50C1*0PuE>l7s^QCOBJMek_5_N|3lo>Z}D ztvYS1*F^QUL|X4EP^aRlc|+L$)sY>kVNcUDo!CK**j9%#sgKz|0%i5mHiw0_FMC?* zU%Oj|-AuoZB*9TJj6PEK2))CkAFSJQY@hE)f@zXd1{w@&k z#jFJhbUw9{E}gF}?uWL5X0L5SItB40Kew`9vwdrwyRBmmexCW>AC*n%CdP28U#n{^ zoNhNg^|GFSNoyH`F}O=S>b*RA)5>d+^op)qg*<^w8m?YjU7eU!%deiIMItxx;NrNy z1L+|+?6uTkYnFksvg+_L45KUCM(;M+m()i4z8-(~^)62ld?RAo=iaBeFQp7T`lcI9 z4+Wmn7PhbB4PD_U`|XaC*J1YSsL5dWiTS`Yy5u+;qq!7CO{iqm8H$oB0MF7s3BtaO zeo9c@7?pX^n0v16O&>l2Yef{YDxv4z|NP|DC1eP;MCTpt45Ss;k}wSbkww* zUbEYr74?o7Rj;8>d4DHsXAaD1)i~r3pf0Aif2s~Q2FkAT|&)I zV5}-AspmDV3Yxy>_vh1#jnf*FM%}wBA>ub${hF{bn0I0IwEo+80`v@}`<7961eTjSsYVZ=0l7R49cp4}*Gx$bPG>sUfg>sb@gYy5`oh+H?x({q){DIZ$M% zy=91pr8D19p~{odlM0MfsScHwrp&DdH#g!dGbzvQ(+mdNi24Hwp4B&WOgEZVeCuhR z)Thcbb=Kg)9wSAYWrraN)RUP&o1I42tM=xW{>AzHd|Hx~k8`AMI+%&t6wEhI^x{um8RvwCZ&gJ_|(o}KUmm1Dz;Jr>0UXd~g$&PtoJIGkW#)61?lP4b7w0}Kf z|6MS5m)>i%)PpcuD3i}^>RFh}V+>&WU3^}T3i-qfd9nDKRSUh-OWvB}W;e|$K3X0_ zwN2xLD@*3affUx=`OegF)tXsmk3=1=-yct&^%mZ3b)qhg&uzig@N_9t|ImiTIvTL! zkaCnFTtBT<=pKU)S$p#r9}iG=r8%K|uHeZNuYU%fuGeXcFDT`Tg!4{WsGi;(Ie&hGza;KKZ9B$J4 z+!z!xEmBJK^ck^~Wy#RiNAXkEl8wO%7MeC(U2~f5;ELZ?csiv%?<)oIZ}Z86ENA)~h*RR?!}18)f- zQ`VC4)y!#!dh0L)y`%4^> zK0@u_qhWZdOS+fX>T30lOXD{CDu?&>TDNwBi>!fFj(ok!;a{aPeO(#B{7W77)e3*) z#?v{ZaNqF*3aOQByg3oab_cVf8kKH*pV95R?yzA*m$su}Mdw?+c1ISRjQ;7XQ(kol z)aiaWds5SGam?)rbX#vS>#fb0!-cqCd_Iqqm5;l&^<|j8*X(gz>IjAmJcTiSOxUPn zea2Nk$46bT4Hn4VX;H2x7EtEYS|0@sRrg?TZqq|}{LN4Lt|xRKvqOmle@QXOinMWH zwkubiUEUn=bgUCckH?bLmOpx zrA&2V>rRMv!PC{BzYesMVR>j%E16dxf$5$-V`-YsKW0eFv95)>(OQq#Ukr1cy~%|7 z2&rlRBmzuqm8T-7IYJgG(s`MxBk>1l)$5IT-`T4j`(l;W&;7HysFXA&(`snw86`cd zaIJC%+iQ==a^TDQm1MY#ZttdrHNUG5=Z%)aNLlTb?bims2VprV;TOkN@weI&vP5jH z1l=#Z>1x1xYr~EN8qw~%X(KyezuvQA&u6Nls7V8+g=G~%H!0{LOX0kC7#gEESGRxY z@j164yP3Wr&9z}XiiVzi^l47Wkw;Q96?P4(JijGsD(*3+YLLCl=;yiM{r(?WWGRS)uJ7cfb&0 z%u4rgj4F?M*&057+CpF1P+yt%d{Na0+ob)zZse{T7)IJFz8+R(ij6gl@AWl=|2NA| zdSHU8wbea@6C->3!FSgMjiDN;(#34oUcE+<`qB&SKUwQPZDjuUk6ZdcK*J;tZCCQp zC+h8UeS30JK2>Gr<9!*;W1C#DfP!XnzTA-pxq_dEmm*a)w#dSr_a>pXI3k%+N_l7% zDW-jHUX3uu^d$X>JF%_gJEeU>*1B*l50=KbgO-*>OK&a6{G4jQLp5qgyQW^P*xm)6 zI=aZJ06k2`Uw5R|_4zzLCrKFzF>@cGd!KA zK@$l|wN=^D%vPsuHowJ}X`~Gf`49IL2Sn8;{)^dh-U|F-ZMYk}Bj% zQ*#8LNAOn5zSpyW$_jE?na1Ka@2tBkbRoy~{GORN@wE(KMo*+Ey?cs#|7OW%yJk88 z5g5a~E|Td91|yNci2|#BdZWFs^JV@zfqcBs?b^Y_e9ql>O~o~r>5j{&1yO4uFNM)V z53#KgW*q&=8l}Ac$1OF+JRJ3GuE*=j=(s{0pQZ?W5~2Sb zLby+AtwT3C*OissEwTgO<_ns-PkE}HZpBq?8@sOs^7P5DzdAy3FFk+Hc6`8cUur`` zXTn~!=I@^+m-<4laKC{A;V+Cil_*NF;O;2Mz1SR8cEter*zebp?BM!R>Qo-v5L( zDOQS*=a{84QQ;^0V4}uU(7W(v;PvH+=8AEcT{k2u;?vaY4^af$L(A69E(}n7$U>gX zi&eKY#%i!~Br$~^=s_a;zle)IOZ`T5PnDo~s-sPwq-d4*AqUU6?yvhP+G0NVnbE$> zVh62S*p)18pEYMJs_UeCp}LtDU22tl%E$0h7jU3-yswkKFZo9sJ=xD-1Z*XgsRW$T z{oO^C+MPD6T zAH7juA1fO*vAnT7hHsvqSvqFK$jVB*X@b91Xg$wn3`n;2P!DaU_#v(x_s!yl(A(AM zl{HwD8d(yW-VTfYx`g~WTlXgA)8ZAzXRx15>|+`tBi$1V>V_}BI9$s`TQ7{GDiX3$2$Nf z#;fr;9C`=9^rjZl`Td)DqIS{@?V>OC9a*o}*a~3rK#Zy|mUFzxxH&p!s2+2`46Sc- z)*ugN1&o4aG}SKwp%!-cfc&Q+bT7&Z$N|_w^1{SSE7zMqpjyCS$ z>o>W!WxvPpf1oAb-$^)or}Osw^|?4Cx?eAtQCoq&Z|;yslxfgr>r&!hpbV_&T09ba zA;ioXpJGaL;;M~ZFTEe_4ufeX7x^@F7AL01XV$r&)!?~#Mt{Svc(!@4yBqBL2CDDA zbgvRKUzlSIRH{`B3*OdN+~1EYn`S0_P9ZuX>jp+P*%CCBx(`EI#v$BAyDF}qq*l^1 zjekZOq2|qML(Lm4YeVYODit%E8_H@^UQLS4x_G@hCI)-NJ>L377^~`=>l|Js&=J27 zpU!;`&KN%O{w=0hFqoDPw6(2C?S)ABgwTGDrfG(y)RPo#n(9D%)M>B4z-4J#_szcH zc2fo}`U7Yb-3-UTJuWR|t0uMOs_#19nc!fx#x<@O# zc$pDL*RUp`GeUV}1=Zp%CItN#@!<8W!Cw&!?B-G<IZ zok4GsV;rna);2cqw<*R? z*mUm|)@i&=?+YnywtcRk+M82O1TA^dG_e^a1pFBrBA4>H0veS2us?M6~A3~*O>;k?IX&DQSkW%#<_M> zHZ>gPTeyNxt@!s)J%tqemrrl;9~Ym22k&QMkP55-`?OY>`QUq@(y5rg;8;n5OOLOW z;8aTsw#?%*62X-XTOFgm%on``GZ;J}DO0j^CO55PVatN|s>4(V!7#h&&&>H7Pp#~$ zHz&sHX2<8Y#1faxjMuTHLX~Ek6YBvWY-yu-a=+%p^nMszQ$Eq*pKWkNsI=gx9>OXx z{2AU%u99yZ)#62%3T@1PwdZ7?MEX_C{|ZQ@n&0-#IohUq2FUDW^acufSB~o$xvK!s z*kEn?`jKAy*slunxj>m#TLbO_SCa1wzMdUOofm0i=o-mP&bQ@Qv3@f_TiiRHJ>yll z>8y%w8M`gl3A@b_rpRK4P4jBoM@k*43tMVuG|a4zRVicXJA?0TP_So*!S~y$pWj*- z?VU*reVQh=Gtk78xq^J(>%hzE;>qba(Ik%%rnQiP`bQe>;q_3x^HeI`R=K&nV{;eG zw#r~Y%mZ_HoCe*MKS6G{B7q{I-E50bUMrXx@pnv7O7nz(F+zODLK#*OYH3?LO5OC( z#s)p=dtB!C7uvSI@9jbul_fo0J>BH=YnfZ0j88+DZ04{=|E0bL+T`@Z`xF!X(AoMm zH88+WHU3f@VP2X_Iy8L z;IJJOryJz2rn;olPrXmDAO7q&qY*#pkCsH0(+^L5o@^|eTgW1rU2;`FO( ztglZrB%SZ!IudbY;a|4I)jfy*&|y!(bwIM_bu50g$3K04q1>;-s40xUI|P0Y#&7ff zO1WQ$y#w;Of!|{S_s^62br=oE2k)N@{;Ss3MxFoVa=#8&$^Gpl4CX%${6PHE_m@cm zI@}cD8>x&`cl!SB3_G<5DM@{Qv?CKb92CfKu>LQBc&m~BNuBwA9nRyQj?TYMM~Cyl z?=$Y-BKPZXliW}Fr>yAw3+&t=xQ=gS7iM%=DdpGc>-%;2Z_(4}x{qK-|n^&MZon;`+`=e2oc0*k-i6k!&{sO>HjTo|D5CbejP3x=f7X; zk48TT-0vhM{}N6W{nhfp^#22bx{NO7%0+zt%1b#6*0)YyhdB_VE~D>XEBCLJ`?Z`- zU;ox&7u-)N>HF8q{p;oawVVxoyW4*>&=WlM9ew|t#eBn@c^vkahNb>bmrhrg>tSFd zsqbHTBj2}jK8KYY(5>py_v`Su|2LpKNC`|o!vv^?1_-SH(FP}B`d|XuKxH5?n0^PS zeg&xh9h@+g5ZVEi%U}T153kft&|(J47Xf)VKt(iDetID8gQts34GmO}|bD#8s9s2SYWWaTx&RoUa%F literal 0 HcmV?d00001 diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index 8732a789..8ac790ce 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -3,6 +3,7 @@ namespace Pronounce { PurePursuit::PurePursuit() { this->setPurePursuitProfileManager(PurePursuitProfileManager()); + this->paths = std::vector(); this->odometry = new Odometry(); } @@ -12,6 +13,7 @@ namespace Pronounce { PurePursuit::PurePursuit(Odometry* odometry, double lookahead) { this->setPurePursuitProfileManager(PurePursuitProfileManager()); + this->paths = std::vector(); this->odometry = odometry; this->lookahead = lookahead; } diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index 47827cce..077e4c30 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -26,7 +26,7 @@ namespace Pronounce { double dotProduct = pointData.localLookaheadVector.dot(Vector(1, 0)); - double speed = this->getSpeed();// * dotProduct; + double speed = this->getSpeed() * dotProduct; bool inverted = signum_c(speed); diff --git a/src/odometry/simOdometry.cpp b/src/odometry/simOdometry.cpp new file mode 100644 index 00000000..39cb5505 --- /dev/null +++ b/src/odometry/simOdometry.cpp @@ -0,0 +1,23 @@ +#include "simOdometry.hpp" + +namespace Pronounce { + SimOdometry::SimOdometry() { + this->drivetrain = new SimDrivetrain(); + this->reset(new Position()); + } + + SimOdometry::SimOdometry(SimDrivetrain* drivetrain) { + this->drivetrain = drivetrain; + this->reset(new Position()); + } + + void SimOdometry::update() { + Position position; + position.operator=(this->getDrivetrain()->getPosition()); + position.operator+=(this->getResetPosition()); + this->getPosition()->operator=(this->getDrivetrain()->getPosition()); + } + + SimOdometry::~SimOdometry() { + } +} // namespace Pronounce From 5ad4eb308485e2082d6c0eba8dcaf017b58febee Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Sun, 9 Jan 2022 16:37:28 -0700 Subject: [PATCH 17/21] Testing in sim --- include/autoPaths.hpp | 36 +++++++++++++----------- include/chassis/simTankDrivetrain.hpp | 1 + include/motionControl/purePursuit.hpp | 8 ++++++ include/utils/pointUtil.hpp | 5 ++++ include/utils/utils.hpp | 3 ++ pathTest | Bin 168360 -> 173672 bytes pathTest.cpp | 20 ++++++++----- src/chassis/simTankDrivetrain.cpp | 19 +++++++------ src/main.cpp | 39 ++++++++++++++------------ src/motionControl/purePursuit.cpp | 2 +- src/motionControl/tankPurePursuit.cpp | 23 ++++++++------- src/odometry/threeWheelOdom.cpp | 4 --- 12 files changed, 95 insertions(+), 65 deletions(-) diff --git a/include/autoPaths.hpp b/include/autoPaths.hpp index 52ec17a6..82b398b9 100644 --- a/include/autoPaths.hpp +++ b/include/autoPaths.hpp @@ -34,10 +34,10 @@ namespace Pronounce { int nearPlatformViaLeftNeutralToFarPlatformIndex; int nearPlatformToMidIndex; - void autoPaths(PurePursuit purePursuit) { + void autoPaths(PurePursuit* purePursuit) { // Default pure pursuit profile PurePursuitProfile defaultProfile(new PID(20, 0.0, 2.0), new PID(60.0, 0.0, 5.0), 10.0); - purePursuit.getPurePursuitProfileManager().setDefaultProfile(defaultProfile); + purePursuit->getPurePursuitProfileManager().setDefaultProfile(defaultProfile); // Test path Path testPath = Path(); @@ -49,14 +49,14 @@ namespace Pronounce { testPath.addPoint(-24, 48); testPath.addPoint(0, 24); - testPathIndex = purePursuit.addPath(testPath); + testPathIndex = purePursuit->addPath(testPath); Path rightNeutralToRightHomeZone; rightNeutralToRightHomeZone.addPoint(105.7, 60); rightNeutralToRightHomeZone.addPoint(105.7, 16); - rightNeutralToRightHomeIndex = purePursuit.addPath(rightNeutralToRightHomeZone); + rightNeutralToRightHomeIndex = purePursuit->addPath(rightNeutralToRightHomeZone); // Right Steal Right Path rightHomeToGoalNeutral; @@ -64,50 +64,50 @@ namespace Pronounce { rightHomeToGoalNeutral.addPoint(105.7, 16); rightHomeToGoalNeutral.addPoint(105.7, 61); - rightHomeToGoalNeutralIndex = purePursuit.addPath(rightHomeToGoalNeutral); + rightHomeToGoalNeutralIndex = purePursuit->addPath(rightHomeToGoalNeutral); - Path rightNeutralToMidNeutral; + SplinePath rightNeutralToMidNeutral; rightNeutralToMidNeutral.addPoint(105.7, 62); rightNeutralToMidNeutral.addPoint(75.3, 40); rightNeutralToMidNeutral.addPoint(60.3, 65); - rightNeutralToMidNeutralIndex = purePursuit.addPath(rightNeutralToMidNeutral); + rightNeutralToMidNeutralIndex = purePursuit->addPath(rightNeutralToMidNeutral.getPath(0.1)); Path midNeutralToRightAlliance; midNeutralToRightAlliance.addPoint(70.3, 65); midNeutralToRightAlliance.addPoint(120.1, 28); - midNeutralToRightAllianceIndex = purePursuit.addPath(midNeutralToRightAlliance); + midNeutralToRightAllianceIndex = purePursuit->addPath(midNeutralToRightAlliance); Path midNeutralToMidHomeZone; midNeutralToMidHomeZone.addPoint(70.3, 70.3); midNeutralToMidHomeZone.addPoint(70.3, 36); - midNeutralToMidHomeZoneIndex = purePursuit.addPath(midNeutralToMidHomeZone); + midNeutralToMidHomeZoneIndex = purePursuit->addPath(midNeutralToMidHomeZone); Path farRightHomeZoneToRightAlliance; farRightHomeZoneToRightAlliance.addPoint(127.9, 16); farRightHomeZoneToRightAlliance.addPoint(127.9, 24); - farRightHomeZoneToRightAllianceIndex = purePursuit.addPath(farRightHomeZoneToRightAlliance); + farRightHomeZoneToRightAllianceIndex = purePursuit->addPath(farRightHomeZoneToRightAlliance); Path rightAllianceToRightHomeZone; rightAllianceToRightHomeZone.addPoint(127.9, 24); rightAllianceToRightHomeZone.addPoint(105.7, 16); - rightAllianceToRightHomeZoneIndex = purePursuit.addPath(rightAllianceToRightHomeZone); + rightAllianceToRightHomeZoneIndex = purePursuit->addPath(rightAllianceToRightHomeZone); Path leftAllianceToLeftNeutral; leftAllianceToLeftNeutral.addPoint(29, 11.4); leftAllianceToLeftNeutral.addPoint(32, 67); - leftAllianceToLeftNeutralIndex = purePursuit.addPath(leftAllianceToLeftNeutral); + leftAllianceToLeftNeutralIndex = purePursuit->addPath(leftAllianceToLeftNeutral); Path leftNeutralToMidNeutral; @@ -115,7 +115,7 @@ namespace Pronounce { leftNeutralToMidNeutral.addPoint(65.3, 40); leftNeutralToMidNeutral.addPoint(70.3, 65); - leftNeutralToMidNeutralIndex = purePursuit.addPath(leftNeutralToMidNeutral); + leftNeutralToMidNeutralIndex = purePursuit->addPath(leftNeutralToMidNeutral); // mid neutral to mid home zone @@ -126,7 +126,7 @@ namespace Pronounce { rightNeutralToFarPlatform.addPoint(75, 100); rightNeutralToFarPlatform.addPoint(60.3, 115); - rightNeutralToFarPlatformIndex = purePursuit.addPath(rightNeutralToFarPlatform); + rightNeutralToFarPlatformIndex = purePursuit->addPath(rightNeutralToFarPlatform); Path farPlatformToNearPlatform; @@ -136,7 +136,7 @@ namespace Pronounce { farPlatformToNearPlatform.addPoint(58.6, 45); farPlatformToNearPlatform.addPoint(70.3, 30.7); - farPlatformToNearPlatformIndex = purePursuit.addPath(farPlatformToNearPlatform); + farPlatformToNearPlatformIndex = purePursuit->addPath(farPlatformToNearPlatform); Path nearPlatformViaLeftNeutralToFarPlatform; @@ -144,14 +144,16 @@ namespace Pronounce { nearPlatformViaLeftNeutralToFarPlatform.addPoint(35, 61); nearPlatformViaLeftNeutralToFarPlatform.addPoint(70.3, 115); - nearPlatformViaLeftNeutralToFarPlatformIndex = purePursuit.addPath(nearPlatformViaLeftNeutralToFarPlatform); + nearPlatformViaLeftNeutralToFarPlatformIndex = purePursuit->addPath(nearPlatformViaLeftNeutralToFarPlatform); Path nearPlatformToMid; nearPlatformToMid.addPoint(70.3, 115); nearPlatformToMid.addPoint(70.3, 70.3); - nearPlatformToMidIndex = purePursuit.addPath(nearPlatformToMid); + nearPlatformToMidIndex = purePursuit->addPath(nearPlatformToMid); + + printf("Array size: %d\n", purePursuit->getPaths().size()); } } // Namespace Prononce diff --git a/include/chassis/simTankDrivetrain.hpp b/include/chassis/simTankDrivetrain.hpp index f446d537..13d507c7 100644 --- a/include/chassis/simTankDrivetrain.hpp +++ b/include/chassis/simTankDrivetrain.hpp @@ -5,6 +5,7 @@ #include "utils/vector.hpp" #include "utils/utils.hpp" #include +#include namespace Pronounce { class SimTankDrivetrain : public AbstractTankDrivetrain, public SimDrivetrain { diff --git a/include/motionControl/purePursuit.hpp b/include/motionControl/purePursuit.hpp index 39776607..64fb13dd 100644 --- a/include/motionControl/purePursuit.hpp +++ b/include/motionControl/purePursuit.hpp @@ -186,6 +186,14 @@ namespace Pronounce { this->stopDistance = stopDistance; } + double getLookahead() { + return lookahead; + } + + void setLookahead(double lookahead) { + this->lookahead = lookahead; + } + ~PurePursuit(); }; } // Pronounce diff --git a/include/utils/pointUtil.hpp b/include/utils/pointUtil.hpp index e0d6c5d7..e46a2cd5 100644 --- a/include/utils/pointUtil.hpp +++ b/include/utils/pointUtil.hpp @@ -73,6 +73,11 @@ namespace Pronounce { this->setY(point.getY()); } + void operator=(Point* point) { + this->setX(point->getX()); + this->setY(point->getY()); + } + void add(Point point) { this->setX(this->getX() + point.getX()); this->setY(this->getY() + point.getY()); diff --git a/include/utils/utils.hpp b/include/utils/utils.hpp index 6988775f..265f39fc 100644 --- a/include/utils/utils.hpp +++ b/include/utils/utils.hpp @@ -4,6 +4,7 @@ #include #include #include +#include namespace Pronounce { @@ -28,6 +29,8 @@ namespace Pronounce double clamp(double value, double min, double max) { return std::min(std::max(value, min), max); } +#else + using std::clamp; #endif // SIM template diff --git a/pathTest b/pathTest index 48924c126206768e59f90e57b1d5bf63e05339de..8226ddc1e832da8708922cc24b889a32f74b12c6 100755 GIT binary patch literal 173672 zcmeEve_T~X`u{RMQ&Vpu97Vp52PVAf_)NO`;7T`DcN zUu&DSR#t9XEt%<6$xE#j+Ak_gDr*nnCYjq(S$yBmGc)JRIrm(ocE6v$!k4_ynIF$Q z^UO2P^URz%hnur=F6b5)XQ-d<#<>RFW%Ls%88RdFp>FaDc}BX?6TeR|QjCL;8jt@O zGS`hwvYNs~S*|;f>Lt^K2OcAm4TXwBLaG<*r|GvMN1@>p_f#)|E>q|iep2|ig^#v~ zdxd&EZqG*)@Z-YTYecd_y&lPC%^jlNn){qMmzgmPf0C%L>XEppUeyv&zUl!drb&4! zRPrPq>3_PEryEm{M?We2+c4bq@?||YX36pjsSWxW|9QoXU(#N#tkXBT!`Xh(k7$@6{H4eFQ925$!4CD0DlIdp-JH2$qX{9A)l?zT=kbdTAXAT=Y zZ_ePM%mVR6ZBX?KFUd17EMZEMV&t*tBkw7{Z}{n*kM9|@ciD)edSu-8-jv9Lf2&tC zs7)$EKU7~1G2i#X?}0MyVBne*-$B!ixWiJ9&F+5a5k?jjqWnSle>(o3f&atspMK5~ zz`xVw^$6hES~^``bMt*S<_8~Jo^wRmz1cq&9KED8_}lo+b7NLv%JUX-_`ed(M8sA`!zb%+mRw} z3Sy)m8zcQX2+NBOO`{YK`dg6ZRsNM2^iKzUlDYfmWh8jfc_c>q>Hmq*U(%@*{CEHShy*V_$=-OSUmHWtp&024Vx&)s(cdXC+HH%$ z=NmET92bL5VGKIK80nwI;Q!_r?VgG9Uix->41Pw%NPi?o`rR?w{YMNw$u^|mzx(Hl z7<8&o&}-b+Fh4${?{$Jwopd;F;E}okqw>>ay7F5) zkVom^#|52aE^QcJ$aGVttMco>j}PTjR*3SlxN)Z}f1|7223fvc(oyA0W%;?T@)Klw zm5a|KB>!t%{5;R}kB;J}n=IcX%lD8CFGcwi6%!iXBio(jYPS!{lYBB{e^uC0Da$W# z@o&K2T~%HtOJ zMPYeGL4hdhS#Wf&QBqb?!DNl1(mC^r#bv?FtBU57&M7wvX3i% z7G7@@%q^K=T!8$7d6nfe3yX@4^5UY3!m_KtK~YJ05iv4d(m`cW^{Vo@lD}-6LO7tMdiiC zWh97UNV2k&>;l{^JkY76rrto1r^uNEe5@r zbFxu#e8o@{te90k=emN@;!bLLf)7Z=VRGofHYT0!>s zGchJ0SCL*aXI=qH6b~DNQOFvSJ>Mdpd%?KzbH*1CcdmX6ISYOA>H}qnK1?s1QBYV~ zI;V)}xvEo7=Xps1f+{SS4s|LkC@QQdnuV&=b5f=S3kv2Im(QDn;VP-PzF>YD^2S$` z&KuLUUKdS3pNAI+X_j3lWa;YsXzo1oP+rWv;5LR1Q+=9KSy3=&WuG8H$jqWHv-Z&H`R7tw; zjx|mq{!_kKx5OE-{~d(9c>JdyDs?HyQ|z6B|GE9IKg1h}T8@nCl57NrV8!2Fg+NYoEw>^XQ6O3zQk?MCfiL$@{tO_rmjbGmerDPOS@-pGrBI$r^QXy{OWUsuJm8S9)_l zk>2P^58p53)#OS)@d{DC*_A$Vib!vBr8h}B?XL9nkSK4+e8uPCzZdB~SGpq%+Hvo_wJw zzrdBQ=vTSY|9Y_~U+YTuOMaHS($`3SR=LviW%)I(^b2J9I#>EMncm<^Z|g1eq|ue$ zB=4JD>Av5H@@=m4G@0J+N>}5RDEU=-k}Jz6yV9#uH=^MN?#%AOmn4& zW%?{v`doRxz?E*ueTu{tqTh;tbsv`frCf^7lwDBz?oLJ6-kL zov!-fPFMO!>C^{Bzu`}mBKDkUFGKw_YU#9RpnjUPbh%Z-SHRrH{A$MDDSzTt#rl-3;#=bV97>Qs4G)Qa(VmI85*dwJIt;P()1;+K*T8wr zTDmmZoNj9Aa4^4#gXhLNhJt1U>%PSetrj!=5KmaeZ?GqiNt?@~X0ExoTw1mQO@3$PdYj}YWbc5 z?7c19ta}Qq_qJ@b?kS+&+wxcIo&xE;Ee~7w6uj?kxzoC*fO>DsE!I5+$9r3@weD#F zv$v(tx~G78Z_8!YJq6NxTQaSC3ZVD446*JhaNgT;f^|;;^WK(T);$Hvdt2hHdkT>E zwtW4Q>MsSx=)ZMO0Wtb--O~aN{kQIEp@jZh_Y^3j|JFSP$mqXyPk}M|Z{1TsjQ(5q zv;ac?t$PZL(SPfn0%G*vx~D)G{kQIEfrkED_Y@GL|JFSP!sx$sPXRFc|D)_bv|-so z(uOR9^#S(_Z*<;Qy6$JY?u%XbQ(X6XuKTgB`)t?!DA)aP*Zpa(`;%Sw$GYzOy6$_r z?h{=1KmN|y|9`vg|K+;>+;#tv>;4_r{p+s#S6ufmyY8QN-9P2Jf7EsVpzD5_>ptYV zuhH*^{A)~L+f;wxQ-AfYw%iFhp@cI($H|sZ&kef>Mm;soFgp6)fGYcHar-zf{Go(D z6O3rD=nK{}8@ zjpC-DuGK!(Z@Ercf;?1&wM^NY)GNCkzs9!VSDxt)<+b@k+3o(oyZ%7LoLxpOY(k3Z z4{Y%V-ZMi;*_-4uUfoRem`Y$_yFZxSJ~L@g7&Hv+IwP@milZF0Mh%TMsTAn&9ao_n z6IsqW)w?tNfrU-}KxN|$e=z=J+DP#SvfGD*!BaD_cnwT2xNZi)M#=SE*cqPbPr51W z59Xn2H&yfjD$2zoX8$XxAHA|0RKi$J@QrOSAKBm0p;bRWv6h&f;Xgw(Uy)#5ixRJH zW{)A|n5($-2l5)+oCc|tTsS6T9Za*Bb%sBg4;q8ooOBM|~E3!C{6+}@-~*_6!XpGVJSc^~z`Ro;*G9pyKm zeAIA!`h712(=~2RLl9pu4_U0?DVPwfAHlpeGO4FXVj*|r3#qSCI`kD1 zAi)N3HFg#CkaD=ml$4_tRr_KLkp`Po!98?}7J_|>b}qL)YllN9!2KGQT< zh0ZwiEe;)Y>f2n^J809Y=pI59tnQo(=f^GBNdrYvm_{s5_K?`-eq@OrLZ$Naz~W|1D9d)359!`M@iGb_q{Z#wmnLtVC7)U>^cAc z)9Sg}8t=blcRL%tmy=011JC;ymL&opf*J#;OTi@bSTl_aMa(h4Ej0u28&mB;t{SWn z6e8x+S7WfMO~?r5eWw|r+rUPDu!d+`BBa5>+++G4zn)>nAZp~p+4K5ODy{vs7WJ! zGF+&#mONeLHVLt>hV;I)m)h;nk1tDC+W62=&qP| zaTwV(P<6_OD%Fw{Hp-Da86ycroJ(0jp_TzMw|Nb$4k62q&u{0-q(I1KEqHG{G+Qdo z2Bt&d0ctw*O&S8O@h}2dRU{1{1FpQ9@{P|v`5T@T4|qWb5Z3or#8Z;ZKA5vM5C-r z_wxi2bNUasrg=>Hme0BEVMvqYd_PVKldYoMq}%8e3??3WroxgnvJb^ybC+N{L!zO) zHM+xjZXai3#-dxoj~vY+p-C*&kvn?*SZYBiVxh)miy(mJu-?OUORZp#83Us|_kPHX zZk#_1qO5{LTI_O2?CeC-z8t%e{UFwQfr=f7_xb65w-JKSC=zuu+ihkF zJpj`?IrAd$%6kQY8lJzh!*jt44Mjc=#p#?k-%lx2N~wD%+^KoOqC8dO?g$}1Xk5g6 z2nqrb*V6S};<}2i_wu!68$QErwU}8gD-n{}20=(NVs1nU+fb;sBj)2oNEnLAyJ-#P zFhmLFUs{nbi{DaDMgWF`$jf~VpKdpNQ=N7L`$vxa(o3BA<53_T1Q3r@hNJ9=*sDlK z9Y_Gi*3!l|NhN42g9ce>iCJWi?j1Pa=jzAFt;Z>m$Ssg!6q5a(fi9XGzC=H(>(jN~ z5qHUIAxUx}!9PwqPuD^0D2cWW^jfFS%`>e>no@lkqPDcM0MW63qa)+ zwPR77gz4CBxU0pr>ytse(jFX{Lwz7=AC4LTU!TDb={$eLnneSv{403E&KL7zvEEB# z{YR$IxBfjIf(Ei#n~3t=#4nAj7bQo}o*85JY&57v^{mcx^(+xR6Mj*Ox`*gSJ2hNN zBs4$i*7qZzsCvGqMtx0F->FfL!Bs_RRHzW;#7un_TpmcHrlL67R#O!QiT6{-(xz%c z;9c? zqVaxAB%juT+3l_GQ9bMppPsPq9mAMU#hB5aKjKy{8By$gPLJl1x0QLFHvdo*Nw^oa zT91-0BD-BAuBF5T7X=Jf2C<;H$KE1tr_fF*ZNd4nX%&gP$$9u?cg;5z#U@jCr=kaw z;I4gRX)8>02LstodKoqk%`yx`kp~egvTdiP*qQ}R+VU@+9BPj|!>0|M(kf!MjT#`; zTP7M=cR@Y~hp_`y%~2s)<7AQdoSk=-m6wlAdAH4_nH;EWlUBx- zHOmxo@dteJ62x=q(S*I5Cp{Thvd3UF9KDi-*BG$uREty-k|P5*R*oVElv6b#mdNaO z!L!bXvN}G4lf44Jq?5IJNNbBG3^CRgsU(WP^C=9= zav4GtU*!Zibj%5aD7M0^Iw@%Y$395|##SW_$g52nFl9y3fZ{bt17?Sl22?gC4Oj?S z*9d|Ub3J+HzBajlI?1U9`!=C_HY zb_%*w>%XO*y5Nc((lK=!I*Dv3y zt@4j*!X{Hib(5;!r0F+^+u4XD^oKBMqWe|Cu`(f7D{g4l8HxIhPrq@roubbh4=aX7 zr;x=jZj4Ey3+!KoWxs>{sWO4tSJs*NXOl@~xdU`3<~ub{cf?EvcY*HUQ+j1M`=CYB zC}9=#r;wWzRC;AF&y=k${ONjj29?9}wp8JzvPMCJMEia}oNz$&!Tn zUUoSi*mDv&Zp*f*xrCv#y~drQ%5ioT$(ZotiB8WiS_}2vGtp{6wM~{$Z_SP_Lw#3? z;wD_$hGdu~^A8_^QQ<%r(B2RQoB`WOTC<<}Mm{psx7gJpJ4lyTq|%|j=h!7(vV!3f zvVy8?$A1KBd%`5Qv%!N z_bIzc>nmOcvDy9uJL10e6YL=k_5IkoU1WZm6#$ zrHmAH*GzY*`WTQWUW_io6EA>jMMW4jl&V&o0}$TAD=mimq-4;~1!;AikwQ;uet4C_ z|I{Wtt$AO|1K+BgKaFe?%KXDz3EJCtyVl$TH4==er!VKH*`=Z>B}7vKKX?XiJ{nC418Q-tQO%$l zygK_WsEMTp9UQOwHXqrM=?4+VAX}HsOt>s zFwCXA@0FqD`JqKtIcCnf@0FqFY1d@iJ^6Y#llgi|@`YGG^%df44VWEEzY;!)Pzhp2 z94 zbSSfoqn0A5-PCMjvs=o)+XI=3Js38s1|I!Kjb(aK7q0W@wX?4Ln{3 zyF@w{HT8XJa`?YrL1|Qe(_PYUl^jMT10a%cHfYLFuRv6Pld6YCT}zEEk-g{M;{4B< zM0uzAZ%Pgge_S>+(^=|vS&G{a4PPuvWjISMJV(%aoRf)_XUIH>sPk<~6xzTWN8COe zwo@~RJF!*0>*LPiQCVmM3dse+$L}E?9f4m6rpXG)VA@~3$JcTN9ynSaN_pT=-|9x-e4C%waElgE#Wnj>_-8>1{qpHvH**5D zNsiYPEJw_qWVb_o``B%7@Ik`n@9g&K?3f@~Ff-N8ywGCiV-jNNdDu-ki?|sRs9#T% zNbL?s`JBLK`r;71jF=Zt<6;f?1Cgw*_g$Ge+1|);N{EGwXLiCvP9N(fEy>`^Z(GuO z>?>RfCr(ZN<6MvJGg<>mKIRENXhT-Xl(5b9chgFdbT3eIQ z$xbGmu!-!oh)<|&2Fa(NkQv?Q(|x*7qgDQd<*YNm-JC5S8eg{& z6JW}A5ES!&D;<8|W|!B3o^vRY7CnTtmZkVb+C)_(OOL}cv?3A`6D1i1Xkb6z7Bx{c zk^ECE$Sk216AkMDFYzFy`vG>(+!;QS(=BvLLQJ?j&;@P}dXnpyb<#w%liO`W*VsCK z1_hyOjA-;)gl5Pr(iKFyE2!G?Xr;MpjHlB4k%kGZyOd`41`nm#Bc2La{qHVz6g3H5 zBdK*sY3ljGh(l>!r@1Ca=wMRG11Qah8G?J4(rlk-lR2CYZP3_IxDu!(9idy2<8qo7 z*o)LBZ_=V$QKI#CE_Jy93ho?HYocr;e=G){r_!ZSMWt5MLwrse^0CD=bml^6MMWdD z;>|bF^XmFp4jXvOZj+UiPZ7F@SDkwx@5%=Wu!(?8G%FR}4jiBI;5} zza2uo5Qh+gRV*dw>-}Wt0%ET&Xl>c;JdKq@oaeKXYmw{^@mU>6S02BJn9qx)C%}qoR&!%`E6IN`6KQxvfx}#m*1|A}M!0q(q>t*zO z8xQZ9j(YCSWgmqFfe_|$CnDw*r+bR(MMxVlw2+`(It!(>%AXImA8)6zaJUcX{sM&g zyAl2*d#ftnvBz$FeUtj$TFtDAoK6G)}Ce0^-TL&C_x) z;Scg@5`QSW$`S2ng=NABI-Z&&qIXkV1)>f1b# z*aSU*ZdbLDpiz2DRXeT(1H9c=OI>i$PvHm?^idNF6lw%dwP@1w!}$AXB@ya-Rdj0; z{;SsLsU5Z0ELt236s@Xrvg1X=Uu8sf^TWS)v74k1bgqRW<6CyGAW;Nfo`rcG?F%WD z2H+{Ir}?~KQqAiy2RPHtIYDt&2n7bE6P2B2;#u@OIH~3dE+viv@?2#Pl|gF*GFs#s zsy9K#oczdE5~i?aulI+s`4PJl%7`u?7G&n9WF?85boYl3;4Vw+V=?o0FoA)8kfs@I z6?W$6Ri9p%kv79uf?=e&t7ajYOlCwI|8FqDk3RXpTJ@ zke}t5e|pvG0=5rB!&9E8u8(>s3tJj5Mo6mIZ^&+DFG3q9CpXBngn=j`y+0E3m956!8Lu#22T5vf{0VSSb zmAJzj5#hv~U<&HaZbtd1*ltNF$U+$VI=CO|w-EQF23#jxfL6r5n6KyAe9h+wvKK3v zqfjN$d|sEVO>>5z$+>vMK@aoaAi7^c6trcA>z<$TwMADj042=qc$<|3tlf<0p!GzT z0lb<5G!Z0Tx&@2H);MS2iZ|QteFcKQrJm*nFDRm(b%^OH<&+28aF-BSZ>TjQhTa?@ zh^GJ@+hJPNoU<%fsPDj0jwwvjtPV$^wZitM0k8Ta=7N)0(mmV%Mo0%+1~q{blWnBT z+hOO0*OG4ud<@Dj;1Q16wo$x9kv~$B_@hn2B0pT_EwuAA@|T0WV&tt81(W0Lk`|Rc zGVd%qFTD0R#bhrJCNuMdnOcrQ(o888(#=)VkT6t&XEUirqZOhGSVu9cbHv`qL#OQ6$b{-r>bojlgo>a@Z^jkj(E_!~d_6`)tb>RcTV7!@ zPhSs>q7pBtI7t*aNI)g(}D!6$s(8sQjPd$bw| z$;{VOCRt0FH&f<4ZRhDq@y`vc2;9bOP5ldTT@5+6+=G2qTNk+B-`Q@Z9o1dAA0k(O zuYpPT201; z=VEz1d5jp?flt|EM{}Mtx5&)HwM-gV7TdKl^Xt{JrWjbx3(359>^yy74=3TtHkJyT z$<-F)x;lGxT+27n16ztbeU!Mu%%ha=8YMU+dP40>$Y%Z~^W$o< z7ujwb2t)~K7)ICq5_vimYZqU_4w-^%abA^I zGHqnp93EtxaN$kPSY<;JOp57W*U_=I8?M$T;1@PDk=73#eDP7J##;Kdp3+3dKos7P zNJV;iRQngwC@dvzn7@(Wk7Cre`QyPZeSg81kjy-@C2zD6yW5FjZkXGI5Y7fktJJ@r zAOVPTs%@xEgTA*)9x;&0Y*zGqEr_IEFoSn#GVGedbZcPG`oebfnY9d@EE zq==np3+Y)qk%TnwMR)6-LfSybbIdbQm^eS6xK4+-HjsriyQ7LNxYi${1lJ^!G{L@;Lc3b*w8C`1%&WEY!fStnPH@C@ zbsgC|aqL)MOZZ{3>hy31PZou=5>W#^sI$EVte1L`9*-SKrR2VL2V9@GW?<=Hz?qku?{y^rPXy=7_0;sF?pDfw_Xf&0jGH-{S z7hX%cD%O9X;vO?vi|S@T+Qa*80z9i|!X(^gCraMlK(D5OD$PbVL`8NHyWS;sqU46^ zr4l!`tt4rADNiRVbGJ6sTj7bEMZFYdMLSAKMak1@|DI~gh~QRSA5c-IPz9kVKJ>$- zDCcS9&ag{<@jMhI6TdtZC1%$lsoOB?fVPROu{59w-DEAa7*?S}*nC>nrXoFe{+S5# z;UTR^5Jg;K)edb-1`h&*QmijN2VwQWub(3RgbCs*Lw)uCvEGMp+1Ju&|lr6<4D$Q@>vT#u6Gk@)4&^;DN_HOGThNWJeN zEOlScuOBAq`x3qbIvh9REt6iXroy{Kp`H>G2yyc1d3POty!D!>)N_NVlt75WVNv*f zG@?BV+k_cL%|F3~`aVejK`K?@ee>PqfuwZ9-`UrR2#BceO``72UUk=Kbr)%Mw<3MR z;pAdh{8do#3o4mjRIb*j{6n(|w;`Q4=ppLzFH6We1zeLnM#jEaIt?n&a-6gVa zZ&CLoue!suy4hOYTv_+sKXK3Z5V*&@o&2Me)FE2kKCn zcdDp+vsc|Jt?r##-3Mgd6Gh#Nz3OIZb@Q~k(`4P_MBR>uJo=lc)jd+H+fUa0k}3uJ zZuY9X6&^*&>Z5l1+C)0__XSb+cCWg%THS}Wx~pZ~TSeWAz3NWT>K1Et=gPW|J;*%& zg}^<&$y(jZwDBD#>s~GD{>`iI4swZ7H~MOI+mS9FJa2ucJ7$y+y!>-!06m7?A)Hwxg+h|J*%Unah#pIEjrh*bN?2d z`zbj_A&q6xx%GDLb;vchKZ(-fy#^W)`;liAG{@yjBQ;AAq!{=KCcKu4@8c$&$}!Kx z``MLZB{_9lFky|BlZ705#DJMR0+;?!O%^|PwlQTF)^h$QV5{s2U zLgo-W0aFzs=92aF{^Alj4mcB3OPvaF%32y4d5GwP$6*`j-ps%Vi>;=|koFDi;~Nl> z`Qj5Sgr2YBhJ^7r$t~FT&q91*Aq;CvgT>fJk6l7Fl!u;FQ5UK=`Q&5R5xuD!HO-U> z87~pt6=h{AZ-^$OiE^mDK92c~m?12sBQ?uWl{gOa74Og27}Q8;Su=r9i9hw>`kaAw zR;A*Wc44tmFG?dZa4PTkFKR&pNX|g*;4&f)c?nW{cq$(PR<%OQsFZBu`a`XH)R*L! zsb)+vy+B5hXRQ>Bo-e3Vdsatx9|6L_zCYf>^eKxpn1%Zdvc&0uMTua$n&%om1}3LN z#GL#Vb0PT0*-jzvD&`vJm$q{5Ger!MkQv2j1ruKAhwsRSbBdZJN$0?QAsA+&sJo}X zVT?(7rk)1xUK%`=u@xh_=)=l{mbcJ6PC>}If-hU}YQP%gr;j8l(Wu6?yo%rEzrS(p z7jn4x$X{r>Jb-MWS#%{dD}y_yYgV>kkTbyGC1B9fER}dVGbc`MDxMwcNq@#D$PMy? z9N8-t-Z`YI0UV6fXaC`eEKx;&{6AUb>h`r{hrIuK3U!(K5Z6M-?LcZ8bpzZ^!yYu@ zv)Ik>81PJ)eI>Fb1Nwm900)K9;$|HKJ_b(;EQYbtMmhI>S;k|qF9$=s<^_*371kF= zCqE;#S1A#*4Cev0+s`rkae(8jy9q`;d?F5TtRqT+O+vTCvC=Uj2@9*!Q9_+HMcZW2 zdMrcp|3nFMJAS=HV~qxsEn3742)hLlUB}y0Z0|{8XTQkYG)qBVx07#`Tvs>pZI#Tu z<@JsZ_*Q&26i+;R@F#|o7R|wYZ7IetE2gn@_9KMvEnkD3=&VhY^^7AcMYeK0JhS#N z#iI5HRMFE7S^g2oxAm&%CW4f1ofx;LSjovq=hrs)h`L4pFK`vD$4Ao{?V_UuJ5Y>k zm?jk@dE9y@dn;r*twU%yB)5G(b{3l^(=%~!N$0joruQV%CIXuJM=-?4;}@P8Q-H$f zPKaOi38KKl{ejB%>V^B`Du>>(5HUJFfIR?O)iD5Cb;L^Iqwm2fW6pY#(+P z2P5S0^QbuOJJ46g_&J8jYYFjuA|AVEs*yG=eK*V-HpQ|V%iO4sWF*GEYGBS~LC=u5S z#5Je?UQ53Z*BJKbvrFRCB$w~6m1nan>0h9wkBg?0qVdB#d<=zFW5a}B=Y)J7EH1H~ zR9(i-(910V{M2 zO%$)e%lPze^5zhqQ*Z6D7vIim^V270L@;_Z1$@D=m|VFyd1v?o;>(jx8tM@PECaqB zk6&ZmPpbUEDaiEEW;!2ba_(CWBNxs46j+n(G<$NSF1D4&BFnWI9KE}pO7(@I|L{Q= z`ZMuMZt+G-MQYDtMA?op)xL~D^M2$3^6@~wGu?u~AbBCfW3hdTrj&iJgTsf~#N=!; zoMUI4`3{gD#hIOW_XwzF4?Y)(F3>m)|teCtJETl-{BF}XEPlt0Dm=WwS=b5$z!U+*XJor+AfP}v;F z+Y!v(A2DD`!MGcBqeyx6^+YqFPpoq&&2e2^n50KxP1@er}$Yq$d+DH&LRA!)4?I-g`|c7dXEB@m){Nh zoF2Cjqfn9aqH-h1)x4agPr;1jF7ygylU}H5hPje&!aP6*jT)10qqI{{fWLV(iW2eK zXmxu>#Sp!~dsG14A~-IUY{!Vk`MoI{R6kKvD-PyK*P2j=6ue1OaU>H!Sc6wF{6R7# z)VYrBttZM$^Q2c~pHWCJ5a*C8w6)W*65sAoax7*}?XDe*dz}BYBLr(cDvv1YgEux1 zn`M1x6qjg8ygHmlL-g4FlJ)8^tZc-*$G*pG$DWM3$MqMu)_XJ_#K10DT#7Og4hHX_ z^`k#{-wJ{NS|jIk$10Jyh7#{)JZsr4G2xjlLUKl=!HcA7ep-M7yz7<_|N(L=0YzkDqtv{8JAC(Q} zy&a&>?_@VYrJ&`ZQJbq^n!%D`*51X$aH`p#&m~ZhzmLm%z=oI%$OY@1%yVQ&J1VKK z=sqp%bGv=WJ;A&WR2?JD+(Fb)e|sv(pIK~@gI>#nKDH4~4-&o%vLVM$1Ct5INrQw% zz4){r(wUb>|6}vAhc@b{2x56_2MX`v9LDTKdje%;Lb=rUHc2rXv)*Hl%bBa&Z)s-& zZHu$_fdHmq-oC}P&5&!-3)%a`*YST#8MLTy%|2HPE*dnOG1-)z6knjoz!2BL-ex=g z5)+Qdp@}-b{i1j|>><85!l`0X)#UA?-dPQZlo)9bEZm33o?V&s=rSS`8zb7rkt&}2jM`DdhF*E1lF%e7_)(upEQ}CpV9^lB& z%xpwBHzx23-|~Wk8yL^2G*$R^H!9}@TKs_zaspov0}mn}o}mG&3jQ`llWpZjw~nOg zDL!KY_9Es{)SOtMk3g4Iu4LdCJNIbhn)5@f&8hNuzpc+M{Y)el0>S|V{X81HN5KYq zDDy|I0e`b2!Lb6j{40jf^6Knb2ceRehKcPDVXX#0o{ji}it+l4Qk=1JAf6)1!ds6L za?+EkkYtZKdmD{b=0v3jDM}A`5YEYNNLtj4iEnO#8Kyr;MV{1rbPryx;J-FP;Si5i z12$oW8N=vA%umR52!nJBT1MRCj)UMCu`P_EABX@DT84oQUgQ(l+dp8NKk%A=`gGPg4ZS@@c$3j`S2w=lWXWXm-ke-Gx0$?$Sb zJfE#^Jq2((22Ng%_bT`$F@aeCnYhgf?9B;$MIHZ^C+??G0n#CcmRr=wh}n*pkX5ts z#LdR$_%Wd#WctD^k`JU*P8Gw$427&F8*+lv5=B|wjtJ)j(-gVq@g4$^%ZY1)?a0BO zJQZq~rYL#Ihln-6nWgab&zx$TUyuC}+Lfeb8&*9dHdTzoO*3^mo=2M`jyxV+Q+8s% z7$vHbD1AJ#auZvLX|CHqB{&E`M#L;3VbS&jNClKA_Mwd0$WoDrj9Br2&-ph*DS8f3 z2*noW>0}=JHg_O)>tfv##H0l#Lg=$iZ)yyBLml*@C5N76bJb+k?=$(9w`!J!A%Feb zX6!22T2hEZx()NjV2_SgMzdxPTZ=|NrQIB^4%Ni9!`dnJ937L-sYF^qo@-GCZ70%B0vqoLAgDf4+j{O2rq?pLPVMl`mAw4f9GpO@4$6TX`<`{ zo#lH-JHcX5m-bAp#iN9@6?1jqRohK5@{dpju4+wYZF1i5B6 zW%C? zGp#N*kZ|rtXEeVziwjfW$^wYPt?l<-LRs76{D`|w{9cZ5R0*DbZx4x3y6dr4lb!j! zAAexKm*Dn$|5lVNzo*HEX3>A^_gBU=>wN3- zdzX-ni0K>H8N*=N7P&hyQ}^T(;>Vx#%qGoWC~F@bGap8$hiF@ptvLJ5OOO=X&Q0YC z!p4{5x-&bssIzK z(cYh*=3<=PanoKp@am~QUs4W-Qye#W=+6sW*V3Q=@U2UK7Le>+`lD7mscN;O2T-n6 z@9N_PfA*^PB1(}4;B8(rxK_PEDj-+AJLwdgoXLR{6*R+gQFqve9L=fq>h?KQcC31f zk@2Hy*DaIn)0 z4S2-{(ev#auH~3-XQHF_e5*6?V=I(&-O90d>bVDFL(9aID)!u;fDFBD;r86$a-S^E zJ&@e7SSq{)K0G{kr5eW9kk8kiOSQl@|HkjS``2m~2rJoWS6(HoV^>}Ig-&*FWK+q3 z#tgv@>(YnxOh$9%%P7xwPXu;bb2j|=T3Bnsxf@VtH5F?&faI#}23*-j zOc8RL~A%sL2vvE zx|paOF^y!pXoiwSQUQ{p{wUxFA5fQ23wyfMtn;NFG=jZ%@4q66KraB=A;$(sp6E{0 z2FJtKIYzHjx)_XT!uwBTIYklnGhyY6qU9t<0<#1g_w>XpAU^yE^^yT5ZxgHsc}?8f z<45tB&EXxlps;JUrC3A3!+}#7iTyqL)vN0G%$vmgfV|uFDZ-#oRc>~U4IXI^s z3PlkEN>Mj&S2o(3<|$L39;V@OstG$u)k%;0@Bw!`UR;gV>>jwn1}2N9>rhb(E~3V( zdSRPUAs-gf15XT_5Y`%~no~g5Ah?+0>1NM^$EhL-%YJ5&U>XiyRi6=S`&g`y%>cE} zr0v|$EKEn?CJ3<+n$iIE3ZnvMBRNT)iTrgqQfNxX@aOUxA4Y_FQ%R*!D`H+u$zZbe zJW^&#`Dh-e2wHe|K=zwX`HMU>m!W`iMa<`EM%g=^kMS+p zHgJiqBA|KGe1sCCOajTd-I`F&mD)}*H`IiT+4?8W*0+1L{$>|i_nyw(F~qj!snOJQ zI%S#|rdlm1iQ`knAZ0#EP8pWRCxyzpt#ODOFL7jD|j3Y#Tet{}DL@Sc-7s<`2-3&uh z2V72#bywX$4Q#**m(}c#qtOM^Y-_%z<&yj}2j+>`0YRL7tzu&}2e0&q8XQE-BfFs! z!8AFK8stNj38M8ne|2^p%@RAU>;|p{Y&x*$}N6DJ4b5yl+oYhuw zHFtv}y&8;j)-3aEu$!!Dj=?vO$R`&^Ffqq1!;`dV8T6wih+k^f|8owg zRxhkGDo;XDIetzmtP;0Fq4=Z{i~R=~fd;P|$`HRb6%NRT=U3*h*>F`l!`r&38b_F)vFyblqwwoq|tJvyXoest)1 zXz#iuPFxn*k47;JmC?sR_&bPi%Gpy%N)gI?6S}Hw^?jU_jS>-a2EA0r2T1bP$QqAQ zb`ZCAjk`EWd^~SH9l4PQNI>8!zU75stDuW!@I7a|aqQFrxXN3~Xw)4aI)afA(qsSZ z2tZmuPIrCsIfKK#r9lWyx?z%so`msn$8ArFZeVDgPc&L)|Ce#wxEO?MnXqybN=qC) zNa0lKeeAfc56EkVKFX{+#CA+9v00W~Mjz2n@hH%BJbC+`>^aW`r@-n;^_a&RL!K@X zGfi+{x2K*E{oEN~Q*d`VX1uf+9J`gqGyW1rDl$G$0t;g zrm1E2pzyWVIOL?{;1O@>Ps+LyZ{3P50$xDKc#GckWe@0#x9*OLw`O0>6TS&Eyb<#N zJ!2z!7sXrKz^;n7mf>1j%d6=!`aCshZnO@eef!DnTCvd^HQ^S330t9KhEFTFlh$_Y zoqX#G-hNMsKPz~94K*|siP`#AXX`I}wZ66st$PP=U!kTgf-aZ_4(%hRckuQOsA+xb z`V9Y;I^Z$G-<_q85Y2Fx`g^X0Ryb<8pMG{RqI`6s7EvxB{sIS#D8HjmDg>e;%2UaH ziS0x^qAU@~&FFYDvMHG0h_Z~LMLKgrPxiWWI;S)COK=;cZkWMIm62jg=FgN@Un>lSi8aBcs7{i)!;+U zn(wnxxEmxLBWammz^J&w%PC9%QgVcslQ^P=z=B$M>A5d!$D8kSXv=jlHa-@K6>rj- zz++ru2c8d6;JH)_Jj;s7mQmn2DCRILa_kV!La*%zw34_ZZE!@O*V;UXkp;flrXG%D zbKy+ere@+=+SDU(X$AmbXe=+f=a>B%FEi|vh-ANxP>=U?Lyn^)VN#8A$q`lo`x&xpY~HMHy9{Kx>o zWgVfmQLz*~EcCFnrA5EQ(w^z4CAXKX5$d9)J?Apb($e>#F}!*VV0qDXE=ax-dKmUi~fwX~OXW@#UG+RL}8(Wr%dv0%k% zX|HnDypL<5vST4XP}a09ZJM)Mk!OPiUJZWhw6p^}8$4Oo^s=lV#9wmF3p3P8MmcP zp$OJ9w5N?sk_x+kWHECck^Kt=XaJMEvk=ZJvLw0)E;PE1Rm3?YgX3fjPV{NYWxQ#1 zW+ycp744>>A6;JsQyU;16_kHAl?;((L*NBs(`B3BUS5BSj|g}XzJm$>3=8ZXF|P!9 zP2BD!q0{WIMq!8F@bIhjx70oS>a~=t`_^Q%75io|N9+`4mvg9F?OebvHxo9 z9*aTvjma+WM02Jca|QtfmU`YJbpwcLBPAi! zF;jaud!S+$k2Uy#&KITAGy@lnF`j|+=4bq5I_T*_#PsvlSkyC+XULUdYTM61-oJuV z;5;2`@;C6RpE(Nbt2KEXuBBCb_exy;qBVIuwi~@vXcw5U2hGcN!5-poPV$f{wU*OexWfxla*4xKX(>aT54Mo?($adHirAz+@ zaqxK2cC-<->@~^E4-Kt@h8|!~cmzqvxhKqL>_cKt_<@gE9TBWqd%`7D!?`Csk(0!p za0>R?wLRfpe9L>n&u~-XLnnuS;ISt>JD(L<|M4&*wN5kEJ?vt#1?5^uu z4WI55@|Vw}F6B-AGz=Iu)gYfo-62|cKFM0;tl5`q(okdcttVNzvZfsXU+b*)@fT=6 zD&iKW|IkhS(b-wfnk%`cyTNqXpgE^GYOCQ}(oS;Ej;)4Mh^$z9AfO%R^(5S5X z(d`?!GzTyb?&wz7uIT3~x3I|FUr35odb})6wtv9q9R65F$PrUH9zy(+<8<|1n|8~; z^Fu@2(tyiD7#K;~=D_RHbkJ0$HjBjBv#NWX~{J=|uf1v{;tvDn=P2?$xOe#DgySbb` z|G?Gx%dbe8f4E8sp=N75?odnnA|oD3{4fr+oloJYzsZ(7<+9_D&xqS(CIRNZ|CDZV zLInN816v&WalJpKOP8O|^hH&SH3nLA=2Buwe3-&9D2|atNZF`Mn;+=WRHwnkU`ytP zuwWKaq&HHX#5oZivk6n5QmsDG*)dR7ok^wYEPay(=19Jcpb;v8k~l$2r$fvf%7}_& zV$Kzm*0cx=q*$6v(Q=UfI}TlByK2Z#+4JeI(tYtc0HO@uh58GoBj&jvCk~x9Q@0K$ z?(JT7;Dt;3An6&LNwW|AWo4U4DdMF>hwF{i-B~EFcUOi(cHK@mU4*(Cr2gD%9;vOJwl==nkkm%MPO4vVoq_n|>e=(_?}zb1tPY>bJ8|S3UScTD0N~zH3c1UEU8|+M4xC<%~=`U&5H;G zSxo;~FJh%mV)hKMB`DLtMw{hH=v0O#s;-RuL^K~uz7Fq2Z(Hl~jn%%*p+3f*w(l;G zv}~VUk0?X9T33+b>={k;c1(0Aj;9HkDVVisYLBcz8x{wfH3Q)WHn!v4HW*~*In4r& z$4C`Xl26z}-`ROC5g`?sEhIV5X-bxKPNTZg$?X50U#+f3qo9mun%3cXXbL`MfLnX^ z@8L|{PW48Qy=K49l9Y3C+0SD*9YXJf(+t$r?9>oy+P0`C;@0N0KWFN8Y7C`#Sk$g) z>q)3*$=CkD|28(&{$lzyZ`^7lGJK)rgXoR_pKN zA+C_SdQu->N9@aQ#7t>K7`TCF)e(>Khn4Wn3Hs2{KcB!CxsRn$qH=+cDeX{{$O*6w zJJZi<75%20GUosFY}-rwc=nWe=>ThwWfy`W*}FeD*B({gYmaO3d6VebHa=?YQ9_J3 zX4~aR@t$orUl29hRQM1bI_M{f*8Rln!~Z)^q74Q?Tc=5bldZs5E*1U{X6}-t|J}?j z11_C*j4sdI(@%Tq5O4mWo&PU;6i1`Owgz|7-zQy?iDgM* zd5#$Cp;~wQDUJzbM~@yZE;^i?KwDS=uW&MlayZKTpNErIqYGM)b~bJ`g&&ApJ4h?w zOg)^ul~O!{G(<}>@OJqul-D)?=LEhRQCH*iS!Tvs_CA7Jo72B=rXEhdMkyYgrdcBv zdn;@u>gvxn!1d4bwCh0t-M0LvQ&YvdwvAS?Jo=a|yyQD{znG-4G~BU4R4tltDR2`x zXSa8d>)LC-Ao7lN?JN?KwUNV2E`(hyd#_|2{)QGdAxDU$ zhJ<<>#NW=9b%-A%~`>TbDC~q2zEw;7rJK%%Y zvPU|JyW>iJ9H?HI#7bMTHo&Xa0ggORp-wZm&OoJRl!tCXTykCS{XlZCn*q%xi5cfZ zWZ;^WDVE*h4FgebKAQI$gpe4rA85#ey8M+uWr6+lhh|&_+-8TS9X4r6j`Vnr1^*lf zYon^DioJc-mOI#u!{-iAuO5;G;bwXA9v)i;A=I)9euHl(LD5eYNfGlxe35|^>v&o< z0+$fV?i`G~)(yHqqO3S{yel1i$Js$!ZQHa>9TzFc2eXzG8*(})yBR!7jhjb*T@Br5 z0rD4aeWXt`5yec}N+n}kVUUDOgy}sVw$a@~A$KS^%_xYU0C)1SjCiMu?qxOt9!D>t z)Gv(QYi)GZCf$!}x=rdvowRMzC&=b^Gb84YbjijHUwfu&h$7_|*reYx$%uKF5NCUe zw@r#+KK7xuLyJ?q=2-8uodQ?NE_LqT#DZ%I34zK2U$p+RIW{5o43TOTHOH_MsL!#| z*c6;|>~R#-=h%-VPRy;-`TTvvTumsu^D^@OH*;*YlfD0Pj#aZg(C65r)C*E9nqw)g zG3S_+<{+G7piXafvZaPQh7KiS!PJQk#c)9svy~X0kA?t>;h-PU1gz7}+Fx@IVim*&$!{HI5uSHrzgra5b*wafI{e^5?{g zH&MfAhxx+n6T_@l0A20$9#^NcoSnXhtrK_pJgw8;J3AeVZ)wgZQ_arI_aoSYa2H5( zt;|3nDn#lF!VbeA6kE*-2q(&Xdo9Ivdpd)12D_G_kq^v23z22;SjajUbA2*@RJv2P^69pF30{YF1N|I~NSe$OBI<~_ zl+6i-Q>Z!2IGe2dDH+R0*XHrpr;|g}eTrKz5F%sYK(*=pt9!$kD+%V=sK)-4zd8{y zuV6CDW_dkK6wgtZ!{9gS&oi*pZp5u6wTL;JZ?QQ`Cnh(Fy&$t6+bRB7w0^F@);Xz} zu3+75d%O-vod?po1mtMjLyeKnh0?+HM<0X|@7jm)a2X$s;Ew<`;o)+VanoqwO+fJB{pyfO#7$BX(1u}1F? zkv`CXV=F{_>W8(&`5C8!*2{5psl^AUx#Fb%FA|u##FoHC>^8d~f%6=!dCtRA{|>s! z;mdh=B|ON1=V8>~yXj*(Ma;o`w9hg*_!F@_wRDqX&nVk^_(QoV7*k9rUR!D!7S$}q z6dFzT_CPjg1Uq)Qf4XHu3O0PqIRTHp^26`o_+)wj?hjm+Oow(lvq2|}cH1CN%dnN) zqh=XW2BK~9CL5cv!or(7xYt~JbWf#i^VZ--_Y@+frfDRM+OagKata-C1~*JKFftkF zqnveI1e zR5jt(?Dn|Ucc?Ml-gMf3u%%`&z9HP`F@vw5Ls}jyon#09o@#tOSB0>I=e(M4yW%-J z*J6jxy0?(Hu>%Tj=Z`T3r+kdNM^FhIDqDwo_QdDOF#R@4b2;EHOolYFt5F^|PyEm^ zBFp1`LQje5k25(v?f`zd5X0x(1-&`dZNWX~)e}Tin^z5|&^S}{<#_u$V(vtSJ;4s( zdb9rRaJ|EEYso8O_UBud>m5OiL_Kk#d91>7=IR%C-aJsYIael6GmEaMs8^Il>iQV{ z*?Wv?63{uCV$L!8uz#1vsMIw^{ZP$wjLuTJWyoO$fLmWp-G&~bti(LA9 z#Od0(_vlu6%a9ei5wi(xaa{O2kkU6O*YTTn))|Ovxq05J`#a^x4a#!CfO;NnZ%{sX zJh*pmQ1-yHN;BaEdxP@T6zU;&_941-GOmoPdu^>G+ufEd1naQH*luwTU!4k)>{`*1 z5#LXZF&-wrHf#yxeZF;#2mf(Ij0agIY})=eFvbI*(YS)PY zaUWEWJC$)Hed@s2cF`w()*k-^u?cU6Nqy>WVn;sY;(0gnAC9=eQf0O`2(8&7amnYg zq{sK2^mUpvWE3rS>2G7HE_qtoiykN5tW`TUYYp>7eE2-d(t51YQ&?=ovv#;4llCB@ z#4(C@CWJVa?sJQy;H|ETW2h2`>XaHeA&vhwV)8NbmNYnGdUAn>H1q@fj=hU0FXNUv zD?J^D5mIj^1$mNgv1zk33{~x%98|?EcBY8$v`Mi`?O`pPh13IWThnK`G+zGjGkCEz zQM1?7;ZzI@*s4VD=n)I~n~3?h4y9^H-XhL%Uvk|6gd6pCgxZTrIzCH$!Z!2roY1K1 zI}Iaq;+Vj@nR#OZ|IVC{8Q7oa51n=+lE>!^_z^56n$H}8wl@CQz2f*GA0{1Ng?{3I zAN|?FtiV4rJNoSOS8tB9?+|3e+CY7Z7 zUw?j;z^@YcRRX_C;8zL!FC`FX(5lAyqo-sQ&n&Dgtw@<$K4)f0X>m&FoH^GN&MGdP zkusxXUPWP9QSsR+C(k_87+XAhdU1Ko?40766)6*oOXn1oR9v4jp|Jd_;)=6VjFfRD zSIzRu$fwLn^lQSb;)+6CjIJy%FD|P{$t|pyg(hblN-6UTD=N#ufiZq=aq$db&YU@O zi{@085pn*RUtCl%r~K@*3&s|d7nWUBTu?NtxagX*Qwj>oQc|y*RZ=u7rDR^p$v0FE zNI7>@O2w>_d8eH_ujGc})B&z+L#I?+ScPJrqsn>T zcAjB`QEg{t@@ZKUemLQ~^8_9u>Q&9mkoRGMM~ZZ#ZG)h5ZpIn>^A_mvPlkX=5)&m3 z6XotM%-Hi4e#*|un8`mE%6z}L?>|M}r%TM2cwxrtTj{62pffK^q*rCidebER%S5@- zD5MtEiz~{nr@Hi`<)^#zL<#3_t^AO)K#y3;DleH2nuR50**d);XCPnCbG0{gXy){J zs8&?rCgN<;ai_PRuIjrQi95RcImviGc{&Wk{==|?jq4tVcXU($j{znQNIdIAG=s%t<)8B5)7}U|R1Nc2KKE*Ij#Swviz(!yea48N=%mA7=rLqXv4qORL zOhf;H$-t}=ARpii;BCM~z~_MRC!##CAF%%rlmlh~R|4k(>w%8}cL9&Wv*g5+3}YWK z6&O0Jqazo1A8-cn3t)UdtozcD4}1Wa16&JS4ZIr9HQolc0rvx6IJ=`GAiK z^kO9Bo@yAqvFAGsxbIwyCvZX*_yyJhcL9^}MnwDo^aI!r_!BS-ICM-$M=7uzxCHno z;A+YTHUb~H2>JrNZYmV74Zx&Q(80Vq8CVZY2hz7Z@`3S~XEy?~fWu}(?!b$Hi-4uT zmB2;7df;QgUBIt^@%WC>nPrd{@CjfR@VGgs54;Pw2>1bTC9n-x59~b`^?|1X<1t@z zfc=0Afc2PwxXR?Z9MwwEIh7I#sPQ~Z~<^Aa5?ZX;5y(s z;11w+;C|qjz%b_7jg{aZ_$)9U^XrNEunWM~fH}Y~fu+DhuR}S^qZ5Jgm^UMV{eTmJ zD}klJdf*b^F5m;e8JI6SfQx{=7XUFoQh_Uh=K|}2mjHJGmjX*MAASNZ0rtU8SqA1s zKj1Xrm%u9E_rMjvvu^~XqbtOTY3222NDv;=$uP2eJ6N(lW2P6pNk7XxPmd+zm_~W*E84F;2k8fRll* z0dEBE06qZh{YUT(JOQ`^m=4?zycT%OaQHvqNZ=R1$-uyUkQeZM;40w3_ruNsF9+@h zE&=v96a4}X0`36j02?2IJpt|oE(ON_3F8Fp2Yeei5x5Un4D53j>=JMo@cb2M7g!3s z5qJ~u0pPp9b-=+7gKuC4a6hmTcuYF{18^kp1>j`hL4QVlV1M8Pzgn3xDWU& zu+K>F0UQSG_9W^9#{nyVi-Ajl%Yn}U*FBAX1A9D!eglsK9y1E`fLXvDz!|_{YcSrx z3xF$uzXR3-p8)Ox8h^$7I2Zi@_5)@Bvw+KiGk|TtMZlAvMSb8%U_G!HxC{6!F#bHu z4`4sw@Baq50Y3ni0#AJo^9z^{TmxJMd>i;Na3Am|V4n=k>*vvLU{sf!>%wG$>f!7090-pxf1Dk-mfDJEUyw8XH z*1;|SM+5!92Y|DH`+!S;$Gwd42Ic~{0*ipVftA1>qY-xk(||qKV}1jV2hIhCfJ=d! zfX@N@Y{2{m_5-#9Cj*nS;2(hLz=SaTCU6{Z0dOX8Iq-I19dI463HSxD9hkTg^|K)_ zU^;LdFdtY5TmW1OTn=mpt^*#n333A-3)~M30#hz9jOT$FzzA>}aQJ4(4R|$hC9odY z0Q>@I0^hAizb}N{eg*vo76EgC>wt5CZvbn7{kNdsz+B+lzyjbt;GMueev}6e0}hR# zUEl;@6)>v-?E-6o^}sKHCh*u-F8CVKD^finZFdeuWI32hZxE#0} zxF6W#BGCB<<~ML0Fb8-euoU!S^?~KUX~5Tj zRlps<6~JC^p+4{wU^DPmpmC{TtOlk4{{_qd`rbx;;1b{>U;}U^@LOO#@Yr`S&w%Fw z<8v|oz<$7`z%1aqz!|{7@1j011Go}c39JVOfxCcT0OK#iJbe%KfoB7=fOCN}fa`#Z zfO~-}fk!l^&Uv0S`?~hpYhPvt;gN4b-w{?KT#N8tgfAl8i*OghoVTDiRgP1N za2Uc15LO_33}FkxcMvW^*z;}NkFX5kiwGMK?n1Z*Va_=ie-REtxD8xA4hoEyU<&N zzel(S;a?CAJP-cWHjJkTOAyXLcrL<42rovs0^#!rHz3@Ba4W*Rzd~=Op{!o`FmT#2yP-*7*|qY!RII3J;NKJ*0PV1&i*q1_PPfUpMPrwErK?Du#0 zF$l{LZbEng!W{?~BJ4RG7YOSR)*)Pta4Etq2v;L~2jM1!|3bI}Va@xn zQx{-o9$_KEjR>m{?m(D8_!YwC2&+Coy&yjeMWc`!nY9SBiw^<3c`UGqJ0pKL3lI583=oSjCw=(9KzKIUqiSF z;Vy(b5cc^8%6$>+FTx=RS0F4$c+M{58({+Ba)ccS*C9ONpGX(s7=(KePDVH|3Vla7 z2H~#}&Oo>W;Ua{+KS6sVJR0G8gv|)IBHWD7nTd8mn2T`0ztG+YPewQs;Z+EiAp8l! zRR~`}xDnxd2)85r&TjP67}7;J7-1{I5`;?;)*#%5a4Et)2zMfE_&3^R7TVw8D`VkQ zCu4q2#^Js9>A5U}@qwVW?%CUUGKrMzlS9E^{42!2)t~R}%*n(beR3xB>3?S5{pR&t z?3_N}loN&z9t2dyi)L_^eE~TFrqug(xycniE{`($36#Ov6 z|0|Qvd{7Bc{>s5`N|FBt@K1w3+Pr_77k>x%4d4$o`NAfPWJF z8Rq?$di+lC+fwko(H_0d@9bj}@fWHg;4j=y)mtO;Z4)pVWAAhIIZvnp>{M$bM6_?)$ z{^76ocJB4@|91J_+32r(_jbhlce?RKw1pMumBj%N( z1pKyr!|$&Fza015^oH`e0(R*c+0pFAb{qWtDA@(K6A$)?GTu6L3% z#)(&uUPFrV>=vHJ6E}{`yWRTew-4qKxc?0w|B}lWf`53wP97I^9%{Y%r~<$4yzu%+ zq~VvR;n#tmh4gKDMfF5>j(Am1tIzPt7^tT`i09^zc&Ob6Lcf0ueyCXw)m}NrfWI>Z zKLh*&;OCq7XEwX_xCnftcW37~lV9M)zXJSm;1`*EW}AEedhlz`4Y&7ifnNpQX76(m z=N|C)f{&Z=Qym#TL+-v96Of0nIw%G|6nudhN4-~unczfj(66NE#Kt7)J@=JE^LCC#Ia)%gl7-ut|^W@%w+zj-QCrK{DkfU;~@yfLm`T7`g zYCfaOZrJVK`(xb!{5^=rtsBEX8w!5O{+*rA`uHbR0@N4F!4K)v*;$Ek%Dq49%nTAB zz5)Dh;ExQ^bBcc__(Q-ShQHnXRe1H&yARe|Qt(5;Z$bG^ zGVeG1uX6BjfG;-rd0zYt;J-+5e+T&c&k66xYrwArA7%@;2yg2{s{G(rBmELHf6$S+ z$RhE*abv3T(YuJLd`Fn~S9#?t2R{t?JKf|da{Q+F8^Bk9xAjlrJHX$9_)j$NH|8H} zz^?*tyFVBAYytly_*AxZ7i4-thh8_+$b3;{lKSQl*pQ9jf0~WH^ejrE`w98BOW9|n z`Fs)n8_}<`6Dp-H%6~bqJYeO7==(CqtGHG9!Cze!-o72+7p36WfNuqlB6#r|^N%gy zXMwlb*j(JQ6Z{(ob#}(g`^iRBavPCM&H>ol?}xRjpp21DA!H^(CQJ{iz~>?#bIdq0 z*ELbi zHL8yi*pY|956?n5FFeI7!&@6RFgN+$CAKcl_;mj5uTBm2ro)^9SEFv;e^K1}&e zXXiO2d!Hd&CbHu_*>cFvKc=(uUeb%ZEwam5H>gf$q7!{`Y-i`O_}gvs3%xd54E}TQ zWW!xPlNX)o{*~Y_I8L6y;%gi^jpaErTXe9^72XjD1+;Y z;_5(L51bg@rc|D_kjWd`*?A5A_R70h<%iPRfwX=C{!9FwJ;t9_=0{3Q_1PTs{W&K= z2Psd-`Q@^X^7?iWO~gMAo<5COfWO^(FxDMj1HV7UV_P31eb0d{7yzDL zh?RY&kq@o!`+My&2C{uHc22~7*&_{EV;y56j8*|;jyLl&lk1!ETL*p&_~T6eB9C7R zz6AUjljo%#W!qMRp9vnO-7By7WYq4Pz*m4D0Ndo&$642B{V=;Da%GRK9%P$xLG6Ov zIE+ocF`Vp%tTR$x`yCEn1~OrOY$5m^;42{Orj>byDh%CU1-?JlJBv*oY0z>3@d@xn z;3?nk{l-4ja`0ooquM>*SnpT|z5smKJmD4ar-47pykFLxbAk1SO(6bk{GB~#q?bnK zM7Iq6kW}t*5GY=0}2N%@Gpd?_Q?gm3u&a&tBH`?c0p>rYJkj)8Q9OJbhS^y z%b`lgJHRKvk1=_p53B*d418F9Z2`Xmd{}*D!zK_v3-M=PTIl5=lQ+R~fe(Sq8<0`$ zc99`tv|HhkSSNvutsE3b75GCg46h5aKg*ELGRP?V^Tlv4FBbc=9dZ(jE!nNe_mAzYBbw-M&<5-=_j{+hXBu)B^rv@Cdvz8-0`P z9Pz4+_QJYrJ&`sdou%g}hR(A0&0O%WfNubQ2mW^N57@ZRA@d$&!faT7M07}XXD3`8 zFOD*09@O|*0UOg3d@bng=|(;&9b->+CgPa@x%13;GI>**%CZ>zrQoOe_$jU(S_%HK zkbKbn8^EsykKXU)Q`S6*-wOUI@U}S@D2MFa7VtIrJNu4&FOEz$$P@>ikMCUr-w=Ph z^_j^AnfMa${ABQ9y1Nnlso-G_z59)G z1KYtDf*)=2E!>ure)b^8nFM~4$!C_hZ9peF7J|3gdMfh_*qtlD-%W8vhk1D*U66g# zTyPDD=PSthbdF@kd3jj|nd9T(?X?#CDDbJ`cm*=mkO|X?-Qeeg4{MKp-+^xk{#4}I zZSMrRTe1}V?o5>ThLb%RlqKsuo+nVf&Okg>b>Zg~7J)w(d{{nKfS(B7W-BQE z^}?g~d3i8=z_-9p$Ngb?vj==xNcvRHLL@u}{AT=}{Ri|QZHuVQcxgxJX9QRr{O#bw>_avtrxbsf z?>-nj-5+KjO2BUhA7&pG!T!7q{%+Ev>xTOENbCdEa|hy?Jjd>L=Yn4Yej#{YJqPT^ zi;%e&GPbs)ICgt^V*$Ml03i!cUNawro7L9(JbqIMXydSX#@z8U0VdL6BIBE^xZF5K} z#~APn!H4Pf4B^A{dJ*^z+;1xf#lHglBJg2)y&n9{;KSPCE$~ah+jN2A-;?J4f#?u) ze^@(?0e>%epFSGxI0O8v;KSN+5%`_pZRMwST!;VO0=gT@s#;?cjU1 z+UtqZ83_CE1@5oK-`N-V(=mOyp)l}8h$qZW)AOe-;KO{m2Jovx@?=1b;8?x6Ru~4+g^?JPlsi=_q~}`lkIjs)s_D@KX}u zcDf3DEqGtQ2-xZQkhu{uwzkYg8n=L7nI?|)kl6y6u=;!p{5J4m_GypsVfJYt6lFK= zxAjk|2YUWU%lt&o1zr@ppD#3`}Ny8~)WQ#B*c2Js!%(M(|6( z+w2sjLw4>i@XBBP1v(sa|1MSIF;1NbfA z;SPAbF<0yW|9kLZ?YRd0Ht^`i-u>cd<^tLRekb@{CQo{|&GSWfLFVxV;b#DHPKM0| zKgx`w$-AGPz5N&X^G!aJ4^iX-Q_tis4A=n5gKc_#Rm!H2cgV(`BOAJ!*Ug8v zJ}m!R!M~RxetJfG2lz03r)RgFMRr|M?hmW~nc&|APtmwGLFTBrfNp{9+6}%2 ze`k+EEoj?htiP178CEK>Y3IL)H&-0nGk>qC6OOYz1WI zKqjnB)`L%g57WK3z*mDu^Lu$P)<^b$Zx4wdL#9&*+p!pYJO0l885VuCZps>UX01 zAXb4Vo8s1!VNZ60-vQp%R@4sk{)P9!qpH07jWuO@FT-B&Vdbj=-}CbD_!Hpw1#gQ# z7fG&x!X62}9e-yJM~<}KWpXAckB=jcX2=|bzg^zwJFkJC1wO1DKL=k0K9x-zh(YrX z$b^-14EWV4(wG6B-j9+hjm41J4jEfrP&rqE{{nniAKw7}eehv@d@J}p;1PKBWbC;) zaNhe}5njez@JE6V9sj|9AG~e+&qb0m!QT&ls+m6ZS@B^=W(j0ogUq6!jNx~#hRm=l z!}qr~fiDM-S%g z#k+pMhvjbw_#NQKnduwPs!RmmYe~Q^W_tTrb>PQ=xAjM=pQYdn!H1>48hjb}L(KGz zXP!2JKOOvZlQ-sGJHRglAJ&(9j)5M6A8Xz(XGkf3L%`ny-qt?3;3tA#4Stb%Kk2!l z!wryet_s)T4)6oPhw0!N@F#!|(}6AE^TCJdz)tW5Dfr%)Ko18W)&@htPXr&P1Lff7 zfS+d8fuREp;O_z-rUM<|m#0X74fy-Ohv~o;@IM0|rUN^{zX3kXM)W=n>)znQ>VGKs zkHLr8fO7EJSBKkx2Jpkcht+Qf_zB=`IyMk>x(582;6vLV{Mq2q%$|)f&QI(F-vmCi z{HMd81Rq*{@K=C8(v1Hc&xX=_dlrKaYhQYwPb>J)@`GOrKD7Mc>3w0gF`w3Xw!_9< z2L1{BolR2OZ=ino3ooDa-k_Wx*y|}5_x3BsIwtr<_}dqU(U*%Lvjj3>eQg@}t5Wdu z!CwtNtS)W=e;fEp2bV5~Ob$pF9tZyd_^`hA8u%Vd!`tF>@SmqhzdsD&{1fczP#Xv3WoA zK%YVT9Q<QcrkN9L{*` z(?ce#Pv?T44n9mzi@~>m538q{;Aerq&CEmQjjms`82mfnYkfRBZj`^3;0Ir8zdslJ z2Jk-vpQ@g>L*{wNgyk{21n(&UUyS%%T`+WIF!;B?hv`ZQ_^m18uL1uu_%K~r0{(a4 zFAAhD%c|`EK_=t6a9!C1-T`mZ1**p#;Ex3#RtG&xp)26;HS>^pyW37fz~2G>d>_y2 zz7+pN@UMXnYsWh9M|OnQ@lx=ofgfzfZ}i92;KzZt)gh(73H&JVw*2LS-vPb_e5yL` zjmoqa6HqewezywLqp8GGYB~8TcCTVf}3__yyp@+VMs3 z7lRM8DZ9YW0UuVzoHMZR3f@*ms^?+g={w?|#o!NJmbwmBL8c5c zVRf(({C89E+rgg%KCI7WpXoR!f)8687!3Xt@cqp?;;F4eWhen(0Di8?(^xOh=TY4) zhW%Lr8ReT^x35p1Oy6`F;yU<8;bmP5z9)EFUZ}q5or4beu(Hy-2=}Ha3%#T8(==rv zJ2w$&sIt7-Gqfx-5ZCJ|^0Em0YawN!I$MWyUIc$T{?5K3kj@QWKi-IVCfpcaXWPLS zrQox%XmdgeelYlf;4eTvTsx3C)g2p4z@Gv( zLhz}4oK2AV0c67RxC8t%;D?6fu_qSrUH~7K$06Wf1|OEkiQs<+K9wzNfXsg&6V{JA zz<&t-R5Oq0N3>i?y1fQ`&zr*U-va)N;QexLmG0jO{!rW>7JqM4aAAu0hk`#Ad{`Zn zgC7XqHzy)HVC-MDKxS%49F)gp;QzC4_a=?N* zU`0mcrG1<&8IdRUaX#9I!F^AQB%B}8{gCK+a%7}4CHe2Z3xVCA5&3PBl2dZ^ODd5#vh7)A9f?7#mb@RR)%Z zGa`S;az4+9{3P4?VP@o`Ea$$g$Q9Ynjx6Xr3UcrQNZ+0j*^%iykQw=7rgOPuqW>`< zN+Q3`aHivrj*Q6b8O|#i7zwHLr%;8@k35%w%4TT4n#h%z&UG0#BTc)+W|AMP8uy^nKwuP3ur#^$vnZs_RM2RKh>L_W@OZpdu-9sbXXJk!V7l65Tp z{#*94jFmagH9aD4_i=vJBeJ@$^FoidWqqBydPY9)*W@3kcKmtF&2>+4*( zUt~jH=ce8fyhP%$-a~-z=pBLPU%UV5`1`H{kR4PN#(?j_0(EAd{&sf8 zhgn1L%xL83mmc~2MNhIU*tkLi%BS&A}!?}qR(u)ge9!_b#p7BWr z1pkmV%PNQhc!f!qw#r{O%7VBjL?$_LWK31`ZHHy_JwGxp<3}02Zp&~UFe{1jF)mW( z#7LIpP7aYv$sL@re@WzmjP_oaIX^OE*DdjF_-ze*TLa(Lz_&H9u> z4SZVz-`2plHSlc>{QtKGa*yG%4_M6MR<+>l)yD=**6A9g7E$qjfD1j2{(4RLq8~Ee z=XyWCL->AJ1EuTn4i4S_>1FG^=>@AqrM7e*h zzF){`f=>{9W`N&yAm>Y$Psf>akh{#HpkeyA#HZydG%mnm<98-7oj(0dm(FJ+zFw7M|<9S(}i2gk#@Vh~N_ttsI1a^*>-}^C4uZ>fe z+6$1sDUfKLwRdp-bbV{0pUCbbA(nvE^_mbGU)+~*o$qOqQS2P5OQ)~)`G9D-FJ-G2 zsViu&{9fCK?}PR>(_c~?(r5L%K=}X2?;$MyjsL$ms7I2*uw4G5Si%YkXG+*2;bIAw zNw`wNwGwWS@I?u?O1Mix=V(V=ITGedI84G~2`eO=DPfC*izQqp;YtbDO1MG77bV;( z;VucCL6W|Nxe_w^_5bg=GDF=wCJ@CLd(_e&#sbe$fK?vH+aA4m6F zKi<>P`s~N|b#y=QFX3*@f@c( zFfLLGSU7r-;W>U3>G`>$NM?O$Jyi$c3S4z@IxGJZ~gHc>S#Ob z$NM{*#Qys6!yH@x&vFL1_R=p8>n?ij#|JvaR{RK4O#Mxz$#(wP86;?&$#im@mOwp| z86%))wKZsXE@3Ad<$?}{_j!p z2Rb>@?mFEK3Log~zR#bZKZtxkk=OSBQ^ETO;@J%SF%I;U9LjWeMDaS$$bTXM(`iJ&cOMC_k&_U ztDGapGH|lsV+DU%GD6>eqN@!!f;cd4o2tKld@k2Op zt`&UIM+~TEQ1It7z;#+8s)8LNkL_^vTkGdgOdu%TxndvAmYbr$seZ1N`nf~!t3>|e zYZ=h>_FKUhy}-C`-vKaT6#r+^j|wE7VZbT=b5CGE+krBXANv=^M~M7-!F#>UfMm=0 zkKottWn7)>#GjX7qDJW!{gH7U|GmH|-I`*?pX9*#K;(C=^2=9X0JhazMnzG&+KO;42ri;IBl! z6*$!oefEH^`5ZXQMc&!Sz%;?15xnDS26X=aE%<|XF|PaL=z}=^cgh)GEAdPNPWgQ2 zT?Wv6>Y{I25Pt5P{QGFZTQT21Ff-Yoe@Em8e93}Giu^#5m%q*6WQFHALqwr25VB72 zW#U&v1fLI_@^hqR0h;PXWC&n#v6BP7Oy z4ww3@W8hN3j|WcmpLl}--QODopSXGC5048z?Q#}`daLV?g3r8_e{1;+C@RHs zzZ6LK_u+!y{sPNuefT+Ws?Xp!^*eDQ*`)>~@Opb%f2#oIs0jGGH=CC|{LxZmG z0;l{`iN5LjZx;CtVyJXGUMungU*-E@X4Um~!56*p$yRAM?lmgy56^%J@`?=U_N6B;QZ!U+dewz{yTd6gycg z@|#8e?Y}XAVyY{DFvqiK6aUtF-T?eSkuih0B0uJ8Mzy{@BY2M=F%Gk)uJ;9hD`%>|Dq>20^KfiL*%a!`KN!+@;d+TDS21| zv9~{${5V56{=HW+aERc?2!5v6VeN-608Zr!j^oQj{#t3T!@0Vhb%HOv&L96)!RP*z z@jE2l!N+s_!Eu(}iA(kH$yF?uFp>ee@o=? zQ(Y&a;FNC1X8wJu;2prJ9_mUN(EiCUfm4538SpFKka&XY28FoM)-TQiPU+@Jz3FmY zA^7L}a0Tmo|0sB{yq^On|83=+ET7Yp^BaM}Q~Wb-=HCOdI2M!`~f)A4MYr5b^Kp`pJbC)x4l<3JM!N-bS6?5+_6a432v3#+_vllqk zv)(_=5&SzCXej>PGEh$tyk78)VrO6m)pZ?kU55gx;5LOPujf1wBEMPUU((axE=RzC zQ+`T&Fg{rlIUBgL=WzxkTTY|MZ+)F{owpZ6{`yINd1n~MzwC0xwVoUf`~Zf0|4#x= z>F%m#nAUCSx>Vx%WGDYVk^_g{b4mIC^e+sw3qCZT@s2$V6bpVGaEd>;Zt$SU_X+gV zO@a@5mLt&RosWFcxc0e>;}X5or-0+1FC9_q=kbD19?O#V$PK3hr~JS8PX;i2sOtvc zx$?Ie+#&JwoWkfHsh_7Lo`Ng}w4T%Z9V!0cy7aNYsUCXEIMP=V86)x^zsJCVg4YW^ z{R#%!1iwnfBR`DbT9F^Vm_co~ZxnpfZH!0dp8pa2nbi!;68v9+XMM^*vEb7Sxm+%I?r3@O#aPd{Kl=jRl`=fBDLE|G5+eD78UU>?=AP4KGQ`M0)9 zhmGX;gY%Sf;AG$QzLjjNIMpIQ_s1O1L=K!AM1GOj!)(Eqi~K^dZ@RpFM{&CM-pGQw zf1L`P?9WoM^I9J+6#1<(ZnjJO4~Trvz_{?gB3~u?FizwPi@2U|zK{W!J9W{g-Kd_w zknwAp;ID{$a6SK@BESAQ7S!^2qdA_He`Q?zGrtym(DRH#?fE)|<)04J!-<0b;uRJ{ z^Qr4z!E4v?Z{5E1J~hh!w2h2w{ont)jQ13KBHhn9OYj5!#`5JHICleAdWiVw(sp38 z$Ul6QAKwp-8Kt{M4DF#zJ0}SqTvu!te3#@$=krd%SNw+~xJcr8Tkt;DFd)_B^n;zE zbg$UP_+=trC-}!QE?~G+*8_rI_9g$;<$4!5mG|C8#_9WlboGG0OYzVB4gZE3tE*V> zvfuJ=UEUVK8&)x{`^9ZKo4))sPlgraLRws zZr>{M@4d|OQziZn1g}`ZfX?R;#S~BSbuw_OhyE`yr}eE}@Wp@hNas>FPt{H-7zr(+EKe|)!{FfQm_5Xt4AHK?X z69>+LP#B6|pZ7dn@G`*<|AYZ)Hs>-n5c|I|P4J@baq}(E9w9;JJTcT-S32 z23D$vLH9FWA@STL_-1Jrttab&t979j8A>uouQN%0U0ROYq=1 zkhcWCTI{X%-*T%sp5Xr1Ou<_N`F~XK*Oqa{b^Y`?hvRuall!SI?+n2=ihrf;!{ve> zcm>C!>vM(R!Tr-W1pjm?%O5KB*6&VA8z<;M}CzM)7amzAuY>-hUWBm;>i{WQ_DV8~ur{0uG#sz$yNP(t&ijegvGx zJN?|m0Fi%4;tB4X{7K?@^|vfoB=Uz|!0{jQ2m?C)If9SR@ayd_1^?Mbme+c|9XREG zXrSGD&EWW-eB3YpJ;AsBfbl~(aDFU!xeTy+eR3mkivQ^EvY^(JcSQcV#~43U;@Rgy zmR~N4uiJMhaH`L7VsAA*U+|#aepv7uKH`Xu_ygS{=k_WPq5y`3O@H07CcDg7Ye>^ z6$4`gzgO`2dl}IB&@;yIZ`s56V39vhaOVLA-24k3TnG50;N>^7ysn=UXL0T??G-NkZ&NHq*{cB0og*U-#2r0w;Z&Q^JD9 zBLAkyA1(TGwBS=}SpFB{KYS_pJm8d{fBu^RU9P7EZ~Q0Y-x2u(;w-;$Cj+{FO#x2% zxmN7S9U|W@xPGo|coq|@C7#_6^KYHcFGYTHDdTMt&!AdPcg{uzbiJ(-e5ACmZm+$9 zk9(Ho@l#zRW^+BSmHDZ*+eN@B|Gz^&pzD=P4le{w^)vou{;m7bt%83ccCwyn=dXe< zlX@!_e0&|ppSy2{LQqU~RRX8@zj}~=>-v03@Z+Ulz)e-xClb%+r}A$xH_msE0gC7R zKQpfDr&jQmC5)fQ0lwSH^5s8Z;3mOu7ksnWbA4WV030ogJp#L-IVvgt1tsIZm!{vep&l_w4PV)=>++L34|2^RPUV&7Q3B9L$ZePKu z3}en1!Eb+_aeePH;8fnH&tkls1LskZulbw-tyjGpIsV`|>O$Z;PKiPVrz<@9eCCyc z2mRr@B>ro}4(K>P6Fj(1l?O%DGG@Akz*T#_z^LwbO9jvPE8~;oruBjc&)d+)RVbb> z#2!u)`4P>G_xOZ?g9X1@@V|&(I#lqd1P`tUz7L$*S3j4k$C3S7IR4FRID)|v&nUsK zmHwj3b)(=@KVU&!C%*-*|CT6JuvOv7=aDil;dE!b!_p_nO@jnK>+cM}jZxP;!T0`+ zf9w3b4V?69%=wI?`P6kpE62a)7yMiI-<5(N^`0Mp2ROy^S_$J4IGutA$M<7kNU6PM zz0dMGKQ{_~*J{RfKYb_!-vXS{-6jL_M83`0A@XO+ym+qQqZ6F&_a0(EmurdOr*$%p z=2q7>!F!2a)$Lo<&hZ4#V=n+s`3df`-y!nB{hiH9UJ^5ccYz;Z{MLUSf`U-JZMl;X z4D0GTPjIJ$e~%FSdcjxzi-98re_HUMpYxgEy=C65%X`c`PIu?;If9WA&m7?7SL^4N zb^IM7-+Dg_9w_pE1Wxtyeb`01?%}}sMC2#_kb&m}KV&|qn|O(Vg9L97JUE`-4V>a1 zc{U4f%i!=uk*|A;f0s)pB-m1s90?j0YGU zE#%LXe2x=br+r!Ew`^iTtyd>5;&#{1g&!mFQ~{@a2KTk+0H=DJwv7dKd4DSSibojV zEb)9I_)n$XVcyks$@e*);BynJ1Ro&w;J0!AFQaKSc09 z3O@HK2F?+D;9`z{+4T%e5xhk34Pptv{aur+NrJS5+eF`|`C%C`7Rq)$l9Kku69PX8P z^!p)neonfQ^;W+pLD%OQz)3%E_>}LzNb<8p@I!Vop!4}B!51xNT-(Wa1;1<;Q&{jQ zk>4zM@Z8{T;N<7%_gWN*eE+LC-Jd?nK%U^0z$yNM;SBW8=I{!U5BlLx3*PHNmb+Wx zDS+Qk^?#t8d(?WkOzH0kK8jinS+Fk3_MS>^Ru)OZ4KLxIJfEoV(evyA+qhEfz zl27*224BnRZheO3DTH?zD9SI$|27w%wOk6(Wg{DDr!i#c%0mvKCsKlkGg1E>67e>&r@ ziu`9Hf6BWIGzmWLM;uRZ{&KtE&G6A9Q)o5`6KUEO?^G-zxY64>F+j zcHf&go=;$h=+gabgy7EK86Uxc(-Q)@mgfa75&61LSy1Qa9>H%GebD%S1P?yvG7)+} z?YsJNjz{ZfwcsyGe#T0Eo)A3fpMN3vwg*^H>uuhT?fs7C2|8~QwF+(nPWf4h{L*y{ z2hMX!KDm8+L7#F(#ta4nr+CiW!{`VhW5DV8O8p)YeNU6fZ~f3O|AycTA7NbUL*Jip z{N+;58lNioqhe1^kOZy~yyiIuw7uFS_`vOq>weMm7S`wBy4=aYsa(N*mo=OCHT@31WIptPP_ej_ex{B5Rjx$^Evc(J>BzOyO%1>}T_Ey1z&(l3B@#La^(>0L; z=N-ZId$M#p?iGB6*llem55JAm4W0`cD|pZksRK^!wet_0V2PyrhTt{NGca24BUZ5d zo1zaR1z#+9$(;;nJ^8iZnO`w}u*mOsJLfa_e9*DLDL+B~VWHq--{%O9mUwnZJTEje zaK=6yelGaGPvPG~MgG7$XkLG~le3Z)BwO%9fK$4|WS`;*!7mkja$x`TCBYwhl?8P_ z8uc?SS8yL^25^eM=wB>9TjIZ6@ZkEu?*$+FCl(wf@&~Tuc!KkbQv~1o3JdD|%n>|k z-Y58R;_t2F+nl~=KgwsN%ty`@{A|HLdY6F$!EYA4&piy(WpVh5;1~Xlf9rl!a2LnF z68;oj8gCK2<^wIua31=B$k#}_==_wd;&ivdKc(vs4x9vVisu9wC?*KrA@Yr1GN9x6oyb2v zj`7M24!4Q?r$6A|hjQTT5xm!H42aosCZIj29%{Z|e2U25B=|#8&(j6}hv32IERMRD z<2hH#rR(Pm!SDVzM=)99IS=`zeXE&wa>jcKzDVTP!fw%3tp3OMDFk2rGy~c`AMta0 z`xXMHas{9FpCfp1yn8_639bXYDe^lc-BTq$d8;Yi8Q+8AsOx)z z2gl{L5>N1)-X_7vl<@spZ$FWEg5zDmeVp#ErJw5j*9(5@FE}1umWKo%CgZ7e8|Ndz z`@!DRbub6csrPgI!E+{;11EhRbP)?eZPfLU$mee3-$jD|L-5C?ztjj`i2PB#ZC=WN zPIoqNia)q7|3i_VEAjM|c%B#eo8t@|EBGrS|MCkAoFMpDBEM}21A7HOY7OZvYD*pn z$QC>gIOVhS0S0uxs{l^& z#z#o}R{*DUpS_R)o$lQtf2`D}&gb(Y-@lUOXGS>uOyqa`n13I~fpgr0obDNc^^gYO zly2~S3)hMK3s-Oi+CJPPcyPV?1Hq?0$MRY~Pk)HhJrN;Y6&yGXg75f>fx&`r7Cbnw zIczP*GeG)I+xf|YuYZT}8j=4I zaH_Z9bEeM<9@L-AhdKU=*Es^+PbUjray#RFCH^}FANLXi1%m$__|ce0^cO#;r{GzS zaDIa4$p-=_ebetlJxt`M3Eo>eiteYs68w&xEU5e42ZH}V@^hfXGZ_vB)kAQfXpZ2) z^Vrt_r~FL)j3dzTY!^JZ?-qHK;}7nC9SfY|3BFIJLGa*vgjNY2eDBKNB>td%?)w<0 zJN*>Sr|$0~1%K|ljLUHDOaV^oX82N;B665^>VZ=}PkxmFUEWtDp5SwQJ$}XM7T2@< zuO*(rz$u>Kdfg1cGoNQcozDe=Z~h14V$Phe1mE)l|B=#P$^~x`Jowzl zOTek!gZt*6iv0Nha0KT|Jn<(u{-x62bv~Wy)znGMvDVhu zf@r)c(YnB?ZH+a?qc!b~jSFy#@hb|+gio|3mZ+Z=!&N`%8>4M1Zk6q26J;K=&fP0g)w{3yiDZHZW-zFOt3KGsmb5Wkw6qOqnLM9UeV z-^1$bo#+|mQ^t)g$1Ux%qGi#x>ehI?35A?6b?l_lXzApVXcWJE#jNoINUIeEka(s{ zm{3_-6|EXOuDld?mYhF%?4+{sxZ{k;=R`{(vLsq#^@+B!%2?Ut z(G{)DP0j61)$tJ(sGvk?Y3XRU?#e3jqi5nDz`0W^3!)WO(UO)aRl|@RqO{&!QcyaV z6C61=UX6;gB!N3sr1_(wlcKG0l`j;$E#8_a)5#f)1hFV;yb8xEmK4oltrNF#P{C*%rT+0!Ro{it%EBn=fj`ZH5k`KbYA3~-Vzc9| zCHb7Zr)7l|=(hQzX2%od&CM5&t&7KMSnnoRMx`>L^`x-6Mvc zjF(P5i*q)*r4@Qy6>Evt;PPixrCx-@In72tTQJNl2=#`NSRyuFG}Y-^jy__qtru89Zk+U*@yhm=*p*vPF7BvO5*sb7LB{YxoS{@{4O6XFnHb(! z-&9tEW`u6R&INsgkvxisAAq_kYHuPJSNY2E8l?znd$^f1(JwD!X4kGDzl*!a_-N(0 zwCxd4)_iED=Xpt;f0Lcr=7ZY$wAobQYA%gb>b9@z%BS$iAPlXt>I)UvFoqZ@*)zA! z7OXLpqWwz?M!_pD$a&Bl-%#q38Jwpd#mCQhms*ECejZ8XOvyy7Ant(r7m&w@;k zRx}9tuJBw$)i%D4={NnQx@&c#H^M@Q%j4QA9+JwcCSfwCC%(ugO?#_ivl?g)*bQUI zV?XzhRQd83McWzA>0G)f_-lfKS8Kc$^@BO2n)nnZ7PQ0z9^LSYvJ#Y^JaTdGk!_i8 z(Q<(rCQG4xYSxT7Sc*|h&8kN5py5r_()W{5I&RX^QnK69e(7e${sw`wJFJE$t>kj5 zc`?QVHJ9j4Yq-s(+LN50*{y2oQp?%04A6diB@UC(TGCfWv{lD2yA8~JgdASeoG2Ba z+U^Df)TYRtVX=EQoZOAr#c}1{MC)rYH;>P+j<+OShsK;PaF#31q6t4NvsAh_;&Ea{ zHCR-NL4kD6Jc0ZX@X#CLCH1wUV^AWhAbZ~ZH8eclRKtFQ-QV#!SGuF=u4TQ&AAf#9 z9DOlX9mg!G`r@)Pr&1}QTJEBRQH*>{dIHlC)7plsFDL0)c~9ljc;=ES8Jhd^n& zy>J5EQ~;Uli6`Z4A{p3lsISD4mEH=Na zG2ob?slP#gMq1GB!MM(dTOf2S>bc5BhE7;)^(*t13C&FjES|R3qQm*sOnaGXmaitj zSXidj*tqCsv>>k_Z-oCQ)jg!MSD7ZOpkVAQECj}?v51tkNRi6I2aSX2Pk2@(&A?|G zg)};^dyv<|N2qDZ2r@#rX!X%`g3}FhVrEJ`bFUZF46T!jrp1D>WR+D<@hwielQ-o6 zbisyViD!z;Nkmac;X^xUa%P|iv{*R|UIE>3c-&abuto;@reqmiT~wZ?h1>Z>MqY1SK0(vCqs$EN}VfH*yAT@`a6 z_Ub3Nw5au2{8imI&z+n<467sa=f`H%&&{VDo4Jkk*nGl_B1*0%whn5WOU?O&vNDA< z?MUHAk{8Hx#X?>df!Ea306)ZUCh~`4;PzH3rP}g`D_5rUis#CA+4H>DRGv8S6 zZ#UbZ;AImHNqvu;h*CAVwbTOk$%aKs^GDRUZlqEjs>QL<$`YPTxIczZ8obGFKN4%wqU2{k5c`AQhjSH_JV89XpS`)7Fe>b3`sZ4t80>7 zMRZ3~V;E7}?YuJ6&Cw8zG76ho@!74|N>!V@v8F`XELxqG(YouK#NHMqO@L_}@b93y zMeq$e?zFoLW4f)=<9>5!_ZmEZ1o>*l_8kTfS}zLq<%o1^m#4~J7c-iYbwrQt_47*` zodmXtU2R9fdBZV81<*nC5{nV5t&1ba>>dxt%A0?cl()5wnRd))A0>}$25AP$W&qA0 zwrjhvEbVV1T~?)ytylq9^KaF_YEBVY?3E?p;7r47niR&A$Gqq)4CK0FrCd+5XVkWE zr}u2T()*;h`p!KRM9;(uSAJkNhSdxA`~&uLun^*JCtm36)_S&06O6rLvg{b!_&9;G z^Zpg?sbJB<)O~$!xMh!&WYF#0%{AUEG6$Yyi|cK3U=EhXcvp^6V=O0QalUN*Ip~AY z)&Q(iOC9oRCYO3GS~noYhN(g&);Qxx7ro)#Gje z`FokYrBZe}uM^mAhW3*cqOpn=Q)F&DEIM8vT{4||TLh)D;6zKAu3j2e#+!L3`<5Yd zTyNdH06urJcJn%I{&3B8e*?!_5YP0&7bJz}DQtxb*_xGVH%&ECSG`PYYCJO*r_&p# zfIKT4ZXT~YL+NmMstvS(sl0@y1ddr?OI?{L_kb79u#gL^_9Ox>jr{{AR|J^H5^YJEk!A-1!Zu3Os_51bdWRkLS;Ol2*dHT5i7 zxv=Oxua=bZx`=OWJikb}@yH2ZwCk&SBIz{rBg zQi)83wzQ4UCUw2FL-xSTO-Xh~1EVE3t~(5KK51Y&Uv)oBI?TmcQl>Nuvpid-`Lm~% z$rYgome39s=rC}e=qZGdK7%$&v+!YA!M19J&KIT`lcG3_jwcOb2|T+{qk5^oBLw@V zWZCWhU#Bw~H6^Z?%pwd0@`gV0B1WLC&MFaGiHdNK9Rye312r0Qpx4*s+)k>e4gREM zG&XI6O`%gyL5<;+&yPlDH^QS;>jm`0gwF(+d%D_LH2YHu(`4&P#%34~7rsGLs=QQt zdj7(DD|Ueyx6y<;26+F$Bf(4!kJZ$uBN23v9A(9BdxZ>K7LAqYw2m4(Yh7=5wKx~)b7{>x|%u>TNlUNvLW6?k9^SieE)K)+Zwjv+Ls%f9(%Qn zY>|2-J)Yu880zUCt_`*FoZJ-lB%qDb9o2?Ndm_m%wq_s@1$VTTdUgKCdV@X3|92|m zn||h#sjb8#HzoQo6LnSpvYdZ2vFn}_YfRD-C58~}`uKbce|qMrBT6kvlhgGZLmhN$ zcs<@!Cd@17oQ8L--t`%h*5-ePG;z{R3)cO;bfHPk3EV(KyFqq~mrQIt|1#w6sYC+SXlK^PQA(p98{45BNW=cvhyl)@)j- zT$EfMMuZ^=nS=QgOtW5|Vy7y97z&AAp!WM|gFEFuRX~@LI~Kg~Nzt}>u@<$fj5EaY zGzCo=j4HMo9GbVIz=3l^Sm411jI!|NgREZ1wfP155OjW_+RdI?-!%J-*5>vWBMYK{ zTw;sQ87M04zO-Xfr5IQtV`d}+g=_h4}zpw*T(_E(?w163B< zE@{=ioOi|&+S%n5;PAD7YgV*96w84T8;X_wk&57LYMs`-EnQ~qtz#@-c}E~pZLeCR z@k&V(6e(7>Hd~F(n!FtIBIe*@)_Q5e_sotolXrWH+`7Hn z)qKl_wo1509pumtWGjbSxs@RPl3m}j7G@>~P6>dhu(4Xef8hV6Kc>E-I4lS-}p z&7fDFtP0>4McpUA0z*GWl5T*~OB(tif&UMd45&5ur50+Z8fPlWGcdY|WuVm6VT@I& z&vRJ&hf{_|n4d10JQJh2Is3I<@c!HNV;Vnmala^7SvQ)OPePl)Yk2s>~ z(>zI`l_hY_vMWx5zEyX3`+y}<+S74YP5f^NNnR$aOf=wyMX>zUbuqkrieF$u|ebDkB1>R{3uS@eSu6_0IUMK67eZ~{e($L*LEa${#wP8IvI(z>7 zXiL1ct(l%XODu@a9Ts>X#h#GeQiwaKP8+MG2HT`8m2$Y<%64!>SLzgGDSu@8qat42 zCYc~w`l)P*%kfD=bzQrotpO$V^-hO*M>h0Sj~7_^Z64S$nVqP^RxHlp+k3pN?)>AM zRJU7cMmao}J~+qmFZ~x_NSe@$m&MJ)8cOLbI7PhAO-m|tXPjPkqLxB}GejdXt1{4{ zx*VuUVZ7`eTDz{6^&*?AEhqVu;V^f*(hYs-ir^VH-^d4J;M*}UH)_*anm~E27U#b| zm>4{srhF6kfTHW5_-%|i%LsbM=Db3DL;t`Rdc4MUD^YT9B02(#qwxff^yVDcoC#Q3 zn#w_5{BSIw;{15B7jNd1-ql9OHPmxGb}J@!U-}W;r%C*B0D0#JJ>LnXvLC_7SI?dp z2Xk;L$+I{dbE+3kK#AP5IL3{EV=Vp|d+HI*h$a1i7TmY@DW*1l#(0-jv8`s^s^8{_ z>UA+A_f~tNJujU%)!Rc>O9Jicx=!*25^axZ9C5icZj~$NzV(9EhrM@?n2m4E|JTt4 zQ=JRwK$-EN5IPnu>dOlYX%d)XU5fg1Xl{LjN|&>V_Ar~wA4&53(RFY1d+|{Bfvo_u z!`rJ6ngfq2{mi|9c0Jq;KHs*sk!N?T53xq)G+|JziB65TwKviO`Qyjq^?Jh`G(#5_ zxU2=xI_$XyYUj!5X6YBh?awlMmdAF|(d#os_04VS)rf^ItQ*h3Lo>tC|{nXLHTYY-)cOdb8;Vg}Hw+o~QHvEKaBlL}tY4dau#K zKBp+`=|-|gsg{=A!>kp2nAOunBPGAb0=K`bp z*NMK~LaL?yT}R6s2Gi_O1T+L4IsJr<^|nh?8T@~m&S4y=rH-wqIX(3pH-V+5C?sG(FIdW55tEC6TGKCi*rcb z;^o?SILLixih7jNA1QZNdiWU2VwhT`Uae9Ir&-O`F?vTp^(i5vECJUXiw}HTz}pBu znVv7pS;jMX!3nTU{f&gRjqn=NPB4w+JcX*>C~;N(#3~Jy;pnE8$MLuHczRhw%SJ3CFjM| z5VD&|GYGVQyGikST<3wO~r$(_OFJZ7lqnDe{1Qr5=qnDfcE?yqd$A*6WyUJBf2``ZbV=i zl=QiUbkhMdmN3uE7!>vE5j~9$`CJg4GsBnB+UPZF@**R5^Df2K0<;OkzpWPq*R;&t zj4su(VGO!e&8ZsQh?5R%abJKFUK4MK;nQt66X@w@x<04lvW_t9jObpL#*~Y`Yd0>C zkMMqCt#$l10oYOu!?llJ;2A29qk<)ZPyyS;={ezYz*y1vNhs`0ye+_-{ zRhmrr-bbWW$ZL6X*h}sE!%n4JbCu}nGj`gCc2`+LTOY;eX_afgZN0}e!Q=vTNhQC5 zMzboUUfZ#gNriFuU0}TR@mwr=>UmK#7R^upG@9&V&=|l=7Fe%x-#VFMT4?J67;UL} z)aR|#498pf_`iBBiaV;O9<93TE4W`>OyM6dU?o|ig;zFjZE$th&X%QscCrnj3of)I!C6_LL6yAV$vE>jsrJLf!gA|-R66j`^ zJpki2cgv`233;oz;nfjn4Nov|lE%NW88pYrT&G-M4W<*ivg(~qOx77yXP(J3-A(ft z6>2B2uBKkZ;Ws|ITD|k+xXpeL%zFuOs8)H?1@Sp$wZ;DkikV>Wyg@Pb9?M_tuEa;X<5zKEO!I%IAT*`m$1=+re?E10yo<6h-+tYNPb}5U_sG zk-A_PERegcuUtEgg_SFTjU zw9kNr`i*`IL+e?3z_aSOzh|OYyv7=KGCo*sU+Xxkby4=4b7<2%^#cX#s#a*H&**0_+=nWwL8uv<-I`_*9>_?g>Fu zT%z#$3rsb|LBeup@F7^OlU{uUW{38SrD!_8B1_Amty6j3TASHMhWXhju6bhLG?x+q zCWXqek+UozYZ|HCHe?ges;ciLSJT_7c-P&l9s7Ei*3a%4>C_h1YM1DlFFgryjd&VU zZI8%un$7xAZ+MvQ7)EP%zRpFHaawI7WwlqfUmN@mhh<6MFOCmxf32-7OT^YnpzM>f zd9&Mqv)6@<6f~mU)zfGGhtr~Ymp>(F&u8*btn!UnWJOibs|q^QQaJCGl*XXX)$Jdt zd~Q(4CaiA+bZr<9x}nE9eVP+;p3|G5rm*j}{%brpObRLQai~m;sBde+2dR}c?ba)+ zOzUEA6x(8!d-l_)WNn+e_^ws*#J}cKWPwL{l#V1n$l`za?$yu6{e9M?B9ATi^er=MbJ)m~$rf+P@T>JUwTHwmawnLkKgH>R}^Q z9`)`#d|0=QzO6#etKqt;KG-Gg_jMy}y6m$(J*jwU}LU#R3XyalWdX+hifnd-YORJPk`!{sokvW}u)cUo@bG z5M%z4`sAz_PjZe@KGJP3N}yUyugOy`ci7Dzi3gbQ;E{1U0P_PrjlypbZp3FXl4=o6 z`Zb3c-%~|&;EQ$~t!lP{+M63|Xpfhcj*RjL5+`Ffhh9}ecZ^Vfl_m?h(ll5FpOx@d&v;A2ZCdLI zBg1%WWwtgpY?8Z9pKh@2@=m+EVn=I=mSM;5dU-Qji>S`L_Am4y_3llB&33hDwr?pj zFi5%iN3+pnF2xs>yzUz~VPMryuV$#V5wmhlx^NIszDen}e=sqh_x9hW;_hFhI&z~H zNUeoj2&0D{f{`rsi;`^fEvk^!rpM_*N#$57|F|^Dbm-k+0b3W{~}IbYiUdA`6Ap1^dhhG z`Dx5lxz{Zw6>M3mg-+q)Jow(TyieEb8(&k~bdI~^g!&%~g-+raWkXptwPO0WRk3%1 z9l+qGJSyM+lsPF@l8{%W$uH+Y?efcc*g@}-Nen-Q2$NV=MK3Fyjn~`9TdO8vy51D8 zqOT{iv9vwn?Hi%kR`3}d)vx3TPPC@2Ia-IMD2XZbKoM#*#lD->e9*I-${>3Qnx{$( zyBzMhivD@$kli6H)jNl6LxYaOe2zBlYMQK`P#?FeqqX4L*qbvX)yY!5aNo>}F11QN z>0^n>D?(6D-Y80KHTqgkbQKe(RyJ2gOM^y*x|z@MNq#}3 zO}VXpk85;%v&K>M`a6235VlRYBB0&$8qdnWl6}|$4jMmT)O@GesIM57(L527KMZD3 zfAp1J)MW^|>jvgI7lT(>b>D}?(;2sbdY;3JC7zD?ld!MO>f>InVF^rob!@IqqOLvH zoA#b8vxEP3-W$-+kcn>BI?8`{5XIUTZ8pI@`SP_M3YG#}D_JkSdRpZwi}n>#_4bsR zwKz1caf4y-9V+e8Ou^ex=)zH8@3YPM{Jfg7Hv#3wI}@hHYVbWIdS^myOB*S5_olLB zRQR|6oQD`bpy)eWss|hE9>?>9yf*D#@lxWXRK=WY8xqP+E6V8ysc>1DbK5 z)o^vfyS=TJ-IH2I#|a)+v~_r7v#T~NaD+yGr9zEK?(6z7xteux+D~f8E7-ga=~GG` zruaKaU8)dK1^2{<7cVp7O&e7cI9}X9U-wZ=@5`B8u=2-b%4&4gj-+^{LAX|4;>6YV}fYw-pWyrI=d{i5j zF7*gse^QTUlVc^{9jBF(FvBO+Xt?BFXVOOluy|9SsBdoKPneWV!N-_u>YM1hZya;- z`}B0INt?q-i`M9>DbJb&vYxB}`g~*Hxo4dN#19vkAKL9&P1;6+;5$#r2A1;CO82ec zDLib;l$BP+X?)?QAJxLRu}&>B^QnP1$rw8CwGufn>fB2iZR|t8#x=L&`{aQMy>B@# ze?)r=UQi!bC+|w|rutN_k0h$sm%VRJ;aNSu(X%OjX}ZVNy@Ei8y*Hhw@NvBl>2%q4 zx`F{iliGAx%cJW7o2rwdWK61B0`^32QkwpSu0-1V^PYDl<7Fsiy2TEAeyqm0D-S8! zqtk{iSY=9|U}#e;>R2Nz?MhbsUEg0hIz3CZPEB8?XdK$4c4ZwAL$jBZdF)V*EhCK zyd~j)yTFy?`*^fx2a@Mi+8DYcy3y9u^0b*ex@Oq_@EM@ao^ob*5}vAu22*#l zsfItDu-hzQiY#{6?4cpgMFpIVqPF_kP3?`*YGo{aj~2MQD75_aU#XwpS{OaUH1#$u z^l6&d&Oj4W<_hwCuW+wuh$U*9TN|K|#iXYxb!&QqyW8}{kOLbI*X7!dQA zAY55=*KumUz-~p7Rm!&H<+XyD5r4;&E@7TiF#3Sa2QuSIQz)aahpbp7@62dpgBJY; zHy8Ycw(Tl-TO~#TrKhWhww%1S1&xW=EQEh}_)huX25*#L4nVE~Pnqji%`w<0)J*ybq zAb+(qB%D0;cE>#YnK!!`Kk1LQc(s#vaaT33VE^e-e+ zT^)_jua37Qq9`Md1gTh~vDQ|+SWLyC|E72-8;DY6Io4Q@v^e%zZEa3ob#r55yeZ-Q zzgEiMHL4(pcx|{$DtM)ffD-WCOH49C0asOnT&B zi%-vl^-~r@TW-He?|0e4ai+0MmVC|@jrQ1>FVYM8M(mQWPFVm-ykiL)Z316Ak9HTs z7l1?GM}A;|wd>9A4hA0Y2N{(0zg$o&CG=2h?R?_-eUvFBx?}1YpIlD{Anz>Ijy}n^ zhYBM?>{si&3=E0kNJPeggzPn+epoZ@y(hk zzY{$9(K!jzCj-Cb{Fd{?{fl1|UNgaOJHPGx#L58g-Vctx%D5 zje6METk&ZmeDlhV{}UG?(P?{L(kv4Va^jGm!wla|9@H@wOgcpZ-28)Yx=;8Mt)pJ QWbils$Jna65`bW)KSb5OV*mgE literal 168360 zcmeFaeOy&l_CJ15DQa}MmKLRB*TxJ>4NVPG3sdS^P?S-sgdvQ`0W&6ceKvKb^JnG)hhDCvs9`!R$aMd8KJ7TC&y+zx!%l?I`4S z!T%Il>cj@w%)mHVuQQO^CD4Tn_7>Tifd+?!)GpdjLV_qUQ1gg1wTq=oFa5%gmw%i1 ztS-_9s_nQx4^hC61E=MSYy;JHB%3u0M7uS&*|Ch7(X@l;XY(9gtA{WE?|e;Kmfj^o9+oVflt zLEk{5zsu2%LYk_vz+`*TR@@zTI zph1079r~g6a*8?K9lr<4yrY5Zyq=?`X)(V`{6lKzV^7e=Qza@Ng#StSKMene<3If* z3*g@)<@LG1QA$2t&bj%4g;~MXE7DFVyf5`|cCTdx!4tbweSWCn`mEj`b-#Pz3!mJz zFyol3UP&&wTFWoJS{s-8*8b-o89#eZ-tM_e-ne>hj}=|V{b@&!=N)8i$-@|woLXD{ zoGAGNqU2XVSZ;J^8F_7#MPetwt^S@U^hbd{$=vz#A~M|QJQ5}UswnwSM#;Yg6YoYp zJxc!aC~}w>rT$e>@;gHgZsR=@e0uTU`EwWDcoEjBD3iBrAOfSgOva@H+ zEh@||@#hr#v$I82*NWpZwEV(+Ka7nU@ST@a zJR@&@J~$}JEzZj;BvF<4XXKuFCdq1qmVM2nD=!_Al%1VhR+ck8fBul6L$b5y&&|)y zMZYE4{u}4zf%eRzRMed4ABu|p*~LXSWEbQW&hpRB&MPi1D$ckB%w031AY=Yq;H49b z3QAIEm{D#LP71TKkv%!Ong+AvorLdo^Tel54CM9YDm4%Oxr-Jq4^v%1X6&CM>6 zD=V|`hI}->BCn)$E~(!1T&YI1qH^bC=gyv!Ju@f2Kz5Yl&nwF}dYze1f>{7%g_2GO zOy*LzKm6(f=KVvM%^9eyHBHY)duGi>!?PH~vmTAO9BJqO_BC zt}G{p19#qw?Zq+LM>4PUaYnA(%SIT^!BR@{=zcU>9pI3=~vmE(n zNIKIT`N ze)VxePwE``^)lVy$X_Sx>yG?-ncw2bZ&W)Vs6zwQpo5oc4vs&i7SSMq6(VEi;F`NtcXz(ytCINPIQ zUCHmS)NfJpPgn9=mHYupeu9)gacji>RBXh%#QSK5*!-zi z@}+CwvIZqznrzN*RPy0q%pYCJr@oD!79}4J$oy$l^2t-0KT-}v0}jUgiBs~8y#f__ zl>BaHZOBT=|Gkp$Rq~CaN-9oN@(mrK{3In`-M=O)`E)L3{G=%PJ&jDDPsu+)$C#F{Ao)5$x8lgCBK)FKTpa3gOXpSDVizE{bwR`UBQ`74xs zbw5|5f zQCnMEHK!?XKG3wsOjE#oplPd_ra<{X(?85K1;_`Q9x~Gulpkoi(@ayKe4uHunWo_O zK-2YRnl>f}nsUrE10q}vQ z7&A?Q?}4VTe>TQT0WZdHrYX?H_{}tJ%rJg4O&cJL-%L{gjPaXk3VbnsGfe?6#&4!6 z(8c)8G;M4!eltx0FUD`CDbU6E%`^qL7{8gOjTgpmrYX?H_{}s0xEQ~groa~CKWvQO z%ju7dG_<2~E@{Vjjr9ZRyaIcAiX)xrNT)l}sgCp*M|!v;J;;$h&5{0tBi+-H?&e6x zI?{*d*vIp&BmIRV{i!4Uz9apXBmJ5q{gNa7q9gsRBmJZ!{iq}TS4VoeBVFZ4S31&* z9O+U=dafg#r>2K|F(I&LsxR=duVPj7{^d|&ksxH^Gww~9Z$-!zQ z1Gw;2#oj_Nven-crl}8I!!#Y!));?EIkZpPE)n&w=K900AQETB*{||3q;6X2nVG(dF&nSLr7!TQzpF1e=08a2Cqd8k z888MrV@Zu-rl76aKecbV!LSsWXb5ZSJrLhLwH3e8TktDW_f=)K_^MJ{eSx=qfv}!4 zk9ydK9Nib#=?lE0FGkLRc#rn-cB02r0*hLG!PM57@n3~NLsPC(;;N_E>QQghQMyjG zK!;P@gc3T6>}@Lcr}zSk8hnA$`We1pm(ysY=nJH_4hey$Mq+UeOf-4)1wY4eDFNmuqW@q@$7Tx<} z^&HfAc{_U)DaQnemC+A?);!{`a4bG|)2CP-ePfe-g$C zRVZzY93!&B`ulLG=(Q0Y#DS;u21@vXDRB^JVMxz{;10xJol4nU|Fdh&`W_mCqkb~_ zx7Gg|^&_U^jUU_Eh@g$rY2dULoUU_nS_Sb1Gf~7E?!|&&{Rn2RlUdzF77KX@`Xi~Y zF?7g_3`npJT&1s}5mE_PJx^AxF{%#YjH^>?4#a1rQr%Rv^5o%H_dJtc90^QPIE3{~ z%U}%#W7D^pfu|HoUMo4V)IOZb*BZNw2 zWrFqYnN-46`^l;+jH<_TMpi0iG?Gr$5Jh@MQ?5uu$^$X)FqmS+_T+NW*)igp$sfkr zj+oo;T6u13ZF8GsXdwx;!8!aOTNh}ZTyinKz~xwcLg7A;lVWP%C&-BCwOsV7Y80#- zjG49O|1Yhcqpyj+#rs>?@V%Hox*2%Z!>~LK01;GbKvfDlna9d$Tq&$i0Pd_j6Th)E z|H@5+m4ZT8e;AL0_$qYB2dV65a%xubd5kaj4Y{5_qq;^1mGe;S3oI`q5cEV7tNwFp{nT=d zd@0nq+*eh_ZL3nNeSzJi=!dW@eO1djH(132t4hTZ;KC27Fo?Rr%oQ;EQh=HD5EI(7 z?YY#nzk$jm;zzE)rEud>nu0nvJ)R9?R)}UlS!tRsn%1D#HI815rVX%`!h(5NabU?n zW^x_!wi3A%h1}0Q1kY%DvGRl*yNE*@V zXUQ^Z2Nquji(BJw`2b3W7O^jUOg*1fNu}|()QQ|mYGc)XM%KMU)}_+;TUN@tg6>(| zCjQo1=&o3IF__tPP<1MYDpivdw#u124KoQvoJU1Lp_TzMx0!XU4ppWdpWn)jNr6zz zTCg<}nk|)P3)7+S04;6$CJh0%_!pk?GFnto3u)RHi|ciy*2mzQBq&BM<>4|KDtC_N zDt5&k7|ojRBS!O$!rRxvr5|B5u}X_A)IyHtpW>QFGYZ!<8ZkG1jsc!lF`9U5cbiPnt0#|B3@VI+9k7xxyOb_tdkT$7XTOV=NKZuwr3-mbk8_>ubez zIbFZN*V4p?^|eS=2shI792kk;z+SMTC1y#;KNiD_<3(pg=Jo93f|UtEuj{d3J#;DT z`RmXa@P$fYeIf`q_cnc(SYW~Bv$?hiH!SztpO`}QVQnBXn=hr!lP>_DX)@b}1<~Bw z%oiPfPMJrWnWjsBgH}(Vfp{rx!Je=FE9ygVzIX@43fHQ!O2vK;BBoYw(MnBrLkX*u z{R_nxbu_%di)2X=U$74dEKf$t8CL|^ViTFKq29EH9(kYEQg^l&;mS#919J$kO;^He z3vyw7_zZMndhH_K-LSt2E~m;iuRVn7M)BH2Pc*T-c8prz@Y=#RSEa*wn_m0E17OSa z+B8HILao?q51>NJYlnm##@33funAr94Gp`y@Yq&Wp*>CAA&SV&b{`Ebxfu4w+3m#Y+=bdIflHic}TFGRidNJ zb*jTze~^o@Vlgb?M|!bHXc0?w(5(Lm4_ItQ)sum0~+hDX?@q5hZ z*7?IA%5pfQr4EP0&Q5fF!KGFwhd`|PLL+t{-sdO#oJI&jqe#@r?2qXd9Ufs^Y% zsR5We$Q5bemCp(SmAroCfaif1nu;u*inF+EzK?RKmZ9$LaA&L&7Ug7xyAy=?pmAaS zK`01BTus+^iR*H@KET(eZTJMq3bC@9Rv{#_41$nkSl@~omZ32E4(pE-Az>)e_R}8B zW{6_-`5X7{FSv0+mT>S@h=43WqqkgHKij(ZY@s6YKV##yl= zSs5L1mtbrpNiHP#f0EAAbr2^?qVIzsrPAkmKTI|09~7h$+OxR3P+hgS=sF2qM{Zql zG6F8{qZJ&)bwvmQ4(oSf>L4U=6xRP_l+l@&;P7WWfoBxgip9@Wuc2l{rYgfD%J~Sd z1S)S-{{yO%QrM0gZfSCy`lJxAbOuM}P@PCRhocU_*C+5pD$nn;X3@kN{uMmoaJoK zt<-S=kx=}kQ{TN%RJGhyqkf{LZ`Y^?;Hn}tYH=>=iIw^=xP-E{t5H{=I{G%2Dhv{z zr>4`PYHZ)P$zxoN?U<+AANYFeR%=mGi~s@ufZ&bm4pq&I>VozG6DgC5aW>@HNt zhAFl6hEB~1C>Nb?Vj@|z7ffw!euvuOZ1}9$WyqgT)tJ$4%efkF8By)uoFB;}A1m`d zZT_*S5_=+AHJ>b9L~5(Zyn-@g9TYHGDa3-oJ1TmRsPLb(&6gtA%#X=Hl_U-?P_F2gI;6!2^pVg4pQ_ zSEL3`u54o-jLPn-1FM0=#ss#&r)YX;ALN5@7$;B_92Jr^P7r0Qtg=~VSr!iEohyV^ za-g(DS{X~$EK|tE7x2hS5YM1n6V_>-^kiVknuBq0^oA_l=742q^hhlsIWlnRauzwD zoT?BpMP~I2o>e|fkEt42I?a=AEy-|=6(MLqSg$e8c5!_VU&Cc`T@E{57M31nJFEx5 zNHxk7w>hyn&2XDC>Y;l_N*Do~D?7R*q5veogv$zF_K(#e`5q`gH0rWkvR zL=r{dSuex#42CL-uhIe>I;I7xD7M0?`eXb6j(y?>q?gAJ$gGYZFr_AbK;F9e0dqs~ z14`@T2P}fDD+R%@z8NDASB^$obcBruUHMk{Dq2sxVVqGdxLowhayfgtrd4pYnC5yz z1Qxw|=C^^Qb|QvU?OVKqhTw=DlCgB^+KFtI7;a07@E`&=C;#uvnav~flg9P7a~ z#zPTLMglxD=8GNmZ4)3jIWxQH7Pfu*BBP#OmJgZwF(%~skIV@%9ED+RK&sW4+(L0^ zh}9F;8z35W)f)cMSg;Ay&`2bzi6k|FxSfqi?B>^bbC}{YGM<$g8A^3cxlV~w6CO2T z>)WfY8y72v1v!N*eqMc45*=W_ZMTE{?_>tEZ&+vMpG_t@6a%1?Snt$5rHGjn9s;G{ zQ@W?v$Dl;hs9{$1dEt<7B2QGhr!db{Y+U$~)#4PYhx=`b!b_E&4-FFi`+RW1b@BJ% zz}(;0$V-wJDT(CbM5232Qgb)DG-jDAfo77R*;k>N0h(LqGdZh5aw{o1589VOVMy~a zMmMrQbYWC5hM}Qioy^SOQP3bg!UboUB}TiHI9Xycon`cqrTSrqeI-3{>WwW;&liy& zAt_=t>>x{0)pNi_xM9y(eM$` zMzuF9x~%G1E~@KrX5vr+myi`yKwUOM zXrM()3-Oh~??J&^`ztrv3}x9#Me5~ z(sfutH9nm0BiGucG`!c=CRX)^2Gfu|O{bE9DYa;^6lz^7PdmD>|3NlIMpfpi(N$yt zjo9f!eJD(jNQU)QjVPk0A3(%hyni_l6{Il5`b7u4e$&A}nnF{<`r!}T3%g{c22_%9 z@MmCOzktTDcn2*u88iASzVbAc90D!V5*wbTs%J@xYACAAlrR*=ikv0x7O`7;0XH)g zKcaeuqeOGdGvvKP%<~%Vm z&?4lX%M5-o*5#Op_BxV}Khe;{ zCfJZEaghv}*$(OWX%N~}g!RdyhdR1$1$jbW3L!n?hbp{1dUzCaiW33Giz{2__ zcwN=62~EjBgEdZ{R@L*l(cFHGP}DWXV%kjZEtt9{oI-m@QqeUqPO;B#6VX1*Hmqnx zD23!RTF8vjS(MHYYP7}|yMlEltXE5FJIfo9!-RL1e`H;L%$M{C0GfBF=5$w|x)Ad2 z2SW}Saq%P=J)ya4|AmS|F^-4j5cOA7gO*)}@k<^=Uei7JMQT7zB&|5mYKE&88cuN{ z&B!p&b!fOUmJFIgF?t^D4wwaXF_>Z*39&c}JT$;JucUq&=+%lYLfy=Go`zWyE4Ndj{Nv%WEeJVA#Pxo*b9%G8~3}qs(7^tS%B}U0pt`Gu1(poR^OKw4p z=07&H&xOfsx!A3l!#U_OZLH?`7`L5{Z(u%W?7@gCcFb0zW{NF! z)-QfS%{ei~J$3SEe3Kd*R2!o2N7;%F;Sk7XC zzDyWRO~pA-&^!)$b_h?acvj5Ho{4N<6+Z_8@yc8KxR+1PS{kV3sZ=FHrkR(&Qx-oE zm%)Z&c@{f@)EXQ!u0cB>?A+^mMiS}?20`7IBsSZ$6j39r_eC#wC@w)(*;!6DA?5}A z(wZjmsiqv;yf{>G?MmJ?rsyf1Z|I_5K4N@}{E_VEdA?pw_fGM=8q+cE>2lo(WK@it zupW1|tEgrTr|c{tL96zGp%|l;ycaoz*s<~a6`e6~JP=N-p#B0#zNB~Uq|r(_4cfrXTsQ`@{=@B>;jBPSv+A86ccVdRzl>VadHh*RkQP9 zW;kg5aj=HD5j?CXm+Bn1qxl;2FY0siY*Js@{1|RdyEJ}s(b2Hh-mt&Yu>MWzH?^Dt z_5kssGK`&$+T#}xpwZ)f+|bYt`AA^*@&?g@r^8QGFu^o6v-#RofvZK5bsnV~kbEJA zn~H^myoZrj@l%ZdXkKy6v9eqQMT0O4ZiVZpuNLebP>5k!R@gta`6|l-W0+xmEIP2P zr?4`VKY)1?{k)U{(``M>Bm8|e=u2<;#H+BbN8uOt4rEM~^JW$yP=9!oRWwlaHrh z9^R!08FASL>{#(IbLAX%2hyTR4Q5vqn~aK8!{c;P2&7bJ#&&oqEgMy~sB z5u`V=K_%*&x#l)sFm}}lh?kt!J9-mk%2j_AwUCNi5%Q9T+%*tc!JdzBhp9D&f##d? z{Yg)$X_dH>Q?U(Am}uE<%UG+H@tJzGu!j8vhK;F}j}Ftl>h6Z!BLT&4V1=TmyN6>j zqh=~%$D6wK2Q&0|Fli7hlzhl%1u2`EDi)332k_>DI#6Q|XAS5#^7PPXjfHR=4w%ZUrq*DRnDu zhDCInFS_MYkfl4iyQ%BN+?_Z%DwSQMoP8OwN!??z$F{xM^nognBZ+4b@$w?Kj^O2e zj-~`{Lj*rOYl+|szUG_dhT%3On@MDsyG!;~L6%EF7T!M*Pm+6LA7pZ3h<8PhR)=UP zE2il$@Zn-BFLpmz1!4VG%CyX_=?e-elob1ukztn&>5`og;^G~&gl#)~(+0EIk~)?N z3wD=Kx8r;j+Yr|r$IC>VgSWk*>|f0GRXt+{+bkS$dmN5;l*-m|f;>uC)1Ni5+wJQK zX}Jt+fH~8t?G9O1Y?XyJk_QZYfYMbj(I6ww2@+t8$p$lt36jKF773Glo-8}wDpSa( zg1kYcv#igIvkZ#o`XGsuDOL&aIVWsI884Qwe(7mKvcoLKFm$tcmMrdR6)U5^2z)D* zJITuWGpYbgTD@fP%T}=>gP*qBXnj0@Oj^%JQP<~;Y}b&E%0TtHSNM7z0@ZS9{V%DL zSs3(V{fHIubS|2}V4KzYiE1^ZLq1ePF^Q7z$x~i3Q^pA^_r!kXJz0&4(?!SJe5}C) z@`sCS4%@!|qY&;p|BwP1A3snxIPc1=dAe;>3gMegajln)A27;U=gs2RWbvP@;?Vd& z)A+#0toL0>oKi*)3r7d}g!MCU4bMUEjTvur4rxBaiszW`>y-vSybMCZV8nr@p1Td{ z#XCqXVIam%u?_)+#)@N#r4AhhD^t_MwO!ei*a26IXB&lBPdH3c--BHX*vH} zBTBy-1~;QTx6kYk1v$m{2)6$~{RuiDu;I|bSp9dz8y&2;D^(Wkwe83Yh7W3tW0bJI z7fc8ZqW9q{al0B?vlhQG$7}f+d{J*b)iWQ!?~4j3mpZ_tSO+#xEmH@00+~#`=#J~$ zWvc@@@%u_FufwN^iT&hB`^0i#f>#voR0?TgS!~;7%g2pEF|l0sp)9Mi%G8PNvxO&? z`&cimBR3;USpiWreG@sc%TT7y5;wSk8jD#v88jniDQ`2+QkG+uU}EVGtS9#HS{mSF zz8x!W%(hwv0x>`mrm+EgED~lt&E0M|L3y~rPXTe}*GeXnT`kErQb#S+(LIqJ!M?PR zWwV`v6blF4V4b8=B(fzQ%Asey*w(g@jv_Y4;@1}Z*Ysf+;Pa0{H8#?(&6Fn!MxpYS zII7aurP*QRA@qR*k^CKefZK0PnCe zLy%A+NGnkzCN{;5H#E;|BpSqmcvJ-{@-F_HPeg?DUK9`EZGGM{>irJ$PKKVKz|)$1 zEZ1FTk>>J45FuT>A1c10ARmlvKEzU_XRkc`Xf3{|5W?ECv*{{AgTvUzA9oSbJyxbA zq?@fwOGwvQnIxo&jn3X(g|wv$srH4aOq?H4TxUUCTgbxd$D@fQxMqHP60fCOf@_dj zir`+7S#_u-1@{bRd2E8)Wfz>eD{!h1g?nKMAMOV-OK&qdA|*>}|pNP9TZBEY7H7EJ7UR;J`_H%2uNRB1J`DePrcvDzJFWlCv9ap%LhuBIuoV*W@)Swszl zqIfY5hoWRF=8xjG@-G(xQL(s3>l$ANPkMUrYhYY zldZv&QYDBg4zVf^B})eTzi5i}Bj5@QK*+&kCVhJE=i(Wu)EqERd%Dwm1M|3)Xu z{kUydVWcP1xl+$u0tnAg6+RE{`hq3V&=1yiBJ!#22+{T&x3=}|#>bvCTI@xxqXd7^Adz{ji zUJN%zG8p+=IurK?{vkNHKv22FjmoQVI7Z7Cf3&W3W{ zMU8?z-*am_Nokv^w4Ep0-Y(ic=GKW!Pk(dad2g*X#@BwZu3M2$ z<2^yNJ;$xz8l~->O507c?Yq=ruxDqtwlkErnM&Jo+4gPG_Bl766P30nDQ(BgwhxQ8 ze{yTPA0EY+-}hUs>p0oAP_#YYt?fFc?L$i2SCLP$I#;yq?AF$=w9Ql6R?D_iA7oi& z6FAp2d2@s3%a!?^B-@@U+Rkxndx%`3)Qz4>+XS=~H^28j<+Qc&OZs=h^ANr9%i(-K zCThauRz4kJa(7szvm#4ZTcr~sOP5-uXGWG@XO(t~EKRdYzrtV~JP)=?_e7R@tkQo* zmL4D^oGdN4OZ#Zk)JUaNF_ zWN9a>^wG%DedIQUH2#cI{o}Pri|6)9=6u^#-YZCi!BxE}&d9=*jfdo$VX<{5;R~_x zXK>WhbtOAf>?Nn}3C2F9l>GP?a=TOUtaQ(>aOuM%FNhax?(XW>!Gg#aZ&z2YLo6iE zQ1!QP865rsw_VN!_;wVB9F_G%2`(77O8J4DGlWbxxv9PIh9qZYbjAAJC4KDb}YeN|O@i6L?5`###EfOD#tMOjdf zy+VX13euBMSCv5G@ML#zUiD4N9ktfPlNbOe#zI^d?A~p6)sWD%vT62=!+U^coBl)Be+a zW)W!^Pk9cC_`54mi?v-^yn~dT- zS^OA^B@yUM71u(md)6@z+?AmxtPxlBHR}`g8q`xxO*k&Q_;FHX-Bb{|5(-i+CQnF( z$sHvG!v!Gs!vIh>6vW7U_e@d{|Mg(Ao@bQ_+LU9vAS2jaPPL>0?)#mM-8Ony$69i? z34x0G_~y|j9BMP;F-@s-4n?1x)`O4PhR7>#)*6dWm8$TyJ#GC>z_~8O+U=}+32}Q_ z+^6GlV2Tw%+$3{-9|k=+Bd7+EUWz>t375_ zQ&0JmF+?d{BKipFh9#wYI4KRTYTvHLK@1kisTiEBZZ42Jg#9&CH5+z4*zKX?W3*Zw zI&%N_KYSB^Mo6C~`ZWf%r@I)`CCqJv%045D4<2Rqr>ZP@N6XqKSvs()k6E8a_XX+& zdBH*{gRxz~R7@x>m!!+mw@u4ToZ=Y;XnXbPnl>T+=^dn__mL6f7AP12#a;4VX>8Lg zIBu*)!8|!pM{i`&X2@g$84fm?F-=<$zv-8JZPPAZK*y}61+?E>Ky)P*kfGpgM|c6f zL^Ev7Rc(JHjRj;#|NcZ_VQ(P|?l#JD5D9XJe9KXeis?U!w)_~eI`OwdJC#l!-^XJ# zx*JAnVTq;}C{!@3344G2i2_sOqPJCPXE4 zOFXpoG!YNb<6)JkA)n;hg?i+ykG&h#WeO6y55Ha@zQ6%9g8se~-Fu|seDNZ8Zv-@A z?;>N0Fu!eww(Df&V|R09!`*y{yY7hdg6VW`zAJz1IetkG+7leB?g``!^BOZnnTTsol+!WT#Pg>QhZJe>NOT^Q=fZ8I-ToH`t>)_ip@@ zQNJ$y#5w3B$$ndeJMhTlS2*rbyED|_aSHIU)MQ+tziY3yPB#A$kB+F#4aL}L-8!#) z2zuC919FRZP_*y34@+m?fklS`rL7f<4#kuXUAzdJUVJfq0F?i!6QTT{qCFmI-O!C< z+Tnje7L>l6Qqbi!C{)g`H&at_(_$suta2Zh-cF+TsBtGOG8gZ$(L~U`L>|NAn>Y0I z;RLAG%=k$z-{PUS?FXl}#y=2>-w>({#V-%pzfO|kylcDyN=n4(m>9Q{@f~N*z}YSi zdFv2H^AnQvd>7vYdB|D4T2#-Z>U5Gv-=*U_gF5fd#T~z$Ftzo6wN-sTo}`5PTgcZekzgdq5uI@p+=u9{sqg+#4cRUwPL+dOOXv6EJ=|K( z4GE?YGe^|ux=dWR(Dm&~{sXwiysK{~c@;X`wm<3+-y~Be(33N=ID>1PtWYEeVyk_M zvo_H?QlHOYz1XNc#2HGTt7%2a(QR_pe!^Ls=pCs~`d+xL&p}QqLy=+h>2uaT$61@` zIr@y4qjG4YL2;S5W)UYT`RC%=M#s{USS`qk8cmD-UumC1Kj|YCS>kp(1j>r4YM3Gg z@j(Q+6<9>k1g12aK8mlX!S>)|Lt;}HO95vv9g8L-j{nMl_y(z+hH*0vD;|GE0Kd|m z_jG;1DJb;NZ6|){&wj#x2FD*{PH=Ydq5eGwoWi<{Ly_aQN#uQ?J{)4Ot=jq**zn%? zC2xjAN=0gPF}#ay&c!RiY#nF~_di1Uj>t8pNS$9lfSz#_bu@P8=*lqMwFn)cHc>gd z5dN?|&VKx*oLSnO;!*o`=#=p_Fw34=x1{Oa?BEo#PmLs;QiSa^Qx$|t{&JcBDCf(% z5ER<+&FIA>G|Y_q_vaML>W7HnDERMezyNjv0Z22f7u)kMfKG~n>m3CiqhOw+z-JT` zISMjtGPh*rSm9_+t|h{I82L^K8~Hwm3@|O0=kz#QxoEUx*pWcC+G&I-9rSYrdB)$_-h#pEC1DSh+ zse5U!CRy7|Q9Slzcgybs(KqEtoi4=KuJrl>(xO}l3S&LZL#bIX69kNp>~Em<^qyoX z8sc@S%j0~3qkMrYG4`=oau?E6>yATP%fpiCqG-ysH?+hfbfzq59LZ=}hjB!HRrHs9 zU+WB-1LIB~?l7XG5a};@Nra0}RA?HT0loXZvLb(5oy|ouEg0GM7E%8Zv;IfRt-|gg zd_>#0A9o1l3HPJuOV_AF@lw1wZi;M;xg{>w9>D@lJ3@JcZM0TX#JVAuL19|DUaiao zaTC3Srp-k&h5bMYd|n{(dqdIblV<`Cc(Rfxqu-PinI*#^%JM~TFIvgZDW(`H-L+K| z-o=QpsMNJ)>(Q7abCmR|D~*(uW`eM|Bo?d(GkYkqZFVh^N`g}TNntuTQlNgNsK~8&W|V!qg3&7ralEz5;`y{ki~mhjWAc@Ot})bP!M>aGx@Ig$8-XR zzkW4_GVzjkMQfXXh+1JQRS0Ib2CqmY+cC0!{&7?csvj9t{YUenYmTi&4&I3KpTq?4 z$CL0nmoG?$ga+64M)RriQZL;q$Bas9g&3Pup{?!CmG}ybA;-&@Q)_5PBaJ7etq8$f zkA_DS?ZF$*^^>x_J&J=>6nh&CCW)qK<^7U%`Oe)kEA653g+?0JdvUFfXd;M#U9z|o zWg;95-bVXEU+{q%f&h9W=X2W{k-3gDeW05KeY%b0i>e`!3mc!6h}=4nTQ73KV^%U= zacbaXMhf+$JPrpLpqXZH2#|&vk}3L54B0Lj^t7lUQ2M5N z_fCFZIGFinfIh^O+5nY;mRF6r>L!?Gu%zkptC<*{|Mz8a4OHYWCG)))?FXY2taCQ6 zks;zncq0k;dfbE}``l_h8WyXUgQ{(&nLCI&;;)be`GcDca?%&@q^H-z=|RGmLpJ32 zX=27E;u@2L&ARx=Bl4M-N52P)%vxCglnx513SxQl1Pp&~?CU$6fBy+{D5OrDgCdQ+ zMN*_Y0_qx<)+ErfH1!}=kKd4aaA|cTq!+&-^`Q7`2q!X~$TgXih-t0Q`gp@KSUr4s2OZb)EmWZTS%|lA#=x((x)*QYV%t}14zM8W zX;NRs!4Qa&U_sPq68K8~cv!NhT- zKXPC5C5|Sg?{31Gf<7L<;JZ_BFy-)-Bx8!olGJ>|*3&!^=SSE#lpmoy!mAtK(vkE> zQ)oih(qfMg>xa@_>c790hR%oe6OdMI4(pv52fzDm&AzFTRXrDf3z2Y#9ssnSwxu*a zMoLpYrRkebhWeNU1bJ!#fA7JG8NM-j6s4NGP&3ySRFgY7LJNqSbh9c9|G3U@K3nX5{DN7{l@DMyy#D@4!{`nCj0abp(7 z=|er2DsWC%574b5`N^dm1a1=oFL9E$7Tm!%s4bQYCzm0a7HIMX-c1YqhZq=xR`3CJ z*gxRg$S@+7Jsa0Nnq(~AjRga^zfIkVCn|C-li;$ypatw~?v!{6X3HB`*r%Ty=suTuy#0Ep?Dzc|srmCL!!6+5vt` zg1ar?Mx;9!AnOhgHQ0^cONCtW3&gNj1YjV87ZUhm8BCEJ_STQP_+ms~FhNcH2Mgu6 z?xH&pG_HGTBb;vx_caVctUl&;AFpR~MgvGrfIFA-?c>U{fLQ<^;dCx7a3C%4B@O&u z3_J~gU{)wV15!Py6r;TY;Ei^p{gsHz7UJ#T`84aVtSaNL1veAX~Ai6 zqAnjigwldZ2DxYH{w&C)#k9b7SX|T_lpyg4`4F)>I5aOW|FKgo^XqaF!UkUF{msa2 z{?TaKNP}KQ9Rx_?DC61H1IRAnfz( zA>3day-3MnWS?@=1Y_K9bCM5bmWLpJI*v2PX4*jtb3AAQXUgDON3mw+u0@*STLiyo z4%Ni9&DX1T8Rcu*D>r<)YLQK6KstmjcrlOX!)i)~^)8<~q6;}^bVTKtx1Fiq<5)?k z#9(4NAk;}r<5^-DP$Rq8pIc&&oK3m0qQXsC{v);>Dcwq1!X3JJwsk^1A`MqmV*YY@jMXDXYmnIxltgGL< zgG4CZ^%v+v#>(yZy~B9c34Slu>Gzf!luW;;$cI+Zf9v=1sRL=K?0zptbgfIjM^@kA z_XcrW)9=mYq{HuhiOdMU*N%d$?gbm&h4$=(rL7`vTBW4EI^V#lsG z?Gzz7YuEcZJ;Nvi-#2;B;Mnz^NloOg_d|M;TCU^)UUMb;tX=O5sIBaJCn0Iu^~RzV zJBdICcD?hcJF)9Me^JD)x7aG}i&A~zLKqEt%RqdNBkHbqo|FMaIAV@~=!b)y2dGen zTHVos;(kpnj9hPbb1U0=dmCBSdaFg4q1^J6uG{eB?RxIPIMmYdLIv+wKLQzjL!{@v zm&au8Z(d>B!@jWu0(bG;rN%T~hjPAl-LVGt__qGg*|$-#K-kGfx^gddNQ%)hSN<6( zo#mE#TkLib?1adbzejgplr8LVDzjX9gT{SwRm~hfC+}zaaMCtcK8V^YuKZCmDy@s$ z!aiVmWt2K2nvTjP&Z1)Z_Bbp6oO;&#VnV(cY;GGn`>J|StXxM2Y)yEvMaU8&XrS}( zNH5=vI79LBov@iy#MuO4C|-Ua9^V%(mu0gENz2P01DRM}{t~2`?iX^!sL9D;JL(mz z;rkxM4eYMUx~s<@LXwtt;(X?nPsiHv_+QZpzk{^X`=4o04Yn&m6h?^y%oQvbxJMA= zjX*zKx99anv{(M?z1~-(xRRaw?csjMz0N1B{cgMU_XK%8`fmL(Zfkm-7g}f@9A4)Q z)Ny(p$kGdkgBU1c=ZEp2!^}pxV_$lz7@~E)8LQXNM>nWuSxC@=8CDOAY5e5VxC`8r zX^?cWkoY8ED$_+b9Eow(Vq``9p~j5&Xh>*{`-^Dk1n1`Nf7z3~0v#CG4j^t2 z!-+V6I9zJqxwc0aM<Kb&s`=?D6LgPf*x{i>fCfe2FbK-PT);>3 z#0&kv;{=KZ*y33ci>}9#fcAE zR$($N5D2jz>Qx8z3V}3MBRMf%b_viHR%pt`^k?uM97cpjQ%bebDy&~Z*scZFv)Qv4%MFoyQ1E9{d!!>B|L&I?SFp4%}_w!!umVRmucJTI7zk*T*8YX zK6+h$i83Qh0?E16Tu}D45o4c~sJ(YaJ>ivkO&oOVoj#j)q~6_^^J$=rzFr zoq4CO;eZ;m&X;WM>iHVgy5R^B)#&q=_@4^utV7itvhn=|w8rDCBKt*=-H6tWXjKbb zL7jCrhJhA1AQvvH(HBFr3#QrDd`;V#a4Ii9{ZyP#AP&CXU}G%@mvkE$9EA0gI)V9M zl3Yi1@}|dp(R;10BDI!Q2`J-fNqfr=F@9lKz#J_RzFjg}wrnmknvJqITf@zq9Zq%Y zFvi}p(6z&UvZX!}XD8x*)~QC<{C$rA%q2bOKx8-nw!d-2M!^=Nke@JeNjFZQNJ)K8#;~&HzNl5XwMW-{ zYtM00-I2s_ozGMH&?%;&H1d%R{&wfP>hI<(xd)tfjg6*chY*=Ibxkf-@~ zJHk{CzY~JA&5cv?Ne}|=nmg_mkqOb*8`so+bUv0ogw`J)itKgZ4A zwqv2)4gCm^R}6iGS+|MpJXBUA1~afREjwiHh1@!DXRLRWarLl|%drBk5FA+j{n`~^ zQE(19YP|F*42E;`uJM<(W{q{u2B*Q%UWy9q%z1N5`UzdGv(7YVTBfGigTn96cbk8o z%U)5vlhu)UYZXobS;J+#wZc8#x;rA?dU-Z4c&re_ZdSZ?7sXp+uCuIV46dcM+=)@h zc*{8>kve4CDD4#|o)HV~O)z08bky)^8xPV9-uTs9-k3I6!P`2j^NWJF{d9oZf!@Eg z_x>R#9iiji4)pH6rae$JiwVPlv|}3NzREp#``$jLj<4_pumP=&n4zJw)EOcx?Xa@0 zd!a)!)mF~ClO2pG|1n94C?8;{A2Fi*p(`&3XGEDsqZ7w{YD5_n*^L-@qZ&~b^5Hk0 z38A}i>e(CxPN-VdwG$Abi1FCYWomf&IudGlIe{K%grk(<B&?4tMQvh+Bsb+FSlaq=3TTsI3UJl(-{putlKPTRewQ1im>i{XMevrWuw^eG=EwrWWH; ze~p>3N1%o;6;Ws_g;;NYf@YB?AX_M#HM2#WfDFFeI01QcdV41zaTqz8sDg~CYv)Od za#->INkr@P9vEFI7=g=(>d%jl(sz4?(iRSN5d_+eBE4*W4PM$cw2k=2hD{b7kENpc z!nz#QW_Hxl-eqegkC#mOcF@vZghyY@z59b08J0H`m=+&h)``oMI9%5owrLg(BXaM) zQe-2n;H4XqQPF!MyAj!qXa#d3_U?0ksinQNJxlwL-Clmjl6G3!KMPjumUfoC9VC|X_M^DDqTBV?AGCTc1wGSYlj!fmTs2zSyxN@pI>2VZ#Wt=DW(f^^FOz= z)29AHOZzw!(6Y3zxmwzv-7W1}JpHWSoNZa!ak!S2HV&71E;Hk_v|ic;xrX+(yBFuu z%5X&X#}PqTiuOV{x42dpUWZ+apliE(F@cUN;9bN{k~>eXg**-KvH~ z=e&DCeSmZeJQZzLh$K5{2-8Cfh8Wxgj-evU7Lm z9x?C4V{wYOosH}#w7a7{iKqBg{e8$a(y#8JY}K#6J;Cs+3$OjJ{Hoi?qs!QB?)r*H z10&|H0*w7vb61z(t`ui5;a@mYD?v<|DH=A!E}fJ@%VTVN%(FIL7k8n#vOzO8Gp-BO zwt99`L+47JeT|#;x$VItpHi}-3|h;{v>d=ieUy73!{{klT5obs?&G7ehPWwk&MwIeqzGhlNWN*u`8ZKnZIaH{uo*)Qy#VV$L+oI6B^DFf%`hpySs&X1ugBX z$kI>@{bRwTWg-6`o@k->_#jhXqy!;cIm*qo&&V5jC(yJKDKYhLyg3SxfvgX zrwb$R_1q?Ux8Liz)!ybR4uhHsf!8NMm(w#$$=B2=@@*U*UGIX9{S^Dv-WMUe^AX_j<0H1gagl z*YhG2%8LKu%|Xzn0qpRWI)!qLErzwzUWKvgH)mRwavZLW_z#zQF7x1w|HSI%h`_dI z%w~~0zvdII_7GW{tmD!D;Q+y0rncR@t&h(*lEvSm4A7ZUtLXu)mmDadG2ePZJ=|8a z?6bMlIgq2NLJixSnIe2c09gv*Wj5?gZHs~S!N<^}Arx4$Kp)0yS_;+Z{C{7|zCd-cWM$K}oP@=w!YNP{P~08f!ta@Bz8GXcO=RVpsq)Cw#$x(Z0aLr4>LF+T z?~R;nEc}Pj~dHPywpyV#dL`W$G|lH_7BL3$0m8o8ttRpgQWE+ zWGoF0qvY{&WSU4h;h1W17@zCHX75hB^Q$`S1n&IzAbGp5-tc-umviL~n(4IFGoehor?$042F zBUTruS%&<*0#o5R>k-nID)!;^lCNs&iuhD-{C$(IE;Om;tc(#Wmx-Z>=`V33w%Sh2 zS^<^>jll1}^ahFOKAL=O-s?}qr&2Ro{}zYp9J|`S86aueKC2y3wk;X57wYOivI$8R z%vv->6JZ<3S_W~PaVE5QYb)N)f*#qQWE{is7^xy^+MZ;*PJ~oswy*^3Pcll0sGLR& zrJdFPD)y3!om$CTOLO&CA!)7ttz4+useP353+&W)sPCLko6y_g^f*XY;j}Z7!fQjm zVf~}KG&g$% z%h3W2z<&>^qlmRkjp}GL^dOI)rm>EMbNFR&(M~ip=3kdRiFF~+MG_-+}Rx}iOx&ornzgOsLBbLC) zm^MOj12%2xV0<(aw0uE(d^Fl;GusghHd4owi0Kj{$TP&6Kbn&+5mONrI6R_i9qk91 zH=wp-X{t8m$ky)~2Z88aT_tLoTCKiS#;%jky`(-qv5!6lgm*foz!841g;&*`tNHUl z_-X=uu4mL*d>HxMo(tz?237|X4~|AUn~6`yMTU#;8}&~mQaTgI!Sq!O$S+9|6bbyvZ6;9 z7Z({$4mA$8BErct#NpQeML0PcLr{XWu1G2he;5L`!pR|AsD_i1D90s8L$o9hoE<(3 z^;OM}SdHz3lXs)7!s!xb#teK*k+e9ykqgyr?@G#X;nWr&M49IKXse$7gX>@BX{$j1 z!#4eAq|K2xhDOloGuxX+bLX7-H_AK0&Y37CL+B1~3{9%Sxr`N64+1ARRvRg@@E4az zES7;Q;Uqt^eFt4~L;NLRx~@poJ?%Tt_?TvuDzKtCdZ1(_ulbGKiq-BgkJ_ad|PN52|tcuwi_%_cOA}g%_6KNXTowN@E z{!A!`Q-ZSQEvi5w>=Go|kpW(0XU|gG7VBisNecSWz=sR8vPPvg`p+LZT8xRVwv-isw)acrRYt`aoPd*CrSL=NhIfDeX;~E#^Ih#f|3&@ z=Ip3x9fjUh)A|t7ifJw9B%9WibSX`1DqUj*BnZ>mJc=Yp;$JCYgnST~y)5z$#hh~&1pRPDJQouu8K560P( zYR@b9m<+EO$e5{7iJ8XHIo1CpW*Q1g%7~3+2a{!6TsGlB0i(oBXGGZZTWJ)e&BAcF z#7uVEEB*Jzp*H(O%9miypFAEL&kt88fSX2A+u@wVzGOT8%@3>G6~JlA)bMu zcl+^02_|D$3AYmjaTd=Uo^;UoP(4fSSR_rU;jc`8LrEO)(JRqg#d(5$9QAJ;9a!92 ziYnvmU-6L5AdpriAZOc}YDhl=(ucK;e3*tG@4&M%XTlhZPpvfI24#bG(>U;7hqyhC zWN!S?0&#D;R?f(ZY7A7~;JyN$7;B@BHWm1iLB-sLnC1;2QR|$qbIx+k7i)&wy>rqB zns6LGh!3i;me^mqt_h)Em&l}kup=`0Kas$_cUTh0fdA@{1cuvKb6tl!o(C<*I=rij z@{Y6)BPQQTAImAM59Y_iOq+8GCp%QtI)pI(# zQt4TDZt>!XMPH4N%twrsZ=ePzCeTe(U*Pftx{=zR4LTi%_V(b=)iP|PjfP?wP8f*3 zg=N5=27ezJX@_gEk6qd}cMYz0E+JBCT1LXCWzwX|B^1wr5xonQftkT~AB|PVO|XIH zdi*Csw%u+uD>$3^ZE!BM-DlePcAPz6gpFAAy6vfioBGMX3|5Y9ZUSsGbegv@4PLD3 z)|lqE(6m9dH|>reY#A#UUsA1iS-~fK!2IKkz<#{-dmH~w)nPRr&P^dK;X3NUFfeAlSZde9TD7zhocJ4;K(^5UJR=?qn)+zc`@7{pghOI@4#Y6 za`m{G;)fnZF+J|<_)`E#J3a1+@&=@1VoC=%Ex4DZOS=zoJ_rL5)>jZwWnFDfqwV)}o9o?Zf9iO9W_cpXr*Er_rWHfV~qajSs6rRJFM7ibB z!zLc5zViycgBY-$aV_U$M^-Q``d{sbj7JaPO61KB`A3nDL;vEj16V-$*ulxSs*fG) z2u413@O#vdj~)Eb9|9z|Bt8+V2+X4@!dm;eo~vlq(Y*#sG!JpoE*g6rDZDMLTl=!H zSvP0TY=rvIy0?rFKYY=nk`|hq5t5HIx$aYJOCbXis5^2D>b4Vw&*Y%=66iUC(irjA zB+2U2IRb?PY`hww6t&WIWm5n~xqEIG^|3;aJqPMid@Zjy{I8X4&>|@Esko0K)>8)Z+{1CyqwZx{VF?v6-BX1({ zx;qxD!oGnOs?7EVAuC%XuK6rB@OVv6-IZDUZ$t#bFh$$7A2}lU?g`?}+@s@3PEGH$ zi1HkE)n!laWwBYC0~W_vI&p{)#~40`5aL+Phia-g2EEl$aSS!Y;WX=HoB#Xx$ivK= z(%|^$;GbNip+53$JE<`3m%*UZo3YZ<<0eAtjif?PP!h+&_k=jY{DoS`6t858q=iy@ zSPN$(SJ5+9Ug%Rt3NLs30$walRNl&=P7O&fdVguvTlGbaST9Xn}k;83QoYS0X1 zPfQzd7_7zVe>)Le;!i0j65^xw;{%_KZR_!&uVQpJOuOuAM^h z{@AHwv$xN*x}?e7j&^Kt=zttGDgE2eZxZ-T0>4S%HwpYEf!`$X>m?AQA*gozs5#^F zX6BR@_`UOri)Q8*Ip=z{w4$PUxkaUgeq8g<{JdO$QSrIw zW~XNt=M>J$%g&vhmpkWNZ+3Q}H}Qtq`MI;b`6b@d7L*R~o;SwppPgSa=)98r1$l`B z9L1VSDKDp>peQ#xzpx~)*l!y>A}9K}*_NrboG;Rz6q#Qx5fDQ4563198b9f$zCWBV z@R$@XFQ1tr(;rJT(_|C01IS$?&|IElkVy}NT#zWNeBh3BNqLX_EfsqF%u@lCKkGKSN~t98sQju}r56 zI^K!0{UlNUs4G(*xF0_^UM2g#RN`QX{eTO`Yxt3J+oJV5=%e(dBQuJN3ZVhHc|(Rz z$|;dLySP$%q8*nYa^MD?FK=xK( z67Wr62Jj$oJwC)c>5R5E{^B^W73poj1bj$54tG|QfeFBVr(pa*`n!Fhfo*Mm;DSMr z7x3@EO~4F1u&@`{1CMST0?tl?yu6xL1{@7s3Y-jF0o)7R2|NTmY6$A})wE&2mB2FK zCg5t|Uf>Sk=u+)0s3)gI|Mv90w*`XPUnCw@KWH)KWf@KU@{=X^#On0YgCgw#VDR$-pMy zLf|n)s0SPj+zb2<@DT72uy+s0a~|3OM*t@Svw#bMHNcg?9@m3Da4B#v@DT72aC|Y^ zW4+D*js`9OP6n<7E(ERzt^~df+yv}Yf^w|GB;Z1zAGisa;K%yF`b!251ZDx#fMvip zfe!YSr888jF7WfQs9@fu=^C55GWZ*iWA6O4u z25bSY0@4T8HvyA?NjJ2$O#)sB^aCdY?*aOOSy*RBm4ScYXy8iVup6N_z)8S;KtHex z*3~`0g;+Ohfh%bp0XG2~fupfrz5`AMo`BtHFcAMin71Mn$eE6~3X_TeN+S=-XDL|ddfpLSOr@%zuYM>9e6F3`~a2xaoSO#1RtO33X z)PXI)9zp2IS(tBN60j0D33w0C4_pPj2e|om@C}@N2i7T-1GOaBC7>602$%xwUES6; z4R{l932-NH4e)1R9dPBH@E^cUcVQlJpQ_8<7%wmdI2m{ua3OFia3yf(y_g5!0pLF1 zara>!hC&a3iNNDlK+eGFzyit#E(5*`Tn`+2Kh_)YHsC?vN??z(HEj=Y7*Klv;|0zD zmH{^cR{%c%)&g6A4Z!|?f&Kx90~3Z}Jpz+~mB1|E8^AK)kH8hczpjK{0KWk41NQnW z_#UolbAXA!8lVsO3~)BE1-KNruLkQGc+^8!&%gv=3osez83FwRCIN2*W&oD~=K-&L z82tjvfwjQ9fDORUfvvy`9s%FyU_AqqfdOC^@Ht=^a2Id|@Z?o!4?Gvx04xBu0v7@k zk~QsFU^4JkU>5LOU>Wd&N6{X59k3So`_<4B;59&PB>V!fAFu&99+>zT#tobTTna1# zt^uwE)&UOzb>Pr7(C>3WAD9T7`2@xd+ytBl{2W*fJa#SQ1{@8n2c`jAfVToYqu}>} zNx+@J3}6Fr9`J-G(H=MxxDL1ySPxtaYysAO8-aHKwJ}&XKrgVzKe0Z57XYULCjrZWYk@VuF6+@AI1<CZon^rYk=o%z`6z&0QUno0X^qq-2jt-$32H}1IGjB0Ve^gfmOhDz`p_O zfqQ{1!1|3CcMAFgCIg4PfN=wF2bKY!2Ce|^1J(k6zX|#R{26!%c)^RXXJf%Xa5V4@ z;AG$#n=x+SBw!8jR$vHtKd=$_1W>y`(@xp~eF2UGjt6D}X8^YYmjYXXYk(JHd-y8w z8sL85UBIs6Fn-`b;Ha&z55T3s0^myEGT@8AwZH?wSAo5^p*`?CVAt`QHXk?;xD=QM zybo9a+yz_)9K0QJ1C9mO11ADofLnn*Qt`?Fa2W6~a1wCN4#*8y16%?85x5E1`z81R zVAq`(_l2-yz<$8{f#ZP(fHQzy!my{n$-p(hTY+`J^k%dybb6F zE_fOJ0(SyyfxUO3U*JUGA>dkIZy)p(I2w4uE6_7w3a}hl2&@6F0EU3OfsMeSuY&Ih zpab**mjY9O&j6aLVMs@z)8T{fPUb5;61=^ zf$M<@Z=yZ$9$+i59++?`)(tQjc-mW7XTS@AWx!d$6~L9iTHpu32H=Rd(H`gnCR_%& z0+WGv1G9i%0?U9s-a&id1;AQh8L$Dk1K0}u5txvHxT^u}fvLbOAiY^u23!MN0el-+ z3p@yH03P*kv#0{a1< z0*(hBwHNvhOaLwcrUO?2bAda6n}Pd)p8~r~1fBQM9(XZuJa95_2Jm{|65tl#|Ht0D z$5&BZ@57VJ0Yrp|sEAaLh)OLY3AdoA0TKiZ5J`ln=;4qYNHjN-!_6Y%rHY7374K-N zqNR#TTdJs3(R!hlwrEk&VnvIJ7A;z|R4MsAYp=Cu_RQIHPEfz^U+;WAuydYg&AzU^ z_S%=3S&8uP2sa=c{de>igf}AWPyxRYVPAyZ-bFu0I2K_Y!YK$BBiw^<6~YU*LGKX$ z7vWBXXTAr$JI8U(Mc5zVT?oq%K7+6c;UQ-VFo`g_9eP7J!Zir5Mz|T_od|a$`~qRO$rvX-K)oY;3SlL}13pB%A#6gp z4B?Fk*CG5p!mS8jN4OW^ZiGE6QLc~B-w{57a0)aoSJX;wW=El#6{^P@oy^ObiZ7b)?)ml?*<%3SV`x+YqCck z)NULygrCH(!oOzlhahzMu^zt>Z~}bPTf6bJn+5D`;GeRlmq`4{Etk2nwP)6;CDc8`^z7Blu-hHhPn0)p!C7|>l{37r>eEhpEzY6?B=;uQ|{^u^g5&Ty0 z@A&x5F257}UHkU6?(^|qx_qZxjQg$oT4(wAdYA7D{?FjMnEWV3tNvLE{u%IL^-~A_ zCGcVOvl#r_Y2sf6{$A+sNoM-hUiursuL3{P2mE$3qQv4f%e4fz(a+3|Y(O2c<^y{DmsXeDez@tBe>HEA4 z{IU%EI`Ch&v&T>Q+>L+4ch5yWUO}(aHiPonKG)4>Zad76JKE!+a`Xnj4E1s%{&wSt zd-Ylj{*^TMSA)L>_uKS_^0^Fl=^@;IFaFLQV&s$ReTi4^FF-DOU~4OeXD7F3K+YH^ zHY2?X$c5GWZsBP>am$l^zgr*O+QSdQ{crpDS6zM}_`5o_^0=t$bh=j`72qE{FFgHZ z27YM%iZ8Zn(YQ3jQ|mHhUjM zoO{9F0X|{IPjzJY4ABEHCq*8@>YxaGH}C~!9JO8 zINM934`h;%In|VD_W04@mw*q`gBtMnfiE%dpXc4b5c~%4HX9kmJuAU?Lm6&1@25Oo z?ZvSXGFL)okSSBgJlTa@^mo$t|IpvNhkN=)@qFyX)2$Qy_B8fuUcJ4OR$r~isV8~(o%6`$4+X}g2^pU4X?p#BT%C*WX*G}Z?4alka zjJAn}-KKXvehB^n#N*mb!$0c_zOHj?>+gO1Qz`-Ki>2W6y0o^IXBqeBjLjke;_JW{ z=h@qs_{HD{rr}qC@12IWqELG<;w1Yf!$E%=-=h zs}%h6;EPOtwiiFWQRe+L_b&#&tTMbGuL6HF_%K_zQFvP)QsoD~1nC!>`GbzkLKcbd zgd5Y9uP=Bi-w(|DE4=cRg71a=oni76Iet_8b>K&UxAjlr7lU7b_K9;M(`Ej zZ8kQFTXuqf2>FYf_mhn%=Qbjlyn`{vgG@zG#z=?0Ue_IE57UDR@LiFQi_AE(*Ey_rYOaS^~qZHC;1$j3D#cc&poWt!uaiN0~L z4stI+&TSWxS<5n%rw&~a*P-Eko4$AP%%t$T9}WId@GqKaWUo^RQ2aIEscpjAZXx($ z@I~hRhV57hp4vX&7raIc;yk91Be7ya{0Q^r_7 z=?lIuc$%lU^(YfVy1x|sL*Q@n@z=O@PzSyT>}x-hH~gH%;QN3N^A%TtF9UD$XGtHn z!@f-feCp&;cacD^q-Uj z`cF@Syl@j&-;ZcxLr>PJ0c7rGsW zeW(cJo-yRe=1qvW?bjC$Xz7uytyN}v+2^@@Dfq`x|2<6J@FDBKH{pJtpP9`IVAL*) z!LJ5iZ{DBH11#~Y!0!WZn@_3sM>!_-#JrVkcQ>OPW65shyiC?xwLjwN5Do8Z-QY;~ z0dE`UqsYfV@Pokn%0c!-%1SbokZFR9&zB;Z+f{WreITbjuF|Bp6pJ@E{N`gHAwi zia4JB)??NMoJZoL;G^Kl#=3kqFA5W11pXTEry(tu&l#u^Abu+N`}<(80e`!E_AM#_ z;unBF`iHHpzwq(*y8LqR4}zcX<7c}3dhod?wzfX)x$x{^J%aDD7;OnJY|rX)VHBGHv2?% zH4pqDY4~N}j{|S(hm@Di$V&ludgWDa)Mz)|Cl2!3&Ox6)9^>C=+?U(QkTupKI>B&_ zh0G5j1ZW6lk^iz8RH%V|gUD++22r2~n2%*y7CtSIoEkof{Ks@>@DqLwk*Z4c5pY^uE+6i4@?aCQlNSRW(%Qvv(5 z5;DsEY=V{3=~(Q~0?00lOPo^Z}m-9wWXNKW~kyem@%g@!-RB zvj+U3;9>5(`;EQ*h2T4ZA8PVV+?JI8mEey9KhET{i`_QZ0DdBPn=Myk6#Dyl;P1!% zxsy-!@<6&Edz(>kdA;D{LC&XhBs0Rx%RtCv)r7ZK1^6!D)5S3dGN(c&OegLDUj{y` zJ=TIB0sb_zK9ZbAD(^0ocPjYZ*(mR|&@646P?nqzd9Fb9>KqHd=Hl=(1yS(*z=!3d z2z(Sgx}ukcai(Fa@C7Ds><=vfUx53=^kzBuV?xrWa&Cc5>jwT6{GIzUJVm3Nvizd- za|hyi9C9a``G|XM+5wTR4@rmWsSo&HgAcP2qrrayKFmhcfbUfoUXKgGcLN`$4=cg{ z5WLMsQ2sW6ACe~i9pFy{@6$=c-|KK3`Um*1cI+d3SUZjeUx)j{+OY=w6!2mFdm;Fl z;KS_0N{K(rH{T%lhuMc6;O|5HVfG;k`|%L?`$>3m7}xV9dA zF?ib?k;<_R{6z3!dQA&4#E0p16nr&!TRABHBJdU9!}NM8_y+J{?XUp+RPZ)kp!k<( zxPQIeAJ&fBz|TkgK7BOW(LslL6nxmY9tHmbcw70Y9V_wQ8t|$eZ$V-q?O20&Rwu*r zu@L+=@V0uQbk^fPdiHNR{?0A;r(^nZ^ekrH%y2tR&uESYA7-cXpo$B?+wwu}(I0#> z_^^Ig2L4*`VeQ!j{xJJh^m#S-x50sJAAF&CzsxU54>rJV-3DIS>B;zE z=$rQAsGYVTp02aQ?ere-r-S$Pi-4W(*%xbOkg>I86ln|tKPN*RQz5egGGX<(0Q^(n z!|c;?;R}$STUNt=S`U6B?zi<%s)udh*MSeSPYx9Ab?{;O6b1h>c$HngL(l%$Q-w?yQ^wc_9|nFpc$=-Fa!vt1AADFj=Yd}c{&F+^Y(6kS z_b&tg5%_UF-kbBT1K(|acw21+-vK;aTdysRb&tK^4*(z5CwgMZgKLWf>msI(|4+I}p|LedX3*M&7Q51PMY~Nt;)%ZKN1&Fpy#=41vn`c2L zOy8s6Yr%I#9Pa(H#)KH1BJk&fPp9wIka++yVfA=5_{Y+uu>$>%mI8t~VE?~1?Od>C!A8T=gZ>FgvuqrM6_JtbyL=kv#Y#uVFlvqbVYc(ya2v4_^@`N zI@Vs-O84j;0WYPwKMxMbCh%c?NPiF?f+w5e)uXo#TL%8b ztL$w>?a&1NN8phS?|x$~cnSC-@L}a!4SsBz_&0$+D^OJC$r}t4D z0p4aiNMGnZ6(!)qbh;Y+dEl`G>!r`fhE$)t8vKReu~g&n#=iOr@Cop?af#A@0sQnd z{C4m&z=!28_Y|B(06)S^-*^tAH~4$OSDJjbvHt`94e+-9K>4c%zadTfSA%~C{9$JN z#&aqw!2cEec_weneO>@h-z^F2OWVPB2S41rU(R$;{&G*n`!vAY+9wLWH~3-T=b87D zo*Ozm8Zt{EGt87RbhrlmYVct?xDfm^;KOuaCHNP?hv~ou@Gqs|cYuExe3%Y&K*qO% z57U7@;P-(K(}B_82VWbm12y3LfDcQ5A^6k4hv~pd@B_ey>A(i?4dBCU#18OD@L~1e z0TcWy!DIOF`k=AD*9ZI^;KOXdXz(w94=Y~{__x8^bgU3TK>~<9soSHlf3xP@oZ=x@ZG?N_3_c*+kp=)Klq;DL(3073f?y6 zVpYXi4;yv}_$Tpq?$eOc<2LofhrN7mLOd%VXRD_u?%f4`J@|R}+ZTt?m%E(-dvRTO zUmFPih%|f!_#WWH>LLmLWbox?9%K=NbYUs@Y2d^9+8Xe8fe&ko&EOZONq;x^pMwwU zYu$=)rVe~qUmFPiHSl4&S^@qo@CbZ$tj|s*L3|CK+SP3XyF(qSab$oYsQhy3%S%rh2Sf}k1~0AS3ne4 zCHVQ^XP7*%1F5GADUNxNp|1xWWy%v>PXZHH`jtcdT4!C(=1+x=1S!@x%tr?2O!kU1GLVR>8t{uuB@h|kRf+Dhxn za_}R-hv~|C@T1bizYTmL_%K~@M&ex{;4ciMFUyX~KkE&d8IU>Jlri@Bi@{F^Z_@>; z$7=A4!H3ns)!^rYf6$CS`yRKQR)EjFA$(r>0{GLxPxsyLwc~d1SA#Dyd83YVi(xat zht+X!@GHUF>X6D;4E`SQ=bG^w>$cV4-vFPkju%2E@5b={wi5h#;3xRf;Kj%&unpj^ z1D~$H?S#xm$b|K`P9=Db6nt2J>kIx}@L}y(3jS5_VR}*reiQgGo3a>ukDKgeqD!v@jNjlejfP0fG;w6qm0YI?*boI z#&zI#gSVBD;@=AXWAL{8MZxa{f7wsd*FkhN)@C6SRtH7ke-1vZPfZ2?Gw@+^^9A4^ z1>fDQ1D;wsl*i@Z9|S+kR(9r_Y?GBjO&P#KDAMg#q z`{leP-9H-q^+DcyQ33%U}g!;F!f3p!XFNMTGdE5#9@y_A< ziJh>~_z&<$n03V4&knk!(--_g#GfF3ROh^#vd47peq&Ba=jaW&C7t^$judz9e@(m5 zoeQsOe`e>RhR%hYT{e2RIu$%FV+O&WzmA z-uYQpkE_}{iz6Rq;l~=O!@P&H&V~}@M!w8-?uzg&y$XJk1;;Qe@|PTEPgdmiT<3=D z$fr5ZFLNSS<~loa(3&XIp>rX9PgZ0{w)04K4C&s(w!7#Vk}iLkCtzuF7_<&$bVr;-?Ab<>*(B`9r;~HN)bz_ zP?V0&ojH;Jc646PiQImm^H0jc-MNw99_YN88~N*j&MlG1=Lb4}i9~Mdrw;k^MJv*}V5a;fkkxl6MCb(r&TByw#x z=dDQOKZiQIpil1}>a1uVxv!gZXNSn|x;g7Q%mK3DfXJ?H&YK5Bwsdo@?|1}|&kl?% zJk(j=De~B%&WD{MKsFu}dHGOhVQ2dLQ5CM)uJma{YKScMa3`6CvbvlbnVt31td4jt`w_E(C=VkdW1Kk2lHAE5a%s6kvkoeb zoS!wb))H?w=RdqcLn64hqztX$%c?lpZ=yx=QEoe3gap= z?jv}r{H~GwYtiL`>r{eaUja0JN)F$tf1e-tJx6|b(g{TQkAvj*$_{*|@~wcaT*SYR z6kZpjhx}eEJo#;OVTPivFZc0udby+rQ=u+;PZ?e9IB?1^O3@{-Ge~|P$grd4Mfh9! zn}Sgw(K;*P4bi3RySotG6zVwbC4{fRmqeuTm0cLt`L2|VVn(MfoxYk&0?~5c$Z`Qv zSI|EBy`?kX2kmX7zoa;%&+7Li;r}bY`>^=;{{NhS9_a-7NBOTJ3Ckp$Dq)j^3nW}3 z;c^LAOSoRbO%iUCaF>M6F^;U zNw`Zwrx&M3&&kmhm9W2rjDGw7)ytQ0`>;S1XO0|sO0>^8)9^{YnbD#B2K4KHQvQ&c z>SzA^g8u#b5Bwp+f%|MfbKo9meKz?VXnUdV00xnRUQubqbDeosJmTp7X+(oq+PVGG zkGFSp|MlY?9Ie-W`~XMy2S47?(f!Vkqt^#JIs|eYSgWWh$$#fK2RTtI-q|U#v~!Nr z#VNDmdCt_{w)hWrv^_N090#*^`XG1U%5e^HUI^HA63M|!E#@3=lSg5bHvBNx?wU#D zIEOph-um(G*nhIcbA)5F1369)*KYdbft9D1iU+P7tg;qa@gD>v*`dvKK5q>YG~Q%m zR=p%p&twh>r{`wO>lneEfZu|nQ0NssowA>DK6P%fObk4=e(EJ2?GNFny5{2lEGM;| z?*MMg{{u?CtCJ_~uG3ww@Se`@JN^0ji^z8qc|8t%C3yEhJO|?TEa=q{0lYhKs-L5- z#ErPdao~&=T>E!=yrx{(@_(UD`;!o{I&jas;dYJVqPEoCo;m<>}8NY}YNO7rs3WNg$UnBDL+y`AN z1n(?);}<{bg}4oaY6< z;B6K>SLC}vF`!k>>BAW~S@7Y4e<2y6cUaTa0-W-5-{<_hmILQek-r@EO4l+DoM%OT z_caWR6#N~*``yaG1i@*7OZgcq6+B+>UV`6s3Il456@Sv=6XmCmBv>l)cMJa7?F{@- z@IL}S82xv>^cU@4y)N>@7P6qO|6PK&dxCMbZi+uoYsdLKR4vlu`2aF7xJCd!1|`sb zc~qfTP5@5%%)5?(gy2_8JbK=-0PRHAqk?zEdMsUW4xB$ITz(kAUWtF(>kJ+v+$1=f zRG)ME^loX&Pod0DH2$cPXIbi8|rF$de zhjHKx61?}P45)KO__H3kj#ETcaEr(<&V@n1rSur29v+fYo$(0Ww{oa{-H_yaI&>N;2Ck9nGZYh8K-IOV^aDE{w7{$-J`+`)kM z>pNq@OX;5S0prJt{Mmw^{{{oPT=xooy6B=60RVuy9T9da<|(-FNA zGw1XdymudtMbyX{2b}WhY-jvz=|{`Uc=epDm<2*ZK84uqkmc!Kt=H}GB}V+KVcUoe1C ztq+rdlfR_b$GXc+3sgK9rygQJ_m}m8pZ+1^THgjA&h>Cb4%;i;zDdESUc>VEsjj8? zgVK%4dSq1aM}bqh-VfOAmn5Di*RtR^k}36L8A^*uOEL`}J=GZ@!uF zn?!!Q;Oj)6rwcytNRDUi*9_DO-XQp{PZ`j5`w_u6y~X%BB7ag(jz@jO3fO-Hzf$mD zOFz~1&?@*tSFs?}Qe8bza4J`F8UNPuqXpkAc0l**O9gNF3(ISL_zXDJXK*~~0L7;G z7p-S`-A~5>&vQ_?z<7NgaEhlvDu&(>O4pSVPlrG9Z(aY7i#(l2pbObh*Q+A`#T)z^ z=1yJxph%RTbHx7i6TDvV_Fple_3bXfPusw_?nmzer+gk?$@mv~#J7C(qd``FU0FUjWZTd4vAgZzP_5 zPq3hlADLA7{7S~ni4xBg!8g3jfY!H9fs;Kf5_?!A@(07Qq4NGj{2U~wt~rAD7kj1k z{5QaD_3%59pT3aq*ZOuqZ;t;@|7BdvgnBOvwc|BX4`NoFMI!%YE6Y#f!1)t!l3y{5 zfxd#%d!q<{rI-P&KV6UGbo+kB_&kw+MDPQ4G9b}8-vFn0^nO^8$RBgOy}W%w@M7Rp zpF5x82z34579#&kkze{}me=`jcLL|a zI|6>f*Ah=~USENVwdw!Gz^Pp-rQUS8?i1W;&lRli{kP!3@^(kY$nGr{e=M&97vMPH z6o1nl{JTdEhvx{s{(k+K4`+dauRnpIuv1b;~EQg^}sEBGGK!}A0`4IPcrz34Uu z=v|_8)eC<3-}(2s95|~5e{L@WMS>p%#in}J`>U{1HeESQG>+;S)zG(c~BjdG1@AS*(`0tR8 zsP%J<;0?oB@&UOa2At~WlU)qJysPUm;8FS844#pA@}!~Yn*?;dBk`P)&4AYPJ_Q_q zaNT$maH@yCGLCfNXq+h`f7^!)=<;4Cc=gqcYd_=x6_4C(1P_V))mJj8?e?z)-+B+@ zF}deG!QXg@0cn2ckO7?kAAHGpk;q>v`12bW5Od({1y1FH2x_=URConGj zQ{?x4z=9)0p57@y^}Kcp128Y@nhl)l=f02mcctLFMLxLResCenH@)naA20ame=t5z z;`y84Z@j_))J9#=p&ZW@uk&wIm%8p2yvO7GTesuy1n=|`<6Sv$vQOc7dWqebAb64B zPi|*G%$#!vaHVeu>C*lES&`p*tsi$z<@nzaJFnZTm*Bzmz>5U$DC3LH=WT*NzK7$# zkOSv6!3(cv;AX)O7{=*-C3YUemb%6Ze&^TxTj&2u;8d;$>lml+9?tNVH(uV~PvYgiQVS<;w!ML_Ra|C~83**Od;JhVxaNlIN;Ez7bf;#`v z(>eb^JA5i|%FnvLviwAe|9Ziz?`1&e^BEP72pIuA*Guty_9}x~uMRtd@kyKg_$a~0 zf8@t66MV}jjAIy8*DHdr{EUC=dN`wq%N3kY)d8pcIG?iou^c#$iu|LJL6|jly)5|6 z$Mf$U95|l}9^9wvF`U!Aa1;x^CGr!1Q@TZK89=vE*Igp7&&^3UbDj}=$#E>#N95m> zct)&XK-d4lFgRpCx5zl#N#u_MPU$WZd6)%tRS3R7>i=@Ve<}DRu>+F@e^2l&UofEU zM*ool}q+ekyvR+ofLcCTZBW z<<{lEss4k0I6d=6`3d?J?`!#=a0F*cJpU8??Y}c1$vY#UXB2;X>8Co+jeZwUUCBv>iw;#e}q_pXjUU)fXefjOBQ)ypI7fm(C=?XDwu0>+`*WfAucox}HB5 z{EdehFXO-&c^1dt^J)fAz3RFExLVJV^M0^&>bgwiUwDLnR}22M;E!C%KveJ-f!peb z_Gzeo7Cg&>x?e|28E<-;ah=a8g8!;rmLhbVKNEcZtt{Vz1LqIGNgsmy?At}Yr}*th ziF`g3L&qtQ3Z?+3eBSs3qdGr7Rr2u1j$>Tg`G-Y*&Ml1h;=p-B`c>4()&(bd$(DE_C2T1*k znRA{4PWrGd;NQLroa%Y^B#x&_;@_v_yE^)uvDU+5QGt|yeXjc=kuMkg)<+oVC-}93 zFa9Y5T0d6_UL*VUx_-V8T%X_WBJp%To6`;M_gw^>@*lJ_*NObBZ5)Bl|33u}p07A= zBF8^P`knUEY6TDOL;X_lO9T1eCwR8#kFJNwXgI33&$Imc|A64Z{qa`>5AIiXsNi^_ z*K@hF-#9{WeV!h}gt{7lca^`*;F=Kp7K!KApRn}ta?|UAU-$t7CkWpC9IpRi7(eOK z?RC1s88iQ{68Ydd?R?TUk}9Lpey?2m%q_b3Cpj0Z!HNq&v2+nguz zje_64jR76c=YqFe$GG+%E`h^CdiB?O#=qgfxfeLaf9n4j!0qaKU*v=5Y8(teBtLo& z%N;86lYvwGFQK2&RltEWOXSb~BLliz&jP3MOFw_0?c_TWPjLSt=Uh&A(FTsEP~tBU z{FOES`0o(>ELr!{>Aov?`AaOX^|>o5mde%P8piebH2^r3t2Cew=Zbv8Q~r2f5xnCf z#t-Ab*)I6h2PA&(HqIgEbNs_kWxTJ*p9GxpGj}Zmx?fBZ`8CoZbi4mp;9B7jQl|V%|fS?iWLWQ$EN1%#Yt8`1+?AAIyRC zp5WL1l>wd4A6&@s& zzhS($$Ui9f8tIR2{sj-t>w8V*c&6UL5$O846u3@HqE^8*z^UGfA7@m{Y!*B?f6R@u z{Doh#yw2zOf_Hy{ab2Gu04MvC49rJ96Zx&uUykP6oKDlYeHV$I7YRNXIOX#XqF2WV z{*cH&EdGO3pYxi?A1L|MvPDxYB>MFbjyKL{`-r4)AfIo;7{Ga5o`V2Ab8OKIS~~|@l?FW@><`P2_8HT zun9Q%jrzH`JjwrO!1cWXsh}eqLW)0Se;hcq%S&Tf8g9J0YDIqjfA}}5U0v%151vEb zq2duCBlx$%Q_npPL4TukgZ}L#;FQnPe#?>QvQYmdJh<-kzKX|4Q2yK@^1*YV!|FJm z;Q5xz1%FiRSf#}CTfw8BGjOQj?cjes|8N&rJv*MF7nrl{Cw%Z zy#;?l@TspepzT9fbU;e?>yH`N^)m{%{#&9@!BmB(p8vT*;wgBSrB9Tb?i2jqA2NX9 zUS0nY{J{_Sx6aQ6joglFCo_(0tLq-%l+US;@NeB8qfLyzEb(akLg1tidx}|J0_SqU zgX8rB5>H2|2c4g;mvH=#Kg99qes^*RUJ9Jj%|4CgM|0rRi2Otu$7c!tq~It2iUFPf z+-6R!x?G);obFR!u-s81f4bm7zh$=I-DJM3%lm-f&;OYt(0<4# zz{!7JBG2jS_&d$ybdO)f^16)Wz^Q&NgI%HP0S@r(9F}jsiGdddzfJJ5uQ70l;5!8m zj*rKpp_Lv^V8OeyI4lEB^?&+1{JT`*xm@sGyG35`k0hSp`M`FwIi7a^WWm8AKO49$ z-4!AqTzC49;HBF*0^NU)p2P94mGhSONc=N_Q~beom77HVUYVC2D)P@MdHG=ke-rt< z#~2(c+|hG6{^0uRMBr3!3tnNtK_dS!aBBCd^8DR#f^U|1g8R##NIYe~WkHF~8F?wk z-ze=1Go`NQ1rI)7@TK6-?_jwTME;B)bN){dM|+;&lYvwIH@wY2rQqvCK6w@c6@qUU z`Ji8#jR+~8;CZkKz^Pq^m2d&*8;ISgVQt)BYk92?Rynyo)+|SJy{O+k7!8zjJP5@5rqTidK z^D`ef>8E~wfUeIwME;jway%Du;JhyQGm;;j&*QJ)`2Tbz3u=25SFYE?R?fBIxEO@lYA9)qy z!E<^gz{#J{?|Uc|`C8zVpK(tx&`JdNTeCp?IqY}@lz$u@9ewKj(!EX}0+Xe=HDEOZQ5ALfv*Kj=g z{S`-u{4l{EU&w&2&ql!ymUh>A^_bv&9%cD+B%V(MzvEU0h6{ecwbU-DR}bJ+t}9<+ zPRCQBp48_%`d-I+7+lYs2%PdW2lYf(FAkh$;M9Lti(k=0@FgPuzVy=* z1buus9jz4cb<3mM$h2X>AV?g^A9j<5j({5v2+w=Q@Q~wI?7q1if;5tB; z#T-xPe{(##ZmR?jo-Oz@Q-viu;4X95%~YB`60x5!`lB@60${)^ya*Zc8ff6D0wpC4%!{A<`V zy0jkNAov`qf8BroA$ZUa?|n1Jf7@dmkJish;5u*2@c+w0@D~-H+Fl)Rp?XNYdIP6+ zyyP3^biKua)ANS<{Tces29aO*Prv-zg7^C^EcY z%z(B(8w7vhAB<}~?{F*YXK>x@WZ=qP!LHDy?eJ`oUn>J?jA`c{k-zO#1}X*LE%<4I zpDTDF`Z>k_XXJ}69seBQ)L%v<7(XqG!^I-MbO-`EkAMeu^{H`k*I7IL!;FO=>y69bk2cJ9pt;EwG?Mc^Y4xGOWuHO@-+jpPf zFNq!2cJD~oBT6@TK4-Y#L4TtLIMwI#n>fK@N%w8RyZ?~^ZHIqwC(8%N$6d2+uzOc{86P#b1EBNEDv!Kq;b%GCXWqggq zLod>${G2cIj!A+KznAgf%ebTK{~E!2{elH+ayWcJ@W==JTlb@0KjU~_!8lBp#-|G2 z=@UPGzu-T9g7K~#IJ%b}-7a`3{7t%AIBd2Uzs}FVpEKT3%5|8;Qw^N*IrcaPMhQMo~59M@)u zd~jZWtH>{t_)n8`cPM%JVFdq{c!K-UT_2G8{ECGilzRpV9vpu!0#5B7JQsJR;8Th@ z0e^l_@q9;23_avU+K6v|;98d5Z??~X3?rjqB@e==d zkze^222K=ww#aAykb!-I-wFI+#H8Otl`Hs4iRZtMGNAj>D-uuTWX5A6f50y}pI3d( zfVMLy3m!ZlezxG%(jRsIS}pi1J2@V0_x1v(@_sPIpY9JH;&jWTK6O4v0w?*UXS4j& z2#1%5{NCI7_X!+0KNoyLU>)N_i6{7;fyl$0?v|@L0^Q$_7Cg9~TrGIJmswux;gf>D zyPEMb$P=DqDr~DlMHb*c-;@Kd0<?YjXur5oJG*)DkSoO8~vIQ}}ZpE{lk1rP3vT@IY$5AIJb7y01(Qa%(s z_@11je$D9y-!~EiPVoor@O6S;dJ0#V?(eGw|KL={M@W7C0XVJ8>Gz=K3H}e@RG*PI z8R#nb_}_54!ROr;2wqgff=`S5y}&7+;5yqIf1Z zzbdCX(VUo3+mcK)$CCB2s=CI8M2i!PRX4_F)HP0v*Tt%njm<5wIQCSk8ta?t63Ik$ zzry~5``d+L(`y@QWAWzZ_}o~cA=y0Fncf_)PsFNc*4NL)Eyk}HB$GbTrg*ZZBGHoU zSJl+y#Lg>EmgWy_s!dcSX4kePVpWX|Ey?DYRY|4_W3k#siUL2!4~@lUG|Y@u&6!hL zkdNFarpIU2C1Z7sRTsya8tZDS=9Wl=1LAc+<0ur8p26VY+8GUv%?bP%h?`rI@nmh4 z%3W=|uJ%&=YHWzb8>$g4XMle9udQ`rXO>PFF}xJF%$yb*6KknzP9z#o$WarAk1L6l zj4zJG@XJ@sYCnLqno$6WXTqpaC`9oskV$BJaFBH5b(VQHklQS9# zVlmWsJ=Cifnn$fMrVJ634?xB!KPo$Cp@;+O8)qd9A)|Epg=I6F6ZqFMvo?t`Pp_>@ zl#~pd7H>(Y43{ShW5v{BjdPJ>S3#_48_`Ool_zy+ktr%3WsPdBB33?BWzUFmKtp17 z%xw%y{gf06n<%L-JBzBbVv><&e!fu@($p|+U`w*GDNS=&>%?swR4^JxsehtG)%U#rd4Pr)2}n&~5XF%t$0l8yhbkUXzGdv)+v_k4a@h z>q%jCjT)uXwXOAsvREIV6KkoxG*L3~EY8``re^4IMZ76djmw`^m3ko(=QQj6Y(ams zAk-U*g=LK`wbai+r6iF*^z51OYG`R~Re4igZ9{?z3_+tn<+1#H;Z&ES zDldS-w6)xWrojj|q-oedJq@a=OT?Q=zAoNEMzqRbZdEHI^Qi`HYj8)UR9N7X>rG?STa7N1P%({Gp6h;vvz%kqKxuh zf_$s|mlu*6AwASry{a$OSIa_gr((0}VX(BAS9?>6u^p(4EVYmkzuUp`^OaF$vzVen z;Uk_hJtbzhKzX2X+()OytJ#{&^7TwEHQG%NPqD^n7r|P^Y#s?Y3Q~kw@L$SMdlM`2 zRR>g67h>jgTg$DwSB9!ChA%D)RZzN!(^j(BsZ0)tsUbR}ZiA+pn}Mt+1L|uV##F<~ zLk(b(g2VV=t_c~kQG~*o4djg~w>D9&)H7peG;_xF;c1%BH7X+)i8Xm-tb9bq_K?V= zInc$%>2U^5lGOS4+3#%bqOJRxO%<-@(nuw4`?_9t8s`bZ&?>9Gs9xwfsTkDQiMBfS z))-3A{v`!N;6ODsH#Ws*VDyY(qM~e2yrl(m9My}f>&j-;n?p#yp_pM*j2o#ZET%OO z4MM)lJa105jjv<+t#pa*TIo8CR&w3^L$r5Ni%Dh-Lw}q{k1-YFFz?cHRAiH8s1@;P zbu?W|-z|NHR$C0u4Wfi}>(Nvr)ISPlbpUxquD4H>I(oQY~4*PKw(oaV%IloS&;HQN}NoZFNLxKRVj#uTGo$PE^s8rhaf4$aZk z*i-^Ls-~)#_@o&+)Kq4W>ZZnknOWn9=(tJWO2`6BOJtgk2DGFkzkfB)6v@w1lTlc9 z-SgYr8m^#fPx3fsG^_c-bk3G#RPdf8sp;^CzMYStDTMsabiwYqABTm5vGsMSuQ(^X4$Z@Qt95<#fcSGV9hSVN8I9Qkg9+L1)e7hy zkJ=5hVUvxi3N?*UYSXC>Ogs%W;~8hHu69~gtg2nP+)&0J`m%`hbgt zrv4s16KO%aFXFltZh_FTsOPE?D|D7%t6!NcjB0F1V#Ts~Iy#(R&9uL$rq*iKiPcANp%nD>=mZTDkvB}4XbbQDy-b3tPG?ZZ-d6c^b9NXj3#dJ+)^>cK;_B<>as=YGUW+g~uzm2Ik z{}>!AXU7If8`UmtqjkuzuV$Iu6;5x22zQDkN}nrJ29qvsOh)I!99q5l39is-4Haiu z_qIvn^ZR3wVa}ZRwAxwuwDB>kz7~5p@b+WmJYofYdSi*{>npo4kfsD_JVWy9cpf*9 zR~O(1HPpeg@OS+D0T_zC1wW~_`~k}ODyxep;Rx4jN7WdC!Yk9NJ+zV#SffZY!@}~S zyXJY8k?4M#0Aq!(sjj4siryAa#=3sZ)0DQl>Dq#j*$KMm^|k(Xvzd7>n`lVtd*l|B zsEMbg7O>saKUR`IsM>W5mFiF}4v&==^Yp+SgwoV}{*abLvY0pCAg^{~(oA;CldOiB z?6kT3VAT(!xaOMRc=(XmQvy^-#bkn?n9U_=w_r>|bz)8lb_{9Qw%NP=sRo@HZ@e-KZd-=&a;YYeYL7#?{~^;=QNgy& zPt|0dc1>v~^St~as{fCxZEnVvYW10o@jAl-OV*Vk*$?yTnq*fI-SN>FM%1n~ubS-V zXoyA`g1w={jAraes=d;9LvqYCTI5yZFZfL3zLc!Q*y*DwEsX>IjYzi$fw5U8(nu=P zm~QLzfuY@N@ccpKeHp5W!GqRvLcKF0-P+~Juh+$lreqz_V|(o!tl1^8+v;jN3eNj> zAu50lq8Ck!SZ!S#IcA4<09M8PE10}HY|NeGKKm$nWHU%}N;U&<@38CHh9zTv6X~)l zZEVKsw3<;T|Kvwg{Fs{O!bxko&dPY|{i|%atrU#x~xSS9adN`aBUVT9~@8 z&#|^_HIfXvox4ZHdoJd{lWK9jEeOo2G8pgjA!>}}WGv2?tv?5SFj}^Ub!w_XUd`mv zuM_JAq}X6q%CTxWJ3hB1mbheQyiN^wTyA&Q#ovAGO^~)XdD?Be8EQ@Dg$5y7_mF99 z|JX=M0B1T?ZFxyGe}Lxpf7irX5YMK< z$s66sxw+$mN4Pns_BK>QL$pwP~asY3k@iHn}^;3a6#*6*H8`r4M`kB zz?QSJJ?;T0obe#vR&A99d=>iv6Pc^4rLA%C8R&;It9in%mhRnsfY^TQ)RcH@=rk(n zlUS;6yRD-JuhhwpZ;yX)ZA&rsLxOA6fvK5gE7wy$qxWbtC)3Q}x?1?EEZ?ZTw6?^Z zItM4CkWYU2I4rn{FD4$jZxZhxll6Ko)C4_LHMQ~y;;P%G-FQdMV}L+cEBBTQT$kFY z6@P--3Ghzfs9mTw>!>-F;wT=*(%@QU%CS7drlzh|dTRlmSg3Co7(6V~!8ASBtsCmY zdRmF(-SwpM#=4f0+BD19Vfo6Z9kmLq6ka^JwmMlO1Jgit*rE-)XsREkY@t=eN_Yot z0_+SG9C;3HRbFHuwQI(LC#{gGJKQ20HwHQhFF42!fIkJ>xbE(a+V@@Tx>i^fZ;Dsd zCg*a0FxNH07gO}u?=3{CRTMRrwC#ihPHl{f;Y=%SB;(v+Gmii1jd{zuR-j&diealq z|NH^#>FLiVy8dcIB5H?}8z=GONu2GkRw?>BLa=X2mfi0EZ91b-Q{sxrEW%JAZ|Ea0 zVi4NutYWd1>FiygMnev~`nsIkN%geBpR|m|rfsk(bo#laF}(8m%Giv0c(iIEfSxGu znE-S9RXdAje@bJTY+cFNx8mW#H>63GmuOGVUwCgRE-;lgno!38?>~5CmZ<^p>S}d* zfeu=utk@XG>&Q^%w)7ng#uFsowzs?6lHo&)xjkgAK^QI7*0IH2jDvBvlwU81!|3?bOg@%a}1^vnZ7lv;`=XX-bGI_TE$1~5~ZFt4B^72dIP*Jnss zbk_z`WhUK9&VFPr(DGg$&GjT+_zCuVcNBw)%1J_dw@qu8yj?IX`TifRou#&bS-SAm zvXB{0zzl`1kE5Nw>n>er^O!1R+pI(1PgOxVPoMded!U4Ad>YTdhWiN82~(b4!`{Yz z9ba^tG38W;T2#U!3>I{0l=sG_u&1u}dlu_EAnFeGZeMl#0-eU;X;;Q10&VNAm-$XA zxeveKTn3z)W;`I$INfYosa%wttQwoDkcpK)!3>MwY4(-!`=gL3y4s!R?P&7Z&1$!e zrsUk9O9W2jV1)%+8!F%Cla_AHT8)Q3Fq}V7?GsO|ZJ2RpbK}e=BMYJ|qz=|0FQDSI zuQ3y|5_cv<%~zgmNFdL?u4K=TxGil+$<>{<^c;VS>1E3OG4Hm9@N#KRrOdS!uLG%S zV#@Y-ue~o>W;zw=Na2_($Xp<+#fg8fTEmLOgtz)bok;&l01?e^}t`d2%MgNRDe2F$bRm)@uX4Csm}Gygrd8w{GutHQ%yT ztP-wPMTf!=^Qopc-baUZDhxLC{Vc#}F$gy%tc z)!v>5dz~5w$I&1*2M%yx5HrU_X9)L&jpF(yZx}bL-fTkFu<6)bupNBy zE#$~4jdW_|Zw9^eV^sjZDC$1-9S!=Ci%bKQUQ^Hq>i<8Ovr}vETNl(;F-|LzXJB*_ z%Rs5C!x*d5pOmon5%ol!{oDjSMVB(8_wpoWD&-J@Pj8V)>_&+G;4kURY*5>C=mAtILy#MDrwi!v$@Y$qC0yn-v(%)h0YTuWtdSYk*EfBR#Kz1<%IvF1Y1zY|1(YRF=vXwvnqy z|KUM2eTMUlT3P%LCm209vzMv6yM3^b1hl8)E?f9tVUfB{Ri3QF8+Bm$t7_tSI}*QP zr>X=)6Gjmn62nV^8u5TjB3?hHisnLtVpzvaF$xfNXQ07z{V9eyI4DZN5J$+wkYgB| zL5G!8Ats^xk`(rxJmoOEp~aY%=$Z>22+@Ov9t_~hhnLl-_ePYaBjEaAp2wJJ`$VeH zTm3TD0VeD$8T$nWCn--f;)7OY<$Ref4i2r|Ok`#uL!e(Cs!X zy~L-rU_m%GW6qpdQ=+-0k)F{?&W+9LA9&Qmo{-&Ah&!mx@rF&j)86TJE39{?oZQfr zI)PMVaOSfbUfrgcAX=s=Z%QQOiBwP0wL97xP*UISc$Rl&LQnO0g_GZ5fh~&}$r|j1 z;)J`s$J_Q+{o|Wdw_9mO7xY~E;2g)l_FjM?X;dTLW;PpZC?(V26!AtgEve9*33`ZL zErkSUh(==8CZ$zv_nFpE<7MyAdeUcEFS5DXa+FRP4s*LH)6kcx2%d5CjeM9?_?GO= zozhH}CQx3h#rf_h1B2(olyBmm5Of_Bzl||x8A0#ZoL7i%=pXn(&$qa4B}(p1L~>0%f#rsggi0hy;8ySc-Zonq&c*L#&!>_ zmpkTz1rxRg-=tz)xQ56zL!>k3Bht^Hn)^Ez+ohI1*t z*fDR|m$zzYyP4J{NE?SCSS{!v^kq-kMKzJJP(bOW=X?dPf(APr7@di0c{u1Tm9nnRzKe+uaPl#;0-Yi z=QLo1s*X)ew9KrhC&@>S#LL+FJE-e6tTx%Q<$90aIIXs9jJ}k4&R~CJ*Jv|~UGzFe zVQpiJdXe71F*p%UZIR;mdr`Sd=xT5rS;m91ZGFl#oc5B_#8|y8OwWr=oiiH6^|-LR zWOuq~GH94b&+vuUoi$5sSmTF|+De;gkoR?=493r#-&%K7T{~%1lC?bA3VyHaWCaDj z$0E~jd!f2QrhC>5XPW()?;>>FGo!EA#vQYg{GO{@kFX$ARkTiDqWvCE=Y75^QsrlT zJY#Mo;C7F+meJH!zXM}>CqeJWqBZEm>Nt&kvA|lxS|!pP#LiHOdUj{6J@2Hd*_lo4 zZ$oc3ot-dWOa|Nxu9!?fhVmPF=|!w;T|Ix$Vj5*QGE>gfy$u!c50IY6;&Hs0~dv7UNmqM50C1*0PuE>l7s^QCOBJMek_5_N|3lo>Z}D ztvYS1*F^QUL|X4EP^aRlc|+L$)sY>kVNcUDo!CK**j9%#sgKz|0%i5mHiw0_FMC?* zU%Oj|-AuoZB*9TJj6PEK2))CkAFSJQY@hE)f@zXd1{w@&k z#jFJhbUw9{E}gF}?uWL5X0L5SItB40Kew`9vwdrwyRBmmexCW>AC*n%CdP28U#n{^ zoNhNg^|GFSNoyH`F}O=S>b*RA)5>d+^op)qg*<^w8m?YjU7eU!%deiIMItxx;NrNy z1L+|+?6uTkYnFksvg+_L45KUCM(;M+m()i4z8-(~^)62ld?RAo=iaBeFQp7T`lcI9 z4+Wmn7PhbB4PD_U`|XaC*J1YSsL5dWiTS`Yy5u+;qq!7CO{iqm8H$oB0MF7s3BtaO zeo9c@7?pX^n0v16O&>l2Yef{YDxv4z|NP|DC1eP;MCTpt45Ss;k}wSbkww* zUbEYr74?o7Rj;8>d4DHsXAaD1)i~r3pf0Aif2s~Q2FkAT|&)I zV5}-AspmDV3Yxy>_vh1#jnf*FM%}wBA>ub${hF{bn0I0IwEo+80`v@}`<7961eTjSsYVZ=0l7R49cp4}*Gx$bPG>sUfg>sb@gYy5`oh+H?x({q){DIZ$M% zy=91pr8D19p~{odlM0MfsScHwrp&DdH#g!dGbzvQ(+mdNi24Hwp4B&WOgEZVeCuhR z)Thcbb=Kg)9wSAYWrraN)RUP&o1I42tM=xW{>AzHd|Hx~k8`AMI+%&t6wEhI^x{um8RvwCZ&gJ_|(o}KUmm1Dz;Jr>0UXd~g$&PtoJIGkW#)61?lP4b7w0}Kf z|6MS5m)>i%)PpcuD3i}^>RFh}V+>&WU3^}T3i-qfd9nDKRSUh-OWvB}W;e|$K3X0_ zwN2xLD@*3affUx=`OegF)tXsmk3=1=-yct&^%mZ3b)qhg&uzig@N_9t|ImiTIvTL! zkaCnFTtBT<=pKU)S$p#r9}iG=r8%K|uHeZNuYU%fuGeXcFDT`Tg!4{WsGi;(Ie&hGza;KKZ9B$J4 z+!z!xEmBJK^ck^~Wy#RiNAXkEl8wO%7MeC(U2~f5;ELZ?csiv%?<)oIZ}Z86ENA)~h*RR?!}18)f- zQ`VC4)y!#!dh0L)y`%4^> zK0@u_qhWZdOS+fX>T30lOXD{CDu?&>TDNwBi>!fFj(ok!;a{aPeO(#B{7W77)e3*) z#?v{ZaNqF*3aOQByg3oab_cVf8kKH*pV95R?yzA*m$su}Mdw?+c1ISRjQ;7XQ(kol z)aiaWds5SGam?)rbX#vS>#fb0!-cqCd_Iqqm5;l&^<|j8*X(gz>IjAmJcTiSOxUPn zea2Nk$46bT4Hn4VX;H2x7EtEYS|0@sRrg?TZqq|}{LN4Lt|xRKvqOmle@QXOinMWH zwkubiUEUn=bgUCckH?bLmOpx zrA&2V>rRMv!PC{BzYesMVR>j%E16dxf$5$-V`-YsKW0eFv95)>(OQq#Ukr1cy~%|7 z2&rlRBmzuqm8T-7IYJgG(s`MxBk>1l)$5IT-`T4j`(l;W&;7HysFXA&(`snw86`cd zaIJC%+iQ==a^TDQm1MY#ZttdrHNUG5=Z%)aNLlTb?bims2VprV;TOkN@weI&vP5jH z1l=#Z>1x1xYr~EN8qw~%X(KyezuvQA&u6Nls7V8+g=G~%H!0{LOX0kC7#gEESGRxY z@j164yP3Wr&9z}XiiVzi^l47Wkw;Q96?P4(JijGsD(*3+YLLCl=;yiM{r(?WWGRS)uJ7cfb&0 z%u4rgj4F?M*&057+CpF1P+yt%d{Na0+ob)zZse{T7)IJFz8+R(ij6gl@AWl=|2NA| zdSHU8wbea@6C->3!FSgMjiDN;(#34oUcE+<`qB&SKUwQPZDjuUk6ZdcK*J;tZCCQp zC+h8UeS30JK2>Gr<9!*;W1C#DfP!XnzTA-pxq_dEmm*a)w#dSr_a>pXI3k%+N_l7% zDW-jHUX3uu^d$X>JF%_gJEeU>*1B*l50=KbgO-*>OK&a6{G4jQLp5qgyQW^P*xm)6 zI=aZJ06k2`Uw5R|_4zzLCrKFzF>@cGd!KA zK@$l|wN=^D%vPsuHowJ}X`~Gf`49IL2Sn8;{)^dh-U|F-ZMYk}Bj% zQ*#8LNAOn5zSpyW$_jE?na1Ka@2tBkbRoy~{GORN@wE(KMo*+Ey?cs#|7OW%yJk88 z5g5a~E|Td91|yNci2|#BdZWFs^JV@zfqcBs?b^Y_e9ql>O~o~r>5j{&1yO4uFNM)V z53#KgW*q&=8l}Ac$1OF+JRJ3GuE*=j=(s{0pQZ?W5~2Sb zLby+AtwT3C*OissEwTgO<_ns-PkE}HZpBq?8@sOs^7P5DzdAy3FFk+Hc6`8cUur`` zXTn~!=I@^+m-<4laKC{A;V+Cil_*NF;O;2Mz1SR8cEter*zebp?BM!R>Qo-v5L( zDOQS*=a{84QQ;^0V4}uU(7W(v;PvH+=8AEcT{k2u;?vaY4^af$L(A69E(}n7$U>gX zi&eKY#%i!~Br$~^=s_a;zle)IOZ`T5PnDo~s-sPwq-d4*AqUU6?yvhP+G0NVnbE$> zVh62S*p)18pEYMJs_UeCp}LtDU22tl%E$0h7jU3-yswkKFZo9sJ=xD-1Z*XgsRW$T z{oO^C+MPD6T zAH7juA1fO*vAnT7hHsvqSvqFK$jVB*X@b91Xg$wn3`n;2P!DaU_#v(x_s!yl(A(AM zl{HwD8d(yW-VTfYx`g~WTlXgA)8ZAzXRx15>|+`tBi$1V>V_}BI9$s`TQ7{GDiX3$2$Nf z#;fr;9C`=9^rjZl`Td)DqIS{@?V>OC9a*o}*a~3rK#Zy|mUFzxxH&p!s2+2`46Sc- z)*ugN1&o4aG}SKwp%!-cfc&Q+bT7&Z$N|_w^1{SSE7zMqpjyCS$ z>o>W!WxvPpf1oAb-$^)or}Osw^|?4Cx?eAtQCoq&Z|;yslxfgr>r&!hpbV_&T09ba zA;ioXpJGaL;;M~ZFTEe_4ufeX7x^@F7AL01XV$r&)!?~#Mt{Svc(!@4yBqBL2CDDA zbgvRKUzlSIRH{`B3*OdN+~1EYn`S0_P9ZuX>jp+P*%CCBx(`EI#v$BAyDF}qq*l^1 zjekZOq2|qML(Lm4YeVYODit%E8_H@^UQLS4x_G@hCI)-NJ>L377^~`=>l|Js&=J27 zpU!;`&KN%O{w=0hFqoDPw6(2C?S)ABgwTGDrfG(y)RPo#n(9D%)M>B4z-4J#_szcH zc2fo}`U7Yb-3-UTJuWR|t0uMOs_#19nc!fx#x<@O# zc$pDL*RUp`GeUV}1=Zp%CItN#@!<8W!Cw&!?B-G<IZ zok4GsV;rna);2cqw<*R? z*mUm|)@i&=?+YnywtcRk+M82O1TA^dG_e^a1pFBrBA4>H0veS2us?M6~A3~*O>;k?IX&DQSkW%#<_M> zHZ>gPTeyNxt@!s)J%tqemrrl;9~Ym22k&QMkP55-`?OY>`QUq@(y5rg;8;n5OOLOW z;8aTsw#?%*62X-XTOFgm%on``GZ;J}DO0j^CO55PVatN|s>4(V!7#h&&&>H7Pp#~$ zHz&sHX2<8Y#1faxjMuTHLX~Ek6YBvWY-yu-a=+%p^nMszQ$Eq*pKWkNsI=gx9>OXx z{2AU%u99yZ)#62%3T@1PwdZ7?MEX_C{|ZQ@n&0-#IohUq2FUDW^acufSB~o$xvK!s z*kEn?`jKAy*slunxj>m#TLbO_SCa1wzMdUOofm0i=o-mP&bQ@Qv3@f_TiiRHJ>yll z>8y%w8M`gl3A@b_rpRK4P4jBoM@k*43tMVuG|a4zRVicXJA?0TP_So*!S~y$pWj*- z?VU*reVQh=Gtk78xq^J(>%hzE;>qba(Ik%%rnQiP`bQe>;q_3x^HeI`R=K&nV{;eG zw#r~Y%mZ_HoCe*MKS6G{B7q{I-E50bUMrXx@pnv7O7nz(F+zODLK#*OYH3?LO5OC( z#s)p=dtB!C7uvSI@9jbul_fo0J>BH=YnfZ0j88+DZ04{=|E0bL+T`@Z`xF!X(AoMm zH88+WHU3f@VP2X_Iy8L z;IJJOryJz2rn;olPrXmDAO7q&qY*#pkCsH0(+^L5o@^|eTgW1rU2;`FO( ztglZrB%SZ!IudbY;a|4I)jfy*&|y!(bwIM_bu50g$3K04q1>;-s40xUI|P0Y#&7ff zO1WQ$y#w;Of!|{S_s^62br=oE2k)N@{;Ss3MxFoVa=#8&$^Gpl4CX%${6PHE_m@cm zI@}cD8>x&`cl!SB3_G<5DM@{Qv?CKb92CfKu>LQBc&m~BNuBwA9nRyQj?TYMM~Cyl z?=$Y-BKPZXliW}Fr>yAw3+&t=xQ=gS7iM%=DdpGc>-%;2Z_(4}x{qK-|n^&MZon;`+`=e2oc0*k-i6k!&{sO>HjTo|D5CbejP3x=f7X; zk48TT-0vhM{}N6W{nhfp^#22bx{NO7%0+zt%1b#6*0)YyhdB_VE~D>XEBCLJ`?Z`- zU;ox&7u-)N>HF8q{p;oawVVxoyW4*>&=WlM9ew|t#eBn@c^vkahNb>bmrhrg>tSFd zsqbHTBj2}jK8KYY(5>py_v`Su|2LpKNC`|o!vv^?1_-SH(FP}B`d|XuKxH5?n0^PS zeg&xh9h@+g5ZVEi%U}T153kft&|(J47Xf)VKt(iDetID8gQts34GmO}|bD#8s9s2SYWWaTx&RoUa%F diff --git a/pathTest.cpp b/pathTest.cpp index 9a06841d..50a34775 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -6,6 +6,8 @@ #include +#define SIM 0 + #include "include/utils/vector.hpp" #include "src/utils/vector.cpp" #include "include/utils/pointUtil.hpp" @@ -57,7 +59,7 @@ int fps = 60; #define starting_point_random 1 -#define PRINT_LIVE true +#define PRINT_LIVE false #define GRAPH true #define FIELD_WIDTH 140.6 @@ -78,9 +80,10 @@ void printRobot(Odometry odometry, double trackWidth) { circle(point->getY() * multiplier, point->getX() * multiplier, 1); circle(point->getY() * multiplier, point->getX() * multiplier, lookahead * multiplier); - Vector forwardVector(20, point->getTheta()); + Vector forwardVector(20, point->getTheta() + M_PI_2); Point forwardPoint; + forwardPoint.operator=(point); forwardPoint.add(Point(forwardVector.getCartesian().getX(), forwardVector.getCartesian().getY())); line(point->getY() * multiplier, point->getX() * multiplier, forwardPoint.getY() * multiplier, forwardPoint.getX() * multiplier); @@ -259,12 +262,14 @@ int main() { TankPurePursuit purePursuit(&drivetrain, &odometry, 10); + purePursuit.setSpeed(1.0); + // Test path Path testPath = Path(); - testPath.addPoint(0, 0); - testPath.addPoint(0, 24); - testPath.addPoint(24, 24); + testPath.addPoint(40, 40); + testPath.addPoint(40, 64); + testPath.addPoint(64, 64); testPathIndex = purePursuit.addPath(testPath); @@ -278,8 +283,9 @@ int main() { delay(1000); //printPath(path); #endif - // Set random robot starting position - Position startingPosition(0, 0, -M_PI_2); + Position startingPosition(40, 40, -M_PI_2); + + drivetrain.setPosition(&startingPosition); #if GRAPH std::vector robotPositions; diff --git a/src/chassis/simTankDrivetrain.cpp b/src/chassis/simTankDrivetrain.cpp index 2a700c38..3c15fe51 100644 --- a/src/chassis/simTankDrivetrain.cpp +++ b/src/chassis/simTankDrivetrain.cpp @@ -18,29 +18,32 @@ namespace Pronounce { Position* oldPosition = this->getPosition(); // Update the wheel velocities - double leftChange = std::clamp(leftVelocityTarget - leftVelocity, -maxAcceleration, maxAcceleration); - double rightChange = std::clamp(rightVelocityTarget - rightVelocity, -maxAcceleration, maxAcceleration); + double leftChange = clamp(leftVelocityTarget - leftVelocity, -maxAcceleration, maxAcceleration); + double rightChange = clamp(rightVelocityTarget - rightVelocity, -maxAcceleration, maxAcceleration); - leftVelocity = std::clamp(leftVelocity + leftChange, -maxSpeed, maxSpeed); - rightVelocity = std::clamp(rightVelocity + rightChange, -maxSpeed, maxSpeed); + leftVelocity = clamp(leftVelocity + leftChange, -maxSpeed, maxSpeed); + rightVelocity = clamp(rightVelocity + rightChange, -maxSpeed, maxSpeed); // Calculate the local offset double offset = (leftVelocity + rightVelocity) / 2.0; - double angle = (leftVelocity - rightVelocity) / this->getTrackWidth(); + double angle = (rightVelocity - leftVelocity) / this->getTrackWidth(); leftDistance += leftVelocity; rightDistance += rightVelocity; - double relativeAngle = (leftDistance - rightDistance) / this->getTrackWidth(); + double relativeAngle = (rightDistance - leftDistance) / this->getTrackWidth(); // Calculate a vector - Vector localOffset(offset, relativeAngle); + Vector localOffset(offset, relativeAngle+M_PI_2); Position* newPosition = new Position(); newPosition->operator=(oldPosition); newPosition->add(localOffset.getCartesian()); - newPosition->setTheta(relativeAngle); + newPosition->setTheta(relativeAngle - (angle / 2.0)); + + std::cout << "Left Velocity Target: " << leftVelocityTarget << " Right Velocity Target: " << rightVelocityTarget << std::endl; + std::cout << "X: " << newPosition->getX() << " Y: " << newPosition->getY() << " Theta: " << newPosition->getTheta() << std::endl; this->setPosition(newPosition); } diff --git a/src/main.cpp b/src/main.cpp index b1c9cde6..6f70a069 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -38,7 +38,7 @@ ThreeWheelOdom odometry(&leftOdomWheel, &rightOdomWheel, &backOdomWheel); TankDrivetrain drivetrain(&frontLeftMotor, &frontRightMotor, &midLeftMotor, &midRightMotor, &backLeftMotor, &backRightMotor, &imu, 15.0); -Pronounce::TankPurePursuit purePursuit(&drivetrain, &odometry, 10); +Pronounce::TankPurePursuit purePursuit(&drivetrain, &odometry, 20); MotorButton liftButton(&master, &lift, DIGITAL_L1, DIGITAL_L2, 200, 0, -200, 0, 0); MotorButton intakeButton(&master, &intake, DIGITAL_R2, DIGITAL_Y, 200, 0, -100, 0, 0); @@ -81,6 +81,8 @@ int preAutonRun() { pros::Task flipOutTask(flipOut); + printf("Array size: %d\n", purePursuit.getPaths().size()); + return 0; } @@ -99,7 +101,7 @@ int rightStealRight() { purePursuit.setFollowing(true); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -113,11 +115,11 @@ int rightStealRight() { purePursuit.setFollowing(true); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } - backGrabberButton.setButtonStatus(ButtonStatus::NEUTRAL); + backGrabberButton.setButtonStatus(ButtonStatus::POSITIVE); pros::Task::delay(500); purePursuit.setCurrentPathIndex(midNeutralToMidHomeZoneIndex); @@ -125,7 +127,7 @@ int rightStealRight() { purePursuit.setFollowing(true); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -139,7 +141,7 @@ int rightAwpRight() { purePursuit.setFollowing(true); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -152,7 +154,7 @@ int rightAwpRight() { purePursuit.setFollowing(true); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -170,7 +172,7 @@ int leftAwpLeft() { purePursuit.setTurnTarget(0); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -183,7 +185,7 @@ int leftAwpLeft() { purePursuit.setTurnTarget(3.14); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -195,7 +197,7 @@ int leftAwpLeft() { purePursuit.setTurnTarget(M_PI_2); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -213,7 +215,7 @@ int skills() { purePursuit.setTurnTarget(0); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -227,7 +229,7 @@ int skills() { liftButton.setAutonomousAuthority(1500); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -250,7 +252,7 @@ int skills() { liftButton.setAutonomousAuthority(1500); // Wait until done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -273,7 +275,7 @@ int skills() { liftButton.setAutonomousAuthority(1500); // Wait until done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -285,7 +287,7 @@ int skills() { purePursuit.setFollowing(true); // Wait until it is done - while (!purePursuit.isDone(0.5)) { + while (!purePursuit.isDone(2)) { pros::Task::delay(50); } @@ -397,9 +399,9 @@ void initDrivetrain() { printf("Init drivetrain"); // odometry.setUseImu(true); - leftOdomWheel.setRadius(3.25/2); + leftOdomWheel.setRadius(3.25 / 2); leftOdomWheel.setTuningFactor(1); - rightOdomWheel.setRadius(3.25/2); + rightOdomWheel.setRadius(3.25 / 2); rightOdomWheel.setTuningFactor(1); backOdomWheel.setRadius(1.25); backOdomWheel.setTuningFactor(1); @@ -415,6 +417,7 @@ void initDrivetrain() { odometry.setMaxMovement(1); purePursuit.setNormalizeDistance(10); + purePursuit.setSpeed(250); pros::Task purePursuitTask = pros::Task(updateDrivetrain, "Pure Pursuit"); @@ -496,7 +499,7 @@ void initialize() { initSensors(); initMotors(); initDrivetrain(); - autoPaths(purePursuit); + autoPaths(&purePursuit); initController(); initLogger(); // initSelector(); diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index 8ac790ce..51a8269a 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -40,7 +40,7 @@ namespace Pronounce { // Map the magnitude to the distance from the lookahead distance to make sure that the robot's // PID controller behaves the same for different lookahead paths double magnitude = lookaheadVector.getMagnitude(); - double mappedMagnitude = std::clamp(map(magnitude, 0, lookahead, 0, normalizeDistance), 0.0, normalizeDistance); + double mappedMagnitude = clamp(map(magnitude, 0, lookahead, 0, normalizeDistance), 0.0, normalizeDistance); Vector normalizedLookaheadVector = Vector(mappedMagnitude, lookaheadVector.getAngle()); Vector robotRelativeLookaheadVector = lookaheadVector; diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index 077e4c30..c5dbbca3 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -15,28 +15,31 @@ namespace Pronounce { void TankPurePursuit::updateDrivetrain() { + if(!this->isEnabled()) { + return; + } + if (isDone(this->getStopDistance())) { return; } PurePursuitPointData pointData = this->getPointData(); - std::cout << "Curvature pointdata: " << this->getPointData().curvature << std::endl; - pointData.localLookaheadVector.normalize(); + double side = signum_c(pointData.localLookaheadVector.getCartesian().getY()); - double dotProduct = pointData.localLookaheadVector.dot(Vector(1, 0)); + double scalar = pointData.lookaheadVector.getMagnitude() / this->getLookahead(); - double speed = this->getSpeed() * dotProduct; - - bool inverted = signum_c(speed); + double speed = clamp(this->getSpeed() * side * scalar, -this->getSpeed(), this->getSpeed()); + + std::cout << "Curvature: " << pointData.curvature << std::endl; + std::cout << "Speed: " << speed << std::endl; // Drive backwards - if (inverted) { + if (speed < 0) { pointData.curvature = -pointData.curvature; - drivetrain->tankSteerVelocity(-speed * ((2 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2), -speed * ((2 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2)); - } else { - drivetrain->tankSteerVelocity(speed * ((2 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2), speed * ((2 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2)); } + + drivetrain->tankSteerVelocity(speed * ((2.0 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2.0), speed * ((2.0 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2.0)); } void TankPurePursuit::stop() { diff --git a/src/odometry/threeWheelOdom.cpp b/src/odometry/threeWheelOdom.cpp index aee36336..d07af137 100644 --- a/src/odometry/threeWheelOdom.cpp +++ b/src/odometry/threeWheelOdom.cpp @@ -46,10 +46,6 @@ namespace Pronounce { return; } - // Print last position - printf("Left Change: %f, Right change: %f, Back change %f\n", deltaLeft, deltaRight, deltaBack); - printf("Last position: %f, %f, %f\n", lastPosition->getX(), lastPosition->getY(), lastPosition->getTheta()); - // Update the position this->setPosition(lastPosition); } From 853d7655e2da4e8478de0815dcf46664e185d44b Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Wed, 12 Jan 2022 13:42:48 -0700 Subject: [PATCH 18/21] Working now --- include/chassis/abstractTankDrivetrain.hpp | 15 ++++++ pathTest | Bin 173672 -> 191512 bytes pathTest.cpp | 58 +++++++++++++++++++-- src/chassis/abstractTankDrivetrain.cpp | 4 +- src/chassis/simTankDrivetrain.cpp | 5 +- src/main.cpp | 2 - src/motionControl/purePursuit.cpp | 11 +++- src/motionControl/tankPurePursuit.cpp | 8 +-- src/utils/vector.cpp | 4 ++ 9 files changed, 90 insertions(+), 17 deletions(-) diff --git a/include/chassis/abstractTankDrivetrain.hpp b/include/chassis/abstractTankDrivetrain.hpp index b816a0a9..80085e3f 100644 --- a/include/chassis/abstractTankDrivetrain.hpp +++ b/include/chassis/abstractTankDrivetrain.hpp @@ -18,6 +18,21 @@ namespace Pronounce { this->trackWidth = trackWidth; } + void driveCurvature(double speed, double curvature) { + double leftSpeed = speed * (2 - curvature * trackWidth) / 2; + double rightSpeed = speed * (2 + curvature * trackWidth) / 2; + + double maxSpeed = std::max(leftSpeed, rightSpeed); + + if (maxSpeed > speed) { + double multiplier = speed / maxSpeed; + leftSpeed *= multiplier; + rightSpeed *= multiplier; + } + + this->tankSteerVelocity(leftSpeed, rightSpeed); + } + virtual void skidSteerVelocity(double speed, double turn) {} virtual void tankSteerVelocity(double leftSpeed, double rightSpeed) {} diff --git a/pathTest b/pathTest index 8226ddc1e832da8708922cc24b889a32f74b12c6..e1feecc3428a408133189cf7dddda22f96ac62cd 100755 GIT binary patch literal 191512 zcmeFad3+W{@<09r2m}=qlxV!;4JsHs@xTp2^g)S6As7@4R}hp-NDvP+7~=ByY!r1- z)@#xAU_IGGH>)BKf;{n#uB$;&qOLkIxMoq;c=CI{tGj1<=9wo%-Ou-r-%EU%XS%zp zx~jUms=B9V=BlC*r*z54h?sv}BPT^zT7H14Dbx*3A9T@Ikw{@=P^1_B?i5%X&}6{zDLUrY#-nbgKB4fYKJWjn7iJ=nCD{t!;89(~8~>Do zAOE8Nw?OOD{2G0dNB%!Z>ofS9k2e0xm%oun5U)(*1%HQWc=O9X_;2Kgm6Lx;e}m(_0rjYde|dp>;BS>!!kV%=2vkQi5xzC+QegyI(+)%{?n(; zteW3{{-9&}A9K`zxw8fwAuNzD_CfSh&nS&xSQ4z$YLu~{C@izx`PykNdGwoqeQ{^) zyW?N^$C_jNC7KKk_DLB2BfK7BDfh8Nldnb(^@G#Y$Dyn+cuu4I5c=y;7Y6@B8u}-IK6M`a zw+av{POH+SG8a-5}fnSuSepl!rOx|T_^m8cq&&U74f8V1b zOg|T=>Gy^-^w+1U|5KX!8EN#eeH!?i)9}-lhX41|(BCah{W)pqPe?;Qo~C}!G<0rC z)9+}=8#a!KG<4>rso$8U{{A%mc1r_K-;KV39@ zlZM|xcl;9I_cKgbzc=fCrv~~h20Z&M)bi$Nv8y!v`~d$IXx}%I7pZau*w1(Rk?pEV~^K4sR-N_9E6qH^Lz>T+_$^a+BIR=@O_(_yB1M3L#Gztt<)t9Rt4KKz1*hC=7*ztkD<;gD zTrqDNIG8(WPDRB`fKQxTIeF5dhf-I^M9R+{HTsN!1?A6J`t_RX(bqylCVx7$=ac95ij#+;Tuv95oyxGi+edJePRMDQAzIHL@IB zLXZiHH#7!h8+a_5Q{_U(Xi)M@oG`h3!u090CXsdkol?&Y(~R^v5#~0teA0xCYGIDdZm?20*aXJMSDRbE;?uK-9RE2qyL-Z|Aw8U@81 zU9MC<^Ae@-fQE*OhJ?8}6(XMWal}zZ*jZJT<+G-g&w*i9luwya32K)K$WfEfq}j)S zX{lg3GnCcLy?9P#WYVm;kqI#BBOFCeNt4Rw>SR9P{9n(1}QG%DsYST-zrB52BloiPEulvhkfw`iCM z1C@GI&72%Lb?DIYBL@^jP8~7)!nvpuEgo)pZAKcY#rD z8Ikn=bw^t_{IB{W++tiZOy%SMl7lYYK7u~F>p+wNE-%pSN@ly!@o zsLTI&^dc-_x<;b9JiGlCWD;E>BT?o*vu-ubD?JZ|DyS z)Hj{3;G=>1zIq>`Bv9X7_d7mNKS;w*4bX+;KEG?fIFC%YWpx)@MAW)ysbP5CY&AL7ss4vmw zvOs;l-bcyO`I+Izl$UG%sYOmj;};sz)Eha1@J8RPXP$2882tt7joiU{BS)~l&EkhL z82X7<2&wkO;Hcbx4OTt(G|az7t6pyZ`R}a{DEh6bx1 zfye#VXw|cC^RLOOM__XQHCy$Jpyr=r)g$n@|Jtm2vld}vyH$_C=Ka%pCNDdBwUI2V z-fW$+ImfCuw!`{7tKME8=UeqV6Hx!_Yt`qPO8gdB^}AU0gRJ^pt@=W%-mEFv9JT6q zx8O^x`aP`rGOK=1tA4yyzn4`%)vDjes-JDu=Uesjt@?ef`f97*UN0`T>i4(cmss@& zSoO=S`h%?cuY;BCztjk&}NL!Dd^GHTy%hm(u;wO8b2;rx)WlPI@ zTeogqB4sA3TUuUq%S=$Ww5)NGn)ms@5Myrty^x6H(JOUpvH%p`D2 z%f)V)3xq8#6WlTr(=9D$xn(A#TUv&=WhSCqS_ZmhCZJnd_I1llJh!y;cFRmSx3pxq zWhRJEF zl#2u9qCk0YpnP4c zG7^n_Sh+(qKKMQqoUgyzy49HsXRq^_Abw%yb*c;JU(urTi9-cvs6OFBp#@=*piebWK=R}@cOL{^jwxB&4FKVBX z{aFGuBGz?b){=2PIQGVliXB2v$v(WOZQhX}SJd`-_LaS^-6JD1CHtH;q(Dk&D0c8C zb0HeGWS5zSLc|b40L^sB0ziBFd#u@97>zAxipHuMCr9Jm4&=5=G*;9;Fae30Dd0s2 z5RkbU1RJ%?qo+h7Q=-{dCZh3Dpms5!w-Z#rlFl3iCiGU+U@Cqm6*0M?8S(A51l=7F zmYvjWE`Xdcq^jmr8Bv{d-a$A=ug&Nn3p^D!u@H?HWM zhbhraRu~&Pp0<_Uw*gWVub_l%5zsOXy4--CDivdjmc#Ii2wMcKoC^HuUE$KpqQW$V z@8AtM4OT!HpS|7mb=dUTtz3r zH@IxCUIg6Z)@I+BSd_?Kv_If=V|*#mYCg$`PI^tx=O+nkI;fqE=4fo`eEukU3dMtu z+weuzkbE)BxjI@`C%AP*OQNxtY3Sc!T1M-ZN^QJO6joP+DIkrT*cbdrvL1Wj=C2U)1a3UxVpT@mQjpf0_S9|8>Lx4Z)A%TIU9}yw3i0 zk;Gjos4#HkmnQJUq!#3)3#JgKf-F-A#p2jHl3=^)mJ*-uvRb0sRF`zhW9z7mbns=m zjd)=3IauzR?5p2}kpUxf)lTgB@LINJU)`W;Yl-8*{#nD`pkdjXef8}cR?$6NaI&wd zhwZ9)mw}O82~%e~Olb+VuttyMffz{`;%qj>m08B9kE>D!QIA4{6m#L&|GMO}+DC*YdWsIf6){xZgfWBwdg1>Tr;9V}+{rgHLstP zYwhBb&O<2Hs4&vcA{K?iMGUAzc9aO zpm?!W^rXlyBnHHm4nirISH#6*lgxi$-kd{^^{Qod$9SE52V$+KnB0N9&l?mCIw2^HnP`yNJ{BF3Fs||=ndnW&Ub`XM-0GMVSo6;nFrQ${Io$bMJsVGfza7^U6FacTwtt#U-6PVIWZP z5?-AKw9oyAfj{DCy=vd-5^Uka+hZolB7q) zPar$Ij$=nj^*!a%NW`Wua4%ir(tli$&g;nI-U)Eqz~j_aBP z6pVO-p@W%#qoi}WY2%)k;xG?3Y?|xUDNWFj$3T!ElegMHI(zr<7Z8IWREUTLUVL*#d;Jap*-Ir;;PK+7d+d1xDnHK zvfRznVeJ~_Od1dvU;#;Ix!K#r^>5`GAyZ%_?bv5B^raJ;7#LZCHftR+vUP+Bn;M9B zo~$$iK38{idP)O&Y=tScec7EKsptS$Od6|u+iNIqa*}OGLjMY`)7f9S-92m=tXdD~TW{)O51Tmhr!;GgSPmPxZ>gMs@ z@IB8PJjJE-)b~Cs$)uth4PtrL+#T9q_OnfvGHjjv= z(AO>$*ahV6;zTkVFeaSnQB$#6SCm-b5$jsr8ZFPEIJolO6^&_0 zbb|e!LG~jy`^Gy9|Kc(!Y8E?WNzHdtA~S^|0^1N%dKda-u(D}DxS-K|?yM>*y$gkB zHk*s+AiKGcaJb*rS4F8F!^H;4O*D!i+>m_>Hq0yc)jUOI%!C?4oav*WwHGhV7zhw( z7ATs3iF!0kKy%GJA?E=MYNw%#3Zf;5p=(-u>SCepueZ6#i5f9rBx4#hScynMwsKSm zE^}L4hO=~w%XFFPqs)%O0sl%n3EGXXY>ffM=ZwJSbuf3wgw@fPof7Cax}3V)ldqB7 z6;(N!9TmN^{P7->AF-+~cV|C12~7l{@Tggr`(mw7NA${Bod>R*L*GHKDr{cO9U-Qf zR%mqRJbPngtjmol5{5yh3n{Ts@mB6ZcA%lxpe3YdN>j&otSNM*tV$u7^ggIx#=yQ% z5ED0m~f=IyIgJ)a7h@pnE#c+%?7Itd>goE0X-6w{(>_K1`5S-cLkdqE<`HTv%;xD z0WQ@+F4Z4k1BU7{52B>6cU{<*ynfqGUe9T;>cLxC(GurLmxQ_Ja&mzOl}hPPsg%GE z?tD8Jr&7Xzx?EdS3yC3XvbCV578tzm?gG;iJVc6%;Z&PIs-6zw57?o=z}!1q2I%}| z=y@H$cxb@Ig{he9LJABgsmr|!t+ptv$b}Q;+;ZzP`hlLk=arf_&0>OEx5qUiKxC2cHHf z=-jIr5(bjapkZhN{Q(=;-O+Oh3B;@XP^W3AECqFzh8p9C8pYl~>wT$yCK}JIrpHhR zwR#a%4Up{MNdMw%#;8rR1p7U2Q%8xRzL9bafOMwb16?^Mzlrj~b#x3mtBuxtmeZ2N zoj))0<4Io~r>-(?4EspA{oRssYQ}p!iCZjmMC2+P*H+B))_!%l_gyK(yeL-j2APw^ z-&5Fe0SSp>${M0xhGfyqLz7a=J7c_mqj=;!}*dps?Ks4s5T<$k%q zmEMkoLq@SrrUH&)IqCGmoJ8OEC-d@YuSiNr|?y3*bk@KCqW*Ku9{LuyeJ6v_F+rvo7bnA!EHQ6~Bf=$*>+3wYFU0 zj)|o$&ET`Ildz1>o_+?u#-@A9)+kqFnvdHknp&nCosx?|(3x)=QO>JiE<=hZ{tXnp z+U>@TVAPE&<1f!J0z?*Yqt8Z-hROmH{?_V~z1G(ScdY^blK|t4l2nVI*p9TcpD2KQ zOQ-?wW?iO}OZokK#}Fb*&yBxb?pg;B#rU5>hG55FWho^GL|1vqqHKLxlC*(>Ab9|t*>rI zjSya6{hoLEzFhK<0?=m>o#zhNh0=EccJ`qoY5p^Jn3F{-1tnQjuYVIZiIa4HdgmE< z;~lHMmZciaewT{T1&t=jVS-EnqxsioAx2Z7ZVtFc zbE(?fvo!QOO|4T#b3D=gM)NH-tVd`8ZE71v(^K~sFq*}4Ju>TNDgh;hh%KRwP+sbB z8B~R{!zg-_H+#|5fM~ruU@mPbBkE3+t&&>E)Do+BHU(7Ax#OX}P^;LNEGjpAdn2sk z%~v3K&AO?+-J^w@9Whcl&lenCa{__URc`5HIgjluHHEel^7Mt6RN@OaGt;2|qV`qQ zhLfllbsQjGEn0%TJ~xt_sa-Q~v+J%C#5mN+IrZEOnbM#K-5t;t^8F`zH<}AXIWj&FzYM8&Z*wj)4^31F z9K2~Sq>w~G!u%eVhHv8+M+va*mOByKe=HbFa|GhE=bTNjIK4bl_rN`#&IJ?ExSZ>N z4yt___%4kU)~^gK+LYFM!S^AD+|s$BXDAhICsfiyHZ4#MqZ~b>=to;a}B+`!y@;j;>ee#}WOvg08I9 z6X*@mA7q4zM$o6$)XBPVS!6w50AnMMIoXnoJ$Ii847B+4+6TYc+Wxn4%>jP z)q}r%Tun?bBh}E)k zjRhHQ@FNbh5Pu_xX6ozHvAwIC6oy#DG&OUoX=vl*+C3<8hAN6fL+gVmKFPya+LIIG z7Sz>zn^Dv@67 z-C60KXHy3DJ2i1co;ta9<+)N7jXZCoXrU|5kG|F_3XSadNQhv;sGRi>ZVjlQ+~YZ} ze;ZIvueyz62eZZd-a~bKN@~YXe%MJd zX-*s|-c^)o8(YO&hN&48YpMQw&xAqqyk~Z8HKGKbNsyMfI_m|11I|J%oKK{L_w%!B z#|e}=$|+7j@|r=#fMWQoLqbvW3^Xj&A3RT0Dk~mygmRN&s~-K0pbOpJ!D>V$Y@5o{ zSGgtslKNiD@$2-5Ihy!4pPXx&t%wvHm^grtBFSEzI`YsPHLY1_Gy8h-D{f04WI6Vz zP<}=ze(u%$xZ8)-QIF>~fzihlz3L69=C10!ACQ~A2(ah0V89=i9M1#$vtWM|z+M91aNSXp=U zEQNa)alczcX?j(7jy8p8EHEYMs#jnf#=Y_tRPF}a;MxS?j$lDsy+d`ubSJrt5 z6v8`rTe1&p!jL$`ovqt;^x6{g;`-RTXl;6iJ1D7pK6!9T^hHAA%K?h~3)q4PlJBj_ zKkBtvLFgc`@+cXO|FQa;uTY(u!;$gd& zrhy5Vf>h(T*VoOIfJcQ=rpvjsjhLF3dKVY^`35f@B4VQ;8qF#wH1DkW{*%{iNq_ko zO78+cqG>JifS~}lIjNf~yk<)Whx=(gk0m4dYTLwLZqnx-4Lo?1YM;fo(OR{8YJ=Ot zYQpna;uK#)w}4m)Us{Z@f3r`c8UpB)gj&+^Fe-zMNH0tLRkw4&^<+XfgXhT3)n5 zysvX@Ux`|o@1R}I9c0%|$slz+FA74(55+ZpOJq$d+XE|ordBH!YN(w^YWh|pw-OS> zow**2X?mZWOnTfIL6aCq^ib6JcSZ(^`SS3%3w5D^0=>&X59Yxqdvh}Ti(JY^noW<# zAEFE>$28IgG&iGl+ZP*c15l%%SOv8~YZ2!fTp5h*$iLnqyAjskI@}v~(e}k313-=S z8Bn*^D&oIj&8v~TR*(k(G9}EM$!=@b&Gzk1DyOIR8-0cWHzz#G*?m!FEv(zHJ%mP5 z)1HxiGZ(?a%2Nn*i{8$zeG?;`EaC%kk$BPVeEfp|9vRLdgYyl8BOeEGsmxPU7TriY z@grse5fu5T>Lh#k-XRh9Wbksm(IhiO*WBubQNf>FiI@c@=B~oK&Xs-4kL` zQ-fYdB5BQLY@jai?OoHT^km%{1&d-qe1Nz1RIwVq7z3m8kUTV`oWz@ibDtR67XWD2 zHXx+LHa8H;wE-DGA=9Y36PU+*FbNEDgBj#02dRNQaf3H@3<>~BItz8*doQD;ipy$FIdvH-)_gykxg*+`8Xd!Xlun@#1p zR;7^L`X!*PvM)AeV({8z^v9)Zj*&H4K!f^zu_Cv#Yb|JcrkB-TDNh z&(qijjwpv(1OfkkFHGYJ{&^bpy5TSYug*fz*(n5VN1$;LKyHM;V(`ZmLEF5MV3)5` z$;s>|JWDKZbSwLKl?mxs`h;dqM>j51cY#s|$J<)(G+p6NP)_FiZ>X+#a=w%pQu`EY zwWUaBQhC2unTWkABF5G$!8iU*btiDQ2%I@~f2&V<`C8-V9Wf}5YgP(ve>_#8Uue2A zjt6`FH;~h2^1qW;>2dn~KV9~zJEcI!t4u&c{Xp7Ucwk@)!*~OFDLayv$Ef>eFp;`P$jMIM$N*_iT1^k@bOVZ~xK^wM1Bz?XRhHtO)m05Z)QbDFRQVP6ykBwd!ZJ8#Z%{1AYVhNH z>M5t!s(-lpa@TQP_f>6od2NX&c7_m=QeX5}`n%M{W)v=~K9J`sZS@2OB&heI1zehW zvqjPwrZ!*1&CNvURQh`TFF_;|K9EJY$B&--22lFe*mqEaxjqPVjHBNj*Gtg9w}D!D zW^2?7-_r4yPXa+X^mD;(p!H3*>bUWO2U!3}=OQv%vo31wBe)~LUg^Cr-A8Hk%-2%2 zy;Qdy>9r+fM>A+-evWEHu#&n-` zg&E57b{Rn#>rxB*dj@Jfvj4&LHVx%PA}B){2sr|V@`y$5ZV$2tAf1!{1k6-JNh>-u zHDoU@>NAb2r!h^oD(M;0%`17rK+la`zzc^e!O^_<721fLiiF$UEDk$IR{gz3OB2sP z@}*pSVW3jaI39j(s3RwSU z@)tM%*5k*ABX_xq&ROB|uc}RSW zb`xKF*O#E4xYsM(C1JSxSh$NU+!Ij0dPj!XyB=0l#waRhhf&$U7^uhh1)KmBSE8L^PaQ|T87FoEfHSWhRh~$wl+zTw+ zo)&J6#(hxXj^a;HYlm96FIi)Ls>YqAaF>MPe#W@0<-Nhe-CpA!sc^@J;r_+KEwyl8 zK|OVKxWdf|!@b19-Oa+iN#lO|yy)t6{siSc!NPsVvXXN&Zc^bc3&Y)t7-QtU%fj75 z-;aZ^-Zt!#MIWmd#!t? zw%+EoMp9cBc&+b4)PO|gUhBHl)*)W&eW|Vcd##I8TQj}Z3sYM^X7p9s7?IlgoYy)a zwe>--H7B*T&THMWB1PU=UhC_rt!H_ykEgaC>9sCHtMiZhA%lA4h+5?xY;(Jb-(I$( zDfY;cwT)Pk!VgE{nZFywC-M(rN|RZUl)#9!6!HaM zxV!Utu%PPI`O4ar$c6Mq`G!|<89%y@;4YO0yzEX=j@m|2LI^hJ=Q5f-LdXF7^mEg~ z+Gel~7OI{V77U_9+rJ$lb!~(I)&ozg$^5{21qxP#TXiGTiDR%R@du<7&)uj9E-_H% zB*U^t$jZ`23Q||cW=NP%w$-7v<5x+$)YR3gzGW|PIfVnCmTPtKy z{6>fJAGBEL#^!Ys2AI6gQoK%0!|P^H>4?|surfq@DzEqN=i{}|&+BtS*5&mK&Fk6W zydJ4}JwfrhXq}Lz+&)_=+y<}j%Mvt%*Ke^}cZUE^q>D_hUib3zdN+~`103(QQg~U) zL87&pGb3N`Ns6W`nv^!#e;tDLWahc&;nubp^Q1HM?|cxv0W>&!U=uIm678&cLaLNu z?0*k@I?K-A@5PmD5q|aux&XveFyb76Y7XkewICDEJ&!+iwK<|FK6q&DRz3<-)@@)^ zCQZ#VIr@;o%7X>50EjgEuDL8OB^{usS~19OrwSb9dzxD`1n$;f(&NmV(K!~!wGM6e&3a zyIPSdQGKW>BRp5`Bz>4kl$2$JP!A(BA7o6u_!M=E?vIMPPwN_)j{H(*JC+o22tGZnrrHVW6D>pQmnnet$P{ zm&&jhn-WPA1ALP9;XOG6kaV6oTv}J^F`k5Ne-7VptOGb~^`cRi!C|_2OD~ru46RO} zfb}dqpJ(sFic-`!N4oH&{wm!oC=?HiAHWDM|Z{!Ml&BGQ zGg^wcOWA|soWI;BB4u*Uz00G6{$yBXh;C8x7-RhH4l;LoU5HsOJL>9Io$`}D#Pb!R zVdW-`IM70Dw(P6+0LTTFkJNBI4V>KgaYy-l4K_@Jy^lKtA@_jxfQVYVBziS%!!xY8 zR?)}v189KJ+%X>V!^G}TCZ^-Ijs>EX3l0Urcr)&7D!NZt}5^@tmh%aMX4n z45?S25gCzs2R8P*ufF~~`;dgQv*LTD9>3Z9E2WIyo_wX4{8_qr>vpbqh7C&n+I{TO zxcCC0DctuM=)x23UBJaRJ|eq=NL)IU8{_u)zXM!3 z5}~sqQR`E%NvqRS-uI387uq3fxkrLRjS$ahDUi)^*Tyenu!nBP_Y58N^K^4hH0$o{ zQQwFV96IVe|7Ee~0M1gec!5!O7$0%`?LtM2#^_Om?1i+{qB7w^2X~J|pn@Z6clN`~-i-c$ii68O|g$p!0jR8@V^F8_B1SjOTue-XR0KF(c`^ zk!#=fvGBw?pT7S{Tc|twg?j!B{t|clof7gKdqz!Y^`ym1w@MYy{{up2P+1sZre(LI zbLTc7IoIG1#zS~1F#1$+C`T8k$=;OC_>)e(n#(3B*zkrhw^9T5l`}Z9V&af|k9+Z0 zZpMpw9%~2r;6(PK{kmeApNBv0qFB$Ur1L0OuXS#cJ4liU*T1Ynz-qasOBmujKjKyu z+NfQ!v51Jpp@@V1i0l1`rxUSHDB=NF*tC3|5ynhUHvKKM>3u|-7K~ho?9$gAp-m3~ z%Q~vyDr7kp0j)DUH5z%Z*+&M{c)d$dY&|6vYyw8dnxG{F+s6Yl=zm6lvU{JcwYndB z_ntp+-TMy+7inbt08KWEVfeUXfKnSO`%&!OlF@LrjHF6EZVjnx_x8ztIf|_VQo$Ucd@GWng!owR2{K!0e1E91)P3x1$P$1733}> zC%O0GYsPRAaa6$tOl1kgn?T&ULH9IK)m>RQhOO2?74wc8-0DxQ#dG`ACpTV@py*RB zJn{Yazj9AyRLI*A`TnB;MeW(QCbAz-)F!f*Cakxb@!Uf2SWG_V9EtNjnCK;2Dsb}( z$6y+;W|U*)4qD~TU%w!Do&ql=IB!+(O~G>X!IAApy4r-3wV&5Xn^oTi4~zR~MGelI zOJ%(zuUz5X(4uzl_NHbV_kr<_1l;y!4=LZ((cH)242(DcPC9rrjNzi!&3}P?K?qz| zP%Iwa!Kn=MIN}xXBnD5^kfjMFfFy*z!lWUgVv7)O;{^yE2|_?|09xEY2L6Z<=e@3W z@1Sg^Gyk^=$|qzA#s(-=2?$wFW>P)^8|;sqH`sqBW5Xm1QNj)4b%4j$Z<4wOi$_{3pdeesGfi-f8vUF&n&jE=i2cq9 zLTJ3gEZZK#FoR!G$`Ne72MTk9e9vS;2QFlE)wR@LXVoJnbN<dgprq|qD(3T;x%erbL<46-wZ;NUV!(MJ}(SX855*(J}OL~ zl|kr9L1@z3R-gZcZ}rLfp;TCMenRi7<%|UT{45AfdVxMu#%MeyouN2gU5kpbPIv2f z$F+}+XKnwltTbT9g;{iJG+0gyG3Ydws9r9nHwUwEEP*(FyYmH883Inh1n*yhUs-*L4lwEG=hj5CCue0!8n!S};&@SpOgi(Xp z516fYx%q|iVbugs@%+QzF!Dq*Tr~IO^$HoH!h9GZckH+L3q5N$o*a}d*@&XpX90q7}N zdjCK42Tm5yz^TN|-pd9?6*4j7TFyuSZf1;b2lpXBx5z zT!RvxHCET?CFz`{uEAc?DZ+J)h@H{$J)9NDA!HI?$X&e~c~sBR(Kt0P>f;19E180; z`ket^1R5(ze*&&s22tZm_NS?5HoQ+DS5-<{4FYHZS?vP>IUMbegRFc2j$Luq=;!>5 zj&P{2c)88k-Cv0k0G)Kom~UvtMyP9aoOB9t-EtFp4a}>)7R;XNdI{lkaBZdK9O$I; zEfNL$Xuk9~5&E+sR}!+AN>$VKnBUmD-j$;O-z9@v1^pH$Z0!yBPBbR6+?*${mS;&lel>?Miuv=v zsB`nRB0+;bhvf3fb%ig3@Vs$0SPJpR@S9aDDbb36(*XP8Q(r)~W6o(K4bRDZV1@XM zqK3JCbla`Y>-nJYsgb}eXSpitw$*UwD_^-#x7DhlW-Y7sk^U?d{ z#`nww-yCuxJ%nlVgj>tW=NFFOI5EQQ5GLIHzZOyu&b4&L!M^l=u~kfZ5eJ*`!#LQ4 zUt9B%UevOcPGY_aT6jzgL8nrOy<14XF8ADfNY4#>cO9<6-UjKtR&|57u^}r+*77tn ztOOBD&NWMHGkx?)iEXcRHIUfWs~g-E9dY+4;>@^)k_mV5rHYdIMBjfI$N1hLyj|j~ zEDXqU30?6a(DYe(D6dqW+d{5+#`?tH<3aoc;4vv({6>`VD4Klm4kH5cVrt!)XJfC# z1V>f7r>f0YwIC(1Z;2mMpZ)PpeP5g_;L{a&B6{cZY|!m3DfgTfOL<4gN?*x&sY z-WZv#^7wN!UPtqb)-9z>w)0!`jqXUlO-Si)m{>lP5ZC41c(}rqEr_7{m{*AS6EkZN%EboIsRg z)J1qxn}K+=fM2ulVw?Be1oz6~c{B%X;QCXt2jzX8;G|M z*XFs0RQ|19nM(Ld%qIDIH9~P05NIQTIsW>SvrNOqfd=?Yg)uwO5H$_60u3cTou^&( z16?#3+<7wfK@FSwXh8F(zQn2z=$l(U2+m54BfzfQ4%+0brN^O0<7JdzMr5ehe2;3D z>XR)YF#;#2zBATX2e$kyPP|%fv2pgwyMa8d_$-Nh_XP@isA`UtZj2Xgl*ON7?XO&Z zVAXdM1Mt2`ioiI{=@iH|IzJlIy9}p*!jPQSBPdb46a-9Me2Dmri&a3>v9WtJHX5=c zw8c*0P&g~Gp^!BxS;Lwf@zp7V4qk#Y5){-jt`B`JH&$W4 zf0p{eU)_d$fJvt_?n*Rr9U)&Vm1r=C6GksRuU7D%x$ylBJcvCB$F+pQdwapDD~X#K zF;ueL`zj>MBS=8K$kmlQ=t1t@h6ftGjrNW_P|%#TdxUeMEyD%ns11tlEVXvSUweeW zX$c32ev9j}V&A$dPQDym@Z&y*7bWKP=QS8TUp-k&@rs&Ak-nB! z@_`IpWd7g4t@oM)bde>Eu!|;EQyiujJV?6rRgSuEH8AfA-#5L?4k9(=z@d91-C+x< zVlj|rh*Sg%d@~62($l8|5EPG9lQNhoEYwwco0nD5^!N%(zaF;Gl%U@btTenUiE{it z%-3Ve3YxE)bYt~@xHY7SSk-T#+7~ZUsldCrR37FuCKb%uQ#rk3e7O@Mnk=yDOdn|d zRZ8nD)m6|3W1R9jAr(5!e!RLFu13EB3`QIgR`e^fs&_%THc>g4m3YZ&P5ai$fi^%n z0r1wP_}P8wlaFhhw-cK|^*uwivWGac)=XLBz{~F@1dJu;NC|fPTI+uL()ki+_Y6?n z0?6=bHE3NyEz2s@)#Il;SxPNy(e6bVuSxKBq+LH}G7W`~VUbCEx=0$_G0&1%qR19- z0RLUBS+7YTdf`l#S4KF(d!|hp*8`C8*bq@DNf^He?>00U+wFy;=-pl%;wn5c4s#@?^HVCiCYLa3}A$zi(g@q1)r}j5u zrJIEhs3Bgo*?qn4gVaNe7HTw8_o))uT91PcdRovFt9spDd@C2+6fb=}#t%poHNm80 z2|RA8Spr{pi4em|G+HJQ0F>@Rk_l+|Ea-+=3kPNh5)uxQ@RDcoQf%>Zth%k)#QP@hSsA?0?8A9v z$Md_XmP^^&v@{fhju z%zBpXg{N^)L_sftg5QwL(3mS#M8?`<3%LVeLgEELtEnT!$taG9wM1iYjfj0jtXyCrQh>tA@@DrYFWVp5dLrdl9{~UZ zIOW%!{D}ST50Oo)X5b00H508);T*BROD@ zk^S%Eo~b+$)S9Wqf00y-0T68>ucL+CD4nnxS)$4w&{UGuT3~Qj2rgY68j{YyZX|`p zD~oSwDtQ=EvkhVlxE}7;UV#r8ZLBokSSg4kq9+tJWG`xln{sdp5Z{T+Uc|WX4Ez|I zcznmJByS0JeYfj$8(4gj*^&CD%5Siu24pa6LmXFzdZJ2K8^rA5r(uS2A9<%}zgMHN z=c8-B>BgBLb=yT_TeMJT%3VefNKz7I^vS|3>pDkY3wPc8-0kIY_bWw6pf+-6nIDPN zoXuw2aYc>#7W69Bk$~2?1f{sAjwx|@XA?BAfl4SNeoQU-Sia9dap5H+jbA`WD$>YC zb}XWHQVmhwlvGHVhEN^xQG=vo&HLS=8MG>JQ0n+4-`klwv34Vn}T+M;3H!1YXcaDQp-X!O3D|F zi07Mbr*Lz9O>?*5bvtkYo)DE7<2{Bd)NEhicG)l@K0Zsq%BECeM4VGX*p|I|kQMjaSl6(h0WtE)wPp;9>30Ul$6Dx{-#k`!Fe13 zmEb(q`8BePcsDsX4Re#E7%62P6FzZPPwXj5YzwB1k4(4YR9aeaCUx*#9=!|G&^zBp zFI97p>?}degSwk3=*d!)4ZEcY=${|pHa<$ivIGGpWVCGrZutp?3G>@JQ2d+ss`Pai z^yrHPcGLhzyt|gR-Q*8;yih}qP(>R8hccO0(!uB+3pWPx9knLHKvy*f#%+DkSJ-k? zs<~Beuqks=!+4t#17_sU{y)CZpZ)86DlEEXhG{7^x_v7>`J&rN(2Ez{f;nOV4?e}n zY)H&LSDy{zfPV_hwqkawji{83Qza*AN6DdX4`}m6$rBWLqA*J4g9+%?j*>kD*Nu{= zN-+>68&DZCyK-DB1oO-Cy-|G#*JPC(S>f&_MJPdY;}g7gME`+p;SoL86<07H5&E!bUqt_i_*O(8BuKP-2pf#( z6WJ&&OlVRgdZ-$1mSd45hppIPM9)kY(Ib>IHKP9xLRb;~3|B62ZrZs^r6=%9Ypl~HMw9!-_=lZBf6!Z zEYbYWi|DN~+R6p{ea;7Lk%V1*4&zzC=R7L7uFv^QiUFT98v>;GoDRHqSNe$h2Om)X zqS=o=V?{y}$5Op{|NY6V&ztl4(e&QDS`Zk_@J0b#cjV{p>!>}%&!x%`>iEhn7S>|_ z#fllh*fW!$P)um-nPkx!10QG8`H7nDe9Y?Oa^?hL)((m-RHw6_CY;>0GQ!=2RKR|2 zMP<-_%sQ^GS;yHaMqsz$<%5*wWcNTa#p$fk4&ZgJ%YwTN4--J|Hf-W*ll~26^5DVl zOpbcH4TGh2ouT*!kbS!izec+RiC8Cg8)nPm7ETe*KTS;8ZJ6V=-hx)=wF%&!FMv_+ zXHUD^utn=2)Oz+5{?tV1jSg(W1APso1hD0XYy3P$S;_Cm?8Fs z@<)kph4O=?+ccqkPa{$2;=HqZk*5w-Lg2-A1S+i7vG*N3YBj2+hP zyKxn+Cs`BEv!+J*8AutdD8I;`8C?W9ttdYQ&nl{rE4tZwfF0%Ifc2vMODMJcPU#ia zz#xZ(cD~`}G;#yKYqK62@&7_iYZ2BU&E9sz|BUx21Ehn||6xOw3$OGVL?bjAmInmm z$c>7iM7{fP-BHx5@2LH!N4<+J7WzB>Xw|t@<5W_B<|H2x*E3Dgbb_nKKaKUR8ap4= z-nY8&XGL$hT}f2qTHW!l#Hd#*sxADC;~a=;uK^|))y&>R$eLL?k#9|lxQqFs0XSZ7 z-#XJ-e;&F4FP;ZBt2!@#qWpbP4Tf=CNIlvEoiPa)y5|es(q<)-R4qhR%D0%$evu*p z3t!}hh9v}fy`U4^16hDw^}v1&HwmE`ZngNfZZ1*cAeQ*o{GXre8@&$cVlYw(@12J5 ztwPwuqEtQUk-#je!uAq)jj7L$fk7ScWZ~M3w?SCywr&Hf+nv5_)B$i{w&lA+K^tP0 zbSSn(ussh^aA#>jd!&+Qx6nPF6hZ_vHm?j411MZv!4@Hafy0(S+W4(P{6=hR!@stv z!(#^nQ=GxGtd=x!%0_IXWdl0zv}#h+qXfeX zoTB)f*ALU0}wU);|?0Ux8s=juBdBQ&cx# zSK$8IoAdCte*~lm)&24(Wgs!er)tqL{Xs*ZaGIq9Fl2Q7#Chiq0r_mhEpzi?FGTL(PMSmXKc?Sr{bS_ry zN#_vR+vm+%aDXrK_CWXX0`$zT8uW(!DXMoo+fh`XV=&d@`!447f(c|k*My8hZT0V< zF}R?@NeDn$JZM1SL_M=u ztF#S`pPdsu6x$NKy~2lS6v)>q*mFRjeWd|;ZcA=mC6wkl2+%x#pn2R$#f5h$FnbY> zUPM~r_(S8OuK!kwj%yawN2>M*s2)E*6)}lRA(EWg0a?5?ovZ#Bg`g3D9TDOI)*6$E z!}X}@LUiYB9qq0PoVB>tZg?>+owdS)@0-x#+u+4?Htx;g;B2f}&=#rG#~gT61G7=} zy5->DOw2cK%bq`KL!Nf#Xe)0eBFerfl@AuZ2`b!)7tvea2oL>2?oo2)4gzo!W-g48 zcW#RlAdQK|q(~GyND^TBQB*^Hvm2|yWb3cY$bCOjY7{LVrB!nC znQ-R@u&dzKI;GUE3VORMMGvwz^20(a1}^D*9h^E6#_k^uNe6 zB?S5RHum+8O4{D{2b`6Q^pRqq_uj1BM(^PPun3r`qxn;P{$ZeIN61e4>w|Gn-SyW$ z$d1A`{qzh^Yet%u)$J`_fC?Na%^;nJR`Rks3v=xF@AfC_*5LbqE_{x8Mtm0#< z=q=dcFpcR9!`dd`udfpVbajo;Bj%#Gy49@h*k2F#ydkuoqoM1W>frjP`s*Gg=(rR9 z`Z*Ys=dYjpl3ED*>u*?VOvdxqOWqmG3Pm zl1IS`>xy2{j`?piin`KQP-T4eMyVnM&JTPb%0v7^>ZDxx$82WN!+2e)_`Dw8i^6BS zWak6DC!M3EC|fE0A-O`rTMsuPYX#R{)JA@I*BLQ&k zF{rnx9C;#Mc_ES2Sy9}X92r~pc8=`p*|%8u6U4Ri_^>fAfciVX#+s`X2&3|^v91T> z{!^9d=@w?e`vn(oyQd+1j1aahN|}&b6U;!uL(E3ZKP$upk^E8dUjW{g+VW*On1!9B zD@iAO5wbc!PIaDo4uLxHogHw1C{_|s_I@LL*$>7)kV1tnYBry4V+HSlb}~w4Txdnf z3(4QMS2YW<8ypfP_vDDDu4;y>>ShSujAl$|wW^uvTh-uxAk&Y)s%ESmB{!mAN6C8s zs^(%bxPm~?>Y{p=D4CBAR?szE>Bl@)FzH&roV%)NP|B$HqU5Q5v`A=&-)S^1qudUA z`7zgv9RxdkMq@gk13C~T<;~J`F}^7IefX*-6JREg;=N|*N75E(KSy8MQBvQ0|52-& z_oDQd_Npd@iX`8sLL@Ir_HdVGGyT9{G>35nJB|jZbFWbcN`!g<` zPlX46lr)}`p$u?a_Wd74JTJ-y9ZlNxQLXCRb!&9h-h#`mwmCL&T~s$efUlhlXao<= zXp47rl>7q`pvh_TVL%LzP{QkWqoxA z-q!^-o4|e}#vSa7Ioya@?hM4(Qbh>o&X-_akNXq6Onss*A1tPNU*A^ZOdflY+{qv2 zR)7glFO;`0iBZc~Pl7j^Y0{aPPuJ$&&>ktpz;daCmD^Y@`NPt0fMJEDw7p;F@BON< z-mmCH@8OYjB``e|NEDQu&N5LdSgcp=Ut+MKlknJh3#eH#L7_xW9i5ceSWf{$MyPv{ zJwnXNIujckhuK&^F*bfU(Ta`7lfP}p#;FbD?1Cu zMw~b07QB6TEXFLeIa;?v7op@G3AO{}D}g{cyeoTgmy@Tk)0E}pn~FmTlzECccJcj~ zI|wF_eSz{0jp+r-rY^n?|4D$94qpxH@J>JGZGsu>kT%9l!ucpQP>vGsbB&J7tZPIF4+Abbr+ z>&4P4az|_M?GRq<@tm+?>5iy&-Z|OxsdwR8`_w78bnX&n!egnm{uza}Q^@*fFssEf z&HAU@UH=qzwEn?D9m^Y^A~PDS)g))TaY%GI`A`9zix-Ve9Q&~=SdT)d|AF%hR4j{)j>~txvFl4;F!&xr=3B^$&>w^^|WVnS;gv37+&_fn8p%c|N zdu9?5>haCg6a5nCF$i0Or=An`vINfML2wtCyJ_!vzRt(#IN$U=tq!Ftty&r{wS zi7D^h^Xz%7I1>a<-LSW0Q+W5J^|O-s~yD4pR^`l&-br|8y- z(%DO%$#B=?J4!LICf}ZwKWa^WDln`ePuu%&fA7bK^?qz8dJnhTi-75$MZP@vYBc+N zim|2t2YGO=>N_=!b#rR!ED8&)hlOtA9?-XZD8qjbD4$A`yF^LnvNy#X>tT*7&5D`L z{(C@qQl;(z<;(69jRL(Vo!(NEdq5W}x{a*f{94F8pgWEdL$<$WZ`K~(?1O0eQcLe0 z<8|i#$eFRbzvRm`Z511n86OO)tJt;8&dY*9f+>f4jYNilGT^^R{JAsZrj*=@Ef1oX_Mk!->i zs)+}KL;CIQ$-nV7;=s})yf`oh*E$aDjZ0^Y@DR*ymG6>#$9Fe#dl}>4TY%C*zas;r zHujHuPtqUP3Hfp=UmwTGdZe^nz1gtcy>~8$1W@FF>tl-472t5F%ZonlT$eb-p#p^O z{TV7bb(j-y$9R3w)(ntr60M1IP`lcASAj(}J-;6U(CR-d{xs2rJt(;$9UZz|znXXI zo$}vtG!O#2M&l#1^y~h3n%K_Ljd#XmtV)36`cxl;COq%yzFk3zt5$(_zqNd`0uNUl z_l&$+zH$eY>IuH}aJ1{QR5uV-cFP6zYAIr)zYfOay~u4GJAnQ(APuBdqq zUwtL$e7iPl=Iv-|zTX8F+zlmQ*)N&NbT$kCw*Njp<;}w|Ix<4qT_@iqw|PPW%-2g1 zXUrfUj_lx|ZQyBad%Wb1PcBelJun@$f?7?M)JwU1!(8C@%)1G(;znEBayE`P^k^@OAs{myq%rc^j_91f8iAgbuP6z=W@YD*=mpM zXQAjlyzvKV4|gM<9%QN~(Kgb^97X0ArrY|}xZ{E|#y7GqU?b7^P_R8RkFS)C#?HzM z#v9rUMi0^jBy@Gq*@$$jytsxFsey*p^J#EHkDVqW&A^*N4eUGqi1c!JM0x>HG&LgK zl@gJ9lM!D;+KL5tctkq2FSzJLMEVO9Y(=Ddr07MYOwjPXAH??5p%Ljuvh+WSNR`}A z2t=fr2m2-pM;XTJImlGYvSO6?mO6=1r^$XrNQ_#*hEB(*T0mR2t-Y0rEu9EiQxyT% zGVSRP=@8+t-FPU{jy3H#?}Dl7e-`IptPzy!1EjnV0dq&vzfo)v0&p6EXK_5Q;BuOx z%nqW>ck*JOb)XK)N#{irt+==fMK9X?M;h(8*heXtum16dt^@aRP^yak!`=a>Cj-}t zi$}6+FM=O{qQ_}pX|&_w>8uHf;01QFkR~o32;5HiymqF6p3lpp&)fbw)`j^z_`Cl* zU-z;*jNsnut>g6eSgXrZ&*PAIy}Mdw z)nnJnOHA>`G`>{ycQ@m+5PQ-45ia&F>;4Fc5iyAl>-H71N`0Hb|17ikqPH0knKExa zg%10r&n$K(Lt45A3G2g8$7~V5z1??elBTn8-#$vM>LOskO&#o`JSw~K*oyS_ zQ7)vC{QD^9u*$!WGK^i(E7|)fXYS^6vq~oj=i55HJ}8V>7ay_Im8IUZDEb#wMiXdu z_ry=XnstHvJ(#zX;vfvXs0VxE4Jx{0g7G7h-rn5PJIWh`j#E`h=Kw0h3kO}LD0dt8 z;iVuZod#gxte2D1x)OBx{T%xN;lS9p1A^ zA=^G8$f03aPREH#IfWK({fWxwyM)*ldO>e7%(d`a>IFdtEFsm5+l2**CED!K#d@}@(S{8<&nnaT0a)p* zH`U1;AGB2eOibfsP7A}@hLgFHQiM2}>vsAHPUcKupu@QSZ){6rm~9xpY}(7Pf6E-) zFrjB1y>QTp^ zEHCo`VE;E><~2WiKhw+9qipo!(>I&^ zHk4+5oEnC;jrnmI2PI^F%*_4?^W$`3z_xwcy2K5Z9NM}0!T!VMhcQ%N8kI#M;A3~< zFNP&gTvjR{dQATOn(|p)gx$_2Mko29jbXVdNs(iPv9K5!GKMKjhrZHDD(5B|LCA-& zH|g^*niFe{(%Inh8H~~nE~V6;7hH~#q9nW}ywt(vYdr(&$vb*Sin`-kA1QjF7cPHHwtNpeMnA%rJIrSMIxBQ8M6rdw&@c2;z1WEe zU115G&uc_fEp$4*wRgUn(19G#=f3Z1p{o3Iyr2_F;t3$^a}4$b3r`ZmHY4n;@%Hp2 z{r>!Y0NVciSlL!hI@fA{{#(nRe+Ah8jX(d$&z_lfa9P%L3nZX0z%*IoyD9$scuK*6 zRgNRXpZn*nj^8hD7np@UkM3KmpSRiX$}ADodJW^oEb`}Mm(N2>mb>I!$aBp}QsksF zRL;ufp{Hh0yK!Nc+@gRDs3{lTv5X!P;6>N)fb zAxn85V}TEJ?b_R~TYa7+xbUpU%8CDaU@bxS1na=(=*68t?aIut4ilHPhSiWeuzfx* ziviL0%t5=rFyh?>#OAXewclIGijz6rn-A>aq#9*P9|&4h8?%km0%tCPC9g08u+o^?F43%`pTY(ZNB;3oug~ zxX8nM3~OdIWwbsH67|9HdboRVyy#z{*3^?mvv0U2 z#VOK_i9!EY8d$`+p*3&-BWPzd@L;BGYN7LR*h8RY0=}My?K4@ot$CO-_(A%ZPDy8! z-{lmAxE#NYGDE{qs85|>LdojdvapnHF{Z!}EDtQmi&##%1a`fHtdBhH5GHHbk*AJ) z(6@X1C?AA)?D?RL5<63T&|rQ0K45Gcx(01JU*u^6K5y^OUFKi2Pqio<-+N$mgs#s`f7>23L-4(54d(9v+})7hv=zSk@$N>8&@ z2=GuEG4gOQD980pf`V-yfs>7=*JgWYyDKy}6#u5?-d*g;2tPqCF-NMF4-TvJgLafO@_Gxrm?t z^D}JzgA+_9`zvw^3d&NRIw8f*`sH<|PBR!}Q??bNzWqKY5HgB`kpmDOWJ$- zeZr1FQ#+vc{aZMP1BISZ%Ql?D-gpV0KN7X!7HW`{>iiN51ksLCjw)1;rD6A zXdxObNdwL#%_+G`pL&A!E(7)%8StK)XqIAUW-upx`Wb8uL0Ggl$BXhXIB<11UL+Z9 z(wT$))zKnU>!U^IPO*;`orJt7c(mvYK&EBZf<229x{`;Byc|sqSdFSk=Y;gJMdm9h{8;1A=}bLr_W&_d zQuotg=SbZ%@U?GDES02JbtMlF#_3Bu=df9uHzzg#+A2-dhC$is5c4 zlN>GD_h>UNO*y+z3SDR(YJ4F zzk1sl*M8*FSeV`wd;dJv!OFV^9=;Cj4CPBK@-}2d9p&8jqOd-7oF}_sN@06^8dOK? z^PN>kiBU%|Y$|Q!E6qvl^X9x8GVRrMXcQkH%=`DvUOzWP8=Y7LhiXT@VvwSpx78cC zM1Or{m&rDk7hdkHb{auPj3rz6vQQzx&1VAf(>U8 zcW!>0z(n?$U}xs2P#n!AjHq4DEt#X;LD-swp}Y+9^K$f$;N@p>*9@Mw#oaD`?t1)q z?!-g5o{=i(i|GQTxtn#8ls>=nOdv1wEdpo?^jH2Xxe_$ zJ;!GHo07fHB4|~;xpc@mBkBgf@Y_ga$mrp*H-?lBk9|30)R5SBrO~?n>rg#%M8EH$ zjx6U_pCE*+`MzuAJ_Fy*-lv-Q>VwL|VjmCL+GkU=W^G3FxOb{Pfq7<~H;(J?A?FV% zUpr;W0K31nx?j>HB+I}2`$Yr4Xy6wO{Gx$hH1LZCe$l`$8uIO? z$e%uI)<-+s6&wbr9 zXO44ld!Fxq&-c7u`kDEBu5;bLuKVYl8FE7|t;xVUik&aamO58Bxf)%7{-i@!B zP9e-YQkYW`oL#5xoKRa{UZy?Nme$O!4)WT*=9HHPYwFHBFK|hquB3Wqd7!kSy!7hx z{DDBVKlR#*%F+sdWxfCOxwFsoUwDB(SW#Jj&V}`rbIViDbjg;}Q+Y{MRZVH2vbw&! zE*Me!>?+iCV+3g(xG3_yHQ&5XIVZR1r{2fp==aIsCT{<9nCAbj@0&j(N9;CfJW1>i zyr}QHFlT^$ePGfNeX?MJV3xMKyCmnIUvpIt&Y59fqeRcw@B3XT@3RFb369EnyIEcR zw4eH1&Ceeu_Z5r(OSN6q6v@|#l1_%aAFTC)G4lQr?Z-bs?l02z9VX`7e;?O%mrMF% z1^Wy36&$VaJARtBzwa69VQ#L~_hA0mA%%4{L_L9=F|eql`szXghJW?5D}#BKWjXZ> zmxdgvPpF(VuB>KOd9dy}b+5V{_h-8`m!2`0`&AZl>ni8qqolGr&v}2w0CcD3x<4~> z*z|gCD-F7xC_|6Sk-v;=bH6K*n3Lnq-@&iH+|R(V^W)aGM1H!d=dRYaEHDi$0H^M5 zZ99m~$j@5a_VB(D%w^NO9xMavC1iPJVS*tjt9SUv+yYU0kd%z;_W=>=0 zfxEy}U@O>{Ulm`&$#X8afOGyba6OpDPuFh)3&38a2wc*&t(pR zC1AH+_y?DPo%rBx12`1i0WJU!f$xJUe#`n6oY&j3#`AG#6L<%>3ETwk20Q%J+Gh2! ztnT1`um$XP8b4`!nDT)QeCS>Vt_Bx?V|n;t71)&rOE!ZuthTm2;2bc%uVvi|_66@z zJov2QPq(Ze6%VHJG}j%|))oX0fy==cc%o|)xF2jhoAUB4hxK3& zzP_*xJe<_lb{JgRo&2V8AGiRVbRy}1uYsGv3scB9=;v|4#B(gG7)%3i2MfUcU@dr8 z&$hOuV0o{$w%y>Zz1!Ln`dik=r?s_Zfj6Dr)>aHY0?r4|>DSiQ1YUIp`2;(pav%5@ zXq{_WXP?>D<_GtJIpE~8s4uXBZ{jq9ozvRd)`9ncTfw`|X=^(KzR;ih(k<(mb2-ui zt-<6E+&7AH^JfJI=eM;T1Pj43`qd0@0eBs_3cL^8488!y^RslbM^iuGlrgj$*b0_` z-S|6)3&26(DsU{g8LS2OfE&Pgek9Z?;C?U&=7KF?894P4?gv+atH5W$&EQUO4|oua zryqA8%l+VRa5Me17Tg1_2jl6dyTDv<^Em1s+ykx$`DkHi1E~!}5}^FxVz3NcSWJ9?tHHJ47O)v?0dwi6ZD1LgSweZhNqn-u3akS+gN5pAYX%8@8A^mR}mB<*XkTy}*fW#*;F+kQU@bTmTnEkr zw}H#Sec(p0J5SZ`1P6hK!G)lI0ObO6z~mtH2o`|z!KL6TFmpEJCO8dj0dD{kvMlRe zFb&)V7Jy%aRbaw(^e6CPaD&pp9bgY02|5Ih1XBhQ?_f5#1)K^dUr)MVKG+2A1vi5o ze!+MSjs?37vaCg57I+_61g-{yVDe3r7aR(11gC;K!52Vluw|WkGvx(0g1KPgEwq#3 z!3E#~a4onKYzDIy(C*+!Ffp6?7EA-zfCXUEFBu=fGH@}t5L^e|4{ilN1P_3nZ*6N! z9zy$p>0t70^kXm;YyeBZW#HrB25>vL1H5h#`96=wCcwVn4`41h>ep>;72rH@A$SM4 z8f*r)fSc|hUGQ@-`FzGhFdgi6XIon#I1;P{F9R2Y72rBBb1~_H3&BI+S}k{oqYt4!8^~244c_gGu)iC*UA(6ZjF>0`^-*d|t$Q155)~fd$|}uogV? zKFSTA53U0nz^&jG@Br8fCgjN+cYz2$KvftC*;6`vY*liW< z4fX?Dz$?In5%do*72FNxgGmn&FQ6Y>2sVJL!L8sH(DyL+gFV57T+7M>Q^6%*KKLeB z0aiaky@Ahy>%dN{nJ2+)@F2JlOv$6af!W|La1xmODCGwI;4*MBxB;vJcYuS|(B30y zZ_p3k3g&=wA0u6GHMkJm1+E6OA1B}7WUvLi156mjcnzk4ot~h*!5_g|@WOTE8=MWU z1K$C+g8lwTzQIDUTR!V@Fbn(*SOh)-2Eh}aB;Vjg;0Ewga0mDzco;kg_8d*W`V;vE zCxXS`9pHR$1K0!(UQe8Y3&7prGSC{sdJFV}UxPVd%AdI(oC_`hmxHUo#-}JZxD{*x zJ3dXhFJ@f{rh;`~KKLeB1s((&!MF{KYv3TT8N44n06qpL7f=o`9X#h5$_-u)2Ej^j zDfl6{0Ze?Ba)UF#!{9=&=Ox6`bL1O*2P^}98_72~4O|7*f}6oDU<>#ym@w9|VxA}8 z-~ccmoCa2a+rXvZ_uzVP?+c_0X1+-O02hKi$B}PvD44Q|`2#!)oCn?vHi2uwP2fl1 zZZQ5O>bsDA9q0#FfH~lcU@>?QoDZJ*GWUZQft$b}xEuTejK7riKiC&cdWG>AoCj8b z4}%NA4d809-)8C?oC@v-uLcvxlP;JBZU+lM>s8tdyb){!o58iJaz7nm}Ma=y#`U@dfTwQdelQn21lEBmlPM3F4Xy+yfjhtk z@G!Ux?D8J>gImDeVEp^U-4x535B3Fr2j+q=gJs|k-~w>W2lN+kCAb+}5AFfK0OPM< z{SEd7r)=YX@Mf?KTnjD$zXDf*$$#N~un^n>2Eq8LjH_T@@BuIv`~s{16Sfn#U>&#` z+yHI?{T~vy;Dun~mG}YEz+1rru+I+S7F-B6f~WnJxCO5Pw}Q8T2f)o>@-)^DU^@6C zSO|9ci18Vm1ug{}!S&$x;5KmR$HX1D3QP%5Utl(P2%H3V+DW~G>%e8|{U_8rSPSk@ zJa`D)2Bs8KUN9RRzKi?8CU73u=~LE?;AC(kxCz`1?gFh6%Q}8H;{|v+m;>g5#o*)M zeDFVD6PWoK;{{j;?gsAxt?A5PpdWl5%mMp3* z9^4M@0Pp+<`7S3;K|i<&%mH_R#o*W$;tlNh1^EX1fz9BB;C^sDm^_1a-A8?cjo>73 z71#g{|C0Iwi@;6b3~)Et09rFG>jTgaTKh>C>cx;5KkE*#8^q8!Q03UCnw9oCLNJ<`=lrpBvvDYTdw=U{& z-dO|s_JOti(v7X%TUy)f8x_f=(hKr$2YkA^UoMqaBmeefwzYLvTwYT0t+69IcesQM z@mA?;`S%g}@nA?F6V{ud-$wU4^~=Nhe$iDKLib-0))OiB6v{i&ssAFZr=dTI|EHaL z?Blk9%3lHc=mBkQe~-|2hV&}*q%7hnLVqBnH=-{=_bfm9LiFCw`zM9-*Nnah{Y0le zHmvVQzZugIP^ZpycdK&uLcJu=DZRqvR`(v-N9jN-LLQfs&tv902 zYe!#;z7^dof6eHJ(7oz!Kl<0`UiFt4XITf(z3MLwy#>9GvwV*FD?s0eezsGe9SeR)W4M)$wj+SU@Ge;U&Fqqm^1iO_!+ z(i7vEM~MGVBJ^z`Jq5cx3xy~ukv}2e@a*1ors^y zX2q08<+EdaD4%8cDc<4jXDH*+ChBE2@fknL<)Y1{q*c;S<{C^_oM26DEjITqnAtRQ_%~!KU%!2 zd}J{mE#&?cDj$DfvuNs1m1nWehq9ZBT`P7htF8FOE<4Bk*i3qv9`&s9vmd>ga;Nb+ zlvZiDyotoy4)jG%J@zKsK;55)KAiG+jSmIr?~~895%>Q-bbl54H1hXRg#KPgZ$wY| ztE@LnUChw=v)iBeXd?Y5;;9Faq2q`=_Fxb%FPMIuE@MdbIh}kI&`kebLLE{#6}0 z)^wY&xsW_~)xmD`G3c32A9_l)=N#);`WJe>Q@=4>MnC!jbXqAKZ?SoyGUlK^iS89k z#ptgMZEL$b;{HXU`{$#dM;X1=EKTU??bP8W^wf6r-RS;ybSsfQ=b`(_vmZSfJz`C# z+MqmKN4eM(V{?MDj0Iu641FTHR~Z+e7qpXyRp`~kX~5}U<>AtB8e6bggU$I)o4T;x zg8mx1R~#gCX6!@HbKXBMe19r>D|)oC+|NDv=uNcq66gIYj|;*+s<26-oCBRURa#f$ zLN4QyiuWIQ9UnI)9B<0c7hyl^@pBM6ubA6*6#Za3y2?j0`RGGg-&6UxV{~LbUJ2({ zjib%jZC7@`aM&>($G#f2>&ZAXmp<~Wva4{|sdB9im#Z;}^WKl5kN;}CS&QBi{UKh5 z#{O8x`WJmA`YRFovvvaN{{849KW=TC!2BP&KW}fmlGpi`-?{OyV1R3bS?VB==~z{e@ZC-&FE{1i<8J}sC{T!!W7S^lKb4cH79B4!z)J|Nl6`f*)%jeiXG^5WW z{amL`jLjhncKf3@wUfWZ<8=8>ao%4P&VL%Z8p|(o>dHCqmHz_tz39>Ux6-T7t4RNB z=lzcTVIz72dbIof+_M(_4)pfM;;q>1!sf5eG-9{fnN)pyHRIqiVpOd`;`cGyIoD7p z>opYBWTkW^R(Yn4p~AlG_=md(u0S#7zSt4AZ@c{HJt@Ce`>MZD)wLbH5j_Fjt9{p^ zA3DD+>KN@OOU>xR$zO>xe`<`Gpxa2<9KdEiHbrh5M;vuKo^xDmyy74W{VDQsmD5M8 z-UzCCC_=Y9%Bk8Qjd7?N|Lb@iKZj^Fbvddr?w0u2CY4)dSA^a7*xjn^DjjyJOby{O zZ6>`Uo-=$6yO1wsvq9UaJhfo+JvLr_Goc%M9m?cY_v&xyjYoggnMUkJI|1cCA6>PL z*ZmdfE$BJU`yFG)LUh&k8BV<-od4D6JchhIr1H2Qo7LEi za@sh~x72f;ThY~iEL4xNzX_Ew4Sg)*)149etsz}K2l@hff2ZzPCsm<0qkE0djp(nT z=R5CrtVP$Ne~lh(y{zJ80Uh@M`pL`>@uOL_N5oa!v1+1F^>7eBd)WVY%|qSjz&qQ~ zv(UG-vwu>5Ik!DMcoco9=+W9*l~awQlRj;2JFLnX9Of?PepAk!_(>z?GoAG*Yk%cu zJ$^1k|6KXG+~J456SvKtR_%Vc6T3q^x4Vq}bNpC`o!WQ)s$;nQsn80(vRdj)FIG>W zs@|*63#hjqPTjGFZA2f5e!5eiYP+}Rm$m3s_>Wiz$La$g<-ZwyE&43y{jquiw&NfD zNAzg>Jyjo@85_rcNqxjp&UnWRib$z5NKa6SLVY5x;_a|m$6YmAL$2G>^;){DRoaYw&seKHs z7q*izRF!=bzJBpdYg=#S>lKGDdrXcyPI*#ks&RA<&s1Ng?Ed7i8!c&$&}k}L^>itSPzW2$WyGANw%Lu*?)>nk|RP=|?Z-}^mc1X`hkNdH; z?YRj3Nn7{BRiLjxuXpOIJ!O1UZIH{j^c6N;RDIoZVK|?vKgQ^~QohvlvfF<0jty1b z9oSrUxV7yzUWdyw-_DOpYaMB+XUTu!b^OT4v|_)q&FsFv1G~F;#{3+Wr;JFuxL)Bg z!eXqshiA}je<_i6PJgM`Rq~AbC^eSEMcTy;(PN2oW z-ETgb=Zwzt-Z$(){}p<){;1O0NLowLd#N(M=19xLbmws0x2SwEkLRm;d(vU+n5WeD z4c20FCN`nEFV=Oc+9t?FMH7Y zp?mE+;!owg6TO%7e)$~154V%CQ|XuTI{xLM;WT3NLuJUvM=>@5rw_;6RDs@v?$zcC z(O0A6J?!7n=EaO(o6+sK8}7)1#GRkpn(@(s%?hUvS6m#xX8JJix=5xHs?ojbLXD$J zx9j4C^TT;{)P;JE{sC;F#hz+U^?dyz4_&qKQuMj#M~lsk*j44WU*6r=?8PSAStt64 zSD%0SIoCpuR_`jWe)JxB-u0D(-VdE*!gb+@ofO6%rB6qWUvgg9CRTrN%I%i=zET-B zcH7oDY#d|CY77@*6RjM|#}@u;LicKWHO{RfogO1)oJ(?~6J?y+ifz&;$(9jKJLNh zGG2$u8LJ0%rEfrQM)#T%cA#%X_bS67^q0{uaQYAGx>o*EaQrFyAg8WB%D2ajZ1nHY zqs6w$lNv|&pdXB-j33~|(N=ML!|U?-7_S@Wy%%jlUyV*whJDnA^SKHACG<<2dTef} zEq9}TjUH{@L9#ZG&+pNH&+GUJk@=LZzvV|uWm9%dp(}P(+zk)sr2v};vGHp6D)c`b z#m8c7KE%c=w$`EVNB3&it?0YZqqVCluNp@WqucFr3#oXtO9~s2Efc(-mB~hb6WuEx zlh8M!M;migd^L!k$?H%a9G}ZALw|?+qs5mU|LD(qq_4`km@#i1`kTCte9L-};9y>ieS(a&<~CE=JTM!yH$tDfeIf3LBs34IgydyQ3_ z&=0lae>eI*bgy`_m>Ap8qs6SMXFq!9%e?cSBlky(H+6q8dQa~68uRC)7odBMGfn8z z(WAwIYLf=WvGM43Jby|wdBk%Ieomd_9ghiTYTYXyQ_<78KUzLiIrGu|=w9Pg1^N(l zj$p!hbUd54Q2Ya7-LYp{E%$qkb6e17;GgCW-!FSARZnUhtwy)Uxlc2~HmX19BTlsCgqwhtJ77wbvlNq13qxX$t{JAqdqQ2w0tCgGn%xFG- z-k<6{{xqQ{Tp4}uuHtSJdUtfMadx-pUU6-uF}HDlv~t+}A3X)#E3R|UGts@;p%}d{ zdbC(j{^uX%{wBHKs~tC?568dP__7<~NUmQTsMUR#b z)gH+tJqX>a-=(8pj1GkB!tohLA;J{&%bdDn-CB#j7@cf{?{|Dgycm52x>x?z$^D+? zN8iHzUi0MvbZfeI`I67&yLaeb<8(TDBD&W&T`2co;w+zIJz9%Cocr0mgv&4caTN#o zj7w9{?Q!}~1g|6Boa6Kc{A|ar!09Jee-`V9+kqZi>WW9#IDHtK{@AE038f=#seJTg z*cy5iA34}mVB-}p#ppMndyP-?MbC8R!Lbf(LSM}NU7Wh(v)WDQ^U=M=r`_oHp+}1+ zRo@#J9~;r%yEv1G7V9Q?$w^@=r^EK zg7E#a-t|KjqAx@r@6=V?=`ESPmkMI@6gCIkHlK&r&C9U4xq|PExop(q7OET@&>u!0 z?9{8n_wPV|9(}S?k1ezf{BVcRzekT4CsaNi-zVugfae!0qnB0XVJLbQI z%~8_mi_LS`M2iVOY2>1-->VqU>rl)&+Fa$M0-IKBy!!D%^smvQjf?93)#x3r@-F8V z^knoKoq32=(W2K`E$B7qUgL5Cgd{0I-DM{6fP zX)Z)xhd$kzzN$mV^G9p3`Pw57%11N$0rd9zmHJJKjaPg3t7Hb2-RNHZDjod?^l1G` zm9r2%y~;bLYtj3lx7Y8MVlxq&XmzF1SdU(e?iEYh(8r-i>zAsY)-nc8M=#@b`~w`A zn6cP#{+2=oti;AE9vEIM2odc=I8;?D8;QD1DPV-qd*m5*HXGIX!FQ#KXYq*uGvg(@BWF_^vgY*guB zLzcsB;uzD{qF;yZ6?@I-PojIZ$$s=z=#!lORURDuT>WOs4s5*IME#b^=jdLsSBU-| zdbHS6v0ID&HxK`80jzvA4x-QIb$lF$8zwg8Gm6;K@Eo@hU)eR@?Xna7Jan&iQTb87 z_0pl%dmZUV&qTjW*_yn#+D-jFOc^#_?N)|#;e_0(D$Hw?K=|A=QkqSxjz;CFgim^xE>tm;rZxYuhC;lsGc0-Nd@{u^k{uZ z)xkpa%h4I0!~PwgDXd1XLiZ})7W6so_-{eK*2BM_BsWp8Msz#w?u9XJ9jh~;@|ZT% zvOdAaYfLOa--_?I3D=|JGuI&c&FEfjxfHz--D@qg9{o%7Xlof-&f12aQt!PU zQ#OaN8Hvq2UWeLR^=rp?+w(&9;@D7KVH^2Oz9-aB^k>mI>I&T?^>|AiiH53KUH6TMf^yPXfCXQ4C7hV$=u-o58VjIZd? z&Q$I4qhEyX)u*ST=d`2GLm!6j6^F~wC!!B`=Fjo{tBvRl=n>;$Z1{7`o#^Y(qxBV) z|HJ4j+eyD?j%7WK-rbqL<%H zj@~|g^o{7<(dY5nD~5MtQ;p3~r;Q_qEfQaZ?iIs+^u_32F`9$E0^KV{i_zDkd&TH{ z^xf!QG0=qmJ-SznZbJVN-77|SqsPqgj!}!?ifu>tqsO6ptfg?tX5za&R ziqZM#b?9C(+Js)#PWqeBuS55W(cS1Z=w2~ujo>>k=$`G5z7E~9{n1}Q_iTUkZRnou zk8WM-UB6A}-O*2T)~{oX+JxQ%-Lw7Cd!u{CKL;!qqI;GfJr~`x{OIG+Pj%++vhWyR zj9!TD)xPu5hogJNR}=aqbkFjmPeqTmCh1F_mNCYSLw|`@lG}`J)xS>SD<_K zwf*SZ(Y@LtaU^Hw?WCWE{t3EQUn@ZW0NtyvRiP(c=N+q!=-tu1=8LuHesqSkaQPkc zMKk&^bgx+1kDiO3gj$*7qS8)@nU&m+tY3LQ`UiGJb|8ENV3C{avAMJ;$ zLLY}d)~TyF%n8S#`pv-Wu<7Nrk>}}D8>`aqHRVx_C!7qK3;LzhUEt zI)L7SKGUh|Ge!Gb)yjwZUBa}v-hEpAUg25jUU8~^$1n%otDe;F8)l+E;LJnp61x&q z`b*ItN1qX)>xHG#*P|cwxZjVy4ZY_2_Uri&HuquUmB*CPmi24&9Q=i1!4WIj=xfov zVr3Hgx_10Gpsz&tij`&P_o7d8r7zoN`@Cc$Ht%8M6)QW@x1v`%eK=y}FnW)9-m%hi z4DE>CUaY9!j$D9^=lG9)GrCu-%tv2_?$r)W=!?)Fjwr)}p;+03p8N~%vxVL0W6-@~ z$-0>J9eR$_zoVV~=1G zGaLOHUdLa~$$~jwG3R=L@EoudU(aIeRafiLpF#I3%Qp0n(7noX5PcVVw7mMsUpFSG z56~y_I+RZ}PwB_~?Xf2tn-256>tho7A$+WN`j7>eYOe9H*|@QNCBJ>TUz$*Kc) z!|5nH$ND(6kk2!2_AYBa`gQ1DWvM`KK=;b)LiAen_VQZBIQB9&c3#i-&g(XOO}NE7 zF9*@bqkHA0+ojAI=sfEb_&R5ScV6bBr=ds7i)x=qj9Y!tALMoX zjjnX=438OG@N++QUa{DM-q?tW)h`tfsYfM^={zr7xtwVi5#i(QL+>Fh~*m&h}KYI6Hdgn2bja46XuRNxq_e1x} zV*&cf=gNc%hA2^xD~w#-7Aj=(0_y8-niDSh~I<7rmM5A z<+%hkc4nbJgMNWir!CYGx6+Hyx3_bD5PggLe#dtYmZJaNtvmd$M~}VLJAd2I54My3 zLG-BEvzhbQ@mC#4KeN*U1u#(w?ib)^=*!^ZjbRj5o3KK+%XsWf{L;Y63+Dvvc~Dx7uA99 z#Q0khRGJ?oSi9nU-*&L>iTC}gqxDX_Z+S=SR-f;W9j&K*zJGPJ-uC%E?r8nZ=X#~-cgXe~?7$(+~&%=FzBV_o2@CHuTsX-s<}<@ic0l{z)hrDzZ!}#u!Z_=V7~e;+*2A&t^&ew>|BSW1h|{JgSNqn-SvU9|h_jxL z@g0b@w#N8AjTE6Sn7c5^`le%#e|5GVO1L|g zHw(IGf60@<&*J_Rv(jfh=M(M^F-&kR@xFU~{4A#Cx{dQa7iX38W=UL^zs6bH;#f#g znm(DojG@tEeDB6thhlv9##^_?`o4;@9*y(e9B;M6u{y@;gzLER!5Cjlto0ZT8Ef4n z`As<;A=md@j5UQ9#OPmRtZgycb(iy0+cfxIjiFsMb!?gMmRRf8G53(Bs>&lRZi?x- z6!GI2-)}ov_Y$I=RElhu2=q?YeQ~~jce4Hx=eze<>r0h|2jYEyKGym$-uJ<=*4;ke zH^*A<`h0gLTEFh#do0mQ_NPs^~N#2U!G$9aExz3FYAs@Yhw1FYQ21{ujv%)=|tai zr&u2)Ho)xd?ECr@>$}dr?Wb6eCY=P+nC!dtRO`;;e2<-KZ9dKiv!<($zbd!4t9t$V z@pmfU`@8jcx|g;11mACaSxw!2@AtA^>7EMzU3cHUUe*UGzMK8l_LF>%`mJB}xCs9J z-jsuy?v@A6@O=+=piN)KZU^TZ&MQ^@aRIIlF2C8rFSifq zd9Gj3dGCMo+CM`3H}zod$r0YXFP8VFyoR6evTJg@kHyI3Q@vJ~DNn50fH>D%XxaK`Q@IZ`Hd zn`)K!gTTIqvY=luT`)(mP_S6AR&c)HV!?Hy-zv1+68 z$@cfz-6_Ob$602abZT)HCz(0A{UiC~ty~$$Bl&KYe{wYY6RZs!0=cg^e*Ddh$4)KI zI?*!Ya3r5%&6n{xl0V6cHa^5zJwoGYq&=g*#C0U!)5?j;pW-yLU#rr@Ti>*~1vL-F zayqxQZ=|AzNyS^P^-XW#-RmCpoq!lVF)Vyf*PE%mkv4y1{mc?SWzXomHMs9 z80*M5+;fd8*OC2NXYa^<^fG?>P!I2`isiD;(!mpAH9zHPo3`xFxOq81_~fmcSKpIW z*DB%b2HFJ)tvB`vKUp;p*I62@5saHE-KTnJdlhHux*5K=m0~qXzw_IyUI!`rGFfkT z5&mWIGn(2^*JRFM~gh{=P~2mszK+6#H9MhvhQu z^}O&q|Dt*OGbdhlVj-yNA@_RC@00al7x>;NW_|D1vNZr+<#SJyCd!4sRQ#BIj{4nm zbzLufrWB||)7CvUFK-<1hWLNs-%4eS;nlSM^3|{3Y@u5imdfQ%ZcEEjN zzh2@nL$nu#-;o+)Gkt|ue^WuFn~<#ulkR!&D&5DsX#0L*KU?^D$7z1J@P8NnptP^? zpT)vo`8nv<_9p%x68?ezXa}af{wn;w=QS_cvQA{fp!^(A10&ZkEn8K>&yo7E|E2-j zL&7&cq7A!?{aeE4oS^+2FMJ$BlF5TmHk=8s(%pEjwl{G;OZd4m{#+_IHQ9cWtyIbQ z3gKT9`~9mlVd}Xf8#Cp9-nW|XE%sLkf8`UJ$Q1q>c-3A9CGgESvq@dwgEB0q&p!~e^Ql$M|!Z&4U z|I@|31wL9mx56J6d$Q$stv5Q+UsbwSNdQVSTN$TmUi}`Cy3W;LorAr~&&p>sVd{Cj z@RL5!ys6J+@P4`13G2oFHHkN=ZcB|H%Ksekf41C|d7S3&mwGdCTMw_sv07QT#Ebnr zv7hycCQO~Ezq_EyyF@zHD`LM-?CYdIn*B!xH>&&;CF**nTI?$*{HVkFy(#ZY!uOZB zHTjRFBOo1d9Sg7g_xn&wG?RT*319WNesAjeUfWNyb%Rvc9I;<7{K`~KNU^Q=#7_^k z5aKf9jE@bzN_Sf~&6~W95kB^I?MI4XT@A15?Ms=D8nkTPF7{T7CMF60obZd9G-2}p zweXEEYToqUO!g%YrQcZ1=EcX5rwg1xXnz%st>xF;vOHC9A|BUd{U(@uFRllx~e$Di1Umu8n_xQZu_9I3PP`{V1%DZlWCQTgnf>-&8P1gAtB=_6~ zuhyUD9Fk(%*OOvj^s0Vu`t`TMPwK4wOcMKwlePap_Sd|Lw}*xIFVTiHpMAXsuhQM^ zTKDc2`&en;fY>MX)a5FcjF^7W4_=jP-7;JFw zT&YVnVf>GVXXrlSx>4*~c52D^`IBwmlfO5v+r`Ay^YAL4yYjR>*|4u&!hchx-`^no zL3ov);sM&v1;URdV~QUXqj}RVcL~4Z58Cifv42_k89lZA4B@-_wV#Dj&y~U#2%p$p z+Yc4~*TQdX(}d~o$M)8Kw*6l7KZt#?@U1eQnELrd_~DX4hAI0xBz)OZ`n|F5*GK!e zq+Bb+evDKFiq^w75?RCG;yi$mGGwRgtDPt z>_QlRIhu z%iW^KPddX{hBcSVh4P*diY%Io25QY zeD*(6`=7d2`(Zk>ugipg@HCyDnZmDvSM44z^^+(3cCml;Ol?0=_><1k_K%ioqIayu zi-hkZ1DI*wDZ*bUj!hgcfLHa9FXPWV@!yMiNb#r3deV$bv*1-e&F82&Vt=>I%NqyW z@4-JM{0f@~?}E46>))C%{p(BHj~F>1HeK7N$#`PQHAMLRGB2Ch zSR}l=yidTZakWX-naK${k&R+s{G@(w|BVM;?iYU13z|3emXe|KGhWtL3@`RILHI@) z-xyi!OZ|SJDsP`}_4_HpZxepw6Pl3axD}tN?c-#8o-FpGguhD;W^#o8GrX#2^Lco( z@E?i&dE$7a@P5|EDnBnbX@cq4zJ|khmDf%fZ}Uf4b4&U;L(K&3W=m@G3vODm1Uo<<<4A*gqxX;i;Oo)DyZY-3@Y%G+X#4;pd#L9pnhF zey~9Kcc0Jn8La&zy887{;nV-29hiD(z^$4$56SvL+*>zeul#qH^?-@z2W{S1h4E#v z-#<)q(*3L*lJ3%zbpBc1*q1t|^UG@|42D=yLz!d72engWy5J=zqC=aX52no_~xfI zACQ}-2;cOoCZ-GDDE#ZE=yK%<|1aT_zSP9;g`a(%uAf6PkgO5@et1+1_pUgzB#!vG(rfjFJ zOn8;g=55;0#6!98JJ)GGU;Nx9e&)$IY}U8;i2dA;wV|n>gHl`@Z;e)ojfZ+cUg%P)T37W?iJKf{F|L_bk+yGk0IY1h6c!>jzfAoJ!V z;kS#u`}3WDiT%bew4t$2zexL;F6-5K;^%qc`+TK|OyOg5w0*b7HDT)E9O3_SNb?Lw z_O&`k+aHj2G4b%G@RM4!o#_i*hH3k6WgjZt)w)FZ4`hE-pl`Dtf>-r(hw!cyMs|=s1d6s|n^@Q-1QV%Boe-r-iXKVXY#r{mjBUKN7xkeK*oLOVxRe9(9 zP4f)z_O(#>(fjm!Qx6-2@8H+|O*JN@o={AYg#qmTZ6S- zc=zXh-w6NXXWGz|_Y@Wks$A~*A{$=iC;JC&KVJMV6n^mrO_+Q>C;ZkQHBT|^D{GYU zf8;e1UirW3JFS_xZ4~}}N!Rcjg|A4`^=9~g34c(=PnNItl|#mq|02mJ!;XEa-@s7( zX4&tUdiw%i)q{I~+I_UP?uohE+N?@TB^<7NEpEBx*7%1@dskXf$S*TcdmpP}Ek z2;VHc`}6C63;#a#s;<9ku=c_pl%79n-X}U}Mr(4-qf$*=%KE=ez zUBch;y|y#;|AO$3{YUfF8m!nt?cY2HeUb1(g#T39k!;&njqsE1)bC9{T?DW4@9q~b z3O`)xVXgStC4R=sddcMH>PxjB_j%nj@TwjjdRsf7S?%k9@XyME$czK$F)%87_vgPg z!uz-A`zMK?74Ygg3iG^kPvKvH?<%jI5H~^lcdrxjg^!Va;x%&9FN806UK1;XSKm)o z`CM^_CRPdmweVw_G-2X=P?5I(+^5G|Q~$RKZ@sSVsb2f~SornQUM7CNgIDV}^W1l` z*q?Bj_W!liPnqx&gnzzK6Mo^ZgpXD~H;8@nXWH-_u~*;IRps6Ii6%@w4+`HV>jC3) z@I-CD^Kot8L;RG$t9WxiuQE^UFP4RXStq<<+sn-kI4Jf_+cjzOb0!0w%IC#DX@0WY z6NFdk9+GjpPWU^-{sjr}KEgjE_LtUb;x^&8z^n6i_xb9(;%D!Px_wPObRtkyey(cL z4op1c3SS}n_Y=f_z3}IYAHvDL_6dKX%nQbTI0aPxZ=SquKjwQF zDPsQ7c$KdC{>D{eUjuK-E|d+w68je=KKqOKobVgg zXu`z#ZsFH`rTI6-KKlxt?lO5E#-w$F@aB6RUBrHs@b1sSzlT@lb&qc+Ox6CU%lU&T z@3q3apM(0N@cGiO2T8i$3Ge)r&xo-ZhC%yEp~EWsglzr3m+*t&Rk>1R-)F{++r>VOd01VU8mzTq zKlf`*nDTxHuf~C5`5sXZu|J-PMy2ciyle=(N_YD{Z7A8Yt{1-F2a*2Y5&j%G2R7-R zP_F&_wnf{UevuEa(tR^m^Clju#s1lyk@lYozw39J@2g}x&!*k0gnvrTG5U)AbHbnerY1u97v6n- zGWcrkzwk+IZ|dhxc$1d6w&4M>@9`JS8k;YKckiQ5s?z=wWL`G;tQG!i@nh=qM|d^< z1YP^4xLMjyw)6`V553`4oVQAx=SXHR7W==u_T4WEe`tv|JWK5Nil2{UJ!8g`Bmzm* z|DWaD)s*)#;WK0(ahmv9E&M_`x9@NK!>fF%^K5mk&|oFjX#QsALv?)~tMMXuJFcX> zy)|tu5&LP zSNZ=-u_m@jJ`akY-+ZrmifLaNY!Fnsdt_WCyzOhQ@I_K@Il_Mgulz5T`GR4`zV?ZI z=XdpcQ=dh3+W+;^k1i4W+u)U-doI+33{TdxVt;b0=1u+lNB9M@&ocaUDpuux$`WmV zw)mef{1_Q0?-u?(;otmP6Xx@s?!oB!83nKW&y#V|w975R?|oSNF>$_8c=x*N)Y;lk zj_fzPN`4j#-y#F{slvZ5{IBI4X`1k{bF?4#b1#G7)q2=`UpHCoi{MRKLfKF&e%#M> ztP%dfue7zfx7GHOZ0)^R^9ADUv}<*K#`f0Zs)^6J!Z$vy4abT7N_gW_C>tKL`6Hi; z{ziEBdOo>9r~8x)0F%U7wea_Spb3-KE5f_a34eq)HqQK5*J=Om=gEtNe?`udO*}6Y z-u*n-Tf#5+i}r5v88cV=e^dI`36l7D;ZKzPRGRR&3GY6q{WH93_olaW{ilfihho3_ z4NaKwJnnj(?#@G+H{;bb;k(N^*3`)oc=K9Z+pt#b`$>G7eD1UDk9@xF*m*kLQ)Pc) z#`84cJInd)6iMVJ;WxRS!}$li8aI|-p$(Z1?CXqQX#b10==TGKUnBfy;>YkU@XAkB zo;H+e$vWl+&AZnj=fbOTpx<%2o=v?i7k>V$+K(9rp7G$fi~so-X#0H0=eJ^ivz!~y z-Rx_`jXK?5%eZRte~0j?@;#IqvEMKJLFtdC-G|TDe%#-ixCLI-gZuf7)nf1d{BE0V zZyj-c34h!XET0MAq|;sVf)-i!+gFM3=64TFxt0lECg-}Riv1Sh-RrTKo3;O3=`W_d z=L*078|`3__zA+>=K!+)H~#Mt`@+|?p^5oV;8p#sl?r}H{2Uhh6{|HN&2RZ{(fN7p zJIx<2_H%@H&*P85EC16j)rOzPX#7a*&yw$(nDO?Q1=@dePi^>s_`e2T`EfsgyIAb| z9Ix$7J;eMndb<7LRh+xe_ihqCTlRyd|2`^wOMmVELCH^>_;;UEoph`Azet`BIYI0% zhBtLClnv!#U-h0UtSdZr4l$rV*d}ZcdyTVi?kp2bCu)aRsF2X(+Fbz5Da8%Z2|y=C9Ml z{tv=Wl73ep{Bd{a{J5Vh$P)g|a&357tj6*1DxY`AIAij26TBM7=F2!{>hl4ypCJ3V zX_D>^;Xji6n0%gjr}qB|iisGtZ8LSM3`-Ka!s#y!*LU^*NSW zFPY!f$(DR>7XPPh*F=Be+r-b-0h&mO7k!D&k9%KmmGC{@(RRNVKf8oKEc3OA&!Kl~ zKhs~=hBL%I2(R*KewV;6{5@jd<8w`93cpYI;(eMpQ+V}!kBT4n=kiwwZ+<7}B(c9& z_(e^cF!lVV@aIT8n0V{-8|{Dm8`|FV-#p=aKB0LTUad0tu9}MYf411a(-P_D3ETe2 z_1-_le#!mX{uA+b+C4fy*)p!0es{C*yZ36tLb3lq_$^ZZW*msWSNmD{h&D9kJr_P& z{>O@aUW^{!OuMWU{vsI<&3fZA+s~2TJL|Db$FuuF;NV{ky`?k#)so!spzl{ZEy+8Y27>;m?tM>+!;WFZ`X-zGhyyi}q0c(fwS( z8hDle_z$#$-s0y!!f%lEo~heQS=cE1F)wMue6gP={G2~(LZ(COQQ^OraoEg{7cAF) z?v;L*BYxHh?{Ct?S;DsnzrMF_#~k6uvanI*N)uwc@OQ(jd_F1pSt0xm;S(f2nf~nS z7z~vCVX4n*;fsWK@5`PLe)ukJ*hTD5{H^wLvg@4rO5vxypbgI!`?bP9FXNJl|C5`v zpM3hax=eo`)uj2CWxgJ0tNeC46Nf*__jGO%`!tz%Ogla;{5=v^hClXq+Q0jIXH($q zaZmQMeo41l?3diB2^0Uf8D83bnAm?RynEl_U#Zjm_HAuw`b81E$(y*aVYvtYlKA=l zaczCN-1Mbwe`K7bGZFa3#tCEKRXhxn^I=oZzk*la<2JvOWbRoi_N$~{8+&V&_OnR( zmx+^s!WVq5Js7@0_-kdnGV%X}@b2@dy~3A$q5WJg89MzTo$ihenjl>5>l)#Ab&9dy z4;B88@TwoV&qa5L{g@_gXyVZSu(o$UCo>XW)mzu^wEZOU|Df>C9Mr^Q;Xe~TP1?)& z@6GtG@^j5q+VBFMU27n`^1rQ%Ci;t?>uq~^!=07`&{Qd--@6A)N9A1I%7K3mXM|rU{H?Cf(?1sen*V6Sv&4SbV>(^;=X5jRmH)%? zJ2o@L{t@Am4oCVqD7^c;r7!(N`RVqPwjV5hDus9N%kC0B^WTyFUlQKEk3Jy$aq|7O z_2PfV6FS{TWgj3dS1^vM%kZxY zpDO2{hVR6@uIk}Z>Az-|7PBkid!^ZE50 z;nn=Cu6hmD3gKtU=Y3;^zntXM=VHb0>2wo>|3K{5Kc$Hr;WPiN(_Jm|V}Id;@X^}$ z*JAJfJ(HJ&ch9r&q^JD2&rdSpRe4(^-3uh$U)uKa#sQ1PkNY`?C&bTKzb-G+oPE77 zyn8*+@oAkO_w%B?;8lLc%0Au1L#5b%Bm?fu%Wrx$BOmKpZ-JF)*< z#*=K}KNEhgjFV-;_j^|R-y(5n(wz*i{JWpuxKZrg&*wiU_ODiI$Nj|rYhwSt)Pou4 z|0(wK&(wy}&8*{|Q*ll$=IC}0%`fn(9*W-9_9u$};qWS-L$A<8K=_-){v4Sv%sBRl z@b2%Aydiv{WMqo?N!_T^-7BA`4-`HKuhM-_5;W=lM(q1aeVTkeC-ylLw1Z_b&we5H zV;L{ib%qA(q~~?I=gWDriMMI+DqZ*Q%=|*^H!Ri;%y@FI@b1qGb_zfK3vEx0+gAqb z4^_|SzpLLD3a|EEihp08zwImhM&Xypxh`R5UuVCl?cMvexx&}VJZStpC42$%r@DG+ zuv&z_YNsYb`ProXx61s|TkLNUzJYb0y1Hwyp4g=AZ;;RFO#FWfujo)P|gX&2LfQ(n>OPM5ef{qbVq|0?-0?fwM3O4t4Q-CM%DzhAIV{0x=x+4#xZ ztkZRW9y$YF`FDRV`75z^|L)e?!n=Qm&G)MI|DbCe9wEH@cdHh_t90Gt{NuvAzvuNA z;Y)|=3LY-?{58DVznk9!PZmDmHJzVt4r{{HL%r}7OEo_`PUCubl^^%_dG`umGfUes z9NAa=>(Y*(x@Kswh6*41l_pGonJoMrvR|7d_MZqp_FtMfApA+pTPmJUmHt&Ae4+5} z?_2#5Ugh8Yyu@~~KS!RonJj+t-q8N*BtA_(t>rk7L&%7Qg@^?{Pv4OVH*tlFybV0l^p?DRqD(TxH#Dyu64 zC3STr*9FR}gLT(gGwMoal?TdZ&zf}|w>aJfunb0+)|Lb-ipuMQ{Yz_Wt-zEC!Geq- zwUyQevU`epD)XrUHNmb=s-qlnG zN~+6nt23b9r&m^5fl&qHh7T*?mf6z-qXYG&b>-#N6msPFVVC3u^2X){0=$bTW?3Xb zT6Gja{EQnpazb8FplI0ef;{fboji8fC8I}h$EdNF1@iL6Z+`B0Rpbf5j6vbD1nWvF zgY}~)l#Cubq_D20x@LBDY5BlHDkzwjmp3F-ccUj{1jg_Wa?bb(nSsKhKyK~0qI8nO zWz@TKGxO%?1P9G2FQww5B*C4w(~QA^O9FM}cD^WheR*AQv`NmgN+L`~b_Rw`{m(3F-;sp6@usah)vOc-Kk&*5@Fb@{b{P-8@?pS)~Q z%kyRxUaYFKXrd#{j0{InRHS-oS@pr1+IE^FYMq1{hYF@~?C>wov+Fx6Fd-|T;=r?k zGcqRBR#jG)>re{0iq_8KC9aNE*+(>VIASvgIx0fi^pcY5l9}aoxf#0LVdJbq#*2)> zGs}YoH8occt0*ri)43cwAt0?tcT+vZG^L|jO*5OoRdq9~q#;mWIk!A-{KdLThSb*4 zfr?6M%geYT+r>^jo5XdRvm({ZbZ0?SH_R;wmW+_D6fQ${VNHFd8eou)NFrm%rL#-Q z=pL1&(g+k7Lq~xo1deQ=Od?g6`~P}`Fim;n5bmR6OQ)G7O_ zl6o~Glt$L2UDG2nRIA8170k#COtinf4tHdAsKG8{2;&lM6)36=_ft}wRZ_`- zJ*8-ZBQi1uPpF(#R8oC)Ze8V^ay774ySikk(Ml%JjdY&EO&aC?L9=ViN`iV=a-@_! zuB>JjDO^XJsxe_gFf%I<2v*e9TpOsF9SqdW2-KBS&nyqjm=!F%xO8q#&ZvUX!$(Y- z6d2GytA8d_uyf`++Q8Z)6-sL9i{JV1|cp?M@DJsf`R&IaucKe~|2(Io*p zKmyFdr4>0jlxNuR(SeNq10tI}Vo}il$Davr-s$3aWvO^<^ZeGGRz>0;n*0psdwLfQ8a`_KsA!2f3ENA(^^d$57e_ula-gKNw7kAPG+zgTB{TC_sOft~ z7hddan23p`P~|<3eB1e-kgXz+^r){{c7561ywLM@Rcsx#9?cVNtzagzEPKqi8`n z=9C0k)G!r9_Jz<$k&$7~IC{=FqAz%_Lv-ey{hOlFb@X5}y`)SJi*q7|7~KX$ky$hZ zYNlVsup5ZBPE@nHg#DbtA{LhEf$>Edvas+TuTA91t!8-f?1Rkhx-6=K+H0=p9bb}> z0rzMt6=%Gfj7IGudfc>|dqQx)tjg-qWwbv*NjK7qt8jq^>9~>g3`NMEU9I*A_GY8J z%#NU=4h_znNnnOE=3KBAs)eiWS0e%wh99*(Tv47uNQalMQs@7Zqd>Hd8Er6dHkEgn zOC#ll+BYxFLo~sZylJO_0}fpb}OofJT^wbl%62vrNum|0p=RZ~YfCIko1sHwZQq^@lA zc;|!`ttaHM6&`PI_3O&*op4?G4C;ryy}cpL3SL)R?pmA)(j`PGI+c0XiW_QC2H z$DX$H7}V|44EDzD%&PWocc7lc!oA?=-EXk*ZHJ_aNNK;LomfOR2=<6O=T)Nkz1JwGe z(=rqbv zj0`r2uC3dDH$CYj!?RPkPaS0!BY6!^@s8!W9_;k$mr(rKCuZDFH>D?3U&~bC*kP*9 z;V89pFXTFdaDvpI|5ae(@O)T^|S30WR>*A|NZu*z3K@c2s#Vn zJaEg%G^aS~jK&1nQO{1?W0mWW)dbLgcZ3pk?O-OPpL?KkL@bYGkO&=G*r%AGu#VpM zBFkp-k&&fNckL62(u(rZtMk-ITvSn=F(}}y+au3UoaZ0*z#ZOEl(aMd5SAusy@DNR zA6M#Kg<5BqG>o3*T4&?_e{gv!VH$lw8d_V1s+RFajnuk`UK`h_^L%Lk8tykyPyf_u zr#ki|osl)wK|Xn?o57$J*;UOB!#-8A4_x?EMtzh~F8w=@**~-Yz{s2IKGg1j=@}Fg z)W=1k=`iwOnYw6iax8LAFkahZdxc|H>VLO2kDTx2%+*at2tUejY(}r}cuZun zxE-j@(74ox1fi|g(bhbA@XE^zPtNA}+0m(_N!2mfFg1tTqg2Fa2%#easjZ`~IXJu= zCx<5CpwlHYYx*$nJOXsYpdIT2&8|rHHLg#gBEyEt8PA&b;`WbgBF=`)81P@7)3iI3 zhL`YaEhyzAG@|Xnp?~&d8s2RW3J?yei;;atLrQC#j^?OgXPHAEc7#_5-m7kL8L?I_ zWbBl6@=*i9xwHz`kNaTV#C+rl3L%)0&H-OTL&@~YIT`B1*EzE)`5c+OZ9wf#_!MwP zO`dZLY7dZEY6IN<&@ZPJS^8v;b#QeRE6d11D`NmlvG6&)R9nUXdv#w}RT5;UHOsLR zI$B?J$Es^iS1Vr?z*Metm+c%myqhU%T&fc}*UG=0lM1?Q=tGd7u{<(O7ap!0%g5TP zyed0PL+TOHYC0e@Ym^Vk^uD~kk=41wG^3pwBHcU7S(T9y5pAXnFXd%*U>|ze2RKm% zZ9Ys-59DPGEDLQp?4VS&I4m$BSMO{?^LRTopE0<;JeaE=E5P3Vtht>-qX|JB;Lga1 zlD)_S@uL*id8#*-NaPc9sB9IHdUcc=m@vXsBHi*?%o>x-x;DyiVB$l%c6dB+j!urx zGc$%z85~w~5D`?1kR~CBxm~b_h`qN;au8hANB{S z_SuKWNsENwe|NNEpX{q=Lez5_Q!)nIBg-X~b#**2QZ}llq{`7-Bw$= ztND@aNa_X4#{z<7C6ElP#0ZuPXj@Y~pT60iDKEqB*u(U&wom2iuA1&zcXzd`s_hws z(26^fZy>~BIdK4qJuV0V7Y?jowRbqIkoXtihWSNiL}o<3$b7GQ#6lqbo3&Bg?&8n(NUncNJze{F0YOf;_ z31?hBgDtd0vPmKbKqh7nRB!|oBo0BzAXB#Sr$uY`pW34HkW6O%tV`~K@ zCpPrP#q3TCL;_N;5iANWpMWR9UMu1v94#rWxV*y+o*YHz^bnec&}Y*}>`&BlMzhJF z91wM}E~KGV1vum3wH+5Ww^kVtGllQX?q-Y$>=gR(@I^UVI;@kpXcQJ981xvs1#6lt z24hP&DGc-us5b?$V?b7ip%@UES^xmS2E=E3WWd3lAgbdqj&|s=1#lpvBvKR&PS}eR z%vBH94%^5EQg7f+2k_f}JbS*GEWc3^w~dx{7Qi z+AY>4XaJ@|mj+^lVthls+dU%cE>|I@w$>j7t349MM0CQil|xlpcQlBstl?&N^-tMt`w460wYT)r$}xieLJ|A3;oH@tYcqCaLYcN9fPPZ z=L=C^d*@c!jU1998%|8Pz$nu01bNvt$PCTjUT*FqC|O2i3PaRM)5z$j=t_7dYu=^f zmNpKPP0rdZ7Gp!v9EbGncpQ{RKg;`qzKOq#$$)qWXDbJ}crT1!!wOdkaR8S<#sMFK zt}+X>ZOtBot>iqMKqLWO53&a(*#Zi5c0ds{IhQcRiw7gJmfpyahV(8y=3S#d;f*6M z8QMmwR&~xoTzQ6Kec=f#o+-n>)piB~^gRhYs9Re|f;9?LXp^n-B zYu5yik7zVb%6Qh0&lg2{p9ki=a~fGEhmXHTz7z-VqyJ_SJvAm)Fup6PblLq!%A?l% z>bqc>hq7upJ6{1LDL8jwvOPIjAVN4FU93J3tSdN~foeRF>cEv)~j_tKne@IGQ$`Z8qA= zaKx#Ec6D?#?ER9rF^ zo^s+{SK%ZIQmkyUHKkBC>sq7&-2!%e?LISlP)!OkmSK_tqLp(8hF>HO6NOL+*ovEN z8uM|WLl+?wwFLHh#xO$mJ9=o;w%3&c5p%w$$7fLNgL8$BvKc0)Gblu7)@0sbz8;0E z@Mjc=MriZCOhnBvOzBs``P^KArAeMJ&vW)~H~|@=c742x62t@s6k269zQJ?~Y)s?`V74OIX3PoO*dcUvx$W2sJ4`!x!@(`wCdFJM zMPDp~+37YY6c9F*KRets=Kh!%{{aqN-j}RK;t9sAbCrvXM0GwGQM1hACOeaie(f!` ztc8hY4-_SxsS{Tb&KxGw@|^83xnk$@9JT)rpmG>YlBu8t zPK5UPLz4mKNa$zhtL*N8UR~WgIV=^bdrFBt6AA|`!c#INou{4Ad0MvlUpS~+-ATB2BWzkb z)&28nzKUqUC(3Yl3T3{S*=HYGS56e$e7F{!IA>1-@A^ngU@@r&pz=(+)Fq1t1H~@) zpJ*%ieZ+v&tZ%YDS}6A@@#cD3slRXgvu*HC16YN5uDucN&>1qy@3>Pgfr4m55+uYQ zLfnxrsQn~;T`}E)i5s#u7&?)I^_gtr_F+2Z0dR3snX{RU54m|`iHUzD+V-PXP?kdq zl++~&zS6LD6%E7RbcFrrD5towq9cGrMV>4g=3`X)got`amfguM(D~?hp-_~CU#e2c z$1_%1B8#E3d=ziOkt7tu+CG=lr;d!PEZ)zP^$id!W(MZC7i11`!n@TE87i8(E9s&*}{o6TJE|rC&@P39Bom204oHDCmw%FwY znxA5lh$1rn;5X(Sk%0}+Fq3|fI3zjNyPtBuaQPxfAo7`BEr4Z)5*kGoN)(QjBV$4n z;=9Jn0Kdwr*pF!y3P%fyhKS;%ikn^kw<8FU?*74Yez09E*59ClVHD)%lo*mG8ja_f4#f#pOYtJZJ^^(2!J#^H+{eoJ)RsnYM-!ObFrg8UL-ocL%Iqv=XAh3ZhQ2k0pTEOi@bb_oURS*G!q7*> zNf9ajcU)?4rHack1vF)1n1qcb9IPmx2~1Mr*{@z-s@?QFpw=jo@|gAGzUU$g$?UUL z!Nq8m#PlD9PHmAQCZUFA- z@v~>si^Y1gqBFPK=hKg_m$BR35uh1TX`)V|Dlc_QfciGMzHWDFjC7K<6yGf~S;=E~ zaIxTAXoZj|cUYJK4aJ55s<7@*N=L3GxYWHpeIU!5Vx5nvW9| znjy76xwq^wXscsov!=B33ST_Ll3PyMkLOu9(gLovYtDI%(~g1Kh4AW~Fly`j}R+UYB|C zast6z4U4r~jB-tbzLZjuv(nT9UprY<_}20{ZDp6LzBZCr(Y3O-nq-%BWXvL4@wedD zUu=U;lRSqQGi0;`8Z8*1Hg_DFmjOXuUApsG3F0N{)57=rlYi z$v-O>Yx$_OJ>)EAZpiw5BU2ApnKJcM!yf9m- zj^b2Y44Ew5hO;j!$(7k^n|abIFlJB|ilIU{gFeVg>{#YW^^*FyfPKp`>Y)=IBIvj{ zJz(!sATPzNO{T_94liH_GONq%AhqnI%2XKL@0~+X&!>+Uo69q*wQ}zsD)n9;VJD3% z(YJ=Ym8Ei{MY_16)Vet*0@yDMk(rm5N}b8>?sByWRhDl)z)2k1>5e6pyGmR?=m_^7 zMcu@69cp&(ubg}qp&qQbEHwS8O_60b2o5eU#e6ect;5cpQkkklrbv;g12p$m`&qdj zoRkR#B?Y8{U>mT)nlh|*=hrXQ9lF17j@y&kTaQ8m^c7p&-Avy!�^;3`yfvbmvLP zD!?-wfiq-d2h0&wQVps_07fP2U2Uj7b(2V~$-_0~Th&hMZKYo5aAPop;7Yg(@2a1Z z=>Z~>whz6W{jVXU1@i#Tpk-W58)em?PZ@P|WtNM&<33I>1ckKovCo~KlGh)_CTrL(H#!4r1!>SgYE*wWQqZMff#-r_=6LgR=gcZfJt+F}l zYM$kT;_b@P?z1|P+|khclKcP>&&S_~J{tXtwPtHpx=dX*G(?%4Y$I1VYgI%zPDlALN0=IVgC&7NZF3h=5MN02VB*VQt&b>7PE+lG zaU?6ltjlA^2BRDt(0&*t+cJ0F1!X&AqI#5U33qX_Z<2lJW}7t)z_JHp0q%_GvMVI$ z`!GCQe==Wuw2XBe$?cN{FOL^l0!rv!&ukq6t%y1?OQ=V~G1y>mJrAT+9NsjzX_5QW zE%gv?63AHIi+{BdHAf3&u~Lp-QRn0^mEkVx^2vsYD9Acl?Raz+T}4`x60AOx%A6P; zW5(D4SxvW7g%mYHpqNSqOi^ut)MwR_R~$49C2E4^xA1DPH z+@e$xA{-UBokj|W)r2aLaMhws%ilJ{%PKwQyzG>vmN&7`=HWhx&9Hj4;!c2e%nmtq z#yI3d_fU!IQrJq~bH&m$&sKAF;^3jES=g$VLP&A(iev{9(6CcIS1puYXM8+krWOG1 zEV}ickdI;9TeT*D&ef=D(mzJ=#rFV2bR5b)d5aA4v%oUylqXx8s50=7d@iF+#gM|P zb?SJV)i%*qV~A^XfRuG=fD;-L=9kVcw_T65uaI<8mats-02vKK0se@;N8G>2vN%C&Vl0MCgl4>C+ z)1mUd&4|gTG~wiz%?MT3Q0;y=&f+2nG9HuboA1Tz1e1U=dC*>kVYtEyR0BuhGaKMT z`r@gVIi#i|3RJ!>Ib_2T4^su=MPjJAybP*3l^^ty>RZRMmGeJ}z@myyNRSUl`2B0$ zKv+BKv^-|YT5uU~mI@%mA&N>kPNVU>D{Cd$r7v)-doj??Gc}qp*V)Z-zH&z-#Zqt& z?}qLZ;Zk-f+S-Wu04bo=cuchP?r9%mg7OU*?p8k!p;3J&NKw$vt~qKol=&C=Aq=pa zasgO-4;6FUX%ky0rTU~PMcM|*%onFKTtmDQ50So-0-$#_YH-3edgLEdlM#QJm({7z z-Bc;DwNr#E=e6`I>e5MU?v!L~T(#*KPTwiQ-bWu-B^XxUGhe-yAhlb)hZnLbNT zNu}CFj96UvF`<+n(7#X%ubYlz`jR}HkRq{O_(>84WD9xPK02u2P>5OKbFO_B@mfyU z?&1~InwUTyUUsb}MafmSnx$EW^NZWb9n%ggZ06p^(927)wz})lNi3d`M1|f8&K+-OmA>kxD zZ#tWf`%mREqpu0IDsFfr0Qrc1R6twX3VqC26Y+43Rx11VFgo42;Z15QmCqu(VH+Bq zJ4r?c>_~}uT_sFj%5zZD6nf$g6C=8;z)R4(2!t1VX zdR=xs+zZ~9)djMusEkDY+rhw9^q`rHkc&I(CZWNZcco%=d?}-z zk1}LIS>gDrT<;fQ+QUJ$uFR0ms*7Ts=sdd^vRh7z3pNpA)+-@vOmMfBS-?fQd3!>- zLHsTj$u^aBV_zXfhy~BxX{;xqwoFpd<;XFS-~bMk!h5k=-FES8=^l@-8vP|T4>~V= zL1}d1s4s9I)-HE~-*_2h1T@@x8qz*;wZybxV6~`FVQiDLtSQSZWnx*t5IL_uz!P|- z9A?)Ku0=_oTTM1EW4Tsndr}I3U_-G&ls-j&4J%pmmE!7Hxeg0sH?=_1MN|D#B!qh{ zF6fvd>zTWIQe15*@(o}2RD&n(FVY}6P6PLF1A2J%s#SfeC*jnTx|T*@sdi!wB(NmG zIMB0mf{`t#1;neB7UT|KsYFR0Gcdpn9U}Bu2Wz81us&PoCV;2Zw;AT6yP#XtC!LW(G(kMqxZcs2{@GZ^$JiCZO<|wHJk7Bhbr4N;= zIWI1k99GyI!A-lTI?!5mC4z2bY2sl~d{@(W4dztxcdzbG%>{Z0A-SN-!S>d2b3Qu{ zxv#qsXTP%Hxy90<4Fyo)O+&M`uOcq>p)|U_C{U%XLP@s56%TIe-f`qD;2z8-33`)Wbb3^0g-&q}glddH(;?Jjy?4_bDR|U2ubs$7S@lA+=!Gg?NXXwIuLY32d6m!B2W-HXcQOb3o?Lky!$TQuj;6hQv zHOtJGUCi~f@u!Kv1F8*GU?KdH8E=cYmP|HCz*f&b_KMO`*UMb^H#@U;s5mrGU>MI~ zIFeVZi})nx564zj09j3`bC)?t#VZiBPpL~146}m%h@vM)s||Z1bGf)73Qpfh-8e>1 z4Ur(ZGUGA8+#loM+*^xdXlx%XaBO`an;#atoDk6(VWc-@(^I+ z3VXeMie8{ZVe%g2#hKK{LK#=k5iMLbbWXH%1s;1|=(uXUnVb;LsCUL`8Ti~FG4B(v z0hpNe%6C!Jgk*7@Bss8%baq249_1R~%jFurM7QkFyVw!Tx8EG%l`r zFkem-z{vf3v0k06aGlWpgRpkWB*PZ*rv$BcH|wzC>2iY$y|;_w#X0~H(EDh1dbyZP zZcpRQ%5NRqoYG~z)Z$k7ZPI-yy-nLu9yH1x$rvWee8Sl)tz-)_yPF*uGh6iv|GYl6 zKeyRw@`6^fVy&{6ZG1$)I;Tc8VoRI34Mv104PKM+5XCW zQOiPfxJ=l{&492T$ncwqslYvsgcQ2uI2J z;tAdRjJ?HT-SY^V+eQ8n^Roi2@loaJe6yOKz`4jhRTGLZNNG(e8gn z8XN-n;JFKD>-2Va-GQKx7=3IrGXthPbInzR{uOyS;-9TR*b`75Y;HnN*0`{=R-6ut z5N%8?TUxRNg79b-+Y9i%LcJ&k0N;D@=5ld5|LS@<52gtE>^1WZjB%qzs(?-+EE@Kd zruOK~#|Nu}>7?XqMCnE!>sI!4_9GmmFXXEa#R~TN$E6h#=#b7Gs<)2F9@)>4wSf;( z1?Phz)2HU-2Kp47*`#Y)iD|qCK@oe*(j5|LND4hlR8d{OU~($)hg z@x>CcTw-ss=qr^jV0gHDFkh4zsR^6}XSeE{|t(T);?`U7lWSi2im9brRQ#j2{Zp40lqS+-k;uKl32_5=LkZh_PklTw*h007STR4vpdy%k-klFBy(6 zFU{2_`0OZ?q*std?Rcgq#Jy9R=%P>Mh>I=~-ilCy11obar`~E^LdgkzQ@d;;H9`NEsKpx>|vEjm!&O zVNLOquq#S>4Bf>WcXVCz^DV+nI7Jpr{G-)5s@h*3ZE+hkZ4YZFN$nWdEjh*!cH5|F zMlN*m^>qF`??;k>Xw^;N+a<(q_aKWhufuP z44w_abGN#w^x8>S=%!@#94#-V-bDb(J}#;w$PB=x zAX0gYhOj+v_a?N34(heA4%(n0>ot8rDAD{ydBr3 z!5n`+E;G)Dk$0&_0Y2LBO%*&wWxJ%qF)c>y&tAl3xkCXVd*Nz*%8E?b zwmwJLAkU-rgq3IfYzjffe`dGieW-g6XU8ZZaS54Pc>fKN1gTQiTO7V{coAVz;qEu2 zvu)ssoEc$)@zk&R1yhumM~1j`UJo5VGh?gf*%yZVeGsCKe!iO- z`tj`fX1e(Ba&{^TLa%2@G^#K%E=UEIW@K0choQS2Y0E3ncVu zb_SC@V)FgRqUibJ!qS#4>Kst>s>R}jg=T)Ii3|>YE)SOpDo4uX#CHD9(2@9_b^@5O zaePQAPYuL|BCG6U%F0QKuXQa6Dll(-CpqY%*EW(SFiQNG-Me#2`Ae?gGQ8#s1h_AM)sQwtc!-k_=XM>RC-PgkX8vNdcaF^aJy7f3#d?KnL$}Y>M~9co)A?7HbN&b^g?IeL@7FwD`>bn)zHaj~6ZjYwt-y-sKAHHs~U zKIC`mho*rp!<1)dONdmtB-ly&SMWRiEb)(ql=de- zO`ncN@;odiT*CiDy!)w||Mz|_G#|_voeo*^g#=o-tU*I!> ziS$3ZhCk@%TKNBn@LT^B;2ixqzSQlnU5jta^EFu*cf!jX$@4FZ_V52%d{LhA9yd?z zd5-#>Hv zG|ks|Jbu1jG`Lpu_ish}`}bpedH%;Q*ak&+qkk{jUwbdMm*<~;!?qXvkx&1tX#d^6 ziS6b2*9oy=i*o$`!N){$jHaWL@5S~fe;1!6yk&fOeh#k@$w~WX-2NH2m-pi68UN+; zFQ7e*B<;V&?Z3tCe;B7B%@h8~2VcVXv_xtD{=dcs@Be*#3jPuO(~pcR>-sBvMsG^{ zPre`9eew_Sc@iJgH2g?=dHx2zr&px?=m*^3pW^dcY?l5n?c{^s!fW)Iw117;U*q=Q z{V91fK3}tcj;^CUjdZ>ET-yI;@p+t8Y(rns-wF5CyN`JMAHEwu{8c>e;GfK2_#aJA o<{saS|G)lAvDa_@i~cl^E1!N5zj*Ec>_21sS7pN7p!jq2f3a!cjQ{`u literal 173672 zcmeEve_T~X`u{RMQ&Vpu97Vp52PVAf_)NO`;7T`DcN zUu&DSR#t9XEt%<6$xE#j+Ak_gDr*nnCYjq(S$yBmGc)JRIrm(ocE6v$!k4_ynIF$Q z^UO2P^URz%hnur=F6b5)XQ-d<#<>RFW%Ls%88RdFp>FaDc}BX?6TeR|QjCL;8jt@O zGS`hwvYNs~S*|;f>Lt^K2OcAm4TXwBLaG<*r|GvMN1@>p_f#)|E>q|iep2|ig^#v~ zdxd&EZqG*)@Z-YTYecd_y&lPC%^jlNn){qMmzgmPf0C%L>XEppUeyv&zUl!drb&4! zRPrPq>3_PEryEm{M?We2+c4bq@?||YX36pjsSWxW|9QoXU(#N#tkXBT!`Xh(k7$@6{H4eFQ925$!4CD0DlIdp-JH2$qX{9A)l?zT=kbdTAXAT=Y zZ_ePM%mVR6ZBX?KFUd17EMZEMV&t*tBkw7{Z}{n*kM9|@ciD)edSu-8-jv9Lf2&tC zs7)$EKU7~1G2i#X?}0MyVBne*-$B!ixWiJ9&F+5a5k?jjqWnSle>(o3f&atspMK5~ zz`xVw^$6hES~^``bMt*S<_8~Jo^wRmz1cq&9KED8_}lo+b7NLv%JUX-_`ed(M8sA`!zb%+mRw} z3Sy)m8zcQX2+NBOO`{YK`dg6ZRsNM2^iKzUlDYfmWh8jfc_c>q>Hmq*U(%@*{CEHShy*V_$=-OSUmHWtp&024Vx&)s(cdXC+HH%$ z=NmET92bL5VGKIK80nwI;Q!_r?VgG9Uix->41Pw%NPi?o`rR?w{YMNw$u^|mzx(Hl z7<8&o&}-b+Fh4${?{$Jwopd;F;E}okqw>>ay7F5) zkVom^#|52aE^QcJ$aGVttMco>j}PTjR*3SlxN)Z}f1|7223fvc(oyA0W%;?T@)Klw zm5a|KB>!t%{5;R}kB;J}n=IcX%lD8CFGcwi6%!iXBio(jYPS!{lYBB{e^uC0Da$W# z@o&K2T~%HtOJ zMPYeGL4hdhS#Wf&QBqb?!DNl1(mC^r#bv?FtBU57&M7wvX3i% z7G7@@%q^K=T!8$7d6nfe3yX@4^5UY3!m_KtK~YJ05iv4d(m`cW^{Vo@lD}-6LO7tMdiiC zWh97UNV2k&>;l{^JkY76rrto1r^uNEe5@r zbFxu#e8o@{te90k=emN@;!bLLf)7Z=VRGofHYT0!>s zGchJ0SCL*aXI=qH6b~DNQOFvSJ>Mdpd%?KzbH*1CcdmX6ISYOA>H}qnK1?s1QBYV~ zI;V)}xvEo7=Xps1f+{SS4s|LkC@QQdnuV&=b5f=S3kv2Im(QDn;VP-PzF>YD^2S$` z&KuLUUKdS3pNAI+X_j3lWa;YsXzo1oP+rWv;5LR1Q+=9KSy3=&WuG8H$jqWHv-Z&H`R7tw; zjx|mq{!_kKx5OE-{~d(9c>JdyDs?HyQ|z6B|GE9IKg1h}T8@nCl57NrV8!2Fg+NYoEw>^XQ6O3zQk?MCfiL$@{tO_rmjbGmerDPOS@-pGrBI$r^QXy{OWUsuJm8S9)_l zk>2P^58p53)#OS)@d{DC*_A$Vib!vBr8h}B?XL9nkSK4+e8uPCzZdB~SGpq%+Hvo_wJw zzrdBQ=vTSY|9Y_~U+YTuOMaHS($`3SR=LviW%)I(^b2J9I#>EMncm<^Z|g1eq|ue$ zB=4JD>Av5H@@=m4G@0J+N>}5RDEU=-k}Jz6yV9#uH=^MN?#%AOmn4& zW%?{v`doRxz?E*ueTu{tqTh;tbsv`frCf^7lwDBz?oLJ6-kL zov!-fPFMO!>C^{Bzu`}mBKDkUFGKw_YU#9RpnjUPbh%Z-SHRrH{A$MDDSzTt#rl-3;#=bV97>Qs4G)Qa(VmI85*dwJIt;P()1;+K*T8wr zTDmmZoNj9Aa4^4#gXhLNhJt1U>%PSetrj!=5KmaeZ?GqiNt?@~X0ExoTw1mQO@3$PdYj}YWbc5 z?7c19ta}Qq_qJ@b?kS+&+wxcIo&xE;Ee~7w6uj?kxzoC*fO>DsE!I5+$9r3@weD#F zv$v(tx~G78Z_8!YJq6NxTQaSC3ZVD446*JhaNgT;f^|;;^WK(T);$Hvdt2hHdkT>E zwtW4Q>MsSx=)ZMO0Wtb--O~aN{kQIEp@jZh_Y^3j|JFSP$mqXyPk}M|Z{1TsjQ(5q zv;ac?t$PZL(SPfn0%G*vx~D)G{kQIEfrkED_Y@GL|JFSP!sx$sPXRFc|D)_bv|-so z(uOR9^#S(_Z*<;Qy6$JY?u%XbQ(X6XuKTgB`)t?!DA)aP*Zpa(`;%Sw$GYzOy6$_r z?h{=1KmN|y|9`vg|K+;>+;#tv>;4_r{p+s#S6ufmyY8QN-9P2Jf7EsVpzD5_>ptYV zuhH*^{A)~L+f;wxQ-AfYw%iFhp@cI($H|sZ&kef>Mm;soFgp6)fGYcHar-zf{Go(D z6O3rD=nK{}8@ zjpC-DuGK!(Z@Ercf;?1&wM^NY)GNCkzs9!VSDxt)<+b@k+3o(oyZ%7LoLxpOY(k3Z z4{Y%V-ZMi;*_-4uUfoRem`Y$_yFZxSJ~L@g7&Hv+IwP@milZF0Mh%TMsTAn&9ao_n z6IsqW)w?tNfrU-}KxN|$e=z=J+DP#SvfGD*!BaD_cnwT2xNZi)M#=SE*cqPbPr51W z59Xn2H&yfjD$2zoX8$XxAHA|0RKi$J@QrOSAKBm0p;bRWv6h&f;Xgw(Uy)#5ixRJH zW{)A|n5($-2l5)+oCc|tTsS6T9Za*Bb%sBg4;q8ooOBM|~E3!C{6+}@-~*_6!XpGVJSc^~z`Ro;*G9pyKm zeAIA!`h712(=~2RLl9pu4_U0?DVPwfAHlpeGO4FXVj*|r3#qSCI`kD1 zAi)N3HFg#CkaD=ml$4_tRr_KLkp`Po!98?}7J_|>b}qL)YllN9!2KGQT< zh0ZwiEe;)Y>f2n^J809Y=pI59tnQo(=f^GBNdrYvm_{s5_K?`-eq@OrLZ$Naz~W|1D9d)359!`M@iGb_q{Z#wmnLtVC7)U>^cAc z)9Sg}8t=blcRL%tmy=011JC;ymL&opf*J#;OTi@bSTl_aMa(h4Ej0u28&mB;t{SWn z6e8x+S7WfMO~?r5eWw|r+rUPDu!d+`BBa5>+++G4zn)>nAZp~p+4K5ODy{vs7WJ! zGF+&#mONeLHVLt>hV;I)m)h;nk1tDC+W62=&qP| zaTwV(P<6_OD%Fw{Hp-Da86ycroJ(0jp_TzMw|Nb$4k62q&u{0-q(I1KEqHG{G+Qdo z2Bt&d0ctw*O&S8O@h}2dRU{1{1FpQ9@{P|v`5T@T4|qWb5Z3or#8Z;ZKA5vM5C-r z_wxi2bNUasrg=>Hme0BEVMvqYd_PVKldYoMq}%8e3??3WroxgnvJb^ybC+N{L!zO) zHM+xjZXai3#-dxoj~vY+p-C*&kvn?*SZYBiVxh)miy(mJu-?OUORZp#83Us|_kPHX zZk#_1qO5{LTI_O2?CeC-z8t%e{UFwQfr=f7_xb65w-JKSC=zuu+ihkF zJpj`?IrAd$%6kQY8lJzh!*jt44Mjc=#p#?k-%lx2N~wD%+^KoOqC8dO?g$}1Xk5g6 z2nqrb*V6S};<}2i_wu!68$QErwU}8gD-n{}20=(NVs1nU+fb;sBj)2oNEnLAyJ-#P zFhmLFUs{nbi{DaDMgWF`$jf~VpKdpNQ=N7L`$vxa(o3BA<53_T1Q3r@hNJ9=*sDlK z9Y_Gi*3!l|NhN42g9ce>iCJWi?j1Pa=jzAFt;Z>m$Ssg!6q5a(fi9XGzC=H(>(jN~ z5qHUIAxUx}!9PwqPuD^0D2cWW^jfFS%`>e>no@lkqPDcM0MW63qa)+ zwPR77gz4CBxU0pr>ytse(jFX{Lwz7=AC4LTU!TDb={$eLnneSv{403E&KL7zvEEB# z{YR$IxBfjIf(Ei#n~3t=#4nAj7bQo}o*85JY&57v^{mcx^(+xR6Mj*Ox`*gSJ2hNN zBs4$i*7qZzsCvGqMtx0F->FfL!Bs_RRHzW;#7un_TpmcHrlL67R#O!QiT6{-(xz%c z;9c? zqVaxAB%juT+3l_GQ9bMppPsPq9mAMU#hB5aKjKy{8By$gPLJl1x0QLFHvdo*Nw^oa zT91-0BD-BAuBF5T7X=Jf2C<;H$KE1tr_fF*ZNd4nX%&gP$$9u?cg;5z#U@jCr=kaw z;I4gRX)8>02LstodKoqk%`yx`kp~egvTdiP*qQ}R+VU@+9BPj|!>0|M(kf!MjT#`; zTP7M=cR@Y~hp_`y%~2s)<7AQdoSk=-m6wlAdAH4_nH;EWlUBx- zHOmxo@dteJ62x=q(S*I5Cp{Thvd3UF9KDi-*BG$uREty-k|P5*R*oVElv6b#mdNaO z!L!bXvN}G4lf44Jq?5IJNNbBG3^CRgsU(WP^C=9= zav4GtU*!Zibj%5aD7M0^Iw@%Y$395|##SW_$g52nFl9y3fZ{bt17?Sl22?gC4Oj?S z*9d|Ub3J+HzBajlI?1U9`!=C_HY zb_%*w>%XO*y5Nc((lK=!I*Dv3y zt@4j*!X{Hib(5;!r0F+^+u4XD^oKBMqWe|Cu`(f7D{g4l8HxIhPrq@roubbh4=aX7 zr;x=jZj4Ey3+!KoWxs>{sWO4tSJs*NXOl@~xdU`3<~ub{cf?EvcY*HUQ+j1M`=CYB zC}9=#r;wWzRC;AF&y=k${ONjj29?9}wp8JzvPMCJMEia}oNz$&!Tn zUUoSi*mDv&Zp*f*xrCv#y~drQ%5ioT$(ZotiB8WiS_}2vGtp{6wM~{$Z_SP_Lw#3? z;wD_$hGdu~^A8_^QQ<%r(B2RQoB`WOTC<<}Mm{psx7gJpJ4lyTq|%|j=h!7(vV!3f zvVy8?$A1KBd%`5Qv%!N z_bIzc>nmOcvDy9uJL10e6YL=k_5IkoU1WZm6#$ zrHmAH*GzY*`WTQWUW_io6EA>jMMW4jl&V&o0}$TAD=mimq-4;~1!;AikwQ;uet4C_ z|I{Wtt$AO|1K+BgKaFe?%KXDz3EJCtyVl$TH4==er!VKH*`=Z>B}7vKKX?XiJ{nC418Q-tQO%$l zygK_WsEMTp9UQOwHXqrM=?4+VAX}HsOt>s zFwCXA@0FqD`JqKtIcCnf@0FqFY1d@iJ^6Y#llgi|@`YGG^%df44VWEEzY;!)Pzhp2 z94 zbSSfoqn0A5-PCMjvs=o)+XI=3Js38s1|I!Kjb(aK7q0W@wX?4Ln{3 zyF@w{HT8XJa`?YrL1|Qe(_PYUl^jMT10a%cHfYLFuRv6Pld6YCT}zEEk-g{M;{4B< zM0uzAZ%Pgge_S>+(^=|vS&G{a4PPuvWjISMJV(%aoRf)_XUIH>sPk<~6xzTWN8COe zwo@~RJF!*0>*LPiQCVmM3dse+$L}E?9f4m6rpXG)VA@~3$JcTN9ynSaN_pT=-|9x-e4C%waElgE#Wnj>_-8>1{qpHvH**5D zNsiYPEJw_qWVb_o``B%7@Ik`n@9g&K?3f@~Ff-N8ywGCiV-jNNdDu-ki?|sRs9#T% zNbL?s`JBLK`r;71jF=Zt<6;f?1Cgw*_g$Ge+1|);N{EGwXLiCvP9N(fEy>`^Z(GuO z>?>RfCr(ZN<6MvJGg<>mKIRENXhT-Xl(5b9chgFdbT3eIQ z$xbGmu!-!oh)<|&2Fa(NkQv?Q(|x*7qgDQd<*YNm-JC5S8eg{& z6JW}A5ES!&D;<8|W|!B3o^vRY7CnTtmZkVb+C)_(OOL}cv?3A`6D1i1Xkb6z7Bx{c zk^ECE$Sk216AkMDFYzFy`vG>(+!;QS(=BvLLQJ?j&;@P}dXnpyb<#w%liO`W*VsCK z1_hyOjA-;)gl5Pr(iKFyE2!G?Xr;MpjHlB4k%kGZyOd`41`nm#Bc2La{qHVz6g3H5 zBdK*sY3ljGh(l>!r@1Ca=wMRG11Qah8G?J4(rlk-lR2CYZP3_IxDu!(9idy2<8qo7 z*o)LBZ_=V$QKI#CE_Jy93ho?HYocr;e=G){r_!ZSMWt5MLwrse^0CD=bml^6MMWdD z;>|bF^XmFp4jXvOZj+UiPZ7F@SDkwx@5%=Wu!(?8G%FR}4jiBI;5} zza2uo5Qh+gRV*dw>-}Wt0%ET&Xl>c;JdKq@oaeKXYmw{^@mU>6S02BJn9qx)C%}qoR&!%`E6IN`6KQxvfx}#m*1|A}M!0q(q>t*zO z8xQZ9j(YCSWgmqFfe_|$CnDw*r+bR(MMxVlw2+`(It!(>%AXImA8)6zaJUcX{sM&g zyAl2*d#ftnvBz$FeUtj$TFtDAoK6G)}Ce0^-TL&C_x) z;Scg@5`QSW$`S2ng=NABI-Z&&qIXkV1)>f1b# z*aSU*ZdbLDpiz2DRXeT(1H9c=OI>i$PvHm?^idNF6lw%dwP@1w!}$AXB@ya-Rdj0; z{;SsLsU5Z0ELt236s@Xrvg1X=Uu8sf^TWS)v74k1bgqRW<6CyGAW;Nfo`rcG?F%WD z2H+{Ir}?~KQqAiy2RPHtIYDt&2n7bE6P2B2;#u@OIH~3dE+viv@?2#Pl|gF*GFs#s zsy9K#oczdE5~i?aulI+s`4PJl%7`u?7G&n9WF?85boYl3;4Vw+V=?o0FoA)8kfs@I z6?W$6Ri9p%kv79uf?=e&t7ajYOlCwI|8FqDk3RXpTJ@ zke}t5e|pvG0=5rB!&9E8u8(>s3tJj5Mo6mIZ^&+DFG3q9CpXBngn=j`y+0E3m956!8Lu#22T5vf{0VSSb zmAJzj5#hv~U<&HaZbtd1*ltNF$U+$VI=CO|w-EQF23#jxfL6r5n6KyAe9h+wvKK3v zqfjN$d|sEVO>>5z$+>vMK@aoaAi7^c6trcA>z<$TwMADj042=qc$<|3tlf<0p!GzT z0lb<5G!Z0Tx&@2H);MS2iZ|QteFcKQrJm*nFDRm(b%^OH<&+28aF-BSZ>TjQhTa?@ zh^GJ@+hJPNoU<%fsPDj0jwwvjtPV$^wZitM0k8Ta=7N)0(mmV%Mo0%+1~q{blWnBT z+hOO0*OG4ud<@Dj;1Q16wo$x9kv~$B_@hn2B0pT_EwuAA@|T0WV&tt81(W0Lk`|Rc zGVd%qFTD0R#bhrJCNuMdnOcrQ(o888(#=)VkT6t&XEUirqZOhGSVu9cbHv`qL#OQ6$b{-r>bojlgo>a@Z^jkj(E_!~d_6`)tb>RcTV7!@ zPhSs>q7pBtI7t*aNI)g(}D!6$s(8sQjPd$bw| z$;{VOCRt0FH&f<4ZRhDq@y`vc2;9bOP5ldTT@5+6+=G2qTNk+B-`Q@Z9o1dAA0k(O zuYpPT201; z=VEz1d5jp?flt|EM{}Mtx5&)HwM-gV7TdKl^Xt{JrWjbx3(359>^yy74=3TtHkJyT z$<-F)x;lGxT+27n16ztbeU!Mu%%ha=8YMU+dP40>$Y%Z~^W$o< z7ujwb2t)~K7)ICq5_vimYZqU_4w-^%abA^I zGHqnp93EtxaN$kPSY<;JOp57W*U_=I8?M$T;1@PDk=73#eDP7J##;Kdp3+3dKos7P zNJV;iRQngwC@dvzn7@(Wk7Cre`QyPZeSg81kjy-@C2zD6yW5FjZkXGI5Y7fktJJ@r zAOVPTs%@xEgTA*)9x;&0Y*zGqEr_IEFoSn#GVGedbZcPG`oebfnY9d@EE zq==np3+Y)qk%TnwMR)6-LfSybbIdbQm^eS6xK4+-HjsriyQ7LNxYi${1lJ^!G{L@;Lc3b*w8C`1%&WEY!fStnPH@C@ zbsgC|aqL)MOZZ{3>hy31PZou=5>W#^sI$EVte1L`9*-SKrR2VL2V9@GW?<=Hz?qku?{y^rPXy=7_0;sF?pDfw_Xf&0jGH-{S z7hX%cD%O9X;vO?vi|S@T+Qa*80z9i|!X(^gCraMlK(D5OD$PbVL`8NHyWS;sqU46^ zr4l!`tt4rADNiRVbGJ6sTj7bEMZFYdMLSAKMak1@|DI~gh~QRSA5c-IPz9kVKJ>$- zDCcS9&ag{<@jMhI6TdtZC1%$lsoOB?fVPROu{59w-DEAa7*?S}*nC>nrXoFe{+S5# z;UTR^5Jg;K)edb-1`h&*QmijN2VwQWub(3RgbCs*Lw)uCvEGMp+1Ju&|lr6<4D$Q@>vT#u6Gk@)4&^;DN_HOGThNWJeN zEOlScuOBAq`x3qbIvh9REt6iXroy{Kp`H>G2yyc1d3POty!D!>)N_NVlt75WVNv*f zG@?BV+k_cL%|F3~`aVejK`K?@ee>PqfuwZ9-`UrR2#BceO``72UUk=Kbr)%Mw<3MR z;pAdh{8do#3o4mjRIb*j{6n(|w;`Q4=ppLzFH6We1zeLnM#jEaIt?n&a-6gVa zZ&CLoue!suy4hOYTv_+sKXK3Z5V*&@o&2Me)FE2kKCn zcdDp+vsc|Jt?r##-3Mgd6Gh#Nz3OIZb@Q~k(`4P_MBR>uJo=lc)jd+H+fUa0k}3uJ zZuY9X6&^*&>Z5l1+C)0__XSb+cCWg%THS}Wx~pZ~TSeWAz3NWT>K1Et=gPW|J;*%& zg}^<&$y(jZwDBD#>s~GD{>`iI4swZ7H~MOI+mS9FJa2ucJ7$y+y!>-!06m7?A)Hwxg+h|J*%Unah#pIEjrh*bN?2d z`zbj_A&q6xx%GDLb;vchKZ(-fy#^W)`;liAG{@yjBQ;AAq!{=KCcKu4@8c$&$}!Kx z``MLZB{_9lFky|BlZ705#DJMR0+;?!O%^|PwlQTF)^h$QV5{s2U zLgo-W0aFzs=92aF{^Alj4mcB3OPvaF%32y4d5GwP$6*`j-ps%Vi>;=|koFDi;~Nl> z`Qj5Sgr2YBhJ^7r$t~FT&q91*Aq;CvgT>fJk6l7Fl!u;FQ5UK=`Q&5R5xuD!HO-U> z87~pt6=h{AZ-^$OiE^mDK92c~m?12sBQ?uWl{gOa74Og27}Q8;Su=r9i9hw>`kaAw zR;A*Wc44tmFG?dZa4PTkFKR&pNX|g*;4&f)c?nW{cq$(PR<%OQsFZBu`a`XH)R*L! zsb)+vy+B5hXRQ>Bo-e3Vdsatx9|6L_zCYf>^eKxpn1%Zdvc&0uMTua$n&%om1}3LN z#GL#Vb0PT0*-jzvD&`vJm$q{5Ger!MkQv2j1ruKAhwsRSbBdZJN$0?QAsA+&sJo}X zVT?(7rk)1xUK%`=u@xh_=)=l{mbcJ6PC>}If-hU}YQP%gr;j8l(Wu6?yo%rEzrS(p z7jn4x$X{r>Jb-MWS#%{dD}y_yYgV>kkTbyGC1B9fER}dVGbc`MDxMwcNq@#D$PMy? z9N8-t-Z`YI0UV6fXaC`eEKx;&{6AUb>h`r{hrIuK3U!(K5Z6M-?LcZ8bpzZ^!yYu@ zv)Ik>81PJ)eI>Fb1Nwm900)K9;$|HKJ_b(;EQYbtMmhI>S;k|qF9$=s<^_*371kF= zCqE;#S1A#*4Cev0+s`rkae(8jy9q`;d?F5TtRqT+O+vTCvC=Uj2@9*!Q9_+HMcZW2 zdMrcp|3nFMJAS=HV~qxsEn3742)hLlUB}y0Z0|{8XTQkYG)qBVx07#`Tvs>pZI#Tu z<@JsZ_*Q&26i+;R@F#|o7R|wYZ7IetE2gn@_9KMvEnkD3=&VhY^^7AcMYeK0JhS#N z#iI5HRMFE7S^g2oxAm&%CW4f1ofx;LSjovq=hrs)h`L4pFK`vD$4Ao{?V_UuJ5Y>k zm?jk@dE9y@dn;r*twU%yB)5G(b{3l^(=%~!N$0joruQV%CIXuJM=-?4;}@P8Q-H$f zPKaOi38KKl{ejB%>V^B`Du>>(5HUJFfIR?O)iD5Cb;L^Iqwm2fW6pY#(+P z2P5S0^QbuOJJ46g_&J8jYYFjuA|AVEs*yG=eK*V-HpQ|V%iO4sWF*GEYGBS~LC=u5S z#5Je?UQ53Z*BJKbvrFRCB$w~6m1nan>0h9wkBg?0qVdB#d<=zFW5a}B=Y)J7EH1H~ zR9(i-(910V{M2 zO%$)e%lPze^5zhqQ*Z6D7vIim^V270L@;_Z1$@D=m|VFyd1v?o;>(jx8tM@PECaqB zk6&ZmPpbUEDaiEEW;!2ba_(CWBNxs46j+n(G<$NSF1D4&BFnWI9KE}pO7(@I|L{Q= z`ZMuMZt+G-MQYDtMA?op)xL~D^M2$3^6@~wGu?u~AbBCfW3hdTrj&iJgTsf~#N=!; zoMUI4`3{gD#hIOW_XwzF4?Y)(F3>m)|teCtJETl-{BF}XEPlt0Dm=WwS=b5$z!U+*XJor+AfP}v;F z+Y!v(A2DD`!MGcBqeyx6^+YqFPpoq&&2e2^n50KxP1@er}$Yq$d+DH&LRA!)4?I-g`|c7dXEB@m){Nh zoF2Cjqfn9aqH-h1)x4agPr;1jF7ygylU}H5hPje&!aP6*jT)10qqI{{fWLV(iW2eK zXmxu>#Sp!~dsG14A~-IUY{!Vk`MoI{R6kKvD-PyK*P2j=6ue1OaU>H!Sc6wF{6R7# z)VYrBttZM$^Q2c~pHWCJ5a*C8w6)W*65sAoax7*}?XDe*dz}BYBLr(cDvv1YgEux1 zn`M1x6qjg8ygHmlL-g4FlJ)8^tZc-*$G*pG$DWM3$MqMu)_XJ_#K10DT#7Og4hHX_ z^`k#{-wJ{NS|jIk$10Jyh7#{)JZsr4G2xjlLUKl=!HcA7ep-M7yz7<_|N(L=0YzkDqtv{8JAC(Q} zy&a&>?_@VYrJ&`ZQJbq^n!%D`*51X$aH`p#&m~ZhzmLm%z=oI%$OY@1%yVQ&J1VKK z=sqp%bGv=WJ;A&WR2?JD+(Fb)e|sv(pIK~@gI>#nKDH4~4-&o%vLVM$1Ct5INrQw% zz4){r(wUb>|6}vAhc@b{2x56_2MX`v9LDTKdje%;Lb=rUHc2rXv)*Hl%bBa&Z)s-& zZHu$_fdHmq-oC}P&5&!-3)%a`*YST#8MLTy%|2HPE*dnOG1-)z6knjoz!2BL-ex=g z5)+Qdp@}-b{i1j|>><85!l`0X)#UA?-dPQZlo)9bEZm33o?V&s=rSS`8zb7rkt&}2jM`DdhF*E1lF%e7_)(upEQ}CpV9^lB& z%xpwBHzx23-|~Wk8yL^2G*$R^H!9}@TKs_zaspov0}mn}o}mG&3jQ`llWpZjw~nOg zDL!KY_9Es{)SOtMk3g4Iu4LdCJNIbhn)5@f&8hNuzpc+M{Y)el0>S|V{X81HN5KYq zDDy|I0e`b2!Lb6j{40jf^6Knb2ceRehKcPDVXX#0o{ji}it+l4Qk=1JAf6)1!ds6L za?+EkkYtZKdmD{b=0v3jDM}A`5YEYNNLtj4iEnO#8Kyr;MV{1rbPryx;J-FP;Si5i z12$oW8N=vA%umR52!nJBT1MRCj)UMCu`P_EABX@DT84oQUgQ(l+dp8NKk%A=`gGPg4ZS@@c$3j`S2w=lWXWXm-ke-Gx0$?$Sb zJfE#^Jq2((22Ng%_bT`$F@aeCnYhgf?9B;$MIHZ^C+??G0n#CcmRr=wh}n*pkX5ts z#LdR$_%Wd#WctD^k`JU*P8Gw$427&F8*+lv5=B|wjtJ)j(-gVq@g4$^%ZY1)?a0BO zJQZq~rYL#Ihln-6nWgab&zx$TUyuC}+Lfeb8&*9dHdTzoO*3^mo=2M`jyxV+Q+8s% z7$vHbD1AJ#auZvLX|CHqB{&E`M#L;3VbS&jNClKA_Mwd0$WoDrj9Br2&-ph*DS8f3 z2*noW>0}=JHg_O)>tfv##H0l#Lg=$iZ)yyBLml*@C5N76bJb+k?=$(9w`!J!A%Feb zX6!22T2hEZx()NjV2_SgMzdxPTZ=|NrQIB^4%Ni9!`dnJ937L-sYF^qo@-GCZ70%B0vqoLAgDf4+j{O2rq?pLPVMl`mAw4f9GpO@4$6TX`<`{ zo#lH-JHcX5m-bAp#iN9@6?1jqRohK5@{dpju4+wYZF1i5B6 zW%C? zGp#N*kZ|rtXEeVziwjfW$^wYPt?l<-LRs76{D`|w{9cZ5R0*DbZx4x3y6dr4lb!j! zAAexKm*Dn$|5lVNzo*HEX3>A^_gBU=>wN3- zdzX-ni0K>H8N*=N7P&hyQ}^T(;>Vx#%qGoWC~F@bGap8$hiF@ptvLJ5OOO=X&Q0YC z!p4{5x-&bssIzK z(cYh*=3<=PanoKp@am~QUs4W-Qye#W=+6sW*V3Q=@U2UK7Le>+`lD7mscN;O2T-n6 z@9N_PfA*^PB1(}4;B8(rxK_PEDj-+AJLwdgoXLR{6*R+gQFqve9L=fq>h?KQcC31f zk@2Hy*DaIn)0 z4S2-{(ev#auH~3-XQHF_e5*6?V=I(&-O90d>bVDFL(9aID)!u;fDFBD;r86$a-S^E zJ&@e7SSq{)K0G{kr5eW9kk8kiOSQl@|HkjS``2m~2rJoWS6(HoV^>}Ig-&*FWK+q3 z#tgv@>(YnxOh$9%%P7xwPXu;bb2j|=T3Bnsxf@VtH5F?&faI#}23*-j zOc8RL~A%sL2vvE zx|paOF^y!pXoiwSQUQ{p{wUxFA5fQ23wyfMtn;NFG=jZ%@4q66KraB=A;$(sp6E{0 z2FJtKIYzHjx)_XT!uwBTIYklnGhyY6qU9t<0<#1g_w>XpAU^yE^^yT5ZxgHsc}?8f z<45tB&EXxlps;JUrC3A3!+}#7iTyqL)vN0G%$vmgfV|uFDZ-#oRc>~U4IXI^s z3PlkEN>Mj&S2o(3<|$L39;V@OstG$u)k%;0@Bw!`UR;gV>>jwn1}2N9>rhb(E~3V( zdSRPUAs-gf15XT_5Y`%~no~g5Ah?+0>1NM^$EhL-%YJ5&U>XiyRi6=S`&g`y%>cE} zr0v|$EKEn?CJ3<+n$iIE3ZnvMBRNT)iTrgqQfNxX@aOUxA4Y_FQ%R*!D`H+u$zZbe zJW^&#`Dh-e2wHe|K=zwX`HMU>m!W`iMa<`EM%g=^kMS+p zHgJiqBA|KGe1sCCOajTd-I`F&mD)}*H`IiT+4?8W*0+1L{$>|i_nyw(F~qj!snOJQ zI%S#|rdlm1iQ`knAZ0#EP8pWRCxyzpt#ODOFL7jD|j3Y#Tet{}DL@Sc-7s<`2-3&uh z2V72#bywX$4Q#**m(}c#qtOM^Y-_%z<&yj}2j+>`0YRL7tzu&}2e0&q8XQE-BfFs! z!8AFK8stNj38M8ne|2^p%@RAU>;|p{Y&x*$}N6DJ4b5yl+oYhuw zHFtv}y&8;j)-3aEu$!!Dj=?vO$R`&^Ffqq1!;`dV8T6wih+k^f|8owg zRxhkGDo;XDIetzmtP;0Fq4=Z{i~R=~fd;P|$`HRb6%NRT=U3*h*>F`l!`r&38b_F)vFyblqwwoq|tJvyXoest)1 zXz#iuPFxn*k47;JmC?sR_&bPi%Gpy%N)gI?6S}Hw^?jU_jS>-a2EA0r2T1bP$QqAQ zb`ZCAjk`EWd^~SH9l4PQNI>8!zU75stDuW!@I7a|aqQFrxXN3~Xw)4aI)afA(qsSZ z2tZmuPIrCsIfKK#r9lWyx?z%so`msn$8ArFZeVDgPc&L)|Ce#wxEO?MnXqybN=qC) zNa0lKeeAfc56EkVKFX{+#CA+9v00W~Mjz2n@hH%BJbC+`>^aW`r@-n;^_a&RL!K@X zGfi+{x2K*E{oEN~Q*d`VX1uf+9J`gqGyW1rDl$G$0t;g zrm1E2pzyWVIOL?{;1O@>Ps+LyZ{3P50$xDKc#GckWe@0#x9*OLw`O0>6TS&Eyb<#N zJ!2z!7sXrKz^;n7mf>1j%d6=!`aCshZnO@eef!DnTCvd^HQ^S330t9KhEFTFlh$_Y zoqX#G-hNMsKPz~94K*|siP`#AXX`I}wZ66st$PP=U!kTgf-aZ_4(%hRckuQOsA+xb z`V9Y;I^Z$G-<_q85Y2Fx`g^X0Ryb<8pMG{RqI`6s7EvxB{sIS#D8HjmDg>e;%2UaH ziS0x^qAU@~&FFYDvMHG0h_Z~LMLKgrPxiWWI;S)COK=;cZkWMIm62jg=FgN@Un>lSi8aBcs7{i)!;+U zn(wnxxEmxLBWammz^J&w%PC9%QgVcslQ^P=z=B$M>A5d!$D8kSXv=jlHa-@K6>rj- zz++ru2c8d6;JH)_Jj;s7mQmn2DCRILa_kV!La*%zw34_ZZE!@O*V;UXkp;flrXG%D zbKy+ere@+=+SDU(X$AmbXe=+f=a>B%FEi|vh-ANxP>=U?Lyn^)VN#8A$q`lo`x&xpY~HMHy9{Kx>o zWgVfmQLz*~EcCFnrA5EQ(w^z4CAXKX5$d9)J?Apb($e>#F}!*VV0qDXE=ax-dKmUi~fwX~OXW@#UG+RL}8(Wr%dv0%k% zX|HnDypL<5vST4XP}a09ZJM)Mk!OPiUJZWhw6p^}8$4Oo^s=lV#9wmF3p3P8MmcP zp$OJ9w5N?sk_x+kWHECck^Kt=XaJMEvk=ZJvLw0)E;PE1Rm3?YgX3fjPV{NYWxQ#1 zW+ycp744>>A6;JsQyU;16_kHAl?;((L*NBs(`B3BUS5BSj|g}XzJm$>3=8ZXF|P!9 zP2BD!q0{WIMq!8F@bIhjx70oS>a~=t`_^Q%75io|N9+`4mvg9F?OebvHxo9 z9*aTvjma+WM02Jca|QtfmU`YJbpwcLBPAi! zF;jaud!S+$k2Uy#&KITAGy@lnF`j|+=4bq5I_T*_#PsvlSkyC+XULUdYTM61-oJuV z;5;2`@;C6RpE(Nbt2KEXuBBCb_exy;qBVIuwi~@vXcw5U2hGcN!5-poPV$f{wU*OexWfxla*4xKX(>aT54Mo?($adHirAz+@ zaqxK2cC-<->@~^E4-Kt@h8|!~cmzqvxhKqL>_cKt_<@gE9TBWqd%`7D!?`Csk(0!p za0>R?wLRfpe9L>n&u~-XLnnuS;ISt>JD(L<|M4&*wN5kEJ?vt#1?5^uu z4WI55@|Vw}F6B-AGz=Iu)gYfo-62|cKFM0;tl5`q(okdcttVNzvZfsXU+b*)@fT=6 zD&iKW|IkhS(b-wfnk%`cyTNqXpgE^GYOCQ}(oS;Ej;)4Mh^$z9AfO%R^(5S5X z(d`?!GzTyb?&wz7uIT3~x3I|FUr35odb})6wtv9q9R65F$PrUH9zy(+<8<|1n|8~; z^Fu@2(tyiD7#K;~=D_RHbkJ0$HjBjBv#NWX~{J=|uf1v{;tvDn=P2?$xOe#DgySbb` z|G?Gx%dbe8f4E8sp=N75?odnnA|oD3{4fr+oloJYzsZ(7<+9_D&xqS(CIRNZ|CDZV zLInN816v&WalJpKOP8O|^hH&SH3nLA=2Buwe3-&9D2|atNZF`Mn;+=WRHwnkU`ytP zuwWKaq&HHX#5oZivk6n5QmsDG*)dR7ok^wYEPay(=19Jcpb;v8k~l$2r$fvf%7}_& zV$Kzm*0cx=q*$6v(Q=UfI}TlByK2Z#+4JeI(tYtc0HO@uh58GoBj&jvCk~x9Q@0K$ z?(JT7;Dt;3An6&LNwW|AWo4U4DdMF>hwF{i-B~EFcUOi(cHK@mU4*(Cr2gD%9;vOJwl==nkkm%MPO4vVoq_n|>e=(_?}zb1tPY>bJ8|S3UScTD0N~zH3c1UEU8|+M4xC<%~=`U&5H;G zSxo;~FJh%mV)hKMB`DLtMw{hH=v0O#s;-RuL^K~uz7Fq2Z(Hl~jn%%*p+3f*w(l;G zv}~VUk0?X9T33+b>={k;c1(0Aj;9HkDVVisYLBcz8x{wfH3Q)WHn!v4HW*~*In4r& z$4C`Xl26z}-`ROC5g`?sEhIV5X-bxKPNTZg$?X50U#+f3qo9mun%3cXXbL`MfLnX^ z@8L|{PW48Qy=K49l9Y3C+0SD*9YXJf(+t$r?9>oy+P0`C;@0N0KWFN8Y7C`#Sk$g) z>q)3*$=CkD|28(&{$lzyZ`^7lGJK)rgXoR_pKN zA+C_SdQu->N9@aQ#7t>K7`TCF)e(>Khn4Wn3Hs2{KcB!CxsRn$qH=+cDeX{{$O*6w zJJZi<75%20GUosFY}-rwc=nWe=>ThwWfy`W*}FeD*B({gYmaO3d6VebHa=?YQ9_J3 zX4~aR@t$orUl29hRQM1bI_M{f*8Rln!~Z)^q74Q?Tc=5bldZs5E*1U{X6}-t|J}?j z11_C*j4sdI(@%Tq5O4mWo&PU;6i1`Owgz|7-zQy?iDgM* zd5#$Cp;~wQDUJzbM~@yZE;^i?KwDS=uW&MlayZKTpNErIqYGM)b~bJ`g&&ApJ4h?w zOg)^ul~O!{G(<}>@OJqul-D)?=LEhRQCH*iS!Tvs_CA7Jo72B=rXEhdMkyYgrdcBv zdn;@u>gvxn!1d4bwCh0t-M0LvQ&YvdwvAS?Jo=a|yyQD{znG-4G~BU4R4tltDR2`x zXSa8d>)LC-Ao7lN?JN?KwUNV2E`(hyd#_|2{)QGdAxDU$ zhJ<<>#NW=9b%-A%~`>TbDC~q2zEw;7rJK%%Y zvPU|JyW>iJ9H?HI#7bMTHo&Xa0ggORp-wZm&OoJRl!tCXTykCS{XlZCn*q%xi5cfZ zWZ;^WDVE*h4FgebKAQI$gpe4rA85#ey8M+uWr6+lhh|&_+-8TS9X4r6j`Vnr1^*lf zYon^DioJc-mOI#u!{-iAuO5;G;bwXA9v)i;A=I)9euHl(LD5eYNfGlxe35|^>v&o< z0+$fV?i`G~)(yHqqO3S{yel1i$Js$!ZQHa>9TzFc2eXzG8*(})yBR!7jhjb*T@Br5 z0rD4aeWXt`5yec}N+n}kVUUDOgy}sVw$a@~A$KS^%_xYU0C)1SjCiMu?qxOt9!D>t z)Gv(QYi)GZCf$!}x=rdvowRMzC&=b^Gb84YbjijHUwfu&h$7_|*reYx$%uKF5NCUe zw@r#+KK7xuLyJ?q=2-8uodQ?NE_LqT#DZ%I34zK2U$p+RIW{5o43TOTHOH_MsL!#| z*c6;|>~R#-=h%-VPRy;-`TTvvTumsu^D^@OH*;*YlfD0Pj#aZg(C65r)C*E9nqw)g zG3S_+<{+G7piXafvZaPQh7KiS!PJQk#c)9svy~X0kA?t>;h-PU1gz7}+Fx@IVim*&$!{HI5uSHrzgra5b*wafI{e^5?{g zH&MfAhxx+n6T_@l0A20$9#^NcoSnXhtrK_pJgw8;J3AeVZ)wgZQ_arI_aoSYa2H5( zt;|3nDn#lF!VbeA6kE*-2q(&Xdo9Ivdpd)12D_G_kq^v23z22;SjajUbA2*@RJv2P^69pF30{YF1N|I~NSe$OBI<~_ zl+6i-Q>Z!2IGe2dDH+R0*XHrpr;|g}eTrKz5F%sYK(*=pt9!$kD+%V=sK)-4zd8{y zuV6CDW_dkK6wgtZ!{9gS&oi*pZp5u6wTL;JZ?QQ`Cnh(Fy&$t6+bRB7w0^F@);Xz} zu3+75d%O-vod?po1mtMjLyeKnh0?+HM<0X|@7jm)a2X$s;Ew<`;o)+VanoqwO+fJB{pyfO#7$BX(1u}1F? zkv`CXV=F{_>W8(&`5C8!*2{5psl^AUx#Fb%FA|u##FoHC>^8d~f%6=!dCtRA{|>s! z;mdh=B|ON1=V8>~yXj*(Ma;o`w9hg*_!F@_wRDqX&nVk^_(QoV7*k9rUR!D!7S$}q z6dFzT_CPjg1Uq)Qf4XHu3O0PqIRTHp^26`o_+)wj?hjm+Oow(lvq2|}cH1CN%dnN) zqh=XW2BK~9CL5cv!or(7xYt~JbWf#i^VZ--_Y@+frfDRM+OagKata-C1~*JKFftkF zqnveI1e zR5jt(?Dn|Ucc?Ml-gMf3u%%`&z9HP`F@vw5Ls}jyon#09o@#tOSB0>I=e(M4yW%-J z*J6jxy0?(Hu>%Tj=Z`T3r+kdNM^FhIDqDwo_QdDOF#R@4b2;EHOolYFt5F^|PyEm^ zBFp1`LQje5k25(v?f`zd5X0x(1-&`dZNWX~)e}Tin^z5|&^S}{<#_u$V(vtSJ;4s( zdb9rRaJ|EEYso8O_UBud>m5OiL_Kk#d91>7=IR%C-aJsYIael6GmEaMs8^Il>iQV{ z*?Wv?63{uCV$L!8uz#1vsMIw^{ZP$wjLuTJWyoO$fLmWp-G&~bti(LA9 z#Od0(_vlu6%a9ei5wi(xaa{O2kkU6O*YTTn))|Ovxq05J`#a^x4a#!CfO;NnZ%{sX zJh*pmQ1-yHN;BaEdxP@T6zU;&_941-GOmoPdu^>G+ufEd1naQH*luwTU!4k)>{`*1 z5#LXZF&-wrHf#yxeZF;#2mf(Ij0agIY})=eFvbI*(YS)PY zaUWEWJC$)Hed@s2cF`w()*k-^u?cU6Nqy>WVn;sY;(0gnAC9=eQf0O`2(8&7amnYg zq{sK2^mUpvWE3rS>2G7HE_qtoiykN5tW`TUYYp>7eE2-d(t51YQ&?=ovv#;4llCB@ z#4(C@CWJVa?sJQy;H|ETW2h2`>XaHeA&vhwV)8NbmNYnGdUAn>H1q@fj=hU0FXNUv zD?J^D5mIj^1$mNgv1zk33{~x%98|?EcBY8$v`Mi`?O`pPh13IWThnK`G+zGjGkCEz zQM1?7;ZzI@*s4VD=n)I~n~3?h4y9^H-XhL%Uvk|6gd6pCgxZTrIzCH$!Z!2roY1K1 zI}Iaq;+Vj@nR#OZ|IVC{8Q7oa51n=+lE>!^_z^56n$H}8wl@CQz2f*GA0{1Ng?{3I zAN|?FtiV4rJNoSOS8tB9?+|3e+CY7Z7 zUw?j;z^@YcRRX_C;8zL!FC`FX(5lAyqo-sQ&n&Dgtw@<$K4)f0X>m&FoH^GN&MGdP zkusxXUPWP9QSsR+C(k_87+XAhdU1Ko?40766)6*oOXn1oR9v4jp|Jd_;)=6VjFfRD zSIzRu$fwLn^lQSb;)+6CjIJy%FD|P{$t|pyg(hblN-6UTD=N#ufiZq=aq$db&YU@O zi{@085pn*RUtCl%r~K@*3&s|d7nWUBTu?NtxagX*Qwj>oQc|y*RZ=u7rDR^p$v0FE zNI7>@O2w>_d8eH_ujGc})B&z+L#I?+ScPJrqsn>T zcAjB`QEg{t@@ZKUemLQ~^8_9u>Q&9mkoRGMM~ZZ#ZG)h5ZpIn>^A_mvPlkX=5)&m3 z6XotM%-Hi4e#*|un8`mE%6z}L?>|M}r%TM2cwxrtTj{62pffK^q*rCidebER%S5@- zD5MtEiz~{nr@Hi`<)^#zL<#3_t^AO)K#y3;DleH2nuR50**d);XCPnCbG0{gXy){J zs8&?rCgN<;ai_PRuIjrQi95RcImviGc{&Wk{==|?jq4tVcXU($j{znQNIdIAG=s%t<)8B5)7}U|R1Nc2KKE*Ij#Swviz(!yea48N=%mA7=rLqXv4qORL zOhf;H$-t}=ARpii;BCM~z~_MRC!##CAF%%rlmlh~R|4k(>w%8}cL9&Wv*g5+3}YWK z6&O0Jqazo1A8-cn3t)UdtozcD4}1Wa16&JS4ZIr9HQolc0rvx6IJ=`GAiK z^kO9Bo@yAqvFAGsxbIwyCvZX*_yyJhcL9^}MnwDo^aI!r_!BS-ICM-$M=7uzxCHno z;A+YTHUb~H2>JrNZYmV74Zx&Q(80Vq8CVZY2hz7Z@`3S~XEy?~fWu}(?!b$Hi-4uT zmB2;7df;QgUBIt^@%WC>nPrd{@CjfR@VGgs54;Pw2>1bTC9n-x59~b`^?|1X<1t@z zfc=0Afc2PwxXR?Z9MwwEIh7I#sPQ~Z~<^Aa5?ZX;5y(s z;11w+;C|qjz%b_7jg{aZ_$)9U^XrNEunWM~fH}Y~fu+DhuR}S^qZ5Jgm^UMV{eTmJ zD}klJdf*b^F5m;e8JI6SfQx{=7XUFoQh_Uh=K|}2mjHJGmjX*MAASNZ0rtU8SqA1s zKj1Xrm%u9E_rMjvvu^~XqbtOTY3222NDv;=$uP2eJ6N(lW2P6pNk7XxPmd+zm_~W*E84F;2k8fRll* z0dEBE06qZh{YUT(JOQ`^m=4?zycT%OaQHvqNZ=R1$-uyUkQeZM;40w3_ruNsF9+@h zE&=v96a4}X0`36j02?2IJpt|oE(ON_3F8Fp2Yeei5x5Un4D53j>=JMo@cb2M7g!3s z5qJ~u0pPp9b-=+7gKuC4a6hmTcuYF{18^kp1>j`hL4QVlV1M8Pzgn3xDWU& zu+K>F0UQSG_9W^9#{nyVi-Ajl%Yn}U*FBAX1A9D!eglsK9y1E`fLXvDz!|_{YcSrx z3xF$uzXR3-p8)Ox8h^$7I2Zi@_5)@Bvw+KiGk|TtMZlAvMSb8%U_G!HxC{6!F#bHu z4`4sw@Baq50Y3ni0#AJo^9z^{TmxJMd>i;Na3Am|V4n=k>*vvLU{sf!>%wG$>f!7090-pxf1Dk-mfDJEUyw8XH z*1;|SM+5!92Y|DH`+!S;$Gwd42Ic~{0*ipVftA1>qY-xk(||qKV}1jV2hIhCfJ=d! zfX@N@Y{2{m_5-#9Cj*nS;2(hLz=SaTCU6{Z0dOX8Iq-I19dI463HSxD9hkTg^|K)_ zU^;LdFdtY5TmW1OTn=mpt^*#n333A-3)~M30#hz9jOT$FzzA>}aQJ4(4R|$hC9odY z0Q>@I0^hAizb}N{eg*vo76EgC>wt5CZvbn7{kNdsz+B+lzyjbt;GMueev}6e0}hR# zUEl;@6)>v-?E-6o^}sKHCh*u-F8CVKD^finZFdeuWI32hZxE#0} zxF6W#BGCB<<~ML0Fb8-euoU!S^?~KUX~5Tj zRlps<6~JC^p+4{wU^DPmpmC{TtOlk4{{_qd`rbx;;1b{>U;}U^@LOO#@Yr`S&w%Fw z<8v|oz<$7`z%1aqz!|{7@1j011Go}c39JVOfxCcT0OK#iJbe%KfoB7=fOCN}fa`#Z zfO~-}fk!l^&Uv0S`?~hpYhPvt;gN4b-w{?KT#N8tgfAl8i*OghoVTDiRgP1N za2Uc15LO_33}FkxcMvW^*z;}NkFX5kiwGMK?n1Z*Va_=ie-REtxD8xA4hoEyU<&N zzel(S;a?CAJP-cWHjJkTOAyXLcrL<42rovs0^#!rHz3@Ba4W*Rzd~=Op{!o`FmT#2yP-*7*|qY!RII3J;NKJ*0PV1&i*q1_PPfUpMPrwErK?Du#0 zF$l{LZbEng!W{?~BJ4RG7YOSR)*)Pta4Etq2v;L~2jM1!|3bI}Va@xn zQx{-o9$_KEjR>m{?m(D8_!YwC2&+Coy&yjeMWc`!nY9SBiw^<3c`UGqJ0pKL3lI583=oSjCw=(9KzKIUqiSF z;Vy(b5cc^8%6$>+FTx=RS0F4$c+M{58({+Ba)ccS*C9ONpGX(s7=(KePDVH|3Vla7 z2H~#}&Oo>W;Ua{+KS6sVJR0G8gv|)IBHWD7nTd8mn2T`0ztG+YPewQs;Z+EiAp8l! zRR~`}xDnxd2)85r&TjP67}7;J7-1{I5`;?;)*#%5a4Et)2zMfE_&3^R7TVw8D`VkQ zCu4q2#^Js9>A5U}@qwVW?%CUUGKrMzlS9E^{42!2)t~R}%*n(beR3xB>3?S5{pR&t z?3_N}loN&z9t2dyi)L_^eE~TFrqug(xycniE{`($36#Ov6 z|0|Qvd{7Bc{>s5`N|FBt@K1w3+Pr_77k>x%4d4$o`NAfPWJF z8Rq?$di+lC+fwko(H_0d@9bj}@fWHg;4j=y)mtO;Z4)pVWAAhIIZvnp>{M$bM6_?)$ z{^76ocJB4@|91J_+32r(_jbhlce?RKw1pMumBj%N( z1pKyr!|$&Fza015^oH`e0(R*c+0pFAb{qWtDA@(K6A$)?GTu6L3% z#)(&uUPFrV>=vHJ6E}{`yWRTew-4qKxc?0w|B}lWf`53wP97I^9%{Y%r~<$4yzu%+ zq~VvR;n#tmh4gKDMfF5>j(Am1tIzPt7^tT`i09^zc&Ob6Lcf0ueyCXw)m}NrfWI>Z zKLh*&;OCq7XEwX_xCnftcW37~lV9M)zXJSm;1`*EW}AEedhlz`4Y&7ifnNpQX76(m z=N|C)f{&Z=Qym#TL+-v96Of0nIw%G|6nudhN4-~unczfj(66NE#Kt7)J@=JE^LCC#Ia)%gl7-ut|^W@%w+zj-QCrK{DkfU;~@yfLm`T7`g zYCfaOZrJVK`(xb!{5^=rtsBEX8w!5O{+*rA`uHbR0@N4F!4K)v*;$Ek%Dq49%nTAB zz5)Dh;ExQ^bBcc__(Q-ShQHnXRe1H&yARe|Qt(5;Z$bG^ zGVeG1uX6BjfG;-rd0zYt;J-+5e+T&c&k66xYrwArA7%@;2yg2{s{G(rBmELHf6$S+ z$RhE*abv3T(YuJLd`Fn~S9#?t2R{t?JKf|da{Q+F8^Bk9xAjlrJHX$9_)j$NH|8H} zz^?*tyFVBAYytly_*AxZ7i4-thh8_+$b3;{lKSQl*pQ9jf0~WH^ejrE`w98BOW9|n z`Fs)n8_}<`6Dp-H%6~bqJYeO7==(CqtGHG9!Cze!-o72+7p36WfNuqlB6#r|^N%gy zXMwlb*j(JQ6Z{(ob#}(g`^iRBavPCM&H>ol?}xRjpp21DA!H^(CQJ{iz~>?#bIdq0 z*ELbi zHL8yi*pY|956?n5FFeI7!&@6RFgN+$CAKcl_;mj5uTBm2ro)^9SEFv;e^K1}&e zXXiO2d!Hd&CbHu_*>cFvKc=(uUeb%ZEwam5H>gf$q7!{`Y-i`O_}gvs3%xd54E}TQ zWW!xPlNX)o{*~Y_I8L6y;%gi^jpaErTXe9^72XjD1+;Y z;_5(L51bg@rc|D_kjWd`*?A5A_R70h<%iPRfwX=C{!9FwJ;t9_=0{3Q_1PTs{W&K= z2Psd-`Q@^X^7?iWO~gMAo<5COfWO^(FxDMj1HV7UV_P31eb0d{7yzDL zh?RY&kq@o!`+My&2C{uHc22~7*&_{EV;y56j8*|;jyLl&lk1!ETL*p&_~T6eB9C7R zz6AUjljo%#W!qMRp9vnO-7By7WYq4Pz*m4D0Ndo&$642B{V=;Da%GRK9%P$xLG6Ov zIE+ocF`Vp%tTR$x`yCEn1~OrOY$5m^;42{Orj>byDh%CU1-?JlJBv*oY0z>3@d@xn z;3?nk{l-4ja`0ooquM>*SnpT|z5smKJmD4ar-47pykFLxbAk1SO(6bk{GB~#q?bnK zM7Iq6kW}t*5GY=0}2N%@Gpd?_Q?gm3u&a&tBH`?c0p>rYJkj)8Q9OJbhS^y z%b`lgJHRKvk1=_p53B*d418F9Z2`Xmd{}*D!zK_v3-M=PTIl5=lQ+R~fe(Sq8<0`$ zc99`tv|HhkSSNvutsE3b75GCg46h5aKg*ELGRP?V^Tlv4FBbc=9dZ(jE!nNe_mAzYBbw-M&<5-=_j{+hXBu)B^rv@Cdvz8-0`P z9Pz4+_QJYrJ&`sdou%g}hR(A0&0O%WfNubQ2mW^N57@ZRA@d$&!faT7M07}XXD3`8 zFOD*09@O|*0UOg3d@bng=|(;&9b->+CgPa@x%13;GI>**%CZ>zrQoOe_$jU(S_%HK zkbKbn8^EsykKXU)Q`S6*-wOUI@U}S@D2MFa7VtIrJNu4&FOEz$$P@>ikMCUr-w=Ph z^_j^AnfMa${ABQ9y1Nnlso-G_z59)G z1KYtDf*)=2E!>ure)b^8nFM~4$!C_hZ9peF7J|3gdMfh_*qtlD-%W8vhk1D*U66g# zTyPDD=PSthbdF@kd3jj|nd9T(?X?#CDDbJ`cm*=mkO|X?-Qeeg4{MKp-+^xk{#4}I zZSMrRTe1}V?o5>ThLb%RlqKsuo+nVf&Okg>b>Zg~7J)w(d{{nKfS(B7W-BQE z^}?g~d3i8=z_-9p$Ngb?vj==xNcvRHLL@u}{AT=}{Ri|QZHuVQcxgxJX9QRr{O#bw>_avtrxbsf z?>-nj-5+KjO2BUhA7&pG!T!7q{%+Ev>xTOENbCdEa|hy?Jjd>L=Yn4Yej#{YJqPT^ zi;%e&GPbs)ICgt^V*$Ml03i!cUNawro7L9(JbqIMXydSX#@z8U0VdL6BIBE^xZF5K} z#~APn!H4Pf4B^A{dJ*^z+;1xf#lHglBJg2)y&n9{;KSPCE$~ah+jN2A-;?J4f#?u) ze^@(?0e>%epFSGxI0O8v;KSN+5%`_pZRMwST!;VO0=gT@s#;?cjU1 z+UtqZ83_CE1@5oK-`N-V(=mOyp)l}8h$qZW)AOe-;KO{m2Jovx@?=1b;8?x6Ru~4+g^?JPlsi=_q~}`lkIjs)s_D@KX}u zcDf3DEqGtQ2-xZQkhu{uwzkYg8n=L7nI?|)kl6y6u=;!p{5J4m_GypsVfJYt6lFK= zxAjk|2YUWU%lt&o1zr@ppD#3`}Ny8~)WQ#B*c2Js!%(M(|6( z+w2sjLw4>i@XBBP1v(sa|1MSIF;1NbfA z;SPAbF<0yW|9kLZ?YRd0Ht^`i-u>cd<^tLRekb@{CQo{|&GSWfLFVxV;b#DHPKM0| zKgx`w$-AGPz5N&X^G!aJ4^iX-Q_tis4A=n5gKc_#Rm!H2cgV(`BOAJ!*Ug8v zJ}m!R!M~RxetJfG2lz03r)RgFMRr|M?hmW~nc&|APtmwGLFTBrfNp{9+6}%2 ze`k+EEoj?htiP178CEK>Y3IL)H&-0nGk>qC6OOYz1WI zKqjnB)`L%g57WK3z*mDu^Lu$P)<^b$Zx4wdL#9&*+p!pYJO0l885VuCZps>UX01 zAXb4Vo8s1!VNZ60-vQp%R@4sk{)P9!qpH07jWuO@FT-B&Vdbj=-}CbD_!Hpw1#gQ# z7fG&x!X62}9e-yJM~<}KWpXAckB=jcX2=|bzg^zwJFkJC1wO1DKL=k0K9x-zh(YrX z$b^-14EWV4(wG6B-j9+hjm41J4jEfrP&rqE{{nniAKw7}eehv@d@J}p;1PKBWbC;) zaNhe}5njez@JE6V9sj|9AG~e+&qb0m!QT&ls+m6ZS@B^=W(j0ogUq6!jNx~#hRm=l z!}qr~fiDM-S%g z#k+pMhvjbw_#NQKnduwPs!RmmYe~Q^W_tTrb>PQ=xAjM=pQYdn!H1>48hjb}L(KGz zXP!2JKOOvZlQ-sGJHRglAJ&(9j)5M6A8Xz(XGkf3L%`ny-qt?3;3tA#4Stb%Kk2!l z!wryet_s)T4)6oPhw0!N@F#!|(}6AE^TCJdz)tW5Dfr%)Ko18W)&@htPXr&P1Lff7 zfS+d8fuREp;O_z-rUM<|m#0X74fy-Ohv~o;@IM0|rUN^{zX3kXM)W=n>)znQ>VGKs zkHLr8fO7EJSBKkx2Jpkcht+Qf_zB=`IyMk>x(582;6vLV{Mq2q%$|)f&QI(F-vmCi z{HMd81Rq*{@K=C8(v1Hc&xX=_dlrKaYhQYwPb>J)@`GOrKD7Mc>3w0gF`w3Xw!_9< z2L1{BolR2OZ=ino3ooDa-k_Wx*y|}5_x3BsIwtr<_}dqU(U*%Lvjj3>eQg@}t5Wdu z!CwtNtS)W=e;fEp2bV5~Ob$pF9tZyd_^`hA8u%Vd!`tF>@SmqhzdsD&{1fczP#Xv3WoA zK%YVT9Q<QcrkN9L{*` z(?ce#Pv?T44n9mzi@~>m538q{;Aerq&CEmQjjms`82mfnYkfRBZj`^3;0Ir8zdslJ z2Jk-vpQ@g>L*{wNgyk{21n(&UUyS%%T`+WIF!;B?hv`ZQ_^m18uL1uu_%K~r0{(a4 zFAAhD%c|`EK_=t6a9!C1-T`mZ1**p#;Ex3#RtG&xp)26;HS>^pyW37fz~2G>d>_y2 zz7+pN@UMXnYsWh9M|OnQ@lx=ofgfzfZ}i92;KzZt)gh(73H&JVw*2LS-vPb_e5yL` zjmoqa6HqewezywLqp8GGYB~8TcCTVf}3__yyp@+VMs3 z7lRM8DZ9YW0UuVzoHMZR3f@*ms^?+g={w?|#o!NJmbwmBL8c5c zVRf(({C89E+rgg%KCI7WpXoR!f)8687!3Xt@cqp?;;F4eWhen(0Di8?(^xOh=TY4) zhW%Lr8ReT^x35p1Oy6`F;yU<8;bmP5z9)EFUZ}q5or4beu(Hy-2=}Ha3%#T8(==rv zJ2w$&sIt7-Gqfx-5ZCJ|^0Em0YawN!I$MWyUIc$T{?5K3kj@QWKi-IVCfpcaXWPLS zrQox%XmdgeelYlf;4eTvTsx3C)g2p4z@Gv( zLhz}4oK2AV0c67RxC8t%;D?6fu_qSrUH~7K$06Wf1|OEkiQs<+K9wzNfXsg&6V{JA zz<&t-R5Oq0N3>i?y1fQ`&zr*U-va)N;QexLmG0jO{!rW>7JqM4aAAu0hk`#Ad{`Zn zgC7XqHzy)HVC-MDKxS%49F)gp;QzC4_a=?N* zU`0mcrG1<&8IdRUaX#9I!F^AQB%B}8{gCK+a%7}4CHe2Z3xVCA5&3PBl2dZ^ODd5#vh7)A9f?7#mb@RR)%Z zGa`S;az4+9{3P4?VP@o`Ea$$g$Q9Ynjx6Xr3UcrQNZ+0j*^%iykQw=7rgOPuqW>`< zN+Q3`aHivrj*Q6b8O|#i7zwHLr%;8@k35%w%4TT4n#h%z&UG0#BTc)+W|AMP8uy^nKwuP3ur#^$vnZs_RM2RKh>L_W@OZpdu-9sbXXJk!V7l65Tp z{#*94jFmagH9aD4_i=vJBeJ@$^FoidWqqBydPY9)*W@3kcKmtF&2>+4*( zUt~jH=ce8fyhP%$-a~-z=pBLPU%UV5`1`H{kR4PN#(?j_0(EAd{&sf8 zhgn1L%xL83mmc~2MNhIU*tkLi%BS&A}!?}qR(u)ge9!_b#p7BWr z1pkmV%PNQhc!f!qw#r{O%7VBjL?$_LWK31`ZHHy_JwGxp<3}02Zp&~UFe{1jF)mW( z#7LIpP7aYv$sL@re@WzmjP_oaIX^OE*DdjF_-ze*TLa(Lz_&H9u> z4SZVz-`2plHSlc>{QtKGa*yG%4_M6MR<+>l)yD=**6A9g7E$qjfD1j2{(4RLq8~Ee z=XyWCL->AJ1EuTn4i4S_>1FG^=>@AqrM7e*h zzF){`f=>{9W`N&yAm>Y$Psf>akh{#HpkeyA#HZydG%mnm<98-7oj(0dm(FJ+zFw7M|<9S(}i2gk#@Vh~N_ttsI1a^*>-}^C4uZ>fe z+6$1sDUfKLwRdp-bbV{0pUCbbA(nvE^_mbGU)+~*o$qOqQS2P5OQ)~)`G9D-FJ-G2 zsViu&{9fCK?}PR>(_c~?(r5L%K=}X2?;$MyjsL$ms7I2*uw4G5Si%YkXG+*2;bIAw zNw`wNwGwWS@I?u?O1Mix=V(V=ITGedI84G~2`eO=DPfC*izQqp;YtbDO1MG77bV;( z;VucCL6W|Nxe_w^_5bg=GDF=wCJ@CLd(_e&#sbe$fK?vH+aA4m6F zKi<>P`s~N|b#y=QFX3*@f@c( zFfLLGSU7r-;W>U3>G`>$NM?O$Jyi$c3S4z@IxGJZ~gHc>S#Ob z$NM{*#Qys6!yH@x&vFL1_R=p8>n?ij#|JvaR{RK4O#Mxz$#(wP86;?&$#im@mOwp| z86%))wKZsXE@3Ad<$?}{_j!p z2Rb>@?mFEK3Log~zR#bZKZtxkk=OSBQ^ETO;@J%SF%I;U9LjWeMDaS$$bTXM(`iJ&cOMC_k&_U ztDGapGH|lsV+DU%GD6>eqN@!!f;cd4o2tKld@k2Op zt`&UIM+~TEQ1It7z;#+8s)8LNkL_^vTkGdgOdu%TxndvAmYbr$seZ1N`nf~!t3>|e zYZ=h>_FKUhy}-C`-vKaT6#r+^j|wE7VZbT=b5CGE+krBXANv=^M~M7-!F#>UfMm=0 zkKottWn7)>#GjX7qDJW!{gH7U|GmH|-I`*?pX9*#K;(C=^2=9X0JhazMnzG&+KO;42ri;IBl! z6*$!oefEH^`5ZXQMc&!Sz%;?15xnDS26X=aE%<|XF|PaL=z}=^cgh)GEAdPNPWgQ2 zT?Wv6>Y{I25Pt5P{QGFZTQT21Ff-Yoe@Em8e93}Giu^#5m%q*6WQFHALqwr25VB72 zW#U&v1fLI_@^hqR0h;PXWC&n#v6BP7Oy z4ww3@W8hN3j|WcmpLl}--QODopSXGC5048z?Q#}`daLV?g3r8_e{1;+C@RHs zzZ6LK_u+!y{sPNuefT+Ws?Xp!^*eDQ*`)>~@Opb%f2#oIs0jGGH=CC|{LxZmG z0;l{`iN5LjZx;CtVyJXGUMungU*-E@X4Um~!56*p$yRAM?lmgy56^%J@`?=U_N6B;QZ!U+dewz{yTd6gycg z@|#8e?Y}XAVyY{DFvqiK6aUtF-T?eSkuih0B0uJ8Mzy{@BY2M=F%Gk)uJ;9hD`%>|Dq>20^KfiL*%a!`KN!+@;d+TDS21| zv9~{${5V56{=HW+aERc?2!5v6VeN-608Zr!j^oQj{#t3T!@0Vhb%HOv&L96)!RP*z z@jE2l!N+s_!Eu(}iA(kH$yF?uFp>ee@o=? zQ(Y&a;FNC1X8wJu;2prJ9_mUN(EiCUfm4538SpFKka&XY28FoM)-TQiPU+@Jz3FmY zA^7L}a0Tmo|0sB{yq^On|83=+ET7Yp^BaM}Q~Wb-=HCOdI2M!`~f)A4MYr5b^Kp`pJbC)x4l<3JM!N-bS6?5+_6a432v3#+_vllqk zv)(_=5&SzCXej>PGEh$tyk78)VrO6m)pZ?kU55gx;5LOPujf1wBEMPUU((axE=RzC zQ+`T&Fg{rlIUBgL=WzxkTTY|MZ+)F{owpZ6{`yINd1n~MzwC0xwVoUf`~Zf0|4#x= z>F%m#nAUCSx>Vx%WGDYVk^_g{b4mIC^e+sw3qCZT@s2$V6bpVGaEd>;Zt$SU_X+gV zO@a@5mLt&RosWFcxc0e>;}X5or-0+1FC9_q=kbD19?O#V$PK3hr~JS8PX;i2sOtvc zx$?Ie+#&JwoWkfHsh_7Lo`Ng}w4T%Z9V!0cy7aNYsUCXEIMP=V86)x^zsJCVg4YW^ z{R#%!1iwnfBR`DbT9F^Vm_co~ZxnpfZH!0dp8pa2nbi!;68v9+XMM^*vEb7Sxm+%I?r3@O#aPd{Kl=jRl`=fBDLE|G5+eD78UU>?=AP4KGQ`M0)9 zhmGX;gY%Sf;AG$QzLjjNIMpIQ_s1O1L=K!AM1GOj!)(Eqi~K^dZ@RpFM{&CM-pGQw zf1L`P?9WoM^I9J+6#1<(ZnjJO4~Trvz_{?gB3~u?FizwPi@2U|zK{W!J9W{g-Kd_w zknwAp;ID{$a6SK@BESAQ7S!^2qdA_He`Q?zGrtym(DRH#?fE)|<)04J!-<0b;uRJ{ z^Qr4z!E4v?Z{5E1J~hh!w2h2w{ont)jQ13KBHhn9OYj5!#`5JHICleAdWiVw(sp38 z$Ul6QAKwp-8Kt{M4DF#zJ0}SqTvu!te3#@$=krd%SNw+~xJcr8Tkt;DFd)_B^n;zE zbg$UP_+=trC-}!QE?~G+*8_rI_9g$;<$4!5mG|C8#_9WlboGG0OYzVB4gZE3tE*V> zvfuJ=UEUVK8&)x{`^9ZKo4))sPlgraLRws zZr>{M@4d|OQziZn1g}`ZfX?R;#S~BSbuw_OhyE`yr}eE}@Wp@hNas>FPt{H-7zr(+EKe|)!{FfQm_5Xt4AHK?X z69>+LP#B6|pZ7dn@G`*<|AYZ)Hs>-n5c|I|P4J@baq}(E9w9;JJTcT-S32 z23D$vLH9FWA@STL_-1Jrttab&t979j8A>uouQN%0U0ROYq=1 zkhcWCTI{X%-*T%sp5Xr1Ou<_N`F~XK*Oqa{b^Y`?hvRuall!SI?+n2=ihrf;!{ve> zcm>C!>vM(R!Tr-W1pjm?%O5KB*6&VA8z<;M}CzM)7amzAuY>-hUWBm;>i{WQ_DV8~ur{0uG#sz$yNP(t&ijegvGx zJN?|m0Fi%4;tB4X{7K?@^|vfoB=Uz|!0{jQ2m?C)If9SR@ayd_1^?Mbme+c|9XREG zXrSGD&EWW-eB3YpJ;AsBfbl~(aDFU!xeTy+eR3mkivQ^EvY^(JcSQcV#~43U;@Rgy zmR~N4uiJMhaH`L7VsAA*U+|#aepv7uKH`Xu_ygS{=k_WPq5y`3O@H07CcDg7Ye>^ z6$4`gzgO`2dl}IB&@;yIZ`s56V39vhaOVLA-24k3TnG50;N>^7ysn=UXL0T??G-NkZ&NHq*{cB0og*U-#2r0w;Z&Q^JD9 zBLAkyA1(TGwBS=}SpFB{KYS_pJm8d{fBu^RU9P7EZ~Q0Y-x2u(;w-;$Cj+{FO#x2% zxmN7S9U|W@xPGo|coq|@C7#_6^KYHcFGYTHDdTMt&!AdPcg{uzbiJ(-e5ACmZm+$9 zk9(Ho@l#zRW^+BSmHDZ*+eN@B|Gz^&pzD=P4le{w^)vou{;m7bt%83ccCwyn=dXe< zlX@!_e0&|ppSy2{LQqU~RRX8@zj}~=>-v03@Z+Ulz)e-xClb%+r}A$xH_msE0gC7R zKQpfDr&jQmC5)fQ0lwSH^5s8Z;3mOu7ksnWbA4WV030ogJp#L-IVvgt1tsIZm!{vep&l_w4PV)=>++L34|2^RPUV&7Q3B9L$ZePKu z3}en1!Eb+_aeePH;8fnH&tkls1LskZulbw-tyjGpIsV`|>O$Z;PKiPVrz<@9eCCyc z2mRr@B>ro}4(K>P6Fj(1l?O%DGG@Akz*T#_z^LwbO9jvPE8~;oruBjc&)d+)RVbb> z#2!u)`4P>G_xOZ?g9X1@@V|&(I#lqd1P`tUz7L$*S3j4k$C3S7IR4FRID)|v&nUsK zmHwj3b)(=@KVU&!C%*-*|CT6JuvOv7=aDil;dE!b!_p_nO@jnK>+cM}jZxP;!T0`+ zf9w3b4V?69%=wI?`P6kpE62a)7yMiI-<5(N^`0Mp2ROy^S_$J4IGutA$M<7kNU6PM zz0dMGKQ{_~*J{RfKYb_!-vXS{-6jL_M83`0A@XO+ym+qQqZ6F&_a0(EmurdOr*$%p z=2q7>!F!2a)$Lo<&hZ4#V=n+s`3df`-y!nB{hiH9UJ^5ccYz;Z{MLUSf`U-JZMl;X z4D0GTPjIJ$e~%FSdcjxzi-98re_HUMpYxgEy=C65%X`c`PIu?;If9WA&m7?7SL^4N zb^IM7-+Dg_9w_pE1Wxtyeb`01?%}}sMC2#_kb&m}KV&|qn|O(Vg9L97JUE`-4V>a1 zc{U4f%i!=uk*|A;f0s)pB-m1s90?j0YGU zE#%LXe2x=br+r!Ew`^iTtyd>5;&#{1g&!mFQ~{@a2KTk+0H=DJwv7dKd4DSSibojV zEb)9I_)n$XVcyks$@e*);BynJ1Ro&w;J0!AFQaKSc09 z3O@HK2F?+D;9`z{+4T%e5xhk34Pptv{aur+NrJS5+eF`|`C%C`7Rq)$l9Kku69PX8P z^!p)neonfQ^;W+pLD%OQz)3%E_>}LzNb<8p@I!Vop!4}B!51xNT-(Wa1;1<;Q&{jQ zk>4zM@Z8{T;N<7%_gWN*eE+LC-Jd?nK%U^0z$yNM;SBW8=I{!U5BlLx3*PHNmb+Wx zDS+Qk^?#t8d(?WkOzH0kK8jinS+Fk3_MS>^Ru)OZ4KLxIJfEoV(evyA+qhEfz zl27*224BnRZheO3DTH?zD9SI$|27w%wOk6(Wg{DDr!i#c%0mvKCsKlkGg1E>67e>&r@ ziu`9Hf6BWIGzmWLM;uRZ{&KtE&G6A9Q)o5`6KUEO?^G-zxY64>F+j zcHf&go=;$h=+gabgy7EK86Uxc(-Q)@mgfa75&61LSy1Qa9>H%GebD%S1P?yvG7)+} z?YsJNjz{ZfwcsyGe#T0Eo)A3fpMN3vwg*^H>uuhT?fs7C2|8~QwF+(nPWf4h{L*y{ z2hMX!KDm8+L7#F(#ta4nr+CiW!{`VhW5DV8O8p)YeNU6fZ~f3O|AycTA7NbUL*Jip z{N+;58lNioqhe1^kOZy~yyiIuw7uFS_`vOq>weMm7S`wBy4=aYsa(N*mo=OCHT@31WIptPP_ej_ex{B5Rjx$^Evc(J>BzOyO%1>}T_Ey1z&(l3B@#La^(>0L; z=N-ZId$M#p?iGB6*llem55JAm4W0`cD|pZksRK^!wet_0V2PyrhTt{NGca24BUZ5d zo1zaR1z#+9$(;;nJ^8iZnO`w}u*mOsJLfa_e9*DLDL+B~VWHq--{%O9mUwnZJTEje zaK=6yelGaGPvPG~MgG7$XkLG~le3Z)BwO%9fK$4|WS`;*!7mkja$x`TCBYwhl?8P_ z8uc?SS8yL^25^eM=wB>9TjIZ6@ZkEu?*$+FCl(wf@&~Tuc!KkbQv~1o3JdD|%n>|k z-Y58R;_t2F+nl~=KgwsN%ty`@{A|HLdY6F$!EYA4&piy(WpVh5;1~Xlf9rl!a2LnF z68;oj8gCK2<^wIua31=B$k#}_==_wd;&ivdKc(vs4x9vVisu9wC?*KrA@Yr1GN9x6oyb2v zj`7M24!4Q?r$6A|hjQTT5xm!H42aosCZIj29%{Z|e2U25B=|#8&(j6}hv32IERMRD z<2hH#rR(Pm!SDVzM=)99IS=`zeXE&wa>jcKzDVTP!fw%3tp3OMDFk2rGy~c`AMta0 z`xXMHas{9FpCfp1yn8_639bXYDe^lc-BTq$d8;Yi8Q+8AsOx)z z2gl{L5>N1)-X_7vl<@spZ$FWEg5zDmeVp#ErJw5j*9(5@FE}1umWKo%CgZ7e8|Ndz z`@!DRbub6csrPgI!E+{;11EhRbP)?eZPfLU$mee3-$jD|L-5C?ztjj`i2PB#ZC=WN zPIoqNia)q7|3i_VEAjM|c%B#eo8t@|EBGrS|MCkAoFMpDBEM}21A7HOY7OZvYD*pn z$QC>gIOVhS0S0uxs{l^& z#z#o}R{*DUpS_R)o$lQtf2`D}&gb(Y-@lUOXGS>uOyqa`n13I~fpgr0obDNc^^gYO zly2~S3)hMK3s-Oi+CJPPcyPV?1Hq?0$MRY~Pk)HhJrN;Y6&yGXg75f>fx&`r7Cbnw zIczP*GeG)I+xf|YuYZT}8j=4I zaH_Z9bEeM<9@L-AhdKU=*Es^+PbUjray#RFCH^}FANLXi1%m$__|ce0^cO#;r{GzS zaDIa4$p-=_ebetlJxt`M3Eo>eiteYs68w&xEU5e42ZH}V@^hfXGZ_vB)kAQfXpZ2) z^Vrt_r~FL)j3dzTY!^JZ?-qHK;}7nC9SfY|3BFIJLGa*vgjNY2eDBKNB>td%?)w<0 zJN*>Sr|$0~1%K|ljLUHDOaV^oX82N;B665^>VZ=}PkxmFUEWtDp5SwQJ$}XM7T2@< zuO*(rz$u>Kdfg1cGoNQcozDe=Z~h14V$Phe1mE)l|B=#P$^~x`Jowzl zOTek!gZt*6iv0Nha0KT|Jn<(u{-x62bv~Wy)znGMvDVhu zf@r)c(YnB?ZH+a?qc!b~jSFy#@hb|+gio|3mZ+Z=!&N`%8>4M1Zk6q26J;K=&fP0g)w{3yiDZHZW-zFOt3KGsmb5Wkw6qOqnLM9UeV z-^1$bo#+|mQ^t)g$1Ux%qGi#x>ehI?35A?6b?l_lXzApVXcWJE#jNoINUIeEka(s{ zm{3_-6|EXOuDld?mYhF%?4+{sxZ{k;=R`{(vLsq#^@+B!%2?Ut z(G{)DP0j61)$tJ(sGvk?Y3XRU?#e3jqi5nDz`0W^3!)WO(UO)aRl|@RqO{&!QcyaV z6C61=UX6;gB!N3sr1_(wlcKG0l`j;$E#8_a)5#f)1hFV;yb8xEmK4oltrNF#P{C*%rT+0!Ro{it%EBn=fj`ZH5k`KbYA3~-Vzc9| zCHb7Zr)7l|=(hQzX2%od&CM5&t&7KMSnnoRMx`>L^`x-6Mvc zjF(P5i*q)*r4@Qy6>Evt;PPixrCx-@In72tTQJNl2=#`NSRyuFG}Y-^jy__qtru89Zk+U*@yhm=*p*vPF7BvO5*sb7LB{YxoS{@{4O6XFnHb(! z-&9tEW`u6R&INsgkvxisAAq_kYHuPJSNY2E8l?znd$^f1(JwD!X4kGDzl*!a_-N(0 zwCxd4)_iED=Xpt;f0Lcr=7ZY$wAobQYA%gb>b9@z%BS$iAPlXt>I)UvFoqZ@*)zA! z7OXLpqWwz?M!_pD$a&Bl-%#q38Jwpd#mCQhms*ECejZ8XOvyy7Ant(r7m&w@;k zRx}9tuJBw$)i%D4={NnQx@&c#H^M@Q%j4QA9+JwcCSfwCC%(ugO?#_ivl?g)*bQUI zV?XzhRQd83McWzA>0G)f_-lfKS8Kc$^@BO2n)nnZ7PQ0z9^LSYvJ#Y^JaTdGk!_i8 z(Q<(rCQG4xYSxT7Sc*|h&8kN5py5r_()W{5I&RX^QnK69e(7e${sw`wJFJE$t>kj5 zc`?QVHJ9j4Yq-s(+LN50*{y2oQp?%04A6diB@UC(TGCfWv{lD2yA8~JgdASeoG2Ba z+U^Df)TYRtVX=EQoZOAr#c}1{MC)rYH;>P+j<+OShsK;PaF#31q6t4NvsAh_;&Ea{ zHCR-NL4kD6Jc0ZX@X#CLCH1wUV^AWhAbZ~ZH8eclRKtFQ-QV#!SGuF=u4TQ&AAf#9 z9DOlX9mg!G`r@)Pr&1}QTJEBRQH*>{dIHlC)7plsFDL0)c~9ljc;=ES8Jhd^n& zy>J5EQ~;Uli6`Z4A{p3lsISD4mEH=Na zG2ob?slP#gMq1GB!MM(dTOf2S>bc5BhE7;)^(*t13C&FjES|R3qQm*sOnaGXmaitj zSXidj*tqCsv>>k_Z-oCQ)jg!MSD7ZOpkVAQECj}?v51tkNRi6I2aSX2Pk2@(&A?|G zg)};^dyv<|N2qDZ2r@#rX!X%`g3}FhVrEJ`bFUZF46T!jrp1D>WR+D<@hwielQ-o6 zbisyViD!z;Nkmac;X^xUa%P|iv{*R|UIE>3c-&abuto;@reqmiT~wZ?h1>Z>MqY1SK0(vCqs$EN}VfH*yAT@`a6 z_Ub3Nw5au2{8imI&z+n<467sa=f`H%&&{VDo4Jkk*nGl_B1*0%whn5WOU?O&vNDA< z?MUHAk{8Hx#X?>df!Ea306)ZUCh~`4;PzH3rP}g`D_5rUis#CA+4H>DRGv8S6 zZ#UbZ;AImHNqvu;h*CAVwbTOk$%aKs^GDRUZlqEjs>QL<$`YPTxIczZ8obGFKN4%wqU2{k5c`AQhjSH_JV89XpS`)7Fe>b3`sZ4t80>7 zMRZ3~V;E7}?YuJ6&Cw8zG76ho@!74|N>!V@v8F`XELxqG(YouK#NHMqO@L_}@b93y zMeq$e?zFoLW4f)=<9>5!_ZmEZ1o>*l_8kTfS}zLq<%o1^m#4~J7c-iYbwrQt_47*` zodmXtU2R9fdBZV81<*nC5{nV5t&1ba>>dxt%A0?cl()5wnRd))A0>}$25AP$W&qA0 zwrjhvEbVV1T~?)ytylq9^KaF_YEBVY?3E?p;7r47niR&A$Gqq)4CK0FrCd+5XVkWE zr}u2T()*;h`p!KRM9;(uSAJkNhSdxA`~&uLun^*JCtm36)_S&06O6rLvg{b!_&9;G z^Zpg?sbJB<)O~$!xMh!&WYF#0%{AUEG6$Yyi|cK3U=EhXcvp^6V=O0QalUN*Ip~AY z)&Q(iOC9oRCYO3GS~noYhN(g&);Qxx7ro)#Gje z`FokYrBZe}uM^mAhW3*cqOpn=Q)F&DEIM8vT{4||TLh)D;6zKAu3j2e#+!L3`<5Yd zTyNdH06urJcJn%I{&3B8e*?!_5YP0&7bJz}DQtxb*_xGVH%&ECSG`PYYCJO*r_&p# zfIKT4ZXT~YL+NmMstvS(sl0@y1ddr?OI?{L_kb79u#gL^_9Ox>jr{{AR|J^H5^YJEk!A-1!Zu3Os_51bdWRkLS;Ol2*dHT5i7 zxv=Oxua=bZx`=OWJikb}@yH2ZwCk&SBIz{rBg zQi)83wzQ4UCUw2FL-xSTO-Xh~1EVE3t~(5KK51Y&Uv)oBI?TmcQl>Nuvpid-`Lm~% z$rYgome39s=rC}e=qZGdK7%$&v+!YA!M19J&KIT`lcG3_jwcOb2|T+{qk5^oBLw@V zWZCWhU#Bw~H6^Z?%pwd0@`gV0B1WLC&MFaGiHdNK9Rye312r0Qpx4*s+)k>e4gREM zG&XI6O`%gyL5<;+&yPlDH^QS;>jm`0gwF(+d%D_LH2YHu(`4&P#%34~7rsGLs=QQt zdj7(DD|Ueyx6y<;26+F$Bf(4!kJZ$uBN23v9A(9BdxZ>K7LAqYw2m4(Yh7=5wKx~)b7{>x|%u>TNlUNvLW6?k9^SieE)K)+Zwjv+Ls%f9(%Qn zY>|2-J)Yu880zUCt_`*FoZJ-lB%qDb9o2?Ndm_m%wq_s@1$VTTdUgKCdV@X3|92|m zn||h#sjb8#HzoQo6LnSpvYdZ2vFn}_YfRD-C58~}`uKbce|qMrBT6kvlhgGZLmhN$ zcs<@!Cd@17oQ8L--t`%h*5-ePG;z{R3)cO;bfHPk3EV(KyFqq~mrQIt|1#w6sYC+SXlK^PQA(p98{45BNW=cvhyl)@)j- zT$EfMMuZ^=nS=QgOtW5|Vy7y97z&AAp!WM|gFEFuRX~@LI~Kg~Nzt}>u@<$fj5EaY zGzCo=j4HMo9GbVIz=3l^Sm411jI!|NgREZ1wfP155OjW_+RdI?-!%J-*5>vWBMYK{ zTw;sQ87M04zO-Xfr5IQtV`d}+g=_h4}zpw*T(_E(?w163B< zE@{=ioOi|&+S%n5;PAD7YgV*96w84T8;X_wk&57LYMs`-EnQ~qtz#@-c}E~pZLeCR z@k&V(6e(7>Hd~F(n!FtIBIe*@)_Q5e_sotolXrWH+`7Hn z)qKl_wo1509pumtWGjbSxs@RPl3m}j7G@>~P6>dhu(4Xef8hV6Kc>E-I4lS-}p z&7fDFtP0>4McpUA0z*GWl5T*~OB(tif&UMd45&5ur50+Z8fPlWGcdY|WuVm6VT@I& z&vRJ&hf{_|n4d10JQJh2Is3I<@c!HNV;Vnmala^7SvQ)OPePl)Yk2s>~ z(>zI`l_hY_vMWx5zEyX3`+y}<+S74YP5f^NNnR$aOf=wyMX>zUbuqkrieF$u|ebDkB1>R{3uS@eSu6_0IUMK67eZ~{e($L*LEa${#wP8IvI(z>7 zXiL1ct(l%XODu@a9Ts>X#h#GeQiwaKP8+MG2HT`8m2$Y<%64!>SLzgGDSu@8qat42 zCYc~w`l)P*%kfD=bzQrotpO$V^-hO*M>h0Sj~7_^Z64S$nVqP^RxHlp+k3pN?)>AM zRJU7cMmao}J~+qmFZ~x_NSe@$m&MJ)8cOLbI7PhAO-m|tXPjPkqLxB}GejdXt1{4{ zx*VuUVZ7`eTDz{6^&*?AEhqVu;V^f*(hYs-ir^VH-^d4J;M*}UH)_*anm~E27U#b| zm>4{srhF6kfTHW5_-%|i%LsbM=Db3DL;t`Rdc4MUD^YT9B02(#qwxff^yVDcoC#Q3 zn#w_5{BSIw;{15B7jNd1-ql9OHPmxGb}J@!U-}W;r%C*B0D0#JJ>LnXvLC_7SI?dp z2Xk;L$+I{dbE+3kK#AP5IL3{EV=Vp|d+HI*h$a1i7TmY@DW*1l#(0-jv8`s^s^8{_ z>UA+A_f~tNJujU%)!Rc>O9Jicx=!*25^axZ9C5icZj~$NzV(9EhrM@?n2m4E|JTt4 zQ=JRwK$-EN5IPnu>dOlYX%d)XU5fg1Xl{LjN|&>V_Ar~wA4&53(RFY1d+|{Bfvo_u z!`rJ6ngfq2{mi|9c0Jq;KHs*sk!N?T53xq)G+|JziB65TwKviO`Qyjq^?Jh`G(#5_ zxU2=xI_$XyYUj!5X6YBh?awlMmdAF|(d#os_04VS)rf^ItQ*h3Lo>tC|{nXLHTYY-)cOdb8;Vg}Hw+o~QHvEKaBlL}tY4dau#K zKBp+`=|-|gsg{=A!>kp2nAOunBPGAb0=K`bp z*NMK~LaL?yT}R6s2Gi_O1T+L4IsJr<^|nh?8T@~m&S4y=rH-wqIX(3pH-V+5C?sG(FIdW55tEC6TGKCi*rcb z;^o?SILLixih7jNA1QZNdiWU2VwhT`Uae9Ir&-O`F?vTp^(i5vECJUXiw}HTz}pBu znVv7pS;jMX!3nTU{f&gRjqn=NPB4w+JcX*>C~;N(#3~Jy;pnE8$MLuHczRhw%SJ3CFjM| z5VD&|GYGVQyGikST<3wO~r$(_OFJZ7lqnDe{1Qr5=qnDfcE?yqd$A*6WyUJBf2``ZbV=i zl=QiUbkhMdmN3uE7!>vE5j~9$`CJg4GsBnB+UPZF@**R5^Df2K0<;OkzpWPq*R;&t zj4su(VGO!e&8ZsQh?5R%abJKFUK4MK;nQt66X@w@x<04lvW_t9jObpL#*~Y`Yd0>C zkMMqCt#$l10oYOu!?llJ;2A29qk<)ZPyyS;={ezYz*y1vNhs`0ye+_-{ zRhmrr-bbWW$ZL6X*h}sE!%n4JbCu}nGj`gCc2`+LTOY;eX_afgZN0}e!Q=vTNhQC5 zMzboUUfZ#gNriFuU0}TR@mwr=>UmK#7R^upG@9&V&=|l=7Fe%x-#VFMT4?J67;UL} z)aR|#498pf_`iBBiaV;O9<93TE4W`>OyM6dU?o|ig;zFjZE$th&X%QscCrnj3of)I!C6_LL6yAV$vE>jsrJLf!gA|-R66j`^ zJpki2cgv`233;oz;nfjn4Nov|lE%NW88pYrT&G-M4W<*ivg(~qOx77yXP(J3-A(ft z6>2B2uBKkZ;Ws|ITD|k+xXpeL%zFuOs8)H?1@Sp$wZ;DkikV>Wyg@Pb9?M_tuEa;X<5zKEO!I%IAT*`m$1=+re?E10yo<6h-+tYNPb}5U_sG zk-A_PERegcuUtEgg_SFTjU zw9kNr`i*`IL+e?3z_aSOzh|OYyv7=KGCo*sU+Xxkby4=4b7<2%^#cX#s#a*H&**0_+=nWwL8uv<-I`_*9>_?g>Fu zT%z#$3rsb|LBeup@F7^OlU{uUW{38SrD!_8B1_Amty6j3TASHMhWXhju6bhLG?x+q zCWXqek+UozYZ|HCHe?ges;ciLSJT_7c-P&l9s7Ei*3a%4>C_h1YM1DlFFgryjd&VU zZI8%un$7xAZ+MvQ7)EP%zRpFHaawI7WwlqfUmN@mhh<6MFOCmxf32-7OT^YnpzM>f zd9&Mqv)6@<6f~mU)zfGGhtr~Ymp>(F&u8*btn!UnWJOibs|q^QQaJCGl*XXX)$Jdt zd~Q(4CaiA+bZr<9x}nE9eVP+;p3|G5rm*j}{%brpObRLQai~m;sBde+2dR}c?ba)+ zOzUEA6x(8!d-l_)WNn+e_^ws*#J}cKWPwL{l#V1n$l`za?$yu6{e9M?B9ATi^er=MbJ)m~$rf+P@T>JUwTHwmawnLkKgH>R}^Q z9`)`#d|0=QzO6#etKqt;KG-Gg_jMy}y6m$(J*jwU}LU#R3XyalWdX+hifnd-YORJPk`!{sokvW}u)cUo@bG z5M%z4`sAz_PjZe@KGJP3N}yUyugOy`ci7Dzi3gbQ;E{1U0P_PrjlypbZp3FXl4=o6 z`Zb3c-%~|&;EQ$~t!lP{+M63|Xpfhcj*RjL5+`Ffhh9}ecZ^Vfl_m?h(ll5FpOx@d&v;A2ZCdLI zBg1%WWwtgpY?8Z9pKh@2@=m+EVn=I=mSM;5dU-Qji>S`L_Am4y_3llB&33hDwr?pj zFi5%iN3+pnF2xs>yzUz~VPMryuV$#V5wmhlx^NIszDen}e=sqh_x9hW;_hFhI&z~H zNUeoj2&0D{f{`rsi;`^fEvk^!rpM_*N#$57|F|^Dbm-k+0b3W{~}IbYiUdA`6Ap1^dhhG z`Dx5lxz{Zw6>M3mg-+q)Jow(TyieEb8(&k~bdI~^g!&%~g-+raWkXptwPO0WRk3%1 z9l+qGJSyM+lsPF@l8{%W$uH+Y?efcc*g@}-Nen-Q2$NV=MK3Fyjn~`9TdO8vy51D8 zqOT{iv9vwn?Hi%kR`3}d)vx3TPPC@2Ia-IMD2XZbKoM#*#lD->e9*I-${>3Qnx{$( zyBzMhivD@$kli6H)jNl6LxYaOe2zBlYMQK`P#?FeqqX4L*qbvX)yY!5aNo>}F11QN z>0^n>D?(6D-Y80KHTqgkbQKe(RyJ2gOM^y*x|z@MNq#}3 zO}VXpk85;%v&K>M`a6235VlRYBB0&$8qdnWl6}|$4jMmT)O@GesIM57(L527KMZD3 zfAp1J)MW^|>jvgI7lT(>b>D}?(;2sbdY;3JC7zD?ld!MO>f>InVF^rob!@IqqOLvH zoA#b8vxEP3-W$-+kcn>BI?8`{5XIUTZ8pI@`SP_M3YG#}D_JkSdRpZwi}n>#_4bsR zwKz1caf4y-9V+e8Ou^ex=)zH8@3YPM{Jfg7Hv#3wI}@hHYVbWIdS^myOB*S5_olLB zRQR|6oQD`bpy)eWss|hE9>?>9yf*D#@lxWXRK=WY8xqP+E6V8ysc>1DbK5 z)o^vfyS=TJ-IH2I#|a)+v~_r7v#T~NaD+yGr9zEK?(6z7xteux+D~f8E7-ga=~GG` zruaKaU8)dK1^2{<7cVp7O&e7cI9}X9U-wZ=@5`B8u=2-b%4&4gj-+^{LAX|4;>6YV}fYw-pWyrI=d{i5j zF7*gse^QTUlVc^{9jBF(FvBO+Xt?BFXVOOluy|9SsBdoKPneWV!N-_u>YM1hZya;- z`}B0INt?q-i`M9>DbJb&vYxB}`g~*Hxo4dN#19vkAKL9&P1;6+;5$#r2A1;CO82ec zDLib;l$BP+X?)?QAJxLRu}&>B^QnP1$rw8CwGufn>fB2iZR|t8#x=L&`{aQMy>B@# ze?)r=UQi!bC+|w|rutN_k0h$sm%VRJ;aNSu(X%OjX}ZVNy@Ei8y*Hhw@NvBl>2%q4 zx`F{iliGAx%cJW7o2rwdWK61B0`^32QkwpSu0-1V^PYDl<7Fsiy2TEAeyqm0D-S8! zqtk{iSY=9|U}#e;>R2Nz?MhbsUEg0hIz3CZPEB8?XdK$4c4ZwAL$jBZdF)V*EhCK zyd~j)yTFy?`*^fx2a@Mi+8DYcy3y9u^0b*ex@Oq_@EM@ao^ob*5}vAu22*#l zsfItDu-hzQiY#{6?4cpgMFpIVqPF_kP3?`*YGo{aj~2MQD75_aU#XwpS{OaUH1#$u z^l6&d&Oj4W<_hwCuW+wuh$U*9TN|K|#iXYxb!&QqyW8}{kOLbI*X7!dQA zAY55=*KumUz-~p7Rm!&H<+XyD5r4;&E@7TiF#3Sa2QuSIQz)aahpbp7@62dpgBJY; zHy8Ycw(Tl-TO~#TrKhWhww%1S1&xW=EQEh}_)huX25*#L4nVE~Pnqji%`w<0)J*ybq zAb+(qB%D0;cE>#YnK!!`Kk1LQc(s#vaaT33VE^e-e+ zT^)_jua37Qq9`Md1gTh~vDQ|+SWLyC|E72-8;DY6Io4Q@v^e%zZEa3ob#r55yeZ-Q zzgEiMHL4(pcx|{$DtM)ffD-WCOH49C0asOnT&B zi%-vl^-~r@TW-He?|0e4ai+0MmVC|@jrQ1>FVYM8M(mQWPFVm-ykiL)Z316Ak9HTs z7l1?GM}A;|wd>9A4hA0Y2N{(0zg$o&CG=2h?R?_-eUvFBx?}1YpIlD{Anz>Ijy}n^ zhYBM?>{si&3=E0kNJPeggzPn+epoZ@y(hk zzY{$9(K!jzCj-Cb{Fd{?{fl1|UNgaOJHPGx#L58g-Vctx%D5 zje6METk&ZmeDlhV{}UG?(P?{L(kv4Va^jGm!wla|9@H@wOgcpZ-28)Yx=;8Mt)pJ QWbils$Jna65`bW)KSb5OV*mgE diff --git a/pathTest.cpp b/pathTest.cpp index 50a34775..de43f95c 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -59,7 +59,9 @@ int fps = 60; #define starting_point_random 1 -#define PRINT_LIVE false +// ANCHOR Printing variables + +#define PRINT_LIVE true #define GRAPH true #define FIELD_WIDTH 140.6 @@ -89,6 +91,31 @@ void printRobot(Odometry odometry, double trackWidth) { line(point->getY() * multiplier, point->getX() * multiplier, forwardPoint.getY() * multiplier, forwardPoint.getX() * multiplier); } +void printRobot(Odometry odometry, double trackWidth, double curvature) { + printRobot(odometry, trackWidth); + + setcolor(GREEN); + + double radius = 1.0/curvature; + + if (abs(radius) > 100) { + return; + } + + Vector curvatureVector(radius, odometry.getPosition()->getTheta()); + + // Make sure the radius is positive + radius = abs(radius); + + Point curvaturePoint; + curvaturePoint.operator=(odometry.getPosition()); + curvaturePoint.add(curvatureVector.getCartesian()); + + circle(curvaturePoint.getY() * multiplier, curvaturePoint.getX() * multiplier, radius * multiplier); + + setcolor(BLACK); +} + void printPath(Path path) { if (path.getPath().size() < 2) { @@ -262,16 +289,29 @@ int main() { TankPurePursuit purePursuit(&drivetrain, &odometry, 10); + double trackWidth = drivetrain.getTrackWidth(); + purePursuit.setSpeed(1.0); // Test path - Path testPath = Path(); + /* + SplinePath testPath = SplinePath(); testPath.addPoint(40, 40); testPath.addPoint(40, 64); testPath.addPoint(64, 64); - testPathIndex = purePursuit.addPath(testPath); + testPathIndex = purePursuit.addPath(testPath.getPath(0.1)); + */ + + QuadraticSplinePath quadraticSplineTestPath = QuadraticSplinePath(); + + quadraticSplineTestPath.addPoint(SplinePoint(Point(24.0, 24.0), Vector(0.0, 50.0))); + quadraticSplineTestPath.addPoint(SplinePoint(Point(70.3, 70.3), Vector(0.0, 50.0))); + quadraticSplineTestPath.addPoint(SplinePoint(Point(24, 120.3), Vector(0.0, 50.0))); + + testPathIndex = purePursuit.addPath(quadraticSplineTestPath.getPath(0.1)); + #if GRAPH int gd = DETECT, gm; @@ -283,7 +323,7 @@ int main() { delay(1000); //printPath(path); #endif - Position startingPosition(40, 40, -M_PI_2); + Position startingPosition(24, 24, 0); drivetrain.setPosition(&startingPosition); @@ -294,6 +334,8 @@ int main() { purePursuit.setEnabled(true); + double curvature = 0.1; + // Loop through paths for (int i = 0; i < purePursuit.getPaths().size(); i++) { @@ -308,6 +350,7 @@ int main() { loopcount++; odometry.update(); + //drivetrain.driveCurvature(1, (1.0 / 24.0)); purePursuit.update(); drivetrain.update(); @@ -330,7 +373,7 @@ int main() { setcolor(LIGHTGRAY); setlinestyle(SOLID_LINE, 5, 2); line(odometry.getPosition()->getY() * multiplier, odometry.getPosition()->getX() * multiplier, purePursuit.getPointData().lookaheadPoint.getY() * multiplier, purePursuit.getPointData().lookaheadPoint.getX() * multiplier); - printRobot(odometry, 15); + printRobot(odometry, 15, purePursuit.getPointData().curvature); delay(1000/fps); #endif // PRINT_LIVE @@ -344,6 +387,8 @@ int main() { } #if GRAPH + cleardevice(); + printField(); // printRobotWithLookahead(robot); @@ -362,6 +407,9 @@ int main() { setcolor(LIGHTGRAY); printPath(robotPositions); + line(odometry.getPosition()->getY() * multiplier, odometry.getPosition()->getX() * multiplier, purePursuit.getPointData().lookaheadPoint.getY() * multiplier, purePursuit.getPointData().lookaheadPoint.getX() * multiplier); + printRobot(odometry, 15, purePursuit.getPointData().curvature); + // Print loopcount std::cout << "Loopcount: " << loopcount << std::endl; diff --git a/src/chassis/abstractTankDrivetrain.cpp b/src/chassis/abstractTankDrivetrain.cpp index abf38909..6196e801 100644 --- a/src/chassis/abstractTankDrivetrain.cpp +++ b/src/chassis/abstractTankDrivetrain.cpp @@ -1,10 +1,10 @@ #include "abstractTankDrivetrain.hpp" namespace Pronounce { - AbstractTankDrivetrain::AbstractTankDrivetrain() { + AbstractTankDrivetrain::AbstractTankDrivetrain() : AbstractTankDrivetrain(0.0) { } - AbstractTankDrivetrain::AbstractTankDrivetrain(double trackWidth) { + AbstractTankDrivetrain::AbstractTankDrivetrain(double trackWidth) : AbstractDrivetrain() { this->trackWidth = trackWidth; } diff --git a/src/chassis/simTankDrivetrain.cpp b/src/chassis/simTankDrivetrain.cpp index 3c15fe51..991aab8c 100644 --- a/src/chassis/simTankDrivetrain.cpp +++ b/src/chassis/simTankDrivetrain.cpp @@ -31,7 +31,7 @@ namespace Pronounce { leftDistance += leftVelocity; rightDistance += rightVelocity; - double relativeAngle = (rightDistance - leftDistance) / this->getTrackWidth(); + double relativeAngle = (leftDistance - rightDistance) / this->getTrackWidth(); // Calculate a vector Vector localOffset(offset, relativeAngle+M_PI_2); @@ -41,8 +41,7 @@ namespace Pronounce { newPosition->add(localOffset.getCartesian()); newPosition->setTheta(relativeAngle - (angle / 2.0)); - - std::cout << "Left Velocity Target: " << leftVelocityTarget << " Right Velocity Target: " << rightVelocityTarget << std::endl; + std::cout << "X: " << newPosition->getX() << " Y: " << newPosition->getY() << " Theta: " << newPosition->getTheta() << std::endl; this->setPosition(newPosition); diff --git a/src/main.cpp b/src/main.cpp index 6f70a069..43ed66ed 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -81,8 +81,6 @@ int preAutonRun() { pros::Task flipOutTask(flipOut); - printf("Array size: %d\n", purePursuit.getPaths().size()); - return 0; } diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index 51a8269a..fbaa37d3 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -43,13 +43,20 @@ namespace Pronounce { double mappedMagnitude = clamp(map(magnitude, 0, lookahead, 0, normalizeDistance), 0.0, normalizeDistance); Vector normalizedLookaheadVector = Vector(mappedMagnitude, lookaheadVector.getAngle()); - Vector robotRelativeLookaheadVector = lookaheadVector; + Vector robotRelativeLookaheadVector(¤tPoint, &lookaheadPoint); - robotRelativeLookaheadVector.rotate(-currentPosition->getTheta()); + robotRelativeLookaheadVector.setAngle(robotRelativeLookaheadVector.getAngle() - currentPosition->getTheta()); double xDistance = robotRelativeLookaheadVector.getCartesian().getX(); double signedCurvature = (2 * xDistance) / pow(lookaheadVector.getMagnitude(), 2); + std::cout << "X Distance: " << xDistance << std::endl; + std::cout << "Y Distance: " << robotRelativeLookaheadVector.getCartesian().getY() << std::endl; + std::cout << "Angle: " << robotRelativeLookaheadVector.getAngle() << std::endl; + std::cout << "Lookahead Angle: " << lookaheadVector.getAngle() << std::endl; + std::cout << "Other Angle: " << robotRelativeLookaheadVector.getAngle() + currentPosition->getTheta() << std::endl; + std::cout << "Robot Angle: " << currentPosition->getTheta() << std::endl; + this->pointData.lookaheadPoint = lookaheadPoint; this->pointData.lookaheadVector = lookaheadVector; this->pointData.localLookaheadVector = robotRelativeLookaheadVector; diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index c5dbbca3..bb1db300 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -15,7 +15,7 @@ namespace Pronounce { void TankPurePursuit::updateDrivetrain() { - if(!this->isEnabled()) { + if (!this->isEnabled()) { return; } @@ -25,7 +25,9 @@ namespace Pronounce { PurePursuitPointData pointData = this->getPointData(); - double side = signum_c(pointData.localLookaheadVector.getCartesian().getY()); + double side = clamp(pointData.localLookaheadVector.getCartesian().getY() / this->getLookahead(), -1, 1); + + side = side < 0.3 ? 1 : side; double scalar = pointData.lookaheadVector.getMagnitude() / this->getLookahead(); @@ -39,7 +41,7 @@ namespace Pronounce { pointData.curvature = -pointData.curvature; } - drivetrain->tankSteerVelocity(speed * ((2.0 + pointData.curvature * this->drivetrain->getTrackWidth()) / 2.0), speed * ((2.0 - pointData.curvature * this->drivetrain->getTrackWidth()) / 2.0)); + drivetrain->driveCurvature(speed, pointData.curvature); } void TankPurePursuit::stop() { diff --git a/src/utils/vector.cpp b/src/utils/vector.cpp index d747bfa9..a881df9e 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector.cpp @@ -7,6 +7,10 @@ namespace Pronounce { } Vector::Vector(double magnitude, double angle) { + if (magnitude < 0) { + this->magnitude = -magnitude; + this->angle = angle + M_PI; + } this->magnitude = magnitude; this->angle = angle; } From 9ce30d1104f560a16ed9c6161b1115f2d3403d1e Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Wed, 12 Jan 2022 14:39:28 -0700 Subject: [PATCH 19/21] Quadratic spline working --- include/chassis/abstractTankDrivetrain.hpp | 3 ++- include/motionControl/purePursuit.hpp | 1 + include/utils/quadraticSplinePath.hpp | 6 ++++-- include/utils/splinePath.hpp | 12 ++++++++++++ include/utils/utils.hpp | 5 +++++ pathTest | Bin 191512 -> 0 bytes pathTest.cpp | 19 ++++++++++--------- src/chassis/simTankDrivetrain.cpp | 2 -- src/motionControl/purePursuit.cpp | 7 ------- src/motionControl/tankPurePursuit.cpp | 16 ++++++++++------ 10 files changed, 44 insertions(+), 27 deletions(-) delete mode 100755 pathTest diff --git a/include/chassis/abstractTankDrivetrain.hpp b/include/chassis/abstractTankDrivetrain.hpp index 80085e3f..1f2b0217 100644 --- a/include/chassis/abstractTankDrivetrain.hpp +++ b/include/chassis/abstractTankDrivetrain.hpp @@ -1,6 +1,7 @@ #pragma once #include "abstractDrivetrain.hpp" +#include "utils/utils.hpp" namespace Pronounce { class AbstractTankDrivetrain : public AbstractDrivetrain { @@ -22,7 +23,7 @@ namespace Pronounce { double leftSpeed = speed * (2 - curvature * trackWidth) / 2; double rightSpeed = speed * (2 + curvature * trackWidth) / 2; - double maxSpeed = std::max(leftSpeed, rightSpeed); + double maxSpeed = max(leftSpeed, rightSpeed); if (maxSpeed > speed) { double multiplier = speed / maxSpeed; diff --git a/include/motionControl/purePursuit.hpp b/include/motionControl/purePursuit.hpp index 64fb13dd..87bba47f 100644 --- a/include/motionControl/purePursuit.hpp +++ b/include/motionControl/purePursuit.hpp @@ -3,6 +3,7 @@ #include #include #include +#include #include "pid/pid.hpp" #include "utils/path.hpp" #include "utils/position.hpp" diff --git a/include/utils/quadraticSplinePath.hpp b/include/utils/quadraticSplinePath.hpp index ab682644..45f48770 100644 --- a/include/utils/quadraticSplinePath.hpp +++ b/include/utils/quadraticSplinePath.hpp @@ -21,7 +21,7 @@ namespace Pronounce Path path; for (int i = 0; i < points.size() - 1; i++) { - printf("%d\n", i); + printf("Index: %d\n", i); SplinePoint startingSplinePoint = points.at(i); SplinePoint endingSplinePoint = points.at(i + 1); @@ -35,8 +35,10 @@ namespace Pronounce currentPath.addPoint(startingControlPoint); currentPath.addPoint(endingControlPoint); currentPath.addPoint(endingPoint); + + std::cout << "current path" << currentPath.to_string() << std::endl; - path += currentPath.getPath(pointGranularity).getPath(); + path += currentPath.getPath(pointGranularity); } return path; diff --git a/include/utils/splinePath.hpp b/include/utils/splinePath.hpp index ef3cacba..6c5141df 100644 --- a/include/utils/splinePath.hpp +++ b/include/utils/splinePath.hpp @@ -3,6 +3,7 @@ #include "path.hpp" #include "pointUtil.hpp" #include +#include namespace Pronounce { /** @@ -66,6 +67,17 @@ namespace Pronounce { return points.at(i); } + std::string to_string() { + std::string str = ""; + for (int i = 0; i < points.size(); i++) { + str += points.at(i).to_string(); + if (i != points.size() - 1) { + str += ", "; + } + } + return str; + } + ~SplinePath(); }; diff --git a/include/utils/utils.hpp b/include/utils/utils.hpp index 265f39fc..bf6f5e83 100644 --- a/include/utils/utils.hpp +++ b/include/utils/utils.hpp @@ -29,7 +29,12 @@ namespace Pronounce double clamp(double value, double min, double max) { return std::min(std::max(value, min), max); } + + double max(double a, double b) { + return a > b ? a : b; + } #else + using std::max; using std::clamp; #endif // SIM diff --git a/pathTest b/pathTest deleted file mode 100755 index e1feecc3428a408133189cf7dddda22f96ac62cd..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 191512 zcmeFad3+W{@<09r2m}=qlxV!;4JsHs@xTp2^g)S6As7@4R}hp-NDvP+7~=ByY!r1- z)@#xAU_IGGH>)BKf;{n#uB$;&qOLkIxMoq;c=CI{tGj1<=9wo%-Ou-r-%EU%XS%zp zx~jUms=B9V=BlC*r*z54h?sv}BPT^zT7H14Dbx*3A9T@Ikw{@=P^1_B?i5%X&}6{zDLUrY#-nbgKB4fYKJWjn7iJ=nCD{t!;89(~8~>Do zAOE8Nw?OOD{2G0dNB%!Z>ofS9k2e0xm%oun5U)(*1%HQWc=O9X_;2Kgm6Lx;e}m(_0rjYde|dp>;BS>!!kV%=2vkQi5xzC+QegyI(+)%{?n(; zteW3{{-9&}A9K`zxw8fwAuNzD_CfSh&nS&xSQ4z$YLu~{C@izx`PykNdGwoqeQ{^) zyW?N^$C_jNC7KKk_DLB2BfK7BDfh8Nldnb(^@G#Y$Dyn+cuu4I5c=y;7Y6@B8u}-IK6M`a zw+av{POH+SG8a-5}fnSuSepl!rOx|T_^m8cq&&U74f8V1b zOg|T=>Gy^-^w+1U|5KX!8EN#eeH!?i)9}-lhX41|(BCah{W)pqPe?;Qo~C}!G<0rC z)9+}=8#a!KG<4>rso$8U{{A%mc1r_K-;KV39@ zlZM|xcl;9I_cKgbzc=fCrv~~h20Z&M)bi$Nv8y!v`~d$IXx}%I7pZau*w1(Rk?pEV~^K4sR-N_9E6qH^Lz>T+_$^a+BIR=@O_(_yB1M3L#Gztt<)t9Rt4KKz1*hC=7*ztkD<;gD zTrqDNIG8(WPDRB`fKQxTIeF5dhf-I^M9R+{HTsN!1?A6J`t_RX(bqylCVx7$=ac95ij#+;Tuv95oyxGi+edJePRMDQAzIHL@IB zLXZiHH#7!h8+a_5Q{_U(Xi)M@oG`h3!u090CXsdkol?&Y(~R^v5#~0teA0xCYGIDdZm?20*aXJMSDRbE;?uK-9RE2qyL-Z|Aw8U@81 zU9MC<^Ae@-fQE*OhJ?8}6(XMWal}zZ*jZJT<+G-g&w*i9luwya32K)K$WfEfq}j)S zX{lg3GnCcLy?9P#WYVm;kqI#BBOFCeNt4Rw>SR9P{9n(1}QG%DsYST-zrB52BloiPEulvhkfw`iCM z1C@GI&72%Lb?DIYBL@^jP8~7)!nvpuEgo)pZAKcY#rD z8Ikn=bw^t_{IB{W++tiZOy%SMl7lYYK7u~F>p+wNE-%pSN@ly!@o zsLTI&^dc-_x<;b9JiGlCWD;E>BT?o*vu-ubD?JZ|DyS z)Hj{3;G=>1zIq>`Bv9X7_d7mNKS;w*4bX+;KEG?fIFC%YWpx)@MAW)ysbP5CY&AL7ss4vmw zvOs;l-bcyO`I+Izl$UG%sYOmj;};sz)Eha1@J8RPXP$2882tt7joiU{BS)~l&EkhL z82X7<2&wkO;Hcbx4OTt(G|az7t6pyZ`R}a{DEh6bx1 zfye#VXw|cC^RLOOM__XQHCy$Jpyr=r)g$n@|Jtm2vld}vyH$_C=Ka%pCNDdBwUI2V z-fW$+ImfCuw!`{7tKME8=UeqV6Hx!_Yt`qPO8gdB^}AU0gRJ^pt@=W%-mEFv9JT6q zx8O^x`aP`rGOK=1tA4yyzn4`%)vDjes-JDu=Uesjt@?ef`f97*UN0`T>i4(cmss@& zSoO=S`h%?cuY;BCztjk&}NL!Dd^GHTy%hm(u;wO8b2;rx)WlPI@ zTeogqB4sA3TUuUq%S=$Ww5)NGn)ms@5Myrty^x6H(JOUpvH%p`D2 z%f)V)3xq8#6WlTr(=9D$xn(A#TUv&=WhSCqS_ZmhCZJnd_I1llJh!y;cFRmSx3pxq zWhRJEF zl#2u9qCk0YpnP4c zG7^n_Sh+(qKKMQqoUgyzy49HsXRq^_Abw%yb*c;JU(urTi9-cvs6OFBp#@=*piebWK=R}@cOL{^jwxB&4FKVBX z{aFGuBGz?b){=2PIQGVliXB2v$v(WOZQhX}SJd`-_LaS^-6JD1CHtH;q(Dk&D0c8C zb0HeGWS5zSLc|b40L^sB0ziBFd#u@97>zAxipHuMCr9Jm4&=5=G*;9;Fae30Dd0s2 z5RkbU1RJ%?qo+h7Q=-{dCZh3Dpms5!w-Z#rlFl3iCiGU+U@Cqm6*0M?8S(A51l=7F zmYvjWE`Xdcq^jmr8Bv{d-a$A=ug&Nn3p^D!u@H?HWM zhbhraRu~&Pp0<_Uw*gWVub_l%5zsOXy4--CDivdjmc#Ii2wMcKoC^HuUE$KpqQW$V z@8AtM4OT!HpS|7mb=dUTtz3r zH@IxCUIg6Z)@I+BSd_?Kv_If=V|*#mYCg$`PI^tx=O+nkI;fqE=4fo`eEukU3dMtu z+weuzkbE)BxjI@`C%AP*OQNxtY3Sc!T1M-ZN^QJO6joP+DIkrT*cbdrvL1Wj=C2U)1a3UxVpT@mQjpf0_S9|8>Lx4Z)A%TIU9}yw3i0 zk;Gjos4#HkmnQJUq!#3)3#JgKf-F-A#p2jHl3=^)mJ*-uvRb0sRF`zhW9z7mbns=m zjd)=3IauzR?5p2}kpUxf)lTgB@LINJU)`W;Yl-8*{#nD`pkdjXef8}cR?$6NaI&wd zhwZ9)mw}O82~%e~Olb+VuttyMffz{`;%qj>m08B9kE>D!QIA4{6m#L&|GMO}+DC*YdWsIf6){xZgfWBwdg1>Tr;9V}+{rgHLstP zYwhBb&O<2Hs4&vcA{K?iMGUAzc9aO zpm?!W^rXlyBnHHm4nirISH#6*lgxi$-kd{^^{Qod$9SE52V$+KnB0N9&l?mCIw2^HnP`yNJ{BF3Fs||=ndnW&Ub`XM-0GMVSo6;nFrQ${Io$bMJsVGfza7^U6FacTwtt#U-6PVIWZP z5?-AKw9oyAfj{DCy=vd-5^Uka+hZolB7q) zPar$Ij$=nj^*!a%NW`Wua4%ir(tli$&g;nI-U)Eqz~j_aBP z6pVO-p@W%#qoi}WY2%)k;xG?3Y?|xUDNWFj$3T!ElegMHI(zr<7Z8IWREUTLUVL*#d;Jap*-Ir;;PK+7d+d1xDnHK zvfRznVeJ~_Od1dvU;#;Ix!K#r^>5`GAyZ%_?bv5B^raJ;7#LZCHftR+vUP+Bn;M9B zo~$$iK38{idP)O&Y=tScec7EKsptS$Od6|u+iNIqa*}OGLjMY`)7f9S-92m=tXdD~TW{)O51Tmhr!;GgSPmPxZ>gMs@ z@IB8PJjJE-)b~Cs$)uth4PtrL+#T9q_OnfvGHjjv= z(AO>$*ahV6;zTkVFeaSnQB$#6SCm-b5$jsr8ZFPEIJolO6^&_0 zbb|e!LG~jy`^Gy9|Kc(!Y8E?WNzHdtA~S^|0^1N%dKda-u(D}DxS-K|?yM>*y$gkB zHk*s+AiKGcaJb*rS4F8F!^H;4O*D!i+>m_>Hq0yc)jUOI%!C?4oav*WwHGhV7zhw( z7ATs3iF!0kKy%GJA?E=MYNw%#3Zf;5p=(-u>SCepueZ6#i5f9rBx4#hScynMwsKSm zE^}L4hO=~w%XFFPqs)%O0sl%n3EGXXY>ffM=ZwJSbuf3wgw@fPof7Cax}3V)ldqB7 z6;(N!9TmN^{P7->AF-+~cV|C12~7l{@Tggr`(mw7NA${Bod>R*L*GHKDr{cO9U-Qf zR%mqRJbPngtjmol5{5yh3n{Ts@mB6ZcA%lxpe3YdN>j&otSNM*tV$u7^ggIx#=yQ% z5ED0m~f=IyIgJ)a7h@pnE#c+%?7Itd>goE0X-6w{(>_K1`5S-cLkdqE<`HTv%;xD z0WQ@+F4Z4k1BU7{52B>6cU{<*ynfqGUe9T;>cLxC(GurLmxQ_Ja&mzOl}hPPsg%GE z?tD8Jr&7Xzx?EdS3yC3XvbCV578tzm?gG;iJVc6%;Z&PIs-6zw57?o=z}!1q2I%}| z=y@H$cxb@Ig{he9LJABgsmr|!t+ptv$b}Q;+;ZzP`hlLk=arf_&0>OEx5qUiKxC2cHHf z=-jIr5(bjapkZhN{Q(=;-O+Oh3B;@XP^W3AECqFzh8p9C8pYl~>wT$yCK}JIrpHhR zwR#a%4Up{MNdMw%#;8rR1p7U2Q%8xRzL9bafOMwb16?^Mzlrj~b#x3mtBuxtmeZ2N zoj))0<4Io~r>-(?4EspA{oRssYQ}p!iCZjmMC2+P*H+B))_!%l_gyK(yeL-j2APw^ z-&5Fe0SSp>${M0xhGfyqLz7a=J7c_mqj=;!}*dps?Ks4s5T<$k%q zmEMkoLq@SrrUH&)IqCGmoJ8OEC-d@YuSiNr|?y3*bk@KCqW*Ku9{LuyeJ6v_F+rvo7bnA!EHQ6~Bf=$*>+3wYFU0 zj)|o$&ET`Ildz1>o_+?u#-@A9)+kqFnvdHknp&nCosx?|(3x)=QO>JiE<=hZ{tXnp z+U>@TVAPE&<1f!J0z?*Yqt8Z-hROmH{?_V~z1G(ScdY^blK|t4l2nVI*p9TcpD2KQ zOQ-?wW?iO}OZokK#}Fb*&yBxb?pg;B#rU5>hG55FWho^GL|1vqqHKLxlC*(>Ab9|t*>rI zjSya6{hoLEzFhK<0?=m>o#zhNh0=EccJ`qoY5p^Jn3F{-1tnQjuYVIZiIa4HdgmE< z;~lHMmZciaewT{T1&t=jVS-EnqxsioAx2Z7ZVtFc zbE(?fvo!QOO|4T#b3D=gM)NH-tVd`8ZE71v(^K~sFq*}4Ju>TNDgh;hh%KRwP+sbB z8B~R{!zg-_H+#|5fM~ruU@mPbBkE3+t&&>E)Do+BHU(7Ax#OX}P^;LNEGjpAdn2sk z%~v3K&AO?+-J^w@9Whcl&lenCa{__URc`5HIgjluHHEel^7Mt6RN@OaGt;2|qV`qQ zhLfllbsQjGEn0%TJ~xt_sa-Q~v+J%C#5mN+IrZEOnbM#K-5t;t^8F`zH<}AXIWj&FzYM8&Z*wj)4^31F z9K2~Sq>w~G!u%eVhHv8+M+va*mOByKe=HbFa|GhE=bTNjIK4bl_rN`#&IJ?ExSZ>N z4yt___%4kU)~^gK+LYFM!S^AD+|s$BXDAhICsfiyHZ4#MqZ~b>=to;a}B+`!y@;j;>ee#}WOvg08I9 z6X*@mA7q4zM$o6$)XBPVS!6w50AnMMIoXnoJ$Ii847B+4+6TYc+Wxn4%>jP z)q}r%Tun?bBh}E)k zjRhHQ@FNbh5Pu_xX6ozHvAwIC6oy#DG&OUoX=vl*+C3<8hAN6fL+gVmKFPya+LIIG z7Sz>zn^Dv@67 z-C60KXHy3DJ2i1co;ta9<+)N7jXZCoXrU|5kG|F_3XSadNQhv;sGRi>ZVjlQ+~YZ} ze;ZIvueyz62eZZd-a~bKN@~YXe%MJd zX-*s|-c^)o8(YO&hN&48YpMQw&xAqqyk~Z8HKGKbNsyMfI_m|11I|J%oKK{L_w%!B z#|e}=$|+7j@|r=#fMWQoLqbvW3^Xj&A3RT0Dk~mygmRN&s~-K0pbOpJ!D>V$Y@5o{ zSGgtslKNiD@$2-5Ihy!4pPXx&t%wvHm^grtBFSEzI`YsPHLY1_Gy8h-D{f04WI6Vz zP<}=ze(u%$xZ8)-QIF>~fzihlz3L69=C10!ACQ~A2(ah0V89=i9M1#$vtWM|z+M91aNSXp=U zEQNa)alczcX?j(7jy8p8EHEYMs#jnf#=Y_tRPF}a;MxS?j$lDsy+d`ubSJrt5 z6v8`rTe1&p!jL$`ovqt;^x6{g;`-RTXl;6iJ1D7pK6!9T^hHAA%K?h~3)q4PlJBj_ zKkBtvLFgc`@+cXO|FQa;uTY(u!;$gd& zrhy5Vf>h(T*VoOIfJcQ=rpvjsjhLF3dKVY^`35f@B4VQ;8qF#wH1DkW{*%{iNq_ko zO78+cqG>JifS~}lIjNf~yk<)Whx=(gk0m4dYTLwLZqnx-4Lo?1YM;fo(OR{8YJ=Ot zYQpna;uK#)w}4m)Us{Z@f3r`c8UpB)gj&+^Fe-zMNH0tLRkw4&^<+XfgXhT3)n5 zysvX@Ux`|o@1R}I9c0%|$slz+FA74(55+ZpOJq$d+XE|ordBH!YN(w^YWh|pw-OS> zow**2X?mZWOnTfIL6aCq^ib6JcSZ(^`SS3%3w5D^0=>&X59Yxqdvh}Ti(JY^noW<# zAEFE>$28IgG&iGl+ZP*c15l%%SOv8~YZ2!fTp5h*$iLnqyAjskI@}v~(e}k313-=S z8Bn*^D&oIj&8v~TR*(k(G9}EM$!=@b&Gzk1DyOIR8-0cWHzz#G*?m!FEv(zHJ%mP5 z)1HxiGZ(?a%2Nn*i{8$zeG?;`EaC%kk$BPVeEfp|9vRLdgYyl8BOeEGsmxPU7TriY z@grse5fu5T>Lh#k-XRh9Wbksm(IhiO*WBubQNf>FiI@c@=B~oK&Xs-4kL` zQ-fYdB5BQLY@jai?OoHT^km%{1&d-qe1Nz1RIwVq7z3m8kUTV`oWz@ibDtR67XWD2 zHXx+LHa8H;wE-DGA=9Y36PU+*FbNEDgBj#02dRNQaf3H@3<>~BItz8*doQD;ipy$FIdvH-)_gykxg*+`8Xd!Xlun@#1p zR;7^L`X!*PvM)AeV({8z^v9)Zj*&H4K!f^zu_Cv#Yb|JcrkB-TDNh z&(qijjwpv(1OfkkFHGYJ{&^bpy5TSYug*fz*(n5VN1$;LKyHM;V(`ZmLEF5MV3)5` z$;s>|JWDKZbSwLKl?mxs`h;dqM>j51cY#s|$J<)(G+p6NP)_FiZ>X+#a=w%pQu`EY zwWUaBQhC2unTWkABF5G$!8iU*btiDQ2%I@~f2&V<`C8-V9Wf}5YgP(ve>_#8Uue2A zjt6`FH;~h2^1qW;>2dn~KV9~zJEcI!t4u&c{Xp7Ucwk@)!*~OFDLayv$Ef>eFp;`P$jMIM$N*_iT1^k@bOVZ~xK^wM1Bz?XRhHtO)m05Z)QbDFRQVP6ykBwd!ZJ8#Z%{1AYVhNH z>M5t!s(-lpa@TQP_f>6od2NX&c7_m=QeX5}`n%M{W)v=~K9J`sZS@2OB&heI1zehW zvqjPwrZ!*1&CNvURQh`TFF_;|K9EJY$B&--22lFe*mqEaxjqPVjHBNj*Gtg9w}D!D zW^2?7-_r4yPXa+X^mD;(p!H3*>bUWO2U!3}=OQv%vo31wBe)~LUg^Cr-A8Hk%-2%2 zy;Qdy>9r+fM>A+-evWEHu#&n-` zg&E57b{Rn#>rxB*dj@Jfvj4&LHVx%PA}B){2sr|V@`y$5ZV$2tAf1!{1k6-JNh>-u zHDoU@>NAb2r!h^oD(M;0%`17rK+la`zzc^e!O^_<721fLiiF$UEDk$IR{gz3OB2sP z@}*pSVW3jaI39j(s3RwSU z@)tM%*5k*ABX_xq&ROB|uc}RSW zb`xKF*O#E4xYsM(C1JSxSh$NU+!Ij0dPj!XyB=0l#waRhhf&$U7^uhh1)KmBSE8L^PaQ|T87FoEfHSWhRh~$wl+zTw+ zo)&J6#(hxXj^a;HYlm96FIi)Ls>YqAaF>MPe#W@0<-Nhe-CpA!sc^@J;r_+KEwyl8 zK|OVKxWdf|!@b19-Oa+iN#lO|yy)t6{siSc!NPsVvXXN&Zc^bc3&Y)t7-QtU%fj75 z-;aZ^-Zt!#MIWmd#!t? zw%+EoMp9cBc&+b4)PO|gUhBHl)*)W&eW|Vcd##I8TQj}Z3sYM^X7p9s7?IlgoYy)a zwe>--H7B*T&THMWB1PU=UhC_rt!H_ykEgaC>9sCHtMiZhA%lA4h+5?xY;(Jb-(I$( zDfY;cwT)Pk!VgE{nZFywC-M(rN|RZUl)#9!6!HaM zxV!Utu%PPI`O4ar$c6Mq`G!|<89%y@;4YO0yzEX=j@m|2LI^hJ=Q5f-LdXF7^mEg~ z+Gel~7OI{V77U_9+rJ$lb!~(I)&ozg$^5{21qxP#TXiGTiDR%R@du<7&)uj9E-_H% zB*U^t$jZ`23Q||cW=NP%w$-7v<5x+$)YR3gzGW|PIfVnCmTPtKy z{6>fJAGBEL#^!Ys2AI6gQoK%0!|P^H>4?|surfq@DzEqN=i{}|&+BtS*5&mK&Fk6W zydJ4}JwfrhXq}Lz+&)_=+y<}j%Mvt%*Ke^}cZUE^q>D_hUib3zdN+~`103(QQg~U) zL87&pGb3N`Ns6W`nv^!#e;tDLWahc&;nubp^Q1HM?|cxv0W>&!U=uIm678&cLaLNu z?0*k@I?K-A@5PmD5q|aux&XveFyb76Y7XkewICDEJ&!+iwK<|FK6q&DRz3<-)@@)^ zCQZ#VIr@;o%7X>50EjgEuDL8OB^{usS~19OrwSb9dzxD`1n$;f(&NmV(K!~!wGM6e&3a zyIPSdQGKW>BRp5`Bz>4kl$2$JP!A(BA7o6u_!M=E?vIMPPwN_)j{H(*JC+o22tGZnrrHVW6D>pQmnnet$P{ zm&&jhn-WPA1ALP9;XOG6kaV6oTv}J^F`k5Ne-7VptOGb~^`cRi!C|_2OD~ru46RO} zfb}dqpJ(sFic-`!N4oH&{wm!oC=?HiAHWDM|Z{!Ml&BGQ zGg^wcOWA|soWI;BB4u*Uz00G6{$yBXh;C8x7-RhH4l;LoU5HsOJL>9Io$`}D#Pb!R zVdW-`IM70Dw(P6+0LTTFkJNBI4V>KgaYy-l4K_@Jy^lKtA@_jxfQVYVBziS%!!xY8 zR?)}v189KJ+%X>V!^G}TCZ^-Ijs>EX3l0Urcr)&7D!NZt}5^@tmh%aMX4n z45?S25gCzs2R8P*ufF~~`;dgQv*LTD9>3Z9E2WIyo_wX4{8_qr>vpbqh7C&n+I{TO zxcCC0DctuM=)x23UBJaRJ|eq=NL)IU8{_u)zXM!3 z5}~sqQR`E%NvqRS-uI387uq3fxkrLRjS$ahDUi)^*Tyenu!nBP_Y58N^K^4hH0$o{ zQQwFV96IVe|7Ee~0M1gec!5!O7$0%`?LtM2#^_Om?1i+{qB7w^2X~J|pn@Z6clN`~-i-c$ii68O|g$p!0jR8@V^F8_B1SjOTue-XR0KF(c`^ zk!#=fvGBw?pT7S{Tc|twg?j!B{t|clof7gKdqz!Y^`ym1w@MYy{{up2P+1sZre(LI zbLTc7IoIG1#zS~1F#1$+C`T8k$=;OC_>)e(n#(3B*zkrhw^9T5l`}Z9V&af|k9+Z0 zZpMpw9%~2r;6(PK{kmeApNBv0qFB$Ur1L0OuXS#cJ4liU*T1Ynz-qasOBmujKjKyu z+NfQ!v51Jpp@@V1i0l1`rxUSHDB=NF*tC3|5ynhUHvKKM>3u|-7K~ho?9$gAp-m3~ z%Q~vyDr7kp0j)DUH5z%Z*+&M{c)d$dY&|6vYyw8dnxG{F+s6Yl=zm6lvU{JcwYndB z_ntp+-TMy+7inbt08KWEVfeUXfKnSO`%&!OlF@LrjHF6EZVjnx_x8ztIf|_VQo$Ucd@GWng!owR2{K!0e1E91)P3x1$P$1733}> zC%O0GYsPRAaa6$tOl1kgn?T&ULH9IK)m>RQhOO2?74wc8-0DxQ#dG`ACpTV@py*RB zJn{Yazj9AyRLI*A`TnB;MeW(QCbAz-)F!f*Cakxb@!Uf2SWG_V9EtNjnCK;2Dsb}( z$6y+;W|U*)4qD~TU%w!Do&ql=IB!+(O~G>X!IAApy4r-3wV&5Xn^oTi4~zR~MGelI zOJ%(zuUz5X(4uzl_NHbV_kr<_1l;y!4=LZ((cH)242(DcPC9rrjNzi!&3}P?K?qz| zP%Iwa!Kn=MIN}xXBnD5^kfjMFfFy*z!lWUgVv7)O;{^yE2|_?|09xEY2L6Z<=e@3W z@1Sg^Gyk^=$|qzA#s(-=2?$wFW>P)^8|;sqH`sqBW5Xm1QNj)4b%4j$Z<4wOi$_{3pdeesGfi-f8vUF&n&jE=i2cq9 zLTJ3gEZZK#FoR!G$`Ne72MTk9e9vS;2QFlE)wR@LXVoJnbN<dgprq|qD(3T;x%erbL<46-wZ;NUV!(MJ}(SX855*(J}OL~ zl|kr9L1@z3R-gZcZ}rLfp;TCMenRi7<%|UT{45AfdVxMu#%MeyouN2gU5kpbPIv2f z$F+}+XKnwltTbT9g;{iJG+0gyG3Ydws9r9nHwUwEEP*(FyYmH883Inh1n*yhUs-*L4lwEG=hj5CCue0!8n!S};&@SpOgi(Xp z516fYx%q|iVbugs@%+QzF!Dq*Tr~IO^$HoH!h9GZckH+L3q5N$o*a}d*@&XpX90q7}N zdjCK42Tm5yz^TN|-pd9?6*4j7TFyuSZf1;b2lpXBx5z zT!RvxHCET?CFz`{uEAc?DZ+J)h@H{$J)9NDA!HI?$X&e~c~sBR(Kt0P>f;19E180; z`ket^1R5(ze*&&s22tZm_NS?5HoQ+DS5-<{4FYHZS?vP>IUMbegRFc2j$Luq=;!>5 zj&P{2c)88k-Cv0k0G)Kom~UvtMyP9aoOB9t-EtFp4a}>)7R;XNdI{lkaBZdK9O$I; zEfNL$Xuk9~5&E+sR}!+AN>$VKnBUmD-j$;O-z9@v1^pH$Z0!yBPBbR6+?*${mS;&lel>?Miuv=v zsB`nRB0+;bhvf3fb%ig3@Vs$0SPJpR@S9aDDbb36(*XP8Q(r)~W6o(K4bRDZV1@XM zqK3JCbla`Y>-nJYsgb}eXSpitw$*UwD_^-#x7DhlW-Y7sk^U?d{ z#`nww-yCuxJ%nlVgj>tW=NFFOI5EQQ5GLIHzZOyu&b4&L!M^l=u~kfZ5eJ*`!#LQ4 zUt9B%UevOcPGY_aT6jzgL8nrOy<14XF8ADfNY4#>cO9<6-UjKtR&|57u^}r+*77tn ztOOBD&NWMHGkx?)iEXcRHIUfWs~g-E9dY+4;>@^)k_mV5rHYdIMBjfI$N1hLyj|j~ zEDXqU30?6a(DYe(D6dqW+d{5+#`?tH<3aoc;4vv({6>`VD4Klm4kH5cVrt!)XJfC# z1V>f7r>f0YwIC(1Z;2mMpZ)PpeP5g_;L{a&B6{cZY|!m3DfgTfOL<4gN?*x&sY z-WZv#^7wN!UPtqb)-9z>w)0!`jqXUlO-Si)m{>lP5ZC41c(}rqEr_7{m{*AS6EkZN%EboIsRg z)J1qxn}K+=fM2ulVw?Be1oz6~c{B%X;QCXt2jzX8;G|M z*XFs0RQ|19nM(Ld%qIDIH9~P05NIQTIsW>SvrNOqfd=?Yg)uwO5H$_60u3cTou^&( z16?#3+<7wfK@FSwXh8F(zQn2z=$l(U2+m54BfzfQ4%+0brN^O0<7JdzMr5ehe2;3D z>XR)YF#;#2zBATX2e$kyPP|%fv2pgwyMa8d_$-Nh_XP@isA`UtZj2Xgl*ON7?XO&Z zVAXdM1Mt2`ioiI{=@iH|IzJlIy9}p*!jPQSBPdb46a-9Me2Dmri&a3>v9WtJHX5=c zw8c*0P&g~Gp^!BxS;Lwf@zp7V4qk#Y5){-jt`B`JH&$W4 zf0p{eU)_d$fJvt_?n*Rr9U)&Vm1r=C6GksRuU7D%x$ylBJcvCB$F+pQdwapDD~X#K zF;ueL`zj>MBS=8K$kmlQ=t1t@h6ftGjrNW_P|%#TdxUeMEyD%ns11tlEVXvSUweeW zX$c32ev9j}V&A$dPQDym@Z&y*7bWKP=QS8TUp-k&@rs&Ak-nB! z@_`IpWd7g4t@oM)bde>Eu!|;EQyiujJV?6rRgSuEH8AfA-#5L?4k9(=z@d91-C+x< zVlj|rh*Sg%d@~62($l8|5EPG9lQNhoEYwwco0nD5^!N%(zaF;Gl%U@btTenUiE{it z%-3Ve3YxE)bYt~@xHY7SSk-T#+7~ZUsldCrR37FuCKb%uQ#rk3e7O@Mnk=yDOdn|d zRZ8nD)m6|3W1R9jAr(5!e!RLFu13EB3`QIgR`e^fs&_%THc>g4m3YZ&P5ai$fi^%n z0r1wP_}P8wlaFhhw-cK|^*uwivWGac)=XLBz{~F@1dJu;NC|fPTI+uL()ki+_Y6?n z0?6=bHE3NyEz2s@)#Il;SxPNy(e6bVuSxKBq+LH}G7W`~VUbCEx=0$_G0&1%qR19- z0RLUBS+7YTdf`l#S4KF(d!|hp*8`C8*bq@DNf^He?>00U+wFy;=-pl%;wn5c4s#@?^HVCiCYLa3}A$zi(g@q1)r}j5u zrJIEhs3Bgo*?qn4gVaNe7HTw8_o))uT91PcdRovFt9spDd@C2+6fb=}#t%poHNm80 z2|RA8Spr{pi4em|G+HJQ0F>@Rk_l+|Ea-+=3kPNh5)uxQ@RDcoQf%>Zth%k)#QP@hSsA?0?8A9v z$Md_XmP^^&v@{fhju z%zBpXg{N^)L_sftg5QwL(3mS#M8?`<3%LVeLgEELtEnT!$taG9wM1iYjfj0jtXyCrQh>tA@@DrYFWVp5dLrdl9{~UZ zIOW%!{D}ST50Oo)X5b00H508);T*BROD@ zk^S%Eo~b+$)S9Wqf00y-0T68>ucL+CD4nnxS)$4w&{UGuT3~Qj2rgY68j{YyZX|`p zD~oSwDtQ=EvkhVlxE}7;UV#r8ZLBokSSg4kq9+tJWG`xln{sdp5Z{T+Uc|WX4Ez|I zcznmJByS0JeYfj$8(4gj*^&CD%5Siu24pa6LmXFzdZJ2K8^rA5r(uS2A9<%}zgMHN z=c8-B>BgBLb=yT_TeMJT%3VefNKz7I^vS|3>pDkY3wPc8-0kIY_bWw6pf+-6nIDPN zoXuw2aYc>#7W69Bk$~2?1f{sAjwx|@XA?BAfl4SNeoQU-Sia9dap5H+jbA`WD$>YC zb}XWHQVmhwlvGHVhEN^xQG=vo&HLS=8MG>JQ0n+4-`klwv34Vn}T+M;3H!1YXcaDQp-X!O3D|F zi07Mbr*Lz9O>?*5bvtkYo)DE7<2{Bd)NEhicG)l@K0Zsq%BECeM4VGX*p|I|kQMjaSl6(h0WtE)wPp;9>30Ul$6Dx{-#k`!Fe13 zmEb(q`8BePcsDsX4Re#E7%62P6FzZPPwXj5YzwB1k4(4YR9aeaCUx*#9=!|G&^zBp zFI97p>?}degSwk3=*d!)4ZEcY=${|pHa<$ivIGGpWVCGrZutp?3G>@JQ2d+ss`Pai z^yrHPcGLhzyt|gR-Q*8;yih}qP(>R8hccO0(!uB+3pWPx9knLHKvy*f#%+DkSJ-k? zs<~Beuqks=!+4t#17_sU{y)CZpZ)86DlEEXhG{7^x_v7>`J&rN(2Ez{f;nOV4?e}n zY)H&LSDy{zfPV_hwqkawji{83Qza*AN6DdX4`}m6$rBWLqA*J4g9+%?j*>kD*Nu{= zN-+>68&DZCyK-DB1oO-Cy-|G#*JPC(S>f&_MJPdY;}g7gME`+p;SoL86<07H5&E!bUqt_i_*O(8BuKP-2pf#( z6WJ&&OlVRgdZ-$1mSd45hppIPM9)kY(Ib>IHKP9xLRb;~3|B62ZrZs^r6=%9Ypl~HMw9!-_=lZBf6!Z zEYbYWi|DN~+R6p{ea;7Lk%V1*4&zzC=R7L7uFv^QiUFT98v>;GoDRHqSNe$h2Om)X zqS=o=V?{y}$5Op{|NY6V&ztl4(e&QDS`Zk_@J0b#cjV{p>!>}%&!x%`>iEhn7S>|_ z#fllh*fW!$P)um-nPkx!10QG8`H7nDe9Y?Oa^?hL)((m-RHw6_CY;>0GQ!=2RKR|2 zMP<-_%sQ^GS;yHaMqsz$<%5*wWcNTa#p$fk4&ZgJ%YwTN4--J|Hf-W*ll~26^5DVl zOpbcH4TGh2ouT*!kbS!izec+RiC8Cg8)nPm7ETe*KTS;8ZJ6V=-hx)=wF%&!FMv_+ zXHUD^utn=2)Oz+5{?tV1jSg(W1APso1hD0XYy3P$S;_Cm?8Fs z@<)kph4O=?+ccqkPa{$2;=HqZk*5w-Lg2-A1S+i7vG*N3YBj2+hP zyKxn+Cs`BEv!+J*8AutdD8I;`8C?W9ttdYQ&nl{rE4tZwfF0%Ifc2vMODMJcPU#ia zz#xZ(cD~`}G;#yKYqK62@&7_iYZ2BU&E9sz|BUx21Ehn||6xOw3$OGVL?bjAmInmm z$c>7iM7{fP-BHx5@2LH!N4<+J7WzB>Xw|t@<5W_B<|H2x*E3Dgbb_nKKaKUR8ap4= z-nY8&XGL$hT}f2qTHW!l#Hd#*sxADC;~a=;uK^|))y&>R$eLL?k#9|lxQqFs0XSZ7 z-#XJ-e;&F4FP;ZBt2!@#qWpbP4Tf=CNIlvEoiPa)y5|es(q<)-R4qhR%D0%$evu*p z3t!}hh9v}fy`U4^16hDw^}v1&HwmE`ZngNfZZ1*cAeQ*o{GXre8@&$cVlYw(@12J5 ztwPwuqEtQUk-#je!uAq)jj7L$fk7ScWZ~M3w?SCywr&Hf+nv5_)B$i{w&lA+K^tP0 zbSSn(ussh^aA#>jd!&+Qx6nPF6hZ_vHm?j411MZv!4@Hafy0(S+W4(P{6=hR!@stv z!(#^nQ=GxGtd=x!%0_IXWdl0zv}#h+qXfeX zoTB)f*ALU0}wU);|?0Ux8s=juBdBQ&cx# zSK$8IoAdCte*~lm)&24(Wgs!er)tqL{Xs*ZaGIq9Fl2Q7#Chiq0r_mhEpzi?FGTL(PMSmXKc?Sr{bS_ry zN#_vR+vm+%aDXrK_CWXX0`$zT8uW(!DXMoo+fh`XV=&d@`!447f(c|k*My8hZT0V< zF}R?@NeDn$JZM1SL_M=u ztF#S`pPdsu6x$NKy~2lS6v)>q*mFRjeWd|;ZcA=mC6wkl2+%x#pn2R$#f5h$FnbY> zUPM~r_(S8OuK!kwj%yawN2>M*s2)E*6)}lRA(EWg0a?5?ovZ#Bg`g3D9TDOI)*6$E z!}X}@LUiYB9qq0PoVB>tZg?>+owdS)@0-x#+u+4?Htx;g;B2f}&=#rG#~gT61G7=} zy5->DOw2cK%bq`KL!Nf#Xe)0eBFerfl@AuZ2`b!)7tvea2oL>2?oo2)4gzo!W-g48 zcW#RlAdQK|q(~GyND^TBQB*^Hvm2|yWb3cY$bCOjY7{LVrB!nC znQ-R@u&dzKI;GUE3VORMMGvwz^20(a1}^D*9h^E6#_k^uNe6 zB?S5RHum+8O4{D{2b`6Q^pRqq_uj1BM(^PPun3r`qxn;P{$ZeIN61e4>w|Gn-SyW$ z$d1A`{qzh^Yet%u)$J`_fC?Na%^;nJR`Rks3v=xF@AfC_*5LbqE_{x8Mtm0#< z=q=dcFpcR9!`dd`udfpVbajo;Bj%#Gy49@h*k2F#ydkuoqoM1W>frjP`s*Gg=(rR9 z`Z*Ys=dYjpl3ED*>u*?VOvdxqOWqmG3Pm zl1IS`>xy2{j`?piin`KQP-T4eMyVnM&JTPb%0v7^>ZDxx$82WN!+2e)_`Dw8i^6BS zWak6DC!M3EC|fE0A-O`rTMsuPYX#R{)JA@I*BLQ&k zF{rnx9C;#Mc_ES2Sy9}X92r~pc8=`p*|%8u6U4Ri_^>fAfciVX#+s`X2&3|^v91T> z{!^9d=@w?e`vn(oyQd+1j1aahN|}&b6U;!uL(E3ZKP$upk^E8dUjW{g+VW*On1!9B zD@iAO5wbc!PIaDo4uLxHogHw1C{_|s_I@LL*$>7)kV1tnYBry4V+HSlb}~w4Txdnf z3(4QMS2YW<8ypfP_vDDDu4;y>>ShSujAl$|wW^uvTh-uxAk&Y)s%ESmB{!mAN6C8s zs^(%bxPm~?>Y{p=D4CBAR?szE>Bl@)FzH&roV%)NP|B$HqU5Q5v`A=&-)S^1qudUA z`7zgv9RxdkMq@gk13C~T<;~J`F}^7IefX*-6JREg;=N|*N75E(KSy8MQBvQ0|52-& z_oDQd_Npd@iX`8sLL@Ir_HdVGGyT9{G>35nJB|jZbFWbcN`!g<` zPlX46lr)}`p$u?a_Wd74JTJ-y9ZlNxQLXCRb!&9h-h#`mwmCL&T~s$efUlhlXao<= zXp47rl>7q`pvh_TVL%LzP{QkWqoxA z-q!^-o4|e}#vSa7Ioya@?hM4(Qbh>o&X-_akNXq6Onss*A1tPNU*A^ZOdflY+{qv2 zR)7glFO;`0iBZc~Pl7j^Y0{aPPuJ$&&>ktpz;daCmD^Y@`NPt0fMJEDw7p;F@BON< z-mmCH@8OYjB``e|NEDQu&N5LdSgcp=Ut+MKlknJh3#eH#L7_xW9i5ceSWf{$MyPv{ zJwnXNIujckhuK&^F*bfU(Ta`7lfP}p#;FbD?1Cu zMw~b07QB6TEXFLeIa;?v7op@G3AO{}D}g{cyeoTgmy@Tk)0E}pn~FmTlzECccJcj~ zI|wF_eSz{0jp+r-rY^n?|4D$94qpxH@J>JGZGsu>kT%9l!ucpQP>vGsbB&J7tZPIF4+Abbr+ z>&4P4az|_M?GRq<@tm+?>5iy&-Z|OxsdwR8`_w78bnX&n!egnm{uza}Q^@*fFssEf z&HAU@UH=qzwEn?D9m^Y^A~PDS)g))TaY%GI`A`9zix-Ve9Q&~=SdT)d|AF%hR4j{)j>~txvFl4;F!&xr=3B^$&>w^^|WVnS;gv37+&_fn8p%c|N zdu9?5>haCg6a5nCF$i0Or=An`vINfML2wtCyJ_!vzRt(#IN$U=tq!Ftty&r{wS zi7D^h^Xz%7I1>a<-LSW0Q+W5J^|O-s~yD4pR^`l&-br|8y- z(%DO%$#B=?J4!LICf}ZwKWa^WDln`ePuu%&fA7bK^?qz8dJnhTi-75$MZP@vYBc+N zim|2t2YGO=>N_=!b#rR!ED8&)hlOtA9?-XZD8qjbD4$A`yF^LnvNy#X>tT*7&5D`L z{(C@qQl;(z<;(69jRL(Vo!(NEdq5W}x{a*f{94F8pgWEdL$<$WZ`K~(?1O0eQcLe0 z<8|i#$eFRbzvRm`Z511n86OO)tJt;8&dY*9f+>f4jYNilGT^^R{JAsZrj*=@Ef1oX_Mk!->i zs)+}KL;CIQ$-nV7;=s})yf`oh*E$aDjZ0^Y@DR*ymG6>#$9Fe#dl}>4TY%C*zas;r zHujHuPtqUP3Hfp=UmwTGdZe^nz1gtcy>~8$1W@FF>tl-472t5F%ZonlT$eb-p#p^O z{TV7bb(j-y$9R3w)(ntr60M1IP`lcASAj(}J-;6U(CR-d{xs2rJt(;$9UZz|znXXI zo$}vtG!O#2M&l#1^y~h3n%K_Ljd#XmtV)36`cxl;COq%yzFk3zt5$(_zqNd`0uNUl z_l&$+zH$eY>IuH}aJ1{QR5uV-cFP6zYAIr)zYfOay~u4GJAnQ(APuBdqq zUwtL$e7iPl=Iv-|zTX8F+zlmQ*)N&NbT$kCw*Njp<;}w|Ix<4qT_@iqw|PPW%-2g1 zXUrfUj_lx|ZQyBad%Wb1PcBelJun@$f?7?M)JwU1!(8C@%)1G(;znEBayE`P^k^@OAs{myq%rc^j_91f8iAgbuP6z=W@YD*=mpM zXQAjlyzvKV4|gM<9%QN~(Kgb^97X0ArrY|}xZ{E|#y7GqU?b7^P_R8RkFS)C#?HzM z#v9rUMi0^jBy@Gq*@$$jytsxFsey*p^J#EHkDVqW&A^*N4eUGqi1c!JM0x>HG&LgK zl@gJ9lM!D;+KL5tctkq2FSzJLMEVO9Y(=Ddr07MYOwjPXAH??5p%Ljuvh+WSNR`}A z2t=fr2m2-pM;XTJImlGYvSO6?mO6=1r^$XrNQ_#*hEB(*T0mR2t-Y0rEu9EiQxyT% zGVSRP=@8+t-FPU{jy3H#?}Dl7e-`IptPzy!1EjnV0dq&vzfo)v0&p6EXK_5Q;BuOx z%nqW>ck*JOb)XK)N#{irt+==fMK9X?M;h(8*heXtum16dt^@aRP^yak!`=a>Cj-}t zi$}6+FM=O{qQ_}pX|&_w>8uHf;01QFkR~o32;5HiymqF6p3lpp&)fbw)`j^z_`Cl* zU-z;*jNsnut>g6eSgXrZ&*PAIy}Mdw z)nnJnOHA>`G`>{ycQ@m+5PQ-45ia&F>;4Fc5iyAl>-H71N`0Hb|17ikqPH0knKExa zg%10r&n$K(Lt45A3G2g8$7~V5z1??elBTn8-#$vM>LOskO&#o`JSw~K*oyS_ zQ7)vC{QD^9u*$!WGK^i(E7|)fXYS^6vq~oj=i55HJ}8V>7ay_Im8IUZDEb#wMiXdu z_ry=XnstHvJ(#zX;vfvXs0VxE4Jx{0g7G7h-rn5PJIWh`j#E`h=Kw0h3kO}LD0dt8 z;iVuZod#gxte2D1x)OBx{T%xN;lS9p1A^ zA=^G8$f03aPREH#IfWK({fWxwyM)*ldO>e7%(d`a>IFdtEFsm5+l2**CED!K#d@}@(S{8<&nnaT0a)p* zH`U1;AGB2eOibfsP7A}@hLgFHQiM2}>vsAHPUcKupu@QSZ){6rm~9xpY}(7Pf6E-) zFrjB1y>QTp^ zEHCo`VE;E><~2WiKhw+9qipo!(>I&^ zHk4+5oEnC;jrnmI2PI^F%*_4?^W$`3z_xwcy2K5Z9NM}0!T!VMhcQ%N8kI#M;A3~< zFNP&gTvjR{dQATOn(|p)gx$_2Mko29jbXVdNs(iPv9K5!GKMKjhrZHDD(5B|LCA-& zH|g^*niFe{(%Inh8H~~nE~V6;7hH~#q9nW}ywt(vYdr(&$vb*Sin`-kA1QjF7cPHHwtNpeMnA%rJIrSMIxBQ8M6rdw&@c2;z1WEe zU115G&uc_fEp$4*wRgUn(19G#=f3Z1p{o3Iyr2_F;t3$^a}4$b3r`ZmHY4n;@%Hp2 z{r>!Y0NVciSlL!hI@fA{{#(nRe+Ah8jX(d$&z_lfa9P%L3nZX0z%*IoyD9$scuK*6 zRgNRXpZn*nj^8hD7np@UkM3KmpSRiX$}ADodJW^oEb`}Mm(N2>mb>I!$aBp}QsksF zRL;ufp{Hh0yK!Nc+@gRDs3{lTv5X!P;6>N)fb zAxn85V}TEJ?b_R~TYa7+xbUpU%8CDaU@bxS1na=(=*68t?aIut4ilHPhSiWeuzfx* ziviL0%t5=rFyh?>#OAXewclIGijz6rn-A>aq#9*P9|&4h8?%km0%tCPC9g08u+o^?F43%`pTY(ZNB;3oug~ zxX8nM3~OdIWwbsH67|9HdboRVyy#z{*3^?mvv0U2 z#VOK_i9!EY8d$`+p*3&-BWPzd@L;BGYN7LR*h8RY0=}My?K4@ot$CO-_(A%ZPDy8! z-{lmAxE#NYGDE{qs85|>LdojdvapnHF{Z!}EDtQmi&##%1a`fHtdBhH5GHHbk*AJ) z(6@X1C?AA)?D?RL5<63T&|rQ0K45Gcx(01JU*u^6K5y^OUFKi2Pqio<-+N$mgs#s`f7>23L-4(54d(9v+})7hv=zSk@$N>8&@ z2=GuEG4gOQD980pf`V-yfs>7=*JgWYyDKy}6#u5?-d*g;2tPqCF-NMF4-TvJgLafO@_Gxrm?t z^D}JzgA+_9`zvw^3d&NRIw8f*`sH<|PBR!}Q??bNzWqKY5HgB`kpmDOWJ$- zeZr1FQ#+vc{aZMP1BISZ%Ql?D-gpV0KN7X!7HW`{>iiN51ksLCjw)1;rD6A zXdxObNdwL#%_+G`pL&A!E(7)%8StK)XqIAUW-upx`Wb8uL0Ggl$BXhXIB<11UL+Z9 z(wT$))zKnU>!U^IPO*;`orJt7c(mvYK&EBZf<229x{`;Byc|sqSdFSk=Y;gJMdm9h{8;1A=}bLr_W&_d zQuotg=SbZ%@U?GDES02JbtMlF#_3Bu=df9uHzzg#+A2-dhC$is5c4 zlN>GD_h>UNO*y+z3SDR(YJ4F zzk1sl*M8*FSeV`wd;dJv!OFV^9=;Cj4CPBK@-}2d9p&8jqOd-7oF}_sN@06^8dOK? z^PN>kiBU%|Y$|Q!E6qvl^X9x8GVRrMXcQkH%=`DvUOzWP8=Y7LhiXT@VvwSpx78cC zM1Or{m&rDk7hdkHb{auPj3rz6vQQzx&1VAf(>U8 zcW!>0z(n?$U}xs2P#n!AjHq4DEt#X;LD-swp}Y+9^K$f$;N@p>*9@Mw#oaD`?t1)q z?!-g5o{=i(i|GQTxtn#8ls>=nOdv1wEdpo?^jH2Xxe_$ zJ;!GHo07fHB4|~;xpc@mBkBgf@Y_ga$mrp*H-?lBk9|30)R5SBrO~?n>rg#%M8EH$ zjx6U_pCE*+`MzuAJ_Fy*-lv-Q>VwL|VjmCL+GkU=W^G3FxOb{Pfq7<~H;(J?A?FV% zUpr;W0K31nx?j>HB+I}2`$Yr4Xy6wO{Gx$hH1LZCe$l`$8uIO? z$e%uI)<-+s6&wbr9 zXO44ld!Fxq&-c7u`kDEBu5;bLuKVYl8FE7|t;xVUik&aamO58Bxf)%7{-i@!B zP9e-YQkYW`oL#5xoKRa{UZy?Nme$O!4)WT*=9HHPYwFHBFK|hquB3Wqd7!kSy!7hx z{DDBVKlR#*%F+sdWxfCOxwFsoUwDB(SW#Jj&V}`rbIViDbjg;}Q+Y{MRZVH2vbw&! zE*Me!>?+iCV+3g(xG3_yHQ&5XIVZR1r{2fp==aIsCT{<9nCAbj@0&j(N9;CfJW1>i zyr}QHFlT^$ePGfNeX?MJV3xMKyCmnIUvpIt&Y59fqeRcw@B3XT@3RFb369EnyIEcR zw4eH1&Ceeu_Z5r(OSN6q6v@|#l1_%aAFTC)G4lQr?Z-bs?l02z9VX`7e;?O%mrMF% z1^Wy36&$VaJARtBzwa69VQ#L~_hA0mA%%4{L_L9=F|eql`szXghJW?5D}#BKWjXZ> zmxdgvPpF(VuB>KOd9dy}b+5V{_h-8`m!2`0`&AZl>ni8qqolGr&v}2w0CcD3x<4~> z*z|gCD-F7xC_|6Sk-v;=bH6K*n3Lnq-@&iH+|R(V^W)aGM1H!d=dRYaEHDi$0H^M5 zZ99m~$j@5a_VB(D%w^NO9xMavC1iPJVS*tjt9SUv+yYU0kd%z;_W=>=0 zfxEy}U@O>{Ulm`&$#X8afOGyba6OpDPuFh)3&38a2wc*&t(pR zC1AH+_y?DPo%rBx12`1i0WJU!f$xJUe#`n6oY&j3#`AG#6L<%>3ETwk20Q%J+Gh2! ztnT1`um$XP8b4`!nDT)QeCS>Vt_Bx?V|n;t71)&rOE!ZuthTm2;2bc%uVvi|_66@z zJov2QPq(Ze6%VHJG}j%|))oX0fy==cc%o|)xF2jhoAUB4hxK3& zzP_*xJe<_lb{JgRo&2V8AGiRVbRy}1uYsGv3scB9=;v|4#B(gG7)%3i2MfUcU@dr8 z&$hOuV0o{$w%y>Zz1!Ln`dik=r?s_Zfj6Dr)>aHY0?r4|>DSiQ1YUIp`2;(pav%5@ zXq{_WXP?>D<_GtJIpE~8s4uXBZ{jq9ozvRd)`9ncTfw`|X=^(KzR;ih(k<(mb2-ui zt-<6E+&7AH^JfJI=eM;T1Pj43`qd0@0eBs_3cL^8488!y^RslbM^iuGlrgj$*b0_` z-S|6)3&26(DsU{g8LS2OfE&Pgek9Z?;C?U&=7KF?894P4?gv+atH5W$&EQUO4|oua zryqA8%l+VRa5Me17Tg1_2jl6dyTDv<^Em1s+ykx$`DkHi1E~!}5}^FxVz3NcSWJ9?tHHJ47O)v?0dwi6ZD1LgSweZhNqn-u3akS+gN5pAYX%8@8A^mR}mB<*XkTy}*fW#*;F+kQU@bTmTnEkr zw}H#Sec(p0J5SZ`1P6hK!G)lI0ObO6z~mtH2o`|z!KL6TFmpEJCO8dj0dD{kvMlRe zFb&)V7Jy%aRbaw(^e6CPaD&pp9bgY02|5Ih1XBhQ?_f5#1)K^dUr)MVKG+2A1vi5o ze!+MSjs?37vaCg57I+_61g-{yVDe3r7aR(11gC;K!52Vluw|WkGvx(0g1KPgEwq#3 z!3E#~a4onKYzDIy(C*+!Ffp6?7EA-zfCXUEFBu=fGH@}t5L^e|4{ilN1P_3nZ*6N! z9zy$p>0t70^kXm;YyeBZW#HrB25>vL1H5h#`96=wCcwVn4`41h>ep>;72rH@A$SM4 z8f*r)fSc|hUGQ@-`FzGhFdgi6XIon#I1;P{F9R2Y72rBBb1~_H3&BI+S}k{oqYt4!8^~244c_gGu)iC*UA(6ZjF>0`^-*d|t$Q155)~fd$|}uogV? zKFSTA53U0nz^&jG@Br8fCgjN+cYz2$KvftC*;6`vY*liW< z4fX?Dz$?In5%do*72FNxgGmn&FQ6Y>2sVJL!L8sH(DyL+gFV57T+7M>Q^6%*KKLeB z0aiaky@Ahy>%dN{nJ2+)@F2JlOv$6af!W|La1xmODCGwI;4*MBxB;vJcYuS|(B30y zZ_p3k3g&=wA0u6GHMkJm1+E6OA1B}7WUvLi156mjcnzk4ot~h*!5_g|@WOTE8=MWU z1K$C+g8lwTzQIDUTR!V@Fbn(*SOh)-2Eh}aB;Vjg;0Ewga0mDzco;kg_8d*W`V;vE zCxXS`9pHR$1K0!(UQe8Y3&7prGSC{sdJFV}UxPVd%AdI(oC_`hmxHUo#-}JZxD{*x zJ3dXhFJ@f{rh;`~KKLeB1s((&!MF{KYv3TT8N44n06qpL7f=o`9X#h5$_-u)2Ej^j zDfl6{0Ze?Ba)UF#!{9=&=Ox6`bL1O*2P^}98_72~4O|7*f}6oDU<>#ym@w9|VxA}8 z-~ccmoCa2a+rXvZ_uzVP?+c_0X1+-O02hKi$B}PvD44Q|`2#!)oCn?vHi2uwP2fl1 zZZQ5O>bsDA9q0#FfH~lcU@>?QoDZJ*GWUZQft$b}xEuTejK7riKiC&cdWG>AoCj8b z4}%NA4d809-)8C?oC@v-uLcvxlP;JBZU+lM>s8tdyb){!o58iJaz7nm}Ma=y#`U@dfTwQdelQn21lEBmlPM3F4Xy+yfjhtk z@G!Ux?D8J>gImDeVEp^U-4x535B3Fr2j+q=gJs|k-~w>W2lN+kCAb+}5AFfK0OPM< z{SEd7r)=YX@Mf?KTnjD$zXDf*$$#N~un^n>2Eq8LjH_T@@BuIv`~s{16Sfn#U>&#` z+yHI?{T~vy;Dun~mG}YEz+1rru+I+S7F-B6f~WnJxCO5Pw}Q8T2f)o>@-)^DU^@6C zSO|9ci18Vm1ug{}!S&$x;5KmR$HX1D3QP%5Utl(P2%H3V+DW~G>%e8|{U_8rSPSk@ zJa`D)2Bs8KUN9RRzKi?8CU73u=~LE?;AC(kxCz`1?gFh6%Q}8H;{|v+m;>g5#o*)M zeDFVD6PWoK;{{j;?gsAxt?A5PpdWl5%mMp3* z9^4M@0Pp+<`7S3;K|i<&%mH_R#o*W$;tlNh1^EX1fz9BB;C^sDm^_1a-A8?cjo>73 z71#g{|C0Iwi@;6b3~)Et09rFG>jTgaTKh>C>cx;5KkE*#8^q8!Q03UCnw9oCLNJ<`=lrpBvvDYTdw=U{& z-dO|s_JOti(v7X%TUy)f8x_f=(hKr$2YkA^UoMqaBmeefwzYLvTwYT0t+69IcesQM z@mA?;`S%g}@nA?F6V{ud-$wU4^~=Nhe$iDKLib-0))OiB6v{i&ssAFZr=dTI|EHaL z?Blk9%3lHc=mBkQe~-|2hV&}*q%7hnLVqBnH=-{=_bfm9LiFCw`zM9-*Nnah{Y0le zHmvVQzZugIP^ZpycdK&uLcJu=DZRqvR`(v-N9jN-LLQfs&tv902 zYe!#;z7^dof6eHJ(7oz!Kl<0`UiFt4XITf(z3MLwy#>9GvwV*FD?s0eezsGe9SeR)W4M)$wj+SU@Ge;U&Fqqm^1iO_!+ z(i7vEM~MGVBJ^z`Jq5cx3xy~ukv}2e@a*1ors^y zX2q08<+EdaD4%8cDc<4jXDH*+ChBE2@fknL<)Y1{q*c;S<{C^_oM26DEjITqnAtRQ_%~!KU%!2 zd}J{mE#&?cDj$DfvuNs1m1nWehq9ZBT`P7htF8FOE<4Bk*i3qv9`&s9vmd>ga;Nb+ zlvZiDyotoy4)jG%J@zKsK;55)KAiG+jSmIr?~~895%>Q-bbl54H1hXRg#KPgZ$wY| ztE@LnUChw=v)iBeXd?Y5;;9Faq2q`=_Fxb%FPMIuE@MdbIh}kI&`kebLLE{#6}0 z)^wY&xsW_~)xmD`G3c32A9_l)=N#);`WJe>Q@=4>MnC!jbXqAKZ?SoyGUlK^iS89k z#ptgMZEL$b;{HXU`{$#dM;X1=EKTU??bP8W^wf6r-RS;ybSsfQ=b`(_vmZSfJz`C# z+MqmKN4eM(V{?MDj0Iu641FTHR~Z+e7qpXyRp`~kX~5}U<>AtB8e6bggU$I)o4T;x zg8mx1R~#gCX6!@HbKXBMe19r>D|)oC+|NDv=uNcq66gIYj|;*+s<26-oCBRURa#f$ zLN4QyiuWIQ9UnI)9B<0c7hyl^@pBM6ubA6*6#Za3y2?j0`RGGg-&6UxV{~LbUJ2({ zjib%jZC7@`aM&>($G#f2>&ZAXmp<~Wva4{|sdB9im#Z;}^WKl5kN;}CS&QBi{UKh5 z#{O8x`WJmA`YRFovvvaN{{849KW=TC!2BP&KW}fmlGpi`-?{OyV1R3bS?VB==~z{e@ZC-&FE{1i<8J}sC{T!!W7S^lKb4cH79B4!z)J|Nl6`f*)%jeiXG^5WW z{amL`jLjhncKf3@wUfWZ<8=8>ao%4P&VL%Z8p|(o>dHCqmHz_tz39>Ux6-T7t4RNB z=lzcTVIz72dbIof+_M(_4)pfM;;q>1!sf5eG-9{fnN)pyHRIqiVpOd`;`cGyIoD7p z>opYBWTkW^R(Yn4p~AlG_=md(u0S#7zSt4AZ@c{HJt@Ce`>MZD)wLbH5j_Fjt9{p^ zA3DD+>KN@OOU>xR$zO>xe`<`Gpxa2<9KdEiHbrh5M;vuKo^xDmyy74W{VDQsmD5M8 z-UzCCC_=Y9%Bk8Qjd7?N|Lb@iKZj^Fbvddr?w0u2CY4)dSA^a7*xjn^DjjyJOby{O zZ6>`Uo-=$6yO1wsvq9UaJhfo+JvLr_Goc%M9m?cY_v&xyjYoggnMUkJI|1cCA6>PL z*ZmdfE$BJU`yFG)LUh&k8BV<-od4D6JchhIr1H2Qo7LEi za@sh~x72f;ThY~iEL4xNzX_Ew4Sg)*)149etsz}K2l@hff2ZzPCsm<0qkE0djp(nT z=R5CrtVP$Ne~lh(y{zJ80Uh@M`pL`>@uOL_N5oa!v1+1F^>7eBd)WVY%|qSjz&qQ~ zv(UG-vwu>5Ik!DMcoco9=+W9*l~awQlRj;2JFLnX9Of?PepAk!_(>z?GoAG*Yk%cu zJ$^1k|6KXG+~J456SvKtR_%Vc6T3q^x4Vq}bNpC`o!WQ)s$;nQsn80(vRdj)FIG>W zs@|*63#hjqPTjGFZA2f5e!5eiYP+}Rm$m3s_>Wiz$La$g<-ZwyE&43y{jquiw&NfD zNAzg>Jyjo@85_rcNqxjp&UnWRib$z5NKa6SLVY5x;_a|m$6YmAL$2G>^;){DRoaYw&seKHs z7q*izRF!=bzJBpdYg=#S>lKGDdrXcyPI*#ks&RA<&s1Ng?Ed7i8!c&$&}k}L^>itSPzW2$WyGANw%Lu*?)>nk|RP=|?Z-}^mc1X`hkNdH; z?YRj3Nn7{BRiLjxuXpOIJ!O1UZIH{j^c6N;RDIoZVK|?vKgQ^~QohvlvfF<0jty1b z9oSrUxV7yzUWdyw-_DOpYaMB+XUTu!b^OT4v|_)q&FsFv1G~F;#{3+Wr;JFuxL)Bg z!eXqshiA}je<_i6PJgM`Rq~AbC^eSEMcTy;(PN2oW z-ETgb=Zwzt-Z$(){}p<){;1O0NLowLd#N(M=19xLbmws0x2SwEkLRm;d(vU+n5WeD z4c20FCN`nEFV=Oc+9t?FMH7Y zp?mE+;!owg6TO%7e)$~154V%CQ|XuTI{xLM;WT3NLuJUvM=>@5rw_;6RDs@v?$zcC z(O0A6J?!7n=EaO(o6+sK8}7)1#GRkpn(@(s%?hUvS6m#xX8JJix=5xHs?ojbLXD$J zx9j4C^TT;{)P;JE{sC;F#hz+U^?dyz4_&qKQuMj#M~lsk*j44WU*6r=?8PSAStt64 zSD%0SIoCpuR_`jWe)JxB-u0D(-VdE*!gb+@ofO6%rB6qWUvgg9CRTrN%I%i=zET-B zcH7oDY#d|CY77@*6RjM|#}@u;LicKWHO{RfogO1)oJ(?~6J?y+ifz&;$(9jKJLNh zGG2$u8LJ0%rEfrQM)#T%cA#%X_bS67^q0{uaQYAGx>o*EaQrFyAg8WB%D2ajZ1nHY zqs6w$lNv|&pdXB-j33~|(N=ML!|U?-7_S@Wy%%jlUyV*whJDnA^SKHACG<<2dTef} zEq9}TjUH{@L9#ZG&+pNH&+GUJk@=LZzvV|uWm9%dp(}P(+zk)sr2v};vGHp6D)c`b z#m8c7KE%c=w$`EVNB3&it?0YZqqVCluNp@WqucFr3#oXtO9~s2Efc(-mB~hb6WuEx zlh8M!M;migd^L!k$?H%a9G}ZALw|?+qs5mU|LD(qq_4`km@#i1`kTCte9L-};9y>ieS(a&<~CE=JTM!yH$tDfeIf3LBs34IgydyQ3_ z&=0lae>eI*bgy`_m>Ap8qs6SMXFq!9%e?cSBlky(H+6q8dQa~68uRC)7odBMGfn8z z(WAwIYLf=WvGM43Jby|wdBk%Ieomd_9ghiTYTYXyQ_<78KUzLiIrGu|=w9Pg1^N(l zj$p!hbUd54Q2Ya7-LYp{E%$qkb6e17;GgCW-!FSARZnUhtwy)Uxlc2~HmX19BTlsCgqwhtJ77wbvlNq13qxX$t{JAqdqQ2w0tCgGn%xFG- z-k<6{{xqQ{Tp4}uuHtSJdUtfMadx-pUU6-uF}HDlv~t+}A3X)#E3R|UGts@;p%}d{ zdbC(j{^uX%{wBHKs~tC?568dP__7<~NUmQTsMUR#b z)gH+tJqX>a-=(8pj1GkB!tohLA;J{&%bdDn-CB#j7@cf{?{|Dgycm52x>x?z$^D+? zN8iHzUi0MvbZfeI`I67&yLaeb<8(TDBD&W&T`2co;w+zIJz9%Cocr0mgv&4caTN#o zj7w9{?Q!}~1g|6Boa6Kc{A|ar!09Jee-`V9+kqZi>WW9#IDHtK{@AE038f=#seJTg z*cy5iA34}mVB-}p#ppMndyP-?MbC8R!Lbf(LSM}NU7Wh(v)WDQ^U=M=r`_oHp+}1+ zRo@#J9~;r%yEv1G7V9Q?$w^@=r^EK zg7E#a-t|KjqAx@r@6=V?=`ESPmkMI@6gCIkHlK&r&C9U4xq|PExop(q7OET@&>u!0 z?9{8n_wPV|9(}S?k1ezf{BVcRzekT4CsaNi-zVugfae!0qnB0XVJLbQI z%~8_mi_LS`M2iVOY2>1-->VqU>rl)&+Fa$M0-IKBy!!D%^smvQjf?93)#x3r@-F8V z^knoKoq32=(W2K`E$B7qUgL5Cgd{0I-DM{6fP zX)Z)xhd$kzzN$mV^G9p3`Pw57%11N$0rd9zmHJJKjaPg3t7Hb2-RNHZDjod?^l1G` zm9r2%y~;bLYtj3lx7Y8MVlxq&XmzF1SdU(e?iEYh(8r-i>zAsY)-nc8M=#@b`~w`A zn6cP#{+2=oti;AE9vEIM2odc=I8;?D8;QD1DPV-qd*m5*HXGIX!FQ#KXYq*uGvg(@BWF_^vgY*guB zLzcsB;uzD{qF;yZ6?@I-PojIZ$$s=z=#!lORURDuT>WOs4s5*IME#b^=jdLsSBU-| zdbHS6v0ID&HxK`80jzvA4x-QIb$lF$8zwg8Gm6;K@Eo@hU)eR@?Xna7Jan&iQTb87 z_0pl%dmZUV&qTjW*_yn#+D-jFOc^#_?N)|#;e_0(D$Hw?K=|A=QkqSxjz;CFgim^xE>tm;rZxYuhC;lsGc0-Nd@{u^k{uZ z)xkpa%h4I0!~PwgDXd1XLiZ})7W6so_-{eK*2BM_BsWp8Msz#w?u9XJ9jh~;@|ZT% zvOdAaYfLOa--_?I3D=|JGuI&c&FEfjxfHz--D@qg9{o%7Xlof-&f12aQt!PU zQ#OaN8Hvq2UWeLR^=rp?+w(&9;@D7KVH^2Oz9-aB^k>mI>I&T?^>|AiiH53KUH6TMf^yPXfCXQ4C7hV$=u-o58VjIZd? z&Q$I4qhEyX)u*ST=d`2GLm!6j6^F~wC!!B`=Fjo{tBvRl=n>;$Z1{7`o#^Y(qxBV) z|HJ4j+eyD?j%7WK-rbqL<%H zj@~|g^o{7<(dY5nD~5MtQ;p3~r;Q_qEfQaZ?iIs+^u_32F`9$E0^KV{i_zDkd&TH{ z^xf!QG0=qmJ-SznZbJVN-77|SqsPqgj!}!?ifu>tqsO6ptfg?tX5za&R ziqZM#b?9C(+Js)#PWqeBuS55W(cS1Z=w2~ujo>>k=$`G5z7E~9{n1}Q_iTUkZRnou zk8WM-UB6A}-O*2T)~{oX+JxQ%-Lw7Cd!u{CKL;!qqI;GfJr~`x{OIG+Pj%++vhWyR zj9!TD)xPu5hogJNR}=aqbkFjmPeqTmCh1F_mNCYSLw|`@lG}`J)xS>SD<_K zwf*SZ(Y@LtaU^Hw?WCWE{t3EQUn@ZW0NtyvRiP(c=N+q!=-tu1=8LuHesqSkaQPkc zMKk&^bgx+1kDiO3gj$*7qS8)@nU&m+tY3LQ`UiGJb|8ENV3C{avAMJ;$ zLLY}d)~TyF%n8S#`pv-Wu<7Nrk>}}D8>`aqHRVx_C!7qK3;LzhUEt zI)L7SKGUh|Ge!Gb)yjwZUBa}v-hEpAUg25jUU8~^$1n%otDe;F8)l+E;LJnp61x&q z`b*ItN1qX)>xHG#*P|cwxZjVy4ZY_2_Uri&HuquUmB*CPmi24&9Q=i1!4WIj=xfov zVr3Hgx_10Gpsz&tij`&P_o7d8r7zoN`@Cc$Ht%8M6)QW@x1v`%eK=y}FnW)9-m%hi z4DE>CUaY9!j$D9^=lG9)GrCu-%tv2_?$r)W=!?)Fjwr)}p;+03p8N~%vxVL0W6-@~ z$-0>J9eR$_zoVV~=1G zGaLOHUdLa~$$~jwG3R=L@EoudU(aIeRafiLpF#I3%Qp0n(7noX5PcVVw7mMsUpFSG z56~y_I+RZ}PwB_~?Xf2tn-256>tho7A$+WN`j7>eYOe9H*|@QNCBJ>TUz$*Kc) z!|5nH$ND(6kk2!2_AYBa`gQ1DWvM`KK=;b)LiAen_VQZBIQB9&c3#i-&g(XOO}NE7 zF9*@bqkHA0+ojAI=sfEb_&R5ScV6bBr=ds7i)x=qj9Y!tALMoX zjjnX=438OG@N++QUa{DM-q?tW)h`tfsYfM^={zr7xtwVi5#i(QL+>Fh~*m&h}KYI6Hdgn2bja46XuRNxq_e1x} zV*&cf=gNc%hA2^xD~w#-7Aj=(0_y8-niDSh~I<7rmM5A z<+%hkc4nbJgMNWir!CYGx6+Hyx3_bD5PggLe#dtYmZJaNtvmd$M~}VLJAd2I54My3 zLG-BEvzhbQ@mC#4KeN*U1u#(w?ib)^=*!^ZjbRj5o3KK+%XsWf{L;Y63+Dvvc~Dx7uA99 z#Q0khRGJ?oSi9nU-*&L>iTC}gqxDX_Z+S=SR-f;W9j&K*zJGPJ-uC%E?r8nZ=X#~-cgXe~?7$(+~&%=FzBV_o2@CHuTsX-s<}<@ic0l{z)hrDzZ!}#u!Z_=V7~e;+*2A&t^&ew>|BSW1h|{JgSNqn-SvU9|h_jxL z@g0b@w#N8AjTE6Sn7c5^`le%#e|5GVO1L|g zHw(IGf60@<&*J_Rv(jfh=M(M^F-&kR@xFU~{4A#Cx{dQa7iX38W=UL^zs6bH;#f#g znm(DojG@tEeDB6thhlv9##^_?`o4;@9*y(e9B;M6u{y@;gzLER!5Cjlto0ZT8Ef4n z`As<;A=md@j5UQ9#OPmRtZgycb(iy0+cfxIjiFsMb!?gMmRRf8G53(Bs>&lRZi?x- z6!GI2-)}ov_Y$I=RElhu2=q?YeQ~~jce4Hx=eze<>r0h|2jYEyKGym$-uJ<=*4;ke zH^*A<`h0gLTEFh#do0mQ_NPs^~N#2U!G$9aExz3FYAs@Yhw1FYQ21{ujv%)=|tai zr&u2)Ho)xd?ECr@>$}dr?Wb6eCY=P+nC!dtRO`;;e2<-KZ9dKiv!<($zbd!4t9t$V z@pmfU`@8jcx|g;11mACaSxw!2@AtA^>7EMzU3cHUUe*UGzMK8l_LF>%`mJB}xCs9J z-jsuy?v@A6@O=+=piN)KZU^TZ&MQ^@aRIIlF2C8rFSifq zd9Gj3dGCMo+CM`3H}zod$r0YXFP8VFyoR6evTJg@kHyI3Q@vJ~DNn50fH>D%XxaK`Q@IZ`Hd zn`)K!gTTIqvY=luT`)(mP_S6AR&c)HV!?Hy-zv1+68 z$@cfz-6_Ob$602abZT)HCz(0A{UiC~ty~$$Bl&KYe{wYY6RZs!0=cg^e*Ddh$4)KI zI?*!Ya3r5%&6n{xl0V6cHa^5zJwoGYq&=g*#C0U!)5?j;pW-yLU#rr@Ti>*~1vL-F zayqxQZ=|AzNyS^P^-XW#-RmCpoq!lVF)Vyf*PE%mkv4y1{mc?SWzXomHMs9 z80*M5+;fd8*OC2NXYa^<^fG?>P!I2`isiD;(!mpAH9zHPo3`xFxOq81_~fmcSKpIW z*DB%b2HFJ)tvB`vKUp;p*I62@5saHE-KTnJdlhHux*5K=m0~qXzw_IyUI!`rGFfkT z5&mWIGn(2^*JRFM~gh{=P~2mszK+6#H9MhvhQu z^}O&q|Dt*OGbdhlVj-yNA@_RC@00al7x>;NW_|D1vNZr+<#SJyCd!4sRQ#BIj{4nm zbzLufrWB||)7CvUFK-<1hWLNs-%4eS;nlSM^3|{3Y@u5imdfQ%ZcEEjN zzh2@nL$nu#-;o+)Gkt|ue^WuFn~<#ulkR!&D&5DsX#0L*KU?^D$7z1J@P8NnptP^? zpT)vo`8nv<_9p%x68?ezXa}af{wn;w=QS_cvQA{fp!^(A10&ZkEn8K>&yo7E|E2-j zL&7&cq7A!?{aeE4oS^+2FMJ$BlF5TmHk=8s(%pEjwl{G;OZd4m{#+_IHQ9cWtyIbQ z3gKT9`~9mlVd}Xf8#Cp9-nW|XE%sLkf8`UJ$Q1q>c-3A9CGgESvq@dwgEB0q&p!~e^Ql$M|!Z&4U z|I@|31wL9mx56J6d$Q$stv5Q+UsbwSNdQVSTN$TmUi}`Cy3W;LorAr~&&p>sVd{Cj z@RL5!ys6J+@P4`13G2oFHHkN=ZcB|H%Ksekf41C|d7S3&mwGdCTMw_sv07QT#Ebnr zv7hycCQO~Ezq_EyyF@zHD`LM-?CYdIn*B!xH>&&;CF**nTI?$*{HVkFy(#ZY!uOZB zHTjRFBOo1d9Sg7g_xn&wG?RT*319WNesAjeUfWNyb%Rvc9I;<7{K`~KNU^Q=#7_^k z5aKf9jE@bzN_Sf~&6~W95kB^I?MI4XT@A15?Ms=D8nkTPF7{T7CMF60obZd9G-2}p zweXEEYToqUO!g%YrQcZ1=EcX5rwg1xXnz%st>xF;vOHC9A|BUd{U(@uFRllx~e$Di1Umu8n_xQZu_9I3PP`{V1%DZlWCQTgnf>-&8P1gAtB=_6~ zuhyUD9Fk(%*OOvj^s0Vu`t`TMPwK4wOcMKwlePap_Sd|Lw}*xIFVTiHpMAXsuhQM^ zTKDc2`&en;fY>MX)a5FcjF^7W4_=jP-7;JFw zT&YVnVf>GVXXrlSx>4*~c52D^`IBwmlfO5v+r`Ay^YAL4yYjR>*|4u&!hchx-`^no zL3ov);sM&v1;URdV~QUXqj}RVcL~4Z58Cifv42_k89lZA4B@-_wV#Dj&y~U#2%p$p z+Yc4~*TQdX(}d~o$M)8Kw*6l7KZt#?@U1eQnELrd_~DX4hAI0xBz)OZ`n|F5*GK!e zq+Bb+evDKFiq^w75?RCG;yi$mGGwRgtDPt z>_QlRIhu z%iW^KPddX{hBcSVh4P*diY%Io25QY zeD*(6`=7d2`(Zk>ugipg@HCyDnZmDvSM44z^^+(3cCml;Ol?0=_><1k_K%ioqIayu zi-hkZ1DI*wDZ*bUj!hgcfLHa9FXPWV@!yMiNb#r3deV$bv*1-e&F82&Vt=>I%NqyW z@4-JM{0f@~?}E46>))C%{p(BHj~F>1HeK7N$#`PQHAMLRGB2Ch zSR}l=yidTZakWX-naK${k&R+s{G@(w|BVM;?iYU13z|3emXe|KGhWtL3@`RILHI@) z-xyi!OZ|SJDsP`}_4_HpZxepw6Pl3axD}tN?c-#8o-FpGguhD;W^#o8GrX#2^Lco( z@E?i&dE$7a@P5|EDnBnbX@cq4zJ|khmDf%fZ}Uf4b4&U;L(K&3W=m@G3vODm1Uo<<<4A*gqxX;i;Oo)DyZY-3@Y%G+X#4;pd#L9pnhF zey~9Kcc0Jn8La&zy887{;nV-29hiD(z^$4$56SvL+*>zeul#qH^?-@z2W{S1h4E#v z-#<)q(*3L*lJ3%zbpBc1*q1t|^UG@|42D=yLz!d72engWy5J=zqC=aX52no_~xfI zACQ}-2;cOoCZ-GDDE#ZE=yK%<|1aT_zSP9;g`a(%uAf6PkgO5@et1+1_pUgzB#!vG(rfjFJ zOn8;g=55;0#6!98JJ)GGU;Nx9e&)$IY}U8;i2dA;wV|n>gHl`@Z;e)ojfZ+cUg%P)T37W?iJKf{F|L_bk+yGk0IY1h6c!>jzfAoJ!V z;kS#u`}3WDiT%bew4t$2zexL;F6-5K;^%qc`+TK|OyOg5w0*b7HDT)E9O3_SNb?Lw z_O&`k+aHj2G4b%G@RM4!o#_i*hH3k6WgjZt)w)FZ4`hE-pl`Dtf>-r(hw!cyMs|=s1d6s|n^@Q-1QV%Boe-r-iXKVXY#r{mjBUKN7xkeK*oLOVxRe9(9 zP4f)z_O(#>(fjm!Qx6-2@8H+|O*JN@o={AYg#qmTZ6S- zc=zXh-w6NXXWGz|_Y@Wks$A~*A{$=iC;JC&KVJMV6n^mrO_+Q>C;ZkQHBT|^D{GYU zf8;e1UirW3JFS_xZ4~}}N!Rcjg|A4`^=9~g34c(=PnNItl|#mq|02mJ!;XEa-@s7( zX4&tUdiw%i)q{I~+I_UP?uohE+N?@TB^<7NEpEBx*7%1@dskXf$S*TcdmpP}Ek z2;VHc`}6C63;#a#s;<9ku=c_pl%79n-X}U}Mr(4-qf$*=%KE=ez zUBch;y|y#;|AO$3{YUfF8m!nt?cY2HeUb1(g#T39k!;&njqsE1)bC9{T?DW4@9q~b z3O`)xVXgStC4R=sddcMH>PxjB_j%nj@TwjjdRsf7S?%k9@XyME$czK$F)%87_vgPg z!uz-A`zMK?74Ygg3iG^kPvKvH?<%jI5H~^lcdrxjg^!Va;x%&9FN806UK1;XSKm)o z`CM^_CRPdmweVw_G-2X=P?5I(+^5G|Q~$RKZ@sSVsb2f~SornQUM7CNgIDV}^W1l` z*q?Bj_W!liPnqx&gnzzK6Mo^ZgpXD~H;8@nXWH-_u~*;IRps6Ii6%@w4+`HV>jC3) z@I-CD^Kot8L;RG$t9WxiuQE^UFP4RXStq<<+sn-kI4Jf_+cjzOb0!0w%IC#DX@0WY z6NFdk9+GjpPWU^-{sjr}KEgjE_LtUb;x^&8z^n6i_xb9(;%D!Px_wPObRtkyey(cL z4op1c3SS}n_Y=f_z3}IYAHvDL_6dKX%nQbTI0aPxZ=SquKjwQF zDPsQ7c$KdC{>D{eUjuK-E|d+w68je=KKqOKobVgg zXu`z#ZsFH`rTI6-KKlxt?lO5E#-w$F@aB6RUBrHs@b1sSzlT@lb&qc+Ox6CU%lU&T z@3q3apM(0N@cGiO2T8i$3Ge)r&xo-ZhC%yEp~EWsglzr3m+*t&Rk>1R-)F{++r>VOd01VU8mzTq zKlf`*nDTxHuf~C5`5sXZu|J-PMy2ciyle=(N_YD{Z7A8Yt{1-F2a*2Y5&j%G2R7-R zP_F&_wnf{UevuEa(tR^m^Clju#s1lyk@lYozw39J@2g}x&!*k0gnvrTG5U)AbHbnerY1u97v6n- zGWcrkzwk+IZ|dhxc$1d6w&4M>@9`JS8k;YKckiQ5s?z=wWL`G;tQG!i@nh=qM|d^< z1YP^4xLMjyw)6`V553`4oVQAx=SXHR7W==u_T4WEe`tv|JWK5Nil2{UJ!8g`Bmzm* z|DWaD)s*)#;WK0(ahmv9E&M_`x9@NK!>fF%^K5mk&|oFjX#QsALv?)~tMMXuJFcX> zy)|tu5&LP zSNZ=-u_m@jJ`akY-+ZrmifLaNY!Fnsdt_WCyzOhQ@I_K@Il_Mgulz5T`GR4`zV?ZI z=XdpcQ=dh3+W+;^k1i4W+u)U-doI+33{TdxVt;b0=1u+lNB9M@&ocaUDpuux$`WmV zw)mef{1_Q0?-u?(;otmP6Xx@s?!oB!83nKW&y#V|w975R?|oSNF>$_8c=x*N)Y;lk zj_fzPN`4j#-y#F{slvZ5{IBI4X`1k{bF?4#b1#G7)q2=`UpHCoi{MRKLfKF&e%#M> ztP%dfue7zfx7GHOZ0)^R^9ADUv}<*K#`f0Zs)^6J!Z$vy4abT7N_gW_C>tKL`6Hi; z{ziEBdOo>9r~8x)0F%U7wea_Spb3-KE5f_a34eq)HqQK5*J=Om=gEtNe?`udO*}6Y z-u*n-Tf#5+i}r5v88cV=e^dI`36l7D;ZKzPRGRR&3GY6q{WH93_olaW{ilfihho3_ z4NaKwJnnj(?#@G+H{;bb;k(N^*3`)oc=K9Z+pt#b`$>G7eD1UDk9@xF*m*kLQ)Pc) z#`84cJInd)6iMVJ;WxRS!}$li8aI|-p$(Z1?CXqQX#b10==TGKUnBfy;>YkU@XAkB zo;H+e$vWl+&AZnj=fbOTpx<%2o=v?i7k>V$+K(9rp7G$fi~so-X#0H0=eJ^ivz!~y z-Rx_`jXK?5%eZRte~0j?@;#IqvEMKJLFtdC-G|TDe%#-ixCLI-gZuf7)nf1d{BE0V zZyj-c34h!XET0MAq|;sVf)-i!+gFM3=64TFxt0lECg-}Riv1Sh-RrTKo3;O3=`W_d z=L*078|`3__zA+>=K!+)H~#Mt`@+|?p^5oV;8p#sl?r}H{2Uhh6{|HN&2RZ{(fN7p zJIx<2_H%@H&*P85EC16j)rOzPX#7a*&yw$(nDO?Q1=@dePi^>s_`e2T`EfsgyIAb| z9Ix$7J;eMndb<7LRh+xe_ihqCTlRyd|2`^wOMmVELCH^>_;;UEoph`Azet`BIYI0% zhBtLClnv!#U-h0UtSdZr4l$rV*d}ZcdyTVi?kp2bCu)aRsF2X(+Fbz5Da8%Z2|y=C9Ml z{tv=Wl73ep{Bd{a{J5Vh$P)g|a&357tj6*1DxY`AIAij26TBM7=F2!{>hl4ypCJ3V zX_D>^;Xji6n0%gjr}qB|iisGtZ8LSM3`-Ka!s#y!*LU^*NSW zFPY!f$(DR>7XPPh*F=Be+r-b-0h&mO7k!D&k9%KmmGC{@(RRNVKf8oKEc3OA&!Kl~ zKhs~=hBL%I2(R*KewV;6{5@jd<8w`93cpYI;(eMpQ+V}!kBT4n=kiwwZ+<7}B(c9& z_(e^cF!lVV@aIT8n0V{-8|{Dm8`|FV-#p=aKB0LTUad0tu9}MYf411a(-P_D3ETe2 z_1-_le#!mX{uA+b+C4fy*)p!0es{C*yZ36tLb3lq_$^ZZW*msWSNmD{h&D9kJr_P& z{>O@aUW^{!OuMWU{vsI<&3fZA+s~2TJL|Db$FuuF;NV{ky`?k#)so!spzl{ZEy+8Y27>;m?tM>+!;WFZ`X-zGhyyi}q0c(fwS( z8hDle_z$#$-s0y!!f%lEo~heQS=cE1F)wMue6gP={G2~(LZ(COQQ^OraoEg{7cAF) z?v;L*BYxHh?{Ct?S;DsnzrMF_#~k6uvanI*N)uwc@OQ(jd_F1pSt0xm;S(f2nf~nS z7z~vCVX4n*;fsWK@5`PLe)ukJ*hTD5{H^wLvg@4rO5vxypbgI!`?bP9FXNJl|C5`v zpM3hax=eo`)uj2CWxgJ0tNeC46Nf*__jGO%`!tz%Ogla;{5=v^hClXq+Q0jIXH($q zaZmQMeo41l?3diB2^0Uf8D83bnAm?RynEl_U#Zjm_HAuw`b81E$(y*aVYvtYlKA=l zaczCN-1Mbwe`K7bGZFa3#tCEKRXhxn^I=oZzk*la<2JvOWbRoi_N$~{8+&V&_OnR( zmx+^s!WVq5Js7@0_-kdnGV%X}@b2@dy~3A$q5WJg89MzTo$ihenjl>5>l)#Ab&9dy z4;B88@TwoV&qa5L{g@_gXyVZSu(o$UCo>XW)mzu^wEZOU|Df>C9Mr^Q;Xe~TP1?)& z@6GtG@^j5q+VBFMU27n`^1rQ%Ci;t?>uq~^!=07`&{Qd--@6A)N9A1I%7K3mXM|rU{H?Cf(?1sen*V6Sv&4SbV>(^;=X5jRmH)%? zJ2o@L{t@Am4oCVqD7^c;r7!(N`RVqPwjV5hDus9N%kC0B^WTyFUlQKEk3Jy$aq|7O z_2PfV6FS{TWgj3dS1^vM%kZxY zpDO2{hVR6@uIk}Z>Az-|7PBkid!^ZE50 z;nn=Cu6hmD3gKtU=Y3;^zntXM=VHb0>2wo>|3K{5Kc$Hr;WPiN(_Jm|V}Id;@X^}$ z*JAJfJ(HJ&ch9r&q^JD2&rdSpRe4(^-3uh$U)uKa#sQ1PkNY`?C&bTKzb-G+oPE77 zyn8*+@oAkO_w%B?;8lLc%0Au1L#5b%Bm?fu%Wrx$BOmKpZ-JF)*< z#*=K}KNEhgjFV-;_j^|R-y(5n(wz*i{JWpuxKZrg&*wiU_ODiI$Nj|rYhwSt)Pou4 z|0(wK&(wy}&8*{|Q*ll$=IC}0%`fn(9*W-9_9u$};qWS-L$A<8K=_-){v4Sv%sBRl z@b2%Aydiv{WMqo?N!_T^-7BA`4-`HKuhM-_5;W=lM(q1aeVTkeC-ylLw1Z_b&we5H zV;L{ib%qA(q~~?I=gWDriMMI+DqZ*Q%=|*^H!Ri;%y@FI@b1qGb_zfK3vEx0+gAqb z4^_|SzpLLD3a|EEihp08zwImhM&Xypxh`R5UuVCl?cMvexx&}VJZStpC42$%r@DG+ zuv&z_YNsYb`ProXx61s|TkLNUzJYb0y1Hwyp4g=AZ;;RFO#FWfujo)P|gX&2LfQ(n>OPM5ef{qbVq|0?-0?fwM3O4t4Q-CM%DzhAIV{0x=x+4#xZ ztkZRW9y$YF`FDRV`75z^|L)e?!n=Qm&G)MI|DbCe9wEH@cdHh_t90Gt{NuvAzvuNA z;Y)|=3LY-?{58DVznk9!PZmDmHJzVt4r{{HL%r}7OEo_`PUCubl^^%_dG`umGfUes z9NAa=>(Y*(x@Kswh6*41l_pGonJoMrvR|7d_MZqp_FtMfApA+pTPmJUmHt&Ae4+5} z?_2#5Ugh8Yyu@~~KS!RonJj+t-q8N*BtA_(t>rk7L&%7Qg@^?{Pv4OVH*tlFybV0l^p?DRqD(TxH#Dyu64 zC3STr*9FR}gLT(gGwMoal?TdZ&zf}|w>aJfunb0+)|Lb-ipuMQ{Yz_Wt-zEC!Geq- zwUyQevU`epD)XrUHNmb=s-qlnG zN~+6nt23b9r&m^5fl&qHh7T*?mf6z-qXYG&b>-#N6msPFVVC3u^2X){0=$bTW?3Xb zT6Gja{EQnpazb8FplI0ef;{fboji8fC8I}h$EdNF1@iL6Z+`B0Rpbf5j6vbD1nWvF zgY}~)l#Cubq_D20x@LBDY5BlHDkzwjmp3F-ccUj{1jg_Wa?bb(nSsKhKyK~0qI8nO zWz@TKGxO%?1P9G2FQww5B*C4w(~QA^O9FM}cD^WheR*AQv`NmgN+L`~b_Rw`{m(3F-;sp6@usah)vOc-Kk&*5@Fb@{b{P-8@?pS)~Q z%kyRxUaYFKXrd#{j0{InRHS-oS@pr1+IE^FYMq1{hYF@~?C>wov+Fx6Fd-|T;=r?k zGcqRBR#jG)>re{0iq_8KC9aNE*+(>VIASvgIx0fi^pcY5l9}aoxf#0LVdJbq#*2)> zGs}YoH8occt0*ri)43cwAt0?tcT+vZG^L|jO*5OoRdq9~q#;mWIk!A-{KdLThSb*4 zfr?6M%geYT+r>^jo5XdRvm({ZbZ0?SH_R;wmW+_D6fQ${VNHFd8eou)NFrm%rL#-Q z=pL1&(g+k7Lq~xo1deQ=Od?g6`~P}`Fim;n5bmR6OQ)G7O_ zl6o~Glt$L2UDG2nRIA8170k#COtinf4tHdAsKG8{2;&lM6)36=_ft}wRZ_`- zJ*8-ZBQi1uPpF(#R8oC)Ze8V^ay774ySikk(Ml%JjdY&EO&aC?L9=ViN`iV=a-@_! zuB>JjDO^XJsxe_gFf%I<2v*e9TpOsF9SqdW2-KBS&nyqjm=!F%xO8q#&ZvUX!$(Y- z6d2GytA8d_uyf`++Q8Z)6-sL9i{JV1|cp?M@DJsf`R&IaucKe~|2(Io*p zKmyFdr4>0jlxNuR(SeNq10tI}Vo}il$Davr-s$3aWvO^<^ZeGGRz>0;n*0psdwLfQ8a`_KsA!2f3ENA(^^d$57e_ula-gKNw7kAPG+zgTB{TC_sOft~ z7hddan23p`P~|<3eB1e-kgXz+^r){{c7561ywLM@Rcsx#9?cVNtzagzEPKqi8`n z=9C0k)G!r9_Jz<$k&$7~IC{=FqAz%_Lv-ey{hOlFb@X5}y`)SJi*q7|7~KX$ky$hZ zYNlVsup5ZBPE@nHg#DbtA{LhEf$>Edvas+TuTA91t!8-f?1Rkhx-6=K+H0=p9bb}> z0rzMt6=%Gfj7IGudfc>|dqQx)tjg-qWwbv*NjK7qt8jq^>9~>g3`NMEU9I*A_GY8J z%#NU=4h_znNnnOE=3KBAs)eiWS0e%wh99*(Tv47uNQalMQs@7Zqd>Hd8Er6dHkEgn zOC#ll+BYxFLo~sZylJO_0}fpb}OofJT^wbl%62vrNum|0p=RZ~YfCIko1sHwZQq^@lA zc;|!`ttaHM6&`PI_3O&*op4?G4C;ryy}cpL3SL)R?pmA)(j`PGI+c0XiW_QC2H z$DX$H7}V|44EDzD%&PWocc7lc!oA?=-EXk*ZHJ_aNNK;LomfOR2=<6O=T)Nkz1JwGe z(=rqbv zj0`r2uC3dDH$CYj!?RPkPaS0!BY6!^@s8!W9_;k$mr(rKCuZDFH>D?3U&~bC*kP*9 z;V89pFXTFdaDvpI|5ae(@O)T^|S30WR>*A|NZu*z3K@c2s#Vn zJaEg%G^aS~jK&1nQO{1?W0mWW)dbLgcZ3pk?O-OPpL?KkL@bYGkO&=G*r%AGu#VpM zBFkp-k&&fNckL62(u(rZtMk-ITvSn=F(}}y+au3UoaZ0*z#ZOEl(aMd5SAusy@DNR zA6M#Kg<5BqG>o3*T4&?_e{gv!VH$lw8d_V1s+RFajnuk`UK`h_^L%Lk8tykyPyf_u zr#ki|osl)wK|Xn?o57$J*;UOB!#-8A4_x?EMtzh~F8w=@**~-Yz{s2IKGg1j=@}Fg z)W=1k=`iwOnYw6iax8LAFkahZdxc|H>VLO2kDTx2%+*at2tUejY(}r}cuZun zxE-j@(74ox1fi|g(bhbA@XE^zPtNA}+0m(_N!2mfFg1tTqg2Fa2%#easjZ`~IXJu= zCx<5CpwlHYYx*$nJOXsYpdIT2&8|rHHLg#gBEyEt8PA&b;`WbgBF=`)81P@7)3iI3 zhL`YaEhyzAG@|Xnp?~&d8s2RW3J?yei;;atLrQC#j^?OgXPHAEc7#_5-m7kL8L?I_ zWbBl6@=*i9xwHz`kNaTV#C+rl3L%)0&H-OTL&@~YIT`B1*EzE)`5c+OZ9wf#_!MwP zO`dZLY7dZEY6IN<&@ZPJS^8v;b#QeRE6d11D`NmlvG6&)R9nUXdv#w}RT5;UHOsLR zI$B?J$Es^iS1Vr?z*Metm+c%myqhU%T&fc}*UG=0lM1?Q=tGd7u{<(O7ap!0%g5TP zyed0PL+TOHYC0e@Ym^Vk^uD~kk=41wG^3pwBHcU7S(T9y5pAXnFXd%*U>|ze2RKm% zZ9Ys-59DPGEDLQp?4VS&I4m$BSMO{?^LRTopE0<;JeaE=E5P3Vtht>-qX|JB;Lga1 zlD)_S@uL*id8#*-NaPc9sB9IHdUcc=m@vXsBHi*?%o>x-x;DyiVB$l%c6dB+j!urx zGc$%z85~w~5D`?1kR~CBxm~b_h`qN;au8hANB{S z_SuKWNsENwe|NNEpX{q=Lez5_Q!)nIBg-X~b#**2QZ}llq{`7-Bw$= ztND@aNa_X4#{z<7C6ElP#0ZuPXj@Y~pT60iDKEqB*u(U&wom2iuA1&zcXzd`s_hws z(26^fZy>~BIdK4qJuV0V7Y?jowRbqIkoXtihWSNiL}o<3$b7GQ#6lqbo3&Bg?&8n(NUncNJze{F0YOf;_ z31?hBgDtd0vPmKbKqh7nRB!|oBo0BzAXB#Sr$uY`pW34HkW6O%tV`~K@ zCpPrP#q3TCL;_N;5iANWpMWR9UMu1v94#rWxV*y+o*YHz^bnec&}Y*}>`&BlMzhJF z91wM}E~KGV1vum3wH+5Ww^kVtGllQX?q-Y$>=gR(@I^UVI;@kpXcQJ981xvs1#6lt z24hP&DGc-us5b?$V?b7ip%@UES^xmS2E=E3WWd3lAgbdqj&|s=1#lpvBvKR&PS}eR z%vBH94%^5EQg7f+2k_f}JbS*GEWc3^w~dx{7Qi z+AY>4XaJ@|mj+^lVthls+dU%cE>|I@w$>j7t349MM0CQil|xlpcQlBstl?&N^-tMt`w460wYT)r$}xieLJ|A3;oH@tYcqCaLYcN9fPPZ z=L=C^d*@c!jU1998%|8Pz$nu01bNvt$PCTjUT*FqC|O2i3PaRM)5z$j=t_7dYu=^f zmNpKPP0rdZ7Gp!v9EbGncpQ{RKg;`qzKOq#$$)qWXDbJ}crT1!!wOdkaR8S<#sMFK zt}+X>ZOtBot>iqMKqLWO53&a(*#Zi5c0ds{IhQcRiw7gJmfpyahV(8y=3S#d;f*6M z8QMmwR&~xoTzQ6Kec=f#o+-n>)piB~^gRhYs9Re|f;9?LXp^n-B zYu5yik7zVb%6Qh0&lg2{p9ki=a~fGEhmXHTz7z-VqyJ_SJvAm)Fup6PblLq!%A?l% z>bqc>hq7upJ6{1LDL8jwvOPIjAVN4FU93J3tSdN~foeRF>cEv)~j_tKne@IGQ$`Z8qA= zaKx#Ec6D?#?ER9rF^ zo^s+{SK%ZIQmkyUHKkBC>sq7&-2!%e?LISlP)!OkmSK_tqLp(8hF>HO6NOL+*ovEN z8uM|WLl+?wwFLHh#xO$mJ9=o;w%3&c5p%w$$7fLNgL8$BvKc0)Gblu7)@0sbz8;0E z@Mjc=MriZCOhnBvOzBs``P^KArAeMJ&vW)~H~|@=c742x62t@s6k269zQJ?~Y)s?`V74OIX3PoO*dcUvx$W2sJ4`!x!@(`wCdFJM zMPDp~+37YY6c9F*KRets=Kh!%{{aqN-j}RK;t9sAbCrvXM0GwGQM1hACOeaie(f!` ztc8hY4-_SxsS{Tb&KxGw@|^83xnk$@9JT)rpmG>YlBu8t zPK5UPLz4mKNa$zhtL*N8UR~WgIV=^bdrFBt6AA|`!c#INou{4Ad0MvlUpS~+-ATB2BWzkb z)&28nzKUqUC(3Yl3T3{S*=HYGS56e$e7F{!IA>1-@A^ngU@@r&pz=(+)Fq1t1H~@) zpJ*%ieZ+v&tZ%YDS}6A@@#cD3slRXgvu*HC16YN5uDucN&>1qy@3>Pgfr4m55+uYQ zLfnxrsQn~;T`}E)i5s#u7&?)I^_gtr_F+2Z0dR3snX{RU54m|`iHUzD+V-PXP?kdq zl++~&zS6LD6%E7RbcFrrD5towq9cGrMV>4g=3`X)got`amfguM(D~?hp-_~CU#e2c z$1_%1B8#E3d=ziOkt7tu+CG=lr;d!PEZ)zP^$id!W(MZC7i11`!n@TE87i8(E9s&*}{o6TJE|rC&@P39Bom204oHDCmw%FwY znxA5lh$1rn;5X(Sk%0}+Fq3|fI3zjNyPtBuaQPxfAo7`BEr4Z)5*kGoN)(QjBV$4n z;=9Jn0Kdwr*pF!y3P%fyhKS;%ikn^kw<8FU?*74Yez09E*59ClVHD)%lo*mG8ja_f4#f#pOYtJZJ^^(2!J#^H+{eoJ)RsnYM-!ObFrg8UL-ocL%Iqv=XAh3ZhQ2k0pTEOi@bb_oURS*G!q7*> zNf9ajcU)?4rHack1vF)1n1qcb9IPmx2~1Mr*{@z-s@?QFpw=jo@|gAGzUU$g$?UUL z!Nq8m#PlD9PHmAQCZUFA- z@v~>si^Y1gqBFPK=hKg_m$BR35uh1TX`)V|Dlc_QfciGMzHWDFjC7K<6yGf~S;=E~ zaIxTAXoZj|cUYJK4aJ55s<7@*N=L3GxYWHpeIU!5Vx5nvW9| znjy76xwq^wXscsov!=B33ST_Ll3PyMkLOu9(gLovYtDI%(~g1Kh4AW~Fly`j}R+UYB|C zast6z4U4r~jB-tbzLZjuv(nT9UprY<_}20{ZDp6LzBZCr(Y3O-nq-%BWXvL4@wedD zUu=U;lRSqQGi0;`8Z8*1Hg_DFmjOXuUApsG3F0N{)57=rlYi z$v-O>Yx$_OJ>)EAZpiw5BU2ApnKJcM!yf9m- zj^b2Y44Ew5hO;j!$(7k^n|abIFlJB|ilIU{gFeVg>{#YW^^*FyfPKp`>Y)=IBIvj{ zJz(!sATPzNO{T_94liH_GONq%AhqnI%2XKL@0~+X&!>+Uo69q*wQ}zsD)n9;VJD3% z(YJ=Ym8Ei{MY_16)Vet*0@yDMk(rm5N}b8>?sByWRhDl)z)2k1>5e6pyGmR?=m_^7 zMcu@69cp&(ubg}qp&qQbEHwS8O_60b2o5eU#e6ect;5cpQkkklrbv;g12p$m`&qdj zoRkR#B?Y8{U>mT)nlh|*=hrXQ9lF17j@y&kTaQ8m^c7p&-Avy!�^;3`yfvbmvLP zD!?-wfiq-d2h0&wQVps_07fP2U2Uj7b(2V~$-_0~Th&hMZKYo5aAPop;7Yg(@2a1Z z=>Z~>whz6W{jVXU1@i#Tpk-W58)em?PZ@P|WtNM&<33I>1ckKovCo~KlGh)_CTrL(H#!4r1!>SgYE*wWQqZMff#-r_=6LgR=gcZfJt+F}l zYM$kT;_b@P?z1|P+|khclKcP>&&S_~J{tXtwPtHpx=dX*G(?%4Y$I1VYgI%zPDlALN0=IVgC&7NZF3h=5MN02VB*VQt&b>7PE+lG zaU?6ltjlA^2BRDt(0&*t+cJ0F1!X&AqI#5U33qX_Z<2lJW}7t)z_JHp0q%_GvMVI$ z`!GCQe==Wuw2XBe$?cN{FOL^l0!rv!&ukq6t%y1?OQ=V~G1y>mJrAT+9NsjzX_5QW zE%gv?63AHIi+{BdHAf3&u~Lp-QRn0^mEkVx^2vsYD9Acl?Raz+T}4`x60AOx%A6P; zW5(D4SxvW7g%mYHpqNSqOi^ut)MwR_R~$49C2E4^xA1DPH z+@e$xA{-UBokj|W)r2aLaMhws%ilJ{%PKwQyzG>vmN&7`=HWhx&9Hj4;!c2e%nmtq z#yI3d_fU!IQrJq~bH&m$&sKAF;^3jES=g$VLP&A(iev{9(6CcIS1puYXM8+krWOG1 zEV}ickdI;9TeT*D&ef=D(mzJ=#rFV2bR5b)d5aA4v%oUylqXx8s50=7d@iF+#gM|P zb?SJV)i%*qV~A^XfRuG=fD;-L=9kVcw_T65uaI<8mats-02vKK0se@;N8G>2vN%C&Vl0MCgl4>C+ z)1mUd&4|gTG~wiz%?MT3Q0;y=&f+2nG9HuboA1Tz1e1U=dC*>kVYtEyR0BuhGaKMT z`r@gVIi#i|3RJ!>Ib_2T4^su=MPjJAybP*3l^^ty>RZRMmGeJ}z@myyNRSUl`2B0$ zKv+BKv^-|YT5uU~mI@%mA&N>kPNVU>D{Cd$r7v)-doj??Gc}qp*V)Z-zH&z-#Zqt& z?}qLZ;Zk-f+S-Wu04bo=cuchP?r9%mg7OU*?p8k!p;3J&NKw$vt~qKol=&C=Aq=pa zasgO-4;6FUX%ky0rTU~PMcM|*%onFKTtmDQ50So-0-$#_YH-3edgLEdlM#QJm({7z z-Bc;DwNr#E=e6`I>e5MU?v!L~T(#*KPTwiQ-bWu-B^XxUGhe-yAhlb)hZnLbNT zNu}CFj96UvF`<+n(7#X%ubYlz`jR}HkRq{O_(>84WD9xPK02u2P>5OKbFO_B@mfyU z?&1~InwUTyUUsb}MafmSnx$EW^NZWb9n%ggZ06p^(927)wz})lNi3d`M1|f8&K+-OmA>kxD zZ#tWf`%mREqpu0IDsFfr0Qrc1R6twX3VqC26Y+43Rx11VFgo42;Z15QmCqu(VH+Bq zJ4r?c>_~}uT_sFj%5zZD6nf$g6C=8;z)R4(2!t1VX zdR=xs+zZ~9)djMusEkDY+rhw9^q`rHkc&I(CZWNZcco%=d?}-z zk1}LIS>gDrT<;fQ+QUJ$uFR0ms*7Ts=sdd^vRh7z3pNpA)+-@vOmMfBS-?fQd3!>- zLHsTj$u^aBV_zXfhy~BxX{;xqwoFpd<;XFS-~bMk!h5k=-FES8=^l@-8vP|T4>~V= zL1}d1s4s9I)-HE~-*_2h1T@@x8qz*;wZybxV6~`FVQiDLtSQSZWnx*t5IL_uz!P|- z9A?)Ku0=_oTTM1EW4Tsndr}I3U_-G&ls-j&4J%pmmE!7Hxeg0sH?=_1MN|D#B!qh{ zF6fvd>zTWIQe15*@(o}2RD&n(FVY}6P6PLF1A2J%s#SfeC*jnTx|T*@sdi!wB(NmG zIMB0mf{`t#1;neB7UT|KsYFR0Gcdpn9U}Bu2Wz81us&PoCV;2Zw;AT6yP#XtC!LW(G(kMqxZcs2{@GZ^$JiCZO<|wHJk7Bhbr4N;= zIWI1k99GyI!A-lTI?!5mC4z2bY2sl~d{@(W4dztxcdzbG%>{Z0A-SN-!S>d2b3Qu{ zxv#qsXTP%Hxy90<4Fyo)O+&M`uOcq>p)|U_C{U%XLP@s56%TIe-f`qD;2z8-33`)Wbb3^0g-&q}glddH(;?Jjy?4_bDR|U2ubs$7S@lA+=!Gg?NXXwIuLY32d6m!B2W-HXcQOb3o?Lky!$TQuj;6hQv zHOtJGUCi~f@u!Kv1F8*GU?KdH8E=cYmP|HCz*f&b_KMO`*UMb^H#@U;s5mrGU>MI~ zIFeVZi})nx564zj09j3`bC)?t#VZiBPpL~146}m%h@vM)s||Z1bGf)73Qpfh-8e>1 z4Ur(ZGUGA8+#loM+*^xdXlx%XaBO`an;#atoDk6(VWc-@(^I+ z3VXeMie8{ZVe%g2#hKK{LK#=k5iMLbbWXH%1s;1|=(uXUnVb;LsCUL`8Ti~FG4B(v z0hpNe%6C!Jgk*7@Bss8%baq249_1R~%jFurM7QkFyVw!Tx8EG%l`r zFkem-z{vf3v0k06aGlWpgRpkWB*PZ*rv$BcH|wzC>2iY$y|;_w#X0~H(EDh1dbyZP zZcpRQ%5NRqoYG~z)Z$k7ZPI-yy-nLu9yH1x$rvWee8Sl)tz-)_yPF*uGh6iv|GYl6 zKeyRw@`6^fVy&{6ZG1$)I;Tc8VoRI34Mv104PKM+5XCW zQOiPfxJ=l{&492T$ncwqslYvsgcQ2uI2J z;tAdRjJ?HT-SY^V+eQ8n^Roi2@loaJe6yOKz`4jhRTGLZNNG(e8gn z8XN-n;JFKD>-2Va-GQKx7=3IrGXthPbInzR{uOyS;-9TR*b`75Y;HnN*0`{=R-6ut z5N%8?TUxRNg79b-+Y9i%LcJ&k0N;D@=5ld5|LS@<52gtE>^1WZjB%qzs(?-+EE@Kd zruOK~#|Nu}>7?XqMCnE!>sI!4_9GmmFXXEa#R~TN$E6h#=#b7Gs<)2F9@)>4wSf;( z1?Phz)2HU-2Kp47*`#Y)iD|qCK@oe*(j5|LND4hlR8d{OU~($)hg z@x>CcTw-ss=qr^jV0gHDFkh4zsR^6}XSeE{|t(T);?`U7lWSi2im9brRQ#j2{Zp40lqS+-k;uKl32_5=LkZh_PklTw*h007STR4vpdy%k-klFBy(6 zFU{2_`0OZ?q*std?Rcgq#Jy9R=%P>Mh>I=~-ilCy11obar`~E^LdgkzQ@d;;H9`NEsKpx>|vEjm!&O zVNLOquq#S>4Bf>WcXVCz^DV+nI7Jpr{G-)5s@h*3ZE+hkZ4YZFN$nWdEjh*!cH5|F zMlN*m^>qF`??;k>Xw^;N+a<(q_aKWhufuP z44w_abGN#w^x8>S=%!@#94#-V-bDb(J}#;w$PB=x zAX0gYhOj+v_a?N34(heA4%(n0>ot8rDAD{ydBr3 z!5n`+E;G)Dk$0&_0Y2LBO%*&wWxJ%qF)c>y&tAl3xkCXVd*Nz*%8E?b zwmwJLAkU-rgq3IfYzjffe`dGieW-g6XU8ZZaS54Pc>fKN1gTQiTO7V{coAVz;qEu2 zvu)ssoEc$)@zk&R1yhumM~1j`UJo5VGh?gf*%yZVeGsCKe!iO- z`tj`fX1e(Ba&{^TLa%2@G^#K%E=UEIW@K0choQS2Y0E3ncVu zb_SC@V)FgRqUibJ!qS#4>Kst>s>R}jg=T)Ii3|>YE)SOpDo4uX#CHD9(2@9_b^@5O zaePQAPYuL|BCG6U%F0QKuXQa6Dll(-CpqY%*EW(SFiQNG-Me#2`Ae?gGQ8#s1h_AM)sQwtc!-k_=XM>RC-PgkX8vNdcaF^aJy7f3#d?KnL$}Y>M~9co)A?7HbN&b^g?IeL@7FwD`>bn)zHaj~6ZjYwt-y-sKAHHs~U zKIC`mho*rp!<1)dONdmtB-ly&SMWRiEb)(ql=de- zO`ncN@;odiT*CiDy!)w||Mz|_G#|_voeo*^g#=o-tU*I!> ziS$3ZhCk@%TKNBn@LT^B;2ixqzSQlnU5jta^EFu*cf!jX$@4FZ_V52%d{LhA9yd?z zd5-#>Hv zG|ks|Jbu1jG`Lpu_ish}`}bpedH%;Q*ak&+qkk{jUwbdMm*<~;!?qXvkx&1tX#d^6 ziS6b2*9oy=i*o$`!N){$jHaWL@5S~fe;1!6yk&fOeh#k@$w~WX-2NH2m-pi68UN+; zFQ7e*B<;V&?Z3tCe;B7B%@h8~2VcVXv_xtD{=dcs@Be*#3jPuO(~pcR>-sBvMsG^{ zPre`9eew_Sc@iJgH2g?=dHx2zr&px?=m*^3pW^dcY?l5n?c{^s!fW)Iw117;U*q=Q z{V91fK3}tcj;^CUjdZ>ET-yI;@p+t8Y(rns-wF5CyN`JMAHEwu{8c>e;GfK2_#aJA o<{saS|G)lAvDa_@i~cl^E1!N5zj*Ec>_21sS7pN7p!jq2f3a!cjQ{`u diff --git a/pathTest.cpp b/pathTest.cpp index de43f95c..8922c8d7 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -1,8 +1,8 @@ -#include +#include #include -#include -#include +#include +#include #include @@ -50,6 +50,7 @@ using namespace Pronounce; int testPathIndex; int fps = 60; +double playbackMultiplier = 0.5; #define xOffset 30 #define yOffset 30 @@ -306,9 +307,9 @@ int main() { QuadraticSplinePath quadraticSplineTestPath = QuadraticSplinePath(); - quadraticSplineTestPath.addPoint(SplinePoint(Point(24.0, 24.0), Vector(0.0, 50.0))); - quadraticSplineTestPath.addPoint(SplinePoint(Point(70.3, 70.3), Vector(0.0, 50.0))); - quadraticSplineTestPath.addPoint(SplinePoint(Point(24, 120.3), Vector(0.0, 50.0))); + quadraticSplineTestPath.addPoint(SplinePoint(Point(24.0, 24.0), Vector(30.0, 0.0))); + quadraticSplineTestPath.addPoint(SplinePoint(Point(70.3, 70.3), Vector(30.0, 0.0))); + quadraticSplineTestPath.addPoint(SplinePoint(Point(24, 120.3), Vector(30.0, 0.0))); testPathIndex = purePursuit.addPath(quadraticSplineTestPath.getPath(0.1)); @@ -375,12 +376,12 @@ int main() { line(odometry.getPosition()->getY() * multiplier, odometry.getPosition()->getX() * multiplier, purePursuit.getPointData().lookaheadPoint.getY() * multiplier, purePursuit.getPointData().lookaheadPoint.getX() * multiplier); printRobot(odometry, 15, purePursuit.getPointData().curvature); - delay(1000/fps); + delay(1000/fps/playbackMultiplier); #endif // PRINT_LIVE robotPositions.emplace_back(Point(odometry.getPosition()->getX(), odometry.getPosition()->getY())); #endif - if (loopcount > 2*fps * purePursuit.getPaths().size()) { + if (loopcount > 5*fps * purePursuit.getPaths().size()) { break; } } @@ -411,7 +412,7 @@ int main() { printRobot(odometry, 15, purePursuit.getPointData().curvature); // Print loopcount - std::cout << "Loopcount: " << loopcount << std::endl; + std::cout << "Time: " << loopcount/(double) fps << std::endl; delay(500000); closegraph(); diff --git a/src/chassis/simTankDrivetrain.cpp b/src/chassis/simTankDrivetrain.cpp index 991aab8c..f6e60eea 100644 --- a/src/chassis/simTankDrivetrain.cpp +++ b/src/chassis/simTankDrivetrain.cpp @@ -41,8 +41,6 @@ namespace Pronounce { newPosition->add(localOffset.getCartesian()); newPosition->setTheta(relativeAngle - (angle / 2.0)); - - std::cout << "X: " << newPosition->getX() << " Y: " << newPosition->getY() << " Theta: " << newPosition->getTheta() << std::endl; this->setPosition(newPosition); } diff --git a/src/motionControl/purePursuit.cpp b/src/motionControl/purePursuit.cpp index fbaa37d3..427226bc 100644 --- a/src/motionControl/purePursuit.cpp +++ b/src/motionControl/purePursuit.cpp @@ -50,13 +50,6 @@ namespace Pronounce { double xDistance = robotRelativeLookaheadVector.getCartesian().getX(); double signedCurvature = (2 * xDistance) / pow(lookaheadVector.getMagnitude(), 2); - std::cout << "X Distance: " << xDistance << std::endl; - std::cout << "Y Distance: " << robotRelativeLookaheadVector.getCartesian().getY() << std::endl; - std::cout << "Angle: " << robotRelativeLookaheadVector.getAngle() << std::endl; - std::cout << "Lookahead Angle: " << lookaheadVector.getAngle() << std::endl; - std::cout << "Other Angle: " << robotRelativeLookaheadVector.getAngle() + currentPosition->getTheta() << std::endl; - std::cout << "Robot Angle: " << currentPosition->getTheta() << std::endl; - this->pointData.lookaheadPoint = lookaheadPoint; this->pointData.lookaheadVector = lookaheadVector; this->pointData.localLookaheadVector = robotRelativeLookaheadVector; diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index bb1db300..85b332ae 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -25,17 +25,21 @@ namespace Pronounce { PurePursuitPointData pointData = this->getPointData(); - double side = clamp(pointData.localLookaheadVector.getCartesian().getY() / this->getLookahead(), -1, 1); + double side = sqrt(abs(clamp(pointData.localLookaheadVector.getCartesian().getY() / this->getLookahead(), -1.0, 1.0))) * signum_c(pointData.localLookaheadVector.getCartesian().getY()); - side = side < 0.3 ? 1 : side; + side = side < 0.5 ? 1.0 : side; - double scalar = pointData.lookaheadVector.getMagnitude() / this->getLookahead(); + // Redundant scalar, could be used in the future + // Found that using the Y values got the same affect when this was wanted and a better affect when it wasn't + // Using the same equation with Y instead. + // Time difference on test path(In sim) + // Before change: 3.4667 + // After change: 3.08 + // 12% improvement, mostly in speed up and slow down. + double scalar = 1; // pointData.lookaheadVector.getMagnitude() / this->getLookahead(); double speed = clamp(this->getSpeed() * side * scalar, -this->getSpeed(), this->getSpeed()); - std::cout << "Curvature: " << pointData.curvature << std::endl; - std::cout << "Speed: " << speed << std::endl; - // Drive backwards if (speed < 0) { pointData.curvature = -pointData.curvature; From 33a508e3bf42a18068089bb19a5f77060ce21258 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Thu, 13 Jan 2022 12:50:53 -0700 Subject: [PATCH 20/21] Add backwards driving functionality, tested and working AWP path too --- include/chassis/abstractTankDrivetrain.hpp | 10 ++--- include/chassis/simDrivetrain.hpp | 14 +++++++ pathTest.cpp | 46 +++++++++++++++++----- src/chassis/simTankDrivetrain.cpp | 2 +- src/motionControl/tankPurePursuit.cpp | 7 +--- 5 files changed, 58 insertions(+), 21 deletions(-) diff --git a/include/chassis/abstractTankDrivetrain.hpp b/include/chassis/abstractTankDrivetrain.hpp index 1f2b0217..51adf631 100644 --- a/include/chassis/abstractTankDrivetrain.hpp +++ b/include/chassis/abstractTankDrivetrain.hpp @@ -20,13 +20,13 @@ namespace Pronounce { } void driveCurvature(double speed, double curvature) { - double leftSpeed = speed * (2 - curvature * trackWidth) / 2; - double rightSpeed = speed * (2 + curvature * trackWidth) / 2; + double leftSpeed = speed * (2.0 - curvature * trackWidth) / 2.0; + double rightSpeed = speed * (2.0 + curvature * trackWidth) / 2.0; - double maxSpeed = max(leftSpeed, rightSpeed); + double maxSpeed = max(abs(leftSpeed), abs(rightSpeed)); - if (maxSpeed > speed) { - double multiplier = speed / maxSpeed; + if (maxSpeed > abs(speed)) { + double multiplier = abs(speed) / maxSpeed; leftSpeed *= multiplier; rightSpeed *= multiplier; } diff --git a/include/chassis/simDrivetrain.hpp b/include/chassis/simDrivetrain.hpp index c1a96e01..d1fe0eb7 100644 --- a/include/chassis/simDrivetrain.hpp +++ b/include/chassis/simDrivetrain.hpp @@ -11,6 +11,7 @@ namespace Pronounce { class SimDrivetrain { private: Position* position; + double resetOrientation = 0.0; public: SimDrivetrain(); SimDrivetrain(Position* position); @@ -23,6 +24,19 @@ namespace Pronounce { this->position = position; } + double getResetOrientation() { + return resetOrientation; + } + + void setResetOrientation(double resetPosition) { + this->resetOrientation = resetOrientation; + } + + void reset(Position* position) { + this->position->operator=(position); + this->resetOrientation = position->getTheta(); + } + virtual void update() {} ~SimDrivetrain(); diff --git a/pathTest.cpp b/pathTest.cpp index 8922c8d7..a542cd1e 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -48,6 +48,9 @@ using namespace Pronounce; int testPathIndex; +int leftAllianceToRightHomeZoneIndex; +int rightHomeZoneToRightAllianceIndex; +int rightAllianceToRightRingsIndex; int fps = 60; double playbackMultiplier = 0.5; @@ -305,13 +308,37 @@ int main() { testPathIndex = purePursuit.addPath(testPath.getPath(0.1)); */ - QuadraticSplinePath quadraticSplineTestPath = QuadraticSplinePath(); - quadraticSplineTestPath.addPoint(SplinePoint(Point(24.0, 24.0), Vector(30.0, 0.0))); - quadraticSplineTestPath.addPoint(SplinePoint(Point(70.3, 70.3), Vector(30.0, 0.0))); - quadraticSplineTestPath.addPoint(SplinePoint(Point(24, 120.3), Vector(30.0, 0.0))); + QuadraticSplinePath leftAllianceToRightHomeZone = QuadraticSplinePath(); - testPathIndex = purePursuit.addPath(quadraticSplineTestPath.getPath(0.1)); + leftAllianceToRightHomeZone.addPoint(SplinePoint(Point(30.0, 11.4), Vector(15.0, M_PI_2))); + leftAllianceToRightHomeZone.addPoint(SplinePoint(Point(15.2, 35.0), Vector(15.0, 0.0))); + leftAllianceToRightHomeZone.addPoint(SplinePoint(Point(46.4, 46.4), Vector(15.0, M_PI_2))); + leftAllianceToRightHomeZone.addPoint(SplinePoint(Point(93.9, 46.4), Vector(15.0, M_PI_2))); + + leftAllianceToRightHomeZoneIndex = purePursuit.addPath(leftAllianceToRightHomeZone.getPath(0.1)); + + QuadraticSplinePath rightHomeZoneToRightAlliance = QuadraticSplinePath(); + + rightHomeZoneToRightAlliance.addPoint(SplinePoint(Point(93.9, 46.4), Vector(15.0, -M_PI_2))); + rightHomeZoneToRightAlliance.addPoint(SplinePoint(Point(123.0, 40.0), Vector(15.0, - M_PI_2 - M_PI_4))); + + rightHomeZoneToRightAllianceIndex = purePursuit.addPath(rightHomeZoneToRightAlliance.getPath(0.1)); + + QuadraticSplinePath rightAllianceToRightRings = QuadraticSplinePath(); + + rightAllianceToRightRings.addPoint(SplinePoint(Point(123.0, 40.0), Vector(15.0, - M_PI_2 - M_PI_4))); + rightAllianceToRightRings.addPoint(SplinePoint(Point(117.5, 46.8), Vector(0.0, 0.0))); + rightAllianceToRightRings.addPoint(SplinePoint(Point(117.5, 70.3), Vector(20.0, 0.0))); + + rightAllianceToRightRingsIndex = purePursuit.addPath(rightAllianceToRightRings.getPath(0.1)); + + QuadraticSplinePath rightRingsToRightHomeZone = QuadraticSplinePath(); + + rightAllianceToRightRings.addPoint(SplinePoint(Point(117.5, 70.3), Vector(20.0, M_PI))); + rightAllianceToRightRings.addPoint(SplinePoint(Point(85, 36), Vector(20.0, M_PI_2))); + + rightAllianceToRightRingsIndex = purePursuit.addPath(rightAllianceToRightRings.getPath(0.1)); #if GRAPH @@ -324,9 +351,9 @@ int main() { delay(1000); //printPath(path); #endif - Position startingPosition(24, 24, 0); + Position startingPosition(30.0, 11.4, -M_PI_2); - drivetrain.setPosition(&startingPosition); + drivetrain.reset(&startingPosition); #if GRAPH std::vector robotPositions; @@ -351,7 +378,7 @@ int main() { loopcount++; odometry.update(); - //drivetrain.driveCurvature(1, (1.0 / 24.0)); + // drivetrain.driveCurvature(-1.0, (1.0 / 24.0)); purePursuit.update(); drivetrain.update(); @@ -381,7 +408,8 @@ int main() { robotPositions.emplace_back(Point(odometry.getPosition()->getX(), odometry.getPosition()->getY())); #endif - if (loopcount > 5*fps * purePursuit.getPaths().size()) { + + if (loopcount >= 5*fps * purePursuit.getPaths().size() || (odometry.getPosition()->getX() < 0 || odometry.getPosition()->getX() > 144 || odometry.getPosition()->getY() < 0 || odometry.getPosition()->getY() > 144)) { break; } } diff --git a/src/chassis/simTankDrivetrain.cpp b/src/chassis/simTankDrivetrain.cpp index f6e60eea..342336c7 100644 --- a/src/chassis/simTankDrivetrain.cpp +++ b/src/chassis/simTankDrivetrain.cpp @@ -31,7 +31,7 @@ namespace Pronounce { leftDistance += leftVelocity; rightDistance += rightVelocity; - double relativeAngle = (leftDistance - rightDistance) / this->getTrackWidth(); + double relativeAngle = ((leftDistance - rightDistance) / this->getTrackWidth()) + this->getResetOrientation(); // Calculate a vector Vector localOffset(offset, relativeAngle+M_PI_2); diff --git a/src/motionControl/tankPurePursuit.cpp b/src/motionControl/tankPurePursuit.cpp index 85b332ae..37116e1f 100644 --- a/src/motionControl/tankPurePursuit.cpp +++ b/src/motionControl/tankPurePursuit.cpp @@ -27,7 +27,7 @@ namespace Pronounce { double side = sqrt(abs(clamp(pointData.localLookaheadVector.getCartesian().getY() / this->getLookahead(), -1.0, 1.0))) * signum_c(pointData.localLookaheadVector.getCartesian().getY()); - side = side < 0.5 ? 1.0 : side; + side = abs(side) < 0.5 ? signum_c(side) : side; // Redundant scalar, could be used in the future // Found that using the Y values got the same affect when this was wanted and a better affect when it wasn't @@ -40,11 +40,6 @@ namespace Pronounce { double speed = clamp(this->getSpeed() * side * scalar, -this->getSpeed(), this->getSpeed()); - // Drive backwards - if (speed < 0) { - pointData.curvature = -pointData.curvature; - } - drivetrain->driveCurvature(speed, pointData.curvature); } From 5fb0f8569c4633d9e57c6b520cd6388737c2c6a4 Mon Sep 17 00:00:00 2001 From: ad101-lab <55064247+ad101-lab@users.noreply.github.com> Date: Thu, 13 Jan 2022 15:00:54 -0700 Subject: [PATCH 21/21] Fix AWP Paths --- pathTest.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pathTest.cpp b/pathTest.cpp index a542cd1e..979e5bc9 100644 --- a/pathTest.cpp +++ b/pathTest.cpp @@ -53,7 +53,7 @@ int rightHomeZoneToRightAllianceIndex; int rightAllianceToRightRingsIndex; int fps = 60; -double playbackMultiplier = 0.5; +double playbackMultiplier = 1; #define xOffset 30 #define yOffset 30