From dd34417768728de6f58f134f36c73c7a91093545 Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Sat, 14 Jan 2023 10:27:37 -0800 Subject: [PATCH 001/103] Initial commit --- .github/workflows/deploy.yml | 32 ++ .github/workflows/main.yml | 36 ++ .gitignore | 168 +++++++ .vscode/launch.json | 28 ++ .vscode/settings.json | 35 ++ .vscode/tasks.json | 41 ++ .wpilib/wpilib_preferences.json | 6 + CONTRIBUTORS.md | 15 + README.md | 7 + WPILib-License.md | 24 + build.gradle | 146 ++++++ deploy_sim.sh | 60 +++ deps/commons-math3-3.6.1.jar | Bin 0 -> 2213560 bytes deps/gral-core-0.11.jar | Bin 0 -> 280268 bytes deps/json-20190722.jar | Bin 0 -> 65003 bytes gradle/wrapper/gradle-wrapper.jar | Bin 0 -> 59536 bytes gradle/wrapper/gradle-wrapper.properties | 5 + gradlew | 234 +++++++++ gradlew.bat | 89 ++++ settings.gradle | 27 ++ simConfig.txt | 102 ++++ src/main/deploy/example.txt | 3 + .../config/AbstractConfigMultiValue.java | 35 ++ .../team766/config/AbstractConfigValue.java | 93 ++++ .../com/team766/config/ConfigFileReader.java | 182 +++++++ .../java/com/team766/config/ConfigValue.java | 94 ++++ .../config/ConfigValueParseException.java | 13 + .../team766/controllers/MotionLockout.java | 57 +++ .../team766/controllers/PIDController.java | 350 ++++++++++++++ .../com/team766/controllers/RangeBound.java | 36 ++ .../RangeOfMotionMotorCommandBound.java | 54 +++ .../team766/controllers/TimeProviderI.java | 5 + .../com/team766/framework/AutonomousMode.java | 30 ++ .../java/com/team766/framework/Context.java | 454 ++++++++++++++++++ .../framework/ContextStoppedException.java | 10 + .../team766/framework/LaunchedContext.java | 19 + .../com/team766/framework/LoggingBase.java | 27 ++ .../java/com/team766/framework/Mechanism.java | 85 ++++ .../java/com/team766/framework/Procedure.java | 32 ++ .../framework/RunnableWithContext.java | 6 + .../java/com/team766/framework/Scheduler.java | 96 ++++ .../team766/framework/StackTraceUtils.java | 25 + .../framework/WPILibCommandProcedure.java | 48 ++ .../com/team766/hal/AnalogInputReader.java | 23 + .../com/team766/hal/BasicMotorController.java | 20 + .../java/com/team766/hal/CameraInterface.java | 9 + .../java/com/team766/hal/CameraReader.java | 7 + src/main/java/com/team766/hal/Clock.java | 5 + .../com/team766/hal/ControlInputReader.java | 13 + .../com/team766/hal/DigitalInputReader.java | 11 + .../java/com/team766/hal/DoubleSolenoid.java | 62 +++ .../java/com/team766/hal/EncoderReader.java | 73 +++ .../com/team766/hal/GenericRobotMain.java | 136 ++++++ src/main/java/com/team766/hal/GyroReader.java | 61 +++ .../java/com/team766/hal/JoystickReader.java | 46 ++ .../com/team766/hal/LocalMotorController.java | 271 +++++++++++ .../java/com/team766/hal/MotorController.java | 138 ++++++ ...MotorControllerCommandFailedException.java | 13 + .../hal/MotorControllerWithSensorScale.java | 158 ++++++ .../java/com/team766/hal/MultiSolenoid.java | 27 ++ .../java/com/team766/hal/PositionReader.java | 24 + .../java/com/team766/hal/RelayOutput.java | 16 + .../java/com/team766/hal/RobotProvider.java | 234 +++++++++ .../com/team766/hal/SolenoidController.java | 19 + .../com/team766/hal/VidSourceInterface.java | 5 + .../com/team766/hal/mock/MockAnalogInput.java | 18 + .../java/com/team766/hal/mock/MockCamera.java | 25 + .../team766/hal/mock/MockDigitalInput.java | 17 + .../com/team766/hal/mock/MockEncoder.java | 57 +++ .../java/com/team766/hal/mock/MockGyro.java | 52 ++ .../com/team766/hal/mock/MockJoystick.java | 69 +++ .../team766/hal/mock/MockMotorController.java | 28 ++ .../team766/hal/mock/MockPositionSensor.java | 38 ++ .../java/com/team766/hal/mock/MockRelay.java | 22 + .../com/team766/hal/mock/MockSolenoid.java | 21 + .../team766/hal/mock/TestRobotProvider.java | 129 +++++ .../team766/hal/simulator/AnalogInput.java | 19 + .../com/team766/hal/simulator/Camera.java | 14 + .../team766/hal/simulator/DigitalInput.java | 18 + .../com/team766/hal/simulator/Encoder.java | 54 +++ .../java/com/team766/hal/simulator/Gyro.java | 32 ++ .../team766/hal/simulator/PositionSensor.java | 23 + .../java/com/team766/hal/simulator/Relay.java | 32 ++ .../com/team766/hal/simulator/RobotMain.java | 123 +++++ .../hal/simulator/SimMotorController.java | 54 +++ .../hal/simulator/SimulationClock.java | 15 + .../simulator/SimulationRobotProvider.java | 120 +++++ .../com/team766/hal/simulator/Solenoid.java | 22 + .../team766/hal/simulator/VrConnector.java | 339 +++++++++++++ .../com/team766/hal/wpilib/ADXRS450_Gyro.java | 26 + .../com/team766/hal/wpilib/AnalogGyro.java | 17 + .../com/team766/hal/wpilib/AnalogInput.java | 9 + .../hal/wpilib/BaseCTRESpeedController.java | 30 ++ .../wpilib/CANSparkMaxMotorController.java | 232 +++++++++ .../hal/wpilib/CANTalonFxMotorController.java | 190 ++++++++ .../hal/wpilib/CANTalonMotorController.java | 191 ++++++++ .../hal/wpilib/CANVictorMotorController.java | 188 ++++++++ .../team766/hal/wpilib/CameraInterface.java | 39 ++ .../com/team766/hal/wpilib/DigitalInput.java | 9 + .../java/com/team766/hal/wpilib/Encoder.java | 9 + .../java/com/team766/hal/wpilib/Joystick.java | 29 ++ .../java/com/team766/hal/wpilib/NavXGyro.java | 55 +++ .../com/team766/hal/wpilib/PWMVictorSP.java | 16 + .../java/com/team766/hal/wpilib/Relay.java | 38 ++ .../com/team766/hal/wpilib/RobotMain.java | 151 ++++++ .../java/com/team766/hal/wpilib/Solenoid.java | 11 + .../com/team766/hal/wpilib/SystemClock.java | 12 + .../team766/hal/wpilib/WPIRobotProvider.java | 184 +++++++ .../com/team766/library/CircularBuffer.java | 72 +++ .../team766/library/LossyPriorityQueue.java | 61 +++ .../java/com/team766/library/RateLimiter.java | 27 ++ .../com/team766/library/SetValueProvider.java | 36 ++ .../library/SettableValueProvider.java | 7 + .../com/team766/library/ValueProvider.java | 14 + .../team766/logging/LogEntryComparator.java | 30 ++ .../com/team766/logging/LogEntryRenderer.java | 17 + .../java/com/team766/logging/LogReader.java | 51 ++ .../java/com/team766/logging/LogWriter.java | 108 +++++ .../java/com/team766/logging/Loggable.java | 5 + src/main/java/com/team766/logging/Logger.java | 132 +++++ .../team766/logging/LoggerExceptionUtils.java | 25 + .../team766/logging/SerializationUtils.java | 50 ++ src/main/java/com/team766/math/Algebraic.java | 7 + src/main/java/com/team766/math/Filter.java | 7 + src/main/java/com/team766/math/FirFilter.java | 21 + src/main/java/com/team766/math/IirFilter.java | 27 ++ .../com/team766/math/IsometricTransform.java | 40 ++ .../com/team766/math/LinearInterpolation.java | 53 ++ src/main/java/com/team766/math/Math.java | 22 + .../java/com/team766/math/TransformTree.java | 83 ++++ src/main/java/com/team766/math/Vector3.java | 60 +++ .../com/team766/robot/AutonomousModes.java | 18 + src/main/java/com/team766/robot/OI.java | 36 ++ src/main/java/com/team766/robot/Robot.java | 13 + .../robot/mechanisms/ExampleMechanism.java | 22 + .../java/com/team766/robot/mechanisms/README | 1 + .../team766/robot/procedures/DoNothing.java | 11 + .../java/com/team766/robot/procedures/README | 1 + .../team766/simulator/ElectricalSystem.java | 35 ++ .../com/team766/simulator/Parameters.java | 28 ++ .../team766/simulator/PhysicalConstants.java | 7 + .../team766/simulator/PneumaticsSystem.java | 61 +++ .../java/com/team766/simulator/Program.java | 7 + .../team766/simulator/ProgramInterface.java | 99 ++++ .../java/com/team766/simulator/Simulator.java | 82 ++++ .../simulator/elements/AirCompressor.java | 56 +++ .../simulator/elements/AirReservoir.java | 17 + .../elements/CanMotorController.java | 21 + .../team766/simulator/elements/DCMotor.java | 49 ++ .../DoubleActingPneumaticCylinder.java | 52 ++ .../team766/simulator/elements/DriveBase.java | 4 + .../elements/ElectricalResistance.java | 35 ++ .../com/team766/simulator/elements/Gears.java | 26 + .../simulator/elements/MotorController.java | 22 + .../elements/PwmMotorController.java | 21 + .../SingleActingPneumaticCylinder.java | 55 +++ .../com/team766/simulator/elements/Wheel.java | 40 ++ .../interfaces/ElectricalDevice.java | 27 ++ .../interfaces/MechanicalAngularDevice.java | 27 ++ .../interfaces/MechanicalDevice.java | 32 ++ .../simulator/interfaces/PneumaticDevice.java | 40 ++ .../simulator/mechanisms/WestCoastDrive.java | 147 ++++++ .../com/team766/simulator/ui/Metrics.java | 160 ++++++ .../com/team766/simulator/ui/Trajectory.java | 143 ++++++ .../com/team766/web/AutonomousSelector.java | 96 ++++ src/main/java/com/team766/web/ConfigUI.java | 89 ++++ src/main/java/com/team766/web/Dashboard.java | 60 +++ .../java/com/team766/web/DriverInterface.java | 30 ++ .../java/com/team766/web/HtmlElements.java | 31 ++ src/main/java/com/team766/web/LogViewer.java | 109 +++++ src/main/java/com/team766/web/ReadLogs.java | 158 ++++++ src/main/java/com/team766/web/WebServer.java | 213 ++++++++ .../com/team766/web/dashboard/NewSection.java | 30 ++ .../team766/web/dashboard/StatusLight.java | 45 ++ .../com/team766/web/dashboard/Widget.java | 31 ++ .../proto/com/team766/logging/logging.proto | 63 +++ src/test/java/com/team766/TestCase.java | 22 + .../team766/config/ConfigFileReaderTest.java | 43 ++ .../library/LossyPriorityQueueTest.java | 26 + .../java/com/team766/logging/LoggerTest.java | 90 ++++ to-do.txt | 1 + vendordeps/Phoenix.json | 257 ++++++++++ vendordeps/REVLib.json | 73 +++ vendordeps/WPILibNewCommands.json | 37 ++ vendordeps/WPILibOldCommands.json | 37 ++ vendordeps/navx_frc.json | 35 ++ 186 files changed, 10883 insertions(+) create mode 100644 .github/workflows/deploy.yml create mode 100644 .github/workflows/main.yml create mode 100644 .gitignore create mode 100644 .vscode/launch.json create mode 100644 .vscode/settings.json create mode 100644 .vscode/tasks.json create mode 100644 .wpilib/wpilib_preferences.json create mode 100644 CONTRIBUTORS.md create mode 100644 README.md create mode 100644 WPILib-License.md create mode 100644 build.gradle create mode 100755 deploy_sim.sh create mode 100644 deps/commons-math3-3.6.1.jar create mode 100644 deps/gral-core-0.11.jar create mode 100644 deps/json-20190722.jar create mode 100644 gradle/wrapper/gradle-wrapper.jar create mode 100644 gradle/wrapper/gradle-wrapper.properties create mode 100755 gradlew create mode 100644 gradlew.bat create mode 100644 settings.gradle create mode 100644 simConfig.txt create mode 100644 src/main/deploy/example.txt create mode 100644 src/main/java/com/team766/config/AbstractConfigMultiValue.java create mode 100644 src/main/java/com/team766/config/AbstractConfigValue.java create mode 100755 src/main/java/com/team766/config/ConfigFileReader.java create mode 100644 src/main/java/com/team766/config/ConfigValue.java create mode 100644 src/main/java/com/team766/config/ConfigValueParseException.java create mode 100644 src/main/java/com/team766/controllers/MotionLockout.java create mode 100755 src/main/java/com/team766/controllers/PIDController.java create mode 100644 src/main/java/com/team766/controllers/RangeBound.java create mode 100644 src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java create mode 100644 src/main/java/com/team766/controllers/TimeProviderI.java create mode 100644 src/main/java/com/team766/framework/AutonomousMode.java create mode 100644 src/main/java/com/team766/framework/Context.java create mode 100644 src/main/java/com/team766/framework/ContextStoppedException.java create mode 100644 src/main/java/com/team766/framework/LaunchedContext.java create mode 100644 src/main/java/com/team766/framework/LoggingBase.java create mode 100644 src/main/java/com/team766/framework/Mechanism.java create mode 100644 src/main/java/com/team766/framework/Procedure.java create mode 100644 src/main/java/com/team766/framework/RunnableWithContext.java create mode 100644 src/main/java/com/team766/framework/Scheduler.java create mode 100644 src/main/java/com/team766/framework/StackTraceUtils.java create mode 100644 src/main/java/com/team766/framework/WPILibCommandProcedure.java create mode 100755 src/main/java/com/team766/hal/AnalogInputReader.java create mode 100644 src/main/java/com/team766/hal/BasicMotorController.java create mode 100755 src/main/java/com/team766/hal/CameraInterface.java create mode 100755 src/main/java/com/team766/hal/CameraReader.java create mode 100644 src/main/java/com/team766/hal/Clock.java create mode 100644 src/main/java/com/team766/hal/ControlInputReader.java create mode 100755 src/main/java/com/team766/hal/DigitalInputReader.java create mode 100755 src/main/java/com/team766/hal/DoubleSolenoid.java create mode 100755 src/main/java/com/team766/hal/EncoderReader.java create mode 100755 src/main/java/com/team766/hal/GenericRobotMain.java create mode 100755 src/main/java/com/team766/hal/GyroReader.java create mode 100755 src/main/java/com/team766/hal/JoystickReader.java create mode 100644 src/main/java/com/team766/hal/LocalMotorController.java create mode 100755 src/main/java/com/team766/hal/MotorController.java create mode 100644 src/main/java/com/team766/hal/MotorControllerCommandFailedException.java create mode 100644 src/main/java/com/team766/hal/MotorControllerWithSensorScale.java create mode 100644 src/main/java/com/team766/hal/MultiSolenoid.java create mode 100644 src/main/java/com/team766/hal/PositionReader.java create mode 100755 src/main/java/com/team766/hal/RelayOutput.java create mode 100755 src/main/java/com/team766/hal/RobotProvider.java create mode 100755 src/main/java/com/team766/hal/SolenoidController.java create mode 100755 src/main/java/com/team766/hal/VidSourceInterface.java create mode 100755 src/main/java/com/team766/hal/mock/MockAnalogInput.java create mode 100755 src/main/java/com/team766/hal/mock/MockCamera.java create mode 100755 src/main/java/com/team766/hal/mock/MockDigitalInput.java create mode 100755 src/main/java/com/team766/hal/mock/MockEncoder.java create mode 100755 src/main/java/com/team766/hal/mock/MockGyro.java create mode 100755 src/main/java/com/team766/hal/mock/MockJoystick.java create mode 100755 src/main/java/com/team766/hal/mock/MockMotorController.java create mode 100644 src/main/java/com/team766/hal/mock/MockPositionSensor.java create mode 100755 src/main/java/com/team766/hal/mock/MockRelay.java create mode 100755 src/main/java/com/team766/hal/mock/MockSolenoid.java create mode 100755 src/main/java/com/team766/hal/mock/TestRobotProvider.java create mode 100755 src/main/java/com/team766/hal/simulator/AnalogInput.java create mode 100755 src/main/java/com/team766/hal/simulator/Camera.java create mode 100755 src/main/java/com/team766/hal/simulator/DigitalInput.java create mode 100755 src/main/java/com/team766/hal/simulator/Encoder.java create mode 100755 src/main/java/com/team766/hal/simulator/Gyro.java create mode 100644 src/main/java/com/team766/hal/simulator/PositionSensor.java create mode 100755 src/main/java/com/team766/hal/simulator/Relay.java create mode 100755 src/main/java/com/team766/hal/simulator/RobotMain.java create mode 100755 src/main/java/com/team766/hal/simulator/SimMotorController.java create mode 100644 src/main/java/com/team766/hal/simulator/SimulationClock.java create mode 100755 src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java create mode 100755 src/main/java/com/team766/hal/simulator/Solenoid.java create mode 100644 src/main/java/com/team766/hal/simulator/VrConnector.java create mode 100755 src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java create mode 100755 src/main/java/com/team766/hal/wpilib/AnalogGyro.java create mode 100755 src/main/java/com/team766/hal/wpilib/AnalogInput.java create mode 100644 src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java create mode 100755 src/main/java/com/team766/hal/wpilib/CameraInterface.java create mode 100755 src/main/java/com/team766/hal/wpilib/DigitalInput.java create mode 100755 src/main/java/com/team766/hal/wpilib/Encoder.java create mode 100755 src/main/java/com/team766/hal/wpilib/Joystick.java create mode 100644 src/main/java/com/team766/hal/wpilib/NavXGyro.java create mode 100755 src/main/java/com/team766/hal/wpilib/PWMVictorSP.java create mode 100755 src/main/java/com/team766/hal/wpilib/Relay.java create mode 100755 src/main/java/com/team766/hal/wpilib/RobotMain.java create mode 100755 src/main/java/com/team766/hal/wpilib/Solenoid.java create mode 100644 src/main/java/com/team766/hal/wpilib/SystemClock.java create mode 100755 src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java create mode 100644 src/main/java/com/team766/library/CircularBuffer.java create mode 100644 src/main/java/com/team766/library/LossyPriorityQueue.java create mode 100644 src/main/java/com/team766/library/RateLimiter.java create mode 100644 src/main/java/com/team766/library/SetValueProvider.java create mode 100644 src/main/java/com/team766/library/SettableValueProvider.java create mode 100644 src/main/java/com/team766/library/ValueProvider.java create mode 100644 src/main/java/com/team766/logging/LogEntryComparator.java create mode 100644 src/main/java/com/team766/logging/LogEntryRenderer.java create mode 100644 src/main/java/com/team766/logging/LogReader.java create mode 100644 src/main/java/com/team766/logging/LogWriter.java create mode 100644 src/main/java/com/team766/logging/Loggable.java create mode 100644 src/main/java/com/team766/logging/Logger.java create mode 100644 src/main/java/com/team766/logging/LoggerExceptionUtils.java create mode 100644 src/main/java/com/team766/logging/SerializationUtils.java create mode 100644 src/main/java/com/team766/math/Algebraic.java create mode 100644 src/main/java/com/team766/math/Filter.java create mode 100644 src/main/java/com/team766/math/FirFilter.java create mode 100644 src/main/java/com/team766/math/IirFilter.java create mode 100644 src/main/java/com/team766/math/IsometricTransform.java create mode 100644 src/main/java/com/team766/math/LinearInterpolation.java create mode 100644 src/main/java/com/team766/math/Math.java create mode 100644 src/main/java/com/team766/math/TransformTree.java create mode 100644 src/main/java/com/team766/math/Vector3.java create mode 100644 src/main/java/com/team766/robot/AutonomousModes.java create mode 100644 src/main/java/com/team766/robot/OI.java create mode 100644 src/main/java/com/team766/robot/Robot.java create mode 100644 src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java create mode 100644 src/main/java/com/team766/robot/mechanisms/README create mode 100644 src/main/java/com/team766/robot/procedures/DoNothing.java create mode 100644 src/main/java/com/team766/robot/procedures/README create mode 100644 src/main/java/com/team766/simulator/ElectricalSystem.java create mode 100644 src/main/java/com/team766/simulator/Parameters.java create mode 100644 src/main/java/com/team766/simulator/PhysicalConstants.java create mode 100644 src/main/java/com/team766/simulator/PneumaticsSystem.java create mode 100644 src/main/java/com/team766/simulator/Program.java create mode 100644 src/main/java/com/team766/simulator/ProgramInterface.java create mode 100644 src/main/java/com/team766/simulator/Simulator.java create mode 100644 src/main/java/com/team766/simulator/elements/AirCompressor.java create mode 100644 src/main/java/com/team766/simulator/elements/AirReservoir.java create mode 100644 src/main/java/com/team766/simulator/elements/CanMotorController.java create mode 100644 src/main/java/com/team766/simulator/elements/DCMotor.java create mode 100644 src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java create mode 100644 src/main/java/com/team766/simulator/elements/DriveBase.java create mode 100644 src/main/java/com/team766/simulator/elements/ElectricalResistance.java create mode 100644 src/main/java/com/team766/simulator/elements/Gears.java create mode 100644 src/main/java/com/team766/simulator/elements/MotorController.java create mode 100644 src/main/java/com/team766/simulator/elements/PwmMotorController.java create mode 100644 src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java create mode 100644 src/main/java/com/team766/simulator/elements/Wheel.java create mode 100644 src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java create mode 100644 src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java create mode 100644 src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java create mode 100644 src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java create mode 100644 src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java create mode 100644 src/main/java/com/team766/simulator/ui/Metrics.java create mode 100644 src/main/java/com/team766/simulator/ui/Trajectory.java create mode 100644 src/main/java/com/team766/web/AutonomousSelector.java create mode 100644 src/main/java/com/team766/web/ConfigUI.java create mode 100644 src/main/java/com/team766/web/Dashboard.java create mode 100644 src/main/java/com/team766/web/DriverInterface.java create mode 100644 src/main/java/com/team766/web/HtmlElements.java create mode 100644 src/main/java/com/team766/web/LogViewer.java create mode 100644 src/main/java/com/team766/web/ReadLogs.java create mode 100644 src/main/java/com/team766/web/WebServer.java create mode 100644 src/main/java/com/team766/web/dashboard/NewSection.java create mode 100644 src/main/java/com/team766/web/dashboard/StatusLight.java create mode 100644 src/main/java/com/team766/web/dashboard/Widget.java create mode 100644 src/main/proto/com/team766/logging/logging.proto create mode 100644 src/test/java/com/team766/TestCase.java create mode 100644 src/test/java/com/team766/config/ConfigFileReaderTest.java create mode 100644 src/test/java/com/team766/library/LossyPriorityQueueTest.java create mode 100644 src/test/java/com/team766/logging/LoggerTest.java create mode 100644 to-do.txt create mode 100644 vendordeps/Phoenix.json create mode 100644 vendordeps/REVLib.json create mode 100644 vendordeps/WPILibNewCommands.json create mode 100644 vendordeps/WPILibOldCommands.json create mode 100644 vendordeps/navx_frc.json diff --git a/.github/workflows/deploy.yml b/.github/workflows/deploy.yml new file mode 100644 index 00000000..80bc5106 --- /dev/null +++ b/.github/workflows/deploy.yml @@ -0,0 +1,32 @@ +name: Deploy + +# Controls when the workflow will run +on: + # Triggers the workflow on push or pull request events but only for the master branch + push: + branches: [ master ] + + # Allows you to run this workflow manually from the Actions tab + workflow_dispatch: + +# A workflow run is made up of one or more jobs that can run sequentially or in parallel +jobs: + publish: + runs-on: ubuntu-latest + permissions: + contents: read + packages: write + steps: + - uses: actions/checkout@v3 + - uses: actions/setup-java@v3 + with: + java-version: '11' + distribution: 'adopt' + - name: Validate Gradle wrapper + uses: gradle/wrapper-validation-action@e6e38bacfdf1a337459f332974bb2327a31aaf4b + - name: Publish package + uses: gradle/gradle-build-action@0d13054264b0bb894ded474f08ebb30921341cee + with: + arguments: publish + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} \ No newline at end of file diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml new file mode 100644 index 00000000..ab5ab753 --- /dev/null +++ b/.github/workflows/main.yml @@ -0,0 +1,36 @@ +# This is a basic workflow to help you get started with Actions + +name: CI + +# Controls when the workflow will run +on: + # Triggers the workflow on push or pull request events but only for the master branch + push: + branches: [ master ] + pull_request: + + # Allows you to run this workflow manually from the Actions tab + workflow_dispatch: + +# A workflow run is made up of one or more jobs that can run sequentially or in parallel +jobs: + # This workflow contains a single job called "build" + build: + # The type of runner that the job will run on + runs-on: ubuntu-latest + + # This grabs the WPILib docker container + container: wpilib/roborio-cross-ubuntu:2022-18.04 + + # Steps represent a sequence of tasks that will be executed as part of the job + steps: + # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it + - uses: actions/checkout@v2 + + # Grant execute permission for gradlew + - name: Grant execute permission for gradlew + run: chmod +x gradlew + + # Runs a single command using the runners shell + - name: Compile and run tests on robot code + run: ./gradlew build --info diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..c0044d2c --- /dev/null +++ b/.gitignore @@ -0,0 +1,168 @@ +# This gitignore has been specially created by the WPILib team. +# If you remove items from this file, intellisense might break. + +### C++ ### +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +### Java ### +# Compiled class file +*.class + +# Log file +*.log + +# BlueJ files +*.ctxt + +# Mobile Tools for Java (J2ME) +.mtj.tmp/ + +# Package Files # +*.jar +*.war +*.nar +*.ear +*.zip +*.tar.gz +*.rar + +# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml +hs_err_pid* + +### Linux ### +*~ + +# temporary files which can be created if a process still has a handle open of a deleted file +.fuse_hidden* + +# KDE directory preferences +.directory + +# Linux trash folder which might appear on any partition or disk +.Trash-* + +# .nfs files are created when an open file is removed but is still being accessed +.nfs* + +### macOS ### +# General +.DS_Store +.AppleDouble +.LSOverride + +# Icon must end with two \r +Icon + +# Thumbnails +._* + +# Files that might appear in the root of a volume +.DocumentRevisions-V100 +.fseventsd +.Spotlight-V100 +.TemporaryItems +.Trashes +.VolumeIcon.icns +.com.apple.timemachine.donotpresent + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json + +### Windows ### +# Windows thumbnail cache files +Thumbs.db +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk + +### Gradle ### +.gradle +/build/ + +# Ignore Gradle GUI config +gradle-app.setting + +# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) +!gradle-wrapper.jar + +# Cache of project +.gradletasknamecache + +# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 +# gradle/wrapper/gradle-wrapper.properties + +# # VS Code Specific Java Settings +# DO NOT REMOVE .classpath and .project +.classpath +.project +.settings/ +bin/ + +# Simulation GUI and other tools window save file +*-window.json + +# The list of available sim robots is environment-specific, so it shouldn't be committed +/sim_robots.lst + +# Don't commit logs written by the framework when running in sim +/sim_robot_logs \ No newline at end of file diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 00000000..8fbfc758 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,28 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + + { + "type": "wpilib", + "name": "WPILib Desktop Debug", + "request": "launch", + "desktop": true, + }, + { + "type": "wpilib", + "name": "WPILib roboRIO Debug", + "request": "launch", + "desktop": false, + }, + { + "type": "java", + "name": "Start 3d simulation mode", + "request": "launch", + "mainClass": "com.team766.hal.simulator.RobotMain", + "args": ["-vr_connector"] + } + ] +} diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..3cbfce66 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,35 @@ +{ + "java.configuration.updateBuildConfiguration": "automatic", + "java.server.launchMode": "Standard", + "files.exclude": { + "**/.git": true, + "**/.svn": true, + "**/.hg": true, + "**/CVS": true, + "**/.DS_Store": true, + "bin/": true, + "**/.classpath": true, + "**/.project": true, + "**/.settings": true, + "**/.factorypath": true, + "**/*~": true + }, + "java.test.config": [ + { + "name": "WPIlibUnitTests", + "workingDirectory": "${workspaceFolder}/build/jni/release", + "vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ], + "env": { + "LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" , + "DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" + } + }, + ], + "java.test.defaultConfig": "WPIlibUnitTests", + + "editor.formatOnSave": false, + "editor.insertSpaces": false, + "editor.tabSize": 4, + "diffEditor.ignoreTrimWhitespace": false, + "java.format.settings.url": "https://raw.githubusercontent.com/google/styleguide/gh-pages/eclipse-java-google-style.xml" +} diff --git a/.vscode/tasks.json b/.vscode/tasks.json new file mode 100644 index 00000000..e0ef0c9a --- /dev/null +++ b/.vscode/tasks.json @@ -0,0 +1,41 @@ +{ + // See https://go.microsoft.com/fwlink/?LinkId=733558 + // for the documentation about the tasks.json format + "version": "2.0.0", + "tasks": [ + { + "label": "Deploy Sim", + "type": "shell", + "command": "./deploy_sim.sh", + "problemMatcher": [], + "showOutput": "always", + "presentation": { + "echo": true, + "reveal": "always", + "focus": true, + "panel": "dedicated", + "showReuseMessage": false, + "clear": true + } + }, + { + "label": "Gradle Build", + "type": "shell", + "command": "./gradlew build", + "problemMatcher": [], + "showOutput": "always", + "presentation": { + "echo": true, + "reveal": "always", + "focus": true, + "panel": "dedicated", + "showReuseMessage": false, + "clear": true + }, + "group": { + "kind": "build", + "isDefault": true + } + } + ] +} \ No newline at end of file diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json new file mode 100644 index 00000000..c19547e9 --- /dev/null +++ b/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2022", + "teamNumber": 766 +} \ No newline at end of file diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md new file mode 100644 index 00000000..56850b77 --- /dev/null +++ b/CONTRIBUTORS.md @@ -0,0 +1,15 @@ +Brett Levenson +Ryan Cahoon +Margaret Chan +Zhanning Zhu +Maya Khodabakchian +Alexander Youngblood +Yarden Goraly +Aiden Tai +Samir Rashid +Alexandre Sauquet +Nicholas Chang +Adrian Deutscher-Bishop +Jason Lee +Rajit Ghosh +Debajit Ghosh \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 00000000..04231c15 --- /dev/null +++ b/README.md @@ -0,0 +1,7 @@ +# Maroon Framework + +[![CI](../../actions/workflows/main.yml/badge.svg)](../../actions/workflows/main.yml) + +Software framework for developing +[FIRST Robotics Competition](https://www.firstinspires.org/robotics/frc) robots, +developed by [Team 766 M-A Bears](https://team766.com/). \ No newline at end of file diff --git a/WPILib-License.md b/WPILib-License.md new file mode 100644 index 00000000..3d5a824c --- /dev/null +++ b/WPILib-License.md @@ -0,0 +1,24 @@ +Copyright (c) 2009-2021 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/build.gradle b/build.gradle new file mode 100644 index 00000000..a8517abc --- /dev/null +++ b/build.gradle @@ -0,0 +1,146 @@ +plugins { + id 'java' + id 'java-library' + id 'maven-publish' + id 'edu.wpi.first.GradleRIO' version '2022.4.1' + id 'com.google.protobuf' version '0.8.19' +} + +sourceCompatibility = JavaVersion.VERSION_11 +targetCompatibility = JavaVersion.VERSION_11 + +def protobufVersion = '3.21.6' + +def ROBOT_MAIN_CLASS = "com.team766.hal.wpilib.RobotMain" + +sourceSets { + main { + java { + // NOTE(rcahoon, 2022-10-16): Gradle doesn't need this, but VSCode seems + // to not automatically add generated classes to the classpath. + srcDirs 'build/generated/source/proto/main/java' + } + } +} + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployUtils. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamNumber() + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + } + + // Just the (static) config files + configFiles(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy/configs') + directory = '/home/lvuser/deploy/configs' + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// Set this to true to enable desktop support. +def includeDesktopSupport = false + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 4. +dependencies { + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) + simulationRelease wpi.sim.enableRelease() + + testImplementation 'junit:junit:4.12' + + // our files + implementation "com.google.protobuf:protobuf-java:${protobufVersion}" + + implementation files('deps/commons-math3-3.6.1.jar') + implementation files('deps/gral-core-0.11.jar') + // implementation "org.java-websocket:Java-WebSocket:1.4.0" + //implementation files('deps/Java-WebSocket-1.3.9.jar') + implementation files('deps/json-20190722.jar') +} + +// Simulation configuration (e.g. environment variables). +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// in order to make them all available at runtime. Also adding the manifest so WPILib +// knows where to look for our Robot Class. +jar { + from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +allprojects { + group 'com.team766' + version '2.1.0' + + repositories { + mavenCentral() + + gradlePluginPortal() // for protobuf + + maven { url = uri('https://frcmaven.wpi.edu/artifactory/release/') } + + // CTRE + maven { url = uri('https://devsite.ctr-electronics.com/maven/release/') } + + // REV + maven { url = uri('https://maven.revrobotics.com/') } + } +} + +protobuf { + // Configure the protoc executable + protoc { + // Download from repositories + artifact = "com.google.protobuf:protoc:${protobufVersion}" + } +} + + diff --git a/deploy_sim.sh b/deploy_sim.sh new file mode 100755 index 00000000..de5a53fd --- /dev/null +++ b/deploy_sim.sh @@ -0,0 +1,60 @@ +#!/bin/bash + +set -euo pipefail + +builtin cd "$(dirname -- "${BASH_SOURCE[0]}")" + +if [ $# -gt 0 ]; then + server="$1" +elif [ -f sim_robots.lst ]; then + PS3="Which sim robot would you like to use? " + COLUMNS=1 + cancel_option="Cancel Deployment" + select name in $(cat sim_robots.lst) "$cancel_option" + do + server="${name-"$REPLY"}" + break + done + if [ "$server" == "$cancel_option" ]; then + echo "Canceled" + exit + fi +fi + +if [ -z "${server-}" ]; then + # Sleep here is necessary to allow Theia to finish opening the task terminal + # before displaying the error message. + sleep 1 + echo "Please supply the URL of the sim robot" + exit 1 +fi + +echo -e "Deploying to $server\n" + +set -x + +user="root" + +./gradlew jar + +jar_file=( build/libs/*.jar ) +[ "${#jar_file[@]}" -eq 1 ] || (echo "Output jar file could not be determined"; exit 1) + +version="$(md5sum < "$jar_file" | awk '{ print $1 }')" +deployed_code="/tmp/project-$(date +%s)-$version" + +rm -rf "$deployed_code" +mkdir -p "$deployed_code" + +cp "$jar_file" "$deployed_code/project.jar" +cp -R src/main/deploy "$deployed_code" +cp simConfig.txt "$deployed_code" + +deployed_package=${deployed_code}.tgz +tar cfz ${deployed_package} -C ${deployed_code} . + +curl --fail -F "package=@${deployed_package}" ${server}:4000/uploadrobotcode + +set +x +echo -e "\nDeploy finished. Your code is running" +echo -e "\nOpen simulation viewer at http://$server" \ No newline at end of file diff --git a/deps/commons-math3-3.6.1.jar b/deps/commons-math3-3.6.1.jar new file mode 100644 index 0000000000000000000000000000000000000000..0ff582cfcb687e5c9608457628f78e9a782be932 GIT binary patch literal 2213560 zcmbrm1yo+ivNnvnySoSX;O-XO{l(ovaCdiicLD?_xVr^+hY&1Ske|$)duAr*US`hs zvsPHFm9D3&s-KeXy?ZN2gMz^T0YL!)NmVHuAbMPnUNn zDEoS9xtGliydQZfC8eci*i9Hz;%|R=cx4;uIg%^Z&_5vb!&Hh1W{a+l_suBdVy<1> z#>(rXnXwpn3~xi~*N!t+(vCE_V`Yp>EiA72;MYE_Jq>r;P?l5zwC(S#0#^|%1c;&m zp%O}rIT;%WU29}Xg@f_sw~=PKcrr4z92XDR!0BfzOG-N*a3fPKH0nSuT;CDhYaGhh zH6Ow5n2YN-kgZUV5>0SnWf!4jE#cA=d&~09!yZRq?H@mhW_=P!g4qv9W3>tAi3B@C z>zO63h$)UTY^t-WHl-mG1F9@;GlO2Nn5FPm!J_chGWFhF>8u(p^r%M0I!(1iRoD=* zYQL}q;Q}?y!bKXa1ML;)Q(UI|L`=JA3d$2*DB<&_2%W4ofd0Y>HrSo9CcUtPe_4I6 z1soEYXaWP_I%dShK=MPa&@4_fOuol{KXh0cKK){+LU(MjF%>iHp^KOeYI3GxmLD=x za^=eMpdc6;|KQXbQ!jBKh)vs(BZUU7WB8mw>-P{-*to8Ukv7p}&$;#304ZuUrg}A0 zL9~e&TzaM-k3O)RBC#CkR9R8Bj(KQq}l9W!d}}4i)P@R&^x$J?_*Jz*e>Gt;M}jGwg?#d)i1W z23LPrQyHGWEJx_gGg0uxz#z+lc!)Z*)Ug_#;Q}5LO*ziuL;D=wAp-{AUeK^QdA)N3 zacR4sf)neze%Ec6c!05}HS(T2Q2jOq;>XN%;@}KIO@3vZu2#(wR*W@5W%;Eeuv}-q zSPr)dK@sJTHjp|vN|fCx-B6#aGRGWmf=4VV&OZ4e{Y%>I$hv!Wl-#g*Z<+6lxM4Qw z?JzMq_Uc5E8taaN(7j50>c{pMf?2?hO}VlS=Lfpg?p`X0t(jW1_bC+&HykUPc1hO8 zn!Mqs$s_!lfvU(Go9%WeH$T(`{4P;Yv@xZ;hR=6!yxa)D9c|)l_H`}a z!tj-n@#uqM)cTirW5NG;=Y-~Y;L_1mjR$M%8nqm49wwgg3AGDIZiMvg!0Owo-nX*% zrh0b~>pE@TjWy!g@avz~wNTHvb5=~yR`OjF6W((=u&)dt+CmU z8kP^E48RyJ7ZGwLH&npDXP)iX#g!rq|;G$Ld#jT-I{>r!X`3N<}S4m90cWHk^$Wpde$# z+s~SIWA+7bQf78u3e7o5(N&KYS=dbA1P=Ut$x=N^)Ms8KJR=8y}BeGKA@V2tq2KOalTs67u40 zCo5XqcB4-lHX2$&dO+tQ`$&kI1KUt7vjG@`l$pf0g>Z7G2Z}FxG$(V=0qdO@ReG}> z1cFjmAk%Lg3e{9UX8C=%RT92UIj%WDdWV*&fx69{>sGW?$4khUwnH=QXX}mWsuAL@ z9OABqV@>B3FC53PfZJ5Zuh=6scc|N=)Ol27GQ&RRexj$h;tj`O+d*4~l0URDlu1XJ zy)u%P?tOaB*3RvI*Q%?ksmjA4R!B7MTCQo(0#zzolGeE;L{WQVez|aw~~#2U$9N_@*Saq zG$d4SVzLVm1P~B3HW1Ly3i5lQ*)jQRp#giTAhr&sztx!keFW^kMi|%`7?}ZH8HoDV zfkw90*0wf|e-c=<{OjB=iv2eCzmWe&z}mpcjO9;azp9M)nwYiKpCp%mnULadBy9lB z4hB{>0H;?l-uz<>r}wtTe*#+hMH$Bb4#?Tb{58}5xmvb1fIqACtB?LUkfW`M^`Gqf z73iPa_Z!gP*hl#{-ZHXsc60(bnA`lB%D<|_{LeuEE(TW422SR-Hm{gS{x^8W=8jGV zHb#FAnqO5Sc@4tA#=z=>qxqj>=vVnyP5QUIvAKx}zyV<6Wd3(1(f=cT%x#PCyoU2? z!2H{|pRRX!QS9%WPw<*nFSL9u$GsYCzsdfl#Y>3%DL9sX$#1VF+uuMO3~Vf44_NBI zHR2z|J=NdBnA`joAFqb$tLyxmK}NO?4uHR1nZL&|1~?iynAdObRbU$f?=o3gV4xcLht_4{J$Dizbo*vkpBVm>q@>_xPFCk z0T?;iz7}O~|K2NqDD^Ki3j-rtLvw@IdbR&bNk=0Ct5;LOf2HKV&|VrQWAoS39Or*y z`@djqUgFKc+~rS^_AAFY@_4}ibf z3cQ;3{xfU->Wx=3@c)Qg0Sp|S9POPAUTVspJo_v2UrnLLCU&ogzS{VkI2in02m7iQ z9PI!`FJ0^Z>-468mwN2Dt{;v%AZ{dE~o&Uet32-*DGB*ainh#n2neYFN zOTH&D&?y+=I7K- z=0>lTw^s|k(@S^kXkzQ|T9Zoj8gop{tzM2Y{$%>rFYPJhi?o5GBj7KafL{l}{xRsU z=h(jvMEUE$|2WS6bv(}hI{tqSssG^8uX04M%Kdt{{j2oPy817hf12~Z9*zIUw&Yik zpAFyNf&9^K{okhiOmP1k=ig-f{aN*|O8wks#$sjL`H;nmbQ0>bn1HaB5C0pq1@}xi6gXtYE1^=Yf^dXs_T=v zk>qur`^grnPqun(3twI6PLHlBX6(N?1gV+%hGQIu70LjBdv_~46=oPIEowZ*;sdO~nE^B8r)`jLj>u4M${ZnK6l#49h<@X>aUK(gxo2GczP)B)evwXY@4{hAetaP#ET7 zHv4>6QLUOkfgeda6YTa}%v%Ym=PY=mBpyKb@vH98T#No9J$e|hm(oRb zeYVE_ENWjGCLFsCH3DMMo0g%oE>eLC*KQKc`;ZXkK2VhJe&^tohNVF4o$V&6a5ju! zQnAOCzPW+JaWVGfC&2+B24KhZqR^8_@`3jIV2!|LUEZrm1s*-q zD7|$HxndaKhZ5C4R94{wXpxXI1jizluJa>zAhmxVW0XY~j$fuGhwG(44#z91YW`hD|2UICpwfKKY7AcQ0xY+c21> z4Y9j60&~N)=&k6O=sW@Ghxs zs*=&y2d-+;&u6g!8K5J9b}}b6C6h_b8tO;ZqEh(uq<+lShbA>yPa8GF+7&@a6I$7? z(MXDU*JQXfu>a@p%la56cMRF zvgnUrKp0~0IEgVEpI|F81Eb?dswmx&Lxk+cG|luqglZ>hFe!1C`(Ri$f}i?a7}t*C z`0GBF8QgfkqBtbIYCQCzomEVT4)si1Zt=#Cfe=LAe5%P~(;8>PRTtgyuJ>5`2KJEV znD69vu$6Km2crqQVBP>=-ph-@5|-qs6@7iTz7LYp45rG1pvy-k2zT8r;}R)gT+%}J(_$o!V{6R^_|=7 z7x0Xyd85?BGf}t~$q-^|u><8o@vb#8CE0UFqo+BA19~rdL2r~5mssG>&P`&S$En#aBGsBFI0oo8%k~3}gJH5#_}Y@9tnVzLAV3_I0IG|yW z0Q)w}g``=PPaH`iZgA0l+Pm>n$RZE9IIwCK$$%6TAlvZz{_HP4q?`-B{on&U41pe( zUP~#AVTQe^bLWz--;!ELyHTo8oT&iQJWY0nK2SY0l-m1P0i%wfRZcrG5o+KXA*xE^HJvSZkwNZ}ocysf zpTe-vAINSLMbE$wwE8x|KR+c0dP25Lr?RdjpssP?0_Vn$|^=x1| zjFb^U;9V>I5tTBr1fg-5TVCD3$})jYhLX89s?rTQlkkD_5jR6yW+GK*r%-r$J6hI9 z(42!ayS09s9w}m>`WhOpAhA|qr|?>V6*M<}Kjr$8(XkBKWFomq#{ApLa}>V4(%lMhkZd0w$M!Em+ZOeV5z1~wf*uP1TB7K zctU?rTLt;d^-(5pKzk44_=5_4JZ{Fu^hKv4lz;$4Ngz0E*)1Mo^ZSpIwS17!EFiF5 z#L$^l&KN;Y$0=i3ZO}Xi%1h{XM8PF-Y9dt54iVO|14~~lF6ph#IQzZTQoh~d999}i za^T&gNkg&SI3fjjQw$f^v>^|WM2A6 z1syqe5o(U(91Qp#9lJDf*d7_{IS?)#S<&bEye~xd-y+<4;; zqJrEUKi@yRElu^+5Gg8Vbc2T1FA z%-YFFB34j&G858BdM97BrUS)1^c|;yTX!SkgxFBX+B0pQx4HvJr+)KV^s;wmNst@$C`AEfevy)p$2=h^8adH0MP{3WCRS!nr9~oscI2@R5zbiu_D9D zi44M8?DfS^CspYvKz5nD74!kxW09NGu3-Fz%eQb8SE*tcJ_e2YLur}50Xd`5j}M|p z*wbO6{yk`OpK(W$**4j0tH9|$Pi57t6?D-r$FKD=-&Aq5V~-b|RPhotLeA*28uZkz zClTt_UT^UJ@U)!-Zz6Suyag`L|KN-w=|z4$T#yL1O3(>A&U+i5;cGzkdU^*Xddrb4V*MCS{xudD`*Gud z6)SFZP`re=)+(J$O&!pct$~uH4&>43K}Ag!J<;1l>qHS(IY?bUmrc3?@5F)cM};j* zDf>R5XHD}uBN;sIS#$-`@eN8Go~mX2_mT74#;V6_@9A!>G{O+SlV^_vr0w%Yw83r2 zYa-#h!8au+)S{XN$Sl8USdhb@QrJv}Q>>LD%c%}D3#wYipOi@I{4s>pUR89DJSCaONwD{pO>{bbk?vK;ABHN7K||r;GL?CC`g?LY4q$nqj~efMq}^?{SFP&yp9oD^r}W*ZW*V@ZIZ?Z67Iuf zA{lu+7f0pA-Ck5_Dl9rAP}&ywk+ox|4v^?-4&=qG)_I4kN~ zf{lP41V8>@zwd%x!kgcuMe0n?9$&kd{!pLiLH*MlE!#V&4g+ZF14B7;RQAJ4#9&X1X;V9A?s( z6P-P4vf)|Bt$BxU7L8Zpder$aJ|l+6&ZSuoBJNM$Kc{45cjf8M>Zj%A?Ga8=U;*qp z+m5YwCVq3qO#;|=lRV>i?1dC!5qnonp{}0kJ4Yqa1FJO$RW9R2EsC-a2LguG>T>UR zq6jlN+MoTjViy%ngG#aVwURkjjZGsvS+a3KgG1W;>mE1{ZbSI9bo{$da^@BYXCSP= zL>>7(#*n%T*KT!YZ|(>l?))tS6cwwXf%t(DDc-V|T&)(#S+sMmmVbw+heIxxYlSkg zv1a^KIoDhwrdlFwK|OTd1%V_UXnEBIAA$aTycpX{kXi7&;CKLce6gea&4jWjLKTMP ziMl1ABrVi?sb@WVF+0R2=Q3yH-n3F9wv#iVH}`{A7N^e8 zWsC_xpwk|j!tpFf>Suo}Eg!Ft)&PEoBFriCu`=nd@_}f94dY3e-2=#^Z@-Z!KkK;8 zxBD@-S4I@kx8_Z!NlqOZN4rKCnDBI2DmSL+4BB#A+$p?kiej8xY0Yq3I>&@0=OnWuC z84#32(fcu2GD#nR7RsSkRC3ui8-Y3t0r|lLh#VR!wxUAx@Nl&aJj>y+CGoJmep$}U zUCrXXV=7;xeS>uDQ!jC!VPiOgypqe_;#cj0bZ`t<`}{q@XIhu?Rz+0h^;9;y#?Uc>@bWvRJ&g zAvyDFY&-z5U7o?6kL+)M|JD4PPVZ^Z_PYF9cjOEWA2xjkDJHG6*AHqs4o98Rp^>-! z*|dcg&rvPx!3gBl@D{4uo^Doe8kGRR2M)m&NS)jYA2G`Hljzpx`a#Dofi;6IF$UaF zzGrtzb89DC8IFR)!3%&fS7xL8+_+1#D`C6Q8JMI2!U%j$>v~3Zwm@J&Q)YlE)%5xK zlePN-9l7W4R0(!wR)TFV$Y`btbs9dN(C|Xd4j^*18%lj7i=d8_r*+tcnWWCxz&$w4`J7Rp#d)JxN^5FK_i`Z}L zO=9iw*!u{N;+C&&74jRK^azmf64?(!g4G;4D(U{hXxJ8TLGi&jw<_+1=fGFdI`2?t z&*zwcYhnk0rF}BpTy1cyjH{iotO=|jG6k{i1h^3KyzvVv;LX9hELRUewY?D>R3OW_ zYHSD*6H0D!OJ|@;N%5B;TDcB$!p%QPi?lJrz|emZ1UP9OxX>ROC)AsFOSTu*e%-`4 zHpTw%@slQiI^}EU6)|+zvHe+uha)%e-bRM>M-Gq@)RK5F3qMU&Zl5>d+GNtpdY*aZ zntIHL2(9IUXR;&R%Qv?aYQ^iPt71km5VyBOXBIGeVnE@G#_TxX-QRub-q`@c`+UFu>&T6eo{5?k08!xi%L$4EAzX3A zdTZfWv9M<6${`&Z5VCmTS52KCBBI>0fD51wKKg|0c962*dUto`)K#&1NB$O@8(+LS zNIsaIXrlh>EA%C}#ko@_lWiBsK_4QXBk>t1bLjJ&I!PzCV^nkX?lWVkxj-0>UjX8+l!jr4wC#_t0&Uw^Xm(#WW zsUB&$iJ4&eyav1;RD;$nSezWj!VTNiZHP~v0kk|>lft%VOfg!4+&d(chq$@a^%8j1O9sO;WG&TK!>xfG;*uz(no~MYC z@P1RSQ1?>J<;`Fta?82-Hh2w`oh{t@*TztzAWECQBZ@MR&@|%C zP779#El@%ER(x)nBR1R>Xl4Z~cYzl&SWrCzN{Z^D=wP)bqBi`-XRro$p@AR?qRzDG zfWtLUf}{b{pDoXZVysi;*)oFT$IIscsS=3{^YJ98Fqc7zQQTk`elR<{v84TZiPLBM z4$!%i+%V(wo7}w{0_ahd7A+kRzRe~^XBtQ+JDsGwXl8IOPohYp!c|?S+k~n;`U7Ad zBw+6JIJAsVeBc4K(S9|D@DOec2mbr6kZWZl^y}FX2UUDkdO+fck!M7m%s5`cS<8W& zs9kfH`kS$^utmaOgQK&J1_V>tD+YEqI2l=ZQhVO6x&@@H)XRooiEmWZkHA?BaJzi% zuT`VZx}#say@~;!B4iS(AK)^X)&6{WVJdG2n(AAHXXtI*HD&Db7C46~UF^h-^8}@R zBXj*b*VK;t{>fpx=hyRd9tu2{6V{geTpOITA)Bi1K zq~J7txx?lZN5v86a}Gox5WcD#8t6L3Ak3tzbeiNAVwwMaBz5|@7SUE3y%u@;f0GWepNtG?XWFeqJ~+pP@=2oDllUYO|U-hrdG6qu+~-E$2R@`jDie5zZ_ zdW3XiG!sY+4F?^3hFe^Ege;|`cWm!2?|O=CsHM`@NrGDo-flWH%UmHr_8dm?K5h6! zrC+(_NPZyr)_lE^z-RUjD9ygn1cD%wnM%}cUj*zYViBs@1%K;&Qs$i4yD;H zXtZB1WWk~v`G>$9Rdyoijng#gia#QtqO<9hBI_2Rkiy96phTzHF_m}` zfJukjf_~}O8wBxdS3sn*JFK+U{UoB@(UfcmnY$^P@pYPP`~2n^!}KCJJh>9~Vd9%^ zBYlVa_VP;-T3Ra@PgB2 z2PFoZO-H4AvKLhd4l#7bdf&nN_Uk<_<@Iljz|ug*Fx{@W4V$-Nd9-CXcvO%&VR;zh z@1o`yoYgW9?{9Q(IHB)`3mDibi`*HC+`4{v4Byyzu7Z)mhp{=J3{R@+Kj$P{CaY9V z2%{{e!T~dqi@L#+NtgU#6ip3Zwe-arnC4^b@L3~Oi94KEf%V>dyC=>GWnyU`(5u=fj&+ZtUlOo>z+ezEA63&&y#0pknwv( z1nOE3=jv>DknC420!OG*cR;7!o6}#AodpeFWwOGB{h%MY3haPJK5P1J1lxr7?VRp7 zU)60+98x4grl8qK)DA;|IiqiRug1qQs!4u9PO?mCUPe!H^YM$5?J*p0 z63DZA-r~bU3hG^|854`Ub0F=>g^X9BMJjNp9Heb>5L3V+p0J&Fu^0-uoK{tEhJLcIB*xN^} zThY9XrOe(|@vuOwxsH=_4TRF9fIsL zAYEfZS#Cdg1OL3Jbh(XM_J|7vw5Rj?MWz4!@!`+gMgP7LD<`k~@&NJY)5FBcc9?EP zH1G{xd3%nplj~hwvM_%Bob?Py>Gja;&BV9FAG>2beYylXAXIQ{5RAiXuWX$fs>^)_(M}fN^S1(FpGwAFsW` zv)qcQ=ZjoJ7_9pN4DRtwpW~;^i(cn;buSi)0RP$MUtddj^#aAqO{YKZE6Ezzsl2=m z;z(~~_42@WOyh%-@*Mt?&E8ns&?uSUpg`6~Dk3ss1F|LM?mQ-7=%4^&q{!05NVt zCjoOf>~*+*Tlt~Yv3?))n9cVC#0UJgH~4O0r}>^i;rXEn!QacO|GUFN-ZliG)5^hs zY?Hx|8PkWBno`k2JnGVge2>dbYYr8$GP2vbQM+Zq0 zUmb395pOody&kaqxlV5k(#X_~g~@|w?-^0~W5a`YtklJ22735L`zSt~AX5+L zJGjayF6M6A}% z5hp!Y_?&vc%Qm}?85YyNh*^u0tFqVG4Bg7mAzreuGM5CC^ z%D)BCQ>$mO*rk#>9WU<7XTmudp7^5QtO?S+SM0lWwK(lf5itZFxv~kZmffd*C1Fpu zmv&}A8HHBjbdlldDy3$|^EAgLGG6oHgBek3%{cmkx?4apYO-i69?Yh6oJqvVcDu@V zak@I0;VflEj5AT%*5XFew1_^y7GA?Uo%-sDBbfy$tM{g?*tw~FZmC9Nz`iU|?_4!7 z;~p!gMz%_^7l$+)5>rDKaR)_14@sc+LP^C^R}3-ZuP-XX@I=e9cNQ!IGt~u&@_Cu+ z^fudDzca22MEOe2C$OczLpw8+aXhl zqsv%2CdaZI(3@aejl@(!SxbYL@4I@_Ti?s%DLoxQb`n{1l>?|%XQj|LX?)&Kjyk-5 z@5N4`r_+(It%RpOF9K=I3U{@Xi9n-! z*ebmPq2V#jDAM0ZdGmN|R+l{JEw&4^ z@=l&5P;0IDfCSKlVRh%|b99^WBi`i~v!~L?zR?j}m2dX_OzbFex0hVHP#dBrup9fX zk^>{a75xk#uHe-WXE?fu8_5gR+mS$P3EZ|ro7N9fHlOpiSAo`gs-5wWIBm4U;5M9S z6GYbJy}8++!Ow6#kUDM84S)zYReZ}PX8V^W&EW@W(JaE|S;`rtt3l0r%YgX$tAM;H zgV&7+^^P3;1K%;xXgdzLCCPL=M!grmX8d&daUdwSp7w|IM(=rR#c8`q+t5;s0>dh1 z4ZG-U9;d7^oMqhEje6*As+weFy$m~8F@B^`d|iA!r%}&>E(5Qp&7o`6_WPY^P!;i| z(zm(V3=HT5OQ(vab>Y@_jIe5jOjhV1b&k#FLn9k5+PsUR^$DoQknTuu`TP>Bd-%7y; zi8)Cg{*jPCa}G^AC^+iWsIIa!8B^zw_}1QlUPUqLdTGSbsqEv#(O7uhSJ=^^J+sA# z3O$Q!^2$9M?6KgcE;G_Y!xN|sFJs{N$lxzgWb;z&8N)T7jF?FZ+zY(|6d1%}1I)#@ zIH40$s=b1)NaU07pfZM4Lgc%OTRk{><>W5xaKxjRXnQy~Arv7MB5f~H8BiJIheo`E zAPBQf!;1`e=w|mK1yD=Qv9gexz)!^_#(6+~(o?QK>wc zA>6Evu6PtK=0~!-vgbwMmM$Hz%!+K|z(4SI)69BiM?GGw&$*sinj7#-sbD<@TXer3J@B zzS(?E%=R6X0B%u!=B-Egy>} zjRKUrSs_ATjh11IpsN@+)ic1vO=D~q@VduR&!)b#^p&F$h zC(wW~o0W{IGnbV^SpsiRwu#_IjV8J*gk-ak zrF=$FW)Bj z8NN=A5YuA_1-jajmzmNZ#!dCBci|)P_BVLCPgFPL_DW}Ep>2*H?s&5Onj;zY1k@BH z1$YF#P@BB{!GELA zP>5$BT*J}Z6#87=(m6=jrL0*tN##V#rZ$czjSi0yg7VDMV~Tbj^-*nK==rSc2A=Mq z6y}KhNxv(}>^Mhmr;+BNnx+2TLpo#VHWHhsPY9oc2%!)(fk~V@*sg1WDFJB}cgP&7 zQzK>RrBZ#LT+8K5Q`qD82CHh@?M3bn`??WS%PV~W2BamliXuGwZ^F^yRJr|)p^>$P zMzlk0QJdW;K+JIoORE*;ui^)oHHlRklnsK0q2UVa*}nNp9t({Xz=IclPWQzu zV%vHC>SVu{N72X#)oMP5qCKH-;#@&3Oy0Ln@$3Py-&cw>G~=r3w(Z-V(vOt7#wxEV z^M;@2Fe6@)i^bTFy*`YWvsSD+LGrG^GeuI^O|QpZ+tQuU64NA`Bf_w%Kt+CjzVHU& zle6kd4latW06~M-jXr`ML-md~JycW4nW0F})S%3G<%S z>agh53iFfL+d|g1$g=|v_Lqd8D&;;dkGD|qc8iD2%)RBeDdLw%-=AqzeUm;?@9gt& zmO7nKVII>WDQbfQ88GbpE?X_JkS*&}m0+{z;W$CuwWLq;UMWH`Qmml>SFKQcTEaMw zOY$jsi@BKVIq`h~8eQNUow?JC9!tj$MeGwLQ;@595#JXl_az$#dv}I6{l9^)-gJJ( zbUf59WJm&E)yk76P%VBI3-T_WeD0)uh4s#4pK&sB+tUH)Tk;^pr zNTigh#mv}XjG`l5#Kln#HfSvL#`nOE&RHco zIwGw$mZ=1~hg6WNd}@Dafy%VQ&@EmGBRh;|1#}`O{OL|n0T*<%o=(u3mih7!4GA@t zk|I``$t09$Pa!TQ#SeYUHIErx){v{)5MrrsR3;PNfTp7-kGPh`S-aZDsAb&6xaLSf zj&znba*nI$uBQ7)C@?Xpi$?T@W?FVCrlhc@B`w=>_CzzIyEvK^Rzq3n>=EtTN_E^pLf4a z%mEIs8p7S_P3HM#`NsKH`Q0&yqD0MK&;_YHzZZN+_WjB@%I<+~QRS5Ej%t96 zvEX*dE9|C3Q`(3X*Qc0FJa-1^NBkvDs-AK?3yR<}OFZ>1X`NDCZsUr8Qpt@>I4Inj z3EE>052|pNh1xHOe{CE1i&y6cYhqr+K#zjLSGf_yAo}&~$5^``Pp&d;D@Q?eZKPFe?uw!1^dM7N=zmT;~D$Q#$0hZJ)5NHxI(%OHr-KdP1{?dWfqr) zg{57Frek|HC&KS8qIzGvCsJHeqwr{|C`}xX3Pe%qcyA3Yhb59kiK&-a)&K{3ffF1D!Z?PUUzjw>M>u{s!o>LUdz#;*h`I zq+>6TtAG#P))k|LJ?Am%1MSaxL17} z<4JGyVk)K`LuR}5u32z7q_-@TogzkFHb z42=WI5|52ByC=9Iv7})y8-@1TtE~rOt%19z<%FDNn)njWWT5tj}KS{ zEl(ED~o`jTHIVL#5QO4|V$ME{mqJd@I847S#aY!cVUqfr!?$K~c z8?dKZFrugj7Y|Do4~heHCO}c6`0B&HtvKc3*jBzr1iW>D1VlQ-f#6cUd%S@zHy6Zq zscczsGdGkZGENb>y9K>VP>9INefZ4*ClXcsi7)2WzWn>Y9q{T+zrRGXik@!8KT5AR@>g9C;^`S6GuCE&!QX14z zuxcMfH{#D+7CxLQnDJu$m%n)6*IXw0^1uHym;KCPWJ)i0w|+9tF!g@AzXt6jT?t3p5(9OnZOupBG6?``6k0*3McG0S zZbcHiup*NoZg6Yt=1~`+ZpBJs zH{)!!6!}*ckk!b{hP4o4tb zs!yl40lDU2*&WD%;|LNSwad7tm!MfD+FuK+`+pc3hN4*?PRsO4AHuQAFY!9HVeQ*- zh~d7A0I$b7eGVs8%Vgwvo}f1K^>!ea|06uc$~wM6Pco9i257ys#) zSZr&LD5EL23@bz0FoUvQ79DuC@`*{^`wmL?xeNKB8r{B@CZ9E*ju{bt&&U_NN#Gm- zT@jmpE6iOyU@5UeSZ=cTo?JU~gh#A$xZyMD!YN_gF!6)YY)8h?tWH*+%D3A9?r&c= zHJx<_04-3kU%tY|8*dzM zQfF-xk%nklt}3g#EJ|~m6T(Vj1+5YRK_(w>Ec5B*(-H5LEY}~%pTGkH{QUSk^)~nO zy#?D?;5{cX!x`S6j%K)@zD@pd_~l15P*o38Y@Y>&V^cvl0KKY2VI;?f1fJW!99w%t zKa!X*baLBEDK$A(* z%M3Arn?)lU0ypHxhAZPXPl6d^f}pOoHxMIzZd<@;=4){2-?gW=cd1I|mYbyAM0ACn~8mjE#NNIgw za6rU`-$jx9$6|Sh5+;R@rFk-omSpCieak$7Oc>;2Ym$p3mUd^+s9UXM4BBQy(ZkTe z0ok#JdNBaK+Rl#L!H)cHuNCrsh!Xq_lm#Y2h7@D~kZqvUMsdw)m;tY&j$mG?x(;aV$#atNDf8)dyxe5{Cy1Z4 zeHTgqCHztj&;CN&U&|r?Kc=nHZ+DXA0OqD6=dG=tOn6|7ry^>zuH_!yN}8?3)zm$BbKGAJ)A;**{=?P7H--C@~HOv2UiA2j=N z*sa#l2v^M65OQGcWS$ya7EBqGwCj{?OoKOq7!4{gpkbDi;WwK?2p5@i1z{}k_PF=B zW2_Dmi~QgfZk^=W$JB0Uno;BKFy(r*uqU3hnwe{!+s&e`q40_8u@=640?GHXEHb)x z4qCyZuMXE4zJ{b2Bb{RUfp7yFO(P21ja+>=Pu9$qxNHZ~`bhxQ*)Z`WrVzJUM$p?x zPFZ7vS{+%su`CBJadX$(h-PrJ*^hf6Ed)@2ZX9DGF~Kf|TdY+jTrm&ZS6Z~(?kIc{ zdiQjN6-~>Br@H^Ry;wHq57Ukin5BG0#Lx*mjh(B;E*ifR8zX>WNo4$yAP$4_Ey$0E zLHNAvLBl3d2kNU`YQEs*_*+kr?&VpWf@#cN8=}yFL78p{NdTVMyvaeaeT+7uo_hkH z0R2~M9izhw!b9d$nA0ZAek;8Yj>s6x;&~N($jU5;*u^hEDV~m^6WJleVAt(O2d1v%#nfh7lMY*(oBe8AejuKJWKoE6Y?;j{ z_V*3V#j@0q4jA!vGfmn3{;cy@CM3xBJZ2$`7l|Hq?R}lP%sX$S#F&!p{UJjo-s#mu zUZ@3?3JykJ&k~Vn#}gO#gu%ph6v*hpJm-8-m0VCN8>!Jy+4LQVb}goCi#oa~E&Z}@ zZ`*SWnS~}f2uf{O{Y1Z+Tk@#UHned9OF)?$Qs#xmvQViSz97qYUP#Dqv_Qj_j(Jes znut65DX+zEQ*kaiFX?KT#A9q37yzR(m)mEjiP*PYfPdqGqFIt&c}Ms`Mr#>OOW-~+uTRmxQa7e=Sx z+61oEOTl@ls8m{%vH0iRUn2G=8g;+0A?($j>O&;sqt&POW%$2o8a}%c>UG`*4_bY$ z%sM?<*E9#E*nRU2&em&2q;#bdM&}OB3|}HQ1P|}x(kYfsCf*Q5&P&jegK~(2(z;VW z2cXbL@*$gQ-ZtkT%cohIRQ>b<3iWge>Qk#(bj-b>MHr4SA{<7rbwg||SIVcBlm;-2 zN>AFUn}OoYnh4x`mDu7`#%*)@q;uAE=xuX8c7U3lm*Z zNTsL+{Mq(QoYHB{ch`j7#OKU!=|dc;*dYZn`Z9j-BG7`&NQ~+rrBY!2u_F1UU^>{$@r<0Qq4A;G zwCM9Cg`afHoh!He`die`Kwv_#z#26BY?d1^8Rk^oYp*`Fd>uaJ|55S7ecjfC8FiXZ z(*9Z9bFV$)hWF+&%dz92{P}Y99nj^Oo(*m1sR!B?FdL6q?s{bKnJfpMtGeKm2E6<1 zSxBI5^Jc$p!=h=f^fq*px`mH$|-uQqJ z&vriwoCfEXSSgAjah7wws$f*hyP#D9ydFoGhc;XW{lUn^+fRP&B|-iKZ2{j(HUY5J zC3V|jedQP($71L%T21qj-d#7e9_x`751rkgHC@NL5$PTzfP5Q?F<>c^#Qb@AHwgp{ zq&bnH#Yofrha`CBGeT@vj5i1TBr7*Xn5PLM=EYGqU7SreDgESiP~=6}2aJX)K)bMc z)1cnDHGMA2)g^iZhMLrG#5<%dJOUcoT`UMsw@?6A}XaV0!4-=t& zptU6g`2dFE%NU}QC}^#nEeY1{Zl@G(ZqmhoTkCufsw}=*FNcDcITBidp!D|CS`}7q z6?~}v`y-+B&iqfQJ<$IjY3~@M*|u$qR%KS&cBO6Gwr$&XrEO<^Y1_6dZQFKM8ZXy6 z>%O>g?%O-g+xN$e8FT&|F-C8FwBB3mwRQ!L8>?=%2HIRd5$B`jgOjm50>Z9Gt&B$Z z!UFqhjS2__4nPi17nHbc?TJvu7a>k5S65{MUQQRv&rBO3u_gC%>Hb(n4)jqrR;hw6 zi9nEBMa~IV@@r(jBFin_q2a4IXa^E_yF>y__u#L#vLeK+)M=q!s;g?tqHK^`E{e7( zV67_Hk{qPoj!JJBU0r~KC3J?_$r=`rijyZI0yr@HBNM4nV60(^jpONeY3hT_a&Vp8 zLXa9qKDQFfO)G-3I(k2P+hAL+4ev-@ma8L+Sr;ivZpo7X1$9PW9FrX=^ zGBZQx*FOS~dRj~eE1&eP*+c*8x; zILy6+bJzL^!}^7fV=U8nmR_6weJA${i!rD3Qy05bXsTEY7pC(S6eI~99r9jo_`O9M|_m?4f8;{lF~27VMlY0ITK34e2xha@pBy#P#u zjn0u|qARBp3w(37q4+c<7y+l!o#HBxFO&dzjX1Zd2$-iJG~XD_d5e6s z?g18BpCFxHfBM+Y$k$+WLOj$+9e~&X(if?;wrmb3dKVNXWS0PG4t3>ugLTk|v~04| zJi6O`xBK`M5X9?oWBb$-0avR?N6&iS`Q-XG62ZI2`@__DP@4(!5?Vwv-s_Kg^xN-< zgeO`4yOV5Y)vq1m~5!j3jX~L1Zh3$`$CYvJTSjW5Hr|-W$ffmkxQ!Yb6Kd^A1rOn<&&% zImwj6i7^ZGDqINR*Nu>?JoF;@1M>sx4kGzYqW%1s%|7c|qR)9bsvn2d2qdHjNeBl? zo3O!dhvjUI%M%uo-8TT5UrkzQ=js@nsq?vglF_M~`{g9n%t(TiO3m<)rISK-+JjHK z`d-b-)kd|anx7&8Mt#koQTh+ zQu=4kj^o)8n&1lk(PS|#%~8b*T*Y_?ZrJLpd$IwsR@R`baG3Eq7@^V}DXYqYU>>pDuSSc2E2=qsU3^=;!?EQa2K>ri@nk5@`Zc9 zQq`qxjZu_7%r_kS%#M}FGlfmJgM=wTN|-sNtg<_4m|M*H^9& zuI%C$IuiML9yn_s0nQ=ii?O9>d&`vlyKS}Xh`kT3l!`&6=&ig{&$t+G=%Zmf)StzY zuyj4y1?1TVzi^Gja1FL$r}bp#ghEbw2+u>a234>Jt(}H4-C*0_S6Mprb}q| zP(I4F8qz@5WlXDc?YRd^L}EKO0+%eC4;Ya(8rGDSai>}?*j6EsIyI6U*6iENTV2-d zFC;>A$W=N1P(;FVSiumiCZXCd!>m>ft%p*aXwuR zp5UKQYQkM5E6&3wJ+E%*vdxq(DRJKH9<8ow(LJ8GLcCzX9;cYoI#n>|yJl+V

@` zL0*D(wkr$v`x_6lCw#)A>3xO>k6t(XcU(P4%}EB9RAm5~T{k$cc_#&V817)G1uwE5 z3+^9>N@+`pB?u{32{0eZG8TZTM2JOa$f3++mwuJ|v~Ta?eCI zY~G%dlL%s3tnfe@0l_$3XFeWQOf(-2Cd%`WeB4CbZ_}voakvoVTf&ZF>2)hRGiqT2e@eWmKZAuJYBjZ{MpmJR_RWuOLdZ#ti;q!*E?$@JU z0O}+CEUE!W^#bCz25Mmvsx}bAh zkn?M$x12c2z-*4Gt(t@WTCgzMbevT5Z>B0IQ_hqiW-D{;VqEA;jpONwK?8=w?s#7l2pEj^^r zT}_=U+qI!pN+^@Ab5y!Ti6_Qn#ouz@B(M-pH*w7_ zWIeii)a5*uc8BJf;WDmzo2M1&{g#=FKzA6)0S$I^!%gP0*M24J(U?`{cfe}q)^j9$^&C3ozuxo%BWt+1jct4B_OK(c#){#5gAM;_90 zm&=p%3Pn-zPjDd14+=kKLh$7{=Y%PHTnm)6()x=AUdX7$oqQ@F&)=K!x8Ejlhgd}W zCpkuquN2NR!#fG3`6x9w1jZKiQ6wB!I3-bDwX7U}Jj{Rj3l}^zuPIn5i;yYj6-34M zla@pmo12_CGQPeESO-&iF`{)#WusXFbo*w2?U`bXvom+=A`-LGu-L;V=P8m4ryL>^M=VeB@<+<+>d9iNiv((Z-)e@? zOWM(zlq(n3Py@JsIij70>+UPKZnV)(C}y4jxN*A|j}o~*HU=Ip9Knvb-eRV}# zCwBxs?sH1%((XOpLh>Z54w7#rDLiM5$6iSWz40agwyaa~AyXYYbI9z#$9GpGxJ~xr z-%RFl7rji$mhA4J^xWrWC+JQ@+gI&y7T8SL8VR`t>&N$Hg4_qr*WzIUx+Trm`LJRd z6CKicUOr~hv!aLIL+xj}WCjcYi)7u@=wk>5kGXCBX7#a>V%lVYjD(949}>@>zDG}( z5a>6Rp${KtA3}EQqF=D0D@sejGB)|0YO`rEPItvLN$-luIH7&p@+|E>zHX^>+OYn; z*_~8zGbPn$IITFhl+6k_7c}EJ*0jj!@1P8&-QZqU@KR_n1Z@} zJY;$1O0SKQ?rM0+NrQ&rYG~<8ouOJbQfs?0k>uxVbb={>l22?$)hy0X z)>t9@kST>>S6i}PPQDS6NiOjkmdmkuxD)MaqcY6NICmp6gJUaB?iu@i+;WEc3S#57 zi$3raket$a`G(M0B|j$OL0^O}DQ7Z|-}B6MX&Dt!=dpokO}%iIRbE+GU^{u=Ci&+m z|9bsWv5e&O+V^Jkabw?Nu0F08nSJIm6kPJJpbATnUW%YKc>AZTW?8lb%~mGlYF#rSIw+NBxI%d?^&7*M%Spt~xiR&2ub2#) z6y`ZtFVRKF=c-U~b)BSkluJ$tLD5hWcfpcnb_AwucTtXBp#EtP%%wXN12E^1!<3rL z^nL!Z;v@ogl+Y>F4On%+E~;@k{Z`N+s+jfcgNBcC1xH!s&fNexaet4oGgC11_)cv! zDRlK`J0@_xo5eP$jm!8q1<=`1qgaDuUQRd;PvxZqB94Ty?DU192bxOJDDF?vAZW+p zPaU^lC^YNV`ZCCfIVaZpxxqYY6J@Y(&rZXpiMZJE{Yn^Odg!V>vBXXh9Uk%4HMGa< z0{e{k!3cG=bWI}9`RHf+Q@NyXs~N#8Hz+fNX5rJ0!FEX%_JCl^mY+lBO-A)Q8)&&` z)1)NBun23PP}-#41vt(90Q&*^kn>tZ{>&276V8Up#GmX!Z{Nb;i5lVWgL^`Qb7&s| zAXB`;c+>(VTSN^AGIw1e$g}&2nQ08nT4H(!&;K5- z0eV9{=<`K0&4T>9Bk(^jasDgbl>VO$udMmC;gLUznyt^uK$K`U`Idk-Rpj!)QESl1 zn=}gxMP^bjTnZ(dINLS^b`!!nGSEK*rVIo^=|8^tCeUY*lhHqXuOyj!o^&;ta^_&v z?eczu)`Jcrli6|l!7WEXl!?GZqpublM!dT?5=#?$Vt`CR6ShzbF23hK z6y&5XrAnlgWS6-Ur=V5Om7lznO}?(Ja&Ouu&xjJRbhd6z=Dbm^t#aD5n<}l^j5DX$ z!K|aql($aKV|!Ya#){Q=lgKcveFoynwIQQkW$uRRitZ(;9vt#XC9>kgJ@!N_a2k_o z>p3rF*{ZT5-8|%;gwJKXoNVY00s8sdEDb+)UpZk%Z_+`kQoTCWM!b5t;AGN%G^e6H zd7E?8ERGAqWC*d~@o}8C>bRW4U6M0+0xP*5z}ksfEs+{)Cpbh@WOTn18kr&XJ9P-U z{}-LS^@h3%vyK&JW2EuwLc^JZ>JSwoq76iUVx*3Ks))#tHT?uWAwK2eVUc#5XPz+U7_b7f2gz%6VT4!lmWbtoqP_(f2F%Qf+1zv0&}N>W(wDJIn#~6521pBnEH)Gb%-uis70GKKWR7+Uq?YM z!jg5yrz|i9bL(Nu9VyyYk0m^92eSy}&ASHMp&vg2_V~)|veS_yiW(I>{0y8>^Df@! z=TtN=I~1+o!s8uIq{4EabOB&!byeItMQ-UUPdmI3|)@(R9XE)PGi7j?sb{)MUoU&IJ$1~(gFLzJmS(l{>{ zr~I9|92m<0dtK-}1Z9RMuUC6j+G*{S+ZZ#~!ULgTU6xSBEsUn=#}3nB9O?Y^w;1s3 zU3RWM5}jR?9S)s6m|VEwk~Ux^;$=_hdS@;Zmgs~@(zZY(>JuVR2w?QQXUum{vqI4t zwbY+;_(Y~JCo9-}Z&IJGe*sVMuL@P*uR>bpmownMZmm%MzXl!^<1fq3FPqr^19tv7 zg&Qtwb?d8;sMpb}{&hgR#KJ)2%=o31vkJo5!Nyi8R;JGFgWbf$2>CPD=P?Xf>X^WO zPXyy6NBbF$uahfj&wpOmWWUwBVTJ^20V$>~(&z2@00F1U_eJW{@ehHG8nOf@&N|W; zBxNn##Ns#H#Ot@vaBVfU)LVG=-CCh1K+ZX6QmZyi zpgv~YnT*jF9=ol_^|8LoUN)(d9FLw3!#)l`&Dcy<%4C(rnuel=A86QT@@rOh&@dh+ z{7IS>sU5BPxFi_8a463AC^dFOi_@iSS@YMgF_M(OY-kEp-P44IHJBqRn9xC-c!3O(K9NUl?Hi`Q4;^gT$|3wJoneAj zy$Un(9xa;Ir*0fdtsz6Z%z>(zn7O#y+We(}LsD+uQ{Qc^OvmKLVaXRmZz;I!3-trx zn!QQQb(qwGj@%3LJ8PLi3J}8-Baah_*Wcc!LMKSxlgI;19!5`;)-?(~msFa54#w#3 zJY_>&T7OjZyTmK|xF=`%fA` z+#FeHS!}$v#~8cJCj{4ZNG}qEe(QKqsUOaHi=(b)8RFbtzm|D+zl)iDKZg2+0Kw;b z50-0}68%xMD6H$uI4kVyjB9me+dqP5jPvd$_(Xk)m}Xb~gd-qfN?$P~jDUHmZ^nKH z_SeowJdP4_{lc5xe~UM=|NnOW--eA!wsy8(&g6Dx=7z!!4z>mP{0dEqQ1;BP74|PE)Y8y^?Bvsg>J-u^Z|I!@WAmTl*|~!E-6}d@K$a%s**|xE&vf)T@;Z9G9ou5{`8FLm zg&a6@HSB?nx*O{M9U79JXh0sLAJParp;lK!_1iE#Vh`C+AbLuzc5gXb?lv}zh9ZN^n3yR6)i~^%O?DnhyWf^b0cEx7gg_~top{pQceWZq4dao zY(f-_ItG=#MFw%guB|5O*Kg7Yz~&sqi1-PP_m>UHInjH}gE^12mT3WV>=Q-0D@Kl@ zl2eH;A`t~lj0h(#PMT_)3Y;v9{HqLzWw=q78XjtlR+tAF)AdAcwS1blCU)7Z#)HNM z7%siphH4}@=Pc42HnQd`6*3QP5hk_}WnX5L&g~whl=CZ#(C?=vls5D$67?D!gaii& zA0Ckw5SF)IEqpY%(Ztw^yKgJ&DT}{HFHsz1`bd~X+siNbAI!tp@q{@4AczPQ=;@Ts z@JI*FDpuVgK2*f=^lHrJz--pi->T$AcsY3*SzQFE`?Az0KBGa3Wi0N-7q%=|H+a4? z>^DU_hmwEh#L+Q_3~Tf~ecJhJF+VF7Kx?pbR=HyOr7lQxpvvUplkP=^V~mfomG5HfsNR51j=3ogYPx9-aZ=E1cLW9-psU`{ z94d8?LVM%RG0>DfeZwt#665o&*hTUh?SC7f$PH9}G`q@9o!uiU&R2WVp`PmvV6!rE z)EH%JR`YAik{jHiFGXk`szNzHtIi0#+_%m6Py}9-S{yvkujsJt*pN7wB`HRxPpt+< zOt-Lzpuu@n@%R}ymIRj#f$DBpn^Wg7U1JPoebAqexL=TbF=vXiWUq6`Gj~y;4%A8u z0Y0Oa`W*Q#UxsgtFHiM&1G;7@1AA&uxfQ3k6zNQ*nuB}yF1M`QcF?UFCl1;=R}&QX zo#l#neMKOkS&bA*I!3@|NkM}Fk4B9b>)9)@rm^IHZ*4+amoN^Xw_;?)5#e&I12hwi ztVm#+Nk@UJMKbAN`J2KNX9B*MOzFW(dZbf`e!J2hvdazl$2ri#gY29=*Q*~5x6 zkT>c`Fu@0M!j5EYo5!3hxHJfo0tQp7XKF{iDd53lw|COLPd!PT*+|Qd5c0P3xVNg> zLn^jP5ajq<#!B|N-RuRCtO)W4RjX@}cV4ez9W@pdAmY9uK2n_b$ER*8k#v3&npM zy}CO89GMPdn^rZr&jW3o&qb(&{UaBKCJ4NzEHiH%sm@5qIu>Vb1ybt%gVvA}`NK-1 zC7`ymSFE#79YnR&mQ>RRp|%~NOL_p6wXbqF{u730|gv?73K^xnhI$0avX2goukuDLS<+~@D|F;?QAE=1#mH_654>2_yPczd$ z!%7|ErzTX1fESap$MdUC1N3hMzdK$|P&}ET^8A7$wh^kSt+gxL8m7B@-{jTV`nHV? z3x$qGCvT?&wnV(snjef(A&Z93B8Ia-ZMfOG?de2xLCg`6rATz9E|=90ylDd6Ru;1lN#u zS?3gFeKxt_49tpt9>$XH2bLl05Ns1Y2I@R%NCg@<=h4GTu z?njK~VZom?90?l;R*h3VT=6+8G~ZY4f)m55v^2(`&64q#g!86;vL5$keU?tmLnSBE zJ9C=jjztkcHN}ZvvPQ`Z;-)q8)l(Y=%ap8hE7$y)tY8s&whk*4yF6qteZZkML-ihw zVQpewf`x5@aI0TU?1?rWMZA`}XVA?Al4#RYZ!=FIItY>4K*z$JM4|GFf-4zR=F2tk zSAZs8hQHQC7OM5z0azc^0U@}~p2br}cwo6w7eJ=xa9~9^#hZm0pw@M^8oIkKrjPwr z?}cGD+!YcTF>}w58pKHZp<*`IHh4`tP(p64MJuyQfSF|6Q)dch9Z&FgVA_Pd}5-6T)^^Yt}u}2W&vHO-rW?83x+6t8}E0wgp(pB<( zEjc+C)dKu+Cck0RMy#|P4dhCsRAP`rs#Glk6D51_XrC%~7l8;FTUj5!x-VJq`y55I zzDO?;Mb>~KWLM?x51CQcDKa;eK`I&XQALU_!jY*RcaUObK(8xGN6s#lj*^|spu3ms zAV>$%bPaOx4;Nnw6v-Mkgh{hQwK`Kb|L>^Ftx7YVjiuiSr>e}bmyG;F0|U>6*HVP6_;beP-H!0geWxw?=)oI5FSbiHA}8;Dll?U2l082x6QuSf|v>BWK8Rf2g5dB*;M-Odu`mjX(z$Qag zF-&7#zC<+3waU&G%wG*6G<#tRza}$awr-L4600n(KLp%EfyXw1_fXdpg!YEtK(S}7 zU?4G_(rp%3kqBQ6ch3qompxDs-_#x^&Qk73E*WyTA2*leG6DqCkbeu_`+7+5hEBaY ze?4N8!1EqcWqsljYd83H*%Zb8&%=2|wqcXeGUp?v%d<}ZW%KFJ#yHNa%tlOATYmEH zaOEnHd0bUV5i9Bh5zxK3Agb8`H=`_Kjw^rL5=hGOv9kOV@ue5S=s!62TQFN<3A~qg z@e5na!{Ye`Ejj~ls&W%(68TFQhJMnQm%anuu5~`WBaXap%Tv`EzylY11-Sg&Oji8q zv2!ycw19x$+jMoQI|qmEIy#dEn5rXpj<=tPq&Gja2BiUg*=_;PlrnpUn|dGORcmat zc`alt+wpGDyvQ6fVd4N}(VO(t-k3r04w}hr(p>@{3ZH?av!@`#neHd$CYXeVe7~pD zf=ig?--v9XHbgflt8ECfcaqh9Zk5A~X8TkM2UG%Upwk0s5>U89OHZ`kUKT; z{I;ooUClUfRp;6{Oth(2@0tDm`4{YG@Z@K5 z>=VYy?93hCRk1Z#ZsYt1U?}35XG@{n9>ySDDu$zbJ8}DCeA7U~Zhsa|`aLHilY_!dUho&SsZOw2 zkQw7sYpcEmOK!$eiOH6LeUip z#MBWkA&9K;ryH;gcKsB`>`%w)Rm>fJd$*%N(zGbB)OlM2Kc9J2K9=QX%5(`&m*H{8 zb^1O(Ql;>art`Fqm3gI?xrnV(%pKyZDUgqd8p}wTmoUQuq2T-wTI~kTp0d z4r^b2ePGA{n)J#eX_D1V*Ed0RY*$?zotsMyo`Fjf^5GM-TN~)%x}zaOjqpkZrbfEW z;_`7U*o zv-bX6JSrD_=Oi9XPC8o&^T#4tgNb4xq_=nZ&7hj+Va4#FTlNq;?)c^KYWG)*W&qzdk27CgV%`G%k(WRCtZYljRg(|Rn{_MEFX;*O{7h)FX_Cs6O(US5fJ z8v#uyjyW0k<$BL4_D4?MOV`Vf=cS00Z#;wXVf>L8HPQog$wTy7ETun}cEeG#)1I)A zNV<9!pt}Z`frXJUI*n(AP!%=Q8SFNCVEhP`yJ-Z6AAeMYAC=~ukJ_j@gUnu1LUn_c zo!!Vge28(8}`7KPx@`5Q5f( z<#gGL6-Hv-Ovdp$3#o`#_l(d;1YwXyxy*WWeYMuZZB%o!Jo+s||FPWL2bIdq3wdg> zI%8_@Mf;S>gA8@GOX=6E%`y4gCL*zcE)w9EfjZh^ywij_*J7wQBmhzm+SMdC2=H@< zf@-0pd+shRwLL4#--|!hFW+q|Bj3;<6Lj`mBd|N7c9uYMn(8C404nU)k8f%3&{oq{ z{S%8kc7~tIf!xo=U7+mihPsIQPP*}vW?27N_oePi#M(Qlps@~&fG(?A>0zu42UUwJ zw3{#ah63gwXfi#&y=UG8B>FN_|NCC86JcYGh{1s=lx?(|%M^+zdLJZUN>$g^qV~E- z0l1kV0nvdclWD9!za&!~1bto5 z@+iq}Hy(YP-#)T%8FIGRK4Nj!j*k~Xnq-zw@X3r8LCX5CT0g>W0&i;OTSi1u#VP%v zYcK}Q-|+n}mDL*pF2e1$yT^{u12@~|3SOU&5ycRrxIU+a_dEwbK3TVgi0wduTgDQv z=m#-*h7d*UafPWIKYq%!`=dJlw8sCrgX}s{^NWCHhlxjz{^M01(NkNZU!`qS-M#w#(URaAzR6dgG91?R zDN~>yN$0v*(z1Nl9k}O}F>mC~CMfm^{8tzZ&L;6U`KrQ{{o5+ce{u;{w6?W%GW)s( ze-RA-orhM@RzxyI_DS}l5=Vt6vdEFJw#Mp74`-?TE|33U;B!~n)WQJ)4Vv7LL&2INy_%c^aai$+Z8w**jesec=9#wj^_w)1bFOtUE<~a z1k&T>fidKa4yl2`zz+^$Ll^>=fuyG}q>6;IqkzWPW2n;)q{rV=`%z4f(Tf2U zV$7^MkH|hoM>QvoUZ%+vOD7SA(kbNO?x3KU8D8luxol%LRAIs?+{tCJ609+6TT*3{ z))1Qve?B9zmg28OV$G)g6~6~eh`AhQU8vN)MUSrhH-KwA6= zLSz&#B+Gnmo}x*Eftht@QuA48a6vMxVmLlow!F#%P^AW<$&6k!Rf>*?Y>-G{mlAPA5Aa5;lgxo&6L6|aMZjo1z9waohV724x`Z^9Bc9&EEh{Sdz5~x5d zGm=uQf0ZoTGlRZd39Ld}hn&x`Ib`;n8dV51)x1k&FCPG~Ctp~&LxiQlXq1R7Qb(7G zsPE^949MkQ#Z7BP&D38F9&0qwnUxqrh_Z~}B4wK9{nT_%7x&PMhMJ+}FY2uD38(@& z>NqCG-XQWFfI}7zqr;>%UCXK(Iy*=TU$2dJFy&i*Dh9o*rMu7TXJivq$~D;Zp*2MYosj7)U@R-C=s2v9-ACN4u` z-jh;ONw&^qs=1AU*6tC71O=c6}Dg``R}){@ujm*39I+om`))>5>?VMX=| zj6qpP#`hu+KzAe0}1ump{B#Dh$F;N$!;?Flkrf(Ez-Zsg)aQ**6p2ioA`YK&u70 zx-8luS36xyH3H|FSJnvl(ib<;o3y-JWg$e@macTAEnPA6)w}t16HO$-NDTrS5EIC>BgzI|I*JXf*Y1kAo^t5D()%^{#1u5qG^L=Ax+GZo* zQxxu)d6X65mgh^5wtN2V^oFJhPkirch7ZveKgj!d=xm-t%usVClG}+2FLDE9loryI^D^&{#f2-73k8OY zuTstNdQ0?pDFj^Bc~g`KrQji3&O+gKlX(7St%^mZJy#a}S9;`oA zf|tJTP3F@Y-oiO;9wD%XipYY}1%fkZ!6f)25$Pd^*g<;#-X$P;Vgl%Y@i_MMA&EK?&;M$sKP}tGH=o8E_X+L|<@AnvdX{{TZ)Rlwee>$RYsz!| z>apAB4TF!if@~LE#SRFAzfQg*8i8NLI8qovL`K9H+E$M%7(xn?fjFNt+`NOliB@z1-bI7>lu!-ojO)%4P;H zDP_?jE3WX0f0~Uzzy!We}_MY)5PNhNT|Z%?T*u;{fbRY!w4JW}DI z1d;SlBh{VdWW}No?;3T*%x6h#D$7M)X(q4A^a_k*aPu5=vFh!l$3n{3YUGvX6kAfd zv7_Zv3p)w?FzzH{(@)3dadq$u9IzDMw;g2&2lZ+h3|tQ$8y^aRCSLPRq&nJQjdSnd)Jq2yI z&)UqQ<>r9FOke*{&Dv}YR^ftp0>INg1LVl&xds)#=Zd^URVRX8T02`4GKndqK)wfF zdo5Z2K55gVSWgFk4;RCucHIiaf27UG z2@B>#jiD)OD3Kz#NXc74ro=n!WpH!Iz=x2^`|c5E6MTJOMUNsrw83Uqims3-QOFFb z*o|d2MGn;yY3EGFM{wtamzAKvm+0UMob|XJPd4CJid;wvLO&%FjWitW^jHA;t}Qki zeS|)8tUl#<-w=3}0rF3Wr_|~un5?Hr+a_9e8;1{SnrE7IAtY6u9Dpf8VW0|E2;;n5 z4&~a+_Zc;;8S$ztjhE>`Ix;{MBQkgBHph%PfbuD^crrc$9Bm6~1T{O^+efU)F8T?$ zVcT+bn!nxP36k6aU*itM+9S!6`U$(*o?1$X)y$CBNCRSbIl(@Q0rY(yefQIUO1l6A z&nIkZiY_bU_HSns=?R_QsxM{f66F6L9sm2tR?+_;I?6lie>pV$m$%8^eHj1LepIY& zk(H5sF1wsuOo}@aZH$$#VRF|NwaHpWlWC^4!v|+2pitVBIWu85dNL`D#x(H;1$;Pr$p?v&IKL`S&08U2sSEmgDmg72n?#oYAjM%W zDiBg*A!-QWC+B7HKYz>K!9Qw+U zH9GO9o8#>?R-iR^xCqB;FC($J+J6R#H}&j(rXWfxk(-XX1rKM+fETzq|0W;ImkYcV zDQM-9u}<{}bgewX6q3DS4fR5~boW2Q6l%2*hF;6b!;)1vv$z-{u>utk&%31!D!yjg zLQs4I32N$@*enl4Z5_C+y+Yuf@r1DsdMZ*nMD`$oG54w*Xi?GwaPZV(R$ z`G)6V7x;Ymi{~gN+kr~74{G-<`oQ|K{1(I?%r@k{h@jf6FK|sSnL=O{ub_&E^^+N} zKF*z&ITJh<#vMxt7;&o;gLegPgtq2Athz{4@(SJH0yce0Hg47K$T&7#CrEUekqvx) zi{^S1KDkmojMu+WeDcG%IBcJIN_U6JiTdC*Gzp+`id%fKj_e#*Mq`=w(Gkp5GJqNp zLEz#ZzTukp{UQm$zzc3%87{seY~q&}-oGXdx&Oxz_U{qy{}@tymDFua|0}K*sz^G1 z#nq3?4vrHhGXmgUp+Q7v1|sMj5qgL`J*VANJqNg!iDt7LBLk=czdAn*;Cdi!kP}XqL3U%X=%b&voe9<8YV1o%AAaH5 z)njcvQO=c&`0pIfStB^e@Pt5Eux>WoH5*?ejG2tEcX;vjS{T@No*jW!I*z7{F4DCD zNh^7(m9qqzjR7m3^$QYShBrfGXD5baU%Z5Z}YDCutXx%u;az2{e1_85FJd^ixMfM&gN?=l5N*6L$P{QQ&kU|aHZF2fZ^h1!AYML}~x+#)1%~QoVdBHOGff;|9}B7J{P;msyU~u4t~g z>=%G~*|z}{@F@|@rJl&Vz_n6y=7+d-DZOP~5gTZ1;287>38+9FiK=PY$oNKqg`K zBZ>Tm?3ss$Mu9Ta%bv@b)aXv`DeO}({mO|I%f$9h;s6?zHS7I+NvZYWduP38)=E0L zd-Ik3F01WDu~o?>%d5`AA$}J!F%_MANf0N;+A%!E1{!eR`e~As9-%rCb+U*5m_JHw z!}|QO`5pqYt7Y4Nv2MF3O3}xvU6#>ur2tc<`cSB|qNla?WXL_67t_ug`|D+3fg$3{ zS2f}Ye#9$G?2W343ZJ9&K^GtOh_)&8sZi<^8?keS8|~3JSx>5It1Yz2(QJyW6AI@@ zPvq5bB$XpmI6R^h?xJ&KIqUA2jR_YCSL-9Gs$$Byf%Ex%7?cMLz8_EO+zRV-r**M+qS&EiB>9a1| zNmj^tth|Tzh}3Oh#J?kp@IV5>=}demR+Q1hNFG&tW#CH{m>n7Pl>dHX#N~`CII;|~ zmn+n;C5AbI&c2>5hUqPCIJLBlN5^9e|6!Y++>&Q(DUg6zeBbUH&k!lYGxmcyz-63a z#8Jv2D6EpfEoR%2s7R*sn>!Po-yWGg_Yj6__$})-=HX2ni8$jfO?gLuHZ`r2!3vm?J0bP zT<(bwUH@yfKKAny@ zY*rPaobp*~387XEmpb%{d|{cv6ius2H7!nbKDKXZ6Nxv6rt5S(6{$P&N?YF?gj*^` zQz(g(^j*K>BJPVyornCmhJe~pd{`h&9WZ6{pHipO-Nx}Mg;*9*AfRf3fAA(UQLU$w zVHFRn;S9-8g1#*%G1KgmPKa1`Itf?OQ4_Y%jF@L}c|b~^$9`q&I8jbckr2)9yQ7YO zK9+N3ljCr8GHshObkye&`01 zlm~QT2|6ocXCYR?mo?9NU{9%<5KoQWxIy>%x1(3La-RSz=(le(|CS+<`_B>TUz;T< z{9{QcUGIV=oxV8rg3xGzI3WCjSMr32ppi@=0&Ja4l0lzVmquP+|7TCNv;i6U?fVA= z@6UIH-Ar?`JX-=_*UNSGM}TA6^V?lN>9^*YaQNL>DhjhUJNAJjaAPf)TI^ko&@<>i zTIeJ7U39JUr_ZN?piM(|9p%b4t##g6CTlnK7f`5Xxo9GB+jchRd zE2%B2)>9-_!Jzdm6Cf{m8lC>g(aj^44tUUGfZs*JF_bYOX2vs-0y|})j=4}dww<}_ z-oiBRpM}j->m=-!DfBrpW*zy{iRVp_9ddHvM6fL+K)6Sfu1Blxilb7>qi2!p8&(d` z=@jRya9b8&Qh!SO#OP0g^LSA>WM0I_461Oh9JX^!wqOp%fUOZU{s{MIqbqeI%3ONh z61Qb{LV;N?+5KUmJWoIM|FHJfL2;;YvS@-k!5xCTyA#~q-C=Nd2{yR9ySrN;xVyV+ zAh_$}$nLv$@7q)7zS^mxYHI$Ze%@bq+Z__na^-;o8{gRpJ8rYDrxH3zoV^0?qrWt) zc(WXj2I_MFKOHiJhg@+!L6LGevJmaVvlmvkdii|`Pq3ci%;{L*{B%O|JAbaVHF_%( zGV5lFsh=M8C-Nmb(Q}lNG6276n+3YZOcwY!2Ayb5yZxekKzG~T{v?*b&gEH97rga} z**4mV>g_G~unOO>c#Ty1;zK-c=1jEw%PN-e&p(Hu&-Aa2zdrzH-hUL2`}gbS|EZ-a zYGCvs1?*13^!He#tYtgPfcmy(DnpM&JFBlfhzY)8MWjvACnHpnKT`lQBjD+(RDNrB zI&4qY9SuUrn0wiUxFtp?D@j0B@S89aHG6kA{@lx@b9d9%=MCiIQ~C!+$xEPma$%qE zN40?666#FQ?A74CW?F*pFwdqMg_Q*#fhYFzeGmnypG+b`Hb1a^IG;ix7Cm)e5*FhY z+%*-ATa#-z@rCBp5$F+R)QX=PxIKI9KkIW~S^(|E%<(gwJr@Q42kHsB%i*Vs#Df zyz#k>_!|jk05nsjrpiTY$2PNAKiN|wMf465)#P5UHu(7W8Uhx%RLK%OUPN0$u^wAc zw&=J%Ta-YWe}$?EvH2dZeu)IJ)CJR9-U?uDZ~%$j@xblCISXHkB?{|d`jHWjB=kF* zj&k5)A5J5aHfqP=bYfQh=0qYfIy|<>N7CIP2kdN?bt_)FoT5>)735PL2}m22acl zchojxj1t!Xh|tR|KaDqtr8`h%pb)TNqD^?RO;t6G9l~J^^QiO+`^U&#t7idy`4MHm z{!udP-{bU-wx-tfQnuzFqqmK+g8{(iW9n8maJ2jzr&reci^`~_uBA%XNTe%p3G!Qz z`>R`MjHr;2p_K(ukgz*;Qm&4bS^Dp)WDElD3xWq&FS1%}Zw9_+f*0yvsk9~L1bbIC zW)m5&cNyniW@eo}?>AUoG*#rWeQqGo+H(hSY{}1d;3zB7X+tEjLDq&NeGQ?w0lCIq zT~b+k`+1ZZX?sy0^xU$39HNr(OVLbftfxF#0o|l-=1JeWE`}CLkuOhm&h#;zP(0a$ zIxEO>;E15j6R!Dz(lqTVXa-oKZ35_vVc`B62982tS5YV}S%xjI*%6u>rU9Gx7Flr? z`_XU-wXV}DHuCyziOXi5>)4z$*{4)OUc;+j(I6zN;`VE5>0ZOstCdJpu5cCf&^pWS zxx3xu9kn2p@^)Z<>8McW6$Z2ZV1EriunAoh%aLaJnJ+(hA%y)ScG|~b8P;2D!n$4@j@ECK3!$14yMakj4> z?84_lF5kd+@TMnFf=l#as zs^&Z%v&gvo+V=G#v_5KU^G66Mley2s*AvPg@vPAy)L1^$XZ zO(e4)Ny`$?7@y2$tQd`Ewk)uhJgSoJE+)Wi%E9h^WE%e((v`~GtWKRb+hS};Otu91|@ z`g}_0oF3~b@TpT6pSOZO+tQ%uW&A;zEb5@zV+qM+I;Z=#Tr@xm{wiORTsH0i{Z78Cwk};+atp&+smee|+%o$_tRjN!W<|uv#Gi?=ei3 zYO?t@HsD*K^)}aQE}6|sB+f+Zt;kusubnNO9q3vak*yMhJn*}fPo=Uh$zRrF+2y4# z10SVv^&cDXzn}H~3?gY01BX9q;$JcIUm}R)Z^n0}(qE$1s~q+y+SnjqeUZ#l1ce1f@7D;k%V6H#YIGkK;}*r@p=( z4$^;;vBFRg9uE-{<)OzA{efX*ghx_RQl_I&yNjI#a6 z1=kqX5knqtO`nj34CpIF4#hZ`%uOcqyK(8nH78X@wp(VzTvvXS$eD))CQ>Fh3V;uP zA5~_kK@jTiD;lsRwVkaQFEnm3_W#vq#0%_^Qo2uz@FAWYr;UKEeafd9io)hTo;8W=rt!J;1(AlV~!YE2hIT94!x@}H3U{S!Ry0bjn z4h$7S)edLxnTX8LmX70=et$RKTH&_d+B8D~JiD9&>)i(YeNZ+-!$hPn+g+(xL%NE~C%KuPtM&{c+H z|ACH&N$R~L@Gvl=YVX0TMc=PM73S=qC8po|!N1p@Da`gETWY*{^L({7z(cgBw*0OT z<(~8o@<)~1I_PmA{-|N3it=CpsLFY#@b2=1|*Vg8gvpal+^Qav$eA z8V{ZbzT;g=^PnKU5d|m3VQhdIuWLn9%AgJn=LH@Ox4OX)tME`Xmc=TW#nVejFzt45 z(K;K~-6{{D^2vJNayqnShUn7hy6Cqna_P%>vzRDsrg#-dxWexvhFDR4BMPV1v_wrZ zNNr~@P*_Z|%4*Bsk;culRd$7#0~Jcy8WjT!KTNL|Bq+hZReE*BRHi@}MA%BvQqe{ja(B_5h*wYNv-}A$t!7N+N%aB`O%`PRM_h~q) z;FFPYW$EP7Ij-xin@BZYp{rD5T|FnDgq1ZEj=jQ~9LKnFIyaRHnHZL)a}xnlfdQU$ zs`i`x9AR{1r;MT3baY#vd#}HZ5AWzWDRgmS%(@+I#fA^M_0%v=1shVVuzB}8&u*3z zgfSRELD+-$hJRL-bPnU!4Wkp6;P`Uz#ek_WVNw`lCHV2Df00u86~{7R{0?y`N;-N1 zC{6DfYb=h&4%j#X1v;&qBIk5+ANms++;q06^t4hz#{dOxT=<3{;u!Tk!=B8($BmUfjEE{nKh!+e(SLv3r#Rj>^Y>?B0a!yii$J8-53f?GhoDTe58!({cQAYR7~ zlZ4mXeWsI?_K>sZT-)*LtY-htiw+(J;wZ=#a?DD&p3zL+b9L~XS!}qwUX}O_N{oOisklV5{%XNvu{KeiUQCNll&Uv$0}3Mi4Zk0k#2@%P_f#s8<%{O_f(Qu*&zMB*IJ#X>7D zAYau%QZ(0L2T7QlCQjP{g{I<9&NdNe)wn_1sZ2%CoqXXxC;zvsTodF_{QgDS$P>+PY zv+yXcUY(P@RTn}iBBJCzeY0m_1eAK=GzXI5b8=%RLz9Z7FJ@SBdr_ytqD`Q%GhtIM<-mp7eY91ArT&5D%f4H!pe(e za*c2l!z*blLLWG7DX*lhQew(=@TJ<%xWfTzWN`X+iw)?PWjhi?L-nuxLDtaA$4%1c zu91NAq2?Vm85#T{GQJGmq8&*{{&1>=MI6h74%3p;sVsSxLK%|-Jqp;5uBv1r=Tst1 zcmz6g4a z%?sxqUx*L0!5FrIk)Z1)w#QF&j|4M_dDi_Hlb=DTF+8n{qzh{{>;RouV~2pDKWGhu z@qEZ5>W7~r$uLnEjrkaO)qele4|pA!iEGRRS$X%Z!Z{SV*t2J!=MAPRj&29L$evHm z-;^dA_wi4fYPL)W^B-w``HyM-?`f+4Jf#1X>CO?{2>yR$x)7hmK1@a9Wq%8}P+kyv zg+8Vj1QP)$T#(csnLYvqdx1{QUd-{gZw!#8HzNkF2TUY{{qVy$hQ`ahaKw_i?N($y zkxneX<0sm!(th`F=bg=B$hR+1ot5f5fpcMn%?s^Ol}ERJl?KIv)DcR&u5UJvw&68t z7FL1f51MR}ca(l#46yqHv38CLv9JhV|NO7aTZk=WePnw7KW6*?zlHq&bd#x61GwU- zVfj><0E_`N+#eNamP}q#!-c4hrNM>4o+g8=5icYYb2Zn5Ci1t0D6=7p!P^>BCz4;7#c8Unad-@{*(wOL{Uy_#@_+Z7p(Se~=`FlYjjRo3c zo9#vPYK)EUw=(brUputqY;j7w{`m3kE^!MU`q=+v<-&ihox+TMWI0)|C6J!ljWV$E zAq=;ZD!4l6!ubcy2W7RTVk;e{lk|%;4yRhZVq4b+;cBXkxdtt3F}b1(nUPkju&Cpq z3ptaiVGvy`jSSG4Hre$?*Ds{hGRj1~K0tG%5zo)hIhKa^+`Oo;Jv4(iUIMPNjVGm9 zvC2RzaNY2D;B>7a)AhiLo7W;EKO$iMYxJ7?PmmuQBW6X;heKoEP1892mZl_rHzW?y!=!@1S2On>fSQAy3u_n4R!3O7LoCS*&_v z433GjWCj`l@!T>(E|SdAmQjR@h2xs86FH4{YQ66O&xt0d6Lq%AR*&~EP!M-p+8Q%& z>P}d;ymm9IL*;X2#SvN>KRleyR9BuN)&XJ=TC^&@y`i`mskl@#Rw*C5fGT1?|JV~-iJQez4Jr1tWohYmop z$f+hSmV8YM zQsX*DMFAa3UoqZ=l&9pEeBNV+aylwla`gQ1M?T@eO_&y`LJTc9`hFk4Qy5(%dj zY@XQS3FGZg`kY)RhDs8lBmv5l;P|vLvrHOT2t=ec*Bjc>Nx0(@H{4NdzRG3-$EAi; zFoMCNfVu=ebMc%zR*NA7EJCXG^JZ}Tb@j`nxlM)Gu3!}>qN+UDb*d(#;IMN;>F#@F zF9Lpf#vl}!s-b>Fa2H!5F_L_O+JJSmJ{X^h9db93ZWT2C{z>H*+@JDxGX3EvDwo&;%0HsmmA$YhOCIoSN;rVKFg9gwD7Lk@D#wVWqqJzS z6ea3?t1w9g5a%W812`bw=aondV!Sx1X{_lSOx`n689F$<+L66|N$WH&>ORA&sz^+9^@=db?KQ5y2#JP5b5%2)xZpg4da?CR0K=2lT5K}X*-mtPUopD zr|!z?vL^{Nu&AHb-z2rGDeJQCs~Q*Gt0yp7Bs&sb2^U&jqOIFJlY@+8MX{o;^wn;jY7G8p~i2Ve>2pd_#lEiw|&)gbBohMbSq^MPDn$XVTW?nLCx>vZN z$>@HFh{PjUE*lwV#_OcdKYm{foJ28^39$Lqq3)cE5c66PQK(PH|C=jKy3B0x_)B45 zbxHS0%@4ErjkxK$UiVqnx`US#-m-LN8n)Wom9cd%@Ex3D^pqcyl9h47_SSL|R=aZZ zMqB(K7Skj+kiJi8#^)EERsX`mQF@xyOqF{*C$dGdi^-Uu?bB|~Q&S`;u}^0U@}<$akB4+6#% z$#K#Y&6E;BrJi7T7n)Uky{aF7UL`qlv}jwtbLFo>5PWsv=iAlyuaYI-j~+x+8pQ zWHelQK;j-+4g- z70AZoZnW6zdS>|15ww%Y>$Jey2$+2)NQf7Md6|nKx8)BIVp-91EQ+hGp(h%i>@9vA%m}8K4TYk<@vdTh^_p{S=GJryh29ub4nC%mz4dZWSM7^V<*ulO7XV`EN73OlWWw z{rc(ZG`ED0hY^)CHN%Ak)p)=iqxiRk2#@l4zzyb=3~$cdyiHEu3Cn5t5#G5}m~z|7 zVclSU*Tc0w9~L+xC}xItq3~P+PZYRF+q+N&wOauQtCb`F^t7#D@rJ#1ataz*am3ZF zY=AgpzdY9zU@zQ7|JTw3dEZ@%9EZI}l~<|JhzDt0EWY{$E>B-nz=sZwJewgr8YD)| zXwA=>3Cyl=1l$UamM9#!%>H$Fq2-us5;dW78DE;0!0qMKODtWQGErb-{!d%rR=qp- zbIg?0$E^y#ak{85A4v=!&2e6!)#@qj_)1&J6=0BjR2U_HM_R`>B@up;)XoX&h{H_N zI^P4wc@O4(j{|eQPT60KnnmR5zXP{$_}8r}5?W@5NdqAl8NF%?drVXQ=i$4%KQ8Zg z8HR-?3>x1jP{lC>Jd;oJa8p^Jm?vatGBmYW`CpZdB~IEul&zBSQXh zonPj|EJ0`;s!T}ZeRr9f%6#~IaCJ3lHu+gPw>&>=k~L$25n5{S%Y=E#%q4h{^Paux zAZG?aD-+DEc}q@yNH};zPtsAGur)k0cBk=FTny_EJ9xhTeIZlB>X>d&dJRg>%uKHL`(FX4y^bIB{v1r8Qq0Boo@H}g9*X}bpEP3@>Bs7U=V{mrNuM5dV78M%b% z?Lv;G%@UNq!ii2i-vqzD;&a+<42yZiC(A>k8QpbRy`1y-3ZdO3iDS(AY!z;AQOAM- zYK|x0*GmkV0;yZ5_Ny4jUI;iK_%aNJ~ti|BoQ|ru+j`=pTN!9*4`=Zh(a5c zB83CI&Cb^Fh-0JX%a?zF8odu>r7^XOLtKFZD}W5)D%^ebbLqEOE?Q?dq0~> zdf{_v7OF>wx%thfRbuRdO*CXdckcQrT8@FrbK!c`P0q!7Nt5?|i7q04O4}By-F#_3%o@|B zu`yuhDv(Vfg#sJR2)3}8qS;5R^$L>8rBZ~J^%8Z!c4W=KgP!69Bc@m6sAkv(hrj@$ z*dEJ_F}%D50@Cql>Y47qK3kNh%h@Xc=gX1d_w)yRI=-)o@NHETyk6ok@<&FJDU?ou zQ#FEOm(V(%2mk_NS>k=EhXi@Qn_{~R`B>A`KC{3PmPN{puf|gmWU|O*GauG5fffbU zd97NyS1D@DmEms*?=^z#tugY77(_>NJaf+{&* zp=R^rt^3{By*Kmq z@4@8iPrz8UX+KyP2xaX)QZ(z26)`OA3xrBROw`w~h%lNeNhg`S6Br<>Ib6i7n!Y(k z6XPmNh6K=Vqe14L&(A4WeuRbrthmoIfKZps+GwDh7JGt6uOUPtA!wo!{4B+xQw(Cg zY+0WoF-U3JE%QW0=)?Ml>=dZFYvZh3u90T#hR|%)JCAKxTI5~@0L+# zR-^H1xyl$EViGYGg4?+75m=5~=1QeX+m9N`pL+L6!sQ-R(WKCslrT8Ux<%Qb%A{&; z+H1klUXw-V!LnnLMUAhj&quZ;STgryI^rq0RyLaD8MK+srfldbGvM|^i59NQ0AGGC zJ<52`q+sNYWsc+~-?S8NHL?6a5rMM@H&R&ZcSFq#5sU5R=-qvv2LNT4p~iPyMACJ% z*_@IIW0G9Ah6KO4y?vwhDK<;S^q38jesujNdnLBCPUJX4^NR5%caWGcfN)$_Lk+j? zRJE@su>!bQLVp0qaPRe&R4N-lMsw$cxpDxDnCF5xQgE6QvJetvOOY46TQI}C<^NWj zZn}B=jgm#RUQ54p=^4JSdHRlNUQi#lJ9F%F{IZ$iIbV($4q9U{2(CgV zEQ@ckGgcNTzn7&Y8@{;5!&QdMlw`lac~C^j1G_N&oi3;bVukS!?GORd`cQ}zvUwqt zV+vk=VkKLQ9>>u%uiqZy-bl9cm6S2ArvZYW2{OAi$|7QoHgyYUp`I;umM6{6?-u~_ zYMLCiSC?N4YizIAHpwJ#LlK*fuV{~1cYai#zeE24%9t%;#+83Gy0U+4bpMxW@{g$D z-+fL=M-D~d3vV;+x=ST^+4oJgz{V>DDg#A93bB`>+|nuRZt zY~2GBG)J~|gCVQ<5WA!sPLRdw3;nCcJ=d1en)1E$hNte_8`|}svuH(d?c~CS5ay$7 zo52tZsM{^qLX~UKrN|u;PqPs)utfX5$w?3rCwn??UkCx6%XMv4-}M5QuG>}+?hQw> z=CQ(_SM)+l7F5pM;eb5X>hT6QI%7hvy}zGE*71#*Q9a7U7RNv4t0;9xXY!(V^@TP3 z%|mch#<7c?8KyozVvnb!^{D*22^_liop~(N9MvwRF|3+K@1o^{(p$Cp$5i+6hZicW zP^;InA#*w>MC<4@!{+9@K$KUAd6f+5g4mbIJA~d8mFgxsh$*m$w;pUJWE~`i2(8HL zTF?xCJ{F9^a~K7ir0X40 zH|Kg&a@*f}7(!2srS|sYhJ473|9X#48Cn-D{}Ia=|5)-xJ}#C2&dd2j=|sf|VC6_6 zZvb%k>s`LEt+Sz($zLH{sATz<>#mjVNmFR;!hJs5FVpgMWqvYIL;tS@5&%m=0`ikM zt7Wkzu}i&Db4rQ_&=-ZBObIwmRP4H%vCLG@3Eq2#`@zZT&CjP>fX|%D%6pgc!qEeE+I)$U=G$IaVyo=B2H|Jo#gEQT&$4_f z@Ne(LOKNR+pGyKabr03;aU@+z-h2Qy%i^LC8K7m{3)pDux)sefWM_190y51_$YE=|ez zm@t`2U?t+gW2-v2^;|ee&|yPAI_aE6kG)+iH5qyU!ee*%BGt2i43Q^-n2}RdzZEGI z59b*BO}0N*!n|6xNMfC!!b1_th7DjT4lGd40DWNYB>X>!pgQ$js0#vq9bHtGiqP`i z4d1sRY(SWhO;RF+b5Z-7?L1Wn3RKoiBIw0^Gvdwq2|Y=n8v#8DH3@@wYncH`jttLs z2o>+(o#gX-66*tSKO~lS+Hc@Tw%}4Hhr$k)2v8vkd14yUugqY*B2|2(3`~IP2K~!xyh}?@QEDS~d7abo!0`R;`WoXqy5?w&of3WX zjYE3~h=pdmQjg9YEej0`Ee9M#^oQeu5rwpye7qzX9A_my6VI=p>8btfkFB?gAZjo- zY@Ja~6j8g%%?@{T$-8$r9f!k zZMYsKeJlW2SMuCxWk&YCrCFYf3);J;wG%aikHN6)vV-gI?tg!4` z7Dt_UxX{@T{JN+~+sjy3(>Hh%&*L#H=(woWt#+QP8ti~6d^+SbvZ`%X-qR@z)tpi- zU?}N2bB^Zx>ljHROFWwOEGHI+T(g?ECpf5k9FD9v#DUd#&0a+sGv{r9fXKHp5H9RF?2gJwUOII^l;h$`c~Bgjv$sDH)fNo>>FAG>bs z{}z}3)vcWQUzbf;lMk^dhrgdtj%#>&X{mX?!)xweAhi;W5WMe>zr^F2_ot)*-%Zmpl3%zTh9;zrOk$x>o7A{k}o{ZmAMaVB4nw znth!QXEv%3z@IQkfaNxUNI&s})N}Z1K8Ru5eGSohBqlIq@(|~TVSF&^!}LL4wl^DGKGYWM;_w01{fF@uJ*av_^8O_)Xmv={Po|5-yzSMV zi_A~h7x18)x4RY@@LQe_odo<{o0tz;{MeVSM2{-lPo7w>0lKvLzNiPjant-b54lSZ z^gb1RKf~U9QLcWD9`PIBWPi3oOQ*W@27M=`y77NUAAKL}ihgPN#=^ce2*Ct_%=8lK z_kL>x>tnIS3VH|!9#n=;9Unr9;yO?l>h$YC`YDPS#?*|;#DtC1sJC~aCO4rc&&HA@ zUe@_eqtwdK*FXNaJ6D}7NyZHI0MQbwy<&{PWNoH3)xVii*-Ek)SYNB`qDI4M=njQ5 zS2mCjvrkEDo5-tY0KGDt$|;aw_}TL7jPQ8w%gQ1B#9X2?;P9)u-XEDKlYMCUWVIqoiInv~Bk0 zo%c{$z+0Z^))-a!PC6+|jX$?Mm6gUifT&`=d&Dvh7igr2aO8;S(dBe_I*yWc326WJXY*hr(sNe%||pu?FBicGQ>+hNcF?4r8}2;s5J z8AK7weqiL9bV~)N+fD~xv0h!2T}XlT#`M$94J0O{Pmp(oVoaIdO>k<}nCEhla4X^F zD!-)>@v+kG40|WR)VhU)!Lz~r8LnxwBi5XGc>DS~*w)mqI??7mn+oc%t`<>Ky1!_b z4Qngu2%L{;a-B$#W-luOP>Yp1<-G&NFB~{iZo9vI2r03yF5QvS|OaE1>F+q z(XHZ`#l%Zc(Y=U=D7FYCmsWkF7>#`FQ=N?zHWT*fd)tV!aAP}r)9ofEG3bZMd`ofX6)YH2M|FbfLUY2G zx;GSI#VNnpJso1aN!k5aY7QzpF3PJZzjc(@jPiyo5jF@#*$j0Gm-!_PA8G7ar_Ed< z1<>$sJPBLW5H1X6wzBh?$Cez}8O!{IC20+zk;o71W0B+Gjm!Hye7&gK7LniGT3)F0 z{KCuf)yA2mV4F1)!YPP`%|4wPS2Yf+kK$_q0IK0RPk(y8)iPOup=HWVvx!Lf)ft&$IiS1~Iir7E}p!gc{14W}fB zF#>;w8cg&bMQtM~>6E^Z@d2Z$=MLeIW$zN?G$oUtcqllhUTRAfHT{8+(8DEU03_8 zEeKetQ?+i8&CX}e(4#RkMRdSKwh!<0FAw_V-=-m-ZOK++!C~+t-RcN(r@$ZWZ*xwL zkEABEKJv{hHWQ|L;SH}T$<$&|IUp7@Crqmkm7OO$u9>+G>y#<^rd6LTbkdE?Mq-X7^nYG>xJgCK5uG zJV$u{y21pzTuv1H6j%}zEep^CdS>^qlWy7#|N6r>0zX~D-&0edm!qly+>7!}TMQ&4sHyJ$^r=y|S%0uTFg!f;+X&X&!ME;gsvNwUGMGluiDu zRoYO!PQ#b;93kM*7r)9R$EFBZyN>Zk*{FmDKnBXEMFBvt>JomN1&9<{))?X5e0($@ zUfMG^e}s-Izn~+$WVuJUfBRCF6L| zZLJ0S53K|t)3_`9S83~y4yNgM$l3JF3Y|d=x&{{BIMxqQY}TwQtW(U2K5Jkup;6?F z&Aetd+-HY0h_c$jh`XN$?@gnwayGhzSSB_E!cpY#?SG@x?;Oqhb6jyyq51@0ER7Wd zAj;9&jJa{r_b4ueiQ$b}?sikyLlZr*Wew&zRI>qLa~>?to${8v2%JRntb0+Bnut=q zohwVF_rw-&jO9mi?zo*mk2GY1d98e&772Gpn_PHK3@1j`-IW76GV_cX9$~ez%5Vp^ z8ou+dh0M!zE%FP@rVK0-JkwaAN~>PN^+iz&R@!1HbuI_q zz)~Dxn6EA{X#ND&e7?v^|HM!zi~8wX7v=TcM&MQG+6G^# z3Xe^>{9wiq$8kc<*%8v#D$zB4wTs@fJ6tj-v5fBL7fE4tR9}73&6&7jZ z>kI*&X|tkd53R|WvpF)d>iD_V3BMV1Nr}goHV)wHirh7Vu+mV}i#2{?IUT-Ek0683 zLuRi;o0Ji-mwdKThIT3eJyL>Xtcc?%m}!xM-&Szu=KCNwOPVyk12HW}zs#N8*PLjU zN@b>ZjX9dH(?qlVR-pOXk^Sb&ZrLzJk|%fI&Kc!&ZJzaS%@Q#O!5M)X9;iB+t6yqZZ|tPwa)#q3p61eRPqSWQ zr{+O1zi!d&xEeUiABVz5C?mw;+}_$v94oK(VUPB3ul6V`r8_#ta<+fyBWXfq+nO%2 zcN&}6MdA4-t9Xi8rF_~sN7+CH{d2ZOMaD4O10u--9n>Q1BAT(8KRMt{^=g&9C~^$o zx2&&Kuh2|xBdOQR#`EoHkx4vj+BKyg4r;XXq$akZLv`FUYRv<6wIHGMc25pQYb7Az zz~Q?Oy3*4g9T$}XtVq1`=5$Qe0?6qB_Cd)&}9GXtAzi$ z2s8a(EW*wX|6v1~sIn@D`{7MBuB(m-0jqu#ITPMNGioALo(B$~TwM^6%w094tmJ|t zU~qPE;pSeQ@sRuI06VM$WsH}FWUQ3oNV91V2l-_4eQGG#FBo&1?A$cebVbI@hwT}T zKAVp|hZ(lMFDI+*pV}^gVVN8_-JEEjBNhdE>lHJS4F$tsk)+F7LZqn5E;H8L`TQ}I zquNlF6ftMqHDL%VO^G-v4AGN`Qk15_lvcEpeqpGnixf1#;G{y;QEBcyswp@0gmi^| zEzV&i#Z_t^!)dcLJyjrQ_SNxAYOvmh)AXPtH&@EOwi*bE&mV6!7W88($gyECI@Dfw z8FZ$m@A*NJAY{#sR&vl#qvJS$8s#rP@q_RvMp>Sh*opmId}v~O^ht#`%Tfo`|`6b2eB!bEBthM4w=csN>;u9+3mxf4B6B1&*h2Y;y_0a(=KNbu9L81 z$7R5JVy-a3CmRlGQL^1bsyP0q4>}y`wcG!=5afAxb!B> zOWes{O6acG!ORfHa}rdGZ>B?;%+Rx}8TO{T9;)mIV7(H>!}dIt?T*1a0BW1?ANg8M zcDuwGCRPKeDaKraqGY2#@Ism@7dvcJTZZeL!1Jx8tpnRB>20-{9UHZ?DM;y2t>c5) zkoe2F4ZE^r6U&LGhrzH~1gQGFR59tu-J{8Vd3m5&5$_G9NdPEkRlm0Tg*rIT${qu@ zRS51;;}Z{|yq|97OwOlN`Rh%|bk`(TmVcx>0OHRQp}bq*eeNV4`*B-Bi+=hpe~)&Ayn_&hD%(=hJKjOLJlsn--`$ZA(@iSY&`OHoVx@4!rX z4pjr{JAL}Y=Ld7h8iL5W1rFPU{ewsvoL}uc-Wisvh0VTGIF^sKEasP(X10V8Uk0<5 zh!U2NK~Px3q3FIUvmp+;(Bx1pxVwHvvQd+BLKlc^`@T}$A%tISB@%cA)!imPNvvg; zu#LdbWi*GF7rc@QHIjb;mX+YknbGL37F&;iTjYY_F?|?p%G~g2u!__ir55DZ18>8S zSnDf7@2;AF_h)$RpjMdY^3}o+?2hnAhBO6H_5l<{UDRPF1uym!3S@U7{na z<=;=4a)8KFUy=EyTz_wLs0(0i4qI))mZsiLN7C#+eBJ9IYnIc22t(eJ=fn? zfX}}3{h2SG*OCG2bd#<)+eqp8?kwu}`lf#R;C}kI{n4NAP?cX)Ph+#imnKP0`O050 z;%=#75BLzDDurjzT_%|e9GsgoZjOIlhQMC1M=1HkcyFX(s0)tv5jAaUIS+4+TKsGa z)EM8(DB|lvjd&Cn(@37lcZaS-se4nSGC|^2P2SEn*<(!};@%xb#osPbT$Bu7m;Z~p zQX6?&k^2E2DgL9N)4#va|F;0rf3VUD6Qpcs1wPof=^XZ!xY$8gK4?&L?o%>bU4$wM ziQknI&gtn_Z%IBQ2J^NY z$^ETUnaWr(Q7X^=Yz(y~tsp5%C$(v?#Fv3v5%Z2!qZ+`zv@q&+M>59JD7^V81FBQ9 z0XO@|_bi4A&t8;E*$ep+Mqgg8Sf82aS;HN=b4Vl7xVgQZ-#^g{Q6ui_6GDZ>(p#Hb zMR1(&oUtFTO!N`j9M0MeKos|X$orJ+3Pie^Fij8AC2hA{Ow~*~*+bLfSOX6^*$u_Z z6YkeoMdsU6xPkLONuzzVA37s;KiHfGn0wVf2ez7z4m*^tAV3{^aNY;Sf;Cr*WVP}( z=;P#f04{zkvc#-}lH-&51QL{8g|5q(8n9?H>&%ea!tg~plpWXo)kjYZ9L>&Qg6Vsx z{fMw|S&R!4F9&e>Is=IjCp%PtpkHkE)#I&`L#q#JX_dA$DrsiOpzsX|bz3u`UKxp!K8}r*1Plc%&SwoDl1BG_>^3Tdf8?kbIsFg(a$xx+HHPea zldc1IeLedm4>x=L^Y!9A!6z8?#n}D~2qiJNNmf)R5{Bws>@W+r+%bAqnj`V;M4$*B z;KxEuL2lnC;21EWNzKKr9>9(jH!29@n@DK0cZZ2=;<{1i~wyMXe7yf(L!v!S+TN)$m1CR z0&^BJ*`&6gbna2yCkV5tpvXy1CyHuhWoM(mXkN2 zz3mn9J%`9LQ49LjdL5WL!;h6`w2nNRdH~*(`>Kt}BOK%WHxKgKdgyi6Z_NQ8Fg>m{DC#zE8 zMX3Jo)2T@jlF{DPKLVuGwNGr~^>+-lLPVZ+spHgY`j9OO{)iN&UF{KI^91f;HB{@w^nY;x zvEK(OcpzEaUw+jl=;Z)hGK}?7jG;f0iAR+&%!>JqXE$`}knrDK2X z*$8Qhu_0DTAD%_Ov8l;)OqflGA0$-ARzlim$r4T|EhJh}A*%2{u`aNzPgs>^{}t?r z>Wn!QRKj(YQh1A*1>EHC{W5GYGqe5lRRnt9_K$ZgJBW0@MnAI02I_yE-B&H`#XrXN z|NQWLeETQt-^j|@(aGcw={O z`7*(cr*emyl_SawY$p`k3yoZb=cHeU6K@iF_AO^Y|_$>;EC`9iuFZnk~^v z+qP}nw(UG=+o($0W~EhW+jeH9ZQFkNp>N;5V|2gU?~SwfkNxwE5wX^c84+`iVrHph zQ}HLmgI%_yAJ-0$4veC+7-{REwY=lyy>>#EuYRk@^k&hs7`d45frz&m5QHf)chg`k z0=yp@s1BQI#;{q#8(L}7W7toq_;@W?gA;E&nBy%Y&K3=wRd^RsV@z36;@MGVi(_nk zFKjn1xPHakDb-jIpVzA5zxHAo+nrq5uSgr(AI;Xp*U8$c%m`l<4@Rb8$tVOx7sGqk z%+Ii_G|UonD($s~2Sl@g5KSxfpQ0j_-Y>C$FJxUd^b10PHjueVg!ShH!0>TWt^X3S0JOzLO^l5moQ~qiH)io`2CuMGoQC4F>=K?m2DKmExNsE-SbBhS+pKv zBo1;;4-a!xReC>gN{4|VAd3WK_&j$@?KuIG7%ZdtJapsWlg4!&)#bLz`ChulKM!&x zpF-6$Y-?!j3JYlGT|X_Iw5DW^tBpCLzgv1JqNNS^GId1XytpQc4lNiRiVi24C(LRD zn}T$3fCDvyvd(K@Z@OY<oKOHqgFp!1GT0KenNDGODf!pp^3**bMl(RoL>2gN^Yf?>A>9t+F z04sif3QD1!bmm2UKlXb6ujk=DvKZW z7THAIjdo$*Y~AEBr}0DNic7`LP%AGdj(0g0?kmwBhxZK+j|A(DABNsbIbEMq`e0pU zpLOSG{K3+h3DX*25@v4qQv>fYP)JE7xfEHlnr-PL*9y(K{?EUlCorN@3tsY{ZZCjj z@SpC+xu?Ll#nHCvL0rd&exDNv4MKj$g>twVf2S_Qc`xnxpjXUgURFgd5DpL*@^J(% z)Vs9Ju4X+MPEGn1#B)Xd02v#E?WDcZ;ch$Eb_KSO+Q#|3Ig>eT)rafSHvTU!=X5>; zH#mGIgui-1u7)dU9x#WMzj?SQh!LZ2?L=!)16@8DC%J{im@M4{xmV89HohO5OgeG8 z{mDqM>K660hV2do7Q+{AU|w0J9LMtYr#Vkl&wKidEc*KJgYsW&&I zbrg5Vr4ZY73C;sd)zQhD5bIK`z@d?;Rj!Z~pXn1j%t2kSUTT8{%0ns-I1po2gB_}R z!ei|V=ji+<;O?Jq?-v4KK2;$|w6JZymrAtCgcIH%G(!#;d6)3z(LlMU&M)h56%yMx zgS*h@Jh5B@EkR@jn%bi$7c9|N-0)!O7(GzPUI~W+k=ncpfd+)N{rkIQK@QMw*Ua!c zXm!ujAr9CIyRbP!T2jIc8{9!)E{)mrA(&b4E(yi1$GvX6qTl`a0eC+oB7w`GcTWBo zg*f796E{Z*FgEiVlnuA3OG0gU_te0(z3t1CRv;^i~vSIBSx!^FZVH;AdPXm1lMP zmggbnU8D^k@!UTHOJLLnxu+j^#EQA3ZyM}8Au)SKe?}8WorUdz*R_mNZuGHqL}d-U zMV(BWHYne_B8=Y}F<%~B^7}+E-69sCKwLwXgQ3Vrg_x?MaUs|Ki6cSUlIB82`jbF{ z#DPIKzB|wSIvzhHgkDDt@ch}rRmm5#xKW22k_`zzE_vj7;pXzd+2)0(_Yp%MkJMU< zzZ;t>*`E0kX}#eSdaitCM@wJZxF_?c_lP@`EWe>@w;wz8GKYBfEL zApu_mtf+5a<{|eCrTqqF2lo5hSNCrOF<-8<-KF>b_-|gDU+TkO>N!x^bCK%o5K8Y0 z_iu~}VF6!UQCVM=F<-{!vGw)CD_G9&u{;H!3Afq8fxO&kp0E(w7+?Q%M`M2^jJf*; zR!JED8CL2fafGkomTL%}7#N$Ij6UAve(574k8r(<(7UGZi@*TARr?_Dww@q zAu#1_Rs}}-FkUP^+Fy6h@y>C!oBp`D8+ZQ!%#6EH5bCwL{5; zp*5h4300ihFUj1AJcKzP3&y*HNONS(5b5OG9$%e&n=BkJ(qVDg9tu`4@5UzKhBvsN z9f~`UU}`DftGH@gIcZd3!$T*vqVZQxPT6+8p|Z(@`tma01UtbiWU(^k-b+N~&m%cq z&GeSKb8*#J!a>}#oJGBM`QL+!vBjY~v`77`S15;aJz!{Y~gdq3MSz+~XT1<5Pp)zSK`@K1+LNANp7FiEn!mbvkoeK0}iF{(#_2vAJ&Yz5Y zERF#)vjW?|mrR!}SA)EQn3f6Vviyo<=Vkt2TewKT6p#cYyI4w_EU$bbuwFwy&A$h- z0g}(+>c3@3=JwlqR9*}Z99({uFkVy zn(C3FB0!Oxl^Oh_CRsK^TB!N1N%+1MSpTOI%70B8_Wyp`{70hvD<`u5J>Pj&=$II? z`O_gZr6N12O^$?KPF0nRkVsk3N|orr@{GPJk|7?Tajo_fRQTW*!gc{-eG^V25H+&a z?ZnhM7t0yfS#EdN*N>VgZ6L1oF#v2cg#&~;g#$tcw4PYHkSo}g*e^qmnMaWEZ9Th7 zsQ!Dsr6;eD@%~P9$kRPpJ?$sdnS|2PkJ_{g(kim zW+!*inH?T@F|)O<(QG>WWv6WL`kkB&KxvNlv`fA|CGc8(l-X{?&sDl?()SrYVqZ>H zor3wYYNVnJaxB)$&S``eq~In1tM4$9nZ=vFo&dVt{0)?<$Ll7lUiw8@X{n~+i2Z8H zaK8uc?vBuGu_R8BIvc6xx7>Q|F6tT*z13v%4xEDq7w7Z8_dPg1C>aM?bfm587}CXB8^d@nG4hOc2aS=y zQ&ed&lm?;u=W2*e((q}gulI9lcO_kiz$Lf~Neo zBoHxU^~|g2_m@OQ2)}8x_jU>RQ*1x4YF#j*xGA}HA)a^NaIxqnV{dwN0+CigKrE-@ z=XqOqzpwOr1hjHfQI|-E(jSCIqf7WjwgNWdK8F-0$;D+(;{W|f|KD8@|DJ4a{CDJMW+oc0A}VL35JR(( z0tKld?gFW@iNcFc7DdcMmLV@JYLQj>gxi#q8Vs-y5(Oy={LI}}K&-bUWVldK8?EOt zUt}@&bzAKIeCGtK38&Da-BAa(q%|L*k#5O1R0~*h(o}Jf=;iK*n0&X8SS%eJ&LDtg z<3C)Kv`D#X>%y?2j}@P0TbiXcM;0fp>C9`IM_z|T8|W8R*xzR@!6@ z-oJ^aMCHd=!*?mmlceo-LhxW$GJBa0anZSmQ!rkmSncM0^~tcmc#>dxJXfo$)RcNp znZL_D2@~WqFbbmY2f_1^{t>Z^@iNd&6o2d^Y-|p#0-EStiYP0$V=g`Y`==?X(f~M{ zJu(?@KTHNdv#_ts@?~pe7Lz1$Z|Lv%9{D8H7}#aP0aZ#0Woj{jAP~+P&A((2u@|7E zF}_2Q@qd|S{;x#PKUksvZ$uEOqP?Y^i;9bpi>vd$nbiNG61(wja0+dU1auRiZY!jP zdQ$`klp-vdky29>|122d8cgQRv_{u0L--G5a{jF=x58emwj1ce&P8E9b?`Qop8hXj z!cdbH6huMAE2bo_Kcou{eHiSK(jys>H7zzE46K!>h7}20>jluMW-fH+9f!OB36aen zSa;D@T)oniHQzCg8BQtO_^n$lF}W&C98;jHknPF3-d0JI<%fvFK`BS>?(h z+dZSvFu~YX-?YYSVS{hc$k(a0VHyWh*|@5&W?tHb2QU7fw1(H~S)qxoEG2cfnLf~E z)@s(dhnwM-NU+*K5~>;f1ZyABh~hV+x(*XC0_!Gi-&ez@ zQA3mRT0Fza%M|^S+vCIE1~cUifz(I$;H+wrF#GnDm`^=e-^0aKx&~a*JQzO{J&`yz zh;+yi#^un2kCaaR6!#p3SR>4jG;)W1)Z=)b(hpgs^Vw9iZ^H$DZryyKiZDEAM6i!l zst6~9Ck^U@RU!dpXPQEqfN*+pT9?@GG1dj^3Cx`r5?~fj*j3L*?s_WvC%8K9(b?%9 zIUI&mgoG?uocl5Q&oP(Yrtb-^`!gIE~0mR^zsWzZ{=_@FMOwlGxs z!pT2D#62-5wf1*B^Zp;(0{?Hu-hlr}Y?`_m*|`4G(VIcV)mFjm-=IR>$jQ>k4q*B} zf?8e2d0rg#bFr4rKvYshn#o;zbydEWQmSQSC`p$IlZVU>I-CDDWu{3W8J5&k4`atY z#eL-m2rqL-kQC4SiSrkTf6@IPQu7Q}Q!9*VkEg5+zOB}CF7t=s-0pYqZ5iGXLr@eg zS!3$R@fPCH3g{}+xS#Z?<5;-jV!aQrbEVWRL@(8(&MNTp&}OI;%%n7Z=zhsN+Fh3| zXBo3h6L3}OF{WHiC0ZffOnF+iwrU<-Mwz;q(P8cD*KPC+7%5o0EK}6xoVpn7_AZrZ zmrYU0?3GcAc=HwvI8|{z4VX_HLBopPCH(ap4?dUB-gF;)jquWV6gM-*6n{E?;6~yrmM?24>;n?h5nYuc-HdY?HlkQjkEy-u* zM~n-SW(ap(yAITCum1vu7)r+Y5-BP=3)J;;{RtYqf7FL&&Y_%6R&ti%qdzhs;Ae=P zS~yM3-%}dEg?6W@=pZ8o*Q~ZKl%4lC7lHaRKQEu^0ON+uHUC$=vbJmNj`Ej~YHd(T zgniAQU7c^X&qG0Mn(^byKGev=K3@qaytJy!`2YrD>FroRqs)c_wz@YLaX_)_8t(y^ z$8gAt&^FMa|ufR!S0uew(si7ki;o2B;@%xhHUIj*!|hblt=S}}n$1lI_cLc54-okxhJ zUn(nqK4>Z<3edeEJ5;2MRU49)x*4~j2d#)hO7BzVW1H6lUgWYi$u z?;0CRFWjxjhdMQ4e_E0{Zu;~jOL?NmdDOOajq`r@BGX5HWvE8W`{r@@eO#|ZdSs4M zXh?3Cws@qIhV`^GKPt4er_a?T%sU{{Bjlv#=ITV`fCzqvbqdiHCpUhdt5DJooM2u% zVe0G|^eAs;%GXDl0(t*_Z(CQFyBnwB=o!}&S}|${hH{R!U!zbZFT`;U(bz`_GjBg! zZxn`93z}ZBz+Y0YaGH_J;Psy>>FgVGvnXKh1kDN5&M5P zMk>|yz8%dm{p9OTiZc%?;v`jTD5d8NMP5o1QX=948h1pr$0aISzKOVC6An@wRI{v` z0IUy)u~Lrp`ynhx@e@^C@L?YRu)S);-1_!tTcbE}2Cpga&91Avj-wCGm94MW7oeX& zx*Cqcfjv@iYu7O$r1EYm*fNG7n{tM@WN;-8+`m{jD|Y$du%|}*gCe9_yK{R`r^XKg zc=c5sr9=>l)h0@x1qCa$#OoJoK*43~0Q~lU;p&YKu!EVh)9=$@%#z(fqTCO7ApK_#F z=7H8urRYQ5s%6W@S7F3+=XutqWQ&z^!TqxL%Z+uW1ui5(Th6hdOP1wPU>iX}9zHs5 z-=Vl(c65IrqnIYKlTD?~SeN6LZo2AFh81@V9juMw+;jN)-6^WN5p#;~46m;z&_lv! zAI|MA?LdhO>3W!X(D)JA`e>MikT7CA^aJ?jfCp07_tliZJoyFxbU-2mtBfTnFxx}M zK)fnFWsgm_-N#Jc(5|x*>pDoXt5kd+^jynD2_3TqdYzDZ-h1vQ61r49 zZepyCitvW@>5NV>PN1CutG~29oOfRDaAcE8uZ7Ty(|M48LCM^9#Twf-4GQ zB4Vrw4N*4h0cacOMpI+zNgB3LxNld}wBBB}mCM6-Deml;^kj+2d#*K!9GddkIu*^l zRHns|^I|Wj_tgxpSv3b1oIm-}&-X}L92-MS+?*TKpX{Cm5>kOdwPeHD(@q?)^FfXF z%!cX|PA^;Vy4c>ebkX)AI7*Kk=>V0OlkZTA`$oU>kx?jP|>wb{E>SZ>M4`V&Oczs~rv**UZ*6rB7Qi|m| z2!L^&!=)cu5Fsi13J|C02&eYw`|AZ@4?bCQPFHWsHgc&<*mi$?q24AD({QTTPWir{ zM@h=xu+6rW>5OcMyrZ79f!UFeUmp4eyWxbdi xwX}1zf${}}E^kZR8=4F=SPA8Q zi2o9%#nb5{Kk?9%&J1p#aVcu|Sqs3%i=x=GJm|$MoReneXNgl!yaBpfuWZruxIgME z*vb#AHJRX8mJeK>`0=Y5(&sX#9j#!L;Az&GsglC zO-;Xgh~0q^DD|M?4yX$}_D!zKH&^);n9gVPL&xWw!Z9Y=A-(j?@rR?=xd{ngfb|D(eW=l?~y@y`wOe-;`4 zDld`~#_i?>QA55Q>E#30iZz6xQd7{KsMtD5ppz9vl$3r(B+;%euxds}0x*Wbd$Gge z6nda*g@pBff&vq%{#w4F=ly}RJ+T}_c>#=`Gk(MM^);FP@_4t0|5Iv$B9D0O7o-#Q ztrRLFeMr4=nqpoBXNhqF(E_7xq7GWWZCZ@4chN{s6_X1+ms|f{lg3Vp{lH;YaqgDy z>nVhY%`lT~tkBBuiD$8S_D-<~GmeN>Xc3puRsf?*s_a_J&JqWld$hea>Iof}n$ym{ z*c&6}gOypJQSp9@4)@m1LPnlOwpaF_2ks}Ud9RJRij=MEu-VPI$QT9J3SdJauPR6d zv$|ki^c7eWnYDNRB|3R!4vyyN^5!@l3cTS8tSZ6vr_6h+ z4kZ|Pw9&($Uq?xNLj5zjlZ{EBO4L#*cw3d&(s?; zxWiE)NE23=gSegz&R^}f$~CZ61qP>SG5RSAeLko`C+o=qFHwBr!R7@2vH(5r*>q%gV&Z((aksuZbw#Dj_v!Y-R0 zN+o@}h56c6=L%d<803!ok6+AkqImN-x%b(Q0e|(3h)2wH!Jkt&jfK-FE7u35kdcj_^i}~@zGiE{POqG(`ie= z9d;^Q4k3jTy#Yyt0AC~8UanO#<{^itBKk!*9#N^8qALaO86~kO2y5$>qOC3^-gm2217S_tLHOhCWZilCW6Hg2_{$sD z|7^qD;F~3#n!Qd#3F>yr$BX5mKe@Q_JE$DqoV^Z0fd@QPXKO|>Sb5Bamt2!kWIa1E zG5Cvxl$c_s?qFe&v+B}MOJTu}U;haqkynK*IlAtEVb~VKh}o@Revc06UbtqXDE}7C zyLYAN`qk~coB5mq;~$%v{mlL;)bF098Fj^d!`DH~LN@;tJddDT+E;BK&}YrJuNyYw~Qq@~J|hKRg|DX<*{90<;&qf1S%?=QHo&s%upRvu4oZ z0Nb4u{Y9<%bvS_Y><;&px1#~7@U|MWNYln{Yp}M4alSeu^4m>VN{2W{I&}ABGH+Qk zXes0cWB(z3=F*Tm0k)_>R*-U&sma}*6<_K`H!`X?zg9GBTQX!9Bpj))u1eIYhKLm# z8bJ)ZFFYP;^DiT^G(x2Xqa-$axr8|>Juk{Ay6}mlNufZ3ES#7`yU2-&3rBC8E6w;m zrkv=WC4XsywYh~xsSzz+G@FZ*X%oo>W};)B zCA(+(u3lq}pj*NiOeUX-9*w{U1+S$RNTizQu3TmBs`55bDUq~8r-yo*s zXB2cLcJ+LJbMe6Wu!n$Rqk)@5M9BT{^^~wd;s{?EAO>!T+jm_h51chtw2kp%I{5)` z=HE^<3u^@=@gCCQ`nZ!nvIe&!2s;XR+#IU5F-cU>_iaZicLbnn`-E{&{kX(;)!RCOO}@`qq0U`?`^?8M7!b4Pd1dWBPpSJn%J$l!KLuC2h8|e zrshJE6CH2+BVD(8PufR0#INu6X{`EebxA>{woc`SbE@&OaE&BAV%hNTv!Rs=@hk^& z#9&>ca(}h!JH{rezWoWLadr&7%c&+qywL!a^8^zoQ>KTM2TssL3iI7Gvrb7xqfA&EMDell8pP(JU1bempgebYsGpl z2NOW1dW#Zb$~>`9mes+H-`CI0Po&wZ6EeLA^rD?N%bV@9zhv2!r6r}ttv0V4JvDb? zBkHOx2;;g={YpD`0y1z=aNx_T6?CV-kpP*Rg)ga{7zoH3nAgfe%m6mu>`$h49~9Pl ztBZA)GTp2RY`+$4PanO5yoFBDW(z1bJseZ(>wfIy#v+N<>-C7&5#q$!!5ner@cB?Y zxwywBe)@abZ%ULgeO8r1cahC z*D#69D8I-1O^nRKQ8wZ&UXpPW2PRnUZPrfG0%4f5X}{w$>00fRez#vP7+d~stU$YP z<3u*!aTsM3X@Q7Jh;wzB`C?4m)3VGS;cQAz$5Aq@FI7Y z!VS@Fj#}-ibfc|buy%8!HL^~R{qBy>h`zW$I(!1Z949LC9FxYkCr|3KOn>l? zTKPwq=Zdp^B1bwByZNGPSpE{XB!D=9E0_q^wT7K7eW;db+iM|`oggL>(?SX<=;aWHQ53^mE# zeZhE$aw#NgmK;=2YSpBJgI72Cd-gp;YMz)yOl3oNAiT%m9(KwL+?)dq!e_8+*QnO# zz^NLL{@W87CZxX?1fJVvw*n$;IPe#4P{s;Xj}GrAINCFwkB>w~>{bDoJ%DX1v1tzh zHcR04U?0yX>58FwPp^wGtEWWMn`wewUYtqQ2qV;yNrhq1b$K!Zq88k{CRML9WB!vL z-Us6Dd=J%=59b1Rlf-}wYuyNYVOW);w2&#cdn0Y~Z^ATO7YCC;;ILmZ@8yW_KKDD9 zO8Bh7kuxbDes%Uh-)g_6XiJN<@<3o3g;t#vGC`b%A7=P1B)WZBb`Mt~r^Z}fhrA&a z#UOU$1zD07r-s=PpW0Kt*%C+XD(`?zHAm_rYylzSQ05 z(Oh7z2-MZXYG(|Ddepq9J(CpAB9ke7su9BnJ;f@C}sus^xYA+F-TcRceVH*NjSM zN1}B$lFEJI%w=Y*G>?&6PL%&D(WuX07u)n>?{-Bm8bi1ma=01`=!L{8AwJ#Q32Da; zm%=D0a^w`^%g%xOgnHdT>&0kTlK4scK7-jR<9~scgn@9v`1f|*I)qj4!{;T|Z~KY& zmT;kN=w|Y$dbD$HH&4n%TRLC_ zc;~NvlrG{l%OC60TrE)!#1Yu1FPxTzW0SSdYRgq%^H?uT7-K@=0RMnU-z5H;V^pdO zCcCQ{q^_)>h9fYLw1I7&pkdir*Ncf<)WQZs*Jpu(LF=OF)uMpW50%ofHQAD4<#2p- zCFp=ybJAKPi&LCANlJ&}?kt|FK59ySmR^Ur3a-GVlUpTHePf;4BMW!Zr5(A2CCAh? z`gAg0FM%?uEg5x%mX0v2Zd?=$>w5(t${EnoCRc)j4uyT}8VFmPYUv zk8Lw|2p7EAFgWN*-am(5g+{OyVbhBac7a2mchePI+9ih0i|uQP0I!K9Zi#ktFvT3u zV-51QpvcKL@(D)vND=4C_6bvwN&reRbGYc6w&3uS^S)-k802Zlrgh;$LM;4lMn z$C*NF&kNe{2Wrl4$8tcjLj@zG2aiZzn~~4y%*xgq_!!rt4!_@F3dvF}(rEQ%>!Rtm9jIIg2jI$Q=%%jMpM0- z?txWcrugM}gqoJOl2Imk2NyfCmet>qRCDt)INM2<4ri;S!2UvI_RDyR%v`Ejj-y`2 z&M3?`2xW?nGuO@(o}(bpZdyO^aNDM+>UTF^0b&JrXXMEQ^p_{EA@mnYOu=`jt}Sp; zJaZ|fq~}yNcsytTIT^xsyz|ktaR{I&cyZ13tXxN43cc|JzwF_|Uj3j+`hFtM{-~#0 z0?%A}DGsyIk99^!zt@Q0reIm8-3X7JOTrNh-Boa|B46j6=osi(a6Gw~tMBv68m^X} zZ>;iVsdMvB4#JL+%CwFg#R880=y8jnYPq&u<$;0vyi@}f#0Te51T$9-zL^GZfb)x% zM6B7Q{SK&WAhSUIG_>aT3^YmwKTV3#9DXm+gU|iHcGYlH<{*9`{P?j>^q)EY|2kYG z`rj|N|2HES|01C}wP1Wy7t+7{@7h=rM-yR9NS}L3Js}VwQ1Fq7YJiZL!doy=Lr3Fa zNm&@ve?PBNTdi2R>un^9iHSAWu4i=7zG@pZTAeLgElCjYpEj+0aXn4R zK|%>Xx9)R1<#XSNL`uzuK|$WPm= zVs+m@5P2OHTaa5ZUVnO<)%IROFufN{+Yy!u+i^bZzk?=lds9yAC8wwFuFuQKX|W9_ zK)!QB`wnbxwv*~1qqoU^9YZkqoSgC5h!A;Gm5cnPGy5T~x2cl4h3&Bwig3*X^0g-c z#ji?AV48V#v- zN62CZnPP5hVjSYxDor`omHGaIZwt(}vuEtP~;o#R}2ekpaes-qTdDlz8ryhsYuC@s=BfC_x&sUOCulV^D)O|$(M(iC(!H6^;>l01Il*wpX!^BGSW4jaAfcZ17H+eopb zoB{WyUOnN;23{mJig_wrrv4CP{77n8c0FOrj0p>ZDw9l8Ic**1&CgLvisUGF&3#hW z0hzGS{s!j$JUz@XIF`g2j}Sr`Dr+p$eT0Y1^iBm}oDA4M*ge#yu}20pkt-^JuzJXX=WfO_dCSq0N95Yq6HG%Z(0(B>vLO_r%_Jp9-ttu-W6a?(ClH9e?)40RGf;yk*`7b(x4~pt=8bnH(uG{Rzh+H zfJ&~UMKqvZTwBVvi@qsZZ@f{x(vNxs@J3vw8EPyz89>5kO7>TEH=SHJ zN&1mCvQQIX**T7Ue1WXTPJSK*qp^-7E61kONY|SGDP_% zqFO4eu^eAe7`pPfGP)ymY<@`DxoH!fDX~;$tjkVK^N%^`4qUlA)#@6`1Znrd^V=J< zS3H(z^i_q{bkQ2R=}j6o(3ky1T)^zZx3^-(5M}m_Y78)8ICbX)G{?j3-6;Cf=L0E- zy>yF!6e2sQGwjhoA%@0RGIZqLT2A)kJv-BXsMiVM@b7(UkHUD;#ojD}Bs(fA^ zLZF7y_&KpU5Y3R{9~lb=sI&;%stuS4C~>-@ETjU2V20{bSSp&d^Ywqzu4hKvh*nln zzJ;*bu|&v03l#&THwS)n1-k<2M$nyug#;MnN{g{qbdJYK0Z}Ey5ru-8)S*I{MBsj+ z!Q=1@gE$4@V#O7p=9Y0X5K53>_sF$y{k*Ce=WEeoJo^!)6DMmEfkcEAWaO3%x{t|~ zqF4ZTVuqpPJeJ`qYixSz2t<`!_cKXG?8o2RwP8_$9{9=rEH{1wrI!>G?GY=ufD67yzuci0)A)V~w zEOT_tSk6m;XQh~xx0KL;`=56Q+u*%UvTB#+QT znP)J!^FlMNorSGVXMR^vZI`DINPU6J`<74)PNH&Z-P|!NyqDV77FuMLy?kBe@ugX= zRqscQ@GLBh#2TpT5vD+_M}~mt{76cjO7O%o>d9qfS+oPBcB z{ScN+!2IelT}PES`z3*~w!!8;(XO|v{%-}%+}cFq&qrPzZw+Aq)RdG9YcBUeS&(9W zKvK-N7wB#$Hw&nFazhS^f<$`;F^=@{C-VFUS<0JC!<&p(n@osP<^HzQq+~JoZa8Ft z%Px>fc3I)8)i9zft#t7-a5SZrh4yBX(?fu1Nn;aR!yh{v{Z1EG6%k+O3PS;&TaB6` zf|N@N9f^`f9Iv^S?{;%&yRxjb91a6;}nqQ<4(HmF+8}T)VLe>1+@$uF+7% z(s{G@sr+`;1gYIa2LSQm>VeF+XnJ}1m)&p+>S9EdlLp2_Y`Rz0D*l~euY^qF(=$gN z3`bP#8pxk8VCCk!rGkxeuTxV}TPwUbIS7}K7JCn@{MpbHxTpT4V-!5#gaZ3B;bj}_ z*+5UThM8ytEuYoWlzSzbZS5D$wGF>4u;92_k#-qzMd$#zjz)clV{Q?J$+7IRfthLo zGhYj+r|Y#U3^>Lv7Jg(zBTj+lkv!PxZ0WH2@p(J?L{ic5><2m~QuS7*G2$!W6vE0a z+x_+p3$U%+>7rlFL2nq+qRtvZ?qv0wLI(fiNeQtkM4sf6T{6~LVvDLTv*x?9n$+_n zsOvJPIhal4X#gg#T~pqU>NJye!z-wRi86W01~I|tUsYN*-Qo+_(1RGMLeVRz8OIv6 zTLP+!1mK;FOgZA1*K?v(dHiTaYmcW;)L(~M)cllo-UUJ}<=WJAM8T)3#uPM4Y`y>8 z-P%zXK!wb!=XnP10Ymla5o@L}dgXeNFU_Di1jzC@;5OEqcwgKswc^}fz?wGc1 z;8=hyhyMP(8`l+Qk5PO+v}3gsgna4 z$LA-4*fo1pYODqO=eFf`^*ft_lt%iZ4ALWh~lZbO#N-NJ+JzL!EqBnhKrss~_cHZonw4vyBwwRQTsRy|2Oj5ApG z?JGs$b-*g}3+}1SBu%}hd@-)Tkp`FRBGX`bnsH9tuyk#(RiVnCwkgVLNGy<2DDS|{ z^55;R#!mFn#R=WpUsF7&+i*m6QCAb4rd*s%Q`p zi%p8f^D^;T9Cfdn$$3z$wm&U3@v)I^=}D=z zr#K34cwkrSqZQF+lkL(PwwG{=k7d=GFKFzd(<=1Pux!Hl7O8q$Tr%V8BOP-LxeM?l z-L*rXAW?Euf)BryOj7y&xo$kr-gh{-3Ha#Tj_e&6Htm_oX78RVx-1op5aW1R*7#pH z_nx0Q`k6AWHStZ?@!7XrtW-7aup55s!V*lB&^x!LDHO9ElOH{IFX*pb92VFgq z?jbYP_g0rt>cY;S4B55){(E4M?u=Apas1nLZFG(#^sZIZt4Q{hl=f)Em`fpJAJ{TA zvPh(>x0!zDSh-cVX=K4E-DYndKE^KI+U25S6nA~%wG~<8rY)i6)%LIrfdkojff8oA zzUePzEShH;TU(lUP(Eec_)5(uh(z#TcmB`#ikE>jdOdf~hQGlTt*0bbT?6=s)VJOl zxYaw}D;_ESOHT9>YQLi0o3%VJ;%v`dP&eh`DpsyonSjNd$l7yk|BMyvD;p~?RMbjO z^}1Dg9e=sD=r6rNdp&}$ZZEKn!;j8c(zr64Hm=pt*O``eP3(IUy=1Jb+9Krb%C)Sl zuN~l>3KsSi1asCZo$8{I)3&L7T57HriZ4#d)J&XrtT~2wQC9B7Xb#`zOir%qs^W0W z&Jqgpjxr$TZ7-`qE8$e2HS>&2?mL!D0w6p~vu6hzC%T^bKD+GAdyK27*0+wc zXeQO4^@vi@x}DhOZZfO0rZFw1L-~XhZfprjr{P*N-ym|US2>K;s15fEK@L|9ddy~e z<4U&UO0XKt8P#$`8ao6dFrda5n1T&@bv^MOZoyN=b!a1-T@AI5udU`bi^k2UBaYM7 zEFFH#H})^w7#3VyN2m1T>Aw8pS8Tz=KX51tKDo{VAJ}&*fnOD0n~WIV;I`mfox~c$ z%fdQ2B)D~ty)Y{#5rMR+hn_@o(}=PWTD?FoOv}vA8yl~%Q#ox3ehKtbleyoO5B}=< zEdcUW9@W>VCH8HE(!$0T62+}CL*QnAgYuGlO3-0C5dhux6g@=T77W@Tr90}mfB4-PannReKl z&17*`6t2VXZ;grSi3ie7^Uu@50Y3K^><7v8b3BG zlfh{n{jy!CA3X4_QkW>9=_M)`DzSBGr7>hQi9A@{ji;kj{yT6h8*;PM@XUL`0bKLeM3uO=_M!u*? z__{H-+HOD?Ohm7{94S2KaCxB$EIj#}(^uGA!-H1?jodlaTldVpW-Z z3*igx|A|KXznI_p_o#}|f7pb`Me+T^!#U`P2w2+_*49TT_IK^Vz}#uA=MF{tpI?Lh zS{^?TOoNs=2ThpM?Kg9eU<6~tB3Q-5N2K8}44Qu-R&z9y7u!L0!ttmZVFi?i^}(#GGaAW0IE!u$Mi@A~;A_;+GC zej$GLGu7;Fw&+>jSOjwdh0AFnyJK5VI_|A)12jP86*y6ui_ z+eyc^ZQHipv28mYcWm3XZ9D0XJGuXZnYnY;eb1dW>s>4Pl5f8!`>EPh&#u}^F}%JX zDf}fthdBj2dgi_)75t{Y-U$2a+jO!J97>jYZ9#!u`?4?&q!Xpg(!))yy*0snn{3wO z^p!pPj78+4bgqLd31S=D3YyP4edVG^0Y_nRryQvX@>f(e(?Fion+9pb$}cgaiXhO2 zfZ43K(mROi4^OOfCtMef%rUBEbPKzxqlIBe4zB)Ph176p|?UKn@G1LBbx36wsVhURSXzC=RWT(U2G~b+m2~3XZP;;<0iK8s8(GuOL>n9o@f4xL)3pjH*6=`m_tsj{gf6f7Ojk{O3Jo85e73i@$9wSE_E?tt+Fv zXE8e@nm9LTNdRnofl~_CJF04aqU&T9Zq5~7stXzHkIKkc9;_%_C;9b9V}u#$U>qMQ zB*+_sUV}3H>5ic)Wzb#@=CMHU4f2uP8QP&jUj;@4(~5D4bYM)h-?gDlHMK^*;S5!z zvh+|#=8M*1naP@@ii<0Ga#`L}M4N_!>N4|U1HL>#jyAGEihZWXpmMgTPGZdh>4tVG zGZ!8Gq-dk^vPypn0qRrLWvQr;3$@~u+gX3}ERE7FE;Wn7N&XCQ8rkMamhIUTcWY7G zq#0o+X&#-~C4DBa$mYTl_M%Otu3|H+Bv_=X21}E2amaO7&GhQxrP6^-SI!kx(Zgal}W8=QeX+Jaqz@ zsRU}Y>~J6LDJOyX7VDmXs9;D9iawiEjmEDt)8`G2l2s*JD@xqVFCP75y zk@}NCrgjHGruGGa`rW_ypSKY1cY-wC_yFPW#0P1^ueAncmdK<8wGU^QPv$EuJ?ZL) zD=Qn->RKqbjthuLw9J1NoML=z@DMTbfzz0BTW)wlpO{KA^N;9I8g{+rQTmvdbM*o) znoM9}^1kC6s!hqSHEX{%Kq7KoMPh&{T3eUTusN=O^mLigx}h?J!(G+5Qt>xY_n><~PHN5~D+k6#D* zF>TAs2*VQj-N9-tZ5J9lNV+c7%`($B-XY&Vd%!+x8u>5D_w2Kz4x;7`HfO!ElQZRf zh?{!h&rY219!&i7{?Xh5L)>>u`%>#yuTG+wGJB}4iwRG>lMLfd>aA-?T8HS0>ES>E z93qjMSCZ`PMA_0MyNc~Tf7~|0mWMq07IiZ3r@nw%)gp|P6CihR=aj&}h6?mRY4W9z zqp5$4uc?>!0z%agY$#TLb$jZrU#X@;6jKZB67)jv4QoFud1;Ec38@RWbqDDk519ye zqmzkAVb_tw!*8I0Iz@uR+pm6`kQGTsYK%%xq!9o8d0#V9DFhTO?T1OcUbYW*5}$z& zuSu_W2-g!1Qxe^dRO+Mm$eRx&l&#_iWwSLo?@`$hVHjW$2rub=mZd| zk^$EJ{wvb`_4SPTKaX_(p81qEZIJ{}-oeyWDVoH!EN`3NUGm0K${2tME$GRx@@4p= zbUAv!iZxtE>(Umuw#AWU3dnf<*j_$uJ%RE1-%eZ!7P$-2xlT`KJx@Jm1Jv5b_iCR& zF9z}qm4ea4ATk+*<8}Dqv?y)MT8fCK<8ZKIc1-8(L;9L>cszP~@R+iy)|O@tQ`QfT zM&x}^wugM*U*0nbIctIs;Vg`7a=VXSMo^1&k%gKE5XvK~1~=o4=qvEFXxXrepcaM4 z`;csd2`fx8VdBd+^UjJgYNE&se8%muI!qMFRO;7-Bat~G0*wbQAuT&~>a(k+z&kdX zel%@fBdc{zZ*JLi+MU@rF*{2nEiRUKN!iTL+k*!(9Bgvb4spuf%9_c=1nlOpl80Pq zC!8hw$J!s0d}0>d6GUDd5pPgmwtozmm#|n}z1PT;h*`XGEKui$43B^}cO2uhxx}_< zJ}?Uc?Ay&G-2$=Rckw)Ehz=Eu;X(8}FmV9-Ld`^t@38KI<3j*RRue{w>H)M)K@U)2 zh&TUW=Lt#vxHVGG%7Kwdl})>5ShLY8ITJ=> z%&A>&mqc9Mc-Ya14RGNmUIED6XGD(;Eh>a{TzHPlWw4RCcE8A=X5Pk>^a`B}igxKO zuqqH8w=W4%D62m=3w0Kxwm!sy7>NZTv7TzwPVYOdTCP^H|Cnq3yhQQwo4MUA0JZ-@ z>|b;9|Btg7TR1uYHswht;$mcNVGP*9BK+rH{=wO#c=e19Ml+oME+mEv999$o>eEV9#kmAA{P=Rp>AK`9~_q zlcGgBeD`}i z8&EZOYXC5}GXO&V7tkSOZesY=$=t;CujrVR{T&@2qNyVCD5%Q(+|>FP7*Pxg;uCOW zX*wLAJXe+E<{4#<%$Vkd22zQ#=<(b?8-M;v+d*4`RN8n zF5|mFS2(!)$!>foD12nlskWJ@sCV`unao48H&7?JwCfy6Gh?kcCTg3{?XUYKc+}va zA?!qqc8TvzYA->WqjU~I8s@^a3lBQ!0YOM``Xy9YD)Q4bp4?kRn?M_F8NfL!>k#Q_c zAnD%2t)yq?8R-~J*IJN@hxZvMmcm~faz>wJgS*Me8>$D;mxS|&uhyv($=@)M_i39F zW7P$dQ-kEq(uIKW)~z~tP_@knA7v}ZIfzz})?dyzPAa5ZdjSABW*BU9N%ynZFdnD! z$DDH1&$U@Jspk0=Fm{T6a){LFp3Wf1b-ewB*j^oJjE*#|p& z3jiUP|2qhgF|ai^a0bMZzapg77Jv}%#^sf9ENpC;6&zMFbznnde*~n^AZ`MGSBFnq z#symr`1JgphmaPoE5hL5K(l4$z;_2hMM4KaU_0eJ?0K?<_m3y5{Tl0<8%i zw_&bX8{)`%wD0W~fwu|>7CaUm1kOe$lXAlc2l`5swmvo2SGEABtbKNL?$&Vaw+Dowr`J z3Wf#WL_$#GoAByMNbbOUjzh4}<)aGL7b(6p;VTI4;#esu+G;MCklx~RHAqXL<0z2J zP&y%=rmUiynyLHxiV2}#BP}oEz6!d0@^s4J!!x(`rGc>2khZ_{+`Od3j)o~WAKgU3 zIU52pKL%KePOMatIMT0hA?N3BAtas8cq{Fowt{D`M?p7)r4mXE53oox`wnX^;3&%P$^6^?9D^j+>eou3{xJmy8!0s4RhL@()>WPz8wnc zhiky$%q;0VEL!C%yxxF&6bM%1no7@1afK@_dP9%@uw<9nX7LPhY}!+Q2K|i}>0fv$ zcK}dw{xJ697&r@!Jv24Me-!c%>DQ)BU2p}{B8+`{6NpM=tf zG(<3{p-q0Z#sgP(t@pVnolW@h9f^$=HavVl*vC(+`5ol(YJmxLCK$tr>~Zt;YQyuY z^?ECId+Qn~ZO|GIjrNeifBdVqfQF%BK9K?{M!3rXrJagcEjE~3N+yt@$hQ^*uv!Iw z4Hez|%4WS^LnW7VT0p?fn>{RUpmoV-W&E~;+RH%wG;A~QNZkbm!)5!kOlwfMeUt(B zUB?sYIoQw}*1-zPs+nV_7VD7SxsBF(>02u6j~6a%G#BQc3L?eJaLwYCt;g-81nD*D z82O`PnogA(r27Ws;Y7G;zvv(09(EN|zDN?(r*Lutfyxbb52DJLCq16$=y_e8$n=+l zkruoAqL9TGq;4enoWe(8VOvU}%JVDatMcQ{BSiyQPe5!uZL@Nupe#Ko&ott@vNjlj z9KA!@;OAGWWC;tmIhki{*(FPK!OcB4Z>D`@ZS_(?D8o(4MV+tOWB}x{ojclM82j8h zUMUpSMS)ePxD#QSitk)gNW%$+4za9@Zkq!qfts9(U7UD39_`8y3aV23tR=>i{ z8Yw|rTAkqzxbhjN9rJI0#Utj1<^#4zDOdm+w$D*yp8(iQV>=N1L6r$??U}7JSqOL7*h)EfI=m7(v zm8X4Zjrss2KyV1);+||B0El1zt(Eatg3tM%0{I{41?;VJa&i3A0N6#IK^B++0Vk9= zgkK&C?=x&UMT0ZAj&MBV;!uTS%+&GxYG^)pbO87bMG`Dfg!mWLoZG93ieEo}-9qX| zU`NIeCJ#3HyD&6(qlvhUJ8EpDf)yNBCbGV+kVMwriCl1z({(M?uFsWBL?^b|pK*O% zx#7a*9}p zm@5l5vfX5fUnmiA#A`9F@&S*Dg#ptr^#femKz>JiRbC^nWU)=2yXO$^w}aEWcfg+o z919sB3jEJZg6ls$I3WXDLlZ|wgMS?0zi6fspg;% zP$~jTiM=6Bm-w*fz2l9s*)sc~zc(}h>tLcSA$b5J88HN#7H}f!)z++KKnW| z9grxlKBe_a!-0u9w)oBB4AI*f_6e^Fi+rO~%p=}ZK^2wV;nOXH4h!MG_SzAv{jsld zN;c-s_jtB{zOaPsKLI=JwwDQ1>S&@uz=K~w;hS6XB1duk3C*~f5 zeB`n=Bgc%f+#WK@_uqH(!%MlTrJ=Q->0mqTqb*wJ?6e-Wu*YIRX+Mw`cn9hd6p)ZC zu4Y&p=@Mje?tYHbav@G%O!@ox-{t)RxI!;6_G=ZsC(tboW4)gC)eE=D95(My^#b3( zM}6R$DTvk%?IDk#)y|plVu!>Zeo6a(EMp`!T9D@pFZ5_~!Se;HQCvM@E1kaPe2`@PGTa*m{o@l}1#8i}N*R!i@*TZAedR-{+d+CPjuXD7(t(rf;V5iM5Dfq>)V}n>9fzrOLAkzdJuh`@?;P>;^N$MV51`R#cG((V}{Yc zaZ5%TRh@`NM6vh)59ITHRKm>Ew7P#p7{atR;#x7)PcTkBK$SQmhuLD{ktM1nc9Q+z z-{9CmmR-OvrC1Uz>otmpbJ-S|9Hv?DZb`dW=!=N`nq_33okk=?dX6}x4ck}J35-|- zQ(ixjLC9_329`Pp*O=#ap6=_ubXbQafbM4DiTiR+q+XODlbF)RuNWXU%cxO)V1`)z z^_5Be9vTY&9w(PsCEj))#e%PyCu>Nl8kG@>O2`dBON28;c*ne3L<2=Z8Avi@woE4|TAT6WSo`vedar~eI1f6XYu{}Gtv4IB+@Oq?Ap zj8tqbTz}iVDoU0yJSGUvz=ib2Jy z4|hIuC#89O+P>S_zrFqK<){bk9-|)Pix9i~yi|yJGU_U)k+`Ik8fl|Zm~X`mJx}@; zRC@W4T&h^zf}~k8yA?~E%7O8g)o#*kW(Jty3bvMGTl{wt^kSRnD|e}?HHW!{4X(vo zU$l_HlU>-;1bo^?6k0?5H2nz@cm0S@H@HN11HQN%3BQ-1)7U5XRe-PG1^oWciQ~Vy zY^;AANu~1dix7B_*Buf$nNfg(9*K(_pj;BaL6nAp%1~*7s`C>Qsv?`MNgqbVUkcZl zf%^7_kP`SK5V%AtBVhCTe|)Nv;rCN-kk@cKnws#=Vsff(?&??tkq=H3z$&SycQC~< zqDW606CBn+o+le4vj(GAAD0Z*@7*_`5Ck(C>72vr-^)(Hui$#4b@S|V_~o;$mN$Q_ zP<>@T*!h|VlU=N>h3qdMe}F4jLCJC8e-N*ZMZuQPm0>2Xmmn#cidmK7Mw-8AI)naJ zrJrUlL0Sd>f{VBjQHe>W)ivJfdLei|Ta5RU1hL$X_%)WgJpM`5?4wNs!691=2Tngk*!zlh2>?l+Txi z7w+51DA7#qr~25bp*gaeYw$t$+KkGIEHC)R@%u@YwU?H6ddjscb(SXDgDRCjR@ud8v00Q11j#R$9*=&KI0aaZNXynfJ?}TcdmLV}bgCcAqx&SQIMNlC z#4xq45F&!{{U~2i!!i32ad3Cb$gK$O(OztbOu1hJS4#B4Ohg4(aHJ|?_CY2&i+Dr| z1xiYTNKPn!8V|AkMsT1(1Du5bNrCcj7pigmNB8(2clM8@!1PaBA7vdtb%Vf@>Z-9; z)$~o}O>h>S^6e${>Kb%U;j;J zZ$oAfLk48S*mi1SipR;7tX{9%cNJ7#@XKf9)I^NFWDv!XB74;RFC_GNvq9k!$X}5` zLwajS12>|=iGVRGSc-zWFYX8sKKENM-e=*lUrm{T#BPNwEcqb5RcH01Bg=ZWan>$?# zK71I<+dcHYPll~XqbzM3m*yF7k_N&45_K$fX2xsVME95pu^lnjVJeuXPtoQciEbRD zG*rVsfl4zTMON<4(2DIR1(Akn3LQ54n5~hS&}4U+e?CB1VluWRT{;3D)RtI-kr^j` zWt!`ZR$XaO_$V?a!Rh3B$fNTz1lLLNv?SBveB1X;DNY%_^B8NpZ3Pp09{udDYFt3* zmDgu}=WC+#;)|x8KZuzxBJO9x=;7QT2W)I%Ou;E_9^-{8fmXunkIHAXW0b@scua8k zX`Nl51a+50mI%62llcd)5Ior8C(6^YgM5Vx|DOo!(aY!)70+<@!9FBbTPp%t1`8|x zi2d_p)h%$aLpA0dERS2)-c(*IYV@Kn{>KNM-ze!y&!|@1qe=T7Z^#r`#q2^HkPFz6 zP1IhnSU4k{3LX6%r;#HROfk_RFoTBkDbY*C__KVd_Sr?vgA7Yg9^?l^r{RCYY5wjE zs{jC}VSn53{cmu}`cIrH$^2$N<-NY*kdVQOqS$2t{bdq-0hR_42_HN`*%Ec<(`E4d z&?<=*hm|oG;>I(!c8k5RxX5>$7vL5mfx+0%rj>sD%K0=+rf#m>KKBpNNBhn2?Vl*^ z=fn+JfuWr&jO{IOQW=I>jOs7E zHR-2WOOoQjywD(WAJN1TDamXfZjr$k^2P>)bOHBA_oI)ig;jAJZ1MM_oDFgUCmLHB zPmlcI&>!Kx1NWy=HJR9jj~k@nJrHip)1HPeI@>~5n6_J|$TudAHew}{Z*o9grlwvS zG01S{0a6O7pgnZgcF7K{q}dgPq51$@lXv|7Gh#qaJY+2IJQ2(W5kZk8w6J$l@b;7C zhfcw%kSFu#da)?mPUc{K4+rrF>KBd{k`3mVVJ)DMaAMYAiMK6^4c{eJ)I#*dbHwXVWG-mE@ zIFSR;X#Q_#{44w6|Bs^Pzc`PK0e}O!|09b2k>*{ZxZwKeQ9vGpz5F7eXM_TSPres8 zhXE-Rd8n)Ijnu~P3){0m!S&=JjDAitWLY!h-CoA-!Ha~^2;m^aT=@|ZXM1O(aTIho z_*1t`F!NSNuM%&?3hr#6_grjN3$vlVJp`N#C%YPCTVqL5e7R}LHUCf^A4H3FTGnk( z&%Y)EtFNYV;CYDxQxS-;4`eV1b8j>*3Y+lP@6s8k%;rxSfUoQT{QisO{Pi6Ewy*Hd zl0w<>|IPhOBLA-wh@s*S4BmlI)r4y4>90c)i;2eJLQ*T(`Gf-%zaU+URmq%teGa=5 zrV?D%mmnWyok*6%_2p0(X-O?NV6L%tzP%Ha$&nt%B|9r(s9k877~T~zxjTeX%1fpJ1!R-GUhcCZ0+>~{ogRzV&n0KU5B zZ@>I+7wi7>%Y`jWO-&pDq9KdlbW;Dq!@naTJ8oJMSO8|IyTL{69G@H2>yrQ-Tt0Yj zqM`>S1Zro=d_#5}my)R|x)%#PuOB?AsT_|x1%^1p!K*jq^ZWA~kbPu5(lDv4WEN5g zba>U_g(e}lwvL>THs)5HPGoIfRiIq)QAZckMeB<=Z8}>uzjKz!oO`CuP3+k{R))FB z9_7zgoc2S-{HF_d-BG+CDQ>A*f^u7-6WQ#DqVsU{sISSZ z3~dizKU!aH3A3&z^p3D=)9pWU*-$_PnprY5?c$rvxw{y3kUFAyCbZ(%^}rU(4S>WL*vlLrQaCtQQ^G^gw;qikE*ZE+c2 z5AL(HVLmc$i!DJYHt2zZ>U@oVCdO!9f)Gn67U6o`<{g^B(`4~= zuXj~qkd>0HO*p@Md;{^R=TZi_mTOPM_m8br`$54Ajxqg^83#EJ#tc&K z(kzLfGfsirdp6L#7HXbb0$ba#o!UA=XS&yz%PK1Hijqi=g*d{`AWpOQ!t}>$1{Cfl zFZfR}`&A-yu;XrKF-RCx&B-2(vIL_>@nQo)r=NFC4*A|YXo22;iZ=~dq72BQfEyOC zk?{q++T0sgyg2NHfu@tZ#lA&duh3*pn`}90^CfLPM1*0zo5B^44cU(ilfxi`MrF46 z;jzFT=$CeW?mH-j50qE@OtbvZR2hoR)wj#!zVOZ^RwFwqI>Kheme78Mw>yc6+PAt; zt*U^^x}CBf0BI}ELEFLoU0JbY+FNp8!Edx&hk8>q1i$Bdv=7K4FY$d&Bh1w8MlWlR z8_HK!KO3}R`2kBol=8&rVlK@Tt zZD-?R+6CYVqg!QfnU! zOC(0HWC$ihSjKu-AxOEY4#C@;zAmtv5}aQoaN|CHe^>~X->>%pgI-cWdI2uTH{eeN15Bq862E39LnrFm%}l4b?{k<^^}4%1K;#E4!M_N$|+wlk+Ai&5wu@Xhw|2#-5m0x^}$%Z$`j5l6HDmlcLvM{k|G11kh1Rj4u~Rb zlrlHghdMSA$+8w5Dw}1D6}Z5>Xy;rmT`9-Gn{Vn70=ZGOy+V3d(uH)d6WA{?D+&AT z#X%Jh&tXa}@X7lg{>qyn5T3g0!n1;qCeR$}XlM!y0B){;Q=o4a+bF*ng$>heia#E= zjAfHrUiGVCv4qsf-HYDLqlo;Tsq+lxAu1nZEDs(3!>7xW6^y$|b&WDSpBJS1h&*lA zHOuSGO;b{4qY!$mkc$E~W%@i?;!!nVO9Ur>iL`FXUJ75u4i*v^|B=vjI4qf`86vL|6{o}}1eqPPcS$@a zhvFW1G_}ywfbVQPC__3(a%W-XoOx=7FT9>zOj4i|EP9SqrgH!8cQ+d-b{+>@<8kI*LPtB zYkkN7Mx`DQtf|d_Hi$Mx9wm$H$_R$Hhj&S{X>im}yJow;W$^uI=JMkR;dtQy3$mRg zqZEAjsxA!=-KYOG{tTy~UL_`WfD64-naU=?sw152B%|}_+k+(7vD)m|5D%BbWRTr4 zbgx;87-=EZI0~^O+%R2l%4FkQvU{!o2FsVe8k&KJ$E28`QL9E)QB-RmFGMMm{`>hT ze)GI9X9#O2Bv)jXrYW3qZNXc=tE9I&KKb?o4&>wCa{vFz?PdGppej{1<#1F`J~rFA zm@Y1os$I?1df`EI)Gwh#Ec5uOpj}ZVK_iNkFKaev=V_UYT~nHPm65+%L`N@{G1O)- zlkw(<2Q(Ho4wdkxKbh|F?Uc)Pg&j}bSm2rB)ID{E_2?$v_i~D2DF{ zttA zhav>?VSCxJmWW3~y2ROM#pRWnj!O0C9KGR=3Qpol0Ss9zHX~%YsLl?99kQ;PA#aMrGsR?Q=*6V;zYEzXodl zU3e6$dPABri(zz)(fI&VR(_gp${gF1_G6GQSh3Yc=;sB$bf+9FqLJiE4yl7 z1Z;Nry_kHo?babovd=5;mw%PJAwQOGkJ!?*|A3o|-VolJs8o@enVeTtikAMCNbH`n zwJhnu+!UCcI^HEXZ5t+v>Wbusu0XT%~2u04gN5rD?J1=ps=#NS`!Efo*2!wRDHP_JpWs;Bz^2%H4?$e zdk8m>#JTjAMXV}F-*8;EyqF~~cpBo; zB-BS2R2Fi2B_I&hikqi$s&{^GKFwSDj#=3iGnHm5+7Fzk+RselYC|n}o=BcyNLoCb zL?3;W#v41wl-{cm2=a?IHWbXXK={KM*`#2RrFH~ptXtQmG}MyF?AvWU#o@91=(G{J zFS3Kr=gBu3=bPr)>Fr(y-bjf(jyEDNA4v44_7>s$*Eb&R{ZxkGYW*BvKaqFBtDEwc zalSsfH>0;9zTRBsk3qgcr0y}4cMXKDaS9Qj&F?}yC|RUBBt?5_+!A^`CL`1A7&rNh zepCizXI}=sj9|^r^0(s@Q3r|U3npbs1!=_6dujL2C&58Y@{$fP1#yQucxYIDAw4=x zmq0@8#l^|1u+5jYhMS8-mLo0X@%Pod!I?B@Fr>2#@G6QyB+(k>`>lN5?>?wo2b9h( zQ2%$?_}2jX-!OcRKjWwJpVBO|5PuU@RTNa=&l<+23L*GH%oy-@$b{d)g9qF#O+8nK zRxufw+T+{Fy`kyw7KM!#g1~QByxbfU4~D-tARd>3_eRP@|bd|&Q%KlM<*;W_UL z;;{~S&PFFhhjUA7H!xWAH|`?x+b`vdlS$=?E2Se<6hla<^o{jLv#;I`=0I4^!S8wS z#3**t)~$8W5g}fcQ2tC+X{1EPG?BCpb!1YMiKmDkT@*zzri?*@)LB+3tiuk{x{7!I z(FAd%s2v~F1&cb$75&mAePv}O_#uiDW-n!D(8*(A$}%``1dsSjENN0Y*y40;?{VMU zocyY;S(;$5Zs;ye~l8SWPq2^v$4Ozf~1fC^-%#TD!fry&fYV z-gx^cCwsy@5yy3=eho4cQ??VE2MZ~OcI*8WO7x?NzCYU9soFI#Ld1J@V;fBB z^RRnU>@4cR6Y$+(Y4f)`t^?ir6ruPJotbFfsQoD1=y)+cS$;RZRH^lTC3S1aiR5j+ zsMgU(dYFn#=q0}*Gq@b1nR)#l%W57?U&GnR>fFv$KH_Xc{BMXT<|snUA&jw1%v%xK zMn$JqW~sw;C|b_ZfDl{L^A-@M&p3&)^NO=mtF2WMQ+c zG_r>wV#z{rjplY1wIfNMC?=P}et$Hb7Dg-(1<)h9f1^i#h3bFB)S3TLjcWbI)Q3OF zCF&K}>}# zF>2q7pp1smFQWT&iL6wB8myzz1uw@}p*y$x$81!EaZy#x^!ehJj@Xo`N`)v6OAb)Z zT&1XbBi;$Cx>3XGRXsMCu~s0>xh1RK^7P&J8L(3sSl-B zgXZ2{hV?t{A5`8@z;QK!VfpB=9vq9kI~+UPUO&T>%+stuIzjE;SeL=9n^XU}>RKX? z1KfqYR<&N23)(r8cy3AH8~br+GmDOMD0KNOQ0V*`AH^jwFW4)9ND8jO4rf|pyxSJI z&)&-*i)Ywnjll-dOvWcQf*D;!=e+Jcx00eO?M|Oj|G13TfgZq>htVg96E)Puk(Go4 z%qfXoB3P&I_a{o3M?Ev%9E)rxLdVULz%i zFHj^W-f^q}#PMEia5n9Rb69IMRKpNzL@yG4?;_qZE!;nm!s~~|N1Q&e?j4p3Jn+_| z;2K6>@HNYrYZpZp-he8KF@{ku-lNyDcUTG*C4rWx>Ak;qTx_n_9zHtxK6~MM-nU93}^^;y7cCHYQlEQ6Y z7zkT>w$pF&lUxobUZ1bca0Id85FT;iL;)2c+9*&{!rzQ)(9I0QAF@I^LI`1xG5ZAO z@03U|O+N+dI^gUkTLacOPt$9=bcPu4vRcU)ENr;0yLc7YfKA?qoTfe0**y;_50`?b zoNqu=uge`mr$RVSI9BKf7?5=0`c2>jYC4_=7`QDu4pho|3b?yXf@YFPUZNvhSHHf(A3}t!W_dn5| zV)U~EfPWQDNLIjRJ#T@*1Wlt*Ffsfd<6Li~q+I6@#2_YG^$474aIy_-kS1-`WFPM9 zD&r_YkbQAW(v#LUn6`n72n?iqPmsxY47ZK>Z4_KHX{COg5#s{*<&&Mpdk z)0}(6X2lw4E&9TZ_ztLf`~tTT)%gy@!PZ)T-X4HcG$#dMsU-piE~3h>^SH&4G9$~M zRle6#QF^}rbb3Htp$Y=qCYn%CPPEcwNYai(>z5RWv@+(5gBWIUAw!I?f@DGT0lth$ zqF|!JTJ@C-(tU%e3)2yf5!y{W*-fnt)f0$#pr$iQk~0d>6AD+8KU{VQ-R>dQ70G@= z%RMD~i0iu^R3Nd3pe&9%Q_PSyC)SYoNi1~XP-Lk(=S=YIz^1dCLPM`vJGz@ZG#2ZzdIOY($g(N0W=N!f7_Y)Z>Y(i zrCqin;N4yxfk$cGVXqAV>Ptfh6bKeJWV3|`X~ar{vSo5#z71=It#;zZp0=8gu=8}p zw0=Jlp+5rk%jY*RY!d#r&-ARH!*Qc4TJLYNIgY0$hVk)ZK2d*D@Q;x~gVDwlgRCd3 zN^7y)!|KHdt9ehWdHaq!s3V61(T(ozvv4g&dHX_iN#h|HenTH0-dujbKcHCH>rwos zENU4n4`{ncUn5>Ii&pG5K)zTupd-jO6++<||B^+x4wD^;A5}ewtjR8^;e$D|kRt;@ zxPUDRaA!f0K(aT!<->UE-IOs&TS!&&VIv$LXI;u-0g_08O(~&n#Ye8Vq=@{buY;EL z{>8yc4+cc3yZVh@vhd6n)Pin}Nuk*Rm(4njV*R`R)DVd*GFpsGy!<3Xhy3@d$C`Tl zr!NK;NxH}#M)}BNzo?}T1>D8MMDcFFuNSdou^xT(hQ)J*RIWU_JgCGoD(%@jVb_wn zI7S@rd`3Iy>R&nEidZEHH)n;92!Dof*%~%~JD?FKz+536AeF1l!)J%Nc$IT0LY_W{70^j@q0d z1lP(ETt8tL(0quah2=XhGKraGR=E#E>qr~1d?q6MjQ$(rjS=y|yaV*JH~vj7^H&=2 zUj=gZf4pBds%Y6Q08GkEFLb!Di4**^ny6_~L0#EkO@-RxpiweN$0C9V=0t-JO_sPM za5!8|Jc&<~s6@oQFXeWMstFtvS_{jRDGvP~yB^&>nZX?1`T0?(V@;<|?_X!#Pu|`Z zkT)-XQg-No);XCb45fpGIrz5AkIveAIwYVBi-O8%z7yw92&~6ooG3y^i^nW)^eJ!= z0thqul_m#>orqD4m1($cf}C_59k#0`i*R z>;@@8vosKWLfxYj>ve5e&tWDCX1~=6?-K#b_4)}|4R13^vu^jRtY_w?#={`VQN+sX zhywIKRF16SoVIh}B+sU)7!#zsAvAIn?+f0nQEQA5$$C&kY}l?uYO?O7pX`k7^(87G z=1z@wUJNckq30PjVAjzdc4|POdC)u@f_4u=g33oiXrlBNdeVYz*e!Q4x{3ugVsBu0 zC_RSJdjpsNrdGCn^bfYhr!jI0rBLDr4dO)CdmkGxf%te3{kMwGJTdo|wx=kK31ylE z3+BvcV~VIMS!OK&rTf=Sgc}Zi2?RhX21q)P;r&i%j80zT8F`Z?fFl zXo2;KbLPW(HiI0M7S?)8r1S1_uuc3UCN({>n`p_j?U14C-UF+XL*H-WPQf4H2Jh%Y z&)(8^;Aw}x`#`>7XdmE^zCrjFzmRuRpZA%cze;vs>+LXEhsJOy%M*+be2FSf%bW8h zjIMLtaY7R7H}Npz8Z_K9~D6?ac6P-);B>J@q2#}Sx)mx*c2{{8>Y^){QqL-_8oz1w1f&EWX1VhMbf2 zFcXqb->nk&cr7xYRsXbuK%Wzi0XN+)XbgpJ(hZUrxDVlODvsw(U67u`fCFGzGKa{0 zM35TkTgYda-ooN9g9Tq(l@%pn-i6AFu|hFB;>|Pi4!`pj(QhOvvY51JrzuAm-5KX- zE|vVK$dVfuQSoZV(u%@N#>oECnHD)-@8~KTZuV19U|I4uz*m=AHccK&|c^{YysVc+(>^O=2aVR?52&_w`AeeqUgIh zSgAxaNV0l|kc74hb9o436x*OiNC}R~u4wDHSqo8+!8gJw`kNp|E#fb>^zZS#erTa_%c|JwEZ`?DWQj z+~CL;3h9Uto@wcTGOS;~i2K?SA(7dw5oz(Yvew0k_#Ig_7Iw(qm&uz2`M9CEe}E&V zvQ|X}S);6W+CTQ}&`=dqc`|wpmaCF$z{(QgwI;X8qI{$1@(iVKyA8n=a@UGBXjAa1 z4cZ_UdQulX1MuTb%WR9c{5hmbg>R2bWN6#IfVq4hN$7EG%t8uNPBuJ%^(gR(NVW}g zp`v2DRl${Mqq9Q%`DBugw*tFBRACb9`5DAX4^$p?QR(_O0Xkl@{q4@z&# zl>Gq2DyN7<%BU?TA+oh-!VRRHNL`Jj1A9P)x+T0?3}MTuV1p{j*RkLNb?kAI;t}$Y zg>CGY;IkRq7_i_oddL%HGR!#|+beORnfbE``^n1!<)nR?gqU~`@6tCXOhKJDKK5$y z$a^8Tb(KeAJo|P5vP&QENRjk1THBoFGI%PbK#zD%dDJaNZbnuILt|!+6lr*Am{@#1 zMtes?V|&Afk0*dl7scYioo(f(lGLzFbSv&sOi5XsLvg1)V?*PNJf4K8VoQ%W>k}hK z1z&ju2X86$#iCj1i-fN!Gvh~yP8131oc4|BL(#&Ph>bLlke0ET;FCL<<#^)_ao~_4 zo|*N_86*Q;n~&;A<^o{lbeS#5X8}&aD@(3ZL`3)%W$#oxnPyRKWJoA z;(rcO>f6l*gM**W+p&hsisklNg5&h*80QWcY}kai@3LHjqV0?#^t=|s&UAtx^c>IH zeU4cG(gf)-1BY4tBu2v@5X9=I_lbn-n?5j194_;{eeB|KTDbHQbeRePu0s0z>n_f?7mMY+bIjCu@O>o^nOt%_W zWD*B9);J>Te*yUS83;`+ig?_h-rrMujOzA)IcIolmMWIH#+qeo_)U8vu57u3# zY?`nBOwlo0ZA^jHOwnputn(RfQeRSP{A0P%b1qkd6Zof3=tO_lbr$`PvbyoVBs;&2 zLC`7L8#p?dh&dV(Ntn^Q{v=o#srCJIojSoV>mZgH_hy!g6F8xb7vznR~yf8iuQ3k`cAfm4jqNA_fpnwBvF_F_2 z4D57jiQyu5OHSJULuu8On+9j`;raB6hFwg!kpZUkioGRWY*vmMOf4LcJtseCwRM?z0`0Rsc&nC%6shwxXC{u& zQMZ=O)+K0WVIQt(k6yDiY!>!h4m$n1oY7!uTEja3(ZP)aq;m=IeVA0u@_9r3)|UA4 zuJHp#pH6Pv>K>}rA3S7g8r|>oTMw4+?y$|BDWfjZUDL*ijUL7wf#>NPJ;qFl*y$Ss z#?XnGn5SrD&5Y0fKNVhU`lDG;11lCa{mbq4i}?=bd>t&P64%o=dJkmD*3+!b?ug0U z9QNDO-&Xv&Zpfvt3>@hav*9*^`ApP)P53|V{?b0%9fGG{oiv6|1W&&(xr>7pySYD> z#xuQxNEA!w9y&mm_8C1;lg2Z<14$%L=N>$;AbU;Y?mt+T_US*+Ae(0RnllP5t!sRT zl$e^{(RZLi_L|-?bl^hP-MEX*`j!m~Pw*+Ao)zOquo-Aad>CCo9PVxKudN}T48R{Y-f7?;u`nUcU8Bl zt|Gtu$2{zgnL%C+eXVA&FQJrP{|{|%85?J`rEA79+ht~EW@bBPW@ct)X1mPH%#7uj zV<%>a8DeJUm>I6m>F&9GdZw>Ntr=-crTVi~TJ^2{y;^&{&#K-qR8%qq-!QT@w`V@F zy$i26uC@`;mj~NyK87$6=q0+9tRUO#utoKu){i#I$FR9_K7221D5@zL#d5esr4zY$ zRbo5dr#L^-uVI&5eI-8`e=2gaEo+-wT|20;Lv(jbY)T{8uv&eTah%3Gihm?aV|f2l z<8N%pd_n~&+WUJjZ^LPTi|fq(N|gduW9die#iSOMDjKA`y7mIqroL%udH6HHbI!H( znf_?qqO_8-2>nB z7n2B-DWb28I3QU5O^R%?>_m!`dIzLDNLs-4?e9i9W|-{yrok=PjKNh~BPCezk+@T$ zTT5>^nB(^Zf37bgDoWF9FxE-+-5KsJnl27WHz%U{P9`QAKHtRa=Kq_6BC8t=={3xzLCFL5SlEm`7?XS!vi7 z%uDuLo^d|clAUEliQQd!qs@U*b8sD@Nl6y3sBKh)TskG?8ZaJoD+AVzjY7aD;XA9T>Ke&rF`y`HQe3JS-MC?(Y=0l^^Ig-g@zNBZ>y%hx zkGfRDo^&YWwQ$OQO|GuR>yJ&ZgrYCI+O93aix-c`zBqXemz25f{3^j#W^21*&9+@k z0BzgjSLNSUzpZlvM&a^`A~QK{pe$CDG!l$OEJk6ccLwnCF;1+mp~Y>({4eHy`cr{_ zVIi)b#Qh>XLX*mFXW$-Ps-jxEm)Tvvyg15_g7;3i&FZqFT+A~mM2k8<6U6+DCma|v zJ21c(FT3ki3ivj}CzDJm_)*}+6O9Z-Z87Xx8ZSA{Ekk-o4eL>MCDi*)6!sAX#uW^` z1~Cx+5eT)W%xckl!uMkguaLtvSl815RCr8p$adEl;u&Y(H3~1j>V=fG+J<7Uz0#G$ zd8g-~env01xwBbM%W-m!2rm5LXbTvu{diz7j%<4mRJRvJDKD=~Cb>BVr~F0YSG7c5 zS{)%grj~WH4*XLR_c{Ni|Eu5>Yi$EdW!pB9ofoq4_h94X_y9po^a!c%;6D*@55Qg0 zOX0SV)EP0cVBTH3PDaa3oh#|q&T@7S>vRnqTX(aDVTJm*@)|K5D)O9P@x2N6V|^Se z&@O`b>>tz7Hiv|GuM{8S5s-MU^k2UtY`X5eJO-nEgt)@2Y$2~k1rG8kcqRX`q{{E) zy>h%vMH3oG$bIyD#V&eY)#(L(IPC~sq0PcvnCvO$J>mph3@~l6P!SGwut45X?JB%t z`BTK}!?69TgCHAboxS0FosBZwUR3bX1*7VM@Xfm<<=<6PQqH}^?Yao#dg>2--DY5X zOA_kpFMGg9QDvdStS~V*QJu|oO61vy(8NB$p*l0YrdjkSmKnd#BG&WFd=ZeNzSQ;V zFJH=w4$TdsdTU?X2A}V}-8y7s zc!H1Z7 z-Rl=*2k^p9qFEvau*%#qHo-rRXm_i|0?OHnQ5*6ccu{k5Qz-e+Uj!%~LU)$o%lDCj zo&p-x_`z`UUyeGUt)Q00C*&?oi$i;5+;~~?Av`L9ewkpQMwEaE+$CYd=qdu?KE*A< zE4ow^5p;A4%pr&em1P>+R@FG#4F!@lM)~%sN}_jrxtJs;#xXRdzfEUgczuLYB@hB56+8iDyyH2uZ4rH2;X|DeDBGIE;Qa4s_LF%!ru z+y&0PH1E5Gjh^dMTd2SoVL`A*5ejUK*7>d{ic=IhumT>6?xE`clwvfthS=)jveb?G zhon>onrFH$roCwPLiDrmhiPAVBxraW)+VltbH=9z{qGmd6ZsA<;dyxXVx7`T#fl-n zDiSt^OErsJne(M7-Q{z9wV-*+Y7kZHsXbzVA#LY5SPwC0UqZa5;Cw@dd*Z1q(t(#gy@;st zuA}0LM$zrXYmHvcrdos3=Z3jsi(1asi_FTE6EFJVW8HbmF*gV(Z{3tX=eaZ)HKi%a zF$FIGZy?8XN5HrWZa}Pgv6^f*l2HY|T z9OxC`WocK(s*U?mxXJAJr{knc(D|TGyqJxBOA6F-20@y0DDVwuT<4&tdYb0ok>NWMkb5t$v~RanM_IkKK*; z$LK66)DCJ1357E?KCir&wn@%ZaeN%CoYPC{tKrn{Hc7(qbNu0j;u3;>g)xBpiWP84 zV06*Y$QUcehWPuQ+GEl%_lta_rI0;Cg?Bw^)NZ~)vIG-PAG;3islcdj==Fwli=t}x z+`_2crowW7W(fF)1YH}F^@txt%cZAPM1r;bB~teHcWLW;G#!6`DClkYl@+3LjSo~r zJ+X2;1yObR25n|_*@pG$>auM*8j>38c7o1kk1;F8*s|?}J*5|^4B)aoEn|gonyUN= z(`b=^rf$^!XwkYsar}947$~j~Z`Hf0pMQNRKpeb|LdiiL8JuBd$)K49wpJWkm)IDd z`iKan@x}c2V_Z7x>>Ul+tz%iN0hvnZ(@-ktI8t>8TU!y*yzYqFdIx)v&pCA%{cNJJ zfa^7C8Jr+70f!lu&6vWXmv$V8kO{tM%(xci?ZkD^A3!fghbY3=`IE#~%>4fH_Zdjo zB7uR`w{+|*iShez#hY0I0;}&?hOw4xJ;yOwIeDr&sthWNXo{HJ=kT5q@~S?C3NPU| z7gKvdfOH72NSnoEhV8+oN|U;0@b2J9k^i^>c4w|f$S}p%cK0tH2;bJfy~Up(O6eb3 zf4BBSXvT|XPbGeWjv$XKt_@k7cnxlcu4edxI) z#76l`t;+4pDSm^G9daWUK?stfOCm_Oigy=5k>_ngJ4BX>5K@X-_flH%ZS|@s-9q^q z+w9m0Im<7=Y*Rr6>W4aUBH7y_&HHm*y1bd1h}Pn-&I(#xN&bDjV6BEZmMj ztbr@il?O1%1QSak86etL#2w&9Ae9fNev|$hSQ9TKfBh>(4k95K222zMaTL2lFDA)3 z+t;Gfnbjq^W9jFyg%f)AvhnhuT;55{;CIzW#d|d=9I#6}nONg%1Bl|3 zw6Au9OSSX^I8Q;o*sI@Avo?qC6Xu8#c=0Qx)1D}#Wae{~NGv3ob&{c%$Gl-gWy9Z(<|CjQdN7?rjLZ@NX5;EIIXW$UOaps)H*N2soF#B|0cPv! z33IwadJd9{jpJtOuU*jxtu;k34Z$*9>40X~^4&XTXvZL^E)>jNd9%hG>&YJoI?i-% zJLl7Jt6Mf*x{OUa#(-CG`byr>r$7ocZL1`X)O5Rt>Gt+)9X}}wyt}qsOqB$szph*8 zIs*cvfNpJEA2x;)?)r1H@j$C>)-)a0^j06K{n0408)bdMwpkUWL68miNSlxgrCa2c zFMdRxRs?XKM|S(yy_xIIZf8+oF8*_Y%#!#D1fSO3N~-tH9s^N1?s${QOWX@}bHPlM zfR?Cy$@yBv%I!_ofT4^YD21(0NO*AScLbWXur+bZ%J9wnFnp&V@V6iwtnT@)D-US{ z@tYUDB2Ck)QrL27p14MfTXN)3ZE+m?l=`B}rh|_&R+g?uKOppCaE9e49OjxL**(Wd z-y%)tMv%#C9=|g+6c)q0BUXrf($4}?tnvu+cN_9vttXT9SOW&i9n_6O%{D6M6Uk;Zpolj&|X{?x|ZU6c>D{%|blhz*M9iT$f` z5RgFm@=#VUDizJdp?~+pS8r>FShcXTCap4`8l}v~r`(X>=EFmgo#Ih@Qpp1_w6%Ij zHpn&0h@D*Pf~@wM7=yIr5ueN@%xqJgU-N=DOIKYe`iS8z3aqOZBI;M_QC|ezmz6aO zR@yQts_EyJ?P3`X_V1kp_7cCM0=G4l6i^kE<(O4jWL3vYU*T79o=`#4UzMLLMk+@# z*0V1WRyL}X;+|6eWd8l(j|!^iCYG08#3@%A@}b0$;Ldf7;5fsz-{<8%m|tf$JRRcB zOtsU8ii}g=d+|na#=INY)N>x-<@iMoMn4VKNnWV^b-_BTnj29|(ZQB@?Oi2}RV+f6 z-kG6Oyfj)DeONz}g4|vKiboDwo1CPMS4x+3kLJX5W`#Vl1cAimv*9Ayos)YK8M)^G~+KMq}PWr5=|^-Pn6H?Gtm4Ii~lCM&n_B^tsVQ#GLO| zEHL`f;%xjyc!t0kX&}APEbl1COpR$^0oyzrZ4JJM%7T-36YY!|Lw7nA(b#@eblhuy`kwJ$bs~A` zwJk2dOYS>z&Q6a+q_F6~ni+T%k6@xs3ZN7Qq4bCgP|B}g%ZF;(O+lET{Wj>+W?Xyt z0DV3u%=G~7|C7W`II!QUB_NElf8B^X7LMWqFcCOB;H>-ohzWLWpSRtVe2wL;w*^H{ z7q#6MVT*A<_-J-(vc!XbM3P0VuIjg*5u>jc9sX{)z=#&oU$)oti59FJ=at-YzdJohqHz^AGK9YG*IN%PXB~S7}uYhJQXgySH z7VShYUp(!x9;aC@HaW1{4F4)ej~Rouw^>{zsp{3$8fai>fm@-A$06mek5PKj?((df zq8F<4nAa3R)FjW5Q%w(v>7c&Fs#??|5;v*i1`5~d(wtH)ZqaLQR4VGJZf$gl zfs+YHU!UIK>z1cj7G9QaU4>-auTYYik_qS4Bn(RNLJ^%(O@-c8GiUNjizp1uN7*;# zHuP4@mpSMIWyevep5WE4J6BN%4r(#geJ9KxMCs!_btX?kUt!9xTL&nFr8uK|4+1Jg zXyVJ0A!REm?89dmYPG7L4ii0io0|BmFqT8`xpx2z7K7LA7-Oay^nc9uCbIXyBmfXYTT?4bCr$xLn_A2M?t!=VN7tOTzh5P<%mIG^ zl~OIs#eL`WesXq8wY0ZFDpYX>Fj)ptvqYo7+*F{uEE4gHKn@I{d>3{>L?E@2JAlZT zNGtE?zi4{cMa+nk&Yq?p$zDd|;KP*2j^0L}qb^#uX)&zQE^(9lmvw;6D32b$t%8v@ zYeXK4va%B1n!;{xNMTP?BciWj*^wKHpS{YehXdt+x97yO%WFY?!VM*nHPo*+XOd8}r50U+*CA zh^V?!!u82g2&i)J+bT@E@~1@W>Ii;SZ~zxWVLK0Gc_wBryDC|(vCdb^oOF?aW`F|+ zL&U0FMX$!(u~WpcocFjdR9*1A=?1S>Il;|AZwt42OpX04*{Tz6{+FxGwaVO`%#6Sp zM9>T6or;B3ybJZPT6KNZq=Rl6_^P^UILe9!#jDz+Te^dB8NrzORH0QaBFObO;F+k$ zIX@Zh8gUp$h`tl=qHy7waFDoDKCVCK~ zV(Nj->L?Y*Gm-eTGoNV>9M32nvg0uO$Fw0NHy`lQtNjB~&wDhNJm)@JiX1Al=FW9Q(zlor~^)hL`^+S1;Lw{&0g}?m8 z#=Xj(k9}+D zD1w11#uXJ7MgAmCtAb{0>cFh`Qk2O zThgYxpL&(uO{&MMdg>AKKrc#BDvxTblGKP45rQy$s8(TOeVe3DmU-pJ+xhSe#R)|U-$(7HHzB*qbN#PJ6OA!|3}PB%|Ai0 z{}&tLGkoN1{}#YOO?^3har}>o^YaU5yI_sh`<3Ey6W?#=SISCYF=?SbKB?(UtFzT( zte$O+ZL%H@jL81v$2BupB~elSEI+MH7y=;Tq*I2V^Zi(?XSwA49!AC9rZ$wPWyHcB znb|&`&d2`>-F#$byQ){&X<~|AxyD;6*Pg!Z{gOp=ByBvRqA+Nr%S92g^w&iF))>4giCV)xaz1)3D-L3tglE|IGFwk|6#~MbAw4w) zOMx_9wIsp)xP(I_2$D|HgXRbmULu1S2y^Y#+qecrZW}Jge(Q%-GL;suu!|G82Kk!_ zP#6t1UI;)X=91olTB!Kk=q}(_dIZ-I>rAXb|6KvGc8_Npy z4*oXh#LaD%LeU;HG>C&6c}xk$R+_8{B#a0|+UxvRvwX<}dRGdXyq# z?{PsB++b7iZ#G_V2?yASlxz&k&=QH;$)oa46nrm)V)Zbm(Q)$X@$M^HKBlGwzHKbC zE`G8rDn`py#{EcQHq*t?m>tRr<#Rb$i!_*27;%FLm9pPX^X78+){Ad;KioDQ5A_rk zD?F1W10}Hif>Bv9^j~5=3}p2{_I2A znH`C`Z;u~&`&%WUm<~3};z7--q?5Egp27^(O`Y077D&xfzg2XVcp70Ie!>Uq-9N3m z=hj$LX}Xwb2E}TJSrR*kkT3cJEXF?L}y@s{f58C!?J(D`h))4^J7E-m|P!W4>Mz=jl__0mtZ89lkyP7`0vcV z+%PV4y`e4utRw7WbkJrx=!?EqOy6%%$(%_i$1f=A<)D>oHdH$Cy(d zUZX8GSn6mO=^Hd|*1pwb8N17{>CbiGEd{q;tmu|I=8#Oa989p@hO6^QDKgid2N#)T zjIA9yNRhMak1f{|xO9i>@K67M^7>g=fF{bw=2t}c<>Nhf5*-H>-XMyt^tyGdVZkyiZ!n|Q{)^o6Pc7H$c#%b;{`q*2O>A|Zi6o^pL{vlt&NeyTWAR0ot{xA%G5%T~3Rq2y+AV*`sa;4&GHi8bpe?Ef zM(#ij>H<1?V|`)dDZo|HJ?w9Ow zpt6yPYH+wNoJ`+NA8kx^2<_k=*cu~{q$u(r(?MK!xod)fx9ZQwPbI3xPK`pV(H7U) zS3)t}^44wcE)!nOSD9`Jdi!%z?^(M)nG@ zg_Emnu-0PxmZ_3*L^QXxKv_DYEZw_Hd%ZjoHMs$__5#fW43_JOe0qe7l=u z((|>!Kbf4*B&E0@X1@i(lheH;ga1ONf+_;{8N+C9-K4kp`d_UDTVPzl*)juAHZXI}aOCkGsa zy2A1Q3sT#AU{7w3UrZEEr@yYO>p>iHPVeGu6nm?PYzyMa4VCb5Q;RYs)p12VB(sag zPDr6p{p&Ok`s<%Z&_Z+G(CeoIz!d)fbOdSrk2K!@R?7cL+|K3wJdqSqG{0t)%8j>Gh)>-EDlSU!-{bJ&ln)yh|%Zl%=IXliEjcVw8Q1T@uP zNZv22wDz7Rm)MK9@=t+SI->ks-xcx0uGYVA+j|nzaAOJ~$+PpfC>-R`cZn5$X+N`; z9iAJ?VRQu*r6Uu52u?7v_E`@v#J}oHrQ>npZ2Nc?Gi$~Re7 z7kJ{35Ccl@_Y6VbsEw!{$mg&Hq>;Gz#`hQ1NGy6}< z`5!Hs|IwWJuVHTaclT@gkM(dBu%v47n!+Iaw#Fb3t(u%0WDYv>x9ZPcl4S+sQI8Be zPwDnUNIyu&u0LWF?{{E+uz&pkcXBM>x>$N$SlAB7Kj%|DP5Nay3JGz1qQGc@hFXaAwdA}R?RK&IE@+$i0c!Jn6g)g0=nNOK<` zK(V?XW9*;zQbP(XYS_~*SH=9Y_pzKBD*vO`D7P@*d$V?BkB|&|oh2_(Da~zgL=9k5 zAzvZ|y_$ax1waAOsN+px6KX0X&TR>{1g-RFeidpCnLcD==-~i9wQhs-i?^QCFSx`; z)dKAX;r(N#mWwT;eq|*%X7O3zJMZm87R78U>(Zh`n$iyKazhKm!^*MpKYnZmGM zSB?6Q(D|bJzMV?m6OeW!L`pPPa{Q{CW1RpUSEg#BMz?ci#!{kt)6h_*g3NBgQ_Vpn z4Cgd%FTN@Pu3C=yT3|fX*d@F}&S?uMa!GEEGuniZYm`4dmHPDg2ifye9JdW(7FqAA zz-h=Mi^5(8bhM(4oJU%K@aJi#b*XRk}Mz~ldiUK_n znKX4kt__~P^+)@9ab~7dFWMu_hF49L%P95SQDL2ee?CeL9G z)6Mx|1Z|KY0H_p7$H5)!fk8kbbyOP;Y>(#LCRZa@cdI(GFd75Mro{g!zHxV`&F~{x)yicVCNquXjlTm z;9Dq3(63%g;1F63XHg4I5hw6KrW6^^HceE?&^UIwk|q~f&$4(q8}uZ8SgPJ@)Uk>_ zBdg0h^^fYV2~Jx$g<{c#Rois9@n^`QwPD5q;y8HqJ?U3XVIsk+lzvV*ad}1#SkF;# zMxwYbxY7YNohOWmoPw|IlJ_k&@Y{?!&6DDt2B7DSQkh~jlV%s#89D1G#X1Y~vxsncmfM8ZH`<3f*fx*E*?g8`KBD}a21c>0d8_e*(a&FBdh zb#Q8KZ2(+Z$ZR62a_8|yB73QXTJS6if`pnkFRf(id*q6|EBhnji2#T}-mxa^(On`DCH}+grUwMcxsO1=(LA*Dl4uT3VK-`I|L7d5lrG55!$^5ITCW zm<+`2p55BepP`s81@cFl$ObgaL{#;!QA9lnBC%Y`NIfWwyV_GXzHHzB4o@{~g01yV zupT(IKp^Qd+WlzU-PXZ@)O&F17yTm|XH1hO5!Fs6Uyb_KyliBIgoAk!rBFBBO14u( zk4&+|7}&3b3)|;unuXdpsw5?+hzqrWrop_27+L70Xl?$0-DUILd%DuSQcuw**%(yT z?8lDpR<`U(4oK5LO?r)W^BA=^Ld>^UN^C*-~MWWNN(GYPPXigv7-wjeCai zhSZEN=^QzsvL@Xhol~t?F>H8$^!$+D=Vn%3+HHMIq+E zmyc5KVgLB;<&PDJj=hHtYrN$&nLZB-;ya(`)9XJv&^czUJc-&p&M4;NsuwBYE?R{h z*3hY%Yq(7*oJoJShKToQ%~||iJ<)Q5AWzZuLgHYrd+T5yGXVbiJG5CiuMFIQ5vYL) zY_H(yPm;CD44FTNA?>&yR1Vy<(|Pu*^5-U117I^OfBOz(75yx_vPUf8Te zdoL5i^3-i*bK=uK?fEJfG^agcgbh zR5!H7AeU>DN@be-FRCMgrju5ZZB2oR!kTJ|YLt$QEe!t99vlDE{C~2}KHfgXC+g>) z@!!LYW&cN-|Nr5P__wH^>%#k?f0~3mEj*}xEQgUJk0e8URY|r(75O6EH_Nt2a|ce1|O~$wilPTR0$W*L98@?!1}e~(0)!Ha4+j=$hO^7 zsvQo@`jKX!cF39EDYOPLxP^o=6hp;C(UZ9FB$d(X9)z*mO{9OvQ1F1%{cN`KaiK_3 zr@cwerHiU9&W5780j0UEO10spX{c63$xNtSqjmfqt+xQ9ZQ<6YgP)z_to{L%ij>Nf z3X|eX;t*R<*>%5<`}_4n)bsQlPl)+KX$Xq6fWn0#X$s|uKPgV^=QlVmlqb@41Ie-p z+LvTBi{tx%tdTphpCWruq=ppN9Hd;R9Z@3_Vh$ut;UgNPhEy(eNvl$iT$Q)-q-|)+ z5@vi!e35=JT^%VSh@IUr+!r2Ad3IQ77t$7+77r@Nd}0?R(3=$30;HQ%*WgqyB&&5z zFL{N=;C6Rpq`r~--}Z*Z0z~$N)AncYNJx>;j)|Kxq^Oc4Bl%^_h?0gQUsFc{NTDP7 z74~3Bg~+a5Nq-SvlP4LXK4BzD3bShc55F%Qb!Hp6z7eoRa zjX;=iFQIiYHr3dTJOCBi(7Nr&HjbtxJgY^!R64t27wAxO!^W}+qG=I;#R8P5eAxzP zLxVQm;0dM~js2BGHdVThZg=pVabSD%%rD$Owsk1KxI(UFYcSPtU+1u?hkQ#^qS#+h zVq>Nxm_pj1Vr-islazii%@WQ|GwBM;BV=vc-2l57bRa%DXmBn^WvH9VL!$P>8AcO$yiPEQxsi=4!b;F;WS6uC0i* zQ)nF}XgGX-g%)OlA?;A1?UM5s$Gi=wxS|)9U=MQD8~#cglF7(9&XQtGf1hwT2GKRlrZFwNJR#E;yHk@*4=R=n zU*p`&w^&CsOp ztvx;=9Ts1V9R>@Cz~HTo=Yzr}K5&KPzr-gl?37)hiP}5<$!4Ah*uX(4w4B)&azC;Q zK`piNA_IykDfTMVn!-cQ>*Dw?xQkZ$-^&;7F$IHLKlv71OU&a;09%}B=^~Mk(wCIzeCxQ3m{}F&PKZI9(-p==Cao#t3oIyFrpb<5 z6K=NZW^z~{OS3C{I+EFgejJ;-)XmeXNV83$mp)pwQahfAk6&mKZ?~l3-r`s6lbP-^ zOvg|Y0(3v7VB*fNM2TIoqcZ$pcQc`mm^5YRE2Fobb-3tUP{+W9|eYUn_#wy zbC;LU)?XO+cYnYcFKhe?HZoI#N>`V{)wK+sKBZD~$hO7CqRw$h+Qh9=LyPyF%?5Tu zyi}u%ZJ##T_}JZs#IKBo8PbhAu#;8J-^}=~_HjDIJL=0U_*vlXzi)v~U@KdW`wFbw zDvf?YjX2ai;8-=XP`}9mJn@dzZL~|1i`zD$&7Xtxo>oM;b@15CU6wXyF(WrdH@*ce z^pDj{@;GIB#K$!sre_Aric|%A;3J?_*5tX$Zh(!ItA0$Be{h*Vv9>u|@|@(#p1Rii zO69z-3cS-DY;I^%u^fCPoYx-eRY3pnkpICIWP3dxvQpD!+f@eUXscTF9^$LB&8kNT z%Q3oJ$b#&r1vu&5X=`d%w=eeP z1v=r@@euo&IzMlrHfgyDu8=}}rI;$Y1hC7W=6Hb(DVqnx*}rEosjm#0K` z8!4S}YuNc6!HqqflNSqORaEetRLDN&JH6L1N(sD2k3Qqlpn=Nr7~?(M>o}xmzXBHD z;g8w}kc!#T6=L&qdnuUdGH?rwAO@J6$s7fgT{VGjbZ=KZ6GUC~bBt z>>-dkvSua)z0wNxNkYfpyc+u**mBZ%jSar{ZD@?XdM=q^@e6Of;s*>B`h1)A0R3wE zmE;w+8w8IC@=WSUVf2cZnNmIWrX?``TYdJI@gB+JH>Bk8fdH0o!P^|<@Rm4M*SNxu zEez7(sMjdM+`?JBGjOb~Q9(CQ!qP9jGgIqxhVN$TP4R;o86UK665DExQIf@*`8QB?CnsSFUS%f^z zOLazvGtyx$vJ`EUm^E_*nKUaB98bn9le}Y#hPzURwLGGL|5zRRaSa z6WUNQ%6}KF)5;^sX*U`9a~HQTJ9&wc{Pp3@GuZ-ZAb=FO?+1@r_ zJr-FYFt)+F;Q`o&?qLFa2Z*SOuJQe5IYMqw;z;!ka zNfCIVLYh=`KJ#?&y|-hm5MKmVqAZmG$9Sratuq z8r?Gga;rTHw(g*6 z2lt^{A2~M|2KZnbMEQM%uh9hnvHzbm6=e9tB^& zlqnxaXeAqQrDN1OI}tqK@oJb5_#>x9^WKM?c*CG~H2#!Tq|G=5=VKRvv(n3mcuA#o zD}&Ro0y5IR!Q2x&de$Lf>o`j0c|5D2v{=yilF)GZVgZ(+&i={!;#5u3$uq_&5CMK-OTo{vD3O6<>_O8Vk*{bv7cZ7eOlmZ_hzN5Gbz2=v;t_r z3J)B?RJ?Y0gkR7IADrdO-OPCMRJ%;unQCymbm3QNeUCE6er3k|X}lnXLw|@fg$}t%$Kt_~?bkaP{)CPVCfWOx<(I#}SpUS<`Sw-#V`v$-z(;>7 zvjK^VHmi}pO1EsxsQH722hB0}aVj%hGR8uPK0eT`rt-Miiv62lrjNP~fWYPF z%ZSDs6y)=xpx%Ujw(G_jzV7?~_n-Xw>6MnG(gfe6fH zDTjTT_U5lHx{B#HH4SGeVio1=*twUynKR>9EfT83^XY05)hYR6H8jzhFc}8bAt0XqGK+>-uz4LxJPyp!HGykv>n$!+FP!B zbK7jZhy~0$Xu^IgC~rA>U!UcbiJEzP2NcFjqehcbC2CGt+UuB|&0szI5cWq(Q#S@@FX zGg)ho$Qhw5X!wP!by~!(qHO7tSB(Hli8T*qqaAP!j12>)gjFEf77GN>H8G!MqyzH? zeip`bnGjgg(qI@;w!dua@iZ?kQgMG&V5z?Ypd zr-BaUWmiUvb>)W6!OQZ|=B_x_{>Wx>l{nS4vJv56jp|ws-Qhm28arw@=BL&8-UIkXsEl6C)Xr}YBVY91PF;hY8^2y)2lWBefWczSS_@Irzv zn(M1mi@k#%x?kqUKUQsnpJZErj8%ZRRYr+$;j0IMA!bVqRz~bz1PRYHW495w?6@$y z!lbI)i{t#31DFdi%WVM&n6050U8p9;N9D&1+?j~%Cj*JOB!AHq=j5)bxAvF~rc{aX z8o6}TjZiOr-l*4sm$#og@EP!Kg&=0?)OY@o)7wzE5V7TiLM4YyrhuGGv18Vk2?St0q zl0|cN;eq|V^xxlI+G)^IAqnG~|8*to$)E@I7Z=1$ZQ_jlKKb%(F>I?x>$N|#=yx1K zZk~Z|+VHKlb-A^%MT9C)%r|#H{*utakGzEGn6J!Q{KYz&~?c25% z=sSc^1p-@8fc&zx-w|ppF^7F{zA@=ek7=L{d4JvIp8=I%v+=&MiU=h!1%APQ`9#as zGsbf8+Oe(}!@Ln~9H4ax^?y8+J9PbyU~upQIrtIi4`asc>p-gw)c+~XnR(Qmeq>mW zt-#23c%^Z0nfGG7kIe+{JZAq=gBG-p$7?x!+(qE-Aey&Y2WA?Jbhqw)&m=Xs8`6yC zej$?gK#pI^R^TA7gY$zj&BL^yiwGz!6oP7yP(WmW<)0WQL$- zr;{w3;XGWgYHprDGWvp>dxhXQs7WZgdKaDGn|MM=G1aq@*=a#>%nmw%n7Cq5am9<0 z+27CayXXQj(TF9*htEo-_lh$V&e8Gzi@0|HvMpHCHp{kc+qP}nwq13~wr$(CZR?bM zN~esedvE_S-5ve+AJH=t6Y<7ck$bNdv3KswZ{^PX@_7pjjmytQ_)tjy$}7rd7b2IR zkx+THz>CIyQD!2So!P29!co0h<40zHDzmW5ExebX<&~eg;72CDmzA^0Es&R=!5kSi zxQo{QT#sHQp*BEDUO*&{AF1?KR!%3Uh(#qOE{f?(A@%8EeDJZ(sE7wQ;lu`$W;hms?;_W$uO*K7LVZA(WLPp{f=XUhtuqKFTi)a)`E+Ti{VuUJ5Vl|GbS-27z9B zZ=}*(3@O40398Y_Fq{@Z4EB7_!_nDi=%#RM5!w5j0Z zk?60pi6}r1aGDrS&jfa@ylw{ey+aJ&Y}he2Y|&F}QezE|3VI^Vm@ z3YoJ2(>LqAK9s`;C(&G+sb*B;Aepwn5Sgsq!BE;=Do5&^dY{S~iP1^axPDX^UQD&x z$)qHvBngXFZQ4nhOoeEEUvZsUJGsI%aJv>@wN&zsq$3(_-e0n)nj+gb#XSzD({`F) zSnEgFhVeegFk{xaKF~s4prcdThFp5)Q*DDduUYjny|`G%w)J3jYm@GSuJ>^5f~$KF zt%6K9p-s_kOCkFwq}V!!-C6nWu-qWQ-20lTQ|<)Z>ku@O>rU9%6LFklgIcL!q@XAL zKx|OzH*6YUDK;#7mipjB8=fyL6vH`^z^`H9*LK5C ze#36;MqS|d$9erIuY%?A_<^7vx>W9iRIi8{wER?Z9bNS_>iG%n@Xt`%5#N1rItHZ*xZxi*ILaeu2c z`BG7mHLOTRG%zelL?KNy$wYts-bQ{Q!K_1lJwo-3HFzmWJu-IKd7>E!Zy35J7|XUR z%Pw(qpSJwHP90B|7qD<|tw7NSS8|U{Hbxa}jCw#F0(FxqfyxV@U>x8#D+pnV z0lRowFDqlV`zXl9^|(@uL)SLlJ>N(UkvV6VcOKH8oo6L`F!xK1zPtDw zG)bVoQB4R?l#E3?b~R>;-M~1(6NN8sTRN#pxrZ;(5LAXHOzM;?T^Q6d;nOM8u?ij` zBfN^-y!?AbZx?i)fy?s2B|wwMQo$)gsbC_&26ljnSnd!|nI6WlZmKnBHqYLp?0~bG zx-TFz*l^2G3~o5$afWv!wIJV*%hPnaUyOw{<6eU7xhbGV7j$diaFP7pbD`8rUI~zA zl~7e1GAMyGqX2Ahz=pw7Gcy^c0UV`a`z3oMJuZ2`QM&5U!^wp!S3Fc@qWDnh;*oS! zFu2FFoj7`;$~eX{skP)iw-5>!kuyhzomllU0KeG<&k{x4)>F@A23>B$B8gKgEmPHR zlLfRO+>Nr!D(-bJjld_x-f7Ue0J;QAk2{a@{&z9@MVN=~2`Jp}=3@Wu$%BGo2= z);3Slwk5)6v1nS>?#wJ)dndc#Iho)RtRTA4m1Q?3mc0Quh*uKZGKp;{BcUvkJ~Vnk zc`BU6wXD$NxPpr~opmXpbtEBm2#xi^2&gx5nh~L0xWv8Ed>>Skp}*y&Y_#kP>w4mA z=5RVQO@?p;W0^Kn7_zZklSwSeD9?Ce2QTA^3LA8xIpZ5P3AlXKOPa(E2nP*NnvvyL z=J1t+CR3ekH0MU5r>@boob<`x2u5z240e*yY?FzPjp6j`)af;{QJW@{FCC-lNYaN> zWaCuY40f_%7;`U~Rr*I}O~vJqc~`5-KF*n&0NI|2hAfy0gzdL@^XGl4tEdP^f0G*S zr{Pxc8+cm8ZaPK~{(6(#OpFIh>64iV#=aHfD7UQ`(MbBBj%@5Vk@)&CoF4a-&Y^#4e}K~h z_Zbrr@)gedEF0m-Z$E?kZs`oaJ*VlsmyPjEXnnI@H{$)+RR*w~XaR85?wK(Y>Wtxq z#8!g8VA9k($WGr-yT)xD5Jd5WO{TKCOU)MoJHNQX|YC#7a{~wy*T6r)i)hY zl+UIrb!H5T%Ft1{4f@UFfQH`WsYj~pOvAV)9W-p2ntqB}7WJw(iL9#EAV70ugoti_ z+drc75uQE)#3{7Ewe_{! ze80Ej7?jXiDA6OiGmSGW%DIChF6yD9Js=9-*^!XmF+p92hKt5Af|TyBl1_Ewu&GVb zN@}}KJo)DGJWgF4sTK&T3_tTC9_H>URvkW`tyOd@DN@7e>hFZr(oheV7ZFX>(bUm- z?3kE=ZO*&RQ3-2pBC_)HybSMy!H}gaq?RG#nS`@Oj8S$L7S>i6`|xHuY)+mCR}2iF<}ysJzt4P?3DqModRn15xbj3akCfoqG|ajcE|tV6mzn@kl`~D-IJa<<(N*v z2OUIx|D>boU|rL&U0`+HTsrW6#uK|O^yTQ+bN3tCgUNYycktn*48iR`Ec!F&L6@Cu z>4|4Uwg7p+mIc;2pIJsfOqL!yI6=}eD|P>Q^pK`jxE#%u-iNZ<2ZDD2pw3E?%YPPJ zlGEWx;k8C`o|aLT{y^B#`TDauGgtwg;`g!md)Vqkh?ZPf^e?!Z?60&`$AS=FJT3)M zqzGfhl`$;EjsuG6bxqp@uUKMekdWW`4!aGGzRwjwKt|O0pFB3vx;+YjO@!FL?D9@u zK#A?((bs2Bfq={5+;?L#HKZ?T%4+*Bbh!D* zyU0hWael{iS0KG-V6c!PMwNK6(8jsDA4UxIfiCh*Wc=+{AaP6tQ64@aJwJ ztAVW)GGJCKK}X&|-`cdXWQ~1g7F6#FA6;nX{YuC?&>9VaR)YN{UWtCOZzcamF@8fbiL!TC%! zw!RH4P0hVw#67%h_;BcHTHbE*C{pL#-^^KB=92uIc*+q7+tpQ}NfB5fY&hp{s}SJI zauqa=ptHcKF{=%SLkrqSb!iG2>F!4ph1``)49^h@UgR+$`2Ea(vP)YhgR9*rTjyNl8uvF%nX zBei>8f@?^K;%YnX|9oWo+@-%kaep1zIlxmJ>hb88MQ3*w;lJsMd%rp5yI=A{ zIRNx~BY`oN&*yDHG=$g4%$8tbG!jY6FZdq*n^I;Y zx=32KERJOzrcT4jJZe{X1@6Sah-j}HdWIcWT3@%)h<=un#{an=@|y+>*Ufa|Az4D2 znm$_9fjePA&kTiZF9;{GHddWD4r7Aq1nnb_W(j_JDiqXHJtTca+c*hnxFs*;jFoL7 zH{|4$_WBSM@8eyjEToMkqr98URMX}3%|LX%RtANnzHUP@b0V;ZgIM(M8s*MwXWoN=cn2aJ1($x>f9+qT70xm+GjQh3JuD?eVuQyjs$Bw7mmormms zww7%)%z=3E*6fka`6B6dth>)EQs?1P5uQyaEH92Mt;j1#+-%xs=&$UGo4$!F_(eD(c*%VvId)*K&?QSXC_*|sscef7ok?W#yew&W#n6ma z$ukJLBIr}@zGaevA;lUhX~kT(DoM+v`7WI(&9RD}8vdxdW>Mr{a3ik@;5TKDGbkR( zOlB}!f}dfwbG;#hLyb{wr`tjq<<61r@#3q`X7E9B&2mhkwtotz9XaKeuu4&##Upa7 z)WKbQ-Y6#>QZO}aF375WSXn>3)Yb(kXVG;vGMw!g(WNw~}2%(QBMmH!T@ z&QC#R=_+5FX{N9MtI0%SFYSy9QoCDH!E@OYNIffNxmmJqZ<|JLR^nO+`C_UQ<`?Oy z3cSfjeG2Z;rr;<827azf+NukD92y)oyKweej~AjEnl2)k6#rE_W)Mwo3BfB|@<@{- zHMijNMoU|m)10gakmx2hb-n~;H7ubLa&+$m%6oIg1-!_6DS$9DNp*F(7fLUZZyLxh2Rz{ zsJ6JO-V_BM zDi6pbPceY6jKLRj=L@v+lRBojPw=EqiPX2IUr%6668C&sQ^`o72JY%qs;8rVSH*Lb zbv!tDDOD0COy)!DEAi@bVzT2`w-?)#D?Ld=YuXuTBU7N)e0eJTq)bc!`ZBu$T^wM2 zbNvLViBUh3-EPAe26lOUzIQZUb7fSCT_UWErb@XmIFF_J`jwgxWXUg1_>Pb?AflMJ zaF@vt%m-1l7?hrKlVxTRwj4UA3OyXz)4*N{m_#W}5Ky?FOKn;}#;8bKC?Tr9I)%&5 z5k+{VbP0L|@Hofx#X`=On7YuD`99T?u?xZX@kQJLFEH{No>BQc?y-K%ua99ps+np7 z7Z2+f4)jKkyOG}>C9oO2SIdDCZ=G&PbwLE zrw{ySZ7c$XX*Am1We zglte(No&vx4MAWx81g4;k}nIF;4yEa=NStp9Zs;)t>ORN3VyFm&h%)XQwVnV$Wz~e zf69%4S;2Y-ebp@Qfug7DrlQF$L9HpN&ey4@6@xFW)Hh(H)`o%(T6!6B*YeP7noXP?|2ioY*103f@l7j2QFht;+%0_e5>$%bn?`?#5? z9|>O|F+y5~f6@$Ab^(J$LZm{Fwnz?N5nuT&Y6lxJ#jwS6PM1SNa zhcPS5uz%s<>r4}LLY_f}6UY{{oJofz@dN)dAeDP1mmv4Z#?L-l^2%m}f0+<$-UIOQ z4K`;Fx?hmV_ib@`63BMCQYTMu>7xdEMg;%UQQ^Vfd1q(L3rj#BpEB}W(`aYrQ)|7(aUX1z zS1|i8Y%Pq~1{#*e$uXp$yd&mxSI=-=N-^kC;1?_r^A&U{YFbIyQrqQ~IFNt@2QC3v z^x!#H*Sw93c`)<7qU)oPfg2n_&Vs18ItFRRfXt&!{?~5+<$>uzo2MzB;;7h)vvH8- zT@bh-z$2Wo(4Lu0E^L}IhhrgW$$E{AJ_I)f80EG)Jc zN5TVvP+UN!#NNF3F3;;TP_-LabHnx_sZ?P9lZF~%ScLDRclhJCT)1P>Fr3MkfuH59 zVtx74UCBoI8 z)}?EmpA$vbrEgvIYKXZ(gkNB5$k7w|tn|pqSwb(h*M-A#*!@@Ibn zpYcuiFGp+JA$`c&YD8H z>t}S(iOgmx8|}{q639LER}3v1}B?-cp7-B&iWx!2)ut?t>>dvOux^xnDNaBlqLLyOaNyV*M!BiYt_2-m1O-hNTH`MoF*)$z1 zvyIy}o_+vW+*ypNTnDRdnPr?xeHZM0mPf7JZzC7llC7h&vk&1M#N|`85yYAr|2tC2 zUOmR-1H~J%gH!T?Fl^%Mv3|(J-y;dlv*ucUD+gQ9-%G@3Cf|lqh$<;iAD^q@3ZuH; zTEpjCuIC^FX?}(>z8-~yW+Jw~FK!8WR%pmH>qvCh^;B?*CT;5F8gP~g=(#SJ%o<#t zuWxKZzG9*TV`dI$)*3{eu};b3mZ?fP6|&saZGLH%Dek}rP=`gRG?Rn-H!KUpL;?F* z6`oFj$d0-$3R8S|N5(~AK?;+qPtCilXe!UK_4uDoL~|clSofMFZ#qyK79Cj(C%#=l zN+%Gxr>4Xr#CFbau}ue%o4Hn4@%aZ2D+w#|T&+Z}0l83to^ZanVz+`h>Jrb1gcIQL zaFU$K=0pJo18HWU0vcY7`VvSA%k+DKrCa6|(IF~sp!mzzpkprtC)>h=a%tVIVjWzG zLlzOLRO)_j%8too9aE`VCQ|i`#44Ey)zTxXq8*QmgykuZi=<`hMRMj5r83FL61g;` zzKd-uW(48*O2v-R*9clyO%CR8ouSmuw8S4}RqM`p7^wpYLnV$_;6|i z;0gnHTv)ETm&C4X%h~9NG-AC-UIjQ2A=d9yU+gP_gj*wq5zjoB}8mfKG!<}5A7#ujyI1=alUD;Mcy0) zXQ|JNs>1J*P;HBaT;n9zVC;n@c;^;+4#RMsHj4J#XS@|BBe+B2zAXG9Ei7DW!pXwC z(o=_jBRiCB{Dp2BPIa>W@S`&zGR21|K%3Z=biMuh_et8veIW`^Y#kJ(~8UV|G|wdA<0 zk6k<+?uz0M{GWvLwT)89KVeL9#yfH@J`a-BU}V8Rih(l}t_1BeUU_V$jEZgT?TNG3Bdy|6;^skI~A^iSdSsJ1YGF$l=RMR^=^Du;}Epsv&*6i=W!>t zrO^6?Y*A-Eq)j+F|xH{ZTA+nM>$?*V+y%Y0b!>oskzRk#*Yr=yixXO+t{B-U28O0p@0?4ipko!s5yNzVce zXH)clFMQ}v7TA^P#NNQ(ZN^3%e>J+4|>XJDyt#qzMYS~Ka*(%5g zE97ymT7S#kRjcS`DQWyDr>LF*>2-5 zVnr}0&fL`tJ!Pj1#pa~81af;nyE}L#2fNv-(?X_#+k%wU_Nmx1iFHSk82HSVszpf6 zj#|Enx2xv0H~l=Q4$f0ZE$47>Z%S9y>ipx4+!B}h?3XKz#@HmRmzCN|iq;2Pe{1YS zH@-oR*yJzQT5?@&VCWqQ&P~}{+;Qa=ZHsU>?3hI^z~?Q?%2veKZ#a!JH?8R4PO+{i zs}}Ea#jdne>u12X=cVIKU>Ddk>lWH(vCBd^Tk4%M+oCW5{!-hr(-!d((K_K+#abFJ zsEv~qCJveY&z;thjak6EUwuArQIE7!jw*a8qqk^aYccP?q*^FeA_Z#KMd;uQ>vaJf<81MWPl) zsg7d`>2rs}E%7PXRX@ZG-l5(nN;NZrR*ia1g53tR(_w)>bK}8+>66ROvaT)lA2mg! z{Mu!Sz+asZg5%uu!y4CJ8TLbG<)1pvvm3pI@Kd;G_q@K(_S?a?a^cr}uB(+S`ESWG9pFQwiVc)1VwcqsDyRkSI1!zvm~!Xlq38j-Dda|&@sgBXm# zEkMWwsHkhA%A2D6-7+ATE(F`0zIYwK{GX!8SS4wZE}W3|C0zo8{75pft{GBuq|#=? zAyW^9-MNvw*IXse^TjCe;=j$1?)h6}5ziMN`Dm=znHBeQ`INw zId=aj0^YZl>%)M$2mq%2=s>1=Frz(sv?#Y)U$W^juY4`;wVh)92S!3mdSvtOG$AFS z4Eb6~d{iwQ!n1dCnd< ze)vs|@s~GZ+lzV)s|w#kS{oH9ltE{-_!i-y?LF_wnySm&&oA-B_V&nwJG#-GGFwa$S?hK`lZh| z>Sk5{9K4Zi+&6rSw6D}R91Fl(68~~RBClG9!~WNEkWQ&lH~d>qWIFh4Azb-2h`5LQ zD^k;uv}9C$B{d&O&AXq1IS#eiLeU^~TpL1fF|TfhMvDHuuXg}1uCdz!%vf%ngQ>Ri zr7UyO6AXw@u2!)cA%0@pB1-^wawsB03E|$Hl(c@HUM3(m=p)vbu`?)4FQ{`B33Yl) zD3vf~YfF>Cb+iFmHE*(Zy;~|Taa4^h2=G*(rd!w6z9u*Z4>VXGIJI<;IYSa=L34av zYz8!#fZ6f}eW0}$OHX&iSziBRo|3>fOzAgH>31a9rT)<4yTO~iMfDf0%r`FFrk|EY zyG28R;^6!_&rtppY*H;7%>~nT^Um!&+~fD^?UEgF%q|1dnJsY=-(dG#Oz&e1VyZ$r z6o3X`U58rlhK`K76orWbDN;w@r2Bl(IVWgHSctxmAq_9ZqREe;uzQ5d>GgRV6y6?{ zhfmf1T}|NFPeGsS7Q$e8561%pg$D?Z=jks@oF*KPTUkHx?Ke9|^uQ78J%z!M@;HXj zXN(b+O?0v0C~KKw4+M~V{R=I*}R!C5wDF* zA^F00He-exrt+DqF;$PHOc8JTa|L5mFB=sq$0jNV8l}Uu6yO*$9ETW{L$u<4dNNR~ zFBHx@3da+r!dRhNn2hdm^DhCq^$0Ck{&k8e#8TbCWD~E#!DF<9wG`3Rw!X`4q z2_95*AYQ-#Y0x3Q@L?@JP|Vr0KoQn_H~^M3Knz8`BDlpeFcxe8SgnB=atwQ>Wu_zA z46_zs99t#(re#M%Hdi$2EiU!B;GxZ?S+;Oo(KqIykJmtZfF3Jd;Wryy=`-UWV`J89 z)>?&miFqDyELE2j;26wiJwfBJahLoCS;0d;aIC{~JJ6Uq6qa74`4=g{L+XDP_*Ca# z6a=d62SnonPn zw6}=;`)4dfCCCdZIbbaZ3t+8V_Q1Re5RRm5KoBKlea^R^!^_9o3vKMi!}8X;BeL@RikI+l*2!2 zX4^H>?b;cRZA^!DrlaPnvES*FcfwS1<{XZ1S-FQU%Zz7JyrbvwW<*|<9s#H;za4U0_G&gHhD)vg6I_~9PVg-lTA+h!-T)m2C zFFyrn)JlG}0m%U1spO37_;^}a`rod@y*mhIuk+ufs&7`zuV+GI z;&?~!_&aKXLpg#&K>}ms_y)}Jbs!U$1rKLxS?0C{o`*GoF}F%)`~tTJ#m;q~Xtk_3 zVhtWa?HO`J8a%;zk4(4Bxq0dn`?J33y+!ZzXY&Wrx31Slp;1jr%&!!xp+91y%2Y#p zmGO>wleb+74eEr(bwZf? zKdQs~I;6@!s&voW|0P_t2G{Lczh-N9zveE5M|9w9`Z#f}zNfb0v%{NF`LBP*k1vR4AdF!2C9e*3Rr*y2_sJirVEJ$zM!+!YFl6@2&G0aS}az zh>OBE78SdOH$Ss#Y{h%Psp5+=M>JD#3V+s$Gu|nNKEUd~Q^C^r1bf~si%Bg?O&4vX zi#SsS&GY%KJkMmJZCiaVl=C=`P=QAl6fPK91gSQq2`iKFZ?#wgN*8jJQurb%Ra+@k zTf>cU{&B$lIUE*Kv09-8F{ppy*BLQ<-HY@-)ZBBYbNxlNi67oiRnjUXrp`DXBhZyS|koahk5ra%zf z^NYBu8bPn{3!Hbyoqd&}CnJD%w^4lH{{z0E@sq=LMhXB>toZNq%KkHOOzVG?S0?Lf z^86i>dVSqKK*3i0RP?PA7j}q-l~$5wBU?dbV4bU| zrDw%Nl6S3b4gR&!K!R^$vdyhm{{kBm8;>MoRx+`E-X}76f&a6K#}3^x6r8BMP;6+} zs^or>qnlAa1q7arhx6FbmFy*#zM?S1Qs3#utQd#g`DOzB-yxq7GD00&|8sKBq0ZNp zaeeZ6 z?nKBQVPNpt^PXG#1T+ZM3m_0kW8gTWP?E!}+n^q_?QXoGcp1De4sMn-lBGg=D(f&9 zx?^3bSjWt1qW;Ceyl8EWmV{sLr82P0GIh}uM@?DK*OHM$wd}ZH`@g&;noz=xvT^402T zJ#d^@c$(#q@S_`%fkYGb2g-Jb?_je~4j8m>bJZs#Cw<5k~(~d zvcGPgRlmCqHsW0T^ds>gdtG9solYC3Q;Of$HQ)gYh+D|m$AAg~YV&jRh4e^U=zPK1 zc7HfA;1G%Y8Ts!&)r|4qHe%WT(GT%oaAQdR4N+U8Vk^I-fZ}(<##WvZlSYwGKy<;D z9Jo&n9r2r%nPLC^3;Zj02Hunl+g488AcZ$V_l;sE|u9CPj(Ezp=~q4oT_qioLe zEqiI{;qY|r4}h8C#jjseU~<2uz|>($64(_46zP?{yk`jdU3+BA4NMu5255x2s;3N` zLJe(q)LEncICas{Y`N?1LDQs#{pF1E-uA>C@2{M^wk-%om%@|UYf24C^ftMPkSfP= zTURjpMIpVI^qXiX$VVnSL^gCeQ6Cj%!}UBu9M)aByv%2cQ2x8q-q}2fy5gDET&ipY z0IccCQ;3$62Li-%@=hW%yF`SU6_F2pl6=*Nu=gJEGPF#Y^iVQrzBc@b8D`$v?FFw5 z=VqmPToRBMRr8@e*382jMKSZOsacgW`y!H92T3)OGDwsQ6U-mEv7v?dDt@~zmg~Ea zj!zRtY{Z^IyIN|8Ncaa7sD-QQH`0X5AFp>^0CDNJG7LMN!4ac}tU1kGJzO|3EW16q z-x|T)Zhere*Qmk37-)zrj8WRhRBC5B-h!TMc=a;L?4k_bIvsJy#WSejo8Gd1n>IBS zA{#9XZ-m8X(2;$EjkRFe**Koi7FX>_at0E8uuNWmz=!nnFI~VtxOgH3fCW;H{JRoHLs| znJlL?$1fF2ppo}!reIx#+Kpu}`uHZP9-7urEvl&M1#{<`Busi`g`{A=Aa;P49DN9`C#W!rr$;W+F(w9efig5UNXh!{{{`08K>|ZUcAJOaZ6PwI`Vw1`H zw(7rPQ(g?H5TLFiuVP5Hl$GuqoK5#Xxp#p`Rzv@YO^E+(Y*POp#isv*SHZuY4Ko_r z4%o-2UutbB!&0$9qBJrP&7;+(0%|a&4MCJK2Py**xYTaO+tRCxTDuyHm5Y-clF+t} z*ix3i1RM#91%PCw3xcDro6lM7ubY>ieueGQPd~C8+>)#&{Oh!H|aI+ z^C3Qa-*NivM$zvB()*+%-HFm$-I1>4*r#>#*~B0?jz_ts-yaD2Y(!b#Aw<>Hd!&!3 zi~7WjiEHpo9x$SXY4Xq=K+H=ju(QNWa zJkfe3>R5XIYK#5|w9s%T75MliBw&og66 zv1ThqH?-C#sxH1mYY}EIi;1svXR@-44mW5MDsEqZpeizs-?sZe zc8H%t%EogQjK=sd8lpT{nY(aob_*#y9z8AeiBU^eS_*Fv8*EJqVguQTQB$fgY%!<~ z*`0Ahu@+*7<`R;fy^^S}WGUZEiLr)!pOK z3PP{@aAxQ}PP$Qu>1FApq^Jt&UrnNQc&C8avV@GTsulj(FX?{$(_(!WYn)}H3xTTH zqp%P{fvrs~)T*ktt>x*6t^Z-mn&`=ISJ*lM5fwwTSq|aYlP+JrgN3gX^QR$S`-u`c zGC1cfr5+L&iA&SwXERgO)*T_F?wQ#g&fR?=XVvL!eZ6buC{&j#Z?59v`TaTBfhXjc zqtGxkPw#m89*V=e6N77!JiSHtJrhn>UiVqDSF(>(jl{V&Qg2Kei4VBDv`5AW^-FEA zdV_HPDypYY_9-P=oumh@eZ7bBAk1#QpV0{9CdO}xrYfMGgo4u_;z3M-JoI|Y!Thp0 z)5wq|X%^IT>{XGlfWY^$&Cco5#s!Br9r)wNkfmtB96xSl!R7RYg%^jN+ucHWK&Kd8(y;9=-M~G zO@O3jOud&tqm)^iUD~xN=g9*Y#jL4HE54l-Hn*{qySA-a16qpRPE}j#3gJz*bkALy z8?jx+XNE}SAGU(MBstA|Wfj)&u-RDMOVin!buu$&#nmg1^*V}-y1D~TV|69T(l+jE z2N}Cm&}IMffB4Inbpre8lc?@=!yR}9&jW$m4bHTK8n!#IvK7YkF4>pJ+hN-cY4LqZ z>QCkT;&e+L{c-4pbAC*cN53J#|57bLw-W;ODFEw$Gs5L@Za-i}zNdRIhr*tKAu+i_ zT&xYsAvcCDJb_2zV=gza!dVTi`S1pfX)*aNu%kxsTP!>nOeXAvfR#fo{|3fK_}=mb zw@lGEZz!{=AQaO}{8K!(-~`5M#@kuLn~h|yAFXmI<=!KR*wexX?1>9R$bOJd?@y(B zacP{<5N7qyHgFR5B{|}O)jZQfOAz)B;lFUJ$bWB!VQ>n((Dh3$b}BGA&{MYsQGxIZ zDtW-*;goao`oVZ2uo+??a)r2K7Z36V0AhbHd7y#c;@}NGup9jPqFlxfTdMK zmh1z0)fZjaP;+nT)j0Y2LYiZ@WvmW0fl?H)nq-}h^CNI)mn@jtqXQG^sxLTJr#NiyfY3Jr{DO;k@hnoxk6`!} zj(*2xc4sd13hfuscOd`5y<6b@J-|N`=9oR772)73g2!GvOyHJ4wx|RDhA0lJc&c0) zbIzq-y2WFP$c}%+qqtnS#pCH8eReY1S0BbgZuku>T--r17Diz%MrQ;yWY!$i4v$~f zg*WL1lt+LY5N!w3uXt1JyG9J5*WK<-M(A zu&P?~c)CYrD_HWbM}ltDimAb_dJt(VdFote4QMUTTs=622sDz-}Q5m%PxI1!d z);sHo5r#94xM#TPtlAGX&25(E{7NI&*-g^?{XY9IX%6}|fi(B2MOgD}hOWu6ei&~7 z8s}MhkirZkG=Yg-Bp!7C@;xb=w*p1O2Jn!{1JJw8u&!8E{xfK^;TGZ0n>AHT%<3)w zKgNp0zbgL{KmY*LqyK+7R{W2n!~c3NfENmg@gKHSZB!6=!iX?Nmegv2Ar!5~(^e+z z2{tI*5#|lI0C-ZuG$0O zsoX!dRLa&&35|QOpxAP=8MDKKXUJVT^(u?n?3`HtvZXpGG@M5EPw6 zAmf7M^v+{KAu!z9dx(In@;CB5MBeNOl32GHvFU-YV+AS*?k*RiC`yzs57iU8hWtk@ zPQp-2{QqT3#q_Vi-iZ2)J+>&ycg*!)vf0*G3tR@e&}gY(Ze8{i=Gx$JY|hdQc_a^jOAJ`0W} z2OtCS{TTu!33=>}*F#W}8Vx8fGu1(H)f$arqMJxJRG75lYgb`n(PoDYZAi8}F1(;s z)jm<2p+S);!k{gGa`IPUUH-T()Qg_Q_R?%|SvkS1-6%~dpT#r1-JJ4bT%Tg-g3hh( zZ62nzTNe>sDuUdZx5cX~#G)U)1WQlN$43?(#oUFv2L6XD701wi21`?R0c#2NhfziS zcnzm3qr8Op5Yih9@>LY|QV}MRP3yhuY$%;_|GSl8m4XCjRPXv!{VMvJrPd9?O zL6u7RlWdLEM`}LhWV)$`HGON0a}?$eN)Qp&C+xc%YLw?+BkTwu99R-Bw41 z=Od_GT`+0ipF%B%`fWftC;a5Vp%J?62AP`^KDnpMADYzaR0wOW=ooaY+fXpz7v>5S zyBjltdz^>YzkRM|{aj482@@2=pK9@hm1DOosi$beVw}R{SH>w^xc@E+&Rvax5~*3% zfod(*d&*VQb7!#k49{aqg(}0xGNPEX1OV}+-xGJmCwrv}g zth8+U=K-RZvb<3yZ@bAImFd+oK>vzLfj{wt2k{ytYT z!Kt;EP&8!J+!Ew<_E9e)5hb4x^=P)buMl`DH~~D<*CpH?_G@BJOZOMlP<N#zf@o+aMc&x;Q{#_7 z8Es(G6>qs181ro%LDLE1l_q1%>*gS$Pn0dqaqt3u&*KJ&SxRu1e9nce?GBHw2@>L$5OvyrM&)Atkgep{r_5!g1oh^tsUThM~wVCMK@+S_Zx{Tj-6IN_V>%S zYW7d-SOiv}8vIgk7C{jov7Zh-mb(&hCFwQ*js%q(;p%OC6!&kq0nK|tifR77@yoUh zc7M`O8J8X>tG0MNfr|AB!GHo0t&3wq(W-e) z+dbhsz4qF?_jD`ge0l#rWBQOEx&0aJTW!6xfAR^&3ePG_y+(uPIHO-x5?zrCnu!qS zNd^{jxi#P5_|+UZ0rPhfCpa@=*$Z4nI&t#RG`T0axp79jasxqkpo7q<&<-Is5bI3Vw6q176oeZA+VLdif;oQ@0vcuEpsLB()!X5mx8{A|5+SiTD zA(zB|O_fu~C0m*{djBRM?U3n7+pAe*7YuN!395X~3bu_F#z5 z9@@yLGSQIVavX?AJCkDi3oQMwUk}!ZW!In7FMJrx)}RAyUH1FlA@?=E0wE7Z&C`zE)^`S5UPLVerN` zrX-#{_s1j@xiuVgDzlI|IRKYtKyB!pTh`SPW-`847mh*WK-~`=BBgQ8*a6EhSWgF7WWv93IYChUl7BHFz4(NgTeeAwAW`*vocaW zGKN$97PNcQ{FJ{Rb8IjDsgbZ##VMmzWO{Erbj~%#ZOQ>u=}0lL1plzRRB;H4YY`{{ z!hJTA)FkdfYL9h^$B(%y`-;8^+?a$mb!!J`f|usCIe5&PnmY=())s6^CO?WUEvtJ` zO6KhfwfhxI#{}aEsasUJTI5i?Mf3Yuvl!iy?bc~CuUUvEQIpI>pImDTs^{NWUBIsn zEzqx0wEb$M|IX_EV+;N7$)*3X6pj9>Jlg+Vhax6M#xk}5eG|K{GL>`qO2*RtOLTJi zJIHKMHnT=tLjJh85ThKS99!%&v@td*?q)&r`OXjE2X6$IdZ(~W{|#hFOnrl4QgGr! z4;Kq30v1Iy!BH>6m)a_chzGN5!ccG*(>PaXGAC8^zJQxz@@fAP^l@6Bb682WmXe)6 zXX16VZg;`;$k}Ok*;1zM{6(QCvmZw2@sR!%WeWHPo5z*8#1GYzGsoL~?wh=qI z=o;lgGC#tFOqSc1PELM{$KbCd>Vo<=>*Ao{J3dOkWL!zc`Ek`P10wdj{;Mv8Pv>GUNQn zb1b=X(yq%p2SlJAjmSr_DlDjp?kCi!vL+*C`)^Oj_DA_E@T61tv<}tL66c+m<6-ln zSz~iNCx&BZLXY5fn3x#i(bYsvgoA{@qKrioZ%W4RrX|W!!VPE0eh_jk0z~O|jWY#X z;t8b4N(*w+4_fKP!);=Mk)-YBR~%y}Jk=O>UqzVEC?p~GJ2&1<_=2m;#|`c~gj%C1 zCFeKgD>EO)>q9w95d+iX!f_&~+Snfl?x2R)N&O6r`bCn}I-?8lE?%a*O)2*p$L~Nw zjfT7&pjb?Pc}Oj+jjlNf&IXuEY<=nApgiYKRELfR;pEFvf)FS0yZO956)OGPT`8y( zqKwMy+1s~Zauumc6e{DtYzA(aArh@07Nv)zdU$`fl3@v-3a?-|) z4<}q2J&u_|v@@^jb^Alh(rLvolTzSTl`re%_xiHgRVB6QHQNjyLmypL=b4gCc3qMy zkX4qN5^gprKQ*Glj|L96NLOKe02dq)4Q-LyqB@D>I5+o>SAi~c zO;A;13b$dEZ%Vw|h+IQ=&s-BI$`Uk^1@JT~TIWwxdrDlze3dJdIs|h_&g4Bz6=jQw zd+3+E8J2zvqW|z*;4$m2Y9+(gUM`@BkKifCvZ=eqoIpy-D`toSDKHqCh^tiC(2ZJ_ zLoQ~Y;M~`yL9bNWh?60u`y{j^m30ECWr7KL7(Yu=bN`O(<5&-tY6WBL2}!Ii3WYSV za*wf4@nST0H$KrK2ffa8sMerVL4Kf7=1La4T74KCWy|&3C7a(tau;QR-{1+V9SMI& z%-gwll#P=}E(44dc1Hmu?Kr?EW9<+MGyKnm4RqfI`-NkZM3reQ?298) z?wXl}M+_~NSCFc&F~xmW6^#6~_ed0XlN#r#mOamiIx{e&NgI4DO}~4n_<5S5!khPh zyXeL(w>BtAQU-?Z3jj*Nm0-Ua6 zwN2!(Ab*B|quCI7v@a?t7ocT_DzFR z;&$k&@`=imxYPf!KkTW&8Tm5oa=U4_?TO23@C-q5hl=FL1S~f;+C5~|9uBAXR@8Ky zR{_3MxP*XL0kP8UChkZtAbs`(CZmajIJDlgNYgVcUnq}`$_1QCc!FgiGH{Aum zN*R7UkirI@>5BT@&al%H*s&Li2i&Gt#zT#~a}Z8A9@kIw9q4k>NgrS9@0h`MdJ@jS z+C-B9{JmrLa=yjgx;ujFLg~E{j=*Wbc6C^QbNJ ziGY-7t7<9^uvf9M+BhEbg2Sk04r5vmK=9rZ!p67nX8pHE_)-F8PY!noq`G-eSR3JV z8*!eed)_fq6^qoN(^bRJ+frs&Z>)cDaQ;`(oylKJCIZ}l#7F<=$r1e@L-oJoBR*X_ z!2bbP1SXVKET!8jX3peI@x<6%gR$C~^mgR{|?^SuI&) zPL{%~*jGy?pYkW4cFi1+)NHD)CZD9APPB6}-B`i#Wzr_?8Co9K-8wxF*X^b@cs`#U zAiGW6&-&mchJ#Sa~PTaNNiN!CWYTYOHNU(xC91< zteu2nP%OK$ASv7RK{+tG4$7SS7SKyv?nknXm75yy(f2Jfq%w2rs-;Ay%FBzZkpXCE z(}cL|%U8wyA{XOJ)d_D$_US&OW}|W{Fa-Ols0>HccYnErjSFK*Z^Ca(pUZ+YbvY&S zwwf0*+xJyOWjwX*lLn3M(aFt6y}U=kO>$5c90$f(0ccXoIp9s(WVXBljwA3N(+2Gyo4k zY!Jnz6Zk`7B^e@bphGWaA8J;B4w6}cg$C4+MdoMqCM7m@O%=WMu?j>*$%-W3Cq9zf z&yZfZzz3|QDp@2BUP-Lmej&9)pt=)qIv=M}sbdyd6&P<)Zk(9GB<^&eX0d6;AurU? zlOWE3m0s0sH;IhjXqKRIQEq5m0tS8Su2R6e>y2(pIFhpwnm2{JPF;H2-k_kF{=G7Ln@x(2$)YJMzrbYP7s-CN*w+#ZfaXTPUZIeX<8Lyx zoS0c#XC`l`)pUEh|8+PK8SoB~2?Kgjz_VAF>bCHyuZLO#UZOTv6uv zWV%9Iwhq|h2BpDflhLtD{L>5n(Q$O`^XdZQPm|YYWKc8>?mbN)&gaF=#YWlg#{4g` zBDdfrV;$V*uoI=s^7^O8_^bTdLf*%cNFpO9Q)!bKcrzQ3YnQhgv@FcByrRJ*6l}{x zQVq^^_>#0vlgR1EILL`NZr>fjnv+}yr-2tV4>o$w1QSkC4oGW6VEdme-9Ty96Bga? zkogv~w}dqtM>*HuCh!zPl%S6W$koUr+286xfH)j|nHcYKvhJGex*!oE*L^&Rn5I zoEj69s>*<}PTypQKcYR%IQzK6?BET8JrnaWM}8Ne4@T<^4nqSXqW4C52@>#U4V$q( zA$}n$2+E>L$FCF@SQeCveA7|oCS&L;&>|^OHa;j=5#LIZ+MPmp)cA$?X#6LY3n@_n z+tJQ@Xrncf1^&~o^E`NU8~!8pXj|>L?12nr#8ORQ=0Jr?|B_tKieSWt;ejO;n>=!P z2O0%loJh0REmLV8E6lm80C@=#RB#g30$6Ym*1{twQW7h(Y;*HB2ajw?y)-;XhTmFc zp`k1!NrpsZ^|Cz+Fno|7okk=f)pQ-i-420k5UWVL>0MuJ|Lbd}&GXag?|D(J^!_*# zFN*DN8DMPR`~B4OGP*|i5pX##>Nb_E4j+#!lhitTlrB>o+UYhfOzt0$kEPqsg1kO= znOA5U+#Kh1yx+cO$q{=73b{+oc=D=T%n)}-ztNUxbrLW=!uKo@yp;JDg-zOrPfm`- zgdFj{C|^??1Y-bA=;mq|oD$H)rKeG4l0xnwNs=BAip3Xcltf1K)J9MOFqMY`;}XgM z6oF=Xp67p4yyiXM2Wo)7eT#wqk8|Q5_h^ZKaZZQ;Y%NUe|Ep19W{#!&wK<=aFKs4a zyA5?bShjoq;GG%;gv`Bj0v1mk$tABnl-;oRP~f_)k1(GMNzO%4SHP_@ z>)UJKhM;~LN9~J&GhcvdT3=@H8y$@z zV+U^ibW;M7{KOfI3aZKHoStBKc?%}o`My9Jb3+Kd=7-F~AOarl!Dc~2cY}{4q4Npq zDr(vJu}p?Zq)n1qJH{DS^tpm=-XL#^CXr>paUTV zi!5mATQ5G&o1K~Z<>sga^M3)gtVcL{pSm>rx?L$4qgm0KfvIYn_>2J45g|HQBdB?$ zeX%5|v0x6biB)QW6;4xs%LC;DMhtB!w$?Np5zo;$y!HgPAg|F@9AbmIzQIAu?>^Ns zTLDs)*ZzY`)bt1~*sDDZ*Rf))j*_KbQ|jy8_3k4p@YtJlI-3k3I_}e!joXp!q^jK7Jo6 zy_JZE$%Hv%j$k9QLUT3#63ezDdSQY26&5Ak8Nbw4l`b6{@ zgZh-1Y}**iIT)pp{oc7Sjd@8QU+4uPnDy=V>K7_a{$Vsj>D4!ch8@yyK)gD#S_p##H;cHSc;wZGn1i>8_4BNV%%pUO2JKvFhin z>CwCk?pd5fKPb&Ku4jIJH(C_v&c477~RZm|};>Ei@mXtXiT@4>qC!g1shX zIKQ{-$VhvynS9HWN9%Cb=@H|Erj+Y59ct&8VM`98gPnUWf z8@wl#3umeqb4eYpr1U6_Mi5(m-S)&L%R%|h;)p1ya=F#hk7HlW=avlqt4@mkOg>$e z_{Zx=HfY#x8{6-FeFqHe2i}SV?7Synm6krV!pR|52R1FBa<#C%0$J$V2>haHUNtZ% zW6+chytWIPbE$__FySpN3%EQ1_KU?Ao8aMyKDGD+7(44phRqIvd$t^lJ~oSvGihcv z;5@J1<84vyQ{&M0(uZTOzo{bu=e$faU&@FS z`W#a02AmTi8U9pfv-xmP@u@J9v_vL&OeU?8Cg4pBHAR#CkrwWvtDu$y1ir{olr}R2 z{b2QKGDwG1V0gAskbELit)hwgPFbtY1ilH^VH?r zX>Zmi$TrA2GCwN}M)N|q3X}!f60F`HZ6F+p-cc_;t|Z2C#pnB;csa{@A+Gb`?6IQ+ zdUId5t`GM~LdT#d@7nYgxDSigNSkkey|QBzQxfX>s*O>OfY_rw@nO6a8}k&86+**c zt}?2Gq_Sy1xV(dHm?ep_s#azEX$qjIrkQdtK4W&JRe8$!AW*&d7j%`}BvQIzM`ns6 zq~$MdyC`Pyi~Kk<1yiF(h}9Bp3l^YKouTRZt4B;LmUg*6#d{0Is21f)Qq&oxnXSBd z^1fFjmSsxVawI_Yzw42*v0|jPucXHW@U_FOdxAPOXxRR|5u#FSlQZJ9q-kevQM71% zK*f+AQGq6;a(UGEGO0#Snoek5Q%t-N`?^fs#n$Z_h)K0XrxY`(at)R%v#t!5o+6`o zho(vTEtvTgx3;n_?66n$jY4T~h!m(q)kx~I|VHAEjo*d4OY21}4VQhQGY%Z|-*dy-9R zJAb<|tArPLkB7hH=WFLusN3-_BjRSQdL`n7v%`&TnD*mOOv3?k=8cs(ATwh<=d#UJ zdV6#SN8OPL<_FKDU7lxw9*d_QN%}JkJ2(N6lsnV=K)hc}Z<^Gdv+mo6{`$HS zT`_686hy4zijGV_(z|Kdl3M+a5q+PMCKh(d`!t(_oH~JAe(6{pmV);4-dRUjf&I=& zY70b~#WGS@RD$n8RzR0Bqunj-!egp>N4B`N$f)8=Tk{t6fA6ED`)FpYIGDn>g_-ff zV~Hbq4enacE$AySZ>BC&Z$Pv`LX=G5T}|0E(jYj93L_*o9oa!dd-Ej`iw=s`$)|%WC_R+X8Qm z)avP%cc&IjG-_jk&sW%Q$PtHw2C~G#hFLOgG+!;pxJbo1bXGm5SdK!meA$CA@dC7D z;@(uigIi49Rcp)$RH*zrpwjXNgvHscwVtLtzi+|F#;td;!Ms0|4jv$gaVkcu7K7*b zb#>5G^9}Dj?hLG>G&pox-Mk;d$r1yqEII0J5bb#34dftr{;t#TdQNx297^-$pv)xMvZgZOVKan6}td9-^l?SXyH*mF;;4U>Cd zAN(nwJ80b9HtxgExA0QC^6LS#bhI|>)ZpucBo_(X>$GmxVnWy6SoZ~*$%PqY=yQc7 z@L^8rrIST1yTfrrNGV@vYYrUN8~BJa^E><`-|Ppgi=2B^5WI)x8H-hy)y*Kv zy;o{^g11ha+kofn&o+9};|k&X89E1=fUo*8zNc`+&D!tRW!?|ZZOXq0Ju)kT-o39y ztp@x*PM3cq^kn|UMeQF1_x~hwRw!Hi#p`)miqsk)LK4UjP{@%HmDCQHCZHGxz-dYN zAPA7vw^Ah;nAN7OY}7M&It*Tu9!X%Ihwm-16BZCMV)MMBzL9#$Ol|l_Um*}eGk%eJ zNgk6flO7i<2T@&KZZJA%Cg@dqQoX_qoXL=Q;ragR4DJIx?f$^%69YZD{%Z{P;takb z;AX15Lkw#DI>1@OY*C8fh`HLgTLRb8z1Z|MG`jq~nt^|)r0w*_cA?}&=fo&YwH6pO zX2vxpnaqic*i$G&O^a8s)titvtescous4|E>(#0)0DKM4a`&2r3dgy4}o(P z8ESUP1*-qrz<2zR-I&g>2`m(`59r}Av79j%mt%c$$8Q>`03`SVjKxz^Q#EC&HN(Z@ zv`F*Tphg%4IjC1xX6sF`NxVoHFfD!(@MbV-z(B5rkysSTtWfo77_i`2#e@DbAm-fiHZvR$IysqEup=4T;p%KZEScx6=Tg*;4ot>X$7VdcoqGtO@ z6(GByIkYwaipE|xP!q=kH=Gf8^dvWMKpq+^K(!+uScTd9WB}?=pli?7iG#{Yv8__7 zYn7%HdBGo141=g5@0Z|W$iBfe#9|X^%s4=y8L&t>O@b-Y&e!bgBuKymxr0IW3QaA6ps=IE_!C+k-&%&b z{c1}N?%G^F#Bv=nAm{$dmezdp5Ci;Uu;l42TZi(tFb<(V{cJMVrq?uab?sHG8slPLE)^T~10^3g2X6>fLWt_j|N_^pi2$KtwOYY)KB+`<^ zbs!WPQ;y_13thVuA?#+hjr72iB*vps1#6t-QpT!h>I&XZq4(eB zuvCq(Q>!?sjyuG2!i8R_2q_Z=AddK-yLuY=jnG=AZpG&Xmt)+a2LvF-Bnkq3cm(tE zE4=ml2^Gz3o%_y(Pn-@l4=Q{GGY%RlBO5DlVHJ9fTnC>glnU^Ex4ZKb zR5wa^Ld{JhHYcEq_%KYny$h;6$3*LZdzL_rstlRon_Y$#Ej7$SZP@Fp^kIJXfFUtS zoQ35g`dCwj(RR2zt7}DOj7% zlJ4t0E;&+-vS7Q0a)O!%?)xOoHGWwy8M$jPmplUX(N*nwj9gFV2PBKGy#zCEhSh+b zD44>v8Qn+`Kh0Pc1mjkWGq6C9Dcn5TGejj}>t^wncFJt(fOqU3XnK_wieb->!zqt+ zZOGT&4=#J`K_2gK4O?=r*c;x$`2&~aQ9RSn@4>R1LcV82p0>}_Gm@u8SP=+i*}*XS zXih1WyC4}Lb`@y`%MGPU`l~C973aXQ)jdgY1J!qTLSAMN4kKT7DqL zcGhwJljrTQ&(=-nBLOmzUbpmX)vdzgVP&?e>-~<=+a`W)Scf12(^-)>t2)jke?SU@ zb>L171VjtfSgfbs7acsrWXY~i6R9?ub-wK?bpS=`MRFdLs~s z7MJK^Pz=GNLXmqo^9S)m@j5K0llng9DkSw30&*G#fV==CsG6hve6cyX(yn0$-nJQw zIFcGXt_X1l8@M7>vyqFmyq0&J*e=PxyusjFbHEBXv12=Q7aDu%+Y(OdS|J4T283l< zvtJvK3vUmo~zL;~o<>5q_t|qT23X_C}N# z9ijkK{12Pm5MG3HADTOB#a(uxGNi#uPQSbOYRHcCx%zHqqU=4WnSn;kS~koXvf-R4 z1)zIG2VHMAUN;yuqH8Qd|9;SVUrJ>(j^9hP!85~5Q*d4w2e(D*P$Nc!Ek2IJF&Z$3 z*PJGxAqyf(XHf9qswodxTEVehzujXF6a1U)yW?M4y0r09(c`;>8{s&-85VB|W9d0v zInk;n9?)!~VuB?}UgP**RjBVsVWS!3Vid#2lM_SJBP??>Sk4w0)S4E}xMmR|V-^gk z&Cq{Q7mY+FI)wWtGVV{s&BAu^pog<|4vOfC&=EHn2rK&+peHs$Dau2Cc}s8;K01yh zZiDq>99o8KHxFCJI9Ct?Yr^Tvb%4r}d(-Yp;ka~Sma0RXws$mt-mMJ0KKZw4Z}Ync zL|s9%Tw$LTH@>EmT8C*QMH7rkhQk4d9gu0^9pY@zXc6yYb8wSFY7H)VGs%RrAcSOp z$DSSLEfX;_#Av6A+3pt!iDkU587(S1liIk8Cjd#a2h*--0dIZ+yAP7I^*8Ifhbjjn z++jtX*u2C3h2N5*^kuGpeEU}LPoE+GtAgx*-DeavmA`=71|naeM6YmPP)WsCfLq*e zjsXG-jNj4UBB8&hq3oBP(@FHj)A=!iQ%iR~ooQQBYrpKOX|~os)u7z3Xz$U=Jbuv$ zf;m))u#cH`m+N+u+^-iY&*xEDkKduTb9`Y84A$k~_*g=9!^zMFKp_U{Xb9m2Ik*+* zd~9|OkRvp)*K{RX%`aNq`fbjf;}qq);B&qsaropazjiSx3Ec zPf25lC2Y}1ag4q~$m{#@ykuSJY40YRmIb5z5ZBc5y_->o!`RqLCSdWV9(yzRG*aIM z5zzNYtyP(eN^&6)iF)75RPYR;h^ra|At#M7n#!qf34%V1+$CN_(^em^Mj&pu;^4nI zukdjNfLke0?kZ(=kzUEvE;(*7PN}S;(Y<22M1(&_J1Bi}E^SeOL49tx*aqeC_m3v& z`1)AiZa#`dF=STuRP3? zO}z05G}Eov32oXw_$)b`Ud6bDr{|pIhMqf|o7I(!iN+f%O*?P8L-pkxmDY&^lFo+Q z(eS48zr_MN#0-aHQ#RqR&j1n%Z!pkfX z>kT2v^ALR|t!LI{M5h7hnKBp}s>M~9lA}`sdPkJr!-DV5rjkx>K^&At(W-|R5Gbh; zKOx{N5PCdfpT9L-Me`W^katfELceSDC7Zh2(bOQh?&z zuFdMN4FbUg*3bofbfn1dwZNI3HVaA9(R)9hY-r~pYb>~a6#B3uoLPbxo0R_$t5fIgf%fOeAN6leyBR+l_4x+)Z8*b)5uA~N z5R3a_*erWyhD!?(QsoU|I57YLt%!f;^M2HB3{5AtuH zL?_L$OPg@KY9L_K$~Gf+XL~;0obBg=aC-e@d8NU-QNR>51As7nHGy8EF9r4tProfk z@g`#WVO?UR_$Tilt?##rwTFjLan_z$zWM6p(rO=9HSkdy^ZEP8{p=P?Fl|Uo^#^Wl zx6cp!5V>4hGji3PI&F*5`{=AB*m5i=oO9MN=$+Jyih4}xwdCge7!eaeiQR@3zKXT$ zxmNF^mKf#D5UK8CF+;7Ab-S1({DpV1<`N*8^5DwR>Z5o0=4^^RnQMEB>oU_3EtE5e z9(IMygkV0Qh~fTV-qu;ewpbWpn}TjfM)?&Pp~$w2sMMrPPp8WO_3{D@p=VoKF`QBQG*mqmgG0s)q;uLfMsx5>MdiCh9%p)tT5paKz0X9|R2 zSI-DmfllKqmU2IB!oDz@eHbpJH(vHsm{2D;YxP`lw_&rM%*?bN$wR*ErMOleMm`MX zvZHdeW_UCn1_S**T;{CQ2b4K?rF^z@ z#rj?7+6nrz`xZkBZdJ%0x9@!hq63S?ZUpF%@pRIhlA;}wk9yN zZH5!pmuY*$vqY|O-8#U(Qc)y(m$xtDGL1Ps)SgNOUxyh73d63p1&pQ47+JZx%mTIT zG*c0*)W0zc?4)BtIx9>|F#7`Xn|w`Xp>b6#25-eb^`FuJbc%uz0Es zR8xG+NNqB?qO%orU6Hxo8ij_VulWy)rBa1? zYDc~D-R!BD(z3@2B3^M`QU~fiRL8dJ(8eku+;HO{s0^vY)hMm7!JwN)_16=O zYk?c{Wg=%Z_A>**8fzwd<}kb3!?W5S&v@1ra;v%4{MnH*83R{yjdje>E6nnpJl18+C4H+0-3i{EHF}x6tqX)iY#;iv_o}0upDVcub zw6r_ly~Vw6OMyhCeCON`oCl{qCsm>okM zLmqdx@*!~$STlpAF17NwG(|GA2L&FsGWO7VZj*$|(_=2uu6bpAFw0VbTkS((=)5LA15mDYuHavRSCcCS2q0E*HU)sm#c58;7e0CSEP zeD?y0E|_F9jjNrDqq&f^;pCS_MJ8JTw7$O*5%?vkm47QJo0r2COd~_Be!s%%On{Bv zwHoswT8kf>fP})WlB(D5Jz(<;wkQj2-7qqMAUkRtpfyeyCmMz)m_>CP;uAJ5>+^47 zU>_)kXyTU`i2I-Tg@5$b2>y@fqMVh59>CV<-`__4eGnEXZP_6zB7HPI*GSeDyg?K; zu4V(7WcLFRA7( zHDv&i_pE@=$jw3@hm(axNhZSpu{x{N@aIU;NR0Kgw+~Df_~Uz?DVra}{PM5}$sA)r zcUq$uAFtbDacGSzKxrA+V=>>*Y?0#RPrN0j?UsUT#;?3Wyo81`TfVHNFgpU-dJ5z} zVhZ*~7dm`ZCx7H7iiyKZ2}c_*(3F^CnhdsW3rlLxJb}|JbZ^dmMUcZB)M;tpAHf!0 z%qJL5Cn+47`R0)~#@TY=X)PAYBIi%TPLKWa!UXAQk(rUJN{1=01~7{5`}Z*@RAF<# zl!w|wB`HbmYG;L?IS*p#uruOURP*%cO7*Pw6#m>U3IbCb6+ouQP(ZO-g#q`KF0Cu` z_BIMG*syjsVXJ2;M{nZk0=tHYC(6EH0<^}cu0;?jRQ9+16`R6#lkrb$^`ZM-r%oYT z1Hsslpg0*?oQD;1WnU#KbW~M0Xu^0?eTTSX!%^m}QL4$!k)gN@$H>vvRQz>2NaX66QL2w5lp=s#5V305xAX8T zb{A|(u-3@f|ICt?84d?(=Q#Eyr06uIm92w*261fIx;mKH``C4JsaW_u+r8wv)#Rs< zh0IbsQrC_k6lzhEYH0lwl?4#cf1so>Bp#1c*6834>6Oh#?A=!_NQ{+XkVBF-eJ~$( z9Higc3@5n!fT)4is`;d_@)C*+kQ8b#4uiO~V>HA3UV&G_{JoMV%aI2`W`lmbpT1)- z@0T4XxDk$(levK5`k?nSbDpfJ{AY6b@`zP0igoTKMO@~M9jE1 zh?A9_Q*IH-Z^*;vMB~nr9h*&R4r7#%68)rrbL3wH!>kdSKc?uaD#2 zxSp&8Jhc+lRtqfNS9L=`eVtB7%lz{@wi~0QP1)O_4G&2<7Ef*QJNzC6FIJ(FTI1jd zl!~oiTKqAquT4oE4V9GxYa*`A54ql($X09~nHwzdoWi0$dHzD}*~b zGGVON?I3+PseL;#JM*LXj;dQPjm@ko^Bl&R!OCE%+k<}W{8o7f3CX6#N>+ymEgR9X zV%w&^CuZg*R1;V`v>c1cRvgy`Cu7BVTg6m*jkVYRd2WUk@{^$R#-g5>U%@=|iA)Gc zBNVkU@13uf8X>e^vrVeNz3X6A`AQgQOBhIWD*{w6!2gy;)Q+gh#oj$vp=FUs7w3UwI@2zrEbjYm@}^O)pu@yzNhFhhr9pl6B^Gh z;+uaN%}ACmq6a%V>nIRd<1@Dyh8HTf0IfKB_Mz5U5sknn9YXwS@HQmpRE8KuF2yryEFp8Yjp5>?u6{+ zn0fo=W;W|DD(2iZdVu^(N<02fJInujZRjpAf5^WE@;WG5#Zum+$Zh8Z!IxHqbBDr=~L{uEIqN<6j8H0D2fsth0 zsnB2s>vPH)Q-r~ErIA&1k76I}s#+uw^Lp)(_ zcW;GJ_^9f_kdvo@Kuo5y4f{a^{3(3SDRpFi3NqNt~?6HDvmNZC%b= zjyXQ-v00nsl-fvZ-Drn|ld(qsl=zJk85mg*d`EzCRfaFT$aIn$8AoTIRbwx4icHY5 z$2{3U5aAQa?5XgwmKyvSaZn>i^G$!K{GHl#rN&h2bf=80L*T zhFfbEanvD3D}H zda~JHPWQ@|qRDO_0?zap#Q`-nea?)r-pJjLKEl{SlD->&%X2MrNz z#9%Ky09H=oc;dsm2lPlSjQkP)WMUR>)$i?8+9#yQ3k>}L{2?YpVj1|Ua9k0q)O9i# zo_Mzf&5j#7hMi&bD}Lvr>&^3j#bL-SK4hcBKElOx^`(60OcWb^v^Hf-fSSqU{x;FF zme*v6{wslK0tcUhD4pcKxfVU?M}vewIk@$j@tMOh zu>Pju3dcc$CkWbI2!QNUyI7fKzQ+&R7$Q()IWY90vHWYX?q9d4f3>`<5Xm_2FPaAY zpSC>V|1lg@u+_B&xLTPQ{A1IrP&)k!kbYX+E|W;6-iT<5yO2*40TX2FWG5EVib&$t z=lrf&JU0|gvUKEFk+eX^-inePqAm6dW}{$qH%Oo9Jqq`HteS@Xz}&sG6gvWAqnn+~ z%yhfxIQ*Er%(S!g`g}dq{(k0%J}7iIas;dY%}VEf*es5Iu=rO)uaP~TL&%M@Mb267TMBAvY zvlP3hrH+=TIo+qX@U~mF^;XlaPvYXL&)k6;*c)fYJ7@~xD@4qvATaWKN=6pNy7!ZN zs)$WaaMC)okC;T@DUTX&YlcoZ_PNW0Ic~S1{61dK6g4a);$?vPM)#Qec=39|Y@EnLpCN8}D`hTyE@3M5oSJYq)^fIKuF6VVR^Jsg;kVD#EFdLv*=Pv5MZ2m`)9h>c(%h=ylz>KPhyqCco*%j!7qYCZU) z1&>=zi+r(<4i}TxN~2PU&h_f+n&fDMvz*zIDE?JriF@gug`Co@#|j)!Mb)YVO{mTs z7RO=$$Q!i#u!=j_Vi=E>QpSoM;S_D`0BHTg2MDV~NeM!a#ma`RXQWLL#RL@ zWJl82mC(V$Z{*`{lmRHgTnWf4uX5&+Z=uCl+pc~NZ7m!~2waTyEhL4%Bug9Lh`448 zgIl#M(ia)0r}EUTtY6I3YDFNODHXO!kmU0vkq$MD4DRL6p3nIP40>z6A!MAC%=Ka1 z;de?xr9il0Flggr)EL2UbbsxTAlwi{+c@y)is0TL8n|rG@cV*<*PHi_$var`yT4!u zXc!`Hk7uK5=*W+*=}U1cq6N3m=vUVlpE>V4uBf*SYc!v59L7oZ?Q@9hLL==}0O^Da zL*EJlitvI&XXxRPz)hpjeZ}4E4Yvu{cQvPDI#Q8TzY-;iO(?=4C92RHs|(p8R;SEs zy94qE8aT@L=oy+u<3Q}1)7;|U6pbGBY&jOnfs(sL6`_=do^M4ph{~^Q$X$mQ&*$xJ zbvYnka+nh7Al|-dUXfH>F&g*{+;s-pY7d}y_JDL6b^6K~R(tfjAeqLuxdjJ+afCA+ zu^uQx1H`qdjupixpc})ab99RWKIj~)$eXx4yc4${?KAHY?%)5k-fi#ZqYC}xyG>C4 zRqOC~zAO44gTIW0vAo@&Iv<<1B&^RZOk5Gn2zvJ(w( zDMm`hr5H*Jece^`QVWMfNuVr7J{vi#-wjz?nv?e3T9dZ5bT`zeR720m#GsUpanKp2 zFvoJlnPkKHsI*uVX1cwn3eBv=9_1_ImoaW=)4r(;oQl=@2E`hq8I4|{Vk+V?lG$Wo zf#(uY?6Xj*dDCeC^K_eBqHjM}l{|ZpuaSv%oUc_zulB?6`4)V(*l2|+d%uWg2yMUo zSgSf=LaWFj1)$w`pc+FJsuD83Pr@Kiy-;rI5YpYioY9bNwfO3C;2u&-Rh)Gz!m|~t z<>YO_mXc$-2uO)ARKVm$nWa=WWmlkU;UF+c9ZL);BuE)IO&BXz@0hr9M7Gwc3?~__ z@<^Dm5_D(D5XgWG%#&JJ)85dY7|kFxi*v0}H6V^LR+mjfOjhYA(N`MwQLKWPVU%bk zw%*(`Dvj1eiC{p{CBRS+kSgjyq^Z`qQOQ(t$c7|a*K8t})rx;V#|q=NpVww|L0`(- z>SxLccNY}@@gC{4k$4)NK3}h1AUObvgXSPH==o`5kCVbsunXnslBzgHm{$-QA5E;t z2_i{(;G9^r*x_6|RgwGg@c;;{LxW~8_cYXBxLu}sZ#1GA&b}Xb_V=0Wi#(NkR;f5z zrP{4F8=lZ6It*#cGS*r-ZO-wGK3_{_%SzfNk+qgjZK3VHRgOLMnP?VSZUisi*A!uY zhgR*LfHM`hMIuqqZ1IV(ZfvyS+;{G-#IGt3ri8NIj25Ql_|X%jlr3J#v>6@aA z>8L4IVHlsh)Uf7!6T8*U>TAMYIjueb zu-7zgPtov~UW8r4a9snQcDFWnz^D%3xEDLXujuq1VU;nlLj?l+DQ$d6%Gv$sRSwm- z2gcaY=!OHZ*?py;nUrh0Tkcbt4xN*-^3Y5lB96;4$vK}ILDAy^H$Q)`ExSJ${Ul=_ zmcb{e@BM|*|6LFK?|I05V)*~|;`%?9_J4=BTluzrK{M$9296JndpeT&>{G0X9p0Y40e_j;4(|OLA_Sx& zCpxKkD^5~RA&hO$Ku|l)ZZqyUu50dsO|x$q>YAj$yJ$-ctgPu|XM`kUVk^3}s}h{g z7^UY z)4Ar2`IaROPjyBB+Kb~sB8PVM_7(c+<_yqRAP#Z9^dUU3n=j~W4eDPwqqH=r1A|^| zjJbX-1$;|1K)aSq-jpI@e7GJHxX1eAXpu#1mQ6mhR5t%&mH+qqTIxT(um9z0^?w%& zsanM%f3DNr_apQ%l1c-K*ZIHr`_P-}jh)eIgwp=x8MkiWnH`me zk1>a#437bcgp?o_1hSm^jUPa5{SD|EbWl&VyixLlm{&>FLgl?oWyEtLD;vB%QQk!D zzU?sEY4WuFG5bPK+xMK?|K&;*;qA8|%X4kcFj|^-*lF zPn{OG=-w>_^{llKzoPNo<@;7*bCF0yGU06Jq7fiMy0mmfHPM=y@l9k<=ZGP0XGe@j z;`CAt=91U@0taPNK`nW*>$sW!CB2oKA5PrdycOf+ohOO&o%GxQlbYp%j4R*J)NEMPBvLNUG1% zU1}Q6+>mwr*r@}|I_^RP>LgFzS+v$(Y5UM{asG3mZDfW*pF~NPG;R9A`t`m7Pr<5} zqbjYXi8fQxyw2#bu-8~(nuO`NEl7#d>s`Y0rx%S&oB7^<}mU?%A46Y6A7IvftU^mq>8hyl8ULUqjLh zm82ue?^tN^mcC)UBov>YFt4bt?6ld-u(P|)s9Xc1@DUqK%qzjjDoHQdlq}|3Ot6qa zo;s{=B$L-#P;qRjXC~35$R+4k8F*<4GEl_m_YRxEHjEn9qGlBB`VeSWsaqT znPeu~Yh{Kv%^cJwHJF#IFkuX#kWbmJ&-8&QXiXO8n`E$HHg6RIzFN=G_YzMSGbMl| z2#^X%1JbMwZ@#cfn*TgF$Pg(l_{kiz+?+OZ{$Nd+!^&i9fv5b(xIQ!goQ71xmt-hf$rT@F~>GI!4!=IF@V=B71wPZ*AIe>NgLyh4KI8_7eq*;Rqe`bbHj%DWtVt(qQj&*~n)Ow0-sax3KB#iHnKOX!k?% zVb1p5^Psou>CX3_>Hev1en0Qpgp1P?E4GFY#OUWmnSCT`*4e@=Wel7KKdg1`69^u) zD*T3*3|nUM$4wS3&-a(!%1;N7AH{Urc~X;Y-gsrh@?878^F2PF6S(7My?I>?%&u~@ zm(n)Hf&v`FQI5vqIa8;6Hw9?;ghscAjk64A*E%GsK3Vew3y-QKhI&#qFuSlz&xPdk(Q)06%k4W5r}Bz5tN~OD0c!u1)>nBeQ{QPQH&{U@Slg)7+|`DAuiK_ z`T2iuNcGw_iR&g4R)2Tl^vA^RUw6kIJtnhZ$?g_ACaVIL+xF!i=Q9KuFrYlwh}?l_ z-X@=Mhf84pRE+=)`=e6kgb%15<@XDr2MPGorvy`s@CYZ98ut{5Yt^EY$%cq{f8l+m zT8oDKTB!3Sz8fwyNwY8@R{3Dv8TEGL2|VO*Ht{3z7ZKsBRS|ciBCaL{{P<{)(MaK} za7QDW9n*jjUQ-+Z!4@vhS74VKk*p=nEHyO}1F4{SYO1J_lmA}Js8*Qo7P@7h zB>UAEBDuknF$A>7!Bp?(^fPPoQhGPqg4z-e5ES)72FE<2RpMYKrM|)6jK|5~l&ieO z7&k@-dDlWwr&j>iC4k;F0M!wMz99ntF8<{mlH(PF>lzogR}TaM%N*;}{FW57)gaIS z+yQFYg+NN%zf#cH2+MAghPD?!4~6qi+=e*%@$+jF4%YId^T|C;#@G6Aji55?JhZlc1?mKw~K-5k&MDO zG@ioZEz+mP;w_VFW&YdUlaY%dfj1dzR8|&dvJf1cY-l!U7RXRM*P~XMn#*)LjS(6} zqs7mgJtO;<^!(-JhBnr4F}K20yN%-g~u%v4FLxWV14d`CS*`E$^>A5YCm@&XYCH*BJHAR{(`ICm{M zU6;IWoOKqRI_I4l2mG@M);BRqiiW&r7?L-&@>@N zU{JJs4+_+1Hfiull3~&(pfgJ#O{Ae#vw5U!IKRnoxVkIXq zkfyged4hyABnY^a6Y@)PrAlH!Qjvy*Txx$QzgBZ18?;ho%;1Ibltv@OVwjG9U20Le zU73-oMzPr_+|$Jzzv&uIcr*IfJ0f8&n~c#>Y$u=J(z>+mW5K_^0`S7s)?0lAICodo z;rfw;=9})CbDd|-Lj4fLsdsI!z)^~dwx9V~W`&Dsn+g_8W#^Q?jo8l@uWpC-hyFC_ zWnuM_JizGiLJhhm0MM3l)iNzRCd46AC?%&7agZHySF>NHNTC`*Bo!%Xpt565YU?nn zP%M%wo^j`8kQIf@SV)+WE9a3fV|JEpdj$M4z1wd}BZ5jlkW5QwK=J$jx*Eml zQqQ;_rbr?7qFmo#=bzuI-T#eJ7ZYGO8+r{*i5inoR8>X-2mYKUu z-zk`HG$QcfQj1(5p(7L-i0DU`Nbreu)s@<0LU)~;X`fsTfDPoL18-s^|>gI4M&76iRu&Bt^h+U4dnari$zfvY=c4^fYdxEGe zoMjH;;{M21E7XahDlyd-QaI7Pt&py(y2yqg6PaMJG2HIv3YWSf^_05+-Dgan4grau z>q^qq!*kaY{3Q zoUSTwUj}rCy~#%yp;nMz6)|rzjU2c4-W~nriX8DbdXHabE?)q3c0X};ug@J1V}#kY zKs+WsAp|XNaAZDd%^F(yP%wycOc_Mk#`iKbQW^#CV2F8fGNonyW)_ith+#%V4a|n% z>@%6*RZTW~9oQOKxh;?0=fK`tIgM!^m>=H-+!$&P6jF8=X2xDJ63)%7#9lUR@%GJn z+_Ypo8cI4eIEa*EvMgH1Km|_ZT4@W-qaQ;;KLAeI0k!GgIuvZ>SlatQc=sr9)+p~G zHCOD8*|k@}L^U>u8&@dVSHX5pAy^zX3)6Kf?`$qNQQ5DBHQu9~wo8;BTzXGsS!Z?$ zexqW%p)uQqSeu=r`&=!62YBRSzUQM~lstjFy+NrDQ9_Fg?61q;NAQ2*KS5qDQ@*0< zZNJ!eoep6nweZU&4NWwd=OE`GL z&gBkL=qpcQ=F#KUz0!19c84z|@nfm}gV6*H<6G<;v`2{pE_9en%XFK0@8+T2$1x|4JGD-tS=lxB4Cb%7ayLwy<_0W?=n? zJhCbAToy?H8L&BOemWX|{c*UR-}A~ntGDkW6NHO7mZEhv1bAgd9$tbdH{wMl<9&1bjVx>(139 zD11W39qXiX-Gci`!G+p;&1_^fo~hGJoMsI36weIPCs?^U3R=9?Al_W`=8)ZF-F1(W z)RJ6}o^X_Jn-*_u+VTm5;9S_-h#o**e)l%v(8=5S$N*q#O!X;8p>0SboY->)@J(UI zOc(-3&kQd~4@y{er;k6A_0G8siXSxvWgpErdaJZ*nq8OB1)q#3wnN<3{6uO!6NP?# z*Jay+H*2!_(VblxlcH3g>$df*5lYN`QT+13Y9T_U$*y8i7f!(|%jB(?o~tce4b=OAg`B4Uw^O}gF)^c zDDyS!FbFTMK%{7BoU3N!)HI6r{$sF0FH+L=DbFW|Cl5)MAFp74 zRP+?bJErw#_pbAQ3`+R-%o_enKGbJm_kWG@{%elZKPo-xkCagXn8B__mzD)S_ix_7 zJV*Gr_qp<(!fECB%xuxOn!vGhmEXz@;C2jf|rcUckZY_W9xHhJb+qEh0a!mdsH zRt;p((3J40s3K?Yll*}bT9#a|$Z=;7lbKSe-qt`kTjkYMRY3zKAEGQS<~}7`f+lk3 zEibWcgjMf#A*l4QuR(KUG~P$&yPg{%w$1l7G%6HGwhyk!$!Ls#DTT`uq*AdX1F;5L z#weV*FiJg9iu>F1nDOr&E{oe%Q!U`HvMjk*IA0YoC#(nlIk5`qTc%Pb8%JUn`S>r6ZamzUnRH2wx1&F~J`i&G(S=(76C zLLieB>=a!k#%!eRiJ4e2+s>m~k!PgJ9l6^gne$U&5-1iZ7${1?ztUCC^+*eys?`{( zR4N(?$Ktgr+GN)&HQq-YW*sX}R$ba{i_iB>wjqaFs*1|hozGZC8))>TSu*48+GWEL za9VIy`GnZb8iDCG@W~TwH4xzTti{HdEv0(3Vi$sgI9iNVpdBG&7L&re3>P8sk2Ho5 zH;m`Y7eTE=U3<*>F7xfwPT%^-6sumDiL2veiy@tpu>3YRW!(3xu87OiP;teMR;>&- z9x+L}w!@U`W!R-h50XjDE0WFTgXy@VIaN0r_Z3Qi%@vF`Wb5q4=2xr1MGA`Oit^fN zuKqGlt01YPghkiOaKqA-kY4VoJ{P~4rdmiJ$jESzRB5s0O0w9lX*EGPbj}o09TH+M zEWn~GbJrL$a@Q7vn+=xM3Oz~fX^iGJEsBBWJfN>J6c{3eQoMySc-6xRi-H(mC>vWq z(`GaCK&iuM4_9;1?k5RTA;w;Pfh6uX0gRRJE04X-peXFvq_28iX*D%99I(D3j`743 z-92CU7*qtutSG&~+hc!F$@69y2XlAzVX3$s~Qi-)wOKV~n%2 z^q2emmf_g#?6i?_LYo(LYO;Z~QcF0oOU;2|z5n5Fozoqz7kqNuPX*7UPO280r}_)M z6cNNVUoI?+FDRxt;T`CwQh1*i%47Q@lsDOhLa2|(9r*@ji^>ScAP|wn)Ot&5DlP-! z`}GqazAqHMCy-d33j_tuAQCrSPxc-MSOK*BbdS?`50*SH^w^by|H88r$V9-jR;add zhPk?@i2y7%+q8p@r5st}Xv=(BURHyXqchSA1Wgj^AO(qo7FGm6Y~Gf|0rt&j+E!&4 z-odR+4dX0gga0gwqYUP7Q{{NJolm?A(xepf?U}||5^7{|39pe9&btNUH~It9Y>q>! zZx8xgIOH=d#xqXD9k}%~65Lxz%Msj0Ub}lt!HfS89zgInF*0PlOE%IqY4jGwT?2Cf zW40+pFpTaHQzd+#DIOS^d_Z59R6P2YvC|Ig>}o%L_P#M}UFB6v!Xh^8?=)}PLR<8q zz+g*mEcgZISJ*$GoQhFY^Zs*h8|g1|w!cFQ+y4VOVfrVsD35BSRH#$($oO7rf$XExLsE_}O62Gzv{7-Owf{W@x=eBPdnnl%;2 zUgut(IvzP$Vz#D%_(5-H4_1-((Fh6LU8L@}&ANLT4MJfRg}`NyGs3u0R= z?~l3OYGVC)VB?QC6Rt#C`O<1{yCHli#c~Z6Fw!vAuxtd8ACs{bkU1kT`>|)XiIu>6 zPgW(2k3R!0LtQY4o~jayaCrAX++{eb(ZuK5h1CvM!@~-GAuZJ9 zp;E?ud=oOURs(1&XP-OH*Ilx>1tT%8y?@A!>&Iw72ML(^(B*>h=1jH9m_o-FncJpF zeb5J~0;^fXz-rD@)N0c{FEnmQ_66$I%QFei@&T5W&>iPw=iI1KxR>F&u*4;~Q`n7!wc-}KT zGaNZTNO(#Ai1F9~4R&Z|e6y)%7hrX&Q*lUSi;te=A*unAjZY+gLY9rOEF0vEeFr%w z2${-2BLvEoKfRI7TB4tu!rXUk4Wv_I@ihM?a z8oxU8+!D+x$7^WWcq_Q89S80_%O(`O{@jt|TWmX`pcmn)$_hJM7dD6m)vR|>*fw}o z%V}eo{*Gtc$EF8vRFWxGTalq?QK|6GS&AL-wQ9y z`3HKV54K^bD~`myh!2eSpVF$Iy=GpZpQPjI|3C5I_!sfeu}1#f?7CRXN?TuEo}tZ3 z?mHziCI@gZ9P0VLphdWPPPcwBzod!3O#_K2BEr4XOke2oqKq|U1 zVt5XY>5RSFLki=5+Sv@+YHO#lAt8>iV0F7_J6wCo%JG_Ldzt-N0sVzjUu?>s7S_R8 ztPYI_^Q2bJ`=Nq8cN<@KCO212L{tdGM{tIYwG(@Qz*q$vHB+shti+Ii01+h!=7yu9 z_8vxv_V6iz!fJ3tZn>;OjoQZ4d^g) zpG#FgX6dQ>_GQ$T*Pgp2Lty!|Rkk+9fW9ud+lB}xPuH&3R6WH>`$fEs-S%aup90`M zF{%}U=n%UQF(yyHpNQU_Yo@dK;03K(W{hN}2J1?5%!A7wGP4lPvp(;h1gRzwX|giN z2y@0AL>wA}WW>TROWjTxtAw#irZ=qT#eOyVlzXa=j|ATw`w@OP z`-3K$?31Q7y4(nyYXZOgJ#HH&(vRYE*gjyt+lR@WBGL(f~8$@9zIG})2V<;|01cM`k zuIeB?WXfH(%P#8N0X99eGMwU1d9s^vT$#S_$n_4AC7^0&(ZwuZ3o%Xa=$<)NYI{ z?7T84!}d4VG+G)970|veaZH7{v*Lhp7xGnUUOp725Hq;ipy-HvO9>g`UGzzezt+ zHiFOKSQBfaF*9=q$RJFjx>Sh-zePYyKh*TZt96rjKjDS8ql6ZpG>bq8@PyD1qv^{f zM0OW`>%EivV(k|1rYl-n!Z`dA4}C0eb;QK18^pNsOfwgYehaa=Ww9I^HHG~^2CIQ> z@q~O@L%{f>G4s1?f#hgag|K472m05TEuHFZp>)0-PTCuE+H23TTd>#e-PYm7U9*i)t+j5t4oEk5Cf{AG z)QJp@Ogm$&)*jYt)aERMvz?PTStW zhQx1}w$oavxi|{i16<~07Q(~>iYEw3{Z5JOl&b-U5|nw-O$J;F*bdFG6#0S>S41k^ zs54%OIr8x~1V2-*zVeu6$uq<})+WgJDgzTLkj&&wJ)u!DNE@+@6Lf^~m{%F|vgAmv z06swf;A%xqyk+E{*Wkd^q|D%ueUcBm>r(9+(z^`mgvo5GjF^C1j zrVIni2L{5R4Z9iuw>%NQZi8gBg95+B1HTo5W|`06-UIxbe9#PGva(6Era#fzbYe1_ zW0UQ0Y%Jw6NA8QXQ8^l9WJzp)6>sXVV+y;S=CHspNPuue`;!hJ>YQY9v*GEh+exo$ zhiIQt!1|Vf&)`9L`y?>N5=&b%K1 z2}WzcNuZV$W9L>^hW?IDfbxJ$1UE6+K|+vCCPYX+xHouLYPYGIu?QDL4<&bG=mpQ|n+uMJNkO&#vD44L(_ z;lha`E>fPTj0XhctO)(u_CY&UWInlstN623rs zF*6%i=w%pa!uUhuE+3s)@o2W?d!twAv{?4co>=V+S^q`?N*`$Yy<~291ak=yPlzuJ z|0cJk8&{vyNGh>LYH2dBe^$TMBhqp|BA_uzCb7y09jyF&*z977UR6uhSx`T$I)N1m z2KS&#yho*oIZ1!mHhukhsUVh`l~AkXFNSa&((%yN$i}t~e7{U%TgSF>6WcS0AWb|f zIUFL~zMDJ&;ZB*KFA=|#>YE{6F+?SzjoO8XMPk!KX|=0`h{ZOhLw~U&VvtyDX(l>F zHUnw80kb(!P+~?P_-Et&QOZ$D#T%xdtZx1K>TP@_ihwT zbz$33Z{kK04Io4^_k?!yaHHD(XYMl0Yx3%zXUmae4jXTy@n}^@XNk#HJ5}M_+M*PU zY6hF219nDh?IVn<3iRZiF?`lhN5dHaV0ez%{rX>HP%&JABMx*La5NKVzwJ zFq1vNMH-B+`+LZ3>0w;-ynW2%+?D5}y5JXS#+F^VDUkXiJ}!*`#v3rl_Bu!P-*#Zt zIw%_DtHc`yr{vOIM3{sVvh=hH;s)7eI-@{nd%i|}THHU|s5=+W%y3G#FfJ2Yv_OBl zNgUgWd*^8dRthYLG6f)$#`PdqPuT=J8%JSR15FR-DoVv4Xhyb)vkuNudW-BRfmg@O z@oytX&Ii=l^8oTv2+V+$3cCl1oPzfrwg?n+CI!aDn(} zi`?jLT0j1jI0pL6*tvg}_rhPw`|q!6=Krj`Kji`csO%*9QOUl~wBuPd%SxLn%^ZB& zMwe*?XQFWYaMhD_;^QGtty0Tm@tU*j`o2~-6z@lnh$r-XzH!Lo-o@yiLe?|l<@ zQ8IegC2BFFmBIR*QYsS0U9SHiQu9Z#y`eR}99fCU@jJ&zBj^C5OD1E1_L?u4*GOjx zc`~CtEbG7s+Sgg-fD;U5vK?T2(;1#Y7OWGh3^(37>pLeFAb0I+}61~8)N&phRf4PgG=Th^cm}GwKOF^B|j%`_=`6-S{WWgF~l%|;H}>V8V~|-?jOzF z{I+4WQ9m4S)r#7Zv6isS$y%%;_Y5-+ICYWX-BOiHOpO4hyc?I@ zQkVP@y=>o})Wa%d`s*Cu7};_F6WB`#e%w>b-SJlv_RPjlL58oMlX+ieiiCM&1>Jv= zf@RnKS~68%fy5?x$*1s<=*8oRu5dpR-?@$Q;oU19&#LAKBj{}x3|zBWK8BD(;MqYm zsPt9y2q*%QvnJyZ`Ua;HYv}H3&Fr%X%Plo$qAtl(K5FWY2If3wMUK@Pk_lJ^V>Q5J zkLdtZO{p6!aas;wpprelmN(H+bB<0-$1qa3+SCiN;G|@4Ut1q-=6yWC_dVyu@=L5% zI_dq)C26YT;mqRTI!)~q1F`H-*`HXre)mhaU%(+b`K7T^8jy`EMaIZ2cb7(HVOfbU z_3@JMKQ?GfU)7PfU!nttSLCw7ZhT`<8ot=YQ_Cwm}P>^L>^l`(Fkvf5#D)|ExrXOf0Pb z2_y=me@NbW_E{JS@hN$ccENf=V5g&|TLWqZbxO}h)$@#tjZ8U(yGB}PTCad#$#>7i z4Gj$=BR13~IoL{kKHPnPrv{57u#>f^jRpkPd&+}Y0KH)|BbkiG8C73}s*yIt0g`$a z9@!v57&>8jatWGzcfouJarJN3sZ2&FOpPxF%sV@>?nc8u=^+GhZuwKMzoKdWhOY~M zvdQNu5FF=Hd>VpzD!W3Wnm%j(0dtlOXY$A>O(^$}m_(;}_AV?f0tw0vw;;8|pBC`p zgeNp#Zm)NQ*o7`zXoe2=f!elUX^DfioH5M6>{~=4`qV*Y=p;(Racj=x8e3#W)^!Jt zF|rr5gZ&4PWNvzac}dnpAVVM9L(>k-pnbXh1QO6hvppg~v-9-}XvP@6U#k>tvJH0i zRg|U0Txd$(=SY9{P%S?k{{RxqzW~YK$;^LxN`{XAA~OHNk@4X<*hUbDL?igAgD*OY ztzS?G1cVS2zmyfVZL(*WQVms~xq#U9u+V*7ghQFc;g;_R~;fsWZrb_8sL7e(@+q&%|KN6gfr^G;F&P_em>p z+^9_1NnJ*nuNqS@>qsrpY?s;NU@`qD@djwl-n+IgA*sqaj-Eg23?2I9c|Eq;2ft0I z@m_*O7bTruMKzZ!V$=g0fD_~^(=B2wX?dEna?L0K=gs>+;3keh{#u0tjisi+y2c1* zJ9V5)K*ivKamolNP|<5ntPy`i8ggiYz>)B(Yoh`ST#FZiKzERiq9 zO$ak@XF*r%yfu7J>?You2Vwy@Bok$7S?g{v779tqgc_~KEGC3UnguKOSQG8(&f-?> zxo!2&4`|P;8|;ozw*xFIBF#0BgN5d^5R z+Ck`b6_T*jpy<#Fa00GufaDixEZyoO;fId9B`754q7xbw9=W;VSdHD|jG{!Y7Ep9TqSh_vLLNIPop$t3JfN17P|}7*y}+2u#O*pkLDt@H*8s zj`|hW1tnDI#o`QA;SiofRf{TCi@Y!T{n^Ex5K5;&G%5es5T4Qq*W+01xUXM=UB>u zwi-v4ghd!z+TKXvwd%`9Z?Ff!$({7Pck_DoSR#{lX4b@tqF*9Nw3aY$er(3(TD{Emb4T$2(_r<$(Bf0 z*Sz_0UwCvy`IhM@`I zlcH-S6VxL?=+?)oZ-nApnmXW`#|%9P7ho_jG45o+Z>53bl7}N(<#zYTEA#rpZ!`JN z5_u31mfd!yI6dISEEg6`M ze?tHb2v)0SB_6sdhB24YZPwxHkR;I}NA^qxZA6sg$jPkNIaMucw0w$ioX;!r7-1@E zp!U%kKNY1}YfL*>Nj$XMGto%TP~EtbB$=LIHgb}h` zsRU_ih3}imBWPju@cd(6OB%PxC~*A%Rj|ttfU=4CX{sj{CiH6kP71n1atYKVumAen zum-wc6*;X?2orH@y4)g(2*E|#iB@J7DsZB+lh;#~Xj<+zQ0-dAYD~4?!YdK<5ak(c zB7c>i%NBz@3Kh6YvN2C&C^A4}41@hUn#&lLI{)`*5nw5G)+^Kv)+;zpn2rdP04lkD zv4CP9(y_{oI%y#GkIn1V5+eh@kjhn(lJ2O!pm(R!0vNPZ_k2?>cwW4iq45q)h^@}xSEZ&DXxx5x%WvPt}~cu=VQ2vsFwWGIt5B= z20qdt`*bBiV^3@MJ9XOv{yqQ-?P9j9plTuqwt_vCk5~+wc_|Aszjxq9)WMXL&>yJwk&VgtZ!aQ99fTDn2)B!(dOVA$O z6lkX(`GPs}XsO4%k&EcHZuyI|2$lEqNeEnn{Cs})`HFzh_4W=gk9=mdHAwvoGE`mZ zE^agoaeQNOo9g+`m^oq*O|MHfA91BG##UcoNEtP?^QN-p+YXpkfX|&GjhXk6KlnXR z=M{|{bdOp3ac|26>SWr^TN@<@RWg zZ%DX)hadiC`GE5g^6wnL?(DN!6N=k?`OR=*A2?6Bh&!d}71 zHzKm6k1rB=aB^D~x&YI{_dk_EWr7)krk_SEhyUX^`9JLI{JGF)VPN|&F#AWi<{(!C zQ(D%21p7)6{0wo^B363SF6o>Lu1td~eN#fMEDV8Fkx6g`963TWk7K37PufKG6>~9MF2=ry6@wK=Q&8YOk&c(XDl<%W9FwF z%SGGEgxIDZbT@vd#SSYrs{>bOX@R~Wl$dnCy)(|hY@oM9EZxv!C-f6igV8nkjGK=; zv7g*XznZ6bm=)FJ4?4_JJsrP9fOFSC8$XLAbZW%$!Z2x8_N)6Nku1iTEPA=84**`v`X`%ugkX&Mlw^w5!2v9cj;>oNIDaSmcsJJtE8Cp(4Fo1rOesHAP% z83>$@Bwb^>b8#7YDO!Q&R%GSAu~l7Pt;+AH+l)i95duZ~tp$ymTdIcc=m?ncxUz=+ z#{A2~QBH5b5G`sJ{Td@ZefI#U1Q=*uI>-KEP(IT^xThp7$`C7}1N5pxR|v1X+a+0` zOR^=I+f+<(KS^l08T?Bgm3}jn)KF%~EJSeIlpr0e))MhARDp{@Q=GUEPC&4rXzW*< zThs~to?f`KMtf8tPTZC&knF}QBhu=?z=?e*F6Wy> zC1YQx4?oZ3QSPpeUQ1m{Pf+-3+q>tg4-Y5gv$ilITaD!c*BXK}4_#3@Vzy&|Hq}J4 zqK8i7jjxU?q0U2?P-QQ!Yj_wIifFKRNaOU1sPOmWH(~nwUsVT#XY}cNi8SQgIP`RF z^KxCt$?{yS6YVapd8ON9vB;GPK#w^y6I%67JO}IZvV1)u0c7tf6k2Dcqmx z!?g{PHFW$U-iN5*RP;!Fy2<^8d(jT^vpxDsR>k?kDMpJ(m@9jqE+>w>aCqjIPo|g| z0(;cMH{e= zmMwE-6{pfZ$so?mHC^H^&AJkW>_gfkAm3=W$Y;f)@Ztj`k@e;ir?}oRnmocuqk@!v~PG)FgO2Ry}aVP80tx?EYb{KO=7i5y(b*0BRqFEUa~$3Upq)GpD3f19({Xi zc?dUz&gUqTf~bJAmoR*tc2JTtJxIi-(tx}ft|rVp5MvWZ7R}^u9fb;>H~8+@B1h^0 zx@&T@=1ye9s>Sz)2_e?LlJ_u>{pM+=`Vj+?wxov(CQ;g0{XIo1KCYrYw86YM_L@M@ zj(P6Ptw;|2rk7@DZisK=)G=ejlM2roUy8V8%DIx%cT*VN-BBaCOXH9{6c!?(YTI?evkMF0=_k8^DUpskTLQF3(dBWQ^weE3s`_}CJFWD~;e?h%=bKhfr0esz3 zTfW0D9Vm`T9G#Nhve9iPq2=w7s!vqApwMjxi%BGcEUEM$cybeXaK&vSfr)Hk`7&6< zHF#{D^UUagWB-B#S&u`$D0R=nneD99%MI_9slsPCa>?kyOnK9W=4v9cgC)F>|KWR{ zt#X);ga)TI2ZbxXfh8(<;X1RGJ#NLR;oF^_WeG*k0C-;l`;QMt|4jy0#p+LL5Xj&H zFHA_q8#VP=zlj%-4zTQr;0d=#J3(HGIehxJ0>`mdI0pR)<;D(27{NG(Q{A)3aoAc z@PG)^5q)qmh8#UCv7YmUkS(UwxX5@$qAkDoJN3I}DqYUfI=)F&G+hgyCoEXA$vV_3 zNX0c=$fTh&Q-2yaHj&<=4k$qTJiBy6AmK96Zke@k*>I3oU%=2>3)PmYh_d#fZ2=h9 zWfO##d5pMoL)Z!qP(?-Sid2>gjSG{wD=4!yG4GLaVWA% z4f~&p3?CdN9Y-hyZKO!zeOx9tAr$RHJ0R#TVu~3Lu((3Op;I3kcal^Lr;8J}x%4z@ zivs<(m-w7?lP8(bN2rW3?w~}KG;`^GNg74NMX-$AN93^Ar>H}e`D)PMgmpx>RQ*`J zw(531Y}9fM!5g};<>c5_+l}60?&;fP9>_@}Q)@GyK%2JCR?k_8wL5>nlN4@a9LbIW zn`&e{=uz&K2xHY@x2SP$X=&MJJYn_DTIg>;ZaUrX&7d^OW@9NA$PwuAAW?SGi#6j? z>7FRvG_D@PQn^4_RjI(SG)hsd0M}vaRZi)}MnBu|#x_++`A%l2?H}d~17=iru`olS z-;+fW7MjlP)JyYvOsF+&>|zhNv@BHaY|RxQSbMZBkea_a#xM1(CgSmKn~Rqxec2xb9 zm6}5}xWKKMOik};`yE~rUvsDG2JU|5s+I2;$LOCm5gl0B9kjp{uiq;T96^_UxzzyN>mDdXHgl4)29N9X zqu9`-AYGau@CquMXO!MVteF*S>?wQ>FNL@P(F6}Lb3G(8UlX>&n7kp^3*eo1p~s&9 zuT*gIG(uO9#I@^!azs2J=K>8>EI#T2>h4-!QO=9{n$K=4C$CrQ*1g*elXCpWCslr= zqpk~#Sy#UwU5O7^Q0N8;h_3pfEx>bv$+tb_bFFw&&oN80qHr$G?02QfdmfzE68Ka)diW>*; z`5fd+5Be_vy?GO0E$|%D#^Hqb*8uug_eeS>2}6z$G~{eyijO0x#J`#xFUYK6@q&pxsjU@V22wvaHHlHvAFAc|Q{@`TUKc2_?>MkP44Vm_jWb_k+mMS?= z@0|W8cgnvGefBDjM*NOrt?nkEz}IP& zSTP$xE+YtvR;U&-ma|`v7uWfdLuwCzoUBmCp=8{BfcdB+IlV>VH)pxoj*5Z31b4;l zlWp{wC6`{}p198*9T88$E3;w@a=E%;inWhX*iB73qKTFpZv*;`2oIS)qoOZYUJpDW zF$EIgu!?YFvLQdu8huOy8{wo1#GDtP&N{z^VZ&QO%tp@H^|eDtgJCL+%R`5%00!-; zM;X{#_tZ+f^(Qo3!oJ4XS6FW06&~bY!-eMwy&^oZ9s_^66z?2uZ#b`)zkhaJ)z`m@H@8u2TW7tdF8qoki2c8Ata@w9&jR%q~#%K zlo@@nBxeeIGxM8JrH`m86gHKw)dUuYNmg-HAZhQ7_v|LLJ zJsG4H)CzK5KVOHcymX`mNQcM7vAd%TUd#G1GNwib3iBWrI5YFd^tqcUAuqr}d?nmWvHG>uk-@E} zC+GBm4*SqBIxq4A6?@(TF;{A^zgfFjXy#pbCY<$NyJ2SDFSZmZvFDEbGK|wbRRk%q z4_Uyv0rYWAYQJleAP|+52;@idGCg_`Pk)1wk9Xyg6&Kzh&c(<~g~_?~asa+e*XdNg z*U3}NMKBzxXT_sR=jx!=05;=O1zi8itKZ(XA=2qJW*`@S`%irM|4*e;$=t^9AA20o zW{mYRy85$e#ip)W$)pF@*Lf*uC`h#~BO}J4LVG!mirtut+d9D7G-+i)(|sMh*Vb2$m)DfE zR=Z7-Z!8YTEcz<%sT#X-R0CA~_Fh-#YQ%%};Aa7Gay%QYO_pO1<3Y*m&;F{*YGm6l zjZmk8ai? zak0l6U(z{rlXkq?AkYK+JcgLbJ}1L@Y3$K`3hSSu&aQ3}l65zckin{qtm>8Ua}LMK zWyZKtlu64}C*XZUU%;buN}TF`iW8fhuHqgn`+ZZ?m^@3-DDQQi!y&()H9Df9v8kox zch#wCGDtQd*4b6>VCgsd6=*f!Qle0`Mx`0Dhp^tt}V2e=Bbx3c$ga z8trr$#rePjOIG9gn4fv*U8Y5WZBw8}mns8SHPNNK!#V4q&NJp!R)ncdhvmn>VU<>5 z9PY^W;qsSA@Q2TlTCLX7?&EgD9Rgokv{B_2X5vR#Ey9YE7={_?%V1778s{j{;i{IR zb~`KaZ6X@NHeqODreYO_yLMnsLk(axv-&ecI%X+q^*zz7&D6??gP!cZqHzlpXpx${ z3n9ND7?S_U=h%-6>5>RxIQDWkZc0^RX%YagQo`-SO<#I_mi0=b>$CKt5~v}=P!p2m z5;^Tr)X!_^#&riu`%3lMp(IkdPS* zUs`a%dU?*b7F=)qg_h@B(uZu}dpQhSUtGhQ4sFpv<`+<{*9u(&5#Si{qfvEly&7>O z1Y}@+i#_FA7hPA_0j3io8#)TGq#CrP2>Vv#IK%Q0(4Y}@-Sq|3*Rx)j!p9pXus z4;6I^^mb;8y8TPozocdhD|FAyb(K4o*LN;7b11}8U&Ini8jMn@`#zWqht#(|Q*1ue z3>fjDeq2DBe<+>AmXtN!fc_egMHM(c5PuO-_+E_5LYcIDPlHCrPg$fSGKc8qp6sZh z!f|o}^hQ7hJ1l^Qt5m|n_gel7MS7~>UWm5LB?t@|B__>Kj}S_6EI7G1`#oQYo_RZh%QlflXiAQy6`-E0&U51Lb;2?j0T zHQTjvL#2fhk3wOhux!~Aq;NG#Du6$2Kg+3gE5l76wUe`_W@uCNLm^$8a&8X`X?h@| zl6@3>h>WH5ZjIfl9{%RAkmm!`lDi)^={T}#mu|up1@dazPll~MUB2vNc+?jiPa-F@ zP-fEWpK4SHOYR}LYI+y-H1YO)07N}bvU!K5ihwra?bL1|4*!4)Xfk_<@O3GkK-+V) z(M{}M-=6Qm$2Qn`!X4crYwjzdHqaFU=7d3&HZ49N(Yoo-^a@m91PFgxMIrrw;W@Ar zV7Mvq0h4~ikK>zbx92>)?1r~J4#5v*4${`nfK3`cluwZ_iL=HH=|B5`lA^)OoK{x_ zBD;gCu%C66Ukugaz17f)$>TNS5=93DcL1V2bAjmNr4x1l0k#-q0Y?p3ot;`{=#|$Q zYP0z0y4o(0kEWWi5BP&Gj}49 z*LTqW;|1kEj;CBD9XX)!ns@3Hl4eGAI_NW$U@rJj?F1yWq(MFj2|Bz*G$8N5#VWwc zb>K8EqZe|kN^}eHoIGES)nI+1o4~laY8pi*1c$)oG?g3pj_GOYLfIPM2?#~Dl|Ggd z27tkuFhGjTgvKm^DY8y4L(gEgJ0)-kuGjfsz$}n3k$xJh+PIApYf|MPu*N2j(D$i% zL(!=EkbAl0g1^xFQ@)5bHj}!mdpkD~OiovX<_!-rO%o3sc-Bu1$P?h?jA;Vm?DT-edov7F8%= zg#hl+Y#4DZ8iWEu4d`l2XE4@qy`(XTc6wZGjx3Y{n>)!P4^ajVublgIoAVgZQ=%SO z$V)xT+%{0>4nr)SYX^c#7DPGRWm12;G}?{GdaF6-Yzt9h6R-`(GO7HMRZUbtL2_0L zcQ9;@co>_2(zW?jI*u@Vu~O%>=9oKFW@EfM?gh^6$9a47(jlv`L9Se<{G*x(i{U8; z5nP^BuAt0j4Cn0Y{XAi z=ZJ4`VbR_IR1OJ^LbudQmdeBh1H`~YgG%k`L4rsx_V$W?P?C&HfDf>7_O?N{3CU{w1a8ocK#}jiOq2h5%ai?kKgGZM7XIxIDN(kz1wJbN z#m1noz;se^c62KjZnj3EX&BnDJcQ9NP6hUGR#8-;8qw~^V?f86{8DNOL~s-F8^6~c z`MY#3#%gcj&9-w)r0|spqMsdn=N)`+b=y}dd)l90fiKJ;g0R>x_yr~fLenIw_iCUz zr!cQ4j4LpYGw5fSud{;f!8g;%Hx>)VY9mvqS|)=o&UDn0Gc*(mo|)iSxlhnG>@YL6 zaM|UyQ4+_NhzZah6sfms$4A07lPH#cn}HUhZ#*30xUIiiJ^Xmc=|Hj4x>x`GBbHwU zYJbkx)yT~2vmPp!)11uYe1U!Kc;vg-CXA-RJ7cCFyWv0s=eTQbdQ_dV^_tDxBB((+ zVhP{yScllwIcBMmBvY|vHJC}nv)s*XhUSfFTE#iM4bzlz>Oo>7<+j8#>CA$PDWCgwhZzyv#&G$_p_ z+qBF#hi@VpGDKtCCm^M7f6J2}4if#A=nCp0%k(|k4afj()1s;CN1Tf^vk?7CjWl1B zl@(8m6P;8IEH0_k(Oj+=vKgu#k+`g*(ORk+c^Y@oL~p9BpGu;7HgF2At(llPE(k5P zQDgh^fxV#}8H5p9k*#@X9)GDx>`=}fnokHU{R+h^61Khzj*Ssx92<5&!I>e2k(xaVfOgY_I92Nf zy$_%N3_s)A>_Pv)QyIT~f0CR3VPe936b0lyNab_%0dCm2*6q1Ysqrn6d9g8_+Q*lU zmIOnU1?)>ibKg&==F-2Q-+t(+!_}`UU_jdDKU&p=|K1P%cFH+AnH&DwZ=9>FVGDe- z`-M!mH?h7JchZhhCMj;xq{Dfc)JZ(Kwi_Cr16Ec`|M45yQ~`4hZ?s$Q!R0&9zB3a8FmYdHl(Y7NRqkmbC>R z`8GIIt*Z^((t2FUFKtR<7%|`+R|gYpY7V({e_GsMK{5jjl}p`f;~V5%rPo|irB`Ve z(rlAG*+2r&h2ugbQx~#Y8XOy1Q$Tl^2oC#wos`BM!eFhBE6r)eu}nf^EqdLT9K66S zkVtuBIQfE?fh4Z%il@I#si6$LMh#`Ht&XmqP_Ut*NY3Eo74Ypa8|x{qcB9-%G$w0v z*&q>0ILZ%`-I^y?09$J(y%}|xoOtvIZR^>RIcdw~xMk~xx#O4M-YDcg)#^U`caSP6 zL5868g>IB#-u-=yfdw2tBh~D-Gqr)Cr!nan>e%QS#g@U-8Ks%ytgc#Bf1m2chgz~^3yaZ&qRRhd5)9Os^?BoS3ZRzd@G*+JE>lu*CdC^)rOp*va3V<#GnukrOAIq!LH9dl(Py<-clK>T=D+($(#4*UTLY#e z(3rZvi<$+Al&$JsQp5N_cWgtV_F|yl^x#qx$rClxC0!);o#|RVLVHeFy?c-v>c}1$ z{h~4rDKMuX&nVHNmZZ8;9NHQjSzG~ilxg0Ry#lH$l$m8QIQ zif9%ASxS7&sH;k=I(Ql;%Q)+hw_rcqf{}y^wx=A)-$2-k9xdBIEHgjoRFIL(17?lQ z9DC2_-C1NDqWDArPa$s3Hd(>_kN8g77_V9J~ zcx&%tzKms)Qp!lGCC8N7$QN!Pq;2XZxZ4;amQb{O>YA!H@UqdP&+Q#PyF4HodAdOG zFeg>-S=!HzHJ}aN&zl(yvVt2w)YB>3#MVq*P83Lr(+k}SIoq7p?y(Qk!aQmK2)s0@ zk2$MG<<4BS3)J-w*&7b78ss`y0U*AJE#XXWG8r6!xhhR)iI-;9P>dLx9f4I?Z9XT@ zHv(#jPSCsKD~y4!EjIBGI3 zC**i{9ME8|Q>-^5Fw&9q-5JnXpgftvXmk|HCv>X4_6WCAs{CS%g79l!6Ao0cQ0D~r zG9r=r6?OtMF*b8`BNvW?J$-ZJ7%v_`vxf)GWO`FDaGf!Zu}vz*G)J|WJb(&X4(k#X znZ!lBWyOrS9MWTZB~6xS>`a_mKE;I~tVcLT{@a#bwx0|Q6U%GKfP96c+sEmM&+xsi zrdVMw_>S4z-KW;SMy)<}t(H}H_kVL0wxXlRed;Y>bBWBonwq`F#J;SCUEmz#a2MtK zdJcM<61O)1lzMUL7AC7fM1uG)Kru|W4G%{b7hkBEGayprHiBL2>}Q zU$(50N>G~S|23;q`j*wvy6J3MT}ZTjO~roND?9u2PPyEsvz-+cR-L87ZwFg?t1%Gh zurId&J`iS>(amtf&nfxINE|ar1~80TM~iK8G#E+${fm@GnMjdXoc2nMNEsy$da0qI zsB7$)d_mJH8)j4IsiaNQbL-K4GriLt0%q8L%T??cw~wLa4p;LK`Wir9Vyfr|3b@{aU|G_LgrZ`yz+AXtp5 zmHx^7*!9Nx@XMW?+wjW>q394_`aPJ3Lo0z%9b#)HYy20YY(+IOZsiI64QzZlzzgo< z*E@#d4^Yt6hZjlbH?W$DSC11rC^?2uYeesySE5|VhwklS5K>~YgikmmaGl4d49$fA zdx5PNBzU1B(i5NP{ZX%rz?k&($*0UFf~JPeM&nw2y?@4|$xd>hV`JI{iCV6KR3&65 zZm>AmpL<`*26z^EihF;6)eZB#GQtH9ur;+~CFNU-9so@v+g8lL%$Ryo{1Ido$_SYNsw>2u^%zp2`_t^hUd@AeP znElCL|4$hZ)_-I`SShvt(!LG}?{H10tYV9)J@GoU>_(*CvCG%5gSb(2&pSiCSFtbB zb(`bnzB*}RHhle^W~G{y#;Vshz=tKns9*`DTxPL{9fDAWLxYcji@|mX&xv|u6lzqr zU@}T;uo-p>qdJrY4`PpoJyu=F50!=C7;>nQCsx^Gax%l z-la`7dyhZ0eT{+0nb ze1oT@!5At65T1^>K9iO7Nt5w8Pl1Z1yP3r1^eiq9-W!6 z>kkX;4Z_7Kg1bdN8e!lbyiA@gwc97d6>ICypRSoeP;pXs1LQ?#z5-s>c;SWu1VL#% zT~ePO(P_J0!s+5a;tAcef#e@y)NpI`25dR4=b({V^hqq{d#0s}<1#f%Ux$((n9+O` zdu>LOohU=-|K^`6oh?G0Y$EDd`wRV;xh2OgsaM-5r4JjY1PpRmFU|x|)!)~FIKYi} zT5?Q$V^8Bo2}2iQjrO56wd-MD`q7SpqkB1=HDSj)r;V`d+&o0(LFxx~6`g3aRK=J! z&B-N!`SJSpAf{2Dy=8!SlW$REjAi8O&DtA0F_djX-&%D3a|GmX+L?gx{1ctZzmtx< z$;rXLmDxGnj1llk>kW{_8Io=aIX#8Ryri&=AMX)tffY}25rx^?|39p=+N4Ntna;d%4d@buE+_;Yp&{i(}N zSk>m{K?oKBby@m26r?kb_a9X>XSa}qZD+Sz$*q}cv3J?P#EM$2s6Iy?_l0d)Aag}s z3mVG7y+4CCjSpw&J}*u9_{Z$*#=k)Bl7Ei71=WH~TNaNJLc!ca|uk*fQE|!#(-sRzq~lD=~E;0v)8<5 zvQ+sj-ISbA&Ao-d>yKT*!k9b~+=d{W9%qUPS*CC3^nOF9EOR!e)(hxu;1@*>8ACdz z(Ji>p*-S7K1}Ww)jcvnou(#n!4NNj(fzgYsgD!}!pPzjg6=OVDMB>P4z_er-g8W04 z#Zucr1O}9x88@5Io`!oS>0aY{5s20Jh`D9!zW7yB*W*YuU_5;Oqu62&;^gTKoo{UG z|Ne0Qo9GmA`zwe0ze49`?fE+@LD0$HG2E+Gd$y6^G2HxL;A6kupM&~C@_h>z4AFV> z4b&ZecWtS198FnBTuE}>iyJHy=Yt~EP7hqTx-Z2(EQY)*LXw{5^t z3uqgVd$SGPD*a&_@W`y_d$SExS%v}O+4=@g7p_j!KjB$>2`UAiHvcC)d(Jnf=dZ2V z&uJ9m|AHsne!{FgqaCI@{2iRKK2E)#FJNZ8zE_@Cw+7op%=FjK8giOJ!=roi5EvcY z6M5bMV^cS_#Ou%duPt5WUL+D3Io7icWx5klbRkfV%;bF^9L|u^G;I_bqE);&B%Wlr zGKE`!hkMQFZUGRUL;p*73Q$M?H9Vhl?Bae8Pfnarp+AP_Re#^Q*mf$yohm}aBL{?T zP&;^KX#2(*xORxaWDTL6_|?bRjCjO|Kk{>>gP#Sj6OJ6ZT}f{fgL8GBi9_*3OT7eK zQf!`~%;)TQqa27Y+a7+W`O81ktG}J?{|wK6%c>ID&#U5;Yh&7<$B*F_A7YCF02A|6_5=tzhSbTN~;_9J& z!XX65=tV^?KZ#EjC|H8uGdccc|8N}hNP~~l$2`zn zX$?KPhiCMo?Zy{;M24Yt>2cy@-SL`og9urC5$!ZM8xjUIK(5!+B062JrRSv;JTd-B zRoewK&+99Ou{uX2$#mu3v|GmKiMW^ek1(e_1=Fb;##xo*=7cf(_5=DbQ{@N9gWnP# zr`+OP5Jra8;}P0hCkCWAkwZI3(O$yjHL~0-qZ~4UkIE1CNLxA0oa3I;uhWVr&>aW9%(u;7Wvnpni zVsrCef6gAPxLknz%84y0#oMUQJWOgdKP?$~bM|+N5N(dvj2(!~=l@9F{Y^iMgpsk0 zlev@opJ%($iN%{V64r z<5aW0Pu_zpc6to^QnqD8em)SiL*80~RG0iY?8n-rtaxOs>h@Lnh@ttdMtO#(L;HC> zde0Nxr|mCt^9R!@s*!SxU#q6%%fIfwgr zXM~$@BUOBGpbfY#JDA?nyECezHW0G%Yf*Yno~g-FRj53C+pSOI1p@(B)C9eAE24!! z0#X|r#KImpEmPv$9EA+dBL>#;Cpzj;K0p>^fNf{3^P>`i%L zug!CG_ik+RR6qe@d!$AkC;dWb%Lv?f9xfF8v>)MlTH73KrFfl)jut>LXR4l-vXeaO zb3RbE(sPnj&Eq}M3&GHQf5*+`0cmYDPE0#tSz`xCvqK)f7u(WUY+zwVZTSj!>yN>y zY(|sY!Adisj!nA$p^zmSj3eDAUEXC?kL}aQ$2ldVPy;eP!K4`&x*YI>cTnaWI21WQ zE?u`*)xslRd4zU;5oV<*%qTVvX^h57&mIQSuu=WeiyL|lE-tEvsBM<1ES<7hj4z`Y zo=n*ts!pguv)}rC*TH@2{(=ZZ9ov6I-QPT}f%EXMWpV*nn*jveNXL5|iuZ$xP*Ta& zNRVzI=!CHVW#CO5g6M+7o@_)pOlM&W>c#gHh_2>)6oPg!!qfVngbLK0S%_&nqr9f0 zIy`M(zP>`QgB+4wQY6>=FF~9ph#!sU&?GXHTV)tzSm^b%Qwg0GIOTfuMwBXZ!zIF( zkz?&@PNJ7}>8st_y3Y{~J;a$h=5=`&+yR$K2qwM!I-ajfn@!93P(!x>p)vSkLbdN= z7_JRhj1fLFh&oylV>OGDI)?pW^{5sA$?QcvJ%au0g=6T?Vf9hOT$ZYZ&_8f1*Dzb{ zR7j3frR*m2g_&C;=$LU0<}lf?J>g)r2pg-x5WHyiA6|b54B724K!(wua$a@_bh3dsUpl% zv$5XgW!2&vG{9JU{SQtYSV#nl%?~5jvwD0Gp9s&Y`LtdD(|eS5oS^ajY!F8?z*G4& zXO^)1r@J^GPUNf4^^>fP@Fn!K{0wWuSA2>7%zpWJx zPzrsaX-+`9bY8NVhdU0`-OPiVO$`$2vmP=M_IXSeV#E-^Vvw=ItoV*1boG@On<^0M zPI!Eey(RO=3^2QfgXxe`T)c9t9kQ{mrdpiaw?s6lhBhf8X5s5?bZ}fv@hkw~p%tj* zM9b+wXI*~uQ3vyM0!~iLLLhF_1mXG4lRyEAoFUv>ebAixG+|Bhxm@% zjDtdNrUPfz+G>8jx}rxfRf6<}Q>b+ThXIW)n;Xb{L=Uz}c4ZQ*1?lrAdeC1AGayy4 zT<~a&6DKl!xXZft2^QN3^*R;N$13m(5De$ira+cPO+0^6cGnaQy36GUF{9&S$88Wsk}<5e9OvU~Twe-g3-N zFSGR#s8yA>O^%F!@1Hda;y})VgzqSGf&q&91nykiw31&Vh~=arXcf8#m@j*>)ym_G zoB3x4qu@D=hN>WFP(U|Gm3NKeg+p_k=RJf@A0R#14bLXbq7y6N3$x;8XlYOfQA$13c)Go8t)y= z8n5H&ugB*Wm<&u*DuaFb@dBcc&e|g4hji%3B+4X_QCUqG@#Dn)rJEog=+~6{Y7Fi2 zU5=&tjdZ3^#l~i~-0oAGX?j0GlHv|RnJF%6hBbd$`V+Dk?;YgW%vN`MHN>EfqKu&r zOmbM_HrIFJDV>Ig5|-&T!X0QVEsQ^4u)_$lA1e;jYPWQ^2)2#V>K51kEGmnq?P9i; z`h49zJA7f{=W{Y%$dEt94VaG-RqGG}oU_r#83(%k3|42>)SnuJJxI$fDn^yZJgGGN zfvx0V&XHVi8g1(cFN0--#TTE#L0K>sAKW8hnyrlz=PK!!c}A4!0`UALJw6Za%S5K) z06mgOmx}E_bV%+z z$AWlCwOU}R+sV7@UXw<}v=O zImPLNZf2m;K%ZO7`nEsuR=5ef!Ms+izccWLZTh@l`Q=(7CoX%#l`7bmTXdtJbt+bb zn>Q89?ED~+br3LhWEsOtj`z_Ml`gtfut~?`o518%AaD6LB1J*^5B!hijREWWm5&&# z1&7?`(2=BG358@u1PZR-`V0L$D z)%%n0^JA>INg6T+GY&^PgE+bYEVox&x}iqu5$^N-6PO8BKBBeDbY9LOXP^sEr>=Bb zM_q~%P;d!yrOx{=HXvH_#39r`@MZeIO{mhRoXG_6W#``T8npJTiIT#hSRr_Gl759` zC5e|0HYR#akt|b8#H=iLx;C7uM;+ z!`Umy8#{*u!~Wp{I0e!F>E!xXA?j~NCxDaC`Om_*66F<}DF!TFn`A()e=H-!mg|=7 z0mP7=;5R@-uOzY}i1~L(?Z$#74~tYvdzfZ$TVSy?in!g_)cN}#^cw1O7MKOHOM-t8*zm!xQg%v>ZRdW54Sp1_5_xk+$Y?kKoGPY2Ttd zrsOlV)mU|C*VFWN%`EwS&2*MmOsRgqNhVCcV$NG&!n`p>wW6f zV8IOryk}M_QJ5pdbXTY%7%WWwzGqsR6G?Wx-809+Lr?SzwFy#JXz8zY6k-+R)a`xZ zvso|{x+MTJjE#ohF<8~Od{^1*^L`j}h@^D617hu)LNZzMcaM5&?I;bCx5%xKuI-AR zr9ir-Ue6|x*zLp8g0j`Nxb zoW^Ad7C$A%B!*dwbY~Ae#t)$AW z!ZB_lU$53Kd6aWPRRV8nin&WMqOgEH%Zy39`wIGoQPXgv^|$E6?*C1U{&qwDx%R8B zIHIbcy;?UW%hV=g!1`1N5yeD6kXlbjQWA~J=f4M~R0jDp|1;T%aOH#~8KHF_mbv*5 zY-=tAuD?GTl-Uc-S>7~7;li?a;==!HJNql>jjQb>J=V`2Lgt3MWyiCJRL8OB700{V zPw8u*bW6;;RzaQpMddh8JJe&<;}y!}}7!QNQ|L4nU5 zbuWNl&@&)-oOnW92!|XwhUz{QYgAfWwVz!sVTJ|fYKERkixexUVL(ace4>6b>{3A4 z*lYK#6=o1l2nf}z;ntwDn0}aBRl_5w7=kQ`L}8`Hrnij+lvEP;I_DmSa|$1iy6qSY zCY4_rx=@{khI`tOvf4Zt;wr^i#;)db#42YV?t1q*Dq)xH-+RMU3v$s57t|e|~$pnUp+;eSDe)D;}qDNj;us^z#+Im1DEJMc16g=NjH%%mNN`^lhst{d$Q?k zHoz|j)-$ysmo)>nDy$DbL&XZgR1idtq^5@tw76OzzxIPDke8%WfP z=EO(gh)$E3E9SCYpPEN?w;q_fW9H!kP);!^_Qiw!KFZz_e+%=7@AUP=ky^|`|Hxb| zz$>qNsA};J1L5%dtK(M;$@wh0DZz@H5$@G$wOC`>cv32+^(@S;a;anTc0%n06T8eqnxis;1+i?@Q%+9IlSQPi{CsZ6keDdVaocapOp@fAoq%>5$aJA{85P60Sp!xRZ zs|Mu@3mat3n%|6@At{7=7uc$5%|Mu|qg6p;TZJ{2QnIv!m#W^xd4Px(719Yg${tN* z;i&8(TdVk^%~Vg6E>p@h+@F2Mw9jY&Y~NTgmZ;g565j$0H&#V!$WcPYmq<>C7&n=o;GO zN_lp0><{YRp-inE$;WbA+|A$5>>)m_)7Weo{t_QbufH_)3jTaf-S>5!-5nG>?ZV!K z%U^c$Yp1R_@?zdWUT7opeDBj_ucreB@4PsrbhnK|F?{GIoC$|}fLd9=Ue1P`dlrbO zJHnX$)Uu;Cir^Vs9>ie^Ob@Cr&z;>Tz5r4}tI{eG;bj~t!R9Yl8Yt_=Xjodv(Z6=~ zaOjU<{9b>TzWJ8w*-Haw_2>WSUjLgrg#fT#`7hS`zZB_p98J*ogB6fwj^7&L-xO&W zLMX~_)04}#DKb?mmH*yK*hl(bt%SeZO@Fr%&dRguum23>98Okm-$aw$iVIv)X96-c zW*J5q!x5e&vD3g-!XCwF!mDXuyXgTyc@x-52z>@`d($6fTaR$Y+CbjrY&E=JdW~HO zKetrzfbZJa>9YJ~O{H~ZuhDaCH|TElVX}_f$D!IOwk5OSuoRfaY{v8p`7Nv19%L?9 z!O9`j$AK++%F~eY+foD5n3`{C%zsGIRmp!!(j;C&lxkPwk=>X$OO*!aNrwAHcF`$Fel2bJoSANsQSS@vtPfy z=&N&~p_naH9WB49e%8YQc~#`5ycxErJ~*}lP0`L?9I~jgjoHF@oD#UK<5j2!!T`)b zzAF-$Q1|Wqw)jrU#}yFl^744|YBS^Co{6^Ko{7=%gy0ZI4ykNbr*;+-GZT&guMfW> znx{5aFZmP+`hf1GH`%XaW653nhr?u^PzT}em*NhZGva4>Y=E3$F;G_-PH?8&)Cu!8 zF*H|u5jX4_j-~Gp+bRTV(m|GyF-MWFp}#e0AM5~4KHx_2pUX}ECPIOHjqzWtcQL;U z!24dOFyiQjdT@hWextG*Uq=XkV7R9-Ehw9Nhr(!-*Zl;a7vFh*|P+@W%p#q^F>lj4b3wBb~;5Cg!$ zihP=PaZ7CiZobc&BX@#%y)&a(UA(&9sDtARK|E>_YmT~)oU`Z9N<*Q%;?^w@bNKgvj=X`&)64hMUD)OJwC>YXE&8%UxUkdN9ANZX?>1(Uc} zw~uG9SK3*vof;+V)M^TDpmwm7dhff>7!Cz_$gYgkKn2q+$!@t15W>yDO1lm*vAI`R z4+6fG%(9gFYm-_d05sI z9Fo}@C4kFb@gbG97__AGyQfirF7u6 zNi$lLa7QU*`jfdqPW+ho;RR_yj<9{0Ape?>N+yjgC=3UL#e%Z7rrA5EH8Xsp3whRI zxH3tBcGhjUX+Eey*p~L}GPBvpao3#o4E8ac2*{(mf~y&F&TZZwwf(-yeQrL`wF6?> z^FJ!te^V+HvUU7x=>ESg6)s%+o^lD9w0mY|Qm9d@K-~K9C7sls?|if5%&5|Ai2Bw* z1;^)VAR};HV&5t@qVs1vSJ>#4%lA8l))AUwW8QDxA{OBW#Ao;SUKJ|F$AP)`4|nKL z{&Ao?l!SES4(-i!P~HAid7zLPuIxD_Mctx-N*!v1vL6w=-Vyk#2S|#GL)o97j(V7= zTDE;{ZUvd|DhvkQ)gCtN0G3H-eJ2G>1_HgVOxw642tpguYY=d;waOhLIL_biHJyYG zrxzD7^~Jg;H|?wRAei*$ZI9~5dQ#6JLGGN<%wx~R6FNXJCH)WsrQPUNS|c^>>8H8) zOen&H6Ewp`ixz;TMott>YFweu?a{MqBmLY$j3~x2z)~YRLvUuerq|Sd`5HDJw8Am^ zrml8&xPY%s%M_fIQpxSOPrqyFL*W|8Q5T#gqe=K0go(mp;5g)vzR+WR8?59;1B zstzpM8V&9eB)Ge~ySux)yAw1J+#P}j3r--oySr;}x8NG!9jH`SceUO6?)~#Ja>n2< zoVC|pd#))3!{lgnSsj_*4kg0!OB=wG4e!D~P!#iDF`M>o5E)+UWQ@QW2x6UlEp*PDc~ zibdxZ9NO!EnfT>b6OH$Jdn-D$*amF?o@Lp*Yt#z*wSHsDdJ-V2JYgbUF)eKUm4#QQxv z<>-*MFlNCoRISzod{;4-rpfp}s9IA0f~rNmApgpRsW~M+r)RMFoZ4rD0=qnr3!d2r zh649GwJlB*1Bis2n{&rH77Dm&Vsb{xdjK=(0}g7guK0nxXTj$mH~=$g3E(p86~tB_ z38_YU*A%QQY^VMf8F$MDkz-lavvu}kw*3I4s|{kCY0fd(JO~V3;>Iq{6x|n(LgKem28;RpuV`xH#sk`bpRj| z?$08`x`L?@QOprO|GME?Wo)EwAEaeHjP!5Nl)QP-O&eKk0EOxukfCsGOI8zWqdk{_m zA6rm0m2(Nfab69&fFzR6O{B;D9?WxKP|7%xdf|geEw^1eBLSkWfQdk@gt8Q7Um4q0 zrf?aPbTuMug@9mV?-0L2_+7GXWtcwF495VlPZSxnuF2F$YPu=97h@WsT ztofuJ@84MS-{#)_3u+zO)gRsD)spAmbrX@7e)6|&Ld}A~m}aZRILw?tqzAC%xzr7R zr6pU1>ngcZzS5E@f1}oEAHg(HH5^|*ly6?Nj(=~`X3x2q1z6LAMwJ1q>1F0t_50z4 z=^!z}Y7`^=TC$@}t7v#w5H;b$$gKyoa;bPKHk0@|BpN;FpsogOp7V4|G!8rN zbR5Vc$c(Jl)V9gbY^V_$hC@W9D2VLuY025pw(G#q;HpBKm_k?XGo~px8D}N4nbj20 zWt#;Il+HHQLRZ*H8S4YalWl;23;3?{SYkg_9$mCnAA!H?CPMCl)BtPxFn}SCPrNL- z0-fxnXxYW3utyBQkOw9+FQf7Uc8eQ@^aK-xaeF84mx&zIf=?6aG`>I&!h96zUl`CZ zb{&F5566L+Qu05oQ=c>30=+NjYDomi2`0QrqKh#NK`^oE*&VKox9I$VCQF!8G`y<=&`*2(NLM68}ksWkOZ zpeORpqxXrCmGkc}u2zPRUVDkt(VTp5Z7>c(6Ye!+q7=^lWthCJTQBHtuQX~l!(?pZ zNM~pm-WKtiw3V?JMubVJjW%(Hb2)P7LVq_CK~^50S|^)2;GeIUp5m+p5WNOrE9AX=C}#zb8K1Dv_p<;KKVS5sbfiHR@?geenE7r zDSfe}-vxaB{qXS@-!F<5zh`m*hQya(Ri1sTBlRWC8eW0r>Dj>SJy8@kKys0P^vRTi zwUQ~)rva2lN{9T{#E~;oYDoW(@a4V%j$Oz2o9H>VH#VhB{RSO9gh|-bIMiI~2ISZh zBqIz$wF?JKTe6ptWAghF+gT**?a}4k`1pCVQ<;$WgmJZ5{v1qk3_?u>xddo#omh9v zQwD`9!$Jn4o`9u1cQ@lsUFdlPz4mF#zVBvy3&x12~lK&!ylC;tT*uGY# zgdjoNW0xjX1TlgH_@-%7aa3YqwQi2>Nzh!R z&KZ~&Ov=o-&gbiw|H4B)D&I%JGy5xryRTTcl>cTz=NW0nYOfqZ$qu-PbB;VvW zr?sG0xk>1sf*@xmH|oK^N(#)f;_pg!cx#_dn(izX%IO%#YWdlWY%&y< z4#|5*A{FzZf5Mk8Q0cPiMGr*>&_fM=dF||A57KlL>De!x-9AawYVU)^@c6Jj{2lu( z!AoZcXi9ja!01Ff0Gw(6uDXkQ#O*w}V1J?ENA-^yD`NLpjIdd~>WOUuDGY~--A&jJ z!@ZN`KVy4?K2g17j;H{}#J@SMy*839y%E;`o?P@7nW-`^*3K68*1wpkFHUPO?VZXk zoe=U@dtXL3%&+7Z4AeB=OLhwEY0+`46Wdb5phAXurTDmIMkfC1@1uRYOI#n2kCf#* zML&$Z(E_T)7~CBsck7V1tOB#0nV`mJ8v!!`#g zXv#0LPkUIHJ(jy#!C0n~Xq^;?Hex(nnB*q`OSaPNX^Aoy%TzcMxG$}CgT5tAIiM8x;uroKRlR{uLqtGs%5C-Na;JMC-yAg9rp&PR7@>DZEw{Lpn z8*ikXB{+dHTtZ`139;n6p)j(2FQKpFl9LCLF1Bb@`&HYp zcJ-E9(wpRrigfLn?BK4NPqGDcYo|R%t$lv`X3*pq{=3uKUo_2?uyr+YbovzsQ>Hxh z8-r5}uAD#~UtTwVeS$bpGmth6VALqDOaWY!zaW<`!Ia1pb>slh1EprYVQqf*0twV_ za^?kyXio?3j%u%Zo_uQf1-zCT_VmJ*FR8ajYNWU4L_*tY{vr-1p_}3YI9WzPUNy6Z zu;?;1r|$NfKrlJrWjxHGE_AQPE}^6ZQzs+xR#Nay!O~BhUA6Micy0 zM+B-{I((!Wwqps70Wwf*6u#@HYiadScv1whf^UxU=LRU^`|TZGJjc0R%Q2i?#Lgzm zphcX8<1l$d4}UR8qH8YB2p*hZL!u$vZ)-18AzELM=?_qcy-*p8)cw2+4TggCHDYTR z6$qAT901G;GX#IKf!p<%>z1}Yd>f%xa}y}`Fwc9>+8b#b@hs0LW@F~giF5g5+P9`_ zO%?(J?1$xkd=MpP3jD*9?yULI-W|12)c)<%zdTW!$R*mj35tMy~ zp^ltjSn>}Tfs^b~RLRstTBR?OU_3T9rWw*Mu9SlQ66R+ynMM!l!@rVl(;!KmC^% zn=RH$loqPsA5mJrDb@ZlO6&h=X_beakH?f3o=+;YQ?!%>I|aAhuO`q&(!%yHlxl^n z+IGR=JO%)Zx9>iyE?z5Wjh@jkVwWp-gS#2+l{Jnytp-g#ZW#nzh%JCfKC65{B%c(* zh^dx`C4M#L_{v8^3LuZAmq%|ga#~xK80*K^;iPT|0Y$i*` z;SD3`d@uw=^3Cjv%OL?G`PTV=N!7IF9D|6l8(*br<~vDP?zN>Q6$z%w$%&`50I3=y zK&l1-kgCy?e$c89@%MYt0#$fShcOLDoZPussVzDujpX8)C?74F2U~i`djygFCZyzp zl>!JU%RHKCy&mI|rh5(DIe9q_fxOcor`=%|GfFqR98&EkUn2PcN=m=X3~@5XX7SfZ zzF{J<=N5pH^2du-t>q7`8uaxiT}5`G7p)qAd^|f2G?kM5X&w9A;Z*2Ft2XrTD)f!; zhj|tH?m7?*N@T%<1*bezf>$+1U$Oysbdi;mzEBKCv-u%z9M_*B^L6fsBH@_STJgD} zN^l8}Da%C^%f+79d|vmeWasx>|9r9inPvPJgPW9o^Bn&tyOcyFtruy~)0gkZor)GB zBFzS|T3Xag{+N+r3@AuQ{2-E(r_A4@j$@8(tD1T+jUw9kbI%sCKJzAq_=zF=CY&89 zN-+yC$m|YpdnG%WUOz{5Z_fSZD? z$q3UIr`g_%6pE zR%UStrcBh&l0Z~ry>)L7GMU~o^}G<|zH!P~rjq<4@FtGfl$KXo-`l=Wc3PtRju4_~ z|DaForVf$oJFzNZdaV&NUrfHcm5gv=95$NNd%~J4Aob@igkA0pm%5z!6&?B#amXfP z#0mHX^&A(UeQqX^K3HCEqd>sGU2^1d$7)qS>Zc$6*+yo`$0oD>-ssMYxB1-AeH&R! zk;U5rBYgQn&0ONEdNt-H?G%Be3>}RLE4?7zNBAJ#dw!HK=Wyohslm_vZAG94 zJ%QiWg*rTHNWLYvfjv64A1Kcw2pL&TyP+snB5nZ)=MFJa^IcRtV+NQCoSe7N zD($o)R^?+6&lSkMTXv%PtmxR20Ubmrkh@GF+w@Q!dOKI~f%l%->4&02Gj`{Wr*T}U zhVnJ#c?HpA4q56JzSnVs%2oxd4balh|G_ZqfB9AcXgh5fenC+GvZXgdy(;6G|Bi=X zEq2XG`HwCAH62l;U1lH ziX*QDqDK+b+s2bS9)wz7-94V7JTF^2?@vYG{G=`Sg(Fe5y?Tc%lD zO*`xWB0?CHqZ>fm^cxW&_TFY2ED4&sGIk4Ag56mlZ2c~D;#J-`5o17cRY+^Ku7f_# zkeh9|27iuuf~o$|VvP_Qb5_VG(crNj)hq>T_2Te4vto~0tB-H6e*WqVe#TkZBdB01 z+c)@Wi4T@aOc0pl!Sv(90SUksy62ZIG|s=Yg|2>2n9+YqIANBVS5z5-{dl9uF4D$@ z5AyDsF%rB?Iu&DN;T)|(?lP_u1Jfzi0m#gP8U7Dj=-&boJwE&!TWCD1@!$2wpf4~K zAZ0boJ=rMhPJJ;Ekg{s9GiYW^=1@bFr_)m-K6ust+)MXDZR8d_ng8dO{^t_?i=f8~ zRpy^6^zZUJfAenmd!|fc)ju<3UMuvk=6A+P9snv-u>nw_2Y?EdR-!zk+W=2;hCh|F&}JkWv7sK6BSjj{)*{v&rCJJeks?-+3|zuRIxsjbA9~v$zoinOYlQ zp zvm`DeeXd^5m#>)<3paS`R?+>|>_^X)!MPumvZ#32+i zJ#iZI=Ge{L1>~pgjQRT9!L=g_;$)!DopC~Ak~&KpN{TU^5LVnr-ndZf$FBQDkx(;vb)LqozwIi3&9b=F?lOYYGrv{rQUktk-qu3JxR0XImu@P* z>>E-=?C0lKpN5`hEh>W~=2jcEk?>6lk}FgJ-C)C>gX#l~`{aLrMF-Q}+oD1-uIjAK zp;b~U{_Izy_~lbnj+xfB$&i~nwoGrQOE5eZjfW3~nF@`k&W`n0#j|C6waU(`_4IAc z?E*jKty#-*9L~%%Di0DeNE|LX-Fjg|!=)q@T>>E*E!BozSEfK8SD&<5wfrB}8rfAM z7jsOHaM(3lalm&Ng9Cf=oKkfC#dJ2Q+NkVp@=ihpgvlB01cY_kb1-H7!J`{NH747G zNm_$A2V2nrq1;oHOi@}exX@nl7VWtzW;QbSaihuwG2gvq!?X3Ox>D&bBI&KV;R9(< zQaG8c8cmiMAw9q$Aiz>6 zRv%Fa6B`5zoxURUTTmDfTBaXmCi*D`t9$)`;u|^rTNDkNai0`kCn~JTFGK3L&u$JW zU4dPwk~5DH@9Mq3O*|L3-cp11$_iBOnlD(4+Rw0eHmuDkTZ~UDWojX_i$yoMdkJOk zMi0+g$z(=u%U)Y#wJYu=><_pGuM8-+ag7M^>|eYCUY16HMna}Ql)DE3 z;;Cbrv#Fgy{L5oG&J?@j)Yy{+l8ScmfzOU2er#vaUYQSW9_Ya{X zf4;hf|C%c8_q@q}dXD9*tiG7gKBeD^9hh1y+Vof({iM{HjBB)jVRk;`Ooa;@WaTVG z+1{UZnQ9_-HQ}1M1~)%t!_Q^_4N+Sw3Y0B#7u<*j=H=4hgdZjmoj3s(UfsI zBv_gVF>UgS5KPoR_SVyK^4q9p{d_(Cbrskji`Pe~_#H^ergD$3q*m zh5Bl+x>$e6IT1=9{g(H7%XT>+)-xAPtmDWRzvm-L)Mn87{N<(dq}EJcU3KT6q}Q9f?egn=)2;c88e)Bh7U@!Cs!Ke<(nqDW7zH`?i?zTu26k%N3A6T71QQF zo--w)$U03U8+~BHuF`=>4-~nh$n4|r=t;vHrxW7fRag`{P?VryqdXYL$dl4+z~J){ zshd`8wBCOh_c_XqjsZQzV8BCsbV~0-lgQ)H44Dl_u>!ysp}bLO_HQjbvbw^ni?lJi zrKX)pA-;)|X-l7bf_=TdeH786K7`^sFD%rF;~Y?7WKg1-+FJdZlEiEL$yj4RvpCVl zvB=_+jFg?KqiR&=;B8{_(|lom*^#D9jiVLI$l%w1){18KsUhFdVy z!-Q_SIY~wdQ{?hPd`hXxKMnU1caRASHsa)-qB=nKYIxAa;)Cyrw%}um6qdT$C-PKB zz3&jaAn2{8Zy4%>k0u<_v;#UEveesRI)GyF;(G`*a1GwIku*fPZeBWNNHHoub=WWp zc;k$b;32jy%%|m|-@XEg?H@rWzW`iqE&d~r_*X}I0Fd~fMtU8^KjVm0eg8)zy<*fP zfc&2C7!Dx6ABzWl`r^1%@_99B1#6;qK+(K0sY0t$X`PeR)LHKC_0efxNmiP`{+ zqsATtZ%!Q6As;fndab}=OHs|OVV8>qnjmpT{LbI}Q#=}6d{avOE_C0>$< zU}x+s=qjAo2Cja03*03WWvW|luQC=2OiYI!`iA+15CM4#y!idHXh(Ynw`#{l{f8XC zrtHez_Gopxpaq2_y*jsi5jMbnOhh!lJleG|r>paK?)wSA@e06wH@OHpy^;dh1%~Z8 zLQOIR*dc!){1EdfE^94_ z9c-$fDxv^bROIYlT)`I;pDx$s?L!*ytmvs8#C?T=)~C=*?voLjOm!mM|6oyd49vVx z-)G_f%%VCYWc~QxNBX~7pMVYSf2z;_|2#Qcl@DPTfZY5M6^fG&VUK8dnA3392Y}`r z`8^RNw?VgTM1Y8;!bQEn*GC%XF9KwG;k%YiKfi2XE=l%R%+IYa=;ZBXbV<>^-jB3DY*AcO=@BF@Ck$B^2v4W3DZ$ymCjte!MO zkNW<_kZoj>6&n0xs}h9fwJNwHn@bJ34VxKha)h_VrmtEj5l>3)mAWlh# z_Y2D1%-yK%?+m-X1p2xB#gGjHFKWs!UNNB%hs+}P#%#_e+{F_$tjv&RHXTm1c0HM~~(q{Jy?j_B@{?C5uqgw-u!YBQ z1;qKMmHa>o-Pi(VRW?3%7w!GQ7B1i+An5LBs;bJ=D0{rSdIDNQXMq3%5I{PLBU!Kx zSy|Cbm5TCsjr!-Xbb>lfoPRJSa4Fu+Sn}% zaRs&LsQ~;L?81fh6eJ#?m@u09r!JHvd}DK^!{yVn!<0-D!XW?wS{j~7If=0>>?l(4 zFeyZ!ofqmUVLFT~NwYqia1Fb72glMaLb-5E3RudbB!^n+#0g~DBMDNkYMM%sa_1K} z4Vr(T4gYyB!Tmp)gkSgUt_F@42F@n`XwP61&HxQ?K@r~VODRk&V;k>{hRnpzLxzzm z`SFbyi?u242)sEp5aLwcaFVNM*l5kW^()&4kR*d9tu`%(4Tz0%b7ELC-RabiO zPrlJwUZ3HBwS;3Rm{Lc!p{)E(!lYELLk(13frYjNjg)V8w0(=PG8)QlW0o5Pd;yfJ zC}{bnQ{o^MCN8&?3AY#aL2hXCT4EUROQL4mZ>G->lYaXSI6!BBvGI=*`tt$$pP_7m7XR|}n1pk|chVyYn+fsqi}YZ8 zHVAYCLCMcw0}VGJiNeMri6SW%?Eqp&AuRf2xMPubbJx1^W^^8f9J&-r1BGkF+k@HOvJ!zXnakvw6-I`)57~77 z-tmGD!y3|}l%{V+yv3&4>ww?(#c|)rj(7ZM^bCdGP_2uXu`#s&uG`etzA{0mS9SbhKSgBeP?4Z{+lmZ%ugx!nh$Q3X9`JjM>q%8_#)9 zO@Y8x)qo`}2=a}^hG6k-gs7h?h)fu#)GX<7cph4FB1TFbr%;DhTE{tW?kz=RCYeT1 z_D`jBq9q2_cYA<D0%{&pQ5!o-OZr;vWo~!nTIZ%aYgDiwuiP?KdMet%g&_{)s<2=3EJFyY1iA6#8`Mm%+&Z}0A4K5*6B5=H|Iqb(0y z7TQ%nT!3+$oHH0?<=CL^MC+E8iT1Q6T8XJ|e#-OW!rwFcklq8C9qDd`>C1Ju zF3QDw9Na-=*V8N){`k@Vw&NfOknIc{OB@$n>#5+i7DBY{G3k)ofe(#rhOhXeoJjC( z1QMS^RE|E1D2N_t=*1B&im8|C~@cu`*_hkOOr(e*na2 z{8P5`ROF5nt!F;-f-jz&9jY4`3zB?aF~#1JLWW1^+6N9&*YWyk&M<9h)-ajl zeN&~fngY`FlVuI74kOVN3ca|Jz)GqBHWrV}hAk4{=w($cFgh{u{5*XhqTS%t8Gh}` zjio3btUMA@Cb6E7QV}$muw`6aGxY>t^$2&*wN>NrKy@h=cFo#HVJ$Ku&lQ;67F-^= zTe{p$_+2nGwW8=MIB|4X5@Oe$H(sv`Y;^m!A*E7V@RQorF(92gcjt8>jEF+n{t`s% z^be!JpHXGe|54NWj}^!C+iNIaY2r7JRqJmKaJ8Z(6UtgOf`rpGTM9Ijwf6T0+p_p2P2g? znY)wgPxQc{vFT7Vyk2T9L55W<`u3cra*V@QiAiHqXY##YZ|QTy%j`g-!MRmG@xgIQ z6jFnr7xR>vEQi+D#1Ue7BSY}=Z4oB4(r;Ey%;H@TTR&)D?DbO~;-&71r&VsmUe%4B z9tw-N=0C<{BZ(IeAQM`$d6u#HmUDzPh$l=u1wl6|NrTM;MdIQd>sv*3EU{Wp8>^WN zqWPFLw~ehjaNd4-7h5R_F=mXE%7a!{Tp!7$QeQ}4`V=2PZ4tOWQ0mq}pH*~0R1Wgo zW3Lw$uznn&q9+;KTRAQ08i5^|Ag@Svy}vamGhA^whjUmZp(1$a-akv8w%-B$4%op7|qQ%XvZ`m~VG4Pkdu-&?yq9df6 zyYRd89v(;{11m7bC|*aJ;85=|5d_oJ>#zE{MmYk1P#**nV2R>%o(?_m)u`d<5pXL& zK!R)z5WQ5|n}1-({CVh<{$Es@lD)Ns?Vnz8WojDs$R^m&Hc_@sr6@6ueOlsamek~` zFyt|U9|?-`P@pZplP> z^K!)2^HTI(C6zIhB9O#$y=hxLYx8;Dd}zHpoU(XBj1G!7tDbe z<#wE6Qx>ddz5qY8oU^ps=j=e${tbl5Wk{9~BRo|-j2o4@zbDG&hAvomHbwd&va+P8 z=FdIodj@>nkB0Lx48)ru5fPxzZ>Jm`k+_42klw**ePWmz#MBHD;zH=7_QWrRvnmqc zN&oguV`wXZJ8e?T{6}x z$gBvtXsxM$vQ-6hPJXt&ijg`KL6v~W=JMvS)|OK_>!{O&CO#@dj^n+SU5V(Nb&H0gn~c4t(wLf7oMvj(i|AkH=J z3sB~eYL#nLwse{2Of&{clLiuMhboj|Hw$64MBt<3$>cF{v3) zrA3XG3k*?=D9d|UC~5mp8Ka8o@esu89}Qy_97xLJDjJ|!kl&L{w8=3+TtesKq4e?+ zUvkrK8lXn6DWJ{~m2Qw)tDd3DiqF^3hf)TVCZE-Zk)7s+71%3^TP9Wrx8se^cgd5h?#E%6 zs|YeRRNZLSEm}-RfS#r(i6!U#2V1F_@8z+3$rXg?HW4El9X4)R1v{Bqg{RJ1U|$8p zGL5!k?9=$rBg5?Mbt!0nv=G-V)v}7ZQE10=##Kypg7SGb&g;E(9;i&utsstVrE)bgKE=XA@X?q#v-Wv&^cXYr&ivU0VI zAw$DNduyZro`Zm@$##pd(N=`cTrcKHWsmH8pcAB%|8X8`@((9#8RZW=oqjM=WEzBO z=b(oIZ<0I0O>#gl^qZs;WN(HVhwX5P6|(DXL7tz4;pTwlm}U5(y}=sptf*7{3(SC5 zsreR=|D+#Bzq;e^bVd3If9Ih9KC3m_+oE zrJrzkXC^E+q$1M|KUy~8wAmZaOzaM~Ym+@l^rSgQA2k&bSXkzTdwb4d1SRRxI;DHE(<|2AOhQh7LE~%; zEZG*OIcV|2rkouNq*TGG@Cek8RexA(XAN*o@ZQRwEpgjw3Ro33rM(g!>ljDfRr8U% z?r86U9?l5iH}aujf+gRCvx=VZp!wRiVz9d~%uNGG)Exloj%w2zstH5+SbxF?F zRF^j<4;@us_DUZ`?9>da?`hVWgF2^S4gghXv)yD@C6;r~t9yQOfu`~d(8-1>rG(KG z=xtxBK1Lxr!x7!1IJmVPKnmQ0F5@{-Dg7)+V`le-j~Fd&HiwZ<(W1kOnK^1^LLcMv z8ukZ&G~f^z+V4kJr!C<59byrnI)VecIn!%P=txpnUNoEPOi?u^X|qhpAEFCK`l@$f zZM#5oQnmumkO^5vmR2<`*J0**N!c<*rOYEY-sKE&jE^iPh;JVlNlo z?`zb1d&(}?D#Ui~&_+QAm#21&jMR)v*9H!Lp>{ocjG}$clz&`1*HM_)0ycuOrSq@E z;R-{7mq)I&JeIEQ)AkJ>Y~U5^m%CgXi#X8(oNOBCA|vY~=Zgdp>|+rEo}N>f;p9l4 z9~P_o8iqc(A*%zo(a;QjaStH#+oUjd6eq1wzONVMNRZs+SHLn49P#g;Q-2=G16to=bGkv=BDIAT=B`H{1`~VjpWg=20@+lAabX}r%dgq zvbUp_x%0RMa1nUdD^5Q+Jbl`nTz@?7c7cCDR|R$lKYIg@KhZ%#F*F3E%`aIP-svtP z#QBD=*La|xk#;D6I@x$2Oj&k|4u%Dz9YuHMvek5g2*_i#*@ zuwWk9mZKvYU_+(sEMPWjo6rfsc;}gm{a9s5$%j!I#D`)2I=iJ|+v#eb1Iv5A_C6G# z6z0z46zR(?7N>mjct2ZBhgC(g;+$Usmdk81pOoGrHKS2sPM1->c%fjlKu(=9Ay}hb zu4*~)ZJiocG%`#o)NHtES$xBrL|Ln@Y zfqISwt_pflEkaSJG;re)X`Y35c@>f;Xd#D%&1@0&JEO1xv+d$6^Z+W;?);U%Qr$?^ zBUfIqt%jGP7d9B(kMvn+DHY~jn|O)SzcRy}KH5HhKRTgeCite2qzVOZq9Cvf?VYYAqe9MXxYSE|yjASdq)$rY z*S#)Bc@ipO)HCh?syEKypUauqBY+cZFE1n@_V!EEuDyC62P~ENk@%DIuz`4AGqqU7 z=dRA2C=y|pgaA&uR?wbE0Qw-LAqJ)bM#nu_fA=PRLYl>vT@f{3;$vSW47{my@^2{9Q==(R1eB0QAMM!dl8% zFm_Y`#5>ez)an=&-*Y`728MPeJ%}GVoXy>f*=Jq#u z9>t~}MyZ5F#ikQ0#Amnaze{3N5u5BzS|znU`{{smTS`6`% zr_!dn0qG6g&&zMIw;Q4hetgE^J;_4&Di8|0ETF|cc`M!orsv-NeI|tNr_!xgY%fkV z0%X}ecmVu^t-%~b`NnPo?s_sFdI3oCxF7X3A(`)+Etzuw<3Y$BH7mQ@Nydpi2ysnu zBXdJ>!yfBi;(-En=c^zB$6Hu?R5P(cofRKNZX~&=?|#?0Nia>?EKKE}a90#6Om-x& z`=HK6bf%SVoLVPFd2aYKgvZJln&F?Fw^%uEK?5)%%GN`r?tOktNnQq+BSlSZrsZBT-Z`AhrN^CJyK!;a=e8d9ch;2rOF3y;J@ zTsa65WJ#v2>M~7p0_Qn>`gdC(T_Zo;zNy>mAZ@%;l!yHzi@Ln-%UV+9v4BP9Y+I|1 zCgn>~ndU1B($QLJYIoB6LZ`W<@y@!+VB-R_vMP%*r|=qFG~gchAfkc&+ZM575)@D>fn61BdTrZl=7T&+2MwBsps*w+FeuwF- zup)|MfJRHna`l#$tnki2>xv#lwja+!Bf0H4Y)Qu|;aweA=!bCc#_)dfW}>YKxG97)6j{;lWEx6cEFAI%{p_1v z>VWgg8nPpLR#pGbtT>7Y-A=dnKqv9t=(26Yx~cE{XX;yT>C@*Rg`e-#>c`gH0`B^5 z!F}YMpR#9EGtzy@zV~u;HK9q|%`0O3h+^>UvFT&`9&zSL(&nt|(6%jLN$v%qQ);JH zf5vl56j@j4iSzKq*S}zP+?#DVgn9at+jvbB?g|ghF3VBdLr2p6Q=rBZmD3~J{iU1g z5#Hrqmi30O-J2!(l42oUmAa^|WbLxt-%_vOA;81N6iM#_lGfxP%g>NQPecW9I!J;OC#AKtUjvhqXyT;y*dy@{iv~ z_}A9fswi}eQ6v_VPgsfv5~`NoTH2_o%^gH9&dl)9HdWW~-B(?6xzRGkgMucPYB-(n z>>jm@JzZZc-#p*+QoM1w%>|j6-)^^sEu2>hS+Z{edFNG!81E1a;AG-c#PJ-O&P^CB zcI-YJ_2|k?%aIi$1#zUl-yY9SPA123%A8rbsR7{=CgkX@4A1AZM(;x#ysM0@a0Y`q zR^l$u6Am23qA7Sdrxa?>-@YF$dL?WmEJb>i$1kBM7f>T!mnj}(G~x0@3REenZ)ilF zDs3^LT=!1ma8_*PZkX?OTQu^>FQwH+iyd(`m*N|mHStFqKy-`j42(Jz8>@;740&Yb zXIlAX%&3Fo{U=?XO4Y+i`}}H_cWVZi(Ob*f%8K3wVVWzLQUR7V_3!qktUxNCd@SXc zzUJSTm(Ap88slTg&h{F``k9wzL6cd{8Lw(hPVk2<(q*3rljr<=fNFa0#veTtnHQEj zZClXYc|n<0Og#Mkr_}LB5AtlM?}{2CwR6UCi_8M24jL zgR_=00)~%GaWnPe`~wE)y1Vg*_X&2gOpX!eltU5&8Yz+x7o;$B5*aQEjKq1jUZ{!; zja1lhXT*{V<;T;OM4HUXX&NMfDu*(x;#CvxruyDe%LNlD2RhT54!ysN6vS7$=T5uk zrCCU(0G@RxT&9aXtovfYKtUg!o9otuD^63i*d7yhWs65Mx||oGUMwd!&Z$%BO!&Dj zz+@qXbLIMi;%C*?EBrS&KwhwdL``J-D&K{-CFE4_EU9m zG88_c$e11(koqt(?m%@+l;y65Sg!16Sk1@X7^Po)O=pJVa-(w#9X4=EW0u-f&dT$6 zsDfj{ZeT@SgYMKy+*d;pPP38m0IvK#KZH^6xZd{R&AatBYJ9#((_%t_!b zP@$!DWwml@G48sF(bt1_enn$lUNW#MXoAcShbo+&v+*~9|HF+SE|%;8)jqakw#Sa zZ?N3HsC*mMEx+deaVV56BK5_Xo!;@jOX0m85lUOSMKj7mwYzrox0X5OsISMHo&x16 z^Ms~#H5GM`^;B4GQ67r6LwGX#1Qu{=`OnQGq+@zAmDRCcBt`>Ua5R|GCoyv}VvOfM#NM}GKY4vW!1(}T=ya6)R2MTY=W z^A}lTd1ZC8sOpr{Y#-5=ZUH5EMho4F%CB+N412#3A=BS~k2>g}zUoXB%&@Sl>JOkt zBYd{6SSumY^Imt!Qq~I|F*|DoPwU|UzCzthH^FYPx3~89H=Up8M2JQu@0GNyhE`FR zIbJN3PkbG9HYDG*AHph{~an( z1>O*)0TGmaxI;Tic`UgnKSAP|Qx=1)3u8_>LF872ltMwm+5|&fEk;~A2BuORKUKEz z?N_!fAY|fadT6;W24+!VLb+~GrGSYx8NFuV@FFkTvq^*%rK`*dpHq)Lf03|0Ol^Iq zg-l_M9%hr^Ig=6?YDI7x=fT~n1nj5x!cfaHu{ZL2E!_4ouJw4hM=T(JFotfQ!t@C#XHPzN=swFbWs(+czAZY*@keL^A5A7^@bz5oV+QGNAMoo< z`^`5jJmSi76BQ7Z@5YSZ(h4^C$;URD7-gq19~M3f8xDdlxm1gg%~2a6x*E0YAIddQ z9;2{*zT2Yrml!%X%fHHuKQQe1)_(A<5ut-g$3X**ewI^j=j|SLbr_M}BT=6VB>WvW z@JvO&bI-8@#3v0h`UW%3GS#Fm-e3mE<`0C;;=^=IchL;TK_OS@H9m=`jH8(Qdd-&Yt8clO_RPNlIg)Scc|UxN?B}lfT-PlfpgP zPH+P1;DSd95_eIp#sSZaafD)7~a!};W-}ZY_jsRQ|e*cLic5*nF&%= z0@#&lSG6+Np?}Q2KayZPJ&e8=W6E}rB?iU!grZcbAu+U6$88O1dD&u~q@2-gM-aX~ zkFhE85>tVzqbrXCS7&%lW2KT&gOo9UC<8x2_4q(kZ&q?4QPTWi(Xd!0JF_PzU_s?4g)`OmC5YK-?c9=y-17>Ik2 zhoBk`S%M@p9~P!IdgLH)rFWwcgVj<8kv`5?rjSQXYVKZHz`hpcKP}DBXu?+K5yD_heRs}fVws$_C1H{W9wrDjnTDLY>WDL^ z5rt>#^tmhL>WOAtI2YoX_JBB!A@bruf_(sQV$fmsiHxC#=*k=Q^Kf(zoMA@wG;Uv% zeooax_;4a=&E;9bbaY^R6vCvkj1o>^ej{e8aYwiGBexu1x6#rWGab zF#4vsS-2Nvi#E#yb;k8O5j$l~=aUY7B`&{R3&{t1%E}&nCD?-jlhR06j}b~IlrZa5 zg4f%spLJX>uv0Pz++|xWi$e8FnG=~~38NAww93gz<4#Y;{^RY=X>Z4=$Obi`?6R$> zg@kdgid0OsYRg|zsFo&XU>2A{4=|wIeR1PZ9aU$`v4&FA%U1suNR39+tC*oxI$P5^ z^MVO2Y5hjT6}jF0{#(KotA7VB$u3+=f0k5dyIoQXnQT_LRc^^PD%D7z_V?Ib4Im$L z!Bd$>i0OS`)%vo<-0RQ3G#@?AjWpt~RCXQo|9CI|cPi_DaxZuMr*-XL>Y}wJGCzVh zYwLcz+bWiIqec{+a)KFv<`1z%T(A(ZxnjCTn14;Hjl-IbOW#IetWP07;`cvad1&^R zSTqoX4EQFGt*!2d#;%87`2kzsthy%&0@g^O)QRoL6kLg%>7bFHq$^V0^mYjZS7-9p zU@;cASR1zLUwk>MYH&BMEK!%e@Y*t5mX2h|8|#{lt66)dLf^C~F>M%#BMJq<^7CT8 z_h|`I)^eV^2Ksb!;(ZOty|BBAePevh#)z6uN<@QE(Wcl@<-+^!Prc?-9YA#%1&p~2 zauJnyDR~L{xcSo?Rf0}!<<~4DH$Q{BSQu->!|eUM?vSuOyRs1w^4f0&8o?hYLh0=IUw@5NH6{1G8QXE?Pj?@PQjKh2b>zMNF zjdL7mG9x!O!+EbA7%yFNQKdYF_-GVL7@h2m-;bD3pZCk@mEVI&hS0w(4605depE73 z+!$r|kDuH!jk&KZu!9+=-U&U~9+C0j)nO@CmnyX~87aB;Q}O%xqJ`YjvD2Zk2S~ZN z1rR_%x281?uT)4E`xqlCYZ!fIjf#c^8ac5a2*^ibN4ww1=%jOstPp@OlYvx9@NjiIrit+9!TxuN;jd{IYH zV;f@!eW!oL2Ny=yN`UZxIatJZwYi82YMW|9qaq4Ws9}VF{qxiydt1h}S;K_l@&6GjT$K6}?!)uZ{FI{lt$3MkhOSohm~EHX4yo6TnbW)FHdnsGh#S4oYs~{) zdCZ(g#aS;a()F~LdCr!HNXgY3wLvOsB0K=wc4@LX*t$b@a4-Rs*D(xe=SG%+v+2w% zPve8Dd@C~Ng|L42Fara2CHVf4kQJ3_H_M;zx`dFCF>XK-F$0q`&V1mbE4WtHHa*wdAS z3jWrgAo?h#D}gm&@j94i2vs>SJn%<2>`jPjjZ`DeC3h-+4-s`K&juZIz#gF{)K46HWEB1?ng9cdY~s{_k{2^o`|drfIngJ9(jS4KSAby=P{X*8)X6$@u5 zgKQAbt~j!q$PRfW1a#Y3jE)INbn9~j%`X1NcH0tGv<0%!uwd3(w zQ*azj8SpIY1WbAC35D2d7YViI3*BKCOZ&Bp@hv7{5REp$T22pcUCxm)=1(*1wtIv7 zHa`<;BfcZC@@gd)Cnke9RvDjDa2leP6c@8gNN+MiCtFTfLt#O!E<~@r2p;@^o;wKF zZl}LYX++9|mr)0O8@^Y@cDP-G0(JE89_hoSZdl?vM=`s=cOZo}FJDR?Xg^ytZh0&D zX?)rO-R?v!m=W#LU~cCmwT*~7Rx2Qi?_x=QOrBR@2-4^0Bmmr*FHN9UoF*G$D$*>_Nt9 zx|`Xd=y2=eG3;S9J6c?MdReVLKJ8R%WbgGAOhtSl6-yOoxAjoI5!>NMN#Ty(dE!7S z=|bC-ktfNI#3Dz075~zcnU>8fbih-8y2#)$VIV$8urSdVxd)q)+kW)}+2&ib<_cLw zWJM6gl+@VAJm2S};2(hNRx^>a*{`SRZN566so3t0qX88EX|s* zI0Po_D>F~{Xifm~_bva?;P#y|HRGZ!J|^lrr>m@FvjaXq*wP_dHPosF-RkLtmk#CS zY^Dg|6_P(A9~Y&#Yr*kE1>2qoX*7LUfoZA{O6L~5Y1r@V;pG(^3$~Z**U_7HNq`8LZ zboXzqO*}%i8CyhPHFyD@k~`nJ_$!Kx0q({S`F(#J=+7_3TH@CeLJ<8lG*}o^$V~Ip z`s6PyvE>U~H{LZ=rh11aM)?>784!8784uI;nPe1h7wbY^-G_Iy|)t zGO@+!)|3b#Jt`}ouZ+`4B!(Y&s~?h(&kj{h8tyC?d><~`Vi?BlsSTDo>-yzL>}b&R zvN9n305%Z0NMXVCR?d=jxJ4V99jzIbqEfAjbX$8ULxYp8pSvxZ=TuH$a_6_3UZL)X1J^js!vIz zWno-8VCh(wiQ=@Fm_}}tNZGo^-efw4TEO^_>BE-|Y6wS&wi}itB*GMyjuTpGP%;?U0g^(g^awA|>6PcO_%EWf!+@Q!$LZTS6$b>tSA^rBemaHl(e+R=)en4!Db~^wW20ThaCLm~(MTDG}>F2O}p?Kz5C*VoI5o3(b|dvLY43nONX!oaq0ez>K4S<`@eKZ5$e zD>2=j`q7Y+`}CULoYu=(eVS63R+++~Q~)t(nY%%;b?K=lAU_dba8jI40DwBP*{Yp&o;7}b!@>$^+dj4nt>OyU; zl2a+iY;3wb#>HCyiK@{z5sxN<9pyG=!TgR{IoJzOYABCFO_E=^1NDZGSCJx9uEv~s zJjc#RtLZ8%$ktKC`vMd^81QXn&uSbCrxQ*uFk45pE>SxXSUj_KQJgBfvqB!2JWC_j z;scQ}mLDIH5*VC$x8ZFL4_t!=!%$}aDIM3{2vEt_tpa8c5gI~4@Rp!cg%I07JWmlE zMnc@t3cLhpzlhVXOUwqv^|uxCK&L{5pBWFTLkHNYR_V!-cW7p!UHcv01uGDAW@v%) z#HkU=g(B20X3xKy&xq}c`MWJEr?eNyi-)~wW%-ktlR0BS`ovJZ*dgVRVj2(+tH=NG zmcXJ5nX3w+l+-=RN;h)~>$fc_aIXe%Cts5wwM4~v-5yC4=I{uIk9=(5rk!O1fMAcN zo%q6S^>%`WaoUBhanj*Cp!zr?&{h;Q=hQHYg_(tZx0Xo)hPU5 z`U?Jk0Anow1Y=6pUx{uA-pQNVlBG@l11U}Z;j=0`LWE)RVSW%Q{88kP1PoTyl2_Yp zl9yE^o-7|fq=|{KzR(yJvhE)Eo|PsE1B1wjv1xW%*3!lb;OWnT<~QUTfc{P-scAx} zA#t>$I0ifZkQvSZy9A6$#2XO}n99knHP~4j*>AISlmUsthH<^|vUEK$IyZ%NOV%<% zxBhY-^H=o5zCXrzZW@=AQNs@cVDtr)3gLQ-NBZPqO!dF~+a{V@_Mq0}qk`jeH@4$A z%^gSnWKBa~&>UQeEnK(Yufjjx>i3Jf0&CvJbBHDO2IZHE404HZ&YQ=CIBgYxC-ABghQ>>JiQ7 zL6KpC2z2VNKsr0i-h;#py31OV2kM*Fr740}0q*;S41pEIxh}74>yx3MP1>yRdgY#B zIhwPFM3tOuAC@hb3C7`$ludi&(lh#^eV_P*0GMHw zLT(&JaEp;zlip*F-X^~Xj2P4)2haabL~whJtkrrUS;mUXZu|3!Kp;f2KWoE3hRoxQ)a5j9VmfWnkYIL5mKB2Fqwbca=IH;=U zPB$sXLiOHn^-b)S3}%}tdJh`vIb7b;($%S5(Ycu@Dtd-s283U%>8n@kTM%-f0kQ2i z@jZO$H$NPLgxv~4+2OoD0-SdgFoW50(Y*H1SEiFH5aD0KDVPp-gO$}~9oU!KM@;rPf z17urr)kTEy$P5VmbOC&Efw*7>v-vDBNq<3XY=f_PceG!F+^ZOw&uj4~M;6bl`CES0 zNlcSZdiHPCWaHdvdut9wkyY;Yqx0tWt)BoFW1ihojam#?2q(Qy71@t?;}<)5pDv#TsX)##*olrfz=F)rB6i!5u{&5bv1n$0$j zoS`FY8(TxQWhXxFk~U;}?tPnC!y5^#)uN~11vkPnhIyls@^r!(oo0>_uvcc+AB^+} zkVESr79G{&8_3Ea_S{G=wo8Dscn4#a9UANFrpxC#-9vn{+ac@W-$}vcrow7!Zp+bjZGNX!mJr_@3BQl~Fc4P5 zi7&?TWR8Z7McTqvARl3>Xx5|A&aTZOt(5V1LRAUf^~<5jAA!&gsd8SiEy4X7Z|_vB zBid{;^%?jD8+|~jAs@2urDh-Vupx0BUNf7g+oF0SYV@p`LWI3FmM!{@z zFxI~8du{D~P&DF<%RoG+BE?4=KRPDZahH@&0$t_Fuz*aE)16hL$e(~>hulw_>TFK( zDiL?P5*Yjqk*#sXzE9At2(xWH!YXH&CQ(v%*=hUswTLMgnQZn8zYlHssOTa|QuR8WCu(Tw^D9s zX(L()4Po{eH~Ru3%UekIIOxFiq&_+$@wY?jQ|%aq?R#y8Tf*>1T7vM$o+0UIZ+D9` zGjncsL0}X}Gghqvu+H*b2?Za{A0=(gL6{4I0UI3(mi?Tl3k?NjEFU^m~ z27>43BRdt3mnLHF7Hve1T8{g^EWoPO{KFL`8B&e2nhzu3LI7&irUbsAhnf%B1&e+{ zUH=>z0dg=7^f0V~ojw1U39u6GzYRh0g&zFTVo>Q23ZRR4qDg|!S` zR*&CwGn`6onJZj)U{B4eXKb0lkK}ttgTQtctv*gTDnM&qgEbmJt(DpBfQ8sEDtN!Jk5J3{#xH~bnraZh%ChIbF~ zePDTvRO5;g>K7{%fnPOOD-~^HLO)Dt05PY*Mz2->hT>BMPp1@Sn0fY$6*BpK#_uK4^y6Pg^9MZ62ptt zr1&x>e#e!fx1m}mQ=3wud~W!x_XoFmL2|GZsaM= z{N`x-Ot(f&iUqG_z~CyPJ}!H&%O3NBt^6C;8KWDX5S+>neC_^%P!hEmFXELGw<;+K zhFjPrj%iV%M@*M~0z6XPo>-3B9E_%2uJ?k*_=BG%1*kO$M8_h&o~3c5X4~TLxMJ-) zca7kwogLXbQ6ZNr_Rs(F>O;3)F zpguV?O46vVg^lY)%MP-JBn(zmqpDUP_MYiOJGWzMa~xJgcs@*ijajriP*Akf_rOr( z*L=Fo@)9mczzB+eZ}mvkEvVWAI}WU^%CE0cTL4+qYSmEqVu3ja;)_lq<9{3Kh(hj}TAv z&gG1McBGJfzYFzuAedTyhxjOiKuH(!?b1@KULKSey9*r%rymgx%2%r`#+o!p=_ApQ zq%+JKJ3+G6YKbJgqlP|+C!}aXbZWst{TY}m_F+zca^X~flR};>to1R+n! zx|kNs9`r++AT=K*YbHr(=Tgg!;h<54nuI6YFCnYj;E_7H_9%8rr(5HZkhL~t*s^+C z-v#OSIm>;$BKzoM1sRq8+3{!+DU^6A6pzkpOI#{Xqi z>z{cHg^HhFJ#z>jtgY)TH}hDPjVhWxO45`b7N1Jt%*0q?mBcJap!)S2#F|$wW1GUq z&=8$bk2(H%@Y{l6j^YJ!2&FsAD=W4pooQ=XFE3|j@ZaF=o4>(F;8pF%^(-h+ql!@j zS`K&GLa<>jkqf^JBe66|YcMhc=VHP2u!RQ^`twOH8Lol?;jlz*%ZDn3N07(FAgD~f zJ=K;p)+GD(U%ka<7;Es)c<3OQ5XizJL;U>-JsRCC@K1)Q-~iI~B~k^h$bb~l*K(nt zo6-Cs7$z_AOs-rZ%R-Nri?1tda)b~ju2qS*bsjPhK(>5R&MYk#wXSG3{V4jVt!s?e z?)9JyEjKLb(stBH&xNbvxg}_g=a!s)om1Wc-&O8bUPc(N97eYIH+=9)!{m?sHhe2* z*FrIjP3e)$Hk^M}8h=Wgn68nMS}-eqGRP9*eF(N$)#c~e*w!no>~lul+o z+hZ&Q{}jV!vMn5<3EJ&`jM#J)v4@PB?Ez_}lUPV#Rlv|#KyhRd()`LY`PRB1SVKot zFFT9thi{)=!0XbDnJLIYBb=G@oh^*HP}8A{Xl?}W$J!}7xSdAUIvcPGFix=r_u1MVJwKY49stWbeA>edrVrHlscRILs(_L@!^vbuBFERQ$4e&b_1P=OG4?<2gv#9UCV!jO#^y3|OWu z(bDmlYP^v!8i7G3#4Rs;FDH6uoofOFkzO5Ek!gYvJJ3%Ywexe{@5eLl4*C>3=!-fD zp|RqCAJu&YY3(ff%!^{MLR8T?_5Ie~io+YL_`uz+>GP`OIE*%MpU$>BiGkhs^K_*t z2~&d^1PNd<`w9K^o|p6;u7BsdET!hXxQieN?iman~)qiqug~&@-8ybgvpc zZinNG7~6sQH=yqCOy9Wuq-EoZOuyy^lg~gWuH@vVaBox24d(^!VKA(e+*4rKqL6ts zP!1bLvaF;U7#K>CM==h*ln*FDlQU-Ls+~#u22D(P3+!&t3Ftmtk7gPYf|Eaf8@S9* zTxN6R8d)gz;Fj4VUxOKne-AN@`+)qbS}F}vzzcq1?&ts89mdT6@&Ii8291giF>H%W94G0R(Sql$h2G1(FA70m?JlJ@i|# z5*-*Z9K9X;S-#9K!H@3KyCQ?PO6I~Kn2f$Xl~g2BB->y7QvJqs(bbLMC4At~*^F5E zH1>^I&58X$K)zh?W-eTGBAz&2;N~TTH|od_Ex>aq!4f)3f@q>yy%Js53t&8Z$D6qE zw#m4Q^^0DDJ()i-@7sU{D=r-xL}$TN?R+*Jd;@>SEe=sl!atTP`*1{rby^yvLAO+M zjqAhd`^}WJy~}#ppG^{6T<;ChC!m#wZnyB{!U5hJgRwb@;Vk=XXc%}aEF7UD`>Iev z?#cS%YK@`tVP4Ck2?-{L95Pik(HTL}Bd{5N~1lV2Mz%wD21j>}ni2kz(QO z01fYlAZNecoIv66G1K?Z5BLYw< zWIFVUKV&P&1*<19Vr*-Rrv5>@-ZvO3^;v0R4BnrdehKq8sA!!e;wof*MdAidh$-Yz zLC(}j5;K1e`rn|ELp9X~mB*1s6KE5j_e(O3*T*^jA^PuiX`+7r+IO7)sdE0i=>PvI zC+VNP>{*Kc7%-c_Zl91&s-G^K>jE-e*H8a`0T?b9OhNRX?4 zvCxf%m?u-hr>eXq3xxF{?e_+xY~RPn5i^5HjHwE9C7v{4h;%sG#0Ctx}EGpre~+@NGK<_taN7k)DqXX`{SL#ndc?&M_QpEcU>X5U-#$J zQ@;}Z(h)~wywu5!WSVSzTtqwGrT#!4js@On>eF_Q>&#vU>G!bk!Re4`bVSi2tlV@A^CfKN*o3)b)JRk1ox57!)MBcS-FijAUSKlIO zBINM;mTyd<5o#QPC-yycK`+1>`iie$#s0EGdORAbBx5@egKp?)m~7FKtRIY3*QeW* zRXbb&XP)xq;nuCcO4m4@Ma}=7ll1Rf=)V`oA!Kf1V*F(daWdC8urmH%=_V@1hF{K* ze?5f%QNprfr@kB_FoRv@XH|>5Zb+UW!gdI@Q2uff@Syy)PfqDg6zxpLCN4dyciSM( zat4p{3FKf%z`EYL0z6%tyx-Qh3;OlL@{xwX`ang^DI~|h;L%g&5LA;YAAen6%KuA~2-|<_g7dFc z{D&v(pE5+F@`lVjAIgWxnu1!Hm7LNCigVnBf1>t0b|N+!jFBobqQS263EX+CjpXX3 z$W`kMRZdUpb4Cf|FSj0$XROW;k0O*vQc{CtW+rZ*Ka*^xCNf`5|8?NMd`I9K2r`1B zcVrs&!ZSr?hkNGZmKe$mBl#^?ZCsM{PxM#d7pVb#E*9$!?;aaZ0_8TMjpAdER!{ci z0_Bt{s_xyt#g^l)xh+SKr8$2DrFgrmXz?sv<6zPcOuHz$5vH5C#d0RY95M!Q?5X|~ zR8@C-m&xz!4R~V=&TT*EY-*^+n)3G;)*x??89Qh>+EKKL*^Ai=9MHCY|wUzUZjMi?XQ^B+AlNX1MMf1POvGhJ7s5(`|k~ zT&gQ7|N4pvCAx_d94Tei+SF{ap{;%dcQNvNF^4}`(+Bhbe4th$Z}N9+K{&+7(LCJQ zpdPNhHB7j6C1VG75vMa(CEv)%7{^+CKnUciHOIz|OO2EW9*%`ORFn*c5jX!VOTjVF z?8}UG%{y5EPkeH(c={SSn42GMdX$H92|L@!f zv)Q^QoZm$#9u56R)K(Vf2QjvXZ+%jx5Fl>CZq+j(Y{PQ^;H%wn_mV{CP=m=q`GLTI z#K~MX69y^WhuKl$YVY2}j_lZ~QM9fpODA*-C{$+;di@19(x9IHT9C@RQZWrf{EuIa z!ggzk7T~16X*_uf7LukFc6mpDDuD;!`WxzmEPZRhM#|z3xP)~=XF}{4nzX-C8;637 z?GgPRbN;F{!;PeixnB>fbg=&jDgXVN&-dRt1^;zzagOBv3T8tI_#@%t8wOp|ClI)t zT3!VMfmS4n(pWnCz0jPbYOwpSWH#<^cvfS{ol{Q_U^PQ|eDZoS!y>E!;jI+S&G9u{ z?LCsp=Ey@21E+Dn4}VojfE|_hjQ+~nXyjttIrgM^?x~X(XsdE;LdOj`{IOi;{@8~8 z2@$x^j}UB4BlECpX<2Ml6mDc6DJvKP&xP3JSyH`o;5lZRZ9Zu* z5MT=d6nc4;V|R>gc>tLEAliFq)tYqPd7V@{xsbY1nlSnwBITtGmY-Mpa>6JSrv{h5 zuR2|)xStF^o}U&hzcuR*L3ee&9IagWd?pHUiXylx< zMul;bcCt)&)wCF;NM@`(z7KkocC@xwqemQsxZKnN8TRl2W}f`z+;)<`2Bv}BsGp3~ z=>1?!-(WCH!;@jEN}wAUS$xBodHd1RaAN|LTqc=V?OQu z$%=rj&E8(tu8cT(=um(1paNklL>Yr6?g)Zip8^dRastu!7Pl+S9KE_0$b^`00ua zGw$PAp$#eU_=6fySNiqsM?Zq#{acP;YgoN}q}_%hq-AuEleL&b+G~!2EpON5D$jq^ ztaIz!2sBS3fNXTsZeh=_56yK+wd0IZsvcWNU*f#ZLTf4>i2=f#hMCWjKo%;B)>hRT z={oRU^d`XwDoGG)0_}1ndj@*Z-{m=;6EHElS)3Gfk4~VR6LrzsC;-Q4LV;*@EK4AJ zC~;f&|w(efFsQjaLLV|t1(>5F=T9EI*cCcBETMbx0!`nfs!vGP!lbpB0>DUM{J zbc(6vQg*#{va!QMj4LT(hiP};tzVk7R+Tv7WD3^2&!1l?kjx!le(st(vSh3P!jw23 z#}b--n*3)EBcS6GI7YZh>&4x&nZt?O1qjQ(1PJe6qM z!Vi)!;O6+BGVT8TME>_Ioc}tJf5*ECIOrQ%8atWWn94Yr$vPMrI|%%BIr@)>bU_W; zO-s4)V=0r#(S)?vo%yG=Y(fJ9VO9a8If#&$BndYK`!d>bL7}<3G-L5dLqeJpp7ku% zFQi^UA)&YsP))wP5`-BZfyOUL!_}cGhw@$CbG>2v={QdI2FG%(<7s2&KE~Z`BF~;l?b)s0P zel7;uJ}34PeYRM*UUGc7avNysrREcIAix{%J{CWxr_W&8*Ni74WNHU-%Gn1K^U
dl!~PI5`>*YCZ>1f}>^tB{ZM`Rx zOlPzRM9B!Axn`nVnUloQz3tIVp5~Hc@y1-D7f??^?Y*@T35ZPM)2zn37bj+fHm%e1 zo7v*QYXC^-7#o`?%xHB|)&6l>rfidZBy2L2;5CIXHB#NykP74ojN$HFeZr{)urQHt-z8 z_7xMeT4VGN>@bKcnVwOzb*-!u3#J5`ohA%RlPal(5W}qYqt28DYSXXLUmklm1?(y0X>V_D}>W1iN7n3v?9HmqT?1#ED zb2cuToa4msHH#m$2o%TkbLE3}a!^V)`s8&FR3gj#!=@V;!VFaDq%{?+ax64$Z6L~M z`az8>$PgSMjp$O|lOAbspTpGGxn$A=Eic?O{ru$yCL?YMTVKOZStr-8TM+_1>q!{m}W@;xRrB(1T($dXlNO!^e{=dbb% zRmTTr`?;~GjJea-^ZKNmY&&q>uDoW`R*X6>PU1H!?QHB`|BjiqV;j!2es0M1pkgA! zA_bhoy}6OOIUq+4!+@TX+Avn8c|@jUxOyB^?AlP|wqZx?`Yx-P@Vm`Iny4tnX6wEV ztAoSqCOhp&3Jq8LHIsTT4RDf-+=*f0wV$-oAxLRP?e6?aO2E+3Ih#`mHl-~PQ;5lU z3j|ClZ)fKoWT_V7!~&TYhBC^(w%t*;2D+d$KZ|w&UmeK`nZ>)FndNzyV_(Xdbb^^q z|C6$o@2_xty{zyQp*z9%P&pQ3HRX;-RVA&k2`KN1UFD9VT{1WA0oj{2|C~}c5MFc< zUHNNh)UN(&rFYJ3#cO;@@2IU3H{>qm>*VmQohQl<#R{)UrC!;{UnhaI0v~j!J_yhs zh`b6ntRDs2UCQs6TG&}Ep!Ma?+9*BZo6o2tMuZenAHoBl+ec6zsso=pxTtJ9CZM0y zyAZ*`*XK9lH1{nv__8zRm3E%d4v3zNxK&ye*YX3cK6lLnD9v2R5iBH}j0Vy52P%GJ z8Jf(%>MjH_+<7f5bca|LD!z2NkVMakV8HqFk8v7|^7Z@`+o(z9e;(BAE8^Lo{v7XI zW7zk)4`Fc!O;yRW{Ei#$pKGF0mxmHv&Yc56wrwm6qjaG}+CW3ylG6C)J_`gLeNoDe zZ>hemRDB!!NK=k%UQ5@zO-xH~6||OrGFf{`2aWSZXaOPS)L_;@2fGh#LYM#rH1?F? zNB}1UOn8|T%AK8TpHi?}q3BUG%iulRSG(PEJfK`O&#QZ%m&%)Fiy zyqbGQtKmEBItIpQ+}Tq&h|gNZ6j2{>b$IFbpvwMg{i)XIm$sG^R+zuR5G<>&?O6XS zv_I%e-($2k?=-ofDG*A`VAFZ+z~jdL7)?5Gdy33Mm*zw~G)ds?a4!n?xsAx*+x zeYaB7uda4nX;Ia(DJ;H=+Fk?hTAol1H?{NP^;V|ZBCdJF)JAN(f-^orL>_ozN!#&# zUA|SRNN>WAOmyAy42P7V!}UlngUB|LUim3#*Mo1K1_8Fqt2RJ<9=!K2{9Z{|iS$vM z7djwn&=?nMoiInI!{=&&Se8QvT5w=n{6X5|H`<}f-S^d-pj$9f)O^gD>#Cr|zaP{Q zBUTxS1AoIz(V!YxNwdsM3ucaQF3s-h;Qp{_QD9|6vTG@5W!^#L74&y?dz zo^4oHx&TsVqr=Td977ICXIjc+IWl%U)fvaIW#AdjbM+UlHnjgULwy+2++rAxrs+})Pw zNqaYi0Hx)I6huOfB~VK&wDB9AWN+!cqVbRs(A2j9rDct)OAs_;!cYTzp?<0Iqc`44 zoRqcJl!&^@PL0~cg`El3w5VrKVDXjKX}7_OOP(rw!iB3-fycg>enz)?1-??luF#3j zL>$175kubP5lkNO1hznvr+tJ~?pJDM%zo^R_vSp8P88he@G%+_q9 z4Yy*HS^Rc@rLqLC-w93NZFqtrz@tl4ya`f$jO7$8!KLI7EU_0N@em+jiCtRL)Qe~T zBvW!3%+<<|+szWq!lvoSxwyVp*&4*sx_OCdJ24k~gtmAJx80z!MsZnp0ZDL_Y3Pbi z2@k2{wADjR%;c0)G#d9h=(%AF4eIfMuxV_lRf5j$5I0Y+2vcQCjV5@8EqQNHtT-o$ z z>ly-2g19IqY4X zRyE>W+F{h)!%M#U<;)mZBiEClSq<9kEl(7dq{VQ(|AV*&9yq0ek%(s9L5to;8dl8D z7HH_V+hCR?;TH>6E4I;oOxMGaR&%e@8oe6fm-0rgXw7?QX>~EXRSsYxTmdHD`7im> zv$ow(X3L9Rm~JnDJ}0J!{Pbyp*yPi9A#ExPbPrB$%j#6od^?NHA%$UMY>E6DwiBx> z2+1=8(mgdI(lj-8%E7}Y`fljXlf)-Q)C*qQ4d~M!-JZ(ZH)h9pJxcYO-g|uLmBka) zcAMlqzOk$K%q?MUYuCC%*ycU^{TW1g*IL7uSDxlWs*+tGOQ<19t092+lq~J?2it}? z-l{khx0sGcq^FbbyHhOG2@7SOt67m`zQGdZtQI%(+JpG4_LE$xC0SBCn0e@0MHyhjpk%4R`%!Ipf6Qy}Yz&1q~zi6U)rNr!LKuro@^ znR$6fq=G~2tOK<1{@C#!hs3J5_7ja4L8mNFCNI9uq^cDBU)cL0rMljMHi=KO(zgg3 z)cARt2ez}K`+ZIs?}T1T-eEQ=xr+V@M=s8Z z)%|uDJf|p7OCKWtW`3DPr(j5{UY{tvNNt?JBDrETp}_j}R)54=oX{E|N8kgyrdF(1 z`%d0ezaK;?Ti(MFdKFnEoG2W{){;N^}=jy2Sr9qI<9##_c zE2e8#BN^%h&K$MMur%~Ck+v7y?NVx$0`vLDS@;RRIR(1;n7lxYc!V9dBo=Ng<;>75 zH3xZCIJVoMmAqaoxMTe?7F<(sK;@2}CHp`B?O9%B$AXKttYbHUMuX<=;+70v?=mc{kmCO=MU`Z;8lSX?AP#-GaGL=ZU)FK-A^q`2ONVad{Npc}k4J z11yJP8XdD-)O`uR&zw0_^2HtVtm+r{vH)PFkK&%zds9?ajl_~|ieeAGMl%&(N2CxE z-$Z=px5Yumjh2WRl~37*!3hR*al?jj7IPhOk7Ei6WVU2-Vgt`uAn{~ohPw|d&)4)M zl{ibE{R@Zib#1g}hs9T1%Rg2V+2+?$fD{|UEE+GAX3eRXoehMoZdyEbcoYwNg3f@a z-Y3<+Ft2U*%%&6Ew{Jc~{}l`M-(&s%g?ax^?EinnyM=$T{tO6%UC*XVf3f~t0JhMf zB!7kQ5dZDGC-Y1j#X52EI_S=@sofs%>)ifxj~WPxovyt5}wSfkI-*!=J}L0+?vt ze%O*<2Q1LIOUI4r{9g6NKYPjKUMn#-S)`Q0D$jFi!axP?n`P0t5z1gbTCp8gox7V9 z78vZft%!dow)5C3I8VoSo`!5~S`iz}=kxc*xwzBt*yefy&JzJ1Z4|7Y@#@Bbb7r|)R2Xl$te zpNWM^RWB<|Rn*Uo<;il~Vi#?)j*5*@mF6(%C98%py9{IJ_u3*!jgkbu#pK)F4)*FB zQIoC$3KUlI$Vw0bgt;agLFCWxxz>JV(u3hDorq%B;J+Y0^mYXyKE6Q`e22&l-}>!s z-_Dw}T9CZidbH^}^^)ay`SXb9^L`fF7Ptjn_RWry=XfB5es@5Gi*SUX)kQ6yC<^`q z?(}HyHRNDce#A=%Nibes+#xlc)E7Y8c;S`(q{Z-1;=fxdxx;%MeOomczdzaRTE0&^& zP4D@5QiQOC6B;bQK(tt%5sIu#rLkUvc04u7!ZeRGkp{iUx?F2jS~5JEWF$jw&QfWj zA}wECy%DLjm1x0PlVt1?(XE8Y85%_-1ay7mHkAV5xLM-x<7Br)9g|rES_|?a#Zg3m zxkSz3lDh2zGD7}J2b6sS0xMq`lZYv9Oj}(tODBmbg@H>#ZQD(B3-$+WQUxZa#@aahsmoSkkZQ3;;z|W-)XIINyq?X|4JP`r zMj8olRi1MEe5$bp##KL3s&;Ec`NPbRL*@La^0uGyaxO5d%H$&4!~(&Q|0ZjsBqJb( z_-V9se{iIA=z>x3jMYL=7}l}^NxIQEA0cMC?cQoKGai8&$#!ux1qRS2@Mr5cX0vEH ztKw*HTSB)Iz4>fadD6Pr0WES3-eDk}W_H#7cq9on|JVXa-Jetj!)JT8B9`%I zdmIMdy!a0Awf)-)VzT$peAW0we0<@-m>6*fB>bm6WQQ?Bhu0S3oWy-a_Jg6~8%)2q zYRjfplv^2AN33`@$)EM!a7Yi3epzfkc)HznM_8#M1=|!T?)+aW@MR^|vg2LOd(8c` zscZ>>f0xSwZxT2EfL`uVoqzOU0j47^h@PCh7}(t zJ}byA!3sRPgfQBD04M~Er72Col_ zs%Wv#xq`k8r=mu{nL;Md1LgD&T$!}blARSv*`>OWA+D+>m}?|J`a69z+CJ)~%xS(8 zZgXSwn#Pdzz}xV`qc}8kXN+NrA%D=T1)9~e2y&jjS;5PQRz}meE6)vok;29jIe=0@ zmC#0%4fq34r?uRAfb%=I^ZR!q<-RNDYuVm0UeMdXwT@YP0TCDdmw(GxC4>i-y!E zwG3{DIA84tfw+SogExdWTb111LbufAb6iJ`81)0Mdt70w7EZQRf#!y+OOtCzTcnI7CROjpuMQX6cfK7YS?l z0PZDIoHmWRKb6Lb;*;I>_QU6Mp*3S-AsRV(dUTM#~ zBzNB}Q-&}tqa@}23RfB6dIL_+zmsIY*CAvU6(@TrTB`M{(ooemPU%^lB%35t?3>Ml z5eGzBf34w3#aFV#2-5#U+B-&Ro-JR(Rh6i;%}U#LrES}`ZQHhO+qP}n)|=gT{_EcE zS##I)yx)EwpY@!GbM}tdvEyMaU-sVa8Hfz#jpu5Mp6=B6A%Bv45c#?AUexc6mh}o^ z-8I8iQ*XYb@9r6_bf*;J5rb`X(F(A#W=B&uKeIoVIg%9V>Ao(A=!&Av2b?+3()NMS z!z=WOrXw;l))kzqd-Vy`V{$q3O7so06At}4p$VW9DfJq?8mJSIrj4Ru8(Qb*2k}L3 zCO^{$uFI8TbT?O@_M0qwuxIe>Q=}8{CnD9Z=Z?G@oaGhWgKJNIgbtWE3LL+~G6l#^ z5Vdlos*<#rRv`xa4%?Be`w$VORwk*B{SF3}0)LjQZYQY^mbY02-T*k3&68gvScR zi6EjqvmIu*PC8DWzC3n%JR^1?9Pln<@GWL2z!%w+x|EN(m-YOa5Y0wRI%(6}PO`)qMJl+b)(`~#ETmbL*BLJp{b2&h1hL?vD&>%TVp?1F&Vy-VNc+p7Zp~ZZaq&Y_E%_zx`NlucVI%E)N0Cz}--DeSK<2R*`a`nEx zG7PcK8Xt)dlfETXBBa=7=M74dyVIar{%$Snhso%EUbJ1C#8?CwS^8+cb6$cnb!**Qk}q?@I!Q7c&B3-#VJdo` z802X)Z5S1tf(aPDaoKV^Tqu;dL82+!c^ZK)5IG##c<>d~oQwJyP%zH^MIH2;Kq7{7PpP#FD8x1 zJKUoYUO~w?LB~p+X#mkxJ!hOM`HZF`m18YT<3vV6+D-F8U+x094PEN4btOIlYHrJ_ z_mNsE?Ra(>Z@}d~LRbdf>Sn+AL*Bg6wNz=lc^lem?><3H!uqn?0!+%%p$3Q3%>@iy zQ^L&!pw7z+pbH`hub+P(c>j^CG1uI22mJ?!x=W+KF8S&kiu^^-@b|tU$3Ft|Qu>D4 zw)VFFNtw#yq$THm!wi0&s;gGWaRc)40|8a6`G&t}edA@n{3a~HQ>5XxPDZ9UYbxH@ z?gzc?c!gIKOmp2Wi2X*%`D&1+?gAK0C{h7kOP8L!d1mMEdVY9F_3fgEVR6&_{rX|| zkqJ?)TOJ*+so-nKc9CMO$||1xPT5*sQ(t~7^xQ+4V+$cL#4R!D;`-mjq zl1EIT_m}(5gJ-GhA>ySixGj{0ZZ|hjs0cZUw7!$ofCY-eC&w*KVh{57$Xafj_p@Pe zN&W@#hvQrb1Vgq6{*|DnI3Gg2a|^Ti_d`zJT`q(BL|XcKibfW|h?EU@wB0DF)e}Al ze}88sJK;H5;9OblSPTMF{?#rcbGS1AkxVHM$paQdmd*$1(**3_Kjkz`!^(D@O z<)k_G{I3Q;Y$4bU_)1{D3eHVf_VR)80~Y^Fih6E?+$unW?U(~t!%TrN9r10=!Pr&; zAOSZLnF>|m#gqoTYt3PyJ|lX!2SL>|9}B)-ODMJUqNY`)*eM6``i#-eT`!jfjA5??9; zeCBRRFKCXaN=)r*Zw%^nR2Ty0=wKP%F;^;`Ge8v7umW)PlxV&--CsGbS%CFEs8Vc# zha*L%+yXx~y>i;|;N7ir!1@iqV}Xe-t%a638QwG*By*Q08<@N28qgF?mYO1#QYyx# zBGzi;&(AJ$a0{PXH&O^!B8j#a7nMD+`Djnsu~%X^v2W>Va+~g4W!tr1H*#pOaeAU1Ce%-fMeX+A&3CpKNBo$W_Ah2mcxkk$%Yr; zAB#=cp}SuzF=;Hazt7TA4`8<+zb`F}{VVd3lKp8?8Uv_3tE(Cj!kICb^yS0Gl*OE~p{K%{!zYbYYWaDz|z->6nK@T+Y;pwN! zxGZF;LPJ8R=#@{=7Lm6gwu(WT*eNUDJsNoK^r6BVpb-TLaSR@|->i(ZB4&4k0U2T8 zW+!CI!BFXE6#2d$rew?93#{K(Kj*C^67-bymSF~zuw?lNr-3?yie=7N1Ep=4auYjdFRqGK8x-2zaLno3Mn2s^>d*uum;9JRV4Y!NGZl|t1z}w? z6th;NF7|wCbtC+hT{v|WHbZG6vJM!QlcZ7F`DU(^flFn_OBL!FyD(T7D!VYku0Wx@ zwFX~IRA!~_4N-SCI~r;HtF<(KWj;{f?RO#XHaoHcvEs3LebrEH8kM+{5`nyQv2e|` zMKhu+*5w`sZq!fk9X<)+>YFSE>oVLh%^C&C;W1)uQawds)>FqJc#^@afl`wGHV&cl z7)_@0cZxAV0g>M+{tz-42F27f*4lY0+Ic40c`ko`!1ovE0{rB*S09yR6M#|r9;m15 z_&jbtN^YCP`EF^I^zzzIBth9?%8b}h+}xdQe?BKbHwR#Iu^dogfB;2jNV~()sWn?? zLM0tJz(CL{V=F;k3LfdnEi!#0dHSpH##97yj}Alm{WWMI_N-I>06L(Ir=*~`xvj)j z=o6XOLs&WLUj7C?A>LnJd}C-NrGn7)h_qR#QHprEn-%SsxxPp{3NJckYy-TzU=r=t zI!;qARd6K8c`cEfmk|CZRy2`(7#t%*6j2x>wZIS)wFFA(4i23Br0we&ERzoot(+C3rXiDuJ%uuEXxM+v1-|f?VLpTmO|L!~Zo& z{uw>_*W#4FAQ3rnTXcRHcU|ZDh^Q)f_}o62pF%pqer9QaL;?cZJ#?9BFHwtacrBhmG)?y7v{3oU6s>z8mPl=D4 zCatNvRiVdk@PG|y^hP?61=d1W*1~~!ZI-Xoiu$64_E#Zx z^*uush)yGj7IrlR0mV10jrY~o8=F@Tyzvfu`>%}#K~XQ}-?L1wI2#@Pv|rn?;;CKO zSDMYOB3oUv;nA`$q4;3XPIp#^9>0VM_x!m5Q@dZdx`f*^c7;bBQDx%Q zRqyr%igv+CTlSftTyVmJ`9kiXq3*F)+eyZM^xhPsabz=K5`JfTW3J+#k2bV*kUK_? zeD;#{B6#txB5@A280k%7Jqd1rXPrwpcJ}B)Gz~~@5u;YSun$*c>8CHSmL3#A(^oQX z3lu?j%g7N>1t-uk0_$okli$Ynxd z)3Gf`L*-)28e#M4$H6pw-b_h%weICZ??m+j`HMp91WDtD0frCvym1ah;*m@BtAc3@jK}f< z9*>h6h;7)d#44rANfy$`CbefwnoMS&<2~Pj&=w2HA*^BkDCoj#f}qrvI5)IP21JqF z2$aLkZi^h6weo+n4rvj2KsyN3&y<>`lZoh|JAxh(E1RG)RxXd4&)5#DA?a+*GrTWb z_!3RtY<_y_DR`#LC)QzWe%SY2#^82J*fSQrTNatbGS^#Snxi<;_qbXQsp5Ithy)<; zkCT2GZ*x>GO-KuPv%e!=lEm)4I1RmC1gUl6r6=;y4eqzF+js=ps7tr%%H5D6zVYd= z{R+8pv`uRM_6GjPv)Sz}?o#wcPV&Es7XR)v{JmiDf9C@8KLv|FVB)`p*Z+Alq{pmE z{GfpeC=4Or0__LD!un=u7Ur0Pf*>Ts7hd$JJ6mSj(yAvJt$5q>)zt}`t-+u#0!=mh zn0QOKOflx-+}!xS1@b^atXkEpHJ%{-Q!^E`1O;#Kkq7uT-j~rA(WWC`G_Hutzas=s z85tK!>TdjCpsO`Dq=67#Be|x02_EfAC=b-sn>kp|O2t_7*?YV?a7Wo@yOok*mr`JI z5Q9VReG2s1_Yfb28D$u!V#VmF!~dW(io^CdxC6zKZqy}fL!dMUjC=7+hb4!aW1D5Z{h@N|dX@4rIm)RlN91RB}qlk7>)gNXrkijN0mp zH(IVm<}6_>r?`~NdlIJ4|0D)6$y^v-UjrsCU#I@>6aPCM<@`rL>C1D}UjNJN^*_(L zUUAhHT@m%O+t`p#L+5Q^XXnkuW(FAVpbUz-l8kmB>~G3GM8UEqpFN;nULOQN z60jXm88|(bFiS1|un|&9ziA)Kkl}vn4*x*;GT_U1@I6hGa~{oaksvokNg7}kAG)S= zUY4&4OiWDvSGuGf@B`&e>`l+y`dm#f-AK6+mtZ%3A(zEZ9U<7nUO&wHtjBu1%n?Ej zq`7y!Qb$)0Mw(2iQh|UleR+G2hsXMw?}D#qlZS(|ZI8XZhpX?p>VD`;-LUabTD6h% zQYNPvI*w+JHTnC;MKjfe8icsA)D+qTG&&iMSV6R^)rA!2>`@fZ4)6?BlUvmvk4^rl*7$?xLYnwZw2*JU{{B4IK`A`DYbC8I!PGF_4t=!UyJ$=Ot`L($mm zSkDId*vq0`GaHM^-%CC=YmlR^(FgM0)6y^1S_v?uxLg9W5xuA%PfRN_Y>wbFN##zr z%?Cn7hP~e>7nIWVcg58itwO{gjx>XO-q0ApzEW#FXib{(Gbe?=WP!nAPX^2x#!Al{XoL6VAh)8xMF+n}m zf;&@F!NO&!PceIKRHkhp)ekNICd3^n#VC`>7>|msf&@B~XUi}tGgIp#XRkQ6hzEz| zDC%FvViv4pxvt*g2m-^f=C2DD@X0hNZS-0lz;+EpbAr6r6p*R)yLZ-y9dAey$XUUR zJ@8OoZQ<%i#-bHiF4#p!1@?ggN1?zvJUgyvfguZcJt=a5N5S@CQ_c=QB-OS)&~W>Y z{B6Xxl5K{zif!bcR;H_hfS=v8>>t-%d+M!cO)OYFIwxZ0>}nhfJ=LXX8$GLN2h~ow zFkHYUKtvCeDH#+le8Z~_Mxw%-9kT1WS)S0($yV#K0kTN^nk8vVDhUV}tD-*p^&B#J zIbqUD)Q&-y#hfAy>6GMgHtd~jUj?q>I$+4jB^)`4i%z<;&i;E0#B`h{EteaSL;&kz zCL8JtRR8h{v_rS2+*LvNd!^fb>)Y&@W4+;3LX(X3Pa7ZhY$=N9+icbF~GzNY4(_`=i*JR6+P;O1y#8K24{3btlGNeW)RA(14*{Z7>&sno(} zsR?B5yhe1EOMtW3CaVjToB_t*W73>sudx{@Og$pLsV=!<9Nyng za>VuHehD@|rgcPI3C9e%n6DUh<(S(K z$tCF;i++bwIg4{G62eprwi0IoaOTmfJ-M}%kMRL(<%MT)iW9S!2tIu|zW~zi&i{V% z_c@5Y-=cLD6)s`$M8ps)=lu_!9oJbEh|G)mhGx#y#XUAS^H2x+_D?i8dGCUTBW;pd zHO!5LMHaTS;s4a^Pdw7H~D~UsTt59btf)l8)Q*0r#w;H;^qKgjikjKVFf# z-OxwVH2W&??VN$#fg5kv(zTy446EIfw?hXvwR>16;PkWVb=35$6+*1z_f<#+sl2(%zfFpYYsMaaawGYX>k{Jsg8nUZDbldk z7NNRP?2j53;Muv$9$*sTuOuF@20hHqGXdTRb*+GO8i3XmE4 zrPGHZSd2#4a-=E6EfkIxH!xfc9N~X3%vk8WU@mtVhi*Rz)VSvj6Z1L!gpNE=zQ)G1 zI}G&wIOOy_cy;LH#(tBU5y^ZnGHf-K|CzGuJKYV^-t9S%MKxDyuygZu>k1KHIG zx|q3rp}G#(|9t2Fj_m%Kbm!lw?yn-A|9toJrMUmFbT130G2Q9s+OvRXuh@g(xq`W> z+WVd^Y)Gf=KsYu=`GmK*)&28{*xHc;5RgEN*OAvzQCb~4)AI70LDRTZtah4q4mG9N zG4nh(g2tktMG|>yOh%*NG>PV`6kMhfwqIQ(=_Rgw8WeP2#JMPabWUTqpAdLNjdj7c z7PIiQBsNvo<(LN*x0;Fe02`|<`DAK&y!^SHW7MRrzwq{HmcG7Osp|{+o@$@_V|>r- ze&ySEq1EFok^l2&7#ayN#7Y|vG62M@OStrA?VqrT=Kj-o_6roX{ny!Cp??IMxOHsp zzGi>yq%6&xEiBEAwaxzXk1Ur{m4ugu`H-*_T{KZe_znwX*&bBpg^XYXC{hoKLkL2} znO?D4W6-*KmhbIJ5IocOb2s-|5cLovAwf>KD`k8lna=Rw)!<<4Vp3DH^LtWn4j3XG z4?CQW0tiJgK31s|b)l9<{CV^fEr zQOm3uYeOMJb7y0gb*k#mjAP?=W=YrAp965bI?Hw9oqaH)iQuhuWo+0G0e1z)=&Ibc z22Gbvuf6A9L#Dd&@Ry5 zS&GnKTc+WVB)e?`_8OL}nz5VsUUq*pRu6FO?g_Y<4KmfRI}M76A`k6T!Dm~rd6%Li z%0jH}Dd*C?MmIWxDMlgb$OT;^5L$74S(Fx9AwQyMK&piOZWGpA-^!hkdgfy4ySmw2 z9j$UQsIsP2Us2FfF15fjnt5_Cq+}HTBtnEpJPHpYob{yePHOs5qi3YZ6NgoUWQ$qF zJA*qEBWDa`6NDG3JyS92{zK6kGHL~6IjIi~vbtmsvrwMo01T7wrTc)`NW({5SR^03 zKugRARJ==o;LHi6l~=)k0lzz zc@?uM0nd#v(3!nnp(;2FAvY- z^bI@YX}qb}?>FwqILl_T?S$pT+q1L12j~`n#^Sd2dJ3ee#*@?WZhWM;_lmbf-7$z< zV=EhPOXM*!LDkw~@Qa+70O>2aAdO}GS;j%Gt=crLx4{^HK z3_di`OxPn&^3W6cqH|K=wVb}Q6Z42TA)al_(bq%6V3pkPn>Rv99>pGoAINk9kWaB| z^`d1OEjc8Ade-z9O_s9prCta(cUF&hcSnVrda5v(o_|1_>VjrJdTd@j7V8b@P*SoI zqio%HQ}wRh5m7e9iB?hQzLl$wJf<>h^lByR2qu6OU2!476Sn8>aPQT&fv#4<)LYNTv@PNsSkEc-jmV}(iNk2%Sl_<|Gp z+^>Ona*kxNOQ912e(w5C_X)!9h6aCp6Aq$EO7b$zgmM%PO1C?=)aXo@d2-Y1^^oIgFlBp? zS^y!8l(}dtDxeoF0;CQqGK{bwR<;n{H+C>)Ru-=io|ktPJ~%t}hmO)OdOc*32x%*W zFtufbs|Qt}QB;_s^W${bBJ>(V7M098umdNSOxjRc0n)+ffxL7^8#;k$nfDW|bUMR$ zz`H#4vA%F;JPyNwSqIKZiXG?P02oV@K%sez{#>?TZr$TE0jp% zb-K$y8Lr-+cDF1J6Xaht!Fh@F(VG0L_xK9fznyNMpf@gh8c6?Gh3_QP@cMyAeF=0`cm#-<&*TdFAbo@PKBynyFIjTgbf zlVA(SDwP+Z!kM%HGOC`}wCwAnv|DKHqY!#PoGnlHFf>_<@V+j*@H{R}p!YL)?#E?V z!NWm1M$r_dMp5^PoW65%p47O6StEq9C^UgZ38NCU8?wRO=QUs-cKxL=iPoKa~@6L2!hd z!)Z=;%Lc6NZo7~7WpBv~lt18?LSqqzNjyX~x?$T!0*@IUAo89@@xq;xm?P<${8-ey z{R#G(1hF=Ay|7tc=_a<3<*v{*1~ZkqAjx+KH@di-;2W+cSc*iC-ogx%CZ0{0F4}c9$SRH1;ZgWb&Wqmou2)RNnC^Vjs|F}q( z?7%!XzH|XVApc1X{$2v){YO~#Uu_^6Z7U<&zxqqm%ZvWe4f+_EF)8QACA9Vl1MvH8 zCQPH8>IXO&5fhFT9QM`~qqc8l6|P|FEL*BR&*}G$*JPU=fj$_`o?5nkV5_0W-xpdlAyUXIh zkf!!4%Z^(KdlzyA`6-~_)O+-v1DJ$;=!#e!t4CyZZG%y*_d)y%ikB~#*OI9{g!gFq zt5E?pP%@GufT4ngtR1xWQ#KOw>Ay6fntTS*fZ43p`R}zth*&E!vFdckT4$yivCd;D ziU6@N)G&=+Z6Ur9qfoN!q^jqhw0d9stl%y{9BFY)x{qF0#yLPi3Jf{*TH(Sa!jtTh zC$h57)e8v`dKdMmB_LJ0?gHuBCMJyXp65XOJ zqbtkw!1B9yM7ek?%+Xgu|7csdaw9eT#Gi!1u_fX`3#`vsz%Wc+bgPVh2dov{a$ z(i{w8+-2l|arQ0xvRBQw#=|Cv2EgAc7kAE>gb`8pa(~JAr({ z9|XC_x-9ZnU1+wUn3}i>yppP(WPv9w8%wOPup|!VuZKMlS|nC!kZlVXYIAlU(H(U) zu*F!uPa7lh;KyM;{5j5F;ys8nxpk%?d-T(%$?rhcHpoMUk2qZTG%fTTRQj?roI8!X zB*wTM(E7Mo@50Mpi#8vxQ)W{VWo<-EIQVgI=NE(W_lQWGHC`SnxgyfiaiydjV~d(e zl<<&C5FXJCqzV(=e6eoC*LriK#3G8)2jxTT8QJ46XJd@^O;8A~Uo;_x@kvbSaFS7L zZgGrnycUuKrrQ<@?N62HJ^5+zp4vWi=&3M8FSY3_{Yvqqf&p_8Lf~yZ0sgpJ_zIY` zPQLJ2>tC*xzgHdpnQaZXnVF@dzTOvxxBtVu=3g3&d^uCeSuF&Q7JF000rM^|&>bNA zFS!wNKV(l=wkWA6`2@KKHC1jzOa;Sfz_sI(pdP*sJsRh0ZrGta31Hk)cm1&Q%iUUr zt;@e`U~82kxCb~O>823#5Y`r>y2zQJmOvqNAbA`!@i zrEXK>nGCLlxp@|@&=}I&b?4PZD_!ne4qsf-85|Go4rmX3EnizMSzZ--7jGkW+Z!Fk zCXE@)C&xvCQ2oQpvtk}{p6-@WmB~=@6$|k@6-bePHf}YXG(!a_;mD^P*Q3ds_8#2){0vIkZr?%Kr!pgr7|im^|GYpR1hlah+fmR0 zrbZcrVG_0oXh!YM^2-RN6A6;ToZSC0n{0cV*zj0p5=&2!wt3Xj>&E4}yxXC~(8?-` zE$7oQadbkw_yYzCC<(%fxeGSJoumVNBnq|{F^s#1xfd%`NjQLO&P z-j4qYdvY^@(2y?{%l{W)#oxnT;UB%I|5F|MH;es07v1XRPygVw9|h|U#^pTHaUqIr zQeZVZhzO;>aTb0dH{%az&gy#+tgahSLALov<^=Q1^*yZ;U6X_v2ITXH!-|a?7*32O z-=<%taTq?FK1ODKhtQ=Bhk#&N6Wc`zkfmRnv1SVgyujcEbIiZUh1i*ww zU0L86gdktkR!XsMxA$FaYQ}+>Emu$FUE-qfuVdWu!9;O+s_QCZ{pt`S|qCc(x3wS^sg{{@D$894p?w(@VO$jLDj(UNxfXL-+mr&>W5~x0QTHzD4Kw+h0?%DrH0upK#l2V1R#Umb}PW1 zUZ3WL!%?pvlEQv;ijwQD38)>uE#L9R)nOQi);`i$aI#hq7Jsa+8>C1f7~vMm{QUj# zNBoZf!9d&@ySG|0%t#cO(1n&>{Vj;i2q{qbHRMjk-i=4>SL|gHPWB(IoePF8(~ump zVyZQ;z)*?{ys2#ybVt7xpqe2*&Pl^X~A^Vj%`-qPz9)WKA15BjK78wL9iH zCaKp`cC?*VN-oEw-tgjt>#GPL(#zSU-%N4lPB$G2fqpEqF4 z!kg57=Qs|y(Fs13&pjO7uQ7S%bFa+QJXEy{tUsZgqnzcU00`K<8_+AC<)Zm6&iMV@ zZl)xNnd5iOR3rF9LLQ35Oi}?VO4h6|GyjZny+lqZKJhU`3n;J7K5m)*(cQOV9!*b2 z9pq}wZGou(X&}X4ysS%JqT6LYu`z%VWW|B_!jBjevF&!%zd>XY$erg&a2;if>ABt7D9mkNRm?PpTP}Qpt{Mgs(r;# zXCOv|5X&NR%}$`r%|arhGgP#VA4=9#vNN)Smd{m?cPj0td{+#TA4ep7Nj#j27h+GJ zGbMr0@he~H?AJPelw22b+-_LRD&F8L4dT(B7b{l~x(U|HpO$N}b>vIjUvC%Mm!J9n zxikL%mc)Ne-G8U_UkX$5rhk}BbMS(Tiq;3IoWgI$g;ao%f+&EC&Ic8Fxn)uUge_k% zz8ZCL>5IwbV25SC1AU~#NW^;2>drAvK2tT1|j zFC@hkpegd_2osB!hZw3;(T6yC63x}n?_g~s4x4i+m#>vm%UjuIAOWx78J*fUtc^_m z#;)}#hrkBmfvLNMj?J~0LtSpCGgg{6QgS+e#sM9u$0Jc%u|TGF@hvQt;a4@_Gl-$m z<)m+j8umkUbz948%JSdtFxg_a3m{MuSckBjBzT{^l`DX=C(oy1PEUJ~EsCyJ))MZS zbr^?A5#arE%vNFf&FH8@L6FHs=`ip7bLSgBGtCkV;@PILKB=us;AL8MDoZZ?${{#x z6gj*f7rvqz;`o_Dbq-NRYm4R?09L?00NMW#Q;0)IrSz=&NA5u50s0z__T;g;VO5Lw zL{yQmV!c~v9w5$RuhKzo#1nSkQrFk&rkXV?XOw5a$5WVF&QXBrwAc4qj#QL0kk z3%-nqYcc84xsiNJh7F|#%zy>0=DO5?ktX!5U~^H&a(k#>Klx>?5>Yf9U0-SCT54%g zGVD!dP(^<71RppsDY9P@I5y5VggG1*+apkmIee=^VUbwg3^M7{l{C_5X`rgB1>!j5 zKdBN%nA4`drh1K$C>Xeykf=Owh9m^f{cISIP0YH$3V>+mFxj3KpAXGbiQZ!o&?LY= z`u-Av$EJlne9{e5Z+zlSgXRuDI6QKE$(hzA{9BbJ4Hv>cKC*hFC+nvWqM*QSJKNDR zG!wt$7B8e?-fy%eAJOf)0NI2e5=N&G${`oZX}M1EJH}#6s&77g*YGiTn$xLWf$qTv zBtvPW<)m z;!T!z1#t6x`=$mX+q4x%!Ype24C8o#r`1gu0(H##h(ol%6!u7cw1qlY$~)Hp?(#SiVZP~B1ZvP7;{X5(J zXJtcidoweAn|~$m|JqEDuApirCy$^Wcsw>Gv1*(w;i_UJiaKf+FnA@keM5XV+=~Rb zas$)9x;ko=e7r_$TWIXg2h(rl6P)uM@H;m}Ft(B0Z(-`|Ug&2Ak5}EWU_!TT?3Rgh zDHwbl#^%?G+a=RV+l!6X+ud`^N&qE@(Z!c%XwUT5m&sg$q+ol3BnIP!(rsXUM$+3j zT8@!B(pur@?@aN zt1;i!hQzeMeh{tQaF|Q46{5lfYlMwHW#>mMX=;gQ}#9$5Gh59-qm$@12coVH|D58vkSuhVhzk^HA z1cAD40837rt;gA&E^=YR@^hKCgX)F<$0;Gw#iHQ7%$R^&vJy!~_nXX_!hte_n?yFp z2zzB%1UFZh421Wf^2gLF)1{D*SCt*X4XtrT1#2`E;?;QvOb?TjA8?4RGdk}xi@)2+WE&NJ(%n|2$Ln&nk8CD zsZ>k}e$t#Rwo62tZa)0FOT-O^2Q{>5AVarJGI>(Yns*uR``8hVYm<~vx{*$5a{mC1 zRGqNL=*%Q>v)n1C2vyzN7v_v!Q5)Hs}0Eo-a?H; zvj+4TF8%|-H3C_oX&0v{=Ojt08JCGEPb_)ONX-CCj&M&r0JVc^s$8YpnFJ$`6)y#h z`5)G(O<^+SVhQT}$>f~YXq>1`2(v!csB+-(H8&SLS25(V@x?d0hA=GwH|ey$d`%9( zd^Y8?c_72%kU~bIY#57c6yj?;$CdUKo9mLoC@Ji!&1=s3%;O^LRr*vh6q~&CBKoCob;SlOu_o zmb$bl_6PSz6ogu@6NQ(I=Ez0!^DidxYl}O`$&db_?$G#!OOVpDB z9}?Mc69ONhree+U*OLRkRj0Fl9gt&mi{!6cO(tb~(s#`ES+7kQw?%S2#9$mTNK)$3 zXiO`&ARsR|^0346rx418W^@ey<%=<}y#*s+?RSKt(Z$~ugzf~&wXOda;`;cQ3;Q-$jt*_c9wgH*FQ6UFGF(#LQs$s} zK5n~EnhkdVQX0yZssLg?ULA%7IDczCazS)y$W%WQ3M|GDi4T0ZBb!dUN3K7fji6vC z)Uhu*XZ{y7_;*St_KzstAIjMOo!0#Y11g<A*$6y-L-dvH*S81P+2qH=f6a-+eKU88SHzk6S$RY3_xqe#*qdsMy7vn7 z<9o+-@a5O1)x`SgyvsX^Hd8FiW3{Wtq2mO{p<4OpSC`uJ+ZFW&=mW53lf!=aglTt1 zCxe>jeI|T4tld^JNQ@JsSnZ(_`{a%-EJi;#`z!loMb*;}s?MPuQF0Bv^+YF!dQi;) zMcgOSj)6<}^#0MeJ9P36RQ6}+AkVfJg{x%G%JPoz%PJ@Ten(}u$bJTe&o7x|krRW@ z&np!`!K;=KCb>7M{zwE26cmh+u)~3Z38({F-R0o!VlmIpr)9BE7N8L?pZ0fxQk~NT zj%?(T03X-I4Qw>*W9-ok)Z~<*y@7U>SA$Z84Mx#~siD2w`I-z(8JO8ZvV5NT2aEV{ zAB)t`jB-NV=sCNE%AzMwbG>r6Wn#1hbyBjangsp0S8$hn9XSNMLy`UFx{j>F!*II} zIr12VmZH^L!CCoL^1Rvv^D)$Y>D}TI?fvkd>`LokJ&3$ihlhdUrHqSIvBHL&Ca3zU z+(zTrK#^YytsC!pWcthU1}SW%sZv|aA%r;^=uIY+Thu9J0ey8bSXUq(k`jy`NsP`= zge0b>G*hw<$601+1xosjbJ+_dk&Oxo6h}_|LBHG&*39Y-#Y4J|S&5~Wki%^V+(jx; zl8-~gqZ>@=1^Z=pW?MGKW_nVJi8cw)IU)|-^~k1Zez`%-5ED9%qcQ?{Ryn+Yp|Qp& z14+BoSg;LM-Xu@oesA8>T@{75HlUTiEU-7=ow&YOhBQvhTF)N8b-;FR`we4QK!xJG z5Od{bqQ_Y!MN1(PJG8amR{e_vm^46LU21Cet71GdR8+)IgfAD00IHwhMhP|Y&Mq)EqT;DED(F$V^X0AK8jznS}VFHH)2Oj z>Tz%}4e7;>YHLh%*mzu%y70+pkBv$pKkBSIwAW$d)M{`IQ#&;k zI7^;D-v+IYw%&?AL+%lwY2?I(HGd__p1n_7#g{iizWtPIz>~iqudKrW>h6LBh|f&RwA|qXJMiQWbd1?o(7q2j(MV+ zKT~Bv;p~zDo}~@g$c)v92+__ao_sUsxv@H3cG@MsCT-<5s95WxYwu^Ar$VeZVk<8# zUJtUEuTp}TFIb;ZYfpJ#<_|?un0N>g=@NyJ1!L7IesSU`Tx*+~%-{Yil{d&??=CtW zf#JTE|8T)%Gh>Nbe9)N3F-f3uk18V042oXe7Zd&Uhhy0i!EA=+WJ4uhYwI^ZRN0R= zR%K7pmsu&+nf2=3QWG1+6@>Jv)hon45(*O>JGkOiWTocO66g<2STlC9O#oqHq3Omh zZo8b&1L&E=ZY(tD9h}LQ?-Xl1#v482@?p@S*3e9HG@OKsgL_VD5p&|8g@R+Q)!5;4 zp%OC_KaCB4kZJ>{kV55iL*QmfiaS}@F-EHGA4?r z>h;obCVB-brtalS&1FQj0UPZZX3wn}sdzsmjN%YKP=UBccnGbat2OTa@-QOnYxm$Q zmFU9=AkY!m!-V-8U`4~VR%_qG(M*zd64)w3 zv=+$Z5B|Jeu>k7mAp2#6da>WKg;rcL01~i05zTpMVrv5A2&*UhO0l-?g;pgSP#HaQ zn!#h~0N;ta+reX*U_j_c0wgFjb4lBy>+5I)F}t)}AHtldEhndCOPWoImvEvYAR2P} zFa`F&P?lw{F28|C>XiIV5p)kJxh32k&>7}ZivL3c<_tc5^%(99ADalMTEZ>tWgUy= zwW(}c!i{H+cyeM^3^Af^q!B|9V_ak9D}_WJ#w2IbJd8vZE8vJ6C=yub;>7^rPQV^y zmEb?LK7v~gGC90d>j`F@f>z_-RTQo|1LK_mI#Ngz_r;asEq06wjG_(opx9`3nwEmPs-Y2Yc zyr!KfXil$UPIvug`hKTA@+qtO}v>4XbwQ||X=n&Ed9 z#~uyS@9^%9U~@h_7(Es$tWvGX{cy~=>0agsBh`b|=~L04b*gCPtI4e?S|vP_m{iBy zy3yO~kqTNg;!V*;-lRdy8D%r_B(ba{9UASH6eBA zX7(v=O4RJ=BN)=Wnfu`7%M6Le0|^_Z4H2V1vUsKU^Un^AKt^wj#upXFLjG@6u78GW z{yP7G&ueLJWv1`+pSY%8(bP=X?bv4UMf| zt15O%?NTFE^g;VUyGj@opK>YyCd=4q78p*96b&{Gg_tzDL?piC!^Gp>G5@1%rNk5d zCA~Ei2oxHiyq(R_U?Q2t_P~wq@FKJ08wxpL@XHl~4yRntoi<2sh?#Uw zep5MTTSyZee26Hi`iL(qwg~L4mMYE6(34a|*-sX1fogS@jckYk1XM-6!qg;A7}3vq*=FR3umQmvns78ZQHhO+o-f{+qP}nwpGbW)y?lG#~2dAQEoYL&52ra9Ll%;^UX>I#5UKXZ%AfY zV})rp5jbg)V|&aoxbyFvxE0G&zRNQs9lNzwkoUO&SWXc?*fGa^$|H+8$ z6D9)Jqp<%Lo;k!0NAOiaJE>Ehz3VYg8Y~)jC$}LE5#$cgoFeb*asa1L%aN#JjyJ3j zfzlqJIp1)=bax6wd|`&R&DLk^m{zh5ba?xadH6;X#zwVZX)}@LBIPq$=(Ks-Pq}v4zzVys1sp#o2wKla}@zzDc-wg$8f9KIYzFt0$Zpj$5Ry)U=Fq#6* zDE1x@QY6~c(Ux9W>091($51Z$btHYbuWm^!)6xAV^q^+Fqd#a6bf8ef1X8j5cvv$; zJwsH{-ob29wt{OqeEk~nRkZ2KC}rH|%IwuXXU#q1u#h~8SD!q{I8gKg zp!VoG3pmiAmJN?u<_6CzNC=-d)m48oqAqFs9iT`Emy$ROZlTNOM|T#xb!#mf*8K`b zOh)DMf<@@`>Xv(^2uDA!reL!y+2x2vFG}^-EaR#<2D?#4WnIJGQBDNi8kyEh=FTQq zj?M}mVTUR?$UoS3!cDSs7!xjyEs-aSm;=DMNJ+M(a9o#v(;ps(gr1|g#yTH7PL6k6 z-E1%`4AR3&USKp#i6Kw1yVUp~kaxf<`cRd7a{qucwK9H$O4Js0|6}}8le>R!aYEH2 zXgqjk<^-m-bRt*A2~z#~lWLQ5FMcfJPpL`)jc5VqZZ%It)zUXtYTLcJEcmT~nWzej zl5ehA*Xm3`jlwqMLU#j_Z~vo=D@oc$!VOs$jwJ#?Q;Xey1fVG=_i^lBEPG7zl-k<0$eeJm59F=p zcLEuhCG|_9cr8L(>g{5Qm77+oWDs>wkIiPG-d&IuPp%rV_M+qn<~ zgBjULKjrj;LuF!51c%v3290lMw6xYU)b&Sy0DK)#AF1iLROxHr^YqRY`8D0HnoHPSXbBT+Jfw=mKR2&M`!I`osG{5i!Hx=3y<}F<|@*W+Lvd-^G zD-e|Zi4)KcYeHZ#cQft0H*Zi)=plrkxtc3VZJ=4@3Y2CF96=Tq{%DnO@Hz@ST>LkH zGOe+l@X7h#HC#$(%I!PLb2P}al1@3(Bp@D1S7eB3RWsTBEkurHbfQ7XlZ;D9+6eOv z)d{%VAT{`zfs!jkj*o4WqxD{)_tA!VHm1a)-yR}3B=3$rc*)4@-8n-2Bq_Nga3|0mSGS*FFN;So%F9d{ zVxX8f^luy$t(T`6NB<4yo9aysafrfBoN^TDMM*Gj%JTFl>ib;Rq=*+7kr`n%j{GoN z^1i#nQ6y;~LG1kj%=?gy1lmh{>UF+Na_evW=47oTC8VvbL*V*Y<#|CHmW*{5mQs<) zIAgK>kVF4@V3do|v&vbUhxm*NIiCvuQ8da>tvvtM8!xaWhJXt!zXW#NA@B}<7D<0+ zY!kF9bPyc#Jwp}Gx-cy$#|+z8Y{t!SABQ5>JBl8`LNvMJ*XBo0~ z_t^2)?oddg{s*THtDpX|^+fGQ&2^|>-t#sO&%!`%mtdsE(ccS&(CSk7m!*{dKc%to z|4R#{U~KAar7xmy|Ll;AK@!UZ91jKOJ9Co$Y90ezBvdSsH-ysp0n7WwwG#seEO?(X| z0BHp%Yxv&(-ne+y)lISoH-(eh%|wM!$Xv1K9}y0oPbYXi;}GoAxMD!XnTys-b@-6m zoB`)Xvc1>g<7Bisyvv<1)Ls8=LVxuJH2`1@ceVbE_w?5HoYO-L3gg~2|I;H*%#R<(cj+cjziB{Z~9X4e$^6oGO z-lPH8d&Nt*AfnN~Xr`Q`N}D_J4fXY*IJ}vEQTWe2(uv8$I}5J$8d;-X;z1M0c}X7A zrxL?y_;FNOvdN^k5rm_p<|`W%J4Ono0#_YrJg&r&D(}d}hSyK93t5oS3u1w+b4)Pd7-3uFsJ>R2-_7 z*Q~!n+Tha5VAr%jn`av5s$#oWQy~`Nt%9Q7(s}v2(H&_)ick5cpQykXqt<@;dc>KFlLa28DjvjASOu7xVb$0)pcKufEm6 z&q=9f8qFn{b>Wt#@44gluY*j6PneK z^$l#Mdoa=8m7G`7`XDu{0iPBytri63NGdrMUFWqvDU$}Kd8}NtlGYLd{bBf9fYg{K z?aZAjX_}ViSNLN7*(8BP8arc$LSsak0Z)e&T6h^sk<~I~WJkk*(JCwT3QHQ}rkq1% zpHsUM-2xSKxA#C&k$)01o~QeUf*#8aa;wO_bha=j**vwQbhcrJdeEsBMT*O%*R=Q9 z)xvfgN_|$qWla`mw|lNnVPN990QdBUC5#Zt~w&_Sk8dM%^Z z_`i@GOT`rrGMeh6$Lcy00dxGH3;@(zw}N~)XPImrI!E)c-bn4nd3cOz=x6>tbb0h< zG^8UNe$;I*mt@$-gWn22tfSVE14dn9@YzghGJZJiW)Q*$#tOPZx+6&vPDhaEV)_Rt z08RYxLMTEUuXhH+5O`q$7kKHueDw=GF?tMX#q9s_P98{5P&oVi2TXHswTl2ZlY%2M znK7*)h2#j=GQnuKnt0jdK>_9WI}~FJL;YlLh7DH>VTIixJ|tzDZ>Ly3eM4+rGu};4 z%E50#CZ9fsOD&TPdEa4&%|%B)V%=1|O?sG&p;C5&j~(@m-jxkUs)Oa<@yg;jW1Vhq2prLF$Fk*TN0=h%zCvaf-)iUW&v7z2f> zg3!S|i?gI9UfJ^vB)laTuG%Z8WOPe=B3YKtxzrM!EnRS4L7MlIRNcMM zk|Y(vSnLC68vx3@^I+Et%Z$^!GGG2QJJ|3oo49K%yK7^9DG`-7chK3?PmY zyl&0AZ(!4JQL`RkyMs;7kQ1I}av>V%^z<05)!;U3xA))I)&xDH*gP8UHgK z68r(=m5F1;%i=xFqxZwr&e;HIK{SH_sJ3q~XOzelBOz3QIz*%yjLWIWR;CV}MnbzX zE`}w4#9XlJADG{y0g*3n(VN~m}YaZD1*(xv^ zR)JtkGv5StHD|SRmKqPD?|PjFd8o>naR z4TD0vWQ#FzW0~a2Z0<7*tZw@_xoeeuRnoVZc9EvsEoR5Pri#;PyfU80`T{F#N3NVeK=1p6V^d9K` zhMfO`W$?o8vWHPQoRa2PLpPygysb41=`&{4*+1Dn4%;>Sr&rg01jh}>b|2(xg0U`K z^9AlR%=HdzTXD-x_fcP)I}*+rdnGAqrvj!mFM9;yyyPXo1C4bF&8yTWB4)Mdvyf*n zXX)fcXsf^E-1bGPUiWH{<{GD8{@5D9m0(yR;u9ZPx(kzI#b2VkI?#fqU!7Hsfs6XPHS@mZ4mN0Sv5_Ue~#kP$=0DN z^%3WcB^r3s8I~Y4wOU}a%PA!9RL0E3zZfoPk<=Z-$ntT%f=OoKSg|T8iGOI@A9a4{ z`*%9E^$6cT`Vtq7g!yL`JX&W}u*t&@x?+E zB;LgA_M61*Gk2>B{nA+vPVVj_PuLl4H?d=ZwFfj*%Y!H``3zG~e9o$x` zQu`GmELRsQj5J?fB&!x_LwWoXM!Fv0tle3kViHDPootvA9gWXHuPfVmx_>QA; z)1)r-3Z(`xV2I56131W+*H=?8jo>YJiGu@~wd_*B$>n%s5|wr)Tk$S~`skh+j zK7d2nk8@;8;)i9G+HYab4A+ztbHWZQ_lOqLs(NLO3XUbKB|z1Bl7&mDK}r`z*P86l zZY1NTrSZGYV*M2`jG+VxzfkLd+KF%Rl*0#%vMxGj~2zia&IZ!BOq z$cHaAUB<&T5PnGoU8s@xWm$?guO&AXNCZSEKt=JSwy2`oEb(pka&?VSw76@g;mfBQ z1nnrktGpP)du2<0ucNLlIE<&}NCZT7gyWOaQbS{i3CYkC6V_lN^Mm+LLu22rQGvop zw>3#@<2x$FYu1RbRY@+Fqw%voQO=i$kpknq5vs`*=8onQMsuhM%<)n98>14nqPRkB zJ_geo+d^bz*@dKzhM+Ro9DAf0R$~-mb>K} z6?0Y8Z|TOr)veGjU<%ryFBe}bGIwN_*l=>I>0{td0M^`<@8MvVNT}PoY)>tx93|H1 zDg#ai_t`9y zMv{8|q5R%t^N$ z;Mp#LqW|_t^v#RK5o%aJKI=IaRGQa()QD?-#}{fZ@-Q-o!0HXpi9F*OmIqt~e4Wa(Xv zbpwiAh~70bcfh4VKa--a=gsCdNAhWbekT*1{E1>>W5C zt~7TUHlfsaxz+pQtB1hsSvE!jP=w3U`J8adD=mmWbITJ`^)RyS?2e;A-aZej$`Mt2 z;>oRb8PA3&UEmL3qV;qUWXX*ueyFbXN!EWXT~!!rH~W}uf)62xnQjlv^-O6W?(Wqtrb*PD*nP7ZSG})So!xTOKU6nZ$jj z&%kj_pZNL*IRqp4pwnj#&}5o^;~oQc4==i9XE{7s`>AX6&Dw6%3u@qn;d)s0R>uo% zGpLU<&lQMgNYQN(pqt(ABBIOogi^*32;tE`!Asv7HVQ=fu!<=`*Ek5#!kQZXK z=yb+F@P-oK`gCgH+;fykxhk0;7$8D=-{qUi!3vcc2{# z&Vw~SgO1oIRDLUv-h*3&CR#gk&&I)ebs!WzLGn9A_A!%8J|2brx98XkK8?~#vbiwt zeHcu#6=8zt^OUR?gujM;jJL*>*S}I|+CNR9eE(7k{fDO5ziY>4Me$nz^CJrTVmZgl z+x5b$BLdC7d;51({^-D#4LinCcZPCAtROA?sDeG(X}qD7%&Y++5-%Z-}+ethJ%~o zbfhP=yXY?0yv++l{(QHv$(wNmhCE1mMox)V7KR#X8fSY-TDyKS;OxKXf*Yc~^L)t( zAtqiK`ToHZe8y8Wr5IdY?bi7<6b}Je+PSIN`Lzyc|FnQ4{4cH4KUUh5oy@Hq{|&?s zsah*3p5XoACfLnK&l@|2MrUzrqmTVhtQ&Zh1W7D^KpY7?jHJ;1JkDL=71EEW^hs?e) z$3M^R*>AodAD=T_IUgro2tb?Rx@&sFAjtTQ`<$y(dp~fXZ)*d+Sy1=CEo`Tyr5Rj~ zeDiq=MT^<5GvJC2@N(-9zS$S&;Zlyg*)yl{&Y^wh>qls7H??v@pIN)*f?t!19$;~^ z6Y7UyQQ8&m-Xo#GJ6afle*T2nkGb(`v%AW9lEc?L(QA{a6XD4Vt`OoL`?c z&Wn%H6^!9Um%N-0?&re2_9r(m>cA$L<3Ldgu3Fo8lm|Cg$}+=IHEcvI+@ULSmUAV> zCeSzQApI6Q#LryhOonW3Fl5FwE$ZwqmZx)0?e|DYNb*!Tzm7?fvm2KlJjB*Fzyx<+ zM_d+FE;RiTieLYx0Dg_1VZ0ZxLUxn;Fna5VScPgeOZ5n?#!TXuBI>8xSF;Z!? z8@o4MvHQeQ9rk=cPTLxlA>K^PaQCBqEHcX2cKOhjh&(b8Ik%u7ZB9=^vRp(_Bc*3v zy=l3wkOg1bNWsU!O~ppl5naOp103q`PBKgHc`l|MP!NJyg#laP^?i(?aA@91kqH|Q zTT5V~yOW>B~0W?y(tTBD@4PY-ViQE=8=^nqC^+s+)8B1r8 zuChCy!uqMT9LCsy-q(Scv3zJ@O;D;Ihe2kSIH-4NX{c0q#To8;me9QVRXX^!M$k;5 z%9DH#fYq`)qBTYV#T$30XccRxF}%S>bU-~V_L3HvbAX3+Q772n!9e<38p7okq68gN zao=FPfqslFBmsFl!5;rcvbDE{z)rN-_+cMExCv%H6TT#2PK=}3(~(eE3V+1`*6l7Y zGR7`ml3)UJgoegjz!nsS64aLfrq}~HOoo{~zTz39eOz~3jEKmP%s}_(s$XXuJz3ns zua3i>LHK4RcpXK2oi7Hx={Z=#(_i~X@G#ZEZ{O0q2IB+OTK&(G-)XCjRgN^28El-` z_p(sF<`eg33mJ)PM3CnbZ<%?8uYw;SdwRK1d5_q*DX>RG8tcAm9mL*Hpbt$pfMN$w zU9F1td~Nvv7v`jGp_anHZTZJs@fEz^hf%L&&U3Jjbz$#}zD*|{<{iANYv`C}XHP9Q zRu@pg9A?*q&2BXWdufS*71|FX=TD$rSt(a$?S=B-$XIvB$N3LV(^{*jEHeuTA@mA~K?LM{d*&5hAef9z(2-sShOPX6!V1#lB4g{{u zualFi9+YMpe+A!^%J@c=#n>`W^LZQaV6QEvYCBaz&KcwX*+7>@)5`@l@!*d7Br9Oi zsH8R?Zc*NKqF0naZJ8_O<_Hn>_|WtzO+93xUnw%_X^&%rvF%|l+hx}q0Uj^a*bw+s zLmJ}MKL`9ui($izZG%VL5`L=T3D$x-L2MPJ5aeV$!ZL?R*py+9ca0pq#SboSyj-_l zY1kBOsAWMoCNOhKBjKoJHJsHLqeaaI34snWsjJT&vCpb^m#yOr&k&G8LjucLqLxluuH?<4A-XMd`I4VEl_a`xB#`7gu6y*^`ph( zAWasF>24IGwoe01xqwWjM4$IaD}cykq+!)fLLE86UpNm-n>vw~0dsIDX)Pn9RO%_4 zKf+D-r`oiwM#YG5g}%1)%`-q!6_0yyMvf?<=p&VH6@@zBi=-q7ffJ`LY4OuAD*b+- z7NWiS6Us@S)uR@|5Ogc#><`e>9{uIWf*a^eLU770Tl4``XAqe^xa{1-(n9M`)7u}} zLu71`x(AS-KQV5}IzxMQjo;B~c5mF!{uGy(+;ULmwg|u{52y*XKkLCQ_Y0$wjs`T@ z-TM#3phpwLYd}dziG6EC5^7zn77Qzd|3*SnMJA4{5Sw3Xz^>^R#bhc7a4bk5#(I<@ zon0P?c8)}Hx`5Kdxs?rX&Hlb6tYbskAp_jNZ>HarQRxtxZeEP5&+m_4KO4alAlcQZ zxvw3Nny-cqprlIo|Mir~bLS54ELjgr(T5)JgQRssPYmi+SZ&h`X$m!0fUW>T6D|P6 zsFr*rS2BHMH-$Y>E0v$dx&T(}KDAqvRl7Ed!Gqg)m|1p5jyT$9#9iqD=2AM}VO`k^ z^~md(I=M9*sw6>;xO?z9q`^2vDpHcPt?k_L{aBV&6y0B&6s^OL@IyZg_B5BzFmrpm~N7vJX*c zPUtvm>7;$kKyB;Tsa);YDgF&juba-;lX^UnXxw%$8TkRRc{wItc-SEX;#Mu5FSkfZ}_>5`?=prs&fsUWFJg!BH#C^nLTG-QLxLml&}sb!oVK&(#X z(%{>rzV+$^hh1#d2qSfi@$XrfjV!uk>(w%3xdfihlxIt z{HG$haCoQ(Et(rW(!2c^zYRKn>zjZ)cd{NWet(O&hRAm|u%z*sFX>eiCgj-%Kc3{5Yj0B4a1720g$LN;y^1`YzyV@Y3^>D}&0&we1x(IdE7mOH1a zS#-94r$GM*jeQ{M@0aHrfzC;sB-3Nb8t2$YA6peY+Lk@?0hL@UXpQ4e9_Wpx2H~W$ zpsNjNul3Pb3GX)Qi+Tw@6;WV8V16NGhdm`c&Or22+;? zQYZQ?vNBO|p#~$3l1ytc!fO^HFD?i0Kt1yiPl*85_QIv25NuOQNa=ZMnm!n{fT8Pq z2@E|VKdM9I))S`~NJ1z8NkKC?CDIT-IY(BdU%e43Qcd`%j0zj&_}BvirUJ)4?E^uU@r2yc~ zTdMlxH?G7;5xd?bIK$Gn6HGEpQZbZB(0MJ4WW%eZUU$#K;IUeOSqm>E zRzuZ2nElYNT(S0gClsHr4lM2I);u|TD zq9<$oHE>JNIX75=ScloTWw#t!)yH+VU}G$kaiwqUycXBddMUAsyDP za5JD_Mz>lcL8omHt&}fuIbLDe0Lr&9P6AxhAJWsRIQhC9RB+Dq z`F9z*x(h@b`D+uDzPOhEJ$+jG|79c0ZA@jH%w!$Dq}u*VVY*7qQ!aDq%fa@hZs*#> z9aQaI?}v!+514Pw@~Hd@dOy^UklY6c7lUa#boB=6BRVD~T$7d;Eti}0sjUw2vC%fLi%(*?b;pq%fd|sCee!DDu_JPZ|B<~G0K5Iba zb+Hk&o_aoJB>JebM z!PzN|M|_cBuA78DDYZy@-vl_23j5JeFt)L^dSq#kG*9+Ms3SyGT z&nS>L8j7V?Y91!!NfpUIuw$z7LIeT=nrqM-`V1(e>lZPjMvqh;B+S!i#I7inr9O`g z4Bqb(YYpyGz=4H0aE5gl%TI!pFeK(HWz_K3Z?HDg%fh;1SPlwJSVF$T$x9Mp8XXZY zM!tcGm-Zs_%l%>T@;2p0x4D6SgJNnPn!e{&l1j>D5wIO!QtUR31P!#!D2~1w3i?D!G zaV(ilQyO$Cybb=X!4m zcDy1Sqaqx(i`fenoM*_ST4ds?WT)ln%ErPx?lYb_@( z?(t_##*}!)vRhY){ckqvC>!U6T7D6O3#@V(I52gm@0iC`{LPbe(VHRq4~sFb?I#T| zDP)FzRSDIxNCe@?ALC=>Iv5cPT~RZHQamXMzOE);q|K%hlXQ;y_AW*S)W?h|eteke z&-E1T?mkQw+){oJTYTeE?(6E~Nvaw#(C@mHRLEzADcBNSzHkZfT)`u4)nvG>kdjPX zXT6H8t9};Si@WCATnD`}jcm8nw%G?$_nFU*m-Dq7e%z@Bt*1gig-j4qfcscizlLYw zJAZ1!Uml$69!jIqve)J)LfqDa)a)t*-^=Qys9?YK+cQd-*oKP`$#)A@1?zI$QoXPH zJ)SPzmV?ynvBC%5a@fK%P`?HH(|$?n>xu^t+wRIJNc;|lS3cA)<@~m>fM&_uZ^(rT zhebG4`0h3D+7uM>hkYUmnRZ6_{x?b~q&#rhuFf@@dghI3v*PIl;0|EHF5-``E*>Be%_Y&*@OuF#5Nom#8@KONh}P)Hewn5hjbs-$Vh8WuDj8 zVwf$%&%SD5^Jd96QLtg*(s0A;k?V}M5rG&1EVcO6zzvTTS z^0_;Kig^fj`r{X0ys&lYOtpj$U`|G9`Os&8{fj~Qx}uKBJrq2lqG$pIQ0=$a^_D3{ zXQ1Xdc25g0oL}MEe&d>Y1YD*vF zi*xbpFs_4_KDewp^mDd|a^NAIW?yC2YhY+92L-hJ3@VX5X+Ue^CP9jA=1_k|TxPn4h%5)2*6MSnV!k9-lL)^#|(_+0iN;j^;WkWflC z_UrYisJJqKAURItJQuIPmAL4OxM-YF z8P+|n*WeaRR+zw(1)oChpjxiKFWiYRiBbE?btEm?YOMu0= zS`Mnp_}cv+G6Jg#B@TOxPd_}FLvlS@DVG?7GC_*obQftOCR>oQyQ2`$SHVIjwK zRc8XEQ3wFe=RCbfRA>Y?ymJ=nJQlekDj9Djs7;Nmlf|TL%?fRgY@4eUZFaTU8qyd}P8OBw5r#^eMAmQja>kuAhhvB* zgFMZdDaDBwH)vDkiwDECMzH%**$g)zm`v!fxJu+z@C`Q}BI$$bGu+H6;pcoaMsBQX z@im?gxA?tz06UwiTFPXlBdhWeXA)(K=E~UH5|{`7{M(nEs(R@)Uz?nKE7}Qke)RX` zanvSs@}AU3nKsx5Nq@S&O$r*d z=x2qJvuuj?efk{gqYMQ=h393QwR4FvAk0~AhpSkXjJ5|95)`dI5i1|ee3#J$sqUkR zG-SOVM7_?7_ohO-*tkU|EtA*@QT^i1;z67}13LW#UjW;EH@Dw>Vq$JddHM)$DYi{q z-ow!L5HN@V|GkVFaa6YH;2Y6S%d5!Cg@UCUN zV0hx>)IHy_zrpI((%#uVp}{u{q$Xn~6iF3}nKDEu_2DW2BvY_gy~@JaizL;v8-v@3 zd8rbsO<)RLa(9jMKkIN4+P89Glmm~zpdK78e9n&wJN`@mPvC)){lm)g0#kHQYzF^ zyy!2IFIFYm!nA+TnpPZ6tYWuCRUP%kGRHn1pyF!^`(WqE;>bgE29LC+tcT5y zQNq;v@7v?A9m8tLBt}pZE80{F(X5$?TwBj)$9mF|JgZAg)3{S4s1SyD4{@My)oX(p zFH2~6roJyoYy29ku1Yjd=_T0`!0+-mfpLqK0k_NO%=~p@0nMZSOF>IKG0=PdL;N9A zBJ&jOjHWVA9Sx!=>IL4sZWnMyswJF=7E(y>l|s(B9T!}etipEd#}tacU$jSL4g#Cc za2s}5!l@qi`$g&8FXymcn6!Rg=UXaM{0nQR5Q{;?S@wpx%V3#`xy+QgJaA0zTp0zo z478LAPjx-JwTv}HI0mQn!$}^3@TE?;3JZd5rV6$&$FTK6!a~R}GYk8NfJalZhPXUU z4(&pdL0zCIiZrBesU@f4?;6~D$Z5p+RXQvm(34vEMa7;-x2j8zNEJGf8;N$nAT=I+QnzRzRa$PVp%K6R2)X|`dJ%X@ zt0KUOKfFw8N z%3)rNO2MrDKVEdiR(%xF6E3JUSOW$#NRi<_kzNz7rb>f=`~kH;5Pu=>5DIlYURWTY zf&WB_`$y!h@c)8bjExkG^{qtAjjjG0EV-m4FY|@PvxIZ~!@pZ}`dx*v4D(8e(R~y2 zr_Ve6Q*R|aB3q)31(_0Pf z2`Yh}g7MIeB#)$E?rFoPC%vQr3a$1#k;X888-@!>LdTT)fdU7KO`)mzM3bYd$g0=* zm>s@)8IKa8#3Mv;uCeWu71Xtr3J#ckp;?PkFb8F{RHMaGDwR`9ufQz$H&DaWtg-!@ z<(F&Acy2f()Ud_H+wo$N0qSaBNI2C>bg8Z4*p7P?SYwURnUWHNAHk{fk50~Q)&uJ( zFhFw#!h{VU8eA#XOTQ=9QeBMDo2$!vmSaqXlMUE$pL>&L*}G4m_?w2O7*RRQxyGxp z?Wj7J#`c3i&RsF!HWWX5FRp7Z{<$Z0ND38i1Q!%Nb=On|c*xyY9T-#rQC9-{k3%eY zZ>oEQx?F8{^b+bJ;>pSFFz$9>6$K5kn`d~$i&VEnZNlI$s=u~9e4LTi^$W0i{wLAC ze-s9i{eRi^|2tqM{@?zg2^)V+#s~kAo@b*E4pzubRLm z9b8wN_U@BM6~q#oLSx=}C@qvl9EewZV>;MnsXtnjP06_-jZsCey82p3wj!C7Mvq8W;`Tm^@Jh4chb)YCEu`;ni^K}tO43|3+5t||5o~bv z(8sR7c}fO-a3zxDCfmh0%dPj)gD4;tQtfwlTLaW5*;}J=U=NPbWPiDhSeEBvxTp~Q z*yvuC;A}PTKaO$}vC)stlexO}X&ks{8JJk#!)yBM=FPh58W;pK(*qZ#i`qRtG%$~W zyrij%sy|Wxiq|`K?=#2r^+*=|x$QCyI>p4K1=}~vEN(b&-RqOEwB`ji;!onJLOY(k z8jA{(=}~Y```nBbZ&?lZI}~%zoQDhOl7{8NOfCaIr+uVLpz`pf7A68oW-r|u^ql44 z7)Z7cDCfIXkLY!l`!51H^2Y7lTk-+Iy;&eY|2~jp;4;ueU=i$&0i8n5#X$#~1#^m%TBkSAI zMF|m5gj%CL{DJW*n{KgL|1KB|2AmedaXr0iWLl%$lK({QIe3UXwhPNkcf~{X#IyS< zl1*v5HX4~tN=X(cO-!3tl2BO2mmQ?jzDki&NIo9_|q zH9e||k|rH2YrYzj=N4Wb>+k5othiw4w#|JGhRvNukfnt@wFubBN@0O!%k&UhVeFxf zsm6tQ>pV-1LG#!#wbcWN%m^p&M1$joZ{9_TfFu*%((ye8zxR@< z+G~kG^88ikd_BdNkP_>A)0B_#o4EJK9zyBwsO1L3(q#=zAMhk`4??ojvD)$0G(?oV zKt)Va-5(xNT*AEzF?ymoSI?tejJls7&_T;MsQAWe#JJeG!fLpBVYAqJX|;)any`71 z@*aVLm?NmgV>7!f*YQ0elqzFyZjnE|;7i0s=0f!iG4t3&sbUz_nZoIRfn}0#3QrVs zZO9cp!2K1i8p@_<)L+qx`cI?vU$Ynd@~<|xu{HlsE)7+QlD7ZGF2c9b5|q?MC7%`e zArng%DhX3cNGwO4rhppSYO@(c?O=5%TId7W4MOmZGEd?!Zc&Hbad7Gun{pYSKPAtk zq3H=LXZDvT!}~i}FF=dd*6Zc<;G^W`hLSDho|IBeVc*|@mhvLr&lrRX_Q;bV@eEwB zui6n%0{9ZlgCQ-K zSVgxGY?-cg*(^Q{diOjB$qsG4b^jt4;f%=YcoWX+Gz#9B7^&G{hPPtf5+gB{L9N_x zR+ZRfL(VD z=ybjUNqA(hag++61Dj9sc$|r4F7K)S z0kd9nh-f^emrMuEnsUIED6i1=_?0XqMBSywEzP&rvZs$6(lhlVlCZ zRUx|9HHQ4+i7dFZwzx|(St$c7J%w81)mCLzRWceSkvqyeP8%pEV186mwmSHp{Vj1% zS^i5K=PL|X|7jTh&)l#6JMB(seJ2NVHxXwW!~ai~IxBYO%l!&=xX1jWdYRV^*$YJ2 z4$&6cUoJc(Jol74tJr${S}H9~`(cUe1&AjxmHUx6+%J&t*W0hSnVM$=APhG0I!%L` z!R|i0VR?=5`TD-8u`}Yqpd#ir5>1SAju#`#@d-)E?D7`kF&}VQu`*u~&1?FaM>{nT zZJ4e4ar^hXPQ)Lpa`u&XD*kEfh2wvenf~`O{yqCeOwaUx&Pqyu=O3SB9d->G1uFj= zgDMBWxOyoq)G#eBv2;16AL*d%gtK{y*7M|6)12=fFFh&w9myvUZ`zA*WCI53AOe1r z>)OWJTH8rlR$5jKFOSbRxq&U*VY@Hg1QUl^yD1?G1dx>x`C&M~78AW?Ka0FRW>g0Q zhIberfdt8cDD3lqT2COE8EXLNt0MBR35r-d~BEexa%Kg65%Iz)g-A>RVMxK2+W z$ys8S4#I@o>;^BVBD$fui>i|iZN8W=h5WkiC1|YH&H;kF`f8`d&`nQOq43JqMnZFV zxhOwDbz6T`?3*LkWJvAx9(>Xw67qr#6LvMJ$J3uXES-`zLW*)j3Tf1Z-7l$9q4&fP zqr(nS|L#rYbv@$>e0>gN z|I<};*{|9b0bl^o1n^c~Fgos2~t%#FnV&of(xf9n-S#Z1Wv z&?5%PB9-~`p2D;)MMbqMp%_+UMxFw@R0gl}jdkH!d4_eT!w~d_FrcIO!Ns{Snv(9Y zGwSXTF zs6H&zYeoqIu$9DmRRqd@fx~=cn0C0fmu@F+dyS0i z_PAHVBN-aDgK=pOBBr>1{26uF4uVv5JoiTKY0UXXIGl(HPPlG7r`?|}*-dvoK4WUA zfacxgg)vW1jg(&kua$ok$O`jLQ;AVx$|3dUh9lCDV=B;9>Inf82i`YZw-X6>DKSVQ zzkeiKCqWP|Ho0oWe~)1UQxrHTG|pJSv6L+Kl-H$nAmcd0^tg+^)-cfCN}QlVXBQ#E zb7e28xfl*lW5{e`9-%2(e)uIJE79_}?=nVNMBQQ4ejy`Is~Mez-5eQ3GBLWsg4ZG| zV73!>n6iQ4_)c@o@yXj|OdDgp8cg?#gU3_AKaor=2eAUI+QC40mo{~%UMAN~PiIvn zDB*-Akehb)-CGrS%z&bq<&h9Bf;hf~o4V(?tXHm;u5PtQ>2tBXyDS8$j|jP)zzy!+ z$E3`htR&@8qZoObfRNm@D$OO#Y@Bk=q;he8C}{*W@_%vmjzN}&+mdj1RaaG)ZFSkU zZQHhO+qP}nwzbQ)*=0_hbH5ui=f>RoO`IP)-q^AC&*xoFu3Wh?LvDdox912_ixSNE z*x`jC^$~=ledYKC70HwUmxqAK`Es*Fq66IQ*0pTAW%Bo|&;C3J8yU7{1!v2N)bF>7 z)@p!rHu!Tu)^*0Q+i}kBXz5=6meA{NoncOR~g2B4a zQHawd@m6Im=76I|v)FDWTX-j$2@ddgt%U zQQDL84Dm_$6(%k$txW%rUb*N4IkbFUgI5#`WKUcQ!lXv+86J+3s54cX7$ixWS9WU2 znin*`8m!8?RGS$!npTRkcouZtp`KVR_5BA2c?)rqroyGn>E^*k)d_oMoF|JuYpS)P zvcywrDnfug<=*6QQh884*=3or`rfo9B|?PGRPzwT_Rt>Yj#jI z^i~u+xTL=1kG_~+(<(N&S90eFdhz{F`7|bQ3_wZjqi0db??&}24ESCiN z&Lgk)ryWPb&?h@%8(*`87Z9L)4julkH(XfW-1Kdp=TZi3fSR+cDxtf3PR~CT^KaKD z0Q+wk>iq3b@!uCZ(SPIaQLz2)i;Vs+bxwK40Z9nylbxesz?wMY#=uW0-#;82Q%#wX z_jfEWg4!rey%?k5pM)_(`qkC6S{@*=r0iBV|N2hTBxPzvHT58z-$smysIZz=^Em#qRkfY66QTQOEMdrd0 z5^E)6+#q(Oc4Rf^6>CmoJ6iM_4H^sV5CM&; zf8RR|T89+B$g5jV$UTbhMcsF6jaG_Rt05JmoZ%+x+$u9D5z`H1Unc`z8?CU zIkDL{ICEv)2P_O%<`H~bX_GKJ8gRi-Ebbmq)rbQ2zr)O=tAr`VrWp>TVim{96|n9< zEVpbom0+MZ+1+O=@?=DKs70rLLaSj1pdpxgEJaFi-#LEpAQP~L zuHL-cjCw&IQPddCXEkbgfbHOjD0vvaU+hmYlGZ|;3Pyet3V48d$h^X8onLk;>Y-WS zNJTbXefE3@#+KPxYRa4lTt#sxn!>PNJj+PQm!BQgGA3(HT)<`{jez zM#=!F#q;PTTiDPhMRT~D&y7wyr;r?-RoX(E|E%m}%l-&9#~Rk|rfwF{1=AtI<91W3 z-5!z)m+32U*M;A+@F%}Wrpe}gCPuh;2nWg@`0EMbrd%qtKilC+v?zb?Vc%x-drT2JD`MLhz+TzTL80|)_}sG4}c zoIcq&ry0z;bnmesL|&vyW%&6w2|(8J54Zx@Z4+!(Q0V+ zqZId|#5J>iFEgBwcDNhmtHqq>^vVeCvs*c#6L3VIu$sUU;@fqRq1DQ)-{+TnL2M)jjp2ywvcC7gH05qOp2$X>{jqK4CR}#q~num|f1BYP* zQ3L1BbNeIg0f`Np?K)qgX&cCgEXu&vZMy3*g9-M18nuw&E} z&k~l0C5t$nzNl&w%Qteq`1s#y6#V%iR95&={rY^Ba;^NX6%v^ra}$C}tdv*#$Y(*b zq0UcDQP{QK(O13$;{HRotV5ro>RbLIpUr;zXWosJ}r z*{A>VUhS8$3odJ%+~BGM1?^!$b;%(&7&&+1{TUmM4V0cn8Bl#&%t z?|dNn2XS=>#t1?8-5$h$OECZYGOh4$lxaaTXEQ@1!~dia4E}EwTS-F&Qwix4CT)yY z^k9Aqu z6HTYn)1<$u*?G6#;&5`+B&Vy#i|6HG2G`~1K^>L=&sNMX5cTlQ&tm=1T>)U+q1=6W zsD)IzSj9;-;1uXd^i&pGA>C3kuXRV|qU}bmCu1`?UP|yx)te1t-S)on)9<{&?zYdj zmIX+k--0Gq%P>d3@DaZai23!^UydIt8)&_R?$(>YFA=iNct}#MG-d!T zkAK_ArmYt@kvSwUo6ag%>w#vV+80}}XBBTwu3G>3u$rL*Zcox^Tz8gQLb;5BK9yLG zFAA`j$$>xNK`Kd03Tql_8UoN&$`rbA zF?DDa;LB9^Uepn^pRQRY-Sb|F^z|chC_kuo6Gb$a4?IKub@QIE%&_YWhX+>KC*4B? z&KZ{Lm&dx^tL&Yhkf@~pi_XCiO;2vu8La@6l(L3xX@@K`O}FWOwf36a2;{ft!(^Ab zR8l9xZ@E69G(cD1bH)66=rfe^1}#v7Ijqzq6J&y!<`*PWOkLGX+azNvdRLSp$lM)&Hhvq{ec|3q`7&dsnt8 zZ8u8#)Km?k+s64ZNKc}pa(k3JRH0+KiL$CNAOIfVTO4#K@^fYJ)?LANCuW@#2GOK(ZCd8jsxxAA-~G45-Cd|(22+=Y8%3Gpb>@oi1G7DSgGLn@ z;iZW0*MJM>!%X>m5{{E=bm;5DNPX6_Je9LVpluGl6+OR}Z4A`;Rp6eSvb}K@VD>Zh zp?%r+8`Xkn=%7OAm`_?F9B!VUTBCrj^2J|K(rL$P3b2p#f^LyY?O+fAG7ZXP-UX43 zp-^N=MOCyczsnZ%l0oZ&EmMp1JpIJRg+i6Rw3CA&D34yc^pD1(Y+2^hE(q?qJo#wQ zJc`&5w;pHf?C!Q9neP50IxO|5N9gHWG7I!S!o&YJ+3dge!F(2GR(k&}MpV(T#Z*E6 zR9=gqoQT5~nSw~4=gnA4R!}mdQ;ILP+h>)#p{m;-rZcP8t}2Ww)Dlr=a~6Ok^2-|l zPTZZhKbO=kW|*XH_BSA*A9}?8%CPlJ4ULQ8Q$M3i9~!Sr%EcA zS3nvZ-;Uas1FEr!32uvo&03X*B?N@rr@XjhYRfb!E(&!lY(F3pA`^{;?QQuLmtauP z78hm*E-%f$&b?gb5xg&jkra$vOe*BxzV2*k6BB5w@>KZCEhnRea4^Jj1j9_xq;f5g zP65woKh^>xNvyy);)P!BQQTRJ-+HtP`5U+CC090{Dpvp!sxh=r`xp-;k%uMDQ{^dp$q0ta${tC8cI`Ku>n&e(;C#tcjl9ZXsZ!IE(HcMp&roT0 zXP)7dD_2`em7tL=^?AkmYBw9lZcb=90)|vxAq&h?(?&xoAC5Y!{4I4%Z?{3OMWUlq zTwN=jc%kkc#KidJi$<@%!Z#!9Fp9_^GYR!+On73kXFpr6WHp1~Vv(JcLVJ|q<}u)? z{43y005Vd^m2Z$tF}Kor_Op8FPzx(uSJ)0?cP;!|Z z$#MZ^uhU}_+zp^NYJp!UWrkr6_0_swnzocnrRj4_1+n|NFq{cL5MtXB7-Ca4p)OW< zFIpgfT7!&WGSiCx=PCe3KM+-97d{ubnIci?o2x)@g>(|YB)SgM##&*)0W zNL#XN3H4VMjy?xqOC2n;M+Pl3azo~+KEOcd33_bcinfXdYRB8Z^@PchcS;5x&_Y5I z)CfsuIpBo=vr%k4a`mS_vl>mBj*H!4jlRoi_04*>!tK#|wZ(ZSy_W8*df&a;AY*?i zE!b4YV*Yr}DHQF9Q>9E*Xx|vT)UnP*s+uMQGh0jStpzHAO@=3y&vEuJ!_u+VE$yE#2}j`Ad0DF-qHnd((M1CeFV)K99JVwuYk7_24hZ2*W?hiHGUFzYSx^`-HEne8i`j*F6uG~`~l(VcsF#SRGPrH(hr>%}*^JKH- z57BZ-*q$nKEnwiy5h5(4teX#)l`ApJLrh|DaNHXo+`+7O>)mt0z>ZwF21xr2aq)B= zu}%$l6uggFlNVZ%MG|h`7~4n?s8+D2JBqMyB2<=;t-T2|0&>e+?Z95mS~%k zE}L*SFSL=7h-hxZpCn_%Y8+06Tl~v0MpL#Z7 z34j1nA)b>w8-Erb-xE5Mpixk3ISBS5$y_eNtjT`?a&T|@0h-Yqb)xf9<)~M~g$ez6Lmfal; z&CUTZ2Y(vctYv##@pu@GBj_F%U%KZp4gH2CxJ2@EBbV^@V}rQ++}b&OMWX!<8Ex*xEO;jM>Nfmih8lw6 z#u^G5sj>FOsa6tk7`?5cb3dFIT+#^3d)CZ# z;C5XNl`TmRfiLz9f$OvVw-k(*6^?Vusva|cMQLhrdin;uBJ|#v?_BFn^)Wj35b}*u z;6SM1O-rs3{G8#(xYwi#pHJXLn81QrjTO*uVF-Z9W6>Qztau4=>G`V^$MB=lymL3XZKPjTjMtx5J~u!iYE zlqEHTbjs0p@{HOzcngZ;2NadSkh%qqh)i2K)oLiW z57S^aeu6h(o9@NtAAQo?uf8OvZ>+)u_doSX|8FUY|B6@s_p+6&k-eFX;lEP&|8*eP zOvUBSRrCkp7CBE`BNmtsz)Kq(5cn%L^d?AV{d}If?JC{_?-})-VR%sZK7gke*C>+< zJ_>x8@xzv(!J%R1YLc^IyW8glLKkKR@stUhlYJaJ70vUEonBM*=k#jfipiWgL5m%xr8O;(n z7Z#QPo`E(754XioG23Y61y;07A0Fr27qgKEW(7VE0DWqs`M!*Yovf2AK1>01P2L51 zP3=?DJ`=042;E0pOO~`Ez2*epz5C$HDUh*t+}FJ-aPD9-4G8%OH61LEuLI z*TAQd`Vf`Wq0Im7_QVi!?5cP@!8eq?OjtF+*y z#DlJqVp$@eFn(-oaLp;`7;NC~~!BLhd^)`j)Kw9Wq8$92(~ zgjs{Gu&M1jA{5jqS=g!Nc;9f8*^SH?Vd78KE)KfjhbJjUm`vFrMYf3G5E_>j2nIan zs{Ggu_#df6ai+M)t#&A{0JQv43&W~E5!~|wO=U2uR_y_jRcn0BkKk>vX7{vXoI=3h z)d`OB9%uw;LFgj-#6swmRH}iXkxSh83}XISc`=HQP%ksJ^{!v2J7y59@!DqhShK1v zr~ObaqtkKS61h+FSq7~+ufueHn1-wOEj*h6|I7?rltT8``yNb<{mZ=Yze)qu{tYrf z%FMvt#=+Lq$lgfS-p1VMpW1={lfwPabKaz=VT14;=?jX2(p)j5UQxB=-Y1^YtWmjF zB#av##RQO$)po^bMqDvo#p{5q;~5%M$%zUpz3s!@iJ{L{qeU~2mpU29WN@JWo3-w8 z^cGXI{UgzqCW5k>tgdp~+tqW&x>BV(WgCULgtQ>5S8M(ajK`_<+`{d-dA=yO|3o*q^e7ILE5H zk%>?&2CD=DiMokqG3nQUF2In+b}+gkU!5Dl;=}ie&FE#+g%iD8J+zeS$th8CqqjH= zJ(F2)FEA`2l{s#J46&irY!79e*t(!{KRQfkgJ=&+pcsk`Iq%Z0$B4(GoCE5x0Q>Tx zbM&$TM@YZqcw`ich8PEL0PqZ=^sc8Tn(K4&y3JoWObi+B1?qwYKhJ4BE4UP6V2EVq z?M6mM6GOrzzz8fj-U@@fM@&7JV=`+f$v1I`l=5R$Ly5$lrN zQ94e$HXNAN!pS$ViJ5mkeHnDNaz@lEbUTwMt(c`3Gn2q<_zh%o9|#~xy|?$fE?Dxy zVC*$iFitQ&SvbOr&%N|sX0-DQ_|XcAgT<5GU#Wu#B3oUUto$v-E~ru1#~tU`tR#MV znB^AnA65J}3EGzW_W_6hHa+^^Y}bDsh^zh^2mJq=zW&#~^IK*3pAwJ%7>s}KZQ3d> zqJL#|eCLrpiH!ycf&|&|*AoU;rY-W;^71ocgi0ZSmyH`g#cOIh4_twUsW)M~RohgA zLdgFTB7gSP?Hk2yVxaeGnRaCV_}WNSnQq*VeB?O3*rcolFe0}edmeKfzju$k zbYEv4PMYwf0nPfiNNGmdq?-=3KzXhQhCFT4B43ykWG--kqY};+)9X^gMOQbkA0xd9KS;@TgtxjUay9 z6(L5^=NWMoR6|0^NSi zSl-;4>u9cs@N;7L#ZjN;i5Ev^DOxyU2}>1CTUybvY@>Sv1>-!gdmJs8&IfjZhbqwiZ!<0FTlyz0| zF9ylCCm7)yi14y1@z}SSNVza#n}33+%Nm;r7}aJUh$a^+0l0;!$g~*J`0c$j$v#rG zUaAJqikQ#DCsVAGxd^inL!gIf#Dl?l@WqBySRSKYxqJPXpgZtLfn8h~iZGV^aq-v8 z+SO^ zrydf#e_b3ZgdtS`AR8~)`Y6Fc8}XI`Gubx5eLlHDjKjp`91IqD(&&h~20>2F~ghE==NNkbF-{y{1UU&8(~+UvZS(V{bro#e3K^nB{f2Gw+MI#=gUm9-Mr z)M9BDADu;Z@FKl7x*##L`clVO^>|S4GVjdJXX8Py1!W+^#iP@}!;vhprUer-PNajS zrD7>{@dvA60cUDeY&;f;Y=I@2jCK72T6!z*L_2HD5OS|nEX|F}Q^0{e4&6F?s{!Bl z+!oU2$|O{a*4L6nFk{(-12IUD%n)69T33POG;s{EX?koy)4s4VM}pgMXYmKj{)l2B zuq(6(kZKf@{%l`{bfuB%ThT9V%pGmj@=n2vVcT_=o(1; zSdU}45&mJbM-}`GRe6a`ac_M}z_U)o0F4E?!%EzCg80)Dqyp`=`#pRBE{*$OE3e8q zUjJ%bO;Igai6J~_vYj$Wm03W2b$#SQa-KQ@s;avqL&W(5BySi(y4?*suEL>hkQJm% z%p%_9{z%?A`Z@(fOQN^|Jp*+(INM=L1Fu0+akRqJ+nFW&K7Dq0k&yPl5TWhXTMoPs zPVUz@)z%YZ9isFAC}n<$ASPNDgQI33vMGr> z(dH3EbsilE!kiMPj^MW31(}hc44t%B?4xFg^_l}$)bMUm2ryhUwUuSLl0}pHCIk3m z`;RU^^#u1Fm_Skv_t17}>Jj!z)S75ocQGhLK$IYv|0{Xf9=sy1TzT$m*!(XiL^*bA z;x&m1##iRwMb>fRWdw{IAxNyqS%LMA3CXpG!js|D1)+4nm0(iyTS+`z4U(8CI zFxkjUouAI0A1}UdD7il+qsX<62IIPoMXrB;yU9b&w_`O+Y%#j%Pmrr|^iDcPJ8GXE z(aLt6g|IiVbjtIuJH*RBcGuTe#AJ^?^PZM1K~L5-U5Iq^&y!&|f()jcDm~5l9WO3p zm&EOJ^5;zbk>L zw2@to51pYNwYX3FM3OsyaQY@1&)}vy!+{++y7^f4$*}rnY>{whPi7qPy!;KGkw(&R zNme*Jr_OBSnf8z(_OX|u$sTDsOD6lsjJUNGPRW0m2$<^B}mGl&0EsL%4@2b3lNjkfNb2C!~Y~raiNWQ+6d4FTo#ugD*RgysC$k|Fh zi}D?~Lqz6^Mh84Ejk0!tiheiK`oK%mW z>BqJ1t%hQvieEnSP7gNimE6cEn#8V`M38F|D2=F8x{f2QpV#=8ZQNU>CSn7G)Y*^m z(@(X!=*2C8r&N0G5vhku))l_h%7QwykoS@xj#c>X3zV}B$g>aOCln@r-0D9!OGCH* z@)S_K&uI#NrOJ}7(;-y3G>FG6m0GK#`)f>MElgo47)PsAH$>`dqg!jEdnS*ZZbZ1L zs|i;QYZ!D#Nib$6Xj~{iuUe(fFc%~d&5p$Pr*q$YC7_e3G5B}7s@sLH7ybVJ$R}@- z*GrCgmWy#tKsCW9=uzOr&eA~Uw6 zW0N6|MA(Ymvf`_Xr;zYezO-WLkT5vzQKOCw4>T7TT8Ff@pNN2T*-6;Vho zeBwg|JbDw}!FU4WyyQbHXpjrmkiI&;LcMn4eJbxk;|dMVj$kIRcyIl3MLduSW!aV0 z`SKosqte$2m6hE0e0q+VlR~zj{ss9RJsUmO zW!N`~5h@23ZO$Z;)D!0xydw+(&ZPFVUmnjr*`hc6BnVmDaqZ~Bo~?lxulU!4K`v*6-WB)K_wP`# z1U*<;2_W_d?j#rDmdFVE{Q8=rmQ~GiEie-&Usz|6(=tU)x*#e*^t1SlQS(ntp@*|Lr{V z-!ugODUfYaQFFlhHWsfoK21}`Tn%3v6BQ3lfQw;<#o(~Vr>QHf^Y>?_6j4>yFJUql zqndJzF=;^J0Ea_INZ^ETRt$#&7CHSK8T&s8p7(`uRhNQx3$l#H104 zuUYd~+3S{rOwQk|!)y=h8Jo|S2&Nxdu2LfbuHwOV*s!}17}F=Iy=vHelEP!&>cJ-c zB*Z&kW~`_~Zk!YWMFl7d81op#P8Y#d1uzWwJQM?&pduk;sejq8P=FyvO-I91DFR3Y zq(um*O-08tQAr^7r1=Eo1jP6>E?mNeIBINdXD4QeD>IX_8xYNCG9EVg@hy;#VTg@M z_gWjmq?cFfJNr8Lx!Lt@yg6*#NmLR%s!e!X>?*`I@A zFXK=fm0Y}=S&$1zf8?e#)9)*9#W^LRQ%T@=rBNw+f|7LM4Xr{k=|J`zUidh%vM%BW;5$xs(xX8xITC*|JhS%h4Q+_Whw z>$g>aioYsECEOTkc9|uRWTrbZbU^pmKsmIdP^f<+FK^W9IAx>aLClf7^`T$1AEC2B z{F5-NW50mUZ!x~hFk>Q|=K@A-kNHAjx%nm4yQ9B4P708u$Lk}?fth|*(49Y~f?2EX zyeqkh_sx_$$#^G>3>lh#kw%EP^VZKw0LU)c%I!X96*erBNxUFmLPKJpv|Sr$ljStO zVV8|gbCgvA|5aYa=N+Fuykzt%LDnx3r>5w~ae;ub=p1qC%2%pt>SlS>p1QP+z?8f(MGS}kT0at}?L)BSu^M}l08O?N+8z8- zzX0tHcLvrOm;lx8QwqBZ_p8}g0^ZyabAA0<#X|<=&NC)djkz);5Koho@oxThnrpEf zc{JN-54nmR5jbpPw9z45wO-o-vU3z!I@HG?&3x>vt4tcRl-q7_<0mRt`>Lmyh(ps8 z*_`k&yfHx7z+vbP((>cMcNzb*>LNqVlGIP6>Lq&)Zb~RH01hA+fQYNh{!BOy0S!Jh z7ccsCWcz+`X`RbGL$&^*Ha7gaNswM}yH4hPaRHq~KlC82W(JN)G7}QH&0dTb&-K#T zG#Fg+#&RO+tv-*YUxV_&bqZA#C5e3D>DI+?)m&Ucf#u;2Fes~AU~tyq?(N2xFrNrQ zymJw_x>uBdczbU83&&ICUz(!LTdw_@&C{Z|T=mKRi)b^+08AxBRsiC6OR!4r7J*U# zFqYGFubwzh_%E^o{GgdT2Uu?Ycm)3&R-o?6r8PjKfBIJ-D_;=~uD*>>B?KOTkG=53 zzqRT;q^k$wjYY5&97#h3&eR>zsp7XZV^_>9L_bSL#re@$d($cVC5w(o;m-;-n9K&E^tL;H@2z4#q4Itbw1O2# zK9ChVMbgX28DjyzZ*YY)km}CIJisA}Y_sT7y=LTjiZ|y4t9PB~`vU{44B~MMhL5i`(tGrM<*4PBum$rB>$tS~*FS=Hnm+Bsq5B9IX@ld!`4f5%`#xTPM{fN~&&k=E*%fRUN3&w%;A*|r2b0!w z&~zZJ@8lugss2(627)YXV?s0YESA|$EWE)S13d)|q5Z($H*@|opYk1k9xArmEA_&D zPm{UmuT0!p3sp+9zqiGTMC&;)PUfYwb}$XT^h{w9tJvkwQaU1j_5y7|2gh+gx03wacp{K+4Cz9}qC>D^SRt^4f;|iQsXp2v2&|@ziw1kO=`wYi ziNlM+&gX3^`u0K|UUVRNdKe5*n&xg9g8lgGren36ZIA~VzFPc;k3BsEpcH~C~bJ8N8xV^Qk{ z?n=s>q&Bc=4kHI2GPI(ck+vx9CiuE;t|)6y%5qaZw@Ujoj36{O=O;T>d2gRqlzbgl z47?!_VUzB=dn$?CPg!7V5ozh-zGPih3t}!U0iC{aozlFDk?2`iT1GvZpJ{2J%RKza ze)3Z-ata#XO#GBzv0Sj*!vVTx)Wb%+A7!{-V+-b;3UnBq=alRTK(a^slhGbJ%<1-P zD)OkW47gTCY*Yw?ArtkGz}QalatRi9`4FH zzx|hqR*_ZRV7s(3#J(Y{8~}P_u<9MbY~#v&GH%)EZ`ol@WvB?k8E~AOzw__XU6EcapG=W3UZmz2 z795&hF1~z^OHV)r;r1UfWW&Le*GAe?v&2srJJHM~f}x{!sHC+ZBa??Mc`0F|ia4$3 zn6gucUqE(wg{qOSLoqKR@B4a|-%3aAs5AVkv#*M8iC)=LQXmyxqP3bzL>$F>bhL_k1rpVJT2ky$Y6X3xWL!b)o;DLS<+kU z;ph9xq~n3d&$sf<>HOLjbE`^1qQQcdM(tuvhb$FMnPC|?fS@q$rnv4`I{2nYXRj-Jf9l|P)**i-TzfIN@xu-TqhrMHb;aayg!MN?0c}I`Y@6CJ)4Rv} z;y=1IU3QaA$tO+OiBrZC1FjmkI7#_-qoOTLRC%B`y>>^Gx2UHobAM_iw+cU_!lJ>t zo?hy5JesjNLpYu}$C*yqvUO?CaX_v3={1PE{`PxrBy^U`c zVEkQsX(3uGRF}hN6vO8ngCL9v7JppyglD{D{by?_vXv)FKd@`8hbQq2qA8r#StOW_ zCwjN*NsvnI2ezxjEo5vFr0I=)X2@Ok)#JlMcXv_EnE%eQVc+a8frJ*>y<2_tIizXs z!~FOJ{?$yD?5VNz_$emSZcCklYSe|FRK0Ai)3YE1f6)3YbyO3W+ET6O(+6kkrRNR% z%n>S+Epsp=MG6y(%`FEK&Dw()?h&WwXH<)HY=gXql-i?cPGGEOwKnp%Nd;ZRiZ~hrtQEjMu3q2RIouGz zG<^(OqXnvaXBfG!OQ+e}dj&_Of>NeDn-w)zDkJz2xPCAvC- z1k$@igKa3iW}Gp<3jR#*u$^o`?^B|@7&+G_D<#&2$U#=`kX;;BhgYQba#su0>by(c zd=ni{)iCcM|F~;8DN2OMzSn>P|Hp~j|C`&)zv?Fbe;Vv66)nquHrOW4CN9p-RyGWH z-^mMv(3M@zE$4}OtUQ3zVLilku?s+yfjs+G*2@0HbnBbJMQIRsDvIeMs%a5_5id@t zded*XLEc`kQeJ!n8_qv{h@v<0gTM#~G`%h+EEX){ge`-Q8xB`(-y^q;hT}}N?e`fP z<{t+;=d^Ui1|-7;2gHn-^LhH317_HInR9euWYBETCQc{vpMix7>`eX#WZ6xN*F!m1{N?Ze=a<1v|FTXPDpQ+wNE&2YB`$&?RD}#$8vJw=N7&dg8)W8 z;t6Kij@+jO3+Rs(XVx5y#N!RT=cr}Yl~k@Y_?xrCcw9dXs6+bGtvix~=BWF7xXRm1f8=^c`Ue|z2At4bLSq3x_G|X3+rXZnLW)ic$++dG*o4wd zO|7f>>Vj2wSl!`LTvD-Va0_Wv@-!2;i@I5;#@OkIa`<#SpvEk9K^7_0eOkP0Cn*!z zPqtn5#GpDcoXW*o0Yj&peWH51w5bu`nCo~jpg1tc;VJ%_xLt~pC8wf%`{7bG9D;Ib z^ca)vg7$sS5cvTN2P!&{P1dT~EdAkU{+{#oum0v3DdcOm^!U3fl@S2S9nEFGYNd-R z4a_-Dw1{BhwmuRA^9ktP_v9D&AXGOD_!pI6rt*^av@}(mMRPa>n z4RtZ({}VL=gBqQ*K!1lW5^Z!pwfCUw+9fTb_nh0gj|)=^NGl`fv#d?1MDS-2Lp4IONHVgs9(N~-WC zmC49hv|`00xdwlU^zD3^`B<5_M>FLmiT~%O^j~X-&y%7@52>BGd*|3|)-K!^Qs++8 z5I2Et*o7DF>A%=5!wPRPHjEd$8g3-NxQ9u|j(==_>D^&LYI?MK{K7sUy;NDk^A@ZI z?$UIU{}Ta+GyHK7S&YK%2PR6?pN-N_%2ZUn)e{~4xych$9~ST1@06-T4TB#p@N<5; z*cnpHo}RiJ$jIR)GW85b{F*=%zu}gB4_FgF0CQXT0u+$u6u32I31zLxcMKh9Lf8Rw zxj8ulhrW}rS_|-lrZ5bad{_>3h6+KJU|>?{3XkJcz+9shP>D@UuF7Imt_($|``#s> zKxQToC?=kn6t%Xe!ms{#va!Hej>4Qh^O{WsX#tE7j{=sO5E9D54yDl;-UC5oZYO_p=h(C9lH zeu^C(flW!bS(UmLxE_Ay_%6C_ z!>&6yAqwyvI_Yv$)=QQSPvx(#Z9B+}v&z$PK)e?(3M=zNZ95(}ZcydzD6Tb5g+Uu-T#M zpp4ui+kwtRAe`bGNj#UgMxqX4Xd~6^SnM%*YI&k=!`bW--5PXKeolYzxP97qDm(_d z#|JllLt%dePlW^_0=qKg_&XQ8nf}@wjf>JV^3xvgU`R?j9qV|cLLWKj=(u1PT5ibXhV=R^ zn>B1EK4Qt4;LWc~CPrpgEI*)6wh^D)8nMXro&j-y?e^;I~dAf`+qpcVgv^6Px1 zPVIj8Pji>Xuw7x0n}&xZL#D)1R{&EzIvkpeYN~} zD>!Pu#Vd7f=O&8l5UV*^(M$e#{rk|kMYB!xY1&Q0-BqJxc1olhTIZO7R)9#?EnUAI>iDL?P`tPr!F8;^rqUNe0b zPkK!NH<;N~Au`^(30m7v6)ho>FtC`Qt_hc_Yx7%yYgZP?>akDaP51b|^ZGw$p+P+4Q%J-G!q%%yu|Bawq6P*-W=s z-Q~tU%MDZCUd>XU*%;X@w?Nv8p%~iqH%!1fEI0MNJe>~9v)yrBF4njh*xgL@olnGm zP>{+OqsDhZrp2{9>D0u(9)Y%>S023(Jw#ljB{$GlI~+XyFW^y?%>36tvh%Px9;09{ zQwhm(Mu`eeKf*M*)21#WWa~FBy3KaNOzt~`uizAAgcxoM#$0z}ds8N)k^crs;^)L5 zwerd$M-7FynOaKkpi3IZ2gQJE_DQ{gyhdAQD!&NFrwy9g8I#AYV`hmb$g{*p$>}7j zzi1Pm1qq0SuhYd(Nx6ua6x0cXU8y=72U9!G2ttOuwil$Cx>M&&x{xp^a%D(~KsL5` z5LQH%#n!j|^y6T~k|TC~#!~LxaHC94ReA@=HIVv-iv)lL!$R4p2WwZSP8gb?Rd_y8 zA#>7Y6bE#Kr==pu9KO~O%r)|I^zxoL41!XlwTfEYF|1aG=bx4q%7+la=M`hjI2c2e4r>vh8xJzPD z3p<3lhK*)9Q{=l3BQ|EuqzN)QXuOEEkGPT4V#%sqMHidEl3j|WBTY#$5K*x03U*)E z3hrcy4JOP@y5i?Vq9QBF*lX)zY0=8ktI+fiOszoK8|fc)MHG#DmAxDSSp< zsM)hsszn%2$NyVHUsukGc?@IYQ&Uv*ECR#ICZ8mRMG?sgzbN77l(Mg0Wjrj=D!e;q zd6X?kU2zva!7``SmQjstKc@PvVYRh&O<0>dQOuTeLN+!|yO1nZH7Cv5DuNNw=gfn$ zb?8dS5dn-9RRv5)_j{!sz&qJPM39;2W^+p!MzpEwtH@&)2R~tjPq~Q12vS)NjZj+h z#RUDlS3^@YrErFL-BxkX-#u`QL54H{8!1RT6+C1_cOB}lXf@nng52&k0#*V1eM$oG zz<9yBh8S(9noLY>3@sB~ax%VZpyb3i`a&0&{I4nI z;R_LTNmC-G?PerPfFlq0$TeNwzl08*ja1BZvK}B`9|Fc4+W`%k#S4#rrM8i$P!nIu z7iHK`!w1^>mB1P3QfLTWy-K6Wq3bRvuf6kjMw^;+|J*T%O5Zpxu7F(jum->V21HGP z>z(o@uU&Xo?hCacVzk$ygJR4@;rzb->O8uufnP4Dx% zifff-50FKtkxJNy_QVW{_+2Z2ikIhZN+ST zSUA517A&$ncPrKyN1M3VCkBzn^F|e=%~Q5J*5YM%g2}8S_|btxsaa0QVfqL}R!_u@ zHh9xQ(_)F73pn@ma<%ixCq>@kxQ0g0|03-jqce-vE#ZnQuGn@`Nh)?yv2DGvZQHhO z+qP}nw$(Z3c8@;ic7J#DxZj^W_8$8gYpox9?MHLXIl97(3Fe+z$Rj2!or4o)V}@JA zR#fs1v*Cuwa`z^Zf@6!lu1V+SG;qFQP=_Mdvs4qd%#U-*FlcL#h*i+{~GKpI7KcN;6SplH8Hz~|P_+ZMto94A;pw9bm<_6&QZOkI~h<-t>G z%u+ARLE{AQMC=qdPFA=kRMI?YUax|ku)?LT^kmSMi+-bc@p)sin?1lxn+LJv;%+P$T(ANw_x6-}bOJ5kybkqt z09O)L?lvt?8A=_*TsrjB(u?S9=~9|-0(I}0!|_=KJkU=t(t&h(ez~Cgta^5_XdJ;V zx%I(rR$sufys!g*0^A1d9dXV2CicxB>p@Mk_&SNEXR!ctC4&ycsz)+SoZJI_+gS`%p9UHjNOKY&iO+~sp;A@RbF$AcM z7o>!OX6!SBM_#YLRL^R6Q0cF066@T{kNCKmSFtWo+enxsv5smo=}OrhFc&th*IXEv z&)AxnnL4`TV4GIVE||gkdW59A2>~&+el<5jMA{DYgrUo2`Vm>x`|oX2@wuL;nRml1 zn3aQ+%HBuD{CW$V%*?i7>nEGl2I?9zixPurnjf3qNgTe^$Y&Q7!etf(wK`cBcNy;3 zsCv5(k#n4g=6I4fRG}A5A0;~KXG3O zST|EYceR{Jw{}`yxyN?kolid#j&8S-KX`gCo}GxV@kDlbYM}$Ny3B-Rb~#+;*+Dr zsRghXgn4&+6`oE$V=Jj4?r zR3cem{oBbdG~uU3T55Ez(d<|3gP;(R55Y|Ifz%j>%Q)it9xYh_F>%XixUA+{{KST> z?|0Ip<`SYom-}!F^)M8|Jj!uDRU_sZ&a{4kYuL}S?^t=_SFkaLS;l#5W@FyX7$c3P zwdw|H1@F#7*)_LcraQ#S_+?`QN&## zZl%fgs1ao4Qj6@1MpB`Gr|-_{HGLV6WnNG-!Kg?`oKbTeKWs$B9@;cZFX%^O4cGuV3X zZDd}vRjCYoAliKJTf*>fhC8I@t-<}63(T-`wPdD4Iy#vaPXybj3f3s-5F{(PrlZmD zirxgTX_ThD{;#2Q4|*5DRJ+HL$fYv3V9xv-s@ik4bk5Q`X3e6lh6dG_-6HtSxTu_0 z|3SouzQZad^GbOj6aeKu@I}Y4c2{ja3k%z0H!nm+SlXoa=9!9Nsnu%jV9G6%p(IwA z32`xH!P;9pExH7lDxpJ~7saR7XDXLxM$Rj#>At!O!Pa4nt6s<{()6@o zrYwvUd6Zd@bJfd(E$-7SzCrBHx)I+Jz_3!w){SvArNvs%)f);Fo}G&O;k$(i@e|@3 zD_-->bq@1yT<8C}<@f(ajQQ_n$bWJQix}8inArc{`hLpl_6kNQpP%Cg#0*6~z(_bh zEqE~z`7nQ?+W_Yfuz=h8LDmyk#Kon=?fbX*r!d4Q)KBv%mKsBMgya?$%v2s!6ig#y z6;~RR(QLIUX^s_jzRWkc&lJE9T=5v$^6>%7E8`t@U3z)FZN06%@!TCrZ>4}&V^qD# z_zI(N9`Xa>Qungoj}&S#r^15-zwYpl!{hit1-hdL=4c0LV8=}8tn`0~;8UcMu(&^yW=6{mk*q?pdC2j``4)kO z*851z59>2(YMZPDGZ!ivNfH4z4E4v^Err8#@(m5=*5St2Ha9mkm8CJdQZOy(>vI(3 z!l2{FlTIf>P~h_=7!r~b?k!nj1666aDXUn?w=E?Gf@||9L{4#5`n@wR7r}QmR2LIN zO>g|vR-^CMbJwt$>4Du=U`9~UxQ42q)G~^eESs|WCVJtZ z7;_9+1iL#^yY$kOlF00*He4CGOLC&AO4^b8?Su}hjf|F8Z~?b-rgn{+lV{C|*rk`) z=rehU6KJ9abFv)+(WsR8}f{z(DWDFCD(>Z5E^Nv*(7{$sK8nI;zL9!PD*3iEa)~Y+ro!2 z^E;GLNCj4CsXY0stlnIc)7DZ_rK6lrhaJLr&lCV3NVGE<*{R9p5tRDm6q_9uv1|92O|M1`)H*DH9f5U1e;sOi;x|L~JG!7O?B8^IY+OU42l%Ho@S z7-IQOkR>EffTjxR8AozOI!bo>U1-`N7Hd^HgOlC(knaVEhN!%swpQZ~RDWO@`Ed*I zlDhR299JFxl@)crX(P#X^@gYgye=eWHDa5wFcGtjVgu7HLr368A{&+ZN>+E0tTK=C1}UkjvDuYpo#6ThR4O<(fLm?aW?H zutbdow++l1fHPR?;UU{Y|O<~idCU*m?{5=gvbsmglO+2Fm=W20b2Bc@qPocAN?!oLcl zW!92ggAe@Fqwe&zfU$-yxl#1r9`F+FV6S{Bd0=hSg9t6Q3u`#rD}g){AfW8WoVQ!z zH{&LrXuLT$dEMcyq##Eikh8?H64>20CKYZg7F5X-VvIQ-6XZ&5Ijj|V{#j!#u2wuT zXytIN9&DA@h`2ClN|G2+y})a1^UIOrC$+#&`EKDbC2jb}TIi$d_X`qvFgT8-}HBaH9O1r7QC%(dDf->w{aY^-y&E^wXA} zzi1AWw<*&Nl(OS!P7B0)v zBaH@B#{W3cRKPzgx!fV+~+(%s&LD*>5~5xb)n!YW@>)Y_03sZD$ZqfaGoBInQ|T?YA*rFz6-{hD4an`vQeI0%{|8Si_eN z)l1oKmh&v7rl%>V6bcRS2x(A14QGE0 zmYc~`pORsEA5ZXxzyiwMtfmp)Ck}E)`f4z7AAWosqCK#D6`>=GD8GG^h4wat|1t*>qYP}X0Id9mV7O1 z{QFeDw^H|T8jABfnTm#qtjJ@`9&MsqcF&^#wUUF$r?(zY0miPce$k@uwoGxW3`3DY zqf0+I^Tcu~{aX(*2gm%m5`(?dh}@Zhyuse{5Bao%Hvjp`y{%45v8+8l@ys_o}XAY(M_lxRg+2lu_2c5@Qjpi)pUco>79 zcB(=>C98ml*>L&2^oC8f8eoir*tH)k983kPzE??Qg=dZ5KovyvA^(1TU@!@a@!b9g zP)lzU3=Wz-s3_KfucL1A`ZUONUNP<6=OOiMVUj*;$tvCPiuHzy>WTvH2si6rnS~W!ph9cj$ve&at&RisLw;fzK_s01*+t?cihPxgJ__(S zOU6pbM+|NWoYUUQ`9_bAUISy0kz%TGf#VX+s+`;*w&Rl%a-@WEK@Bv zGS!h-6KD(yvud)}gipM%6cYM+_*LAJwrLsh$OC7Eb6Mz6CiZx>Ez5FwvCiUJv=yl} zjRs^sSriUfJp)F6?>cmXZ{Xj!%jBM`Qa*e65czdzS3O<)br&Y^MSF>2N~j_n@zS08 zQDmLkA>$OFWRD8R{tN_P8=%?_OSWJnl&5iN>gHncl0u)Tq{XeCgAm%Nz?i9v9w8cj6Ln(I*|K8 zPjQkUHIUnqKR#8YiwP8;O?E)To+MX;qcrIj8`*W9Yetba>lE$0yt*rCo1Li~61F~W zU|E`Vb&8KSr=!t>9;nh^_y;J?BR~#C5VSdRN_D97FQgXY4pn4Vk3?J{{L6bJVMLO3 zqW(gRg_zt-opeSlK*%a?62dt^&VQy+nTZHXgoj*iCXBW!hbCEOEcS&;sepu*~=!kv!Li5Pee@5(*uH zfh?mQ<0W?x0q~~k+OpvCISr!D0lzHBu{RJUFt_nlw4M!+s0_t z(^mWeyr@vJuSAQQp*B$g8LaB54ECt?JIU0cNFmE96js?F91{&2$U#R(BfD%@;Ve@g z+o^0*v*>cep$ZaaD!y#Yq-YmeY27}jy-^75gsG^LKHgDG$|mn{VHT|z@Q~ihu|ke= z3TRdy507-HmCRO_jQ&0kk(0d~;Ko`0%ja1WYdkO0+gR8mf9-FGa zv0C2p=^Q2^o0&^@V9_RkKupzRV|sM*B+MnQxq$z2&FQR~OZ%=5=cesyzcnDJwy&u;lFyJQw>{w9g6tLWFs1=3s z)WsBi&rFO4NC*$-vU@`!rK%H)BG{rGzQZ%T>StW0<;$xT5|t$(NndY{@+9up%TG61 z-L}ks^VEWg2p0Lxi&u(q3i_(bR+4duWMeZgj5)%!paODQ<1yi3n~>A!246A^cJ*d&sf@4DtV^f? zmb*gWY%})nQQ^#Y@mpwYg`lI%cc;gkf0N{QL>uy%LYD|w8@J(aB`TuAKj-a69slz3 zr3MVq-GI;b_w5h$r?HZKhKk;x8V+pzq5X_Z+qL)|;v|E5rK|Z4B6)**8S->PbOQuH z`06*?)p}-F+RUA7+ueGW@tKbQ$Q3_97)l@$=!!+aFp$wtAfPKuM?Ff=q07-9FgT#- zqDWnivcw)Rf#L51a#T!=7jwZix<*bb4n_M|K<9Ly(~8hVywdhxDNY_pLnkTF!G-@L zMCqIM%#}%6aJRH%buB0tXkHQ&Axvq`DQC3O1%q*PBQfo(8;r|d;z+xB(}9PNdi8z@ ze{)<`eRuQ5TE01yhuMYN>XmT66sLYRqIq`nd@7R9!Do!#_2<^qh^A`5&Lz~=rDJV4 zVlZ}O0ikYG2VnRf$EcYYa58Zq~fG42$~bHBabFplH3h5C@T180wfdPKs)9& zj1T1yzY(mdr(6q9HI5G#f@4k6VC?g7P)GxIIy$-Lo!Nh6nYSRn6h~gTD{noc z6A?Q9_GlReSNs~{D~CA#XAmvV>sjgX4f@!D{nsG+KYP9Z4twVR)$0+{|4;IgZ&jLa z^qr?=Q)M|a^Hxw*aGWIw1#Q;f8xRk8800L#n)!)oyIZ;r;p@v#mv)D1Q=GZx3THdcgR&KuSnU9DxWX_UD&IJ zpoD&MKrL8aNW8q7ceP-_LR2|Xarvhdp;9$np ztFQZgLu{b+hRY6o!5~iMgcVBu$`&{QW8kt^aR_Io{VadSbMNDkO^W>{p*D~3M=UC@ z)$*z;B$St(jjuc#NZ%Js{4mt_Q$Fh3Dbq{EQ;4k7|4W6cm9dL$-fMy*wWTa{{J9!od)Pzse&!BqALsY}UIQ2z+F0-r=|83$eu zV^1AsBRLdq*u6MdU712rgKDOK3#~ia8Xzau7($`O8ImMGAseL!;$)1G+=G3&i`%BB zhx&BFP$Sh2aj(kBka6fW?D02|r;xsKhCZaMNc9@)9|_`E%i{b$NT`PXOAV|4H(Anu zFV+9gZ~K2|i2o-$kCK_Sh9b^a#zvdllTDo4+J2)6nf8hHiX~DaC=9G*4v7gtvan?K zuTir)x3zW0IxI&P5+LMq-UAYD8PJ5qNDwV{`GUkhsQkh)DeT;a=`%NZ;dt+(ED(a% zPLnHb8;Pj&3+9(>UqftPPhaVGYw%t*pxMw{;`n|hNCTjJwlpN#+N3@ZvQpW;r6ChG z8WAg?aJiH@K@#RMcj+N7phrPS#)CwNt_plw65Ha=OazjV4cr8yisHtE8rJFyBiz55r3?ud&_}HaO&)qk#>^)!fVlc{`{Q5;c$Wq=JhH3 zl&g`OKrL&l3s9vUABgm>@vzo!`s+NE2}EcIQ3vJ|?R$h`u4D-1IaBuY{%VCmf%57b z+*8{^K^sRUDJ>5$WLM875EiV-*-%Vzy;(M%r0zLMAmV8u`&WoK@}v{Vy@%VcrM;91ap;j zlG}2pXD^e&L&~c+TV^P_G6mMD_J<7Zd0(N(-Id<9#1kfy1oerDmE`bw;%-eG=OyE% z?Vhpc`k?JwuRIy+Hk7{HG!(fu;Z)nAQxd;MkLGAX#0CXPi|iwN9N}obyL%Amq&L_; z-tRy;nTMyVOaRFY`Vv({sok87g-K=Hjgd4}*PKPJbC~WYWlXNbfm~WQ<|`+I`oo~2 z>6`fGW{2nGQ|LnI`bY%**G#Q)3bnOEvxaN%8pe!@R;A1sfR&^!0iAXt(QZ>pi*zqk z8ftdotq!6N^|d?SUW@S+@XLQ(!~|b`V$qMV+5saC{N1EVg@Ex~d3a26;YoZ#I@Ni! zcg{I*!+b~8y|4FSxjY)cw*JHLw(zT_mwJCk)M84d8U9JV85)T+v+i2bT|C`{iW6m962ss__rZtX5<49>C*K$$FzQq7Z0oY zFbTEVSiX-MBt9V5pm1-ux9L|0pgUs9XOG3ij$cSt#4LXOy;h4oI=Ip7nI(wUs!-!r&mIDm`aU9n%%3V*eSw&TPhxd?$H z#JP3Pffza2UXo}F$w?0z$%N&S)Dwit9#L{9Ge6CKPk7))ie;r^e-KWu09m~+f163D z+axCahhq6~OSuRLl`9REYvKWE1cYn({S<;z1q~BP+vCG5@>;`2zpPD*nVk>6)T~46 zyuMveXk%d`3WTdV_K~C=;cr-C7xUg@dumug~MMlV!QH|QQRJd@-{$N#y@etEO zd496HqCiq6mcP^oRT}GrGo-nTs`aXN8JMPKl|ok5C)RPR z?obm*Crp=w=Yp(z(2dRyeNJex*iIi32`7@+QG^3GxSjczg5g0q0T9)=s`)W`qDQK^ zZZ#lpf57pa^muZB#gYf}l6&^tU8%1R9!zthWoQ_M!Oi%o|5Vj2d;V>C z&`O$)O!h}aO^zAcvhV1?FMRsf6BHOM5)_58za+NOG&uo3Z`)5nG2k$(f6&E;*=*9{pEJ)rl~b86;7w zcn7MUV#3y#N)K0N++(Pp1ps+!yS&g5RR)xtc`W6GUnh=v8y1G@?+)dhfT=gi6A(b* zW}m;;xZfE$*IP*FL&bf-B4`Z(WB)MZKUQbAltCGYaET*V6Dh|Rh%!6X(dImUL4d5x zjkUfqdWEZ$Ec1!G%U#kT?Sgvw`U!6x0esN(Eh-0iM&QoFmTy-A8ln`%<}+kq+zcIOTK5L@V3np?zD^=s`VR_+e&91}@J#l-fGj-$n{6aJFf z@8sQusLvT2)ik=sU!=~3dqoatv%ht#Hwc}xEbeJp&5swJy`Q$doFP2B4WEOZ*4~zB z_#Wuh!Wi|2>#)xcYi=O< zq0PCavpq(DiPW^IR>^Bo%&`0$b2D_+ZC*$qBf))_D0(iARL!(vW$t<}weT|^Z$SqW zsjvA^SMkt}1(K*`2i8N%vRT9wdu&tfx3P$6w_H%{DOx^&A6JjWBA8IU>Y7rZGb+eu6x=lQEM3QJ@!>x4~CR&CAYYrt7S*RIsC>f5_JQaC$mwPzb zHTi>+XTT9)Gc_O)CIvP8Cg(Dka}Hkhk=;aG8A}+L;-=*}9Or6>(%KE~VNeb|0t+}v zht7XB*#o|S{}IwnL_S=~f7krq{>z&G|BoWw{|@P_Z2uRNXodWmDH1RGry)F>gGFA& z>O*|-4C#puQW-vG`yZ2rUxG4(=vJg@4JoxN)NP`omL1n9$O2i}EWW(gx$xWkAzv^A zq0UCj8CIPy(svUlLsM5|KT3=9b#@E=nIH#X5XnhorF1h09Qr?cgS~mpSPJ)QFv-BV z5YQ-LI41tAIz1COxn=GJet4qyOJ%{kuED`K^F#`s2WxK&2IWja5W=Jf_2M}Cx3Mq; z&UjF&Ao-wkYCCJDiw`*Zb@F(T8(8a3auepiZ}Deg*6X&%y^*6 zNrKlc8^;6asu7q%4fO)Y@2t^VHY=lRmA~j#7J+zn>#sAqANo{4-=y2WwVg?8baar^ zQR!8xqXkC!)O^8$q?~BV^q;>r2z%Q4x)Y=VU$OP+e!oZNaJi|b15#!+24*2?(Y`vv z3s7(GR}t?)AIz03+5dXDuFi=@3+EZ`Aa8UC>Rypk@_Tf)a|2PWl|a_lW@P@QwK87~ zv{;4Yc!3>6OK1^D&X&mb`@N$#TBwme2$j98nkp`Tj!maobEguJlPo!|a1LDKuZtE! zQgTS5k!k8GPDfwbsPqXnQSA8~9GY93k-TyGCOw>BoK3a${YbH8l>Ay_!#UShtkB-0 ziM@^MUcgah-jH&MS&3h?s7Rz0+0I^B3bkaN;R*t_-c4TvBbY)7@gFi~=vyOM|B%qU z_%E}O{|;Bce}x&cMmj?ITvRhLaOr`=7bc8m_V;!Vs}bE;E(Bex)kD}a#qhI6tV>)p ztjTvMXlU_gCU%(hj}DA3ge5o$h>m4s$qtEVDWLT*DY96V;y4k;4a^|lOVOoKe-468&xgyMjI#cC*&06bD{4M z@xB?zNpXynS*w3;BiCxO5}PT;%_uXG#eyB1ISdJt8RNh~gIywv!JrK_n*s)-FvPCw zhaoOS^>|En4s41jHI2@|I==^Rjme3(iK-!C(^SKV2^{VjH5dRbjWl~17r$Mm@ zvB#na`+}JI`}tsurQdxLN{y!_{yHZ)DWVJ{;d8n*)rsgKXPTr>;xfQJot@d$;;VgR z0#p(E=x)5+eHv5ig<^bwtmM@xGB$>e@BYseH{>K8HMf`_j)!hmk&BiB9zx*shj59L zNK@TStnHLD<`R+YH`??YM60dg|$Eu-C6&u9=!hxHJ1ma7%3-?d_5z>ji8J`=E z%`7bcjUxKRdzwbJe2F^3J0P@9q~k&(%a|{>>KQ|=5TD0406wFT=L@MgaK~D>4TiGS z8wS-`vCH8sI$+aYz6%P_K}<`FS7;BtDt*T7q}Azzr7e^W(mjw88j;YZeD(>AbH2cA z$pCS?C%51TSPHn{sh?nvoTGfTjtYgiiT0=dqV=cT>`vo5Pa6jb+x0@>=~ai?RJw`u zzScy!+6fP>V8; z{ZrG*n_LZU5d{(;mO9n#n~X!+u`-HGj*u`S5)|u~OBi-K>fSEj+X4N9LNB{`x}IiH zx3Jj(aRJrT^w=A-|Npj7E};B$14`m2S-{P$4Ma8QO1-^j~Tfm z?=dzq8f>D*mkHsHPntr=%K>!d{L=({Da)TJP90k^p}j;p#3PpOIA{v-tQZkA60|l^ zZ&d!MIASwkmKfu!ozFF^PCsq=ZK*f2Tw|%l!lnaWBB?`g;5&R4om@X7)z;emA8v%A}b~4CZ`91SAHC>i4DyR3s^2f#@>Iz zmBKr|B3gmfi^z{Vn*F|hjp66Oz;&uBu5_h+(YX}wJNK2_pbRZ6g`+&G=B{}9Ftm~L z?z(B75a-W^4Tnke-T>`uETx>aPOj3ME~EC1Jc>uxU<5S7Q`LYu`#%FbF9^H@LQh-8r+`8=JF`H>dVm2*Z zI04u~4m^vNKC~02nAW*26Q#Ufn`WN~qDG}Jywo&i+gwJ!aFw4w7KNAa81KWHNSUNyl}_*;#6*O z@`N5r8zsx$UjPe7H&lQIG5fMW<8-mT%GbLyFu`k+{A-%Fpu7p?T0E z+eIR~dYxav2pR{OUA?_s)ylSngecnxYdm}RypRqSxnJw^)>t0ScpA+T0E?Y;u@aE^ z#bEbQ%Nk{_d9F+@*>JDykTNMXh5-B{jrt=8Mms4Ve%rfnZSaru1MlMvX^PklGr{2U zwNVo^D}X-)>sH_+jBq}>1BFJLfY7EIrIs9FWWh${=IFM4OqXQ3hgbc2f};0&NerEr7Cv;2~?vVJRXZX|*kI zQ^1fW@`sIJiTv-?_822sLn|i%n(@oaUo;>0A}=WzS)s>2GVw8`ZwjULVBr`Xvve47 z4Pm&&+oN{J-k}z)!*ShxI3jo0+K1tr^6rns8@pOVUeq#Ci`kEZ=-0$)G9mN&9{G_T zrSu}jRma1wnb~Iq&6lIUb>prDe zrSH7>$0m%1wvuO05*~|a_uBq zuX7?;u15*r3F!`Mv2Tgz=pioJm2O7y%2af9SN&jvjSBl}HXlLajURIQ6nrK!h$A22 z-LH-M+CWuIUtzRMa5vl*subUkT<$viC&t^hkh_KPJImli{@13+f5v$KcbX#qqF(T? zna2NYiYQuGVF~{7Ty(UZTp;Ps3DD)A&SWy`&D<;&#X`quHdztv6AL;n6k2RbJq3c3b}0-ui)-& zr7*s$4z^XI(u0E{yRLZM5o)rYkuz0h+fuaM355cW%&8F54G(n-wTN8KkPrPT^l4+` zR;6FQMEP)<2$*}i&jrkmtvP@j{z=zz3cyPyG)|U^5(YYeb ztB4Qe6^f-^t!?P)O>jjhvqXCZSLw=hV%3C?Nw(9#eVdU#}umLwKqZP2s66w z*(JA8GWDu&l3NDpQ{zM-KiNpGS&CHOy?IF%_MmU0WVg`FgIekeQw8(V@1{9|MYSQA z)g~tSsz?wba26Er2*#L{V>d-yLL-WHp=bw?r?l#<}VCtG? zg|m?E%j>|4HG4=Gg7t3BlHq||`)O?X`udnDQ{bd(@+9eRa`JJXtVAWMHr|B?i&6x< zMfDy-VD&%5<53D1Big4vM(RFx_oy1cctk1PWFno=X0^3qVo~U&R|Sw3Gwc?SA?o_e z?$Q$z*E`3KloLkrpnZ#9;CN>nUU^$t+hS1jti5C<`fv9Wrtq}>Ixe|X)X6?9Fs?!4mLLGmCh)3>h`*(?EX~R#@L<=KH*(lOdAIUxP(1guG>l0)k z3~lX3(@MCP@p9Btl@c7kCD|9RF+@Xr2)KuUFA()(eiIMVf)bLoC!P_-exlS31z+ZW z36w{bD3@&Ib9cl+IUFd`JOJNlyn-1DIWztn2N;1X|BWn&QA_y4Z zO-6!}YsEgKETAG5yapSYs~0vg*!Ozy-<^{AiKD_A*jk6I>A5o0a!ZHEAivFp6cxEigK#8n+{lEJw*J;dnSav zv_M~#h-I@LzK6;`URy8%8<^rtO@&!?XRByzu*PUHHY0JVgvQ9<1e&xe-xEPC>uAw3 z{6{Xz>lECP?e7cYu(15pEUr} zYl>-V0oEd8iNOT*Pv$<;f-gZsNv> zv<00&;suLBRoCAiQCxMz`wUV&F#KR`651N4r!5EJ&59Z9=;}*jvyP{V1cEbhRxYaL z=)K5^W7^n~vFhu_tgU$`iB$R<%+@J7Ji9UER{boR?M0mLk-!Uedup1dmm_toEb3!Xx*xdhE3xQ=tz=BLbtO2W-spOnlXA$VE-_h;7D}awP2d~$mk;R+Xhfq++c-Vh+ zg!H)}bWEP15_6ZVxP>duWS%$B$T0>}Bs)Y{xF<#k@qG8+T+i=Kx6ldn7$@K<6nfu6 z=;Y;7<-TmzqFNY~+%YXvg2FiE2oG^|IKX%m&Q1p8IUueyV&*hr&P)Z(Ujr`;YnLwY z6~))|$$9=1v7{fKv0801G`1bZ%H6cg<0`KQ|+ejGr&`>wEX{o988&u&}( zzp)|z7k%CT_Syfk8~E^af4(AxJ|Ko%{EfuW>A)L1?bvTD|#5 zZG5H1O6~68ub<-ad*h-%yW$?n>JUQfmDFiG?yNlYi;k=ep4oNO46zv8%*>37 z%#8GzSX{Aqli~0O!mF0pIHOYMSfiFH=p(V&%0N?vIWajmRLCNY=QzK71;zP(GWZ8-Hg-h7|srMiPe}!e(f$Nr$;H+5j3$le~ z={>VWX06?XJ=W@gH^FR<>%+&XPm}uLkdyfIh_2x7j)HRtQr%SMt=SRX&r3u?@8V8| zM_4f(Gy4ImyuVWOR@M<(v*>8ufewy;AO#l|8E9+cv;8GM$M-H~jTF>2Hg_^~HogXN zaaSk_)KcS491AyuH^;#k$3f9$B=F3L6=V#MW`j4XCh%>>NkN~|%$VBne3Nk`XQAg7 zIxUuzzQmY_kc83enw)tLy1^RyiO!f{CGWUwjc)|q66mGusmqwQMlX+tUV_4%V(Y=Pd@ZgJG<*YbPS>tkHYCu36- zLz~m+fsx74@hx&a8gC@(NI0;z&DKd`U#ONXtzm;&y(u=RL1Ja0|9RSa4R#p7#-7R+ zczGtAah{Wr=hq_Jni-eG!I6%~dsJ>IYDw$ax#??!J1iXxdWe$KgmmYM-3;zR}Ci_Sk4~~rUM`{aokTo6c$^ne^)uMaZGakJTU61If7x; zk^>?4g6TEtX%N0P>Xzhdk~~i2i;_H!;j5B7PT{}rNQrUAEt>$B(0;{XKQW`j4t@c6> znlZ&cyrNm4RFV^yiMP}`Um9s=I-vI}rz%eIbx_SoCvI(VpThihIki1N5}+PeRXt*4 zMoDE(S;zDOo%Y^Xc-vcOTP9jzyRnF4@*z(yPjum{&~SBC;^??k%w+nU|3?qP<(_gN-2v-5v@=o zH6JUWGDKR!{5As@@s|)toZC0JM#!>9o|IreaeT(2+Frn z?aFx&3D%M}Ce#QPJM<1$MT6Po-vf-|Rfk*v+e6ry)I52SC%_?BjO{^bUp1YDbsPML z0mM1qCqpy%*YD?T?w{Qs&90umX0N}`9uiFlm7Q8#vmRfAy8q;cc-y)A1Esi`1T7HFd*SzUtBY~l% zV6q031o0@V?O=_%J{Q(v0F)eiwaA;go8tYhEewD^1@&Lc3_@$kz1eP7V_@*5^9H8gSJgCo+8PF}K{2ho$fb&KT$mhTf@3XQn?&rph z>~qc@;5lYb_E~zU?pkk1{2FO!tJjOo^M@6yC)C%4!gkT5=`)@Y(R)=L^rr1&?^MRx z4%(#Vb>p4VGmjCf=LvR@Q@Yd6>Y=5e&1N2JhZUuX7F+v8ng7*W?lo*yVSOK5|2?J3 z!FX%uPmUdsY_=iIr=BW&PuR&ejVHoY_QuVNRtQUh${ClaGs|bieI>W8evB>4^py&m zOUI0WwChz@qpCBeW{j3%yS6ifWj|NCBbp_)X0R5NNTy2`9ooi4)>2N(XM9@(;kY*= zYpO;iDw8R!Ycuk)+!g%Q|H0ZjMoIo9>%v{#W!tuGb=kI^W!tuG+qP}nMpu`+?6>BB z&fGaO_r3FB?pTPrtWM?4YnJeREN06yA)ojh=BJbTzaK%4`lHN5>VsKKr1 zOikO@xLfecZ}vKUFa#$^oBW64z%Jk%J-fkiRA4zZps)ux!1%ir{s@PZ_~%dpxNW(J z51@PC_5?-4X8~NXP*nFiV3CBX5QdHouClP58FrnzS}WJks?Vg`{OD$_Ec}XTOz@`< zV4gn~4b=sttviHqbCcoROv?2fSc-!HX%Q6!li4crF0zbVjGR}o3 zY6ju&AR)(HUdVajn5&CU;z14i)A8MzVJyr>u?N&6j3?=oDzWmX*n`{|I$FuU?BTng zWQ{LfBLKc-%T*7Fb;5R6SO&Euo{hQ8{r2uxd4aOWxFZ#|eT{X1q>aeLdUb(#==X`&PN8Q&ylU zVO9Ial@G9I`38&YOQ0sl{j?8zrH5IeT7Tw=BCMY-M&GYdK`D;!c1N&k0dE?UL5@CW zHy%`ZGP#$xqIB)HCC1<;agy{jbklsJ;wVrUkuJ9mf zNvEJ!SpnJFk$3DtCDjp;nuPp-z`9f{GRp1;WN%o2$0nJl>&Z{4is~-~ygh-Bq&uc# z#ma$Hup`M`rR+g64jAQe#av2VAZa&D#BrwCD9409*jhnWD-<&kWb-#;s{CDhJe1K~ zJruJ`xfn9L4z6`Gyf>XjX;#O#)<|uL2@KW2KmDp;J6|ZDXl@R9pRAsUe_l!N0M*@i zEUejn=J?sfB$yl!WCnoQ9Y^88d3QeDfS8F$gDmyuYlsBpgxgboS5lHgC?pgTP7Rl! zEH4d}la~&X5QagKr!-JnRH*Y0=cN2yHd|_%Ye0fhQ5vc^Cnk)9Qc-4FYyg7-L8(zH zrZ6WV93I}JR9L1aDvX7aB0nc142F`WR9TWA5pGS%Drd)m!lPtan4c0Zt#l`E2ZE9j z@KVh~3rf$<hlnKqp_CpP(30$9LQ5w#G#T3|(rP32`ln|c>akTZDLPii<@HSW- zxX@MQKw9`(pu?{&kX)NSAT3ikXd0Vu1KA*=a)-;dMPk)ZL4;)c>}30Z@WXzv2C?eE z!sgx&bd7HEm-8RYd*pAXA7Y4s*emBkDW2xgDO2ls90nMoup1F6cu}LM?Dc?Tym;@^ z1Zjin1?o;j$(UHFXj1_+q!G?xX7N~7Ta9UYwqA&VJ;b!+7mXqQ*N!@ZzM(eG)rzpS0y4?d(u|(N zjR!9Q?l<$Z)xgh8U)D_%ivci3q*1I8YH8-Km0fQE*c5_NEW0q$N&JQZI1*^#!!w!VGll6Gc zO;!>57WqT`<)U)6FU6_;1Nqmyj369YXq1$@pyHlpOW+eJ#t!g7hMs2v)M1@e;S6Ki z_Z{Yg3Pov(IQJLL*JRw(`7u)T=|B}IjpL7d%r*uPA(H{6(M<|Jt2JUaQ-QCyH1nczLh%1 zvs~K$>z~)fSyFqASi6xddvfb${=w=rxlJ_)2Hfya1v z_7snWrJ?PXF0$F8_C)%=b6ALL(P>C`qfYA3&o=d?CULWbzVp=Cxq{v!@s=`1NZ9FK zCo_+tKi*51vxQ_aWwSS`H-j>E4EQMsm_R-lO;$gz8|yx9u{9cuh|_8S=M^_=jYqoy z(GmZilyMSB4%lKBRP&`MDl!K3l=(2zz1`qR>@JOX&9a}e8A$>5$`kNJitx3GzmZ1% zYvOPJsF4=&P8i8Nt*^W}|26StkC+x8h@Suh!PX&OI`DL|EC1t8zTHV{mpriuCYQkp zBp1+mUcD0jC(Yy1;jyn7Zz*5bk}J_f_DK2t3Th3Yo*(rip$hn zj(<#%wpTW&aj@wVj;Ep-f%{P&=+<(P$Fe+tf;4;56imFJrTZwhH=SUvL@);SvKj4f zP`*^XixT}W8BbcXO5W}OqQwiHQ`$Xt1(SB zNvM<==m)Y?sF&7Dz(5sLA{y$`R8;DH?Mru+xhH>6QY!UO=e693$#|m)crydNIaZ$b zQCf&**f?OU+@KoCKOj|=X$DD6)KU&~XKJg%E84>=O}8L8m1|>^XKl+vP1fC>KXgN! z&z6Lb#T$-7@9c5c2b*}Swfl^ijtCp|Bs6Lz)oK<08vpenf@XCH^}JCS8VQ3*%4m^3 z&Tilf{#F@-(-?w7+7qoX&Ksv>p^mJVhzx3~toIkkfjUzcK7hhZtu)GGc_6i{8yfs- zm1ur4Fu3R;bA0{qm`4Rj8D%o?Lp{`ic&zzTH0!0)q#8gKuld_G=N4~_94FE|q>lbF z?7u-HJgaJ|@$f%ZAINRHWEh5PKW&?tj$#TPe$tlq4*e;$qApV-L)Sp3&Ac>HV?0&$scq&nAa(XI0_l(SG20&$ThQE0Iy zk(gG_jwY9MjwS32H&LfGE=H(-PbAQTg9y1v=nt)mU5!{4!Af=Ji4%=L3t=X&YT-84 zPiUo)<~$8?&~m`5+|)Q#46eY5ZshxIkT`g803q0|nbdb+ykbAah@k!-MLTOY#&fCvUs z#_`m|P7|qydjKH?A78&ozq z3pHfa&}(uNfEv&Gg`T_!UxN|s2fK@&?AilyAjLjCx?MB9WD9EDUZg%_5w%0F&FOhv zSvBwykp439_ob(Mp|BA~^J_zaKC+;oE80I?q4yE@P^W~{7^z3~g1l>Hd$Zhf z=k93d(IaGiu~qfRWWj<7xvTHA>up7EG(LvrBMI|zOaWcKWTEQYLx0pW360%Or!Rtq z`PhfROCk_tnEK1yo-1ysP7z}O^}b{gQ8=2(Gq&w&Pu6pqArokJvVw0i>8{UIW_3Gn;DqP>OO$3=4%?uPPkAuxwxw zfCX7D%8acWoR!O_)|Inf9GP02>^7i1FqbJztm8b&A9$j+zn=69aCTpJKX2KEtXUIN zwKB0R`StAux`gEK&t5LgXck6AvN)7p%a0gqG%1ckXWB7eJbh@vRLsdbZl<-)(3c(X z4qnGjW9c%IHB9hILSptIz-3nD7)BS+<#^<1yP2>xgsw9_nw0fvUROIpHv}J}+kQ5; z@b=!bQF^7-I~O}$UX5F>sw1k>G!&KSLBDl8uo*x%3}I0;@qW2o9)@5wJfFR5n^~)3 zT3OEAa!+v|;;x4+3T6ado_WsC%!9G5^0(k$hORs2c2+n^bBgRC6KsmFL^A34ItZMK zIa|l97Gz25m062rGqz~eKf-s4WW16)YS+UYW^Dk^#M<_Hil-^A_9e! zQ6qKKRiBV3SbQ$s&jO(ur3$MR^=Q4(r1$UBBWwXdR6Z%c)16IEIDvg%!i!}+nDR_2 zxNu>^SjhJ=nZmiIZf8+Nu#@ABVsJO|8|4Npm}egjyJqMQ?u}@O&&lUs&E%Q1 z9vqOU-@d6>|GV6f%6|Yw|Buwqzd@tBR6V}hkG{mgr!Kd>HoNCZjgojNE{^AD8`Uxj z8wahS%n}+&nOUOXtXW&etX!_NuevfwOYt>8baVFuMDyeV$-%w&;)BH~^M_PygE4SS zu<>wA3cH8x-eT;AU$|V@YIrS~9G^}yuQG4DdUl?tyGlM^|B(A)-53M2>DBl<0`qd1 z5MEELMdE`~MFQ8`KNWuG@(0Imvqd>1O!dnKPuAB(?)uVOF#&e?Gm@ileG1MS&_S3Q zl1+X&Y;t5Pi=6XSl3%Nf>&ZXv#Srdc7vuk$ujWff@njDiagD;^$>LwL=gq;5Khs^k zi#5N_b~GKJ@S%y2{?c67O%!r9zDGduTt@KW5E zJtwWoSH&j1wVk?*E$RZ?p9T7eGr$NU)WyflL_kU3p&zqcKw@7VC&P>$ttsh;S}?J= znaSOK)_LFrlf0EQTdz^BDO*@6HO!bLB;wGaO2(`x`N$ERKrf}*(x9T@V8+BSHunc> z%!1j#A`91CrNyZV&yj|+l@4=Nns!)W(wW#FmV@OS;i2j7m7ISu?>(&=j9d zOtLYE*F~f*IwWQE z<(;qlkH)kF{gI7?Bgg)fyrer12)=dZWXQ=3;1YM2P4&8%Iv30i7bqoZF#YcY6iY^H z7?`%`N_q*W>t5eU6zw_|Hy%3iRlciFT=(W2;W*Q%N?t70cFWNFT_#VDtcqPnCte*D6&N4&y4NcR}*LG~%0XI$pHkigpwAAkTUj2ZFma97lRC?PG4y_lKoSi z67%a@MZvyuWa$%xj^d5to0KqQ7NyL-6UxsNuo7F1A-e0}-iL~;c8YDwvsJ-IkY%lH z2}9ZoOrH9>)|bHQ{8rD7?>8^*S1=JPCn@LinJ6_DHinASVPq3@=Xl?liivZ6*K@cx zux{ISM>L^bChE45)b45Xa$BMmZ=W5z0QipnOl5G~PlR}zXJs*#N4Pdc@XXncG$svC z(0v#n>$Xk=I$6jdO?kK#5%!$Y91qc9TJ$dCWQ`DL8#D{YI~1oLEH7evaQD$}ZI$1K zL2$Iet}Gk9yGU0!rN~}|DVoxM_A^i#JFJlu@sP1uL~o21P1=XN6^DArddt&F`v#U) zuzb?MU);$lsi6R>yb#^QV>nFbv)`oDF>;CuK4Ib zpDApo63=D5n~1WKJGPoR9T?ZbPD!}JhTfoBf&6_Ky^$xfr+d;3*3{ctk{jWcv>K*7 zUM+teyq?Jmx&N>x&;|=tEh89AXh0E!Pa?}x>Wcma?r9}R&MD9F5~}so25u|Q;tt;+ z0&kgc2%m_QBwRsir)tZ==_@z%<^cv@jm}>vT`vrli&_Pd3``{or>_YRw^fcpR3sf6 zN}LN%f#(c0DC?+=|IJZBl-gHCFj+|nvF(c85X{g4&h-c;{Mkmt%urG__%m=HX!2ev z@d-|!VCXnnPe+rQJ~W;n5%vI6m;Z25o(=+UzZHuiI)?G>hujVOXF>Mvbb{1{V(9IA zJH!mV-}|8#s^&Fz^8tuwq^t;9H2#3Hf};T9y5<|kKO9P4 zW{!-l)6{WNr4b2c(SRz@lLj?YM{PyZnw^k(8fEY&JDbhihCPEYP1|+^;oJKObE&eekhAMq6H> zNj`+aekQzH+2;)Pe5oM@^wcN&AOXE;C+^`H5PVQ1@9N^xgSv60Gz3ls2I4u`(O8eb zzSts@m>yk3$-Np}F-L-d1G!=5gK4jZ#mG(Lr>>8p5zp|R6VASM?meP4b_M_fEou52 zduF+!<_l1=yWzb>e~I%7e>Z~mEaa6Lz4@t2-AiUVFru~&UZ(NeBZ7B}pYmH&WfAv; z=7n#MUS0qyG4}f+{2|9r12KefVDs64t8g-)&5X?&KK?;|~85kB%-@^8u@v~zdpdmK1_FHhAq=U+xpwIL zhYQ+fYIPPVO+?ofkzqoHi+?L_;celM%z3M4e#~^3`SNAy9ydSU?(e~TN7TjzM8)Gc zkTAHJ<%QPxhWM8Fq$gDJF)viDVj9!kl zc34jEy_m$It?9sb1bF|NScUr0amg_deR6*9MQ7U*>{rk@1KxHCqVuMu*YZUkV63r) zCT0^DQq5-_(ws7&GlJ6@hm(_j#+66(?!|Gv_#u#{k_5rmyAJ!^rFL(E+`eoLS6Zd0 zq*B?0D+Ib&6*G!*gF>ba`6tq>Ob&Uy)Vz;m{(9B@nwtY1HY~QwgrZsUC(zCZ790Bu zlG%+~w%BqP2D>-Z+$Iz#v?~QA;=%f&WnlNQST)V z=PWh7=g(cIE1@k>PY9A)j`&1&y`+F)E*AK*@cd#&Y_@%PI=e{S7|UbKH+C18$v+GL zb`j7beG7S6b7D*8x`ABxU{XC%FLUX628a-GD=6vj_1v$l{77k zFOY-?H088j{qI61u91L)SwXZjhErJs@>wHLs!|JY{qGqLg*heKqsEAbNFfsyxHU&` zBq-aQHj9j|PZ&ceq#DSmgwpbi=5KWn?NA@b7Vg}9u@a^7Pa#;nfBbDbb1$sFDt*zZxzk20#M|S;S|fxZ7ur3)8*(+s<7U7uAA)643(r@Zqn&ffVu*-~xp$hKh}0 ziM^2zrrDWe2`Qn0Nb))uA8U0x9A~aQAI#{we2d(72Da-Y93=s%p-fdm5D*cDPf^yG zEN73Tf~+nd-AfM#*FmaR^p~Pam7k+%Hc@tru#*vnUI}`D;Xg*9E@cnQ_^J=pQN0HJ zf!>&D<=`?u&lBSTec{=4zPkBrK3#u)S#I#1jr$ho6fDq}`TVq#N!HibqbOqwIu`p9Vo`Sy#S zR+pJ#_<01j0OC3GY;!MI&5F-SE1ay}Ai4Eo4iqE-DXo#6=IOAuqOiuq@zHvDsfbi? z1X3C;oc1w1x~V^x_UpVTuavDar%7UKWk3EY)X`ycRS!kXG!;yVw`ZtpOjI9-Zr*ih zH+ViyA1#|{K+zl)hznU>af~1kb2hCfAOq@aKy+J%3GmqN9UTQ1{J0_VaQqE6rl{vt zxM!}^s&JAOZgE{n0sC=CRF&CYP;-j;Vy7gC7tN@}Q%aNzePt0I?lDABWTRlV^0FJO zHHySL($!za0Ky9MgB-k`e6$o_658aUX&f)x$$j|d1be1X@ZkQtoUP}cD*st#GLdQIiqRD~mbXJ~qrf?@Opidka&SVz! z-0HNS*W;M6WyL=_y?2W-+J*ayXts2uXK10qKIQDE-k)5~@`Pj>y{etnFLxZPPNp4y(%L22`KUt%9?GwTV8F(b3MNE1E1c(xH*K8O$p-XPB*J{|G&rjM|Q4 zK`Vx-SQjVvaPGY0vCZ}YRca5pnUAu2ond6>f$>RciQVyrhUp{`HC1509=WF;f?i|K zB`|l$#`wx$#*nojP~YKVM1~xUvkC-lQ}!!24iWLpwW2Q-#Nc)~wc6b2<}9mp%hHlFn~1e5O~)2>lJ(W0^l7_|FZm1q1-EG5%l*;I7uQpa-%CjS zBX#-!Y5fx!=?PlhGaAFwkHixK?J*s(L0xu|REOA&w2g^f61Uz}J=;6hku&tC2n9lz zSxFN5^Vzxe2uI`3(R2Fo^-G)651OEU5g#v|#QU<{^&??eaFV|>B6}p2_AGxAaU-Bhjm zn-hu66jC-WZBog>aAw>@#*LPlb8Sk@!{(L73Udws7dNvhGRJd~e!2y6u zHLKp<&_Q_HwbuMZC>6^NLn~1-v79;-we`@HGb`H87jlCU}VlA@ABkz$ ze^2;_d)GA)pV)`t$?-Jr&73*lPGGpUWNNER`Oa-FW`S}#^hUhyP`!Wm(;+(0x0Ffe zkmsO4k;yn3>+0jN$*l>5z!fkfp`fIdz;jk4seD3P8qHgP2Cl)3gS9QIM}u`aGN><; z0T7_)Y)tW>n?6)>lzpnnaQ)pQWPoIPbg~Cp0fE+E8j^AY)cr#HG)rz|PyZB(#j!B> zi|IpP??!9HNiL+k{LEI|BDS#G_@3rY;+=+ju&A(d3|fP$n%`Wek(l|}v|&Bp-2TJ! z!_%agbYUFN#RBp5%AEG$Of@SD*J!72$#?tc9DSNuw35U(hwxVKdS1c)85i>I%`X2;WHR_5S@1v8mFkybDYz&C+K-}u?01;B{ljBptSRB ztwI^CQac7g&9xFchEd+Vpzop5?NL_i!*q^dJ#(^$C0vDbtT_1_iy|&KUOW0EK11T7 zJM`YeW}-Xr&Gh@fsLD-u=2GOT*44EAaP^5fe$f+wxNQn?5uvbt(aJ?`wuZ9V1=Qe5^WRZkyx*>qwQ1%NQdn*4f!+Sf5L9- zs%>&qB>4PgqOvJVDE}rWoBU65vj18v{C{Jj{-=NUzo-NfBrTBSkw-q+(mF{O8db`1 za;ii!(s<+V%x>z;pi$Qe)%=MoPK``ONSOen6lQ3&T4B0;{C7XZzSsn8=bE1K1|4GZ z+ToF*2cCC!ye567c^;=*u5@L966>=05up^q6(khKDHYVD^eKV>es_6CM;^rA>qG#v zKlgbL7!2zd>osNOVAn5tW5TT}7Bna|x{q*#t(6?#qmgidvzP3C z^t58NJG;y@vCW7CT+?!FJ9xF+^5trxM*|A_We@23V&swJSpAEM=-ZE8re#{XP69iY zvqgyxH2tjHSg0HUKJ=xd-@*C#HtxL0Hm@tm?M)Bo@F&G5#s4T$#F1eDZvNZ} z{ZsAir8y0$6daez_pm}psZ(%$Hjg3L3f2RVTInNy+el(HPtD)q6#m)C$VwUmlB=ygG=-xQBY5l*5C!Mh<8f#Rf)&DU(CB6VlX{*7M?wu;4UG1hM~RG z(EflC7IW?x%`7g{>kyfMn}FrE$4&c93hi`*p;$bhJwc|BUb`PaoLUV}l2(malv<5Y zlva%dNG%RkDmKffUVtHts&5T@(^JJ8Rd!!AnUoEsIAXJ@8z4Vmo}=#Z4tWK2+UIT= zB{!sJ<4McS?oUAasSY~RElTK}pP6~_bEL!F4^wBKLdOnAYFqcc64q(6->O;>he^n; z_`AISsvaFu!=E?$5H~6KvPRx9n}fglS?+Hc6jQ&#pQ(SV{;u{PT-yIQ314ON|097x zEb`U4;wYr=sQ=#=xV*FlGC#am6H`Zm`iP}g&(H51;Kq-7NZgb<^}s(W{DXZ**6Y?T zW*539CqX-(QUrSOU9Z8O3I>16gyP>M3%c}_S3l|~Ki2I0^!~ouXN;%4ITg3BvwCUb zn!1OON55Q6dCGcm&_IVcXck_oN1Z%is=$MfjX?8qMqJ^ zBU<<)2j6*&K$c?xt^!ZC?^Ot_{u%Y>$G_jt#Zs&+RdgPvoZ9pyy<4bsxBKX!iA~Xs z`Cu|Xnk{h{~~<0?kSdJbz;W4T&!9=TRynIhBo z{qB}N{|b)nzOAsP0)6`i{?+mHf9`hr&*ZnA_3h2{9RZ^DW=8+mDt`}(qhu#!1Q_6X zgbN{gXW?wCu&|s?i3YV8i1VQ~>oCoKkUToqUXZ+4(7t{9Ij)APvj(5GHkmf&Ho5XR zLgveaEpaY(4%t{4F+9UwVhU^>9iskQ-}z6kccrO_yFub{z8;zqzny*FsQd@6rCf`% z%r>b`izBCobISLr4mK-eD0t!r;s=s-M6gr(-Fb_JCbxQy^3uoc?z?i}bJ-GRGQaK5 zOP{ucGz|*!Ssk(R%uO|(sA3UOzuTlg$86p1hmnNJSKwMT{NtATT4IVj!Hx?FB;F=8 ziYq1~aal`0ZZ$AVrs4;eI1vF1jNNG2X<#5nZo)R;;ET27@@T7kJbP1t>1O7922dMj z3sM=F8h^FA*#5{EMEF__%CGbKkJb3s+e_&`IIGImX8*k$asYcX8zVEr|9wfSR3sgc zm61O9?dOdQ1Fa_~sKZ#2KIgxHDFNziAU1#j1ArNT%v{&4om-tqb)O4D?J(|!d))r)Gil5i>hF=UK}f-fVxLZ}ustCh0u-ou0^oUlfg>5ccjA|-W^FiEAQ^fd<5kxu9h_qmOw zJEH^6hc2XrJyL`^bM=fo-YHjU7L;viY`W<=U6fZXQ~NH=+(5{3h?lzA&ON+;c|`LN z@K!?1phh`1xG~vVKUjiLARL2aSxo#HU>kR~o=U7g5@lYkPMh@FcbE3SP0CCGPa6r= zfWm2^m#U`&uT=InhW@>}A`%cDN!W*x`~dd3;~fq>wZx}n&ibl0g&ZNgwm+r(6I^mT z)k3_Ewg=LwB**Gih-Yh;2_1VksX4?&5o$lP6j?+3=Zt0vga^ezWSn)JBH9Hu+oj!a z+vCo2@uzXkr2(ca0|!lH0d@IZ&yF0$pojynX&HEABZ z$kCUz@dpBlUs7oNtTX~i-`Q-9l>ppaN#ml!b7Xh$AZj|oS|*Uq4!Hi$L*;Td_&ZSl z?y%fZpc9#%@tj1=&7?PxON&7py(_CyrspUp)A$oq-GC24Z=5mDN{iC!B(>JfEHRSq zh3N9R@}c(o#O$3`zvx6-6j~Ru1#`+Y*;8$!q;t;5o5o~`KTa!8WbO91SGq(AoQFm2 zD-sel8>i1o_4;IwZf2D(a-7)`+_^8`0yi&0Y^zI_o*qrJ!-|^1oKls-ik2E5V4MeS zm3pGGnA#e%wFj!{Fd@3oorcttFR`KMCkl1+`f2~jo+3u?GD4Z}As^F&W+;KEw$bVX z;SKba99AD-TGy*~`-kN09-wuO!Hmsjj00ml-4+sB3)Jj#|9$it>73& z`$sm@$Cxa|(=H<}6W%3f2IImelZvDqapv2~e zNTdw+hvg895DQ9-oKh|oJ#r#?B83aoTkb^cuX{}BGSgpyL6`#>&3MpKyvNJ4 ztTaB%f4XL|Z%kXQ?PEF`W+9|UBF^>BJGkvVXEyCC#dqo+hN}B?QP&)OY1VmQ@-7qT=^;kk4G_YdnHg%uqMOr94si08qfq*g z&ozw+pGmOnR6cSym zVsv;Ubv4|g6@sCtrPdMFK?DfIwLy)$dSX0nUYgpueN3u^3XN-Pv3_$+3HqQlyZewa zkZNm9Nm94ZUP8w9lq)`mE}ss8mKdkrNKcrOh)%hdK>5IOTfq(ah8v4uYuG+hABiI# z(eZ)hGM3m71fbz^Duip%D%#A<3Vy`9rnLTyADucPxG(f;OYI!P@(Nro5>Y~eZIyyD<_beOi9 z*?QE?=>cjD;}Ul~NPp0CeLE>;Ns=-6zEZ>xKO2_>=U^u#aT3g|XeY%)Tq$rW?^aN& zVyp)eoZWftAM3G)TGN6Z)T<4>o`2T1hbXv7u9lp%We|EKJf#1Nsy$oLn#CF0C*f+5 zf>92cwZ_J7C&`Y3D*XzW zMZSif*rl~g^Imv@$Yko55!#=vQbOXGmpb7uT*T6d%VXLA%r8*VIyBjai>mrfz_3I$ z+q+Nq5AuutFhfGVUxu{4OuA+(&A=^m43~?HIJWd2;xL8^R}f$}s(%L|n>}eAa;v?q zKcH5KHoyQ1b2(KXVCI?BTNI|?8YCjhl&v{KT)xO3MyNah`LM`b=NCbY_C zZ+e#1|1CC3oZ!xZ}>piKj8!aYT*BqQ}NHB{y)yh-$TGAHEmnP5tNSy z9rgZt;!iQEvzLsuI(}Q=cw<-h6}mA7MiR8sKiHh43EdV!O$!$ zvB*M-vfpE*NT+>5)AASjvq^Xk#lY_F^=)&_gGPiL#w{cbNJwjwN*h9iKbxCr;=~JM zq&XC=WJqmJNE=Rtw#SUuLG5Mi-3P@VWQ$KrJ<8}ZG|A+g6;pT-qXx8JTwGf#POCZW z84ET_n8b?&V+?|I(R%E>x87iH9iDIw*e0%Gdwaujf{iCg7{>3=xlEUdDqmcpV?3P;VK)iFsF$xWS(S1CQfp!9usX`RGTOk1vOrAO)1 z&9C{pn)dV-4CKJb7mYx^o5L14fK-wmOIXQXP$^luDKM}q3O|43>zP7asJ0iCHED>8 zcfrk&UWgwVjt4-%jjEdsXHU79D6pz_7uI!jghlAd5Gzekh`lFpcnpup$f7i9MQNCw zkx40&o45BeV7H|F`H)J z%HLwdxYk*mn!&tT0NPlDls4C#VYvJ(7Zu8P-aNO?_GGq^bs=$xB8`254kb1LMN@=V-7odapu#e#P zF|+Hc(7;iQU4y*p_BgHX7oPE4YjRkdHR;3oIt0BP=b-Ru=JTFanAmO5UIJRb_7Nt; z*+t#Px+5=Q?A|bWV;QX27$dcjR@gNexZT;gh-qVC&Usb1;SSMqXdh-Mg-PcWf8b$H z!BsNsfL9?|XV+5>i`@KJ(iVLAE3hJ6>hO;Y;TC{O<#sxX=(Akhtq8sN;NOJs3zB!bFl%H zQn+lWFPm-81d0|z+Y`4B71d7#wJ6!*1|(5Cn4$68t%PITMMG&T^h)e76nPusJIf}` zo5r&++5yRzs)Ng!!6p$;y-@p(@5s3p!B%;ZT^YusL=81ZhzWJd-7sp=E4BalepE4| z`S65Mnq!WjfFuBei`xW2XP!z7vYhucA={z#N+jg2$>pgEWgczeBD80Qa><~1E%h<% zc4a4v&d|+xd&2%VqY88zs@(cmt4>HuL#18dw=6 zlkS~z5_5v=J-LNNLiWQyTldWEE1-%5GvXUkGkga0{t?kc*U8OAn{_7%CzO`c!=Tj- zrkZpus#Fp&HY;RYRtF3RFqY;^2?1)mh>V5@7%TJFmIwzfaF$f~Kn)qO6OvSviIK~? zfpv3~y(=Qml{P7%?xsR8mg!Cc(hDV$Woe*_>@m7Agu}H!46~pG|Agq@HH)onBd{JI zV94A3T%{zsz)4mv+Z;=cRLc`%H#mhaw@zXR1mF5_)~W9-{lU>SX*C-eVkG9aCiz>i zPDVYIXUnni_gaRXqy}YmaB1T@mw9DwqrqaLzNAPw5zBgzaD&gXLl-BW!Sf$Rw4t!s zez2)>9X>a1sYc&$S0{Z1$4`-la^)Q1!WZ*N*Q!e8xVJ*}rSh6+vHK-W0-lM~N`Oe5 zeX!DsjxP&jG@>fnkZ|SE7|Fdm4c)I53pXeEY_0hcnM7hCfYYlfl*taE#k%N-rdf&d zeU!=Tu?5G*2+L4b`u-?D307D+UlXWev%HbAGFKT8gerG`ixmTwAXMSclpskt+Eg320j~ptMXA#2%3-twjWhg4KIi& z`k&~@Mv`KWCjI$fV1}M7p4!hya zkcMOaOs3D_hmi9gk@pxoewLR@jb?;{8ZSqS++mkn8}lp?5B3p@slO5h&LGlV;(xXdkMC!_KZq)QP^t_yKB z#ZfWmqGfdwNjr6GlGB16=yahQ6szdr2+G;~YU3_`|YIO?9~)*1EEW3rzOit@TX13`(*F zl~y9+$Gk)XZ!IlBtD_Lg4i{BQmrJK` zMT>%AzHSU=Z^8PBp52{cZ_i)7C7$VD0n`^e;p9J6UH-qoe*fWl{d08kUwN9p=V&G* zelQ^OV3b7TjI=DXwc5&4p$``A4=W&>d+irjI6_+)ky50|U)LZb_XXkYiiWW*$Abby<|67*^fC^Vva+H;1gumeamr~Ng+LdXcXT@q?BbYcRAk4 zg56(Z-Nw*QD@Uy(r*0ePC=sTDBeOd0ZrO%Y7PzTjN+n*1s1ahU~u65;yjAXLiJu|naBmy_2Wje z%wy&+Ht~gCGnx2@!jQ~jsKA7~?N5)5Nz(>YN%ZsEkB+wqkE@Qyp3grYb8OxZNl;(S z8nS_9G22LmJJ1QDzifiWM0;?Gck*^%7Ov(z0vrV)E{Y$6P9IOZ`n!Hg;eC7T!@odz z$;0HhzrzwLS@8_QI+T zpf0Xio>!C7-JD;Qib(=6plwh`4QW}{Gow1#6%;X~eYNHn%7UKCM|rMXZux|WYzv0G zsIxoS+bR*o?8{PZyW|k|jUg2f8McW>S@Synn(e*`^Uwg5g@(nMYJ!f!`^n48x@PZb z``grGVs~}-*XdZ?SaMul+2&x_&0Jqu+)Z8b2B}DJF~HiisOcpQRLQv4JFah*HGKtgDo3phf!Mx?#dU)x+Tx;F*QV< z9fG}{t~1vge4u=n2CX3*YE+O34URwhlb~BFwD!D89*%|wHSixP_VI8sGuJKVGo;)b zME0;`V2)%)Z>2y_8I~KYN-*;I6n%Vr((yzNCLGLvl9iCO#U#v+ZSD@v&UG0Mv?-Po zZ}?^`2cvTyVQwD;WXg|-Wu<110|lIoIEY3^LPs4A7n2qtuEe>(NF9=vh?cZY4?cCY zzKi?$(;%*MFq^;lwTM$=^Rn~uFeGj;5rSH3eCytbhRHq*?tgDXLTbzFE8C?18PCAO z%3{y$GBSDy?$O_5Xn3GFuJ3bo908zBb*G( zy07_Shp)u@8@pk`ToeIxTe3;O#*^1dFUB3Gh$ytEk5$*ZWx@O%8T#1`ybE7 zJWf7t%uqJ`%YWeQn&z|JcTnYhQ~hmiZ-zkaftoMA!!M4z^deSZF(!L9n96Oh6e>#D zK2pe*o|qM1mNT&<#CB`j5mS1|4pJH&lA(0VG0%v`Nu){Vm<*tE6uBP_P^wAc5nEb= zf>UtIidmTF%xSsk7gTc3=KgUq`dW#r|6YLnQ??suD2J$r{GGOFM*&o8+_wn2J&|7$ z!=6Ggxqh&Sx-L;ah0&5iQhQvXXp&pdugVkfY(C8`-4}uE9{&IF_6|U{e9QV^+qT`O zZQHhO+qR9{?^K@T$x`=X0-Ck z7!0Sdn&p;+8&2Mb+qE&3q&i@&7G|ZeoiXs#r1FU=Tq&X4xvCzcdY)H(^`3cqifn*( zpDR=(ZDSEegbb8x*^sA$nc#d@>3gMPk)28o0MxrGLaf&#gN4vvHhzJ*Rg zK_wrjL!hNZn4y!`RL*0r_17J4JKmnL?AD~?JNwAjopzMzx~l94tPKg*-LiyvR>yFWWXtQ5D);tuhqsF3Q zx~gKhR8u*WrlS_&FzIYwktMR~LltkeRfg1_qHeOPB6H%ZL#n#rlB{m@En58t(Yzw| zTV$1RwL^i&k;b9>dz9q5GfIb`?-5|XWo?^qU}Z=(oVVPN9jmczL~BTO{~Cs6-6gqg z`1?*t-*Pf3Uj^mNQ8jO@#NWe!wWqW#*HmUq{3SB|ErQlrgH+qn0h(cHGVij(`dgFD zQmls5w)L!{g!8;Z^1SJcvVQVg&Z=rVw4~#&TY-Py>VaSt$!*<5MXCGyDJ~nnAE{L* zbr`pKTCXI{<=_ql-@K-hN9@m0+5T?2<;Bfv#jLVLT<@!&86`WcUjVo~{FY!*^Z2y{ z{?YO&FiHV9g&_P5=bgdC0`ZbSoFX01$l$pKqkGFUTn@#yP;Nd&j&FA+?_|^l*>TW4 ziBAIW==$tp>M^u)PLH^sh+YZ$F~uvoXQ*xwU-8wv+Hu&u$}6N#jIS(u6TQyT{=G|e z#;3HFoL>#gqSLyor|yP~Upa1G@5*I?o%!goU6aMD)&D@NM9^%u^m|3qN6~qrs}3#M6a0BF0QUGVen(s3dpXB#gx|D`=XW1htKf( zj^v8&>Fv}L0;dkKr_=?TDHRXOcZH7Zc1fBuzmQA)8o?hl&Sc#()hSBMebwfXolzWd z`)~|LDw}k3bPdJ9UR+MT!`(sc{`;4vv}J7qhk}t@Q`!;xp=r=mwrTB(P@vf4qjCuO z;&nN(^lG9v`mkEhs*#pA{IIwtv?VIw6BfbkZ7sa=lA~!x;eo{ zL?s`fd;(b(T^z%38ji7)TtS}k26EY@6#+|3MN#V;mW+-%*RWCUu@$*CvW*4Glp*)= zDikpd#j3@M?VHJ#A5|2InxvkPtCk6x&Av&rjTOn`e=16HK4wy*LtOfhxWVt0ea#~&^f`Y)!htIN8dAWGUSA7b9QH3J6Ja#D?^{Q;{5Eu zwemULqk1GuI3i4AG)HtpQN!*G7(Q|5jzq5Br$@H;a@EJI{73TgM>RaRAmP>(w(o7U zp4a;k-!->I@5_%HiI`j=FRGB{jkQVJQq7psul4MvkeBLp!iSWNmy^kIU7l{eOS5h| zr$u+YL)i*l#NwEHTH2!nuj|(Z?}gN7j$dadCGL8)Q&x{&Ts|Fi+iocxgWh{fM-9lTROoYC-S7t7H)jRA5MxQU|xodXyF>i1dS7daf#qp1X z6?44O9gm2T=J>@)j|`{A9ZFvQH3wa-=DG5A#@Cs4MGqyY&apL56xgI?KYb&1h{tRm zE1n+4l{T)t5+fqyDBsNq$KqAsS9rCz4Q4P?R7_NRmKGCix+uo!}@zNm8CvB#ESxU@2iq zQl4BSo8XeLB-Nms5KMwiVi9j#NFpJ@D$$^kP)TBuWE@38A(25MA+?dWx1EB`dot2LlI)< zDH{h`?~P`R=H1xG2JDU8$JQ>r4Q=>BHs_ zQ)zFYIv#X`e>z2xr1&H=mr76Pp=iZ(MKzldw6J_aGmg;Y>U*S5KE#MBWPhZJ5W>$U zxS!7H^1^fC#F4tDBvfjM<0SFY)Qx;2w0w~&YSMAv%H`o~nSwaAV+TP$4XOtvQvV1Q zLa1*;t#`*mK{V|^G&&M!ID`#1MiT#lb{tp#qEMxC!JxSZanzP24i$X7YTr^kI?_Qk zf^UGi3o%K}!<)gQwFfa|Cg!+B`TE;bXxbHPFIn(3Uz@0)!72kRZF-G+8sJdlU1_4V zKp(rJx$vF(ctTc)4QL21K4;DPd8L-9$6_}VsE1-VQ};Xh^j{Ur5%(0R{t3-UJaDGw z)q@AxbK6$Quz_NGg2>_kDza3xC%iP2MJ^g6mF+NcDC{tZy0%gLR03$s#OVO`cg^B1 z0GZ~;AD&*oR)*VyL6`;Dqd}OZjOz(d$AN0}O`#}q6?vGJPPm!jmb0Sy8nxD`tY~>S z{{e+M0KhS*uHquq5T}-*J;m+}BJP-6k0_16v=25>#Tu6x-dV$~HKquD*{|AJ+e(up zrv~1Qx|OqNg`58EQMO4Q;EEnn1Aa3m z8fu67dKzUv6QF0D)T5Te7xf!NP(NG^%~^zcfMQZWGD3ZEyscbz=S zwo3u7W;%C&J&GMQ{>~EAZYEeyxuCaFA6qv`94N)3M!d-0*|+G848YFs=xwW-m#BC2 zp%D8-FI|LYxowdPkAMM8TeouYN+!1fEwW4LB2YtNu)btAI(hX%>FqB5y_j1nR0~i; zD>s%CK}~nzh%|@tdR8AurnTu%r;_q{`$OOu)(-MUMFut#VyLM*qF_PP=c5ZaO5^En zfe@NgAf2S%rRPkBES}XO1q4Er9tP|k(@8(ArLIa95Bo~asKo;BHkIja&D~+aJmjto zSe7qKkbT@x&csH{v?ygTipT_pq-Y^Zv7b=nR0<7HlDHxj`BefxHObH9jd8_!lFk%J z0-&(@vGR;NoiQmJiVQFbGXbeLN;c%@NkPvbB>Dkl%2Gu`Op~Va##G50%}ubAXv*AJ zPMZq^u_apy$6Up6<2e<&p&!<4c|s$(HPmIr;rHic#k=EO1I|;_htQ_f(az=3tkwQH z{(f@q56Y$A@2VCDSpNzWzHG%`P24&N~$I$u}Y90ul5cr#x( zUb`)$So~Wkk25@{_xRCX9KEBZ?Jf>qb|;tXRMtRaIs*_1>=}pz#wiwYo=!QaAv3ll_;SYVW50+IqZ+JrDd1KR{OfZC(` zK%$i6D)vtRD54h?&;=5q3g=-|k#Q5rN11ffnsnR#?fCl%t$Ho=%9-l}Izr{Bzq$|D z&?yT6s1<~Gay--uV!S26GEgt4e+OI<-o!&6U4Ys)zyg3t|N6kW#v@E$cMrW+Di1Jy zFS{}96M9&5Wn6%IH%!qnml4{^B!42V`@C71C zJtvu;$dl(cxs%RPEg24sL0NNy8t>xC&YB5-y$#}9+ohgd+f5Rj5?Ed84Kw{cv~x+CHSd zs$|^TbXn-plyAzYGkrI14&czb3Ck>u*lB;mqcig()&157Y$diFq);rtN5&k2&>rAd z&@7_R9`~abD^P?PfIVx%0S$sIjfCEe-UQlP^>`C*4eQG_LB81&!#|y%dbl+j{XDP_ zTo!xPdJ>rs&`m2jq6=wPP4yh$^6Wx>9&$LDl>mF_&871noa>8YSTi}I1LWawP-^Pd zmr7%ET3%QWBMXnrS&3t&&hpP4Pt2}W134pxZYpMc-7pFMj=NQ{_PV_oeucSB*sHlDv%^^^ZTzXW;!+1;ej5)^kAyl24y@-w`h#}rN?p#`=l20 zYgU%H7TDwN+@ft(euLO)fP8&%?L_yF@P%Hu*o8_gN9Y(0Iv*LEAEs?A;Y=0I`=(jt z^k0|5KX0>ZT@Q~^KSi3KkVayo_o8t%1~IuBLYZ8RqbC{U*uGe!IlhV7U9O#STUq7m z(v8Fh)ZeqVIGiq~er4O0ccvh?kT53!tkLg_P~^q%QwE`kjAKaB8j!g}D2%>)F%qGQ zWRsi|B_O+)@^!{=n~|y9W@Rt^nzcWw1%~P^p7BlL^5cpBqH$?8>DM*s$NSsy_Y+<9 zI&`#ihX+)I%2t2%5741ghHt!s{SEK1-*}()0K*{x`~wybMh?A#WLn!G=JVwF7u?JE z-hSCP`u);lL<)VA8aX!`x?9D3*-vBp+G z8~t*#9*sEoA-f@Aw&~fZ!!;an!7ghMxp6!HLuS@Ao43aLMIi7vU2^lyVvXR znBxP%^Ck`!05mItAhOWlofSxArWhhHEn*kLbdY|49Z!Jmkmz{W8zV0G#vFqT zgaCntBUUB1Dm^B28R3}IoXho2Ab{V~Sb>23M3pAsQ)8q4a78V(`c=ZIU37d!qt$Q) zZMuVIHFH4!u1W@fvC-Ct)UGByxly%ezow=`mbllFb@p;PGghN>tq$8`!$R|crPY+x zW_3KbY9slp+U^`Ruz9&gHZvR zOG;a3I>|U3x6;F!iQ^W*^#~&p0fW7D0Maj@9{d@qVmZXnm!92*G8?yj$9$^K^-hPN zOpzF1AU}K^(JN7PeP^;6Gfla)1Hdo)%qMi4v%pT;wsxB*ezkOOz9?fvDR6@w+P&Il z{ZSV1q!FtJ&gfg(vZp{u^q5$cHY4Th^`5C<1~vVJpUouY)NHM6edTi}Yk%?-EO%IN zL06sDtS*Ft-%&WpI;c5d)fug!R`1nn&5B&!BTAx8Hb$5HDyn=a(V4_2!>d@GjymT- zJXM~VU9D8rS-;C$@a6Gw<6M|N_-f?4;%W%rI&V>ES))0h1DxTW$7yv;KAO6Wnmbkr z??pnfK3Mw$=@)W=Q`iHf3?ukxk%MD7&wfw2B|Uc#Fg1c-PcxZMH<~X7Z`&2VZ6!aU zhUm`K*#AHkt|L@;exnk+J@byMqw(qZZo(QZ?>cxqVS{17Qsi2`=Y|M(es#H<0~hOT zZwD^M%V>yGIl?a*gBq#DbjqLK zrn6CDqelS;1}n3?M0;XFa+Fz~;mk~q>mtsrhvjpEQz^<_c^a}mQ-wu`g1jzEQ?H1# z0M?v;H@qc4T>fL3UMJG8LPE2MT{UJeD}xf{>G#r}AVc-V`~uamLiff~&5w4usZt;Z zePp#Jfv4c@#eCrfw&ZXJJ&SP3pIXV{<$~B@<;GSQ5rVlvPPa))tRmDBbvS+ z{P%E=zfo=2o}#wVJSyf!_EG}Kdd3HtXBONiZQPciRP8X|+)_{VEx1QA*JujySKn-- zcwLxYmBsGMV~>?WB(=77$X0H*R_vTMA_8k?we2LvOkZb*(Y9~K%{QO|I{>)3W zmV!Unc8kRwcY7-D6g(+7qw?4_zR#BR;PvF;;bOn171dakTOo4(qkk>)aPOuVXU>r(KbIl=&Nlrystw~^^l@6hv z@8ez}O6|+EWPvOgYP>@V6)D`*r}fpE@D3dj4f3Y+VYsOe+le0-_C6y>cuGX#?rRl^ zcZi37F}OJli70x9@GNamhz_N;g(V>z?C*#th7R%GKsILQ&C(@vJK>pWdFgS4!cc^s zO(3oi%z!=pyhWh;sXzE8O<@?_gsVr6e4Yi#I;56trcucLYJ$CK{WAfoD(%{wPU7ZR zSFx|~O?{96j%vpc-$p1+wWt51h<1wn%f#kjccz>GH=vq3QD9m$uHjqG?FQQcKELtZrSI;~JH%N_%|m~+XFRB@JD$HR)(fOZDd%^sD-z7VvsecIfyI)y zFflT5vv4x`7t)^pvS0tV-Na@!Eoh5hid2c6Q1}hMNn(`l1JGzP00fN4Y_i%wZxfry*Tu`X=4heF?frp1 zF6{i?wsu;~LXl`NASwW8!_&P?4`;I9GPovZzkCV-^$}`M+(AZJvgYQ090$kd<&n7r zgYXm+M@!)DjNEa`9z=)cxO$^1aq9MA2F#qYla+W4?{s&38!fLz0EIa8UbyAs3rNy$*OEJYPIi9)P5+Q;dYFXLpvGJ11~Q+D`u*jDG>rdWTRI=8^t z)&$0xF|aCzTB=&>o+z_}VVgWQ9rsof|3k+mR9a=UVy)4NHRNC_LYub#T+zBDS{f%L zSxys%2wfM4+5nu~yi#Fq3(yl6kZb++<)8_gC$VndUk*1qe1V zWT96qxBO@OP+{>F$|;9KAC(%TmvJO3J8f09)9ezHtJSQg+OrkZGGmql3Bt$?1<}?J z7Av)rM?#6qp3y2>MQwXtm}OTz&!N8#y`1%#m?9+3e^y1uFJK)d8+NmaZw_!Nhol!DX9w^#l#j z`iOD1&--+NB?nC`>fg z_yDVb4Uv~-7i!%uy+Xeul$L`6+_2*d`54&R=VS7?4fepu`4N_yn8=`su05Kjb^d{& z!;kFZ!i?{mkZc!&#v2TNpTpB6$rqz=YxHM7h4BqHpNuX);E}=zbILR6t-yoz<@mN4fuC;r(gf&p{qyje72v_8031;zGF!vQy7zQwboaY~p2<7fs zXZz5U(lZ1-;$qX} z{f}t|-_Gx}&iqNf%OQFC7ow7p=al+L&|6`>EE7`HBdw8^(p;(bS-4ANvp99a?t9O% z(ELt|paa~-+Uoqwt@SQZfx2-8EyIOw0kK|*lWxDR>N=T2I-plfKVm@J6o5Cr%DX=f z-w<|@-JV!mEdBxU%oiS?2r%CurJAsLO8P?B@mROBbMVo561n6j-1(qy0iy|ie5JD^ zRj?bzKs3xAZYcd=U-JPg3&)r}<}-?%gIIW{o%}1D`O+IP&JQT1w(N$W5=nIYCYfPBty%YHHKl|Zf zbUna3Nl~g1r{H@Yq_`=a1Zr%O<(b3+%1D~6Yr-)aF00m)LJ~2M}un>u+M*xh-NpMrj6S}p%?S-TY zhG-d}B%HzjqWjC#e*ThL+Wa=P;IRMB)XM$`ruJWq>VGSw|9fgyv$~bDwhHR!%#`uv z?-`keBAN7f1Uyy~MjvSlLQ)$G3oaUvgr@ietb<ahb!G#C8MI1#m@BSXEFDXd3w> zs1@*A`Sm8@jqhd{b^;0lKby6sRvljkcRKp)a?@o?np|9HCNrFKogO*7cDj2%*qPVZEm_S-S}Uv z!n3U=F9iX>P{~#oMTv529$NjUW5!wMr%l(yr(~qiL zyeV#rH?nN0dXl(2m-ZtwapRADZ!M`Vp1=0mcr3}3WVugbqTSQAy@zH>(S|Rgv%mAX zogCN_-5LsY*JnC)e{3@}Pr$gz@OXZwDx5g-)|E^Z1fB@tUmN|Qc%4rUx(rVoR}d6% zAqR21td3PTwv$`?MPt?I%BZ&{O|A@^&`g-@;z&WqQ>G8MHcm6BVMjeEVxOMra5sr6 zI3F7;OfUi zY9ve7WMu}%llTVP+$#>PLzl@j+jx6Y_YZx5wQNcx+eC4Uqprc9uWI>xD$hq8)H`n> zX6r%lpX5syGm2>nDM`353HYeGIY*E(3)oxvbC@+jWf%|UfWwZDW9I7`bW|ld zy?P*#Q@ZogrenW&Pfc(*@W$P7|Ag9IF9Z`N76F=?S{I2;M&NnLQwFkbk^h7=eRk%W zhUxfuVK(6+_Lhj??p2JUp;M_Ly-;|oyDe)+t!V|DBOh6kDH|8lhFRSg{)iqmO<4~O zN@Y&Uqp75HO}1y6T@Y%Y9tJ|3?s{I;5@I=pXGfjsywahVaFk8Uct?s#UDaO=MJ0=E zYv#3pxr})Ec+2xrl{r=FR`uj)yS;V#U7TdGn->C!gX9v1x<13d)lvW6L5Q|u-=2~x zJXvJ^5<9TZ#B@qxL`^*k1+5095ut*n3N4|ZJaAurua`c(&Q-)Px!7a1=h&pB{=*n{ z1&iHqk33dGyr1Qo2YP1|9;VBBFYNhe2>t;`n1VSIyHyQ3LVK|6 zenoPW8g}3tMWfwz_nYQhBanq=&%;df2Vbm3q19XxAp!9OuBTT3*c&+ReO<)l?qBy_l1Y zM&1naRRw(|kv9tEEJ(4Pou~*5i7#YgHBBtHneVPYmo@?AVS&37BEp*KLSi|Bm<5R+l=Rr8l{ZGuR?8z!|!5^#Ns1^oaPG9Y;xCu z-Xx}$SR+DXK}K`APo~Ufs?S5z2G=+j1lksWXEW6NOz-#cOwJn!xL{yC0AVW#$95Mq zHKOy|ResVDWLQpH2=X|6xAIo%OD>6MYsr z=Xn$*;|@rtqXp(OuSCK&hctK0Yp8`)DXL{~(lztn)<5YUC+H6O)fI%k zYePN4HPzO;Fwx6E;AeKz9YXS%|AA?eLf6NA%gT_8u5|b#2lg&&7@(%$@GiYJ;bOs8 zv3R#wy&;nsjRMV9F^n}t;P&0~P@Xlnr1 zD)2oqAzdMRtiz}oFWX6Y;048!4DpPL`Um|{nYfIht==M@@-#=d$0)rYACS`z1iGTz z8=Tr2T9YSbOSUttceau}zWW;;;Tyd5B>3(Lcr{RFPIQziDv$2;-oVw&^d_ycak5(X zVVJUl+y!LY8@kHNGF$ke*wvi`eW5z_fYiw<`9P^?u%O{pyvX1R{9i%h%t%P02Pwv4 zBnXhC8^CXfIBL;PlQEqj(K@SsL$NwMY{Y?KTH&EWNUF1jLIU91d)JF0orfCHV(Drn&z^gzT63T2*wiGBTvpilL zX~seyjWsMS&NfV{|O2l zN5jqkOL$m#Sy-lzJMlXO77xleHWmv=bm8V;A))Wlc8SlySgr$i)}hdr4a%sLDp7Xp zXFkk~5ufWj{mpAPd3*$Z$V|r-+#PC>8Va7Ptan zPQSqQo@SSPNYvzkGKKPo04s4=wkrb0l#`l@&O8~y+#`(MJQ$h2l=V0+qjn&okt zdCGRWe1BYp=L06!pYE$9KR%A>?+cEV0EWL#383I+&fB*MIxPsWm^yYZGEyDQ@?YEa zrnEQWxQ1VE+1YM5!&S={N=9$-Z|K%Rn#1$xSuOEl?$lvy1zGyDYowNEwRN`@BU^ad zvfWzgV(GaGJX&M-i$*SoE@|LE8##RK%JC=MFrH77TQ_jP@I#(T<9W%&c}EH|GnTL+ z%lYGFk;$9u$8#T79e3|VONPLftyh2@jfZUMcLN06ou5aT1CBs$W?^sn!E^>Gk|i)s zLljR&BRm=LlO(B!;M%c&ZrHh1pF_5+S1e582}U1Zj%XC^+QG9uGuh;VWG5Zec*c*n zK|`CV^nEWl@@{zE=3)CB&Mv zrxr~nv)^JY*JF)xxl_}B@grl*mkPLCRLqBTU|;D zkWu&IshT7{NSI0;zD9vn>CGm~nl>FW-uV1#K5Ieu#6oXeT{@a(yVGMv(s?YN;L)^S%Y$OVTJ0C$eaS_B5&>%>DO15sHkx3WvtavLDEK0b zs`uSjK_d9pBmqdhbfhgpAKL+S2Y-u`@`PJgh|0np*eT>~) zf*7tL@37|%hLJ@89wc<#!83kx*xQsXxs<1w`6vm`_;*>R2su6>>cxlgqvJ0`OH!xM zGDk3(Ki*&;=uBN~bXU{pmrUs&hRmpcD$e*$P>US23vCKdEk$k*SmPHoJ;&62d1WL#poSPi*f+#*8-@@a_MwJArXmU>BZ{lQ5R!>5 zB&5y?7fefoH$ignl=wgq!uVlA(Jdg+54FM|ND)c)UELd&UkC+_SwbF) zT&%0mIUPr6njg-wkSUg{-iPp~N*&IE`$rjXC?52l1qmTl^|*cN(k-Deq9l?oNfOwv zawxHs6KqpE2*pH&o%g?yC;p;&UD^1i##8&ZbfW(WdE)=m_R2rg1Dch!HN5ME5iVkW5(h8nn%rO}4@!_3eu;+d<>JwBG7ZO(z zkIwND;$liO4k?|Wf?b4k{=n!sDk4T3(A03B?6OWQvYTmc>mJ}K@4*(NDU-}K@R)g^ z{88&vNhv*9y{tXTX2o3=o3Xj~*h1%{#2IjXS~CrN!g**#L4Bk9YN)AcprI+{k_ljz z$yviTGxr^Vt6NbjCgLeJeBGQcQc8!!l{!JHYH1#~2~{r_e|H_SIzx;|O`39VH;L#_ ze02Hk5=}3iL)v1|US5F_{-Xpgag(+^-z);N9E$7x3Mj_Jpuc$Y=dfk8rOb)WoeT(*39%nt|1RLt$HFK>qXGN24rH_Agp z47VF69k9)_jdadwMf^x~tQoyXOX6J0U3LF=TVcdAwT z2$n1iBo=bR5esVzzhv}&D2O)EG(tb7r(t*=TgL?h9~U!u6#4UNlT0j0$EPrU3MZxVLgen)#pp?Bun!`4n|_rZUCz#mV{{~WvWQ#OnlvH|~9Yd$;Q3GTy^IeA4? zzc_@KCjw~oqLRN4PGlBoIkRJ#0cqYL?O zr^$a38kKRecK#=G;eUlm|2a8g;^d?T`4NV9R@RqS_?A1}y4%Xo1%!jusWEum&n>i5 zj3-UmNHPobri1YN;7MiSRsvC&N8fuCGwqXg5JuPzNQBoS6spB4KQITPn2_q^u>b zrD90oT<>!*C$l1-J5ig@F{=1f=5{fc3<7#m}D? z)*`H@5A3s&SrxhoOHdzTlLOHvoM&C*nDKwV#l{7D+Ih0vci>Vk)CW{IBw!A}`tm z?Tt!>Sj}5?>{QqGOve`*4OAB`M!y6~k)QLIzquOw6MF8!^075*@Hx6|cgM$Iy{(3u z-)L61Pd#g{s-AqbG_Dx__^i4Wf&)F=#ycWem}n6+W1VvX{gQdbd*Y%geUfhB)|{~e zYq@VRnN@j>U?}GN_T=05-em2T6Ag~%8W?bthdCZA95Q^+7AKlDLk>{HxFg{~ki_mt zbYeO4e`I5jyVT`b%K#ct9Y0x{ZK#WIzAfrCGYv zIltKEYI^`5t|Ns1exEgOSLa5VKYPwFlmz2KFy zK=eT3(ZcBgqma!hTJQ=suI8YhqFfyC9IgGHA)n747A0Tl37IOl;BDBiaQnRhTUT~+ z^nxR=fFMZTJlAv3TLv4DCsYnc$$E0Gw&s#_oJ(8f|1IthnN0H+mwKS=O zpau!N56ygoda#cTwa@iq2%b7Bm!S^K%lHOaU$P_68>S_eK~iGCYlzz8)?w;S`@kA1 zZNz1rF^wORjT}?mv?udE!@Cq=wKrtrH^paKWE=muzAjBo;LcwV_b;+~H2;S8=)WcK zV*g+H_WyL_Rh%uXok$q|f#z)GEm>p%l+TjRi-iVBk;<0HNVF~6c!7HY@KDSlLEdq(^i2dQ@9yplo`hKays zEaB8$dpJq*_|b{Gs)g*}^VK(fd4pHViU(dpCxpn%)?G&W-9so{ILQMUGdh#rVPr@{ zI&G}LQommqFAB_3a@#D8&j)@8GWpky$DDHx>mzsSX%%iKD+W;#S)oZ&R2G1Q zp;&b!fnyJexru!o51E8V2&@DWCsz*uQ!QYU^DbV0Q@_wp3RgZkFQ`+;u0GHOnPOtG z9g{NbL@@)1$CP&z^{q=})!e+-xe3ib01~j^;-vL8tM^&Dyxw6Je~gCVI6my+*f`&= z4>BKaY_C)D$4qJb!Xfn}OkADPg=R#S~YEU!X5b#Oh;MiA2S>~=}d2bHr{*yBsMDrAs85jgvvyT!ZQi&og?!rp$yEI zk3|*Bcm(dj=Fx{}Li=714kYw7PA z%|!OgGg+*UI6L_KvOl^viK2E%l$C8ob6!Px&How2jG# z6^afHqXBA$d#OkrtJe});n)q1$s1`dK9grqGm(Cqd#bX2P|zcLT>&02jFDLq0zg*s z(565_7;uJyJWMx~=zUt;ip8aHLh9Q&>a7_orb#Q&nNr6uT#E{G1@ry7=Mg#O&>TPb zfP7aWHwue0c7xESjF@DFAwCfSl|&VXg&<4T%xQ>nK^_!I+>VJl`$%BN1+_!>nDyVm zN9|t$lh=Ygm0%QM%eR_^ymrs<-crl(LH`lOy`i22J= zB(U+ci`vL?=Yhjou7tx+1ichCUBX77Ho;4gUrlN5M+G_`a1dpEe^bn|nVd-#3m9I42NIh#WIuGkM^Bfwh2=T0*%y?!NfYjA8)j+J}4SoFTqP-8kVItxMj)8%n}Udia>=$a^gB^sR_knV&rj_ zMGom@yF@dCIKj@K)kz`IWWpOB12scN+Ji0)Q^+nh;S1=Dwn^_Tg+ZpWe1xbjB+EZ( zv z^h}uBVRv@A9bXR~fVxOG4Du09ox}VHX&?)d!v*5r$e?P%BhZa{@CP|W zVn2a`20em@9}R-!kQ`GwsF!4{Fr^5d4XjGqq;NH|WNT5vi_O6FYcNX}YyYNr2jZT& zRK@Y7{anNXcmcALaZPeCk?k4E*lI;-DBvEYD2Y3))n^${uqo&h` z8**rewa?-PNxbndQ;&gykEGpAxljuXoAJO!KGK?tsGs_$Zps*B>B`+(Pn>TGX~-Fg_ZbK{NZI<~wyE*b+*=aplVx5u zRo91_+($@diu2jOLvjo$2KSC(v}7J#hHh$ofnIVM9`f4`ZpSsed-|wzZ4J2C1C8b~ z2OBZe+-D$2S75)0$IPky0u1y=yKGfxa5>zgzWJF{tlsH1Jxu32b9cI*{C*y`gIy>5 z)HOh?-D}kC&jk8)#HL&qj9iA+ie&`1o-rz6$}kz_7)cY<8&YscB-_a90A|L4K5R8j zWcG^w7oZN-be7M*9qZM9p~(NAD>TP{04R=sF3`owliyA>0*}&Y>|Gvg0Ka=`!UDTb z+X*z0e8{noC8|CkO_Z%YZfW~)J=I2p{>~TwX(*{6rJ%_?y#BPm-9s@781YoVAvM)p`^6qz`W7oc5)=D~Y!q4U(;T z#g@^`+W_)Bw?U0}o>2Orb>3TG_W+;|RU-=`=n{YNTkX<}Hy>+u#J5DKKZs z?z$^@gM3cBUVmxOkKq?nGl~${q(~9Op3a1*4bG$TxSYr*gOysQC;0LWpB?@D7iHD=Jz|gG{oJK})xRy1#gJe|cHhh7U;VuP&l^92|0`7g z_m^}T17}AI_kViVe}6}GiRG~bWfni63YaZ(kOMsE$^( zYFcRM$%w)s2xDAfb^Q}ya0rVZ_rjO^3E;geu`8f2kmh=x@FRS+!JTR{uoRfE_nc3HB) z%+1<{>WT|uHb{i?QS{RHNmFFt*7em@7TYzqzew}V{li(5AetUU2Es_1QH}}LDMjnI zPw)%qUn@Z={hZyNTt+vgI^I9Xn0!xuLbN3-b#C$fTacR_Y=}_dtbo&;0tDdVAw^;D=>cjIt z+sP?5HivSEv6+~kgmRhjD!k0RwD{R)RJorcaag+&!{f(<-0#4y5W#4s0yYCk>-oBH zDku$bAgXm(oC?QHb&rsL>7DBapb+?5=cM0w{Xgqn;D4`o0W(JvCua*GI~Qx~f7N)g z@`>zsC#O$Z`fSE%noN3#|BJG3j*fiYw(X8>+qRvKZ95g)M#py2v2As1+wRylI>yW1 z`<#34Id8mu?i-_O)TsLJSL0jjn{zJA9e;i3;o&@av}LS#G6)KB{|}qu*1&4#s2-_OBy-pRjBwhmvtk4F z0Hjo-o>6$ZC5FrPZR)fl& zy`ZjvTQx;2rK5*>bco>WWRo*VM8*iJ$Ky&x#-4?&&s~Q#?FhY2l0BQEohaf@`W{g78kQ4xDwwEV4CGZNABE zahXUCtrZG>+&&Npddcga-gX0Rp%ww0(|0DLCu?syLiOYzwo|``GGM0b4m92b@&BIvX)m8i)?j95}W2um~MY8iuP+Fps|u-7~O={Z3_b zjX3c5E~ie|w?hj|C$Z#MvbvPYD80rs7&H_jztUh$1zFzS<9z|qNIdGxvx(?Ad^K{PQyS(Kqr;7_ipK z3=Q%f6o}Y$-ecr>(zyYbc~8uJl+j5>gE@=jG?pJb>?Ntqh-$J3Q)cU8!6wFc1-YKQ zV&`To^*>c6Ng~|>F~S^X#Zkt{&8SS%@DAoE)=AgR40J@x1y;d0{kl!#Wu5_yRg z-wI&$A*L9EQIcW@*@7)W&+;jW+;zVd@P2cxqzJ>CJ+W93qH4-A@a`v`MG1d|iz#)a z8qmp=?od8MsC2_O$J$RRsOXr_ARYZBr|EywfEb{A!bD7C@HrLvN0eDrEuKAmMp*XW zGEwpWeU!=CI#>g&1nle_Y~9SQ0sm!=`(Np;@Q>QYCocv2MW;gzDoiU6y0<7|EFy2k z8ax(UAkiWm8#r|AvI4g*wZ6{w4E@OcOeBot<7@j)xVv14fCNm~3~xI5^l5|3>}cZi z_H>Qh4V1)Mz)%W+nhQhC@TM|hp+GFtR~3S54d;ZF;8D4j9&kjxg$Z+=P2BbjzR2jD zny$N00TF5?(WzZ<813EMHBOK1i8rCb`E^EKW;be8jHi0P{feypy z?Qda(2|943PL?!W%Fpe^DqtN)Dq3dbG{r5+#_1lLKu?HU+WWUP#bh-Z2pm z36BI}10+e0HX4H8aj2Uqw^gB)7~wb+}ieipzsS+ArQ znO=JvMZRz^cKWt&d+1E8F|Tq-M0JRqf=i=*0=F#=utZlkoUX5DzGRh7S9>^;z^u~dKQ zw*LKd-Nf;6ZeSbJMGt}Ud| z$v)5!&Jq6%55keSLEtxiD=m)rg20B5G-&)5UdbHXcjnOlGAcGTL0Xcw>7D8 zUcs|%iB@5K8Zfo7Tp_0h-=!&-=oqj~UgpOr=752jtp?_R<3zEZY$btLt8GZ62}AMY zJ;XtGNHOt3J&4~NOZ)QZE#IT>h%-LyNtTL*TF~;e4POmW_dP<5x|NB`zrXMvWa;NU zG1G;18T`Z?;}dP&h%EQw9E|AtTn4cD=Bq54L7+zJlqm^Pg~@mq#XC6Qp%i%=6avGM zRix-=?Y~e+r*Zeu6e06V=#@?O(fV7|qxH1Lur08y$ZIF=n)^BZAD3iW<9=Pmrw||x z{&!IHZ{^y5r2zkgpMTaN{zCl?s@6)_Dk$I4fS{$If^LX%MXVZvJ4Fi7Xg@v1pmkb} z4B7mE7Mp33Yn&5|*|3Z5uZ1wIlUe-P@ zw9m=^to6#IB@H zSAMP%JG_wI&6GsM0ADSgUV7u7h?|ZqRacry)X6Y`ihO(cTB0VMkT@23 zMfbTQbF>j7la2%wCcZK7+{%WDeFCQG>__xG?40(feMB(s=9*Kc7+Tm*3-r4=f06JR z%HyKlpZQ^QPy??N*3F`Eh@!kpFt9t z%t&Ow82QqSG)RpBxy$3D-5u&%8eD1^Bi%T%Kd2a8>{(^(aX(~UY~{X)mHUEQz6?u3I@lD5)X z-ow&z-(L0DnLI3Ik}-8*uVj7Gt6~dMHghV5tgM5JM|Y8wTAs`;!d9gD(iL{fWK%8H z6yN=$xg;MHhPCzlT7ZO+Gyqr&3O>r1DsmM$)}I#Bo)ni=$gJ9))%_rsNTy0RG|o4m zoIWTSSyCiMI?0rs<>b@tSX1Lj@g3N5`*WIH#n1Tu?Nu~NFFsd#=GJ)i+ll7}02 znX1l^#}To1sI&4ZnNZ#!CukqHV~ZCyU8fE)1nQ=oP?x@JM#PanZeXK)L%!}*iD91) zbtPuFROj7D5^awGzSXTBT3rc!Nbqg9c1w5Y8hW8V-)}eBle$wTq~jIS+5=s2B{+xk z?#YGo?-k;6vT&uifdN)=LRuVP>}07Am}{GvoXX1KUHN@{7^*xYbIUt}&M`NB_}0c5_PSNG{X7so<(TXciiHE?yII6OVOiQG^tTKAKk}dN zDdk7Xr)0$bFBb6sE`bRBe*hyZTRS^r2YF+FgQKm@KeORqiLg*v=MR3s3v7ihY5f&Z zOI_qCwvnRz8{u!{T*4j}!Co;zgS@%(Y1!oqw$*hkWPH}&iTqo()98%xkHD`AgKbh$ z7W08yeB*1Jj#HVAmut(P9Z=rjcJO0>J43EWtrW=0tvjVS7$JdC{8=iKzM}zaR9EHk z(rHXV_(Ib4A(-`%c|4)1G#wO}+V=W>$7)T4NjUnHK$v~&fOOBbxc64j`(|SeQ@8l0 z%=k&mH45nUnsSxZvQw3dB=o!1F&!PvDm$#T`6cN#RpiN}E!p)(Hq9&G;F4{Ki*UA2 zg0S{$xNs78sS(adK|S~=(j4@e9o|K}PJ(F}tWO_%?H)#G{?z{}#a?tOA~h z9JW2<(*VEFD<{d`qB6@4jS6Unk(cuGmF9L+>JmtH_i}AU2N1S;RCd}YbGt_EuzL! zE?j3pqk<*clzGnW_p>_Ed>~70zbG#;eF$RxQtobO$GebTz7Fx6IJlu`5k@=hdN>zg zn&?{qiqb15F(X_r6OKrk`*cw&v|`&RZBRyjv>rok&*~i6DQ6l+qfpfiLdp`xC#}FV zN8$r!UJ#qh7@@(FPt{%^TBVPNhIR!vCZNe$hDo|4xz;3V$4W7XxMSoDstS~URP+m< zK{QE_ygfuTN%FA05Gi_A7mHMTh+|-E>ocLCkb~1Q5Bf_*I*1}!TgYW`_r`? zqI*4H|C4US{Vm=2_P>uRwa=yoTN@=qTZeyB6f>1K9p^+5-s!?8PVN$L1-XBu zO5f$IzTLY#tafy~oL=(3gIs~KLDgJqe9hjquz{VM3e@tA%LS`KZ8qm@YGhzFUU5cd zhpM?M46By*vfe5BX2Tj9aM##v)o`z@ZzI%{=-YwWfAUUYQMy-a6(k&^fMec%ZYj(H$6ym; z{3R^@7?G$()tcp`VHa$D+Me93{MU!vxSQa+z#$`K$Q}h2kg2ZUMBHWhwmf3f8}Wk- ztLix22~aQ$IPXZAVWu!s1$Z9|q-H+LbZz(OYHGtr!%W9VFn!o(x7e$VqbUjUf(bY= zDJIiW-1jnMKgEJo0do0sq3{@zHxMWgZmJP=MabWdi4~^`<6nYi^sh9{PZV~_Jq27i zCO@2BP8xBfpiSjjwl&nhVy^R;v!bcmkM&zaZyHSW;;tcG$$FV#mOHaO?B$cx#3mjF zGhMX8Yp#yUfnMM+Z+IY_hUVXpG5TQ-MP85YN?-*h%$!hmeaMqBDY77p$bh9USy6@# z3C|BwU*$@;b(ix@vR>8B z6x>|eXg6FIZDCjG043*V)bL)dZS`&obRG3fwe>OJ?=J0Bb2`WbE&g@xSy;OF&@qr) zlf_ADTH6>i*M+C@Q~JGItm4S9aSQq8?Z>Q$b`R-_MaJsbue`=S)z?tV$J7`j)!+11 znAF@ATnQUu?z3U&>Uk{8aeVqQCYTT8Ug9JAcRCrSZ88Vb{kiG5Om_kRi6 ze>ZU8`Hw;C0I;$AT&6;=_}8a^m8q?Rxs#doUw5ERL@iYBAAY0d4Jzd59|Gw3M9t6x zD$})d%z;G>5+qUIGXnmwL(wju)&16Y`e1`h@XZ?{^wV~?FPmtx@E+6q zB3TtEyW9@j66?*BJ@W%ootgL<;VB;nBeR6Oe3Rj368+!YV1P4A3 zg0mk&ZSB9Jc#qw1Zmwb>mdP#Nrvr+4eqHv=;k}A~g%Wk9*o)D| zV9Ec)*nn@&6snjP>Ns~(Ou&di6{BUPsLAszG!>O4I_jJ9YBTbz)>XaDX?6uI^H%KG zTCass+l`HO6q+k0gPMbhqJ}0FEC#_zV1g5c4JOv!GzNpO6VzmsMnkEr%4!Sb_Sim= zYgj<gkIlcY^hE{{|A=McM1blq zqTqmzFrjXygJFL{WwHPw^syFOHSj6uDJVo?vh0mAv1`PH9B%743U2^0o4GM$Q>h>} z06VQvgUXh7BQinE*dLNiJ;Nik;zjI57U6uS==E?f93mD>LOkv$k#|}1LP?XWDiZ7A zu35$}mw}tFgN~4;@MIb;$yJL?#%C_(OWlok4tCvs9nE`6gre%!V_iyjYUMDRpf$zl zQn{6*@P+n3MH*#EsjTar`9|~2BS?U?@_?zXo)`@xX%QrkG0QHP+W=>^Z%sDA$|f`= zO1dCpW4R%ZHw%#ee3fF=0sc9^>gH3&&tyJIQVROsc*Vp&Au-90o`n(=E*r0b@)j#O za7trYuDaL|noUCJ8MKA1;X-q@Ko0Iz2vX#kig}iUikfN75-h~Xj1aDAK*uG)mR7ti z*4JbFU6g?S3z)WE7xa($Z!}rs8WJxHwZffcq^~lE)o}pqyO1W;f(7t2 zA)q9NaQKiJ{#3eWDWD#LfExUxmB>y*<084aCWXBE^;Ez@a6x^FV?2$In~O0yt%@+w z0hDJ)bJuTT4aUb0KUWg_(gf^)d)Tu|cvoSpHznZsMSb@8`Px0CTTQaY+-Kgp|TeP)zSgFqXseXFfOL(t?-L}__ew*75 zPyz6_wSN4e@0VM?ewKEXeyDCs0S_?kG4MQ()7|*jaegt^VSaMgseVF4J8~slY2jkm zAoQ7d5X|UJ&)9}ybq@5hY!Tu5jvPp#4fVLpfNXsVC63d_YOBTe*6@|lRA%)CXzKF9 zSZTVFE+Pa=t5iTEdMv9aP^`xPZI(~hKw+FVAD|41@@(gK4%2&JI9I8`bzr?n&-NC3n{DM6d+ zt!8&3LDHqJk~&(R+S7egQXDFG<-BMOvfi@rXg5pK+dQ$J|7#00WNVFL3hB&Zb?D$L zj4zAQodrx&bu9M29n8WTjrkHMq_qCS>?j|hD}Vy-rG59_{xWBT^6WCWAaX{`shy8= zA#$+bn>aGY1q7>x>ehL>I|utp%|PVhbMjDqsyUUKc$X3CeRbB^VjwB@deB@k^wN(~ z)CE=pN4bHsves~O6^^LQ#)Kz(54^S43=_h`5UZ*mE_}>|MW=@>FPZz9Q$0LW*uI9a zn@~zZ~=hfxa?zMZVG<7QYJ4J1o?= z>64j!P5T&N`w+2<$HT~ddWmno^fR?#SA2<^k;bGI7y1$~9j>H)WBEJlz;G-!^{BAE zo=afE-D@Lg0alS0=sd9vr;G&&Y(zq~pNYaYFlr;%_58Ld$iYC70bL;lG*c~m2 zmRNFS@tBPWpN*8Fqmkg9xVHatW16FtpOggUm)rP>R5Z2v0v~&9iTbd#4XN@CF?ws+ zSr&RiI{IAmEHs)l-SC#iEk#(69}gI7T1Y^OcRNB7gom<$YdpaR+x?TB{j1NUy4`Mz z{n4;j1c_4CogH!n-ocKNS+M?#Axx3@6-~Wv90fD(7r42)^75c4vKD zi-22DW@L(OTOgmC?2?n6cp4)oLp$_NiaBXsTs>)GlZhjLIkM#j9gg+1$mJj$5oWmM zfZWIufZT-uU3OnK&2pHMXAcYo1+ftWSxt?aO2B!EAQ~G-)k6U3+3XDY~)&y z5^l;a)q|0zWQmBFL}Lhd@%6Sv{D^EuCnWMyV`#f#z4#KaIQ^vaev#8I^au^BG5i#r z5q_sQ$71-_@!hnj<;yk|+G?;r`1by2icRFGb67&gibT2{*ii9N#hdhxVobgld#)^z zuiQNvZdrskKyR-^O53C~0Bp4WF^IbLlWuDD=%t!?*rnfYnYHg|7y5DyewlM7Y_jlM zI#xZNzXp>88D5X_Pm_sY^A73ZJn++y$Na{L{{($ySQTD09Ec zDmn1nK(BG^<`&Zx;MFMgnsJ_#38dGkCFazq1*aZ^SVe}rZsTz=LASRmV0&GIM|^g5 z>2y6l$TONgj4|%adFzrl?NE?ttrRN|t6Na!0kUA_FKA(uW+K}sQ%%{tEtO9tkAmXuak%x31mc+;<%r~o!ItQ-Sr zCv9Q;)}_tjX0?Y7o_*FXKGztM8I?4hGK44bMEU6zB-jf(K&VrMLz1Lp$nD|bj5&cDdZ4iyt7}9Lq?0{u0in+~>d?})W_3e8= z`{}ZzB%qG})76}OGHol)pHX(3j^=vAsr}~+!Z*oi@}Y!tT|c6^GtJ#C`u#Sfr#Tp;q_7>w8XRlhRPuZXGp3AoN<+81HZHo-?W&VRu~0m z&ZJTi^-^i4vH|ttw3;XtK$B*;H&y7{_;UbN;Dbuw0!a~XZD5j4*mVV>8j}_`V^Yr( zYVdCxu*QZ)c#->+?~#jmQpkEFJT9Sl%ncpz$57k)C0!HxF^EqL?E)9^IA2#!lPXm9 zEG5(nE&B;|_;IWRNjy|K^7c25Yt@T{n>0rr zwFde-vGV6xHFvMM=tRk{Vj8J)$7x=fA}n4@BgJa{xfOm_DETj}Xbtc}JCplZ?l4Bs zNhY6BH5lC4G&gEK?jOt_g**?E_)Q7A+dlS*m^&lS&QD11I%8BU8aB708ZMlNu_UPy zRf(GS!WOnha{m(3+RBvJl5!r2zO3BQjTx!l9We6S>@K#$H`J@SrX$`=P8N614@7m| zgUetRW5>2lwmJrW!_)juyz7iy_pYnyL+o|(4&p@5JlC2{L6+N(!TqAd7#`;i3;;PZ z8P;rJL?pIsaZuVJ&K0MIgZUNgh#zE$O~wZ`q^bi3603HqE2GYuv0j0>me-agJy~>x z4H}@h>?+WzrpW7i$=fr;7Y22E$2zvDB1J6Q5(Rp+04M%mohQOU^x;ACv-{ui6c zRJQz6%AB)lTUFErg;GYqFQFx%jtO6p{G~rbRw#^yh0PD^OdD}tW!^;c4)+oILpV~j z&(!C~^<)hrDH3v<%tb2mgY&_KmCyV0GjKOjmT1n_ca(@}6%rMmP@-s3KoV=D@JI_0 zkt%B> zRxP&h7xx6h+tw!0Z9`pKE!yA)<<=pj(V~|@0}Ps#XcY@~xQYWj{*t+9D$C1uW4Aae zylca%CC)-6DwUBU&r>w|Rux_P+alVu$4rzEcAD*%a_CG3Q|`v5$=GH=VM3iEtIO#k zNMY%=1H0<=0?D2qc4jRW>v9_>qZ8ccqE+a>Pc`hh*Ieo>td|8J?3z3koI*dXUb~H8 z}eQc5jW9}KG4B&1?>azqh0+4zmp_%;@g8jzC3?NiatAu`vDjiqtUf|$psKoRe zwSqTm99F8{mo0g;ShyI5bw+Y{n`}o(ValBPBg~)y-)*%&Lv6mYx$RU)u7aS4e3UjmA%u(L4xPn=sB#IYCm3Srz z3nDpAHX@)I$srLcBk5alHRyp`UkINS$ku>#p0-u(#f3>jZ3qC|qMYqbsmGI`kQCs5 zuDX|4V^TF|01JbCR6Jy$x8G*}vw(T5#uD@?HNyR^YVn`DeExaV|CPFvd=Ug)4{Esv!6fE{RMO5scl|qnkl*Dk=I1U^C#AXf`BkngP z0z#5eu{Z>DI&F>{TZFo3R8~szqn?fB<%f;&_6DCw4iz z1lAmz4^yjTwuLn-2?AZ?m!u9pjNW;3yRP-&{#aumpq%+h8 z-Uja6{R#}~n#gopPV0`ThtTxs8#z=@9^CjyzOU)k>jLXkGLnyXyzNqq&%Z6ZNf^S( zM&t1K3aX(Cy(kvj;1U?w;03aeTg*g3#==)5H#}>4Q92u9WTzc;! zd0^HE(98k3!#F4o(s2cJ- zE1OK!Qf+rRi_`$t0pRsd+37tT^hEUY>`wk|&+`9Xar?Kk`_CD`ADeQY6RksC=!2~j zRLCd@A_`ReuLAo`qwtv(eaCD+z7i7hX-oD&eKv%HD{RW#tqX6;gvJ;MhBCIF;v4gr z2Ec6i7QB6*Iy~5z^ZZ;b|FBu@{l(i2QHa|{bjDXpA)E_?6|@PHOQTi2Rl~!eIiQW_ zx9*R;mq;wJ4jQg8;3PiKH>hBc!TQ%E+?1e-wP_w7kp%2n8uhf}%4$y=1+8QOz&C0z zrfIL^s^yFDq=Xi)t+8%RcWU{%6f_Ke=V*;pD%AwxLFplvbA7>_#x_%30+wT1Eui0+ zs|^l?ze&fk6Q$sySd4g-xNc{gQsKc2-K+P~RYy(C#z%7Yq)dx$3N}<)C@B-R)1uW1 z{3=jU+KoZ`phT5<`iW6xnk#k~MO7jJ+Bu2IN6}7dcNxj_sX;%iImd!8Jv+l8v+e`; zDW!n&p|b3=Bv6w%Mpw^tjP`?8V3cmhtZp$#Ias0qzZr|yy%^?Hhvhg#f4}pH z`}1AKVaDOc#>LX5E&tcOD;hY=2V`}>DuT)_0U(JzH@6Z49)S@R-P$69_}$iUlp$DD zB^>9AhQ(8QZXLKA*`tgSxB+1ZTI_2N&n;tock$GsO4@gVF>8aFDUc z+{LdM2KrdYNMQ7|;WKH*e)BT1#*N%pIA3lJHv--K+-UP$rL%0fQR|qE(7Dy(e8!5u zGaqO)X-4<8W9nB9RU(vi#QE$VAP9=&r~;rN9fYnE?WyGfA47vpB0fn=_d0KA?V*)^ z$7An(c7_Qp4%m%N?j-VnON9obgRoJYZ#8DwY8;-cQpiC507HEKIy!rEhG{_l5lh|N z*RfkwGV)C%$zW-OTobbEWRq|yUUCoSgmTB9#7F=PbSBRq29gN}*+@86K_r&(H+Zdh z2%Lq?h5mGf2sZ|kWi6cOc-m}FiaXTt-eqIK2*vOqLelZ~pz-~hU|5s^s5aGPilOU` zKl>1Howg!;KF>JN-@+Ka|5$u6v~qU*9LD&g{vs@>BqSg!^w$r@{{Sx&>RL|7OQ`F_ z8dy?z4Dh?6?KeO)S}qwJ-xSjku(8oG4RKaexC&zh@b(C2#p6WV(>jsjBU=`PLtlalM_92D53Vq5CoxHJ;9lyN#ho^Tg}R*{M}ucxzo&M$Xa7k1 z+PeWNnjR@8S#bNdw?NI#m}KMEZ-elp%D;=9`fylOn3EH8gkgoooXF;_RCnjg3*8f2 zNgfkgXKcei$H!<}bJMj*AA5CXo&k`knWYLcg3i@8X5KA(0<_Epc+&DeE7(z$kozn| z(H+Iq0nx|87Uwd?I};X~QBmd-waQGXOg|?i7I4~{IHerZ48yb+=b2g&Z7){Xel5=| znM2o0rw6VWZ0#QNJO)6Et~0UBHzrQ^oDUgjuFSW@RSmK_wh{DTSCPYhm38HmmKUTm z0+$!$So2ip&0{;1=ABtfl_aT8`C?v9kMMA!kwB$svmrjjV*`behKJ9cGAjQNzns!p z4^a>}aXX0CkJz1GoglCD1qXF%{KxcpQ+J*J!%sfR5+}PBQNBD=XC-V@NX9yku&~RrY&KQgEqZO*WJn*KJ)@VkI*yf1Vb_p>R*;6=HbcABBCSVjPO z@+LBE&WZNJWO^-`=|zcW|Bg8ArIlb86_mfX9Oxh;53i80Ydam_ z3C0#THPS;nmK<;#=@gQNYxp+unChRs+a9S$(d^5P@`_|D`KuYh!nnO~%ep;(i~1M& zt`6vBu1fFv?EuoGjxvL<0BABp?v~oG@-1&|)hjnb%BE?7#{UUO!@{@}WtLW%Wlon$rv{Qup#e?`5w%gOsKa*Mt^be8&3JAHJL$A6oI(J_*65@ zTe&Nn3f^vl_;mx!X4m6-f8F2nt0f6cLPZ?IL_`!0b#wt}y4&Ws9w;f^`$gYdJ5)Y* z1?QHf8~*!)w$N*m-MFGj-y@DOb_5Afig}PKx~#+YUX#=oUYkTSo7Fa7uLQYxt^S_! z9u!qEB1WpP-4aWgo7yvxl6t@GNx1v~3Yrv0L<)wARC6$CWoJ>WEtC}RBkU`BmCqu= zjR;w7#RC3~9H0dRuwmKkh{Z}gOQKpo8U;(pxd;73ER#@@*^AEe%k%33NNP8&5`;Tv z$M?qTyi)~gwA*J8OkRnXY^0B(oVVhuFIfWISt2M?jL}m<1JDeN(fMwOayu+pgJWpW zz;{vu4$seDyd#lpsqskUXx&0zxQ7QVa0c0&G%1}&qwXl30Nk94R~)S^eL@ptoq@Qr zlU*7L6@yZf}dOijvRU|Eq6mOwGCy+C8En`0K;$cTBSK7Ik&{y3@T*AGrS&< z;mqK_9y!3Ui-RED%!t*LN2QVPQr_Dy-oIoSB@9Ac5f_>sleDjXN%U+P2UuWdav(~2 z3AMC5w{N(pKLM;oZ8f7Fw^wCWRpF_rRhO4fEs!$xMxXS(UjH682Yl>k@?Y}GR{my9 zTKvTu#EJ&_G-=2xWeL^fE?oa=Iw?>~HAR(kn$0%RZ&(=g%DwUd`LbMGalM%k!XN9$ zuZd&3e+%1;s@L$-2l8#g)F)=lDrTVAC<-J3FVEUBW!=mfIXeJg>Jc-h6f+?E-L$$* z>B@+?Hk-fGiBtMD!2w|V!eWCDIBgb^w>L#Z#Wrb3cgAZ6B4yhB$R;j){|I7yqdvJ} z*SvQfykK6rf?xXJTFkb1>iPjLwejJy^x=Y2P#w=2uCaixPmdp@y44j0c-g#orgyn- z=Js664AK7BT?51n=4d_ixy`Sn+i|(YKQQK z6wpOsA30!hvbQqAojV41C`Ap|5o?VO?8hf1M$DhNTK;6vP0~P!Zw8CTQzI>hJP$mF z^$+ilPy5`yoIH@<`rinO7>NnV0BoTM2OKHEGQ-E#9vL(rX0oh*eCOIDWJD=Le6bt1E*{B)nXyc5+GP2Q>|GS0Sf z0t5yXT!^mqn|8gbhBiT!q{-_z)A!-Jmu}TGe8kK%PchLb&(c2_3N|WL#ROYhOf1r@ zwsq3b2O^iV5N6Cy6-1bRCRI*3?EDOaWysgUN^9JFxjun>68QaxiOcXHr_H3rf|8Df zT@VWRg6P=dok~Cx+dcX-%o6b~6u%iG=9n9eUo*B&9H}7=C1w-jjGsWDu`q`)XC#62 z(DqK?5r>&cUmjZTb$`ooVxx=m1Yzm%MZ(qzEEY2`G`+TNJ*S1&emnK@k z`F8?~CHdsZUrW7$)Uo4vhOY1lx3~mmoIP~J?ptNEPw!r|O}{;hW);hT7m_v3lrOeh z-<7iJVFRBa2KLoq3U8BUh~OWXTSzH;V?r0q%+37hF0d?S7%vv5L4*pPt=0QOAZ;TY z-m3d#7E*t^Kjc4mIR6i3A>wRk^*P=Ru=$5HYHM!e^p`eTsA8*xErRnsY0p8T8Lhwf z8>)hqC6XDuWTka(J&GjsjhtDJ-~!&ZWD=ySTMNhRQsy;viEYNU%qD|j=1gNrUkQEY zwIjzaHNW5Q0C)pG^dZ>avJnKXGiImbp=`{Cr0eQ zGLqVvjXOhi?mtSYcA8n*+&5+R)p`0ro2^zkdHEHoTtvc3i9Hi%$W%rbCxhe}UbNCq zGtuIDHa0hyc(PYC@R+U?tQpIWCZHYQFin=G!cvbT|twS=F%67lQiy(H*g$p z-MLSh8*-icYy$Uegu%7 zdDisNi0`u0e_%)Nqw{(^F?ftpi^d?XpgLhKB&Pl^0cZ)gR2P)dPmeV+DmA3wcZe8#r>Z5EpwuM zF8l$q_CU5qv1_Ji-{Rm)V`MH4F%`RvEgZ|CdzJ4pc9mh?Ot%*cX~7fbh+*Obif)H0l(M}9^}>w-Iol#T zD$8(W$N?8+4ZmSvpiqzC17tgQ!dg_Uii-L(zEK#;oD4TaBwI(iJ-H6dRMOHLCle-= zX8T4p)`s|&H_apU6q%%}5&;kT%1}iZ8#P80A(hDEORVEjc84`v1>NloYphencTu5v)U7`=BUtp$tkO^Ez3+2h{C{_S z{yVDp&!waPks1GAsNx?|e8WH1#HXhx=&v9srX>++T8INdloRv=L$F36g{DcN77OIT z8}C*isYT;1%PMq*ntl_6kmvV}5gc#zYp<76A)UI&(3r~jy{z%^e!Gj(jfPiT8>mG| zQky|UPrn`RuL5Z^29W8&1wDnqXW7k1P01(AHmhQve+*0~&P}~=JLBqPJLow|JpkvK zmi9aW@2$(oZCpiJyMCY`sB~x~;Hl)w0wHHM1HpsuzX~LDkT(_YWU?Ns^kS2`{(1 zMriiPboPkZ{7xQAM>2n^aE3nKB;qTK#kzfX@l z1IO_&1bJvJYqZ*3j|P{eD)5C=Vu8YSLpkaKP`y@~td&UB*G5gOq;0Fuxd!K%nC5zn z|D@Ztae@_6`F0@N&{rc*?b>SlL2tBp+*^1A^ix`wE$xmXZ-;9FI#6491X$M#ock^D zJ$xAbNw|v;&C*BEiaik0|C&=7f=uu+byjH@fN8&1D`AZz_EqjW;{XD!)Q*Ve0~r&G z*hpawqJzd}7AIeOi%uiSKq8Du;u&+VrlsTN&#g>X9^lgGpVu_c-`0Zu)~fkWk^6rf z#(xt4N#y^yr^SWftWV)==HiR^}X_YM%l^Ei|`Q1+o zywL_U3;of0eRrlOexnFx-GTdj7!KD*Z_^Esv}jov0n43nN~vXpv7xzXbGAV3NoqJ` z^`i;%N6SHLtr8oiZs$3=(yGk&^#rYZ?hQ$wXAM&SGE67Iu_}(dglqmhbdZYRisoTM zto4gxs3Z)wXTK@{(iF>De`OU$e`v5mBm<1jMbbvdK3L~g^4NoP-Ue5FWvGYSdzTkR zl4lI*cZ-4Yswrc^fd&zeR;&(Jb8E>fF!2~DUMAWi5j;%u$X%?Xy^&TaO`6{zXUIs0 zv3&6Zc9}*@_tuK9Bt@;)W8(d7sf@!xQy3f}G)PFvNJSDB=zwOw)L(K5B%FvJ;Uv#r z3K{qvgZHlaXHnPC*6hinQ$@lbCtXtKOOR{PIt4c-sAe%0i^Ye6sfI*NKKpxTA$7KO zolf}%;%*-r{Eo?E9#mvmmq82kVGg?fmZ)SF9 zb|QBE*o%%nR~;P{RVTAD^L?L3cXwf?aCKJlAY=|u+t1eDts0v{HK}l-qr=7)w*T%l z_LYgcOXqV>OZ{I(?f?FQ75V?Uw*8;f^B-lM`KQkAKXcDYwN<-MnX&GWJI^ddFoly4 zc!)!77OPxFe1j~sY?idHlXX_;+MhH|W$!>fv_WH$mo;%ee}2^t6``arFkWBL13ZLx zcs#b?JaQ{o2zjb@rNZ`l54#@pyw6=H9v^=Bt${m0@}M*jV~9Z~ps*{W$QTzvsK?s% zs``A-SpI&nH`2jd^Qkzi0v)v3Fgw{wvU3D#AnpLat9@IMN-r!AF&(ElE^;L0qyAn6 zi!Yrf22w-t)}&8l`?#{7e#!B%bUd5N&fgRNJx=QI+P1_abNU+i+ z!=Qe0mUghX3bUo;QhSCqRE_ZQi;|pDP+cWfJaxUoR2{n|el!t3dG76y2=8+S80AS{ zfn~``(E!WWV(fyNdM{f>1uofF4hT`c4S|-|%~A=~P$h72g&3l)_stq?cz*bS*2oy?&4@@C03(pXTj`ruwm*qp}_lr3zJTJma;#1<*<22N>|() z&_=So-0Xpm61_t$IQ>On7}~IP2L9JT(~6%!Pn_$d?{?JKLUO&(H?Ti`s$a2hC{DrY ztu+mT!DPM&VB`VPQO=H{FYV4k_z8T+9XSm(Pi*V3%J`$e1iMyznkmaC@EV5e+g=u8 z|CUAJZT`6rD*rnM$5icW$Mfjn?Gwu4`Tk>W@0|A7y@5s@P)wtNwVnPFA}Ni3hNMTO z#@k<=55{n0CkMVm$LV4(!B}qvKSz+2mK-5yPR$2F=X@G3mwkR4oo zr?1pAEte=A@>?%Oy+axV=!KA?z1sMosX4-jBiTo6(wqnqghpg>Kl!y*GA@5^m(y+Fq ztW|0WohpGaAP{K-dqmBK;8Mt?bEzNFuG|OzKD;<2M)_z@_dhrD@N8to%Fl2=`akBM zV*fv{$NxwE`S0PrQ3J*&aX;-tAnj!|1r5@C51FZo7=?r|4*oaEHv)uh34bsp{CEbC z1arcKOi#Y{LWGv>x|UX%M@l7Lxf>P|0GhC(s;NSquZ*v0y|L27Id#hCo%*XCsg zLjW0}Lc*rctb$DxP$M*tKNB%>@vC?nn~Lcc?G0Gfk-*xcL6wg0bO@2Ou_ zPU6IFM(V_F`SN^(@CGqo(Y)ucgd@B-{l(!Ece=h1(u;82m!|wuj2VLG1^lA#NAqCz zC&GDTy2lIK+C*P1p4+vY9DIL&|B}tbC`io+K8dSx!o~K0cITnTrw6??fUMUi5ALzt zbL}B2`ILtG=3Lm%km#>#waqYp+Fc&5PaWFLens>s&vsuBpni>a=P|x{nJF9nk@9P| z{q32-e-Zq#@(UPCwv=XCYgV|;!U*J5sDX>Gy8FdWYZl*fW|HNIDJoa_n^Ay3f<$9c z`?q}rEQ$q6D=#O|L^`>bP3WItr3^?l273wf6>HS>@MOgDBJ%b5Bso*-Hq=&tvQ=HH zNLA5*S&mHOVrFxXR6$)N=O2E64y`g%CT`+hPMQq4b3MfNNN$9T9>vv!Y_nEie5lEY z)!DI@wP`w#ciU{|*SI`q)VJ|b&yiXccD_|# zHuh>W;?GM(swjbBl88tg-lvSIJgD^LV!`)}!-$0y2+jnrX$yZ^a!=J}?yOb@#QqeL z##uE>JZa7F(R`0UbfR2jxxAT!P4uDF5RLL^5t+KahJ3Wn{uNaTBtaNI`0M`+HPFHT zaTThCkt5S7D=x-6Z*~1;h92A0xk>Age03$&QmIvL0a6$$p#BVsCBwKDID$Iy6>mJ{9bZ-}g>+$flL>`4GO4jauu)rl zsi&5cJc%)Nh#He+2vTDOTC?vj*%X9;drG`>i5mXW^*SUzfrJYy36mA5LV1o@JaLDk zJz%9-uaBTX4@+B0t9@@pVJd9`)*+~a1q;!>kd)Ks7CKbGCON^iGL17z_Iz-(u|%M7 z6Gn=#dpcLT)!vUJ;j~8QJ0!+C6g=CcFD*!W$W+rMw)30m-hu^6*K%gN*)}wQmsg++ z{X4xB3y+q~IDA(tShJ5@uHzEnPKuH@DDK3xd>&+_R_|~gGAA{ES>z&LG?1R7LVwYM z;x$@oMY=dq-^QXQEhNm>7Tn0VY)UU}mVnMgnIv_11K~LKT@u{eEY$&ph)HQ@%wb@yY|R>7o~0UFWP1I7CvPM$ z&I9&q%Gc$7{i|OT{Cxpmo@E2&z?2Lk#5)4hNSzvQ)>Wbj3>+73T$I)G>SxdE!FE^% z7{0D31X8>srlhrCr_?AQ{jrmyNNCY0)KnJIu#X_tL)+}dMB^wQvR&%CxKXBJ;>gmn zXTqAo4BEp=HlogFXKbxp31D%R}{64O$mUN=ua%cCy1>r zib}XHlIi)X42Y}Q8YAt5z9#hOcQ3UJEX)}Vk#QI-W_$tb8cO3>LCbPxKIel?sCt?= zHJymBKg~#Aq|2x$<1co!W-RV;o|%qeA5_|tFOl;2Yv zUz!|MI5tG8GNH__1WPx~m&A{UmBpBc_zXRQB`s;9>bz#ySYa(w&*wB8t_k|<;P0|KbEm(F8on9D*#bq`?G{d-QxGc(=j~O zR7u=3L}a>pMcQgjLusoYDBWW>{dR$_BxiPs>@n5o0mjC%?3PC0)GoSG75FlzAfRqC z15(@1j=M+)LW-{s9bMN(!xnm>R#uX3MF}2Tsy7E-^=dfoL$)p+m*tTjOQURWo6Rwh z@Re4%Sl7vZz?zvSNDAA<1B1PebF%~t^Ww$V0D`^{EOR{_E-~+#I`&gbWfd62ZlS6>kYYL!L0|ymzD_i<}(_LPUmG&oe0-%iP0%Bkk{_;QR&vgnbxA3 zE7>wcCv&e-(n#4e#3YGI=b29L@JG?~$VFY8f0*`%C7+436iytScmFUFdF5CO?6aUc zh{Se%mlZrd|1g?sUT2dd6}w&rHUD_d#WNi?qFXQqV>iJ3k!Sg1z{m%O_PW`}4`R`P zw8|9CneRt&-=`a2RiD6)bxWjo^X_G%VRLSxb!2TA&*+p`DjhMr)DwG-oyJ&N(q3m` z71j2G)JYA#s7})Ssm#a+MVCK@%fdIGpxg4WM4`2S+uC&QnXRhPiy^F9F`gqoot|Yd zS#k+a*2d(-l)r8bu{kmAmtwR}PmR`-f<4o-dD%^Fn47j)DvOh<23dc@=ZZH?oQTQ6?+nI{mki=`^19tA4PlDxn{iGB|iPycxMBOQZnJB)=mMCzMo7o@|WYXtA|QvBKyp4WqLy>byB zm`#ZO47g9}^BiyM{=Ky``YWjOn=jK7+WVT3Fqcr?i0FQoi8p5G8a2De`Vr-l>&5Yl zyd+F^vJ)@q?p1|MKb%qsmMN^;Ftvv!sW&CKAA_qT3Oxnae(9m^3ENIj5hAiOyDOJs z1*4t>?^-UCodWPM&TQ;k>0!(@d5D`7y>Mt4Tg$1c7|?1bAr+LLl^Eovgt#KP&$?nw z_Q!ZoTH7a>P^>0~dD8&B+HGn>tgGoFxx9V<#IChXyXy1N8_%`*Zm#x^tCfSRQmw(L zeer8 zM-I;d8vG;R92mlZ0W0?1r3ivKhbK9{#?tC0$2%d`59Lz!D{hF70`}+2!IL z+f0DFhR8;t<%aQ6xBSDaT>GOBje0al#(U)THnl17G;ob48f3&2qbA}`Mfp5O+%TP6 z>O-TIJFegJu`iQ8!o@H37$GM*f};A`^wiYqLx0oQ+StC9sA&ssSMb%-z5(H=HN-k5 zkGQ!k%zT>1lB0-C?idIP)Usb{U&OoJcMkXvQT;7fiXh_{ttOZMBJ&hYPp$3II3cX6Z4rJipg?(qeY}_pAzdxaD z9V*-Si>@`jcrA=Xtw3QZb1l3(BT&xb%RiC7f*#trB@7Sw}|N}*ObA;+j8+Ctf?{l{i<(#@nyL;weL2g0{q^|WqSm<3$j1cWtzV^&jUahZ9QG!KUc;e8G1 zIe?-Q_3hz)LElUiOHFwFKCfyyVg<8};YO>F`iuBASQVKmv%J6%qA^?j8=6PD?;y=R zd~g>cyM>gg&~&2JCalG&wIdt&uyCY)ub*hh`g9$NzB$G1^z-R*cZC78s&vF#1nkXm zyg`=!n1K$>tp-Ea0Qw)WJC#TLbCq8P(&q~FxydzYs5W-zduF#a!$8Dk``cTBY>CBR zo*CRFDh>9ma*@(D77MFeW_&CM>eTd`s8#<2ke^-T@Z1SyJ-=0~j~jxCIV^FiUsJ(d|^rvxxMf+zh_<15q`et z%)gA7UX7@u#Ev?4*zBy7D^ThKHJ#YB_Hj-2PLJa3w?=Pdb$%>vOFdy$#nHE@*?n(l z-tl&VyGYb#Yxt2{uboviZD7}sF^D|6Y_!e_sj)RVEo-d6VY^9=E=0$aJTd9lw?k{E zwsFWF_5!Vxl+cH{&ZoJGa`pr3*3~-t1pe_}RJTDok=EyB6@(7fkmCs5jcI#HmI&IsBxwP%rPeKzbSS zCCaV&r8c*?wEFRyn46uEhc7O-;I<(wOCZWZgwa6W6Uoeysg)XFio>Xv#~ znLDH%VRHSBtDuOfqAx0kph7H)X9tul+u9$MU_DalmB@`K+L18i#Z~aNu9Q~?zIDDe z$6%`)ZYsEsEtc-%wC!jPPCL(?QjCWFctX$5T78pxw7N* zS(@|)$Zzm;=&P-;en8rz{+T^@Fe zQ$b~#d}^L-pme0|kk`6ynRC`aM_hCMGhg3<*=mKLHq9i^slAuTp;LB!;I!ho3rb+_ z^j)%fBk}%l)P*GA`;%b8W!6&ULgMA5 zxe53uLOwlua4zA+!lw#iX1xiU-~J6h7+DXwf{@AFpp*q=Sm<^0!(BoGQ?C1u_5b&^&r(_bwCcxxm&1ZJMW#a+8Su4?WTqRLL5(l!|29h%r}m1xC57wu?J~vw3#NjE5wf$e z#7}tx{_v7&I(TCgX&7FKEkm$Tcw;~fxxHG*xx}bXS0kv0kR>XSZdP$kMRnsW>~Zq- zWv_Zu;GGe^f!>nlH|nVOEBzvm6#HGBi%Ni@h4_MO6?cd1P)_xY4CWB zPSaW2#Oj&_^m>gJJ;|K54qLJdiCWwA87Df`c$?mhXxA!wFfut=pJqyt3Ld<5TK!kk za`@VK)qE}S(HV4k?n+%lbsZw%G8-ILbh&(DKE^>6VWr(j-&@7jgiimLbJD4#uIWBW zGYN-w?7ha7rgn@_k5z%+CqlMRky560lzcOcJX3D!i1n0tbiE2Fq9*#%cznVG?oh*fVkgc~`eVxg~lj)M3ZVKs5Dq)fl zI8Bvm5>e%jSBfmMRK)rF#B-6?=Chs|7%Ev|fj#sM=;7`lx_a<(@s~Bqh%P`C!Frfw z>|vF0y?ED`StfIVO4mQC{m!}bl$6C6(&dtw5-Qm@N^rH1s8^JXNv2LrAOcz} z*2$Xkt)sa3D3@KBFB%(^kV^6drn!ME6g=T_flSBY?Jsdbo5z5J!t?W$lq)Z_$US1_ zOV-A%NZU{UND+9joA^)S>sR?3keQc{x{y9M-5!nPVjr{K?6H`2t9;m`-{8-03~gtU zlg(nb2Oq}sLTb^FGoxi86;;(KcaV0F6{0iPS&k`p!V(-?IFW=&2TO^IH%sVwP9_oL%sjo!HBhm05yKL`N;mS3A6uxFzEl~ z!4PvYb#(oNhWv-b{IguGp|j}vKAEx41WeHQwj?3pA8dlnJ{tcMjI4I``_DST@1RKD zK&U9*u~<#?QQKq+N2TTPa(1WlrCMX^T1O+4Wk57LgVU}=8D6v8=?}}c0o!yJ`}iiu z=90sWhXW?s*lHM`P47?NtP9N#=Zn_c1$l-JNCVPyH)Fo4vPWAEbRE}RJp1tJ%a&`| zj>;YPbp=N@xNgdgOOsvg$2XhTuN&ioL_0D4yD_S-;TkVZ9T*b3XJfxL;{6J`EPd4Gkh=2ieTJfWm+Sb@oAS{g5GZ*R$9jkPsMygD zPX9O=M7k#BSlAv4JlpKw-5l5zsJlk%piS*!Xn2uldS*Bj-}wECrvE`d{4PH5(N>Ei zfI+la2P48u5&|n7qOcIe*qZW@ztIT_vV==Ph@IAU`$vB*VFbz#Ba?cc)#2(IVFJrd6O}tW$ zwM7E>T1t_%z-b9@7atuY&GbP@imDbU`Oc=SzQB~Ezeke`E5(1u=tu^_j6A&U(ja8HA4i*hXevsC9VGSx)2juI4 z3wJ_>J~n1*ULriU{7D7V(1lD-D1M0gK^7BPjSED@%D-~@TD$i%5+w_H<@7@WRqk@}vw zAqmouq`k+?5gh(3@g{nAmdy5D{d>r@XT!^sVe*uY>(2%_>eEyzu5pW5I4%x~I zXb@O<0|AZ*-NE_`!@~2p{Qj|0Y&-evW*K`cXkkZaUK07-ujyiUE~GD{C~~;A1sN@J z^e!DJZe~#hgrr7P;uPMT_h@>*v@J+z078*LQW>l(GTJSeWJA*VkX9;|{_M~-tc8*P$78l@F8;&Rn|_A-T1-QDC| z<@_IIQ&;7j6l9s-D^kTJwW;>_XhuS%)?wh(Agx_kE{n9kbrVK=T^EV9TSQ9v;@-{r zheA0!PGACBVNbF5l_rlq5EiAo>Z|v*IDH20N^TiqbXd7-s;O zpB7m6q)lqj{c#VQThgB{W{2QauD>d-voLbbu}@92c{mt6O!WfR-@I4stgSCkxj7qN z3>Lexdvmh`GLR6P@6OM0$yiPK(=p@Ft+_?x(D~&Z@>5L$GYhEmmvOHm&}&iR$qM-)ja87qbCCZtzt|5*Oa1ITdXkCrhFk0+DD}Q!)*zH@%A}BSMX=&rwL0Ir>CoYGxMzq z^z7s!6c0E4yTwePBR=rnFshhfp4rlOXE@rC>FB%fpR_Kivq3__P1vhN+hHtQ*k4Ga zmnf1$1PB61S28>{ykJgz=7QOg3iml7=cY^gv2)G0&Roi0d~5QFxUhQ&UJG%&9Vjor z$hw1M=pPA8xI;EQF}qLd9a7qpyHPb`P{5G+HhoJe!_Eg2yBF@Xu>qod8d^-gV-gsCWb;Y#?3fd2r9=5Do zL|;9O(g7^TBGN>nqw4K+>geNRVf&X&p%G_nxz(M(-a(9QMLQ&)1MfZ?nZH!`P|2 zWc54(kiWSA?wAYsq&~bX^H`^uMLet)d<5G^X9*UuFBF+BwZiN*L$6kvEvd+}WjMb1 z)T}u@108lq9Rrjqf0jbC03Uybr+tqhQR3?3W-(Euz6uLR3*hMmool*&aG_5c?(^=z zrwwfxksg}1(WluZU-f>23B2v3IAlMd`*LuTSY+-4rs=^6s2w#rGaB?(!X|3OriJV@ zpXaKO0zSfxJ(fmAT}m5`b+&B#Xbtc?-$=Ezf%M)WrTBkmo=8)r0j=2ofPNtBjA85L zGwMiZ;12+3shBB7Q@40WY_QV=YnfEfQiVO!IP45%6Lv`!&VQj`+^g66bys>J;vF~u zw=`9{-oa><`XP*h9Sy&AATGc10`({BH5sl>q?dXsP1z1=zzKxU%n!P5A@Owz$eFyM8RwSfX?`dlCN*bKuc$sj>1pPLV8eF14C#myTyhhMwC+Z z5{#4Jr-!y2Yui&Y)^F#dva$WpT##=1*-cKCTBZQ>4=YeJ@jqk;J&)b&B!|(+lkT?T zZ$IpqkQuqgByJ}&+ek9=<4^+a_P~Q^vj_x?a0Di(cDp!n!rgpE%I>tE=u4y0HAE$n zuhEjP{d7XywK1}*Ig5%`WqxplC*65QCMnY;@Bw52puw;$aNY+43b$9* zjLC*;;@KG2DzzZPMgt8r^(Q!KC1H@3Ki;HA3-Y0W!u`*ysE{rnK?y@ns=l4P;asFa;_9WDrlqJfa0m|)YO?_t zCU2#(n-Cc$TFwNMu_4Ux`XNVV;V~r*zBY+5xdErBE)b!L=XtzC zlS3nrEhFBJV;mP{UF4{`73`dZ{j#`zY39;OeoTnpS`;&aw9yyRDk0w|d6mDlS@2Kp z^q`^{Of9JLU~hLA^~U_ER+f=TT0R;(O}DtdsBMWlJV!*XwRj0+a8-wl$>e;V&))i9w2!eG+`lu+SHuAuMR<{Q^3&@x? z#P0?1FjbzKC;dp(8Sru}%PX2ofCKrPHe#o-O4KmxBG zoG|w&78IZ_96XsQ9dj+F<^pziLWjzmR`5_)bT$9)C%+cxQ1fIJ#`GCjSaW21yc}cJ*2tP?bK1O0w<@b!klg@Bdv4g!uFtCwhfNBOoqBcp&sjfvA%d+G z4@Dv(z9RQEaUmQM4aY9=KIU-%&(Z-dU{HN21hMP+aGPuS%bsIfRxYM!mfa zt0Ml+Mvwo@+6?B){n|{t zWWXk^f-TD+gdt+{T4$$8*D{mTxVfRSoI|T8c6pNcj+AU^X)FTyBYoO4V%7DKXTjCu zsmCn(OE7iQwDKD~{{5^EyZbG%EzkIGXZP;hKs8|XC{;ri<|dm`3ZbM)j=K1UauTIR z5@jyUr?S{79_30Dokm|M{Dw7u3+Mi@K9gF15OcqkQx%VXlkJA!7O(D3mp1Nu#E9u9 zSZR~47jmg45=n5+%#fuUiZj729xcbM?fu{E#{+K{_fL^Nr{O66r}EmrcEGT-Gc$Gi z2R+IlYiMVuZei(SXX>e{^2x{ik20Iuq&k{9`gO~_{kq`}$` zsFd~}H+{7TZYGf+zSy>){KUpG)w$Va7JJ1W(D-7C{jjSlGu(pePscA0 zxivKKrRYk}U%zO8k(9mbQutb5^9#`y@TR`d^l4c_5&1+DN9v1fDw?p?l3D+skroN}`^(;Hc!0Pk{4y zOPN+#oZ2oh!ca$Z%0^fhk4V{>9b6;ojQj6gi7j;#clSc0bOMv?cq@CLUSTeF1}qGv zUSECipH2wXK2S=ysE`Dklc%&SP1B4uuDYzWdg^x=ClhY2Ec9Bb@=rUx1oR{FspfRG z6r1R+3egqTnQuG93gQ^P)a6Q=imWd1c8pTK(q+0D*NVFzf-w9jsWqefu8#N=r3Z&~ z*X&FU(iR4tvrlxsfA<#tlCL&2{w;(d&oEEikK5b&^Ya#Pnl1<~tbx-|#<&u7Pd++^ ze8KDL>vFMQyR9-be*qRUy-udj4q{?i?${MLihD6A=6tRTxy2j)VG{Y=rFB z)U8+_L|Uq`SeZq7u6}fVS>k*PO7I0`N!_h=nG@a1{Ehw#|CcW*bh^eR(Md#t0A>!OGC5ZaWdS2xCGDmQ9%kBfKV{ei_cC?xgff)FnRq+$TvQlue%k7%Io#!lC? z>!w7WK6$1G?F-L}e!Va!NIiun|o8@+n2D zw-toE!DZfo??oVANT{c0InF&2y=F3;MUh`j%5 z-@;sI+f!FqH=pc31$XOJJqYx7wcGtw>`L~JIl84NyJ8}eK9$+EWqwS&-Z1mYG5nHa z4DXJw#v-GZ+Ag=viblDR@oJ{y$3pI>N+%wtPw*W3XOH}zD?8ywk%#|TJ2j}ks%JIv zbycd*yDl+7zqIsVjYtp4bFopmOKY?8t%M29sgeQzW&*ZL<%|RE-FT0hb0HljJGG6v z)N2y*gr~fvGqmV;O>D;6mp+>!2rzwb2ehlscrbQAyZk6KU z8*fj*ZHB8&w)|sW-UNLJ0{&5iUKT^|E|HAa}0onyr-~F9Og{n=AC+b@LZZKt&O0_6iBEy+kYM8{e2w}v+ zYPcL2%4jNa^P<^jk|tbgauY?YZ-2&&&i+?{am>8{b^X}mdmcYguuI+2G(VENCz*0K zK{6j-v`;O$vW7;AR17)N3yItX{*|yCch!wBfi&9+rsSXBkX1M>cH59PaHg4c4rpv} zIuA~ zzrw3&Q=`}h^8z5=0!OZ~yo12EDd8VJ#Iv@KyOZDcnInGlW){&`F5-D-p@s8NWH7j` znQg8wUpA-fh8|L4vbwM)M*Ln*oLWjHSiChmG5b)p-?X-G%SggVH%OpJS1mi7^{)sbdQ2GWC9|o*zMpaGybNDR*2rA zx!CzSfPWy_k_ze;4!Os#93wv*Xf*4kPP-^a1a z&e*LiiBTtjOjyP*CYX8f(7u+IX!Jwz#|kOdLSWF*+q%F-2Qnxq_BP+y`bIvAT!(CN zxtnpYaPY`BJpo_+o({&cyt|z*+$Z^*%|8`LbNOEsh6<2HwrZU$0w;sFq#o&d525+x zuOI@4V6wkIlJurPcgb9l^{PX6NnNo87DH!KJaYGPKzB)A(FfWm5{(!4CwWC1sE_stXI` z8JV?@2>M;(iZW0D?KNbp`r9PRYxLITw@IjNBJ^ux!AHu0fKND_eaCx-#q~4M$?rw1 zz$<;ofC;`Vyu2*c(ofY2aLu&ML0ljoHagif08V@3aMGR}JcV*c_0?#|phPPWADUw;+f|RQRnup`GNgLveg^Y6rvo zD>fg>Rr~g&8KIL>6I2`fVo2;)_l`N64br}B!^RrWXzBwpoO%u z^UrWmgz4vSIF1U|g(Q;Bz6oa%Ej1g2_~$CJZk61WU`mgeg_>k5bHZ*UkT{BM^pYYm zuYI2-7*C#HBb?p7&GE)$=m3v23>~5?lJc{aOAk$!v4#zTGYZ+OWOrG&nK!On@yA_! zcI|ZMF-wvgT@3t%?gRQs@B`m^TaC}qmq5J1e6VAo((EVQ&6AI5%>`Y10oDt)mV9Ut z=0?@Xby&V(v?}%MTzKz^vnerT6xZ+wwn{YI9BPdrEYrn-c0@WljZ=H^pjqWP@;lOD zMCJZZf_RMjAocnKvyFZS@A_}=9J>Nlfn>!>q5K88q>Vu-D+gwJ7}K4l>>x3n%kOfy zlSIL+%4{a@O2GR@sWm^+-+5kx3Ukr8=aD0?<<2er6h(E7jRK0RXBrRHjgbL7Y z&{s`46<@9JzSAPY1fqZK9{2%S0E7AsClEbAXiAh(!vBrE*9=AvO86UxL=Do01fz%p z+SjH|m<_sKKRCO%KR8-sYKYBJbRvuhb}0sM4N?wJ2s}R>icN{_3+{ zpqn~7sY4z}SJ9j??93rrJsr8hzH>fr)fKsNKFhha0J^p0@FBct4T@Zf@mHqk-W5rN z!UQwtHs!^97%oD0_--Rq;3|um_oiEvI{nP0nrBJ)MlY+(xvDn-@RSm*NltZ%Y1q4Q z5K@#Coho`kjXruZ(QoKcHNnZs?Z`43KnjRErQ~2988!B4`2yTeFj%U@^@`hOKL!cT zhbaOuS~-{P^&1y9uO8^1pJD{rsFH*reJukwB+uv zy^(vlskVJb<^AoiO*N^wk||-X1T(k<8|Pv45Zb@AG~&@iu6N`h>48`8H>i70J&Uf` z{#fC2h?b?zC!g8j0T!)CIbY4ba@yKrO2t5TtY^9twozg@ZHJyYfKDJV#9f?MC;9#g zMtNV)kbQ@&mMM|MQ9^DMJu8$_AOpykL?pCqvg|O&ak3cpCu8HD?Z+c|NbCKO@-s$> zSKmp^#FD=MIw=|4FL{>ZfQky4kx%KwE58SN7&Lw`) zQr2+0u@0FIj(r{4&r5yjm=2YV^qfQ-Ok0xso!F97jparO}^|t3E)3PAtd61LsO|iIYOZwGlfmy)d*Lw%bm8xZQi*#<1JA z7}+MklKY!!eTWzThYRA~3>{YSRi<=${u6;u#UEC^23nC7tcX0{Vd?86uXK6{t_;I?mXjU)d(M@5m1-ffX@5)ERfU&^s2d-2n~?UOMQLDhZi?{5#8gCjJ5S zPl{_0oQL7}sZE_F`JYl;mVY_d^IuZj|184|XgoRN4`95TxvLqU=Qfg)E0k#Jj6ROi+xn0 zv$7a*uDoe!q35vF$?}_5@1A+PBK>%(C`2uBc`V?#-pgq)jJ#53Vg$>WtCO{!?-OlW zn3|Tu4lBlQ*^dg7uW_RKXZ*yhSAx6*lN((C9cidkZO*w~bJq+4AS@k|1)J^^njMod zdrt<7?sdN5%W656EE70$6%neA;c+I3BMh{LT?lX8-424)@p5w$E6yd4$FD;nXk~V- zD~b>^oRFYyVL|Wqk55#T!ITNiVlmpCGr*LlXf^G~96b&(?&K{k?#tMWx3=qUfRTKS zN~({LBrUwfb6NuCN@v{6V0e|IZ*;uINohF{c(p{*;Y~jKj*)rv=-=m=UrSEal4KD)|#56Z* z_g1=6GGVf4*)-_jW^Md0%HBCfmoVJ&-EG_M-L`Gpwr$(CZQIsv+qP|+x6jPnoO36+ zGdand)c1c?>RYv*_54=p$wJ7a1LpR_zIWE#ttPEcXd~AR7$i??#G1(Xnw9Qf?P-j+ zge=*3W9j{R>pBXJ40~+7iTT!3a#DJJc4j40ihbTk!1T3s< z4g;d{a!2M(DxFy602|Gryf$$iG6m~Zs`<{tNns8nHQsgGWJ(_<1(6Di*BWIQ+9_z0 zMiC8OT_F|5fiPvv(xGH3&NHX9j}qIVmOA(v9FSM6 zR?eK#vxsQK5B!A8dMFP2h_hTgZKg(cdUZXvMZPbGv)5mpp~#PmrLO)Eo~hR9ZOW*w z^wu&nDbeyAfi?K7&`U0P{BI~+4nAVtM^7r!%Hm*^7W%3>tZWQC^n4v)uCYWU2j1b` zWBzmAiQ!{+Lb?WaT=c88dIR&LeO_Z?SRfpU0)b0_mo5r+H$O6c{3M%Ai(E!W3y>ND zo|Wl#hO{+>l&{kJ6yDUxJQ<@lrKRY}kjXWpTuH5OCDEFrEMddAm-rXePQBHq1qrAq z9pz|nH2DZ#f;-sZ(*p?Rq)67fevY<8o5B53e@`VeoO6zI7?v2gPvE;IC zm+9P6-*a?`foiT&pfkee2m+}C2L3#+VqgEI4O=6?!A^|>VvkrRc7Lt{rUF`#rN@KaXc zy9u&gnxIwuki`pE@B|-jBFuCb$*`5Cx=$<#Sn(69+)44QVy+KSMZ7Y*%eLZxCnW z->s_xYG$Yzc@omezAH8l1kI*(1SHFX`udb%OQ8ejg1cc%^QdYk32ph8BnP=17q5;I zMGJQ(5|w`2>c|`D{v&8@(9imbgcJ+a(8L->nT~0;7hNF@jcyJaukAQ2S*{Y%{qkulC zUKG3dyHZ9Kwk!xUfM{r5;%egDFs$l_n}8K+0qN4irEnk@nX^Iuz7WgMGL^Fz;R^FX zGd_llqPMhoT67ttE)!~eJJ{8pie4|o$xu&gx?C}18Trl`(1*FjNWD<&Izwbsyku&W zI*~{skE+8rd|sqD*E!%tZGjfP*1wu$DJY|;`D?@$U?4;*YL10v^(Jt0=qXG(#jn4i z7ZA)Z^XIluNa{prCQz=i=+&f_j$lqNpMq1gBJ^YYIT$AZRcF?mz9leZoxcxl zB_o29tnPr(a9JXnB_>eiD+9GQL(Jzb6s;meJ7G~qLLv+Vgc$XNXQVDb0XNKpv><`6 zG&)l6^wj8hEf~H6+!^JU^%#woXAZ+v-tomDmYrWHFg_}E{wP-9uNKH*veZwoO=aF~ zGFPIZm}nFwL98F}`A3J^$-?WSS>}>3t)Q2Ryh;r6|Ne9fq^^^OjLK5Y3;ao^yy3{` z1qaEL$q68BL&(hK4X&KgoA7tF^R@$EWtxlC7@Ib{0F%_+N)|TF7ta=!qlRFvCXfs% z%7`0Hjo?!)-xRoE99>^k?+fz~<_$T4Zox?ty$w87U!erg;t#tWm}`Uzo8<|c<)+dI z-WuPQixpJH^H=qTo;ruvzg5D4Ww$?9*{Mwz-Zr`On=<%dK;6$<4|_J%F)>vd4Qm0} zR7;(06gp)ma6-&nM4K(osUT?5MqG!L#HN~{{cJR-`S^kQ4@G;`8$V+It7x%s{!faQ z{lB4TWo?XA_1*bxY+dyK7i2|M(+O(`<9k@c@@VOuqza$do@SS+0Y}t@#>I$KCd!x; zvIW@-O6HFzb@h=nQFUP?(gLbR9+5N@Q!uKaxP+i)D-&@4kPMx)898LopxA!%i zP2ErNwIyibH74k09|8iFYfPJ$c;B<@CMt;em50?cLp67A9`5xdlpyCQjzoxybl)9; z*Wgd!W#rJJo28IA(IRl*BI3eG(sfZnQG|Ob>O#U4G>NJ)Uf^s+s8Yy2EOp7d;@n^6 z?LuhbvZ3XCuw=1Z#1%L01u`O0ru+JTg0Z1n<7J50@>~4em`jEbu1exDR?ehk5t@-O zmG;c2N?ZPE9&#A0`>gb8C^Stk~OJ^FPAg^fTu?RvY}q5r0gh?}#)D+;^(U+(|~ z`CCzA$j6kjpeN99v-HQn(qxAGr6}%01vLoT%?#QFw6G-XX|G*uRjS1Y)e%m>tzv?3 z_W^7b2@t;6jPs}qM3&STvejI|@?G_dbQ6~1GQfwKF~8EzuVsV_CA_js6Yb3Vgpg!q zePfWR7V7CS#m5RB|FwrTc^RY)CxIJ>6F^FE>GZ|9rcEF)i!eOMYZLb278q>@CF`#= zgh<#63=<_A!_1^A9Y`p|D%!d~W2)o7dq>LKy_J*yV)sOkx~7J>Y>DqEb;F}#X6crx z0!HK}`O!1(jtZwr&lHEv1(3?gmQFL-M4HiSkBAYuRt81}l!y?!=t!T6^3BDew9;EK z-b;Y-7|mgWVK@uJNEkp^O|PJlerVrmc`+1Pb0WZ&T%v95iPbGK*$pt5SE&qnuT$;} zyGHAtP+5pEc>CNjXzyfUd?*e~U)f*Wd&0yqdU|QiMKfe&p>nfe8PM(;qICBFSv`b@ zg}W&BnK4ptJEB-`Ndy-d8b}YQrN+{RjYHnEd=}TFw{XOWfd;fCsH&!|9|>wk-LM!5 zw&U+CwNUJ%Q*Ru)dgANBHq4i3`lQ>cSp5=F?xoeU0-sdcJ{n6dQO&j zcY!c`2f?7HCNjOR-v)+Cm|D>aBIpef#=|)2oPu7ZNSCX7%MDlSgNWV~=J82J(#%; z?*BUrF}_$*9R8<*eXt5N;N`b{xmSuZTISR}g;wYpVo|h_TAgW5dbCQwq=}B#qr+
9(D3_o9ZxzWG zsPr?^N~7UZv(uvjcCIgrg|CVfW4bdID=?ZaQHoRY4vtH^7talK^)&}3?ec=*Y_dBw zgAdojiga_e(tIS`oAQEQs@SL?wKp*Z0Ng)0tTSq;QFCIezd+wSn;}Nc=_Q3D~F&gM%|STsw8{+sDzPq2`wqI)KRcikijE(um8Iogi_ z)+~RnOP0AE|KOG)Kq#pc0Zj6png$X45P46Mmi~Q@v}CIwA3x@5AOIR0IDA83yDRgr zp|~=I)gHp`V8(Eg5m*Z79Cg7p6-Jf$E;?b;-1`S$sR??q5X7829<97oSt`HF+PiF5 z$Ba=IEl{smHU{uw%+TYf>^9`rNquDjdp!)TMbm6Z3xYf6yjcqt6RL41H73B%kJA?TgvU zd~EA*tjn*C3(FBK(zxK&ti!aVd5PNThTFhi3M=Iyy~v_M!;NF&hquxsrWL z$fwvIE8_m=MQ&y*DVZjL>aY}b>onhMS+2!HTsE(qhwq=a$hPQ-16RgaJq+9~zPNdR z4V@WJ#$SOBTfF8isV&d)o?KL+3|Lv?vW;De3^uUJN@&U)?$9MhyT=~b(hCNa3>rg} z<^-nbrIm_`Qn~94H-G{GzxMqp2n_>L3dCASFo z`fnxga_xpx*kwuB#zMMNdQPgC{k#zc8(I{Bz^NDm(fq>OvVV_7xWAuE0RyOy;E5}` z1k{ZKUW+t$E|ml4@clXck8VM7+!$+-vgbL7p>i_8Q}X+DXE_ZRR;R6Kshs1hOx+AK zYoT>1^G$$&j=lXV{lhBx0o4OGEx0@`V6craZhq}_qZ9~6%IGFbv#TURt0q|{&1?hb zbbT$eP!^OV<}f-&8+WLdy_{BH+I`%wY0Ue!R-`=oowwwc!=_fOJf@y%zr-Gps-?WX z9rFqoLuUJi&^8rmBeBMJXlqFzp+EsC_!BU3is4A3{MiVy;$~uluyrdoX-;w4wQ;co z)Yj(v^4ww+aSV<4q-|$Vb4~CBG$ijGp|CFSCQMp>;xVa<2ZALI^CjWabW{>Bd z9sz3=FA1K@q*@;RB1s|0yRxloke#mm?-B^0|*4M9clWTXHbHLR}CAPh!hycQifT^gO}c zNzbkE{^0hTn$@y191X_3M6BBg=3c!B06_rw&{~ZxgK`-JhUT>YLkPG}!)7nn`xi}v zo(O+00Ig7_YB&u_JnCW3uuFXHrQn+se~Q&Ki^(^Q6^X{lK8g?!*Yr;yX-!2!w=P1Z za{0I(UV`%4>XhCYj5M9vi)A8WAnV`Cd9~`S)W@haRk22bd=w#Lfkk5;8?tHdUVt*VKdkb-nE;v#Ai^8BFv4Y7>AoHCJSS>*M{tS%Sjvg7%ty0Np=T`xMFFDa*uhyYk>!8&w7L<7%kMS7E46Ahzrir zFMRylfeih)W#F{I4TCej<%87q)NSczPb(0PBM}MH_>*=Pq^0QB7tx`Jt=0Gz?;e?p zPx~yRmO6_41sYRSR^8iXj3V07@IbD9YB3?1>N4Nt#uBSlP4|xThjk?jfD}BIFGC{< zg?C~EXn2`nMEk#$Nkk|Z(Z&YlPBiHe!wQ4(oj*1|0J-}diyyYG4^VoyYWpfRneorG z{w0y;MJlkRlh=Mis_|xK?|NM0tTDg~q(+5um?)I|0^rLC0Wd*%;qZrt;M+u^w=vG~ z`A6u zPFx6vb|x`I=J3&TkfsDFGA9g#@$^;2s(u??jnqz*iodQ6PIQZcEE=;F)^T4qNj?ai z+(iK{cz;A}83@;tup2y_zwX7w+{PcbbX)|Qb0Dk^PXT}p;wEUePuQNXOAzqo-)W2P z7GOu{=c;8u%Ex2o4GU}7@^jp%h>;4gq0jSps;T7Ik(9fA*LJLb89V7w71 z-nxrB;wO`Wff%B2-YW~OGgx&mYNWLK#&-nbi@HsZP+MOyEdZvy*GM$^j=jx ztvyeZ?oMyn*|%?73&8*<=Kk3(TDe0UJfb68*RJnd&R zl0PfFFPyYAd6E0~8&hq7ED;v4{!Ys*p~}b_FZ)wP{{)l(P#h?YnhY_sm10)p{%(Uu z&%Z(&%*KyEN3ii{C_cL5=I(-cg`?4jrryHPA2P@o0@Ut9>I^7%#pK?B`t)VKqS)@S zc17>p!G8C4wuQW;!Q3!{@#tl<4RqMWRQJ2LV4_L&E0GwdCnmIH7msADYF!W zmFp+OfBZdgY|I9={ssk&|35*&|9x@&zcb(x{m%hcv8twB=I?+@WxiH7!FUZKp7216 zE(l*;203$A&3<&Kbuh-TvIU&2ByH#3R=mDy=X75SvWQQ^OhVE;pNL7?RIkLG)5#;9 zb8A;AQI;^+*P_Genj%MB5t;D^ONtM&x@0pFZQQyY~w62`S%6-1AjDixa$DoV)YY$ zUTSLYV-Z+)I7l)Nx==;jsuA;YcM;K^m_~;;M-JSVJY3mP69pO`@=V8ux314+MFkIy z5k|mi?=!28I^AAeXdE;l1Z)2v{5^gFTZ3uhLLD3jhKnV7y*iG zv@mG3cB8>GW<+wvggO(GDk~laLu7>)k$aFrcyZIx$*gqgwDR zyz^tSsUIGJG^P_W`(fjp9A+dCM}=M%l96Sh?a8U+;V(etw|yyDVd0n%3P_D&UN-tQ%EjdJueiDFS) zN=$ag2G1d<&=^|C*QB#p6l)ao@xuJB#8^q52=7Z)vI zgBCi4ti7&NUHan;N_}Gn23nlT233V0yUJ2Nu(kUqpWA(%V1nJHkW@-HSQ;)c_=23XgqZN5tj z^rNTn?)7+6fSt>F z??LH}Ds4U(v`~u@G=vyFvcm+C-u z{FU&H_h$kgHf!eoK$aWq0^LZ#lj)jjYG02j)YyzNu45lGt?7x!hY?pAb+xj`{ks(= zZj%@qWJRz?4#OBBBFxT+3zBk5K`xR=%@#hh*I)I}>~gno&*)w|zumXS{}(N>g$uw|g-y}f(OPi>ccJRJ|M*m;s& zu4p2D0aUNmiqa4jth;M#ea+}v7IgfZ!htj!17Tz3^F4y>0-!b$b{5UtKzmx<=<=y$ zvg_ILhH#$pu{{*vgZubLy|4_psVZMtau|dyS_zbsAoJuzaL#^n#JauqN4A&ot1x0A zR*!H4J^LMcSsxf+aBR^&;TB&TcSt5{H_!$e#|=IEl?s#$j!}@O7x)bxT1p=fgGjIM z5X%ZO_96R)15cB;#4DOIVN(6R2TQXqaM`Iwfc zt?Ul)`T&+wHAfVSIC@7`AC5SiOsa_x@(q+L;$PMSJoRqDuURnj^$SOtzeC7|1^WoO zxQ&Up-EU+bb60{}zBGem)eXGCv`CmZ96g~_{EObLSK=W6iLyys_9+T@~>})E_^oByA)N$7%>m38B#mxo(3D{fdSZ!0Q3-n)$}V z{&55ue}?=Yhe3kexzh1U?r&+bd=05gX4Ocs8wzz-Hm*h1!_!*{xu;1<8UwI(KMT3+B_Gw-k7BUaq z<6!L>AkM0Q{vp1&{M|$2ntp_Y{eAB>ZJp%bVkvQf;9190L0Y86`TWu++|Rl;GJN$W#Yign z%O>HD;@W}+s#RB%8|ctwWWx--`C}_8KHlA`V~&hDdYVI;0@Jg}BO8^hLceO;*p@n) zoP%uqY}K8$y=#$d?0M0A-Xpn*Cw7XpskK7nD!N`?G#ho}!lp~E^sbDn_;X9?CTAq2 z#3S3fpnRJ-wt5Uj+&jP=+W=eUj%*nsMhI|22$4U2|G^!TQy7%GzaN)AGLRtDCw^q0 zz^^N9K;1r~CrNL}mb9d0PmO)+bLbDzA6GH2LxAHz9B5qg4##M52pK4hyZ zYehOGaf@Qrwm~Z?;k8yxXP+YcC*X{88fkMN$R(?iLvd+l(b{ECJ0%y4{bbm4^)cVc z=777rbSYFVO~TdF|6%EpGZR@`Q(Vb~@vPpmjqn`yHV(5;S(Dbvnu$ius6nQ3 zft)_M9ZUZEdU{UDdoU zu^vY?Tp4we&DAPjHg*5O#J7(hs*%mC+czyk9`ek+5sz=(h!yX)=tG^^cb%{YKp>vP4$nj7BVWgX%dK_pi@ z9rek4jKSvfEatqW<%tx|8Oyp0MdBazyot|uS(c7S68RX7hmJd*)9yPDzX<-EmG7&b z9d(e|U|Xk=Re7@n|Dndvuf^&VExJmx4Fy9I50!_Ed@lO4bTmFdj{~4ZOB4cG!yBjhqqNB zv=(kMdEI(R<1z7AtdM9`0xJ0Q7MyEs^tMLFlWxP)CszXWIjj%cMz|+twg}_IBr8orYH>%M&;>J>64=PY5NlM#cA|*@qzk7PiF=4DRp6g z|5)}-iph)^_0hCDa>~?tw5$H0Wa>0V#3AuUHG-&zIT$1{=_KqzBNN&u>)E3sV^nTD z@rD{bfD&&b6cB`bQznyfJobG`P5N30Y1E!(GD)nS? zjxK4SvJf#;CX;UoL%V=elcFVAhGqJeEfjR6Kq#s!L;I{_H^%bH}T+~B!itd$i-B6pO1@YwBX-p2r_xGZqiSxQy zrc4-y1z9KQitd3-AXD#Idq&cxT@8bL)xW&s)cXhGP9x)MA;m-UBvYdR7Rkg|j|%NH z`mFS%MF!GY&!53bwV?#V;t7QrH{+k%4)T)HBOMf@f7=LeQAG--HKb(IW^OtIscDrE zotH+FgehHQnmir1c$~IW=o~JE*(i^6Xler}IJA1TA+#52{XQ6$u`$|Vkl1aud=D}x zLyAXQHnU?X4<`ACODVnE(QWGu7Ax#H>wXJ$Lx~Yh!&L+;430THLf-`;sZLr$6CAjr z0-|`Z=jgq8F}0(6m2Sc#m2PkRi##Ny_em>GUedVqz$Q1lAwmh>bn0B@8-)!V+>@By zH3wL)B~kCxIJtd^969}ofL}klyvSxr!3Z-LQm=Q9?u-NF*D(0TaO!m7arrC6CWP1{ zQA2+_wa5V-hqKgAwx4)gMYkUa#})_&;3$edT!dLd`o`k#`U(jfw22ZMAg;S?(M_1q zcny#x4ZV(H)Ba|rB06U#?YC)9oUov|YS78DxvYz6vR4YtX09-#P{oCw#f=77L5`TNi4}}(6~0{Rg@%i)NUK6t z-)yHdc9Pza`Tn@x!vTF{ckMJ;m^V7xMcrMYe>VB0JR65Sqby44hTd=_8Ncp?yd%{t z<^>vZdtr0t@6rd=g`(!Ea0_6ubo%DmL2qgsXkyW)AVQg7u9>UdX5F|ROKT&z34#V)@jJx z@=k)OBF9QSWqjJY5@&Vb%cKVlfGtW`yH85*f5j%ulgM@T$YBHlrw+Kqwo4$H7pel| zVGh}V;C7SjP{J|E-lFl`O#xA}ORULkYE_tQ^Wkzw4Qp?l7 zu10PUO?&lfb7}ZKzOFcH3-{6ntsqa8GUxVC>1}Z{z<8zl51Mq8{7AD?CsnzJtCd)@ zD@|d&s`(GbqRJ5{%gg(Pr;;uKJfsui_wuw{Ugh`GjlQCq_0z)iW0@oX;v0So#Y+(2 zczb*0lv%@oMN275Rfwf+!5ek#fer(Zj}X^NJp`{X<912egwzOiO^=`t<)AMVVOunj zk3ZvU@q{bt{f%qp1S>whr`Li`#{3eKwLzcq{9;s6rGGzT2>Qbx#kTBn&VWLpxFUg( zO*hk5X@{EUocRM;iRQ=eX)*@h(xg!Xfji>Q?jTGB!Exrtcf<@zxkF5XEJ!Vt9K~)p z?jmvKY2u~`zQ0%JH7h+(&SSJGN;01j6v3aWv_VOg&!HgiIR4)`eA`FXUqB0=xC?JQ zwsUyx-@m=u=|nvE#jX$^wKaSPn>ZzWg*5r_M;L|0@j^Y685H@R1=$63qS|vZ?TD{# z+YsC8?qGnAT>KNVLbC3Uw(a$P`C>&0dvRNZK`6dPGVCL*va4twi`x3c8&S(vYX8Ei zU1aq@G)slO2N($c@h4crgaEPDUG-zGjSqc-k^dlR-qH>N`tflPJe@#CV!0HFUnj%7iN>9>}AeABvEGtRJ7two_ObxO;XRQSmcUS$#({deS9Uf zrSp_HXu-=f2C-iFdqje3y*ccU>H+}>aqo#B~2 zbRZ|p8nFK-Lx`530M1j0_c?NajR-UzQPxdKag!E8VqOvVjJ&q3v|@<5+8nhic5qnh zFY@weSf*@`X7^K4zCyP(Tjb3Aha*kJ%+LR*@H1kyrq~Dj^T*|mqsWbR@t=5A-}WM=GW{=d5WivL%4AI-(GwNo$XJwqRw&>CNPm=`7iQb`;Y z{MjHpZ=B>mD`IWQ^_W55|16_^X+RH))OE3Skdd94aLifo{J3~&&HaN~|BJO;V}c|* zN1vll9sYA%?3OjCmysoFG$??mUOq+SpuoFSKN?r@Z->3Eg@pnOnzqtMj`aXuHz<;#;(jPR*ICe#-(kB5xQ@+oO;& zEt?RuQjYt$bknI_m9?78uFIo*mC>%|d}DL#z@PArBQIm*7yI)KK(tL6b0Sm;U8w!O zMsY3gvS?>ULq1WCq(_-2Q6Jz$q-xcg`1!11Gi1rE>Os^XkzGvPgR;8cOh|s%IZQ34 z1T=6T6@%^;LL7p|{TC~(*Ad9ou9Xm!-Uy#k7*-G(h}E58(0b*itS?^RZXMbMHZ~Xs zA^hk7Z*+w53+R#WkF@1J zHxk{NFE=x{i*Nsu_l)CuY};OUNQy8Vtin)T1RkkS?E?jPaB0y|uN`naN~4P(n+l*Etqq zgCvn)J#UaHDlV3oP~^{~w|TiuvSIaH@*#%TB~++~T!owuVwKOsK@os#9pI0QBOJ*H zJAHZ@6>|_3+w(bchvy`6>w3Ly)iTQm$}q;h^EU0;^YEc_!s-5yjW+{S*2k(;B`C$O z6%5l60fZhuP!<6U+u`zgb%n?MxiaTVj;^@JuQ2q4o~ktNJn`FXMn=b#*83O5+(^kN zUQs?koZMXvR8X5YnSKk=nE1zE^B7=3hd}sJ$%>EAx+`d9Y9r) zAbIo}z7CA?0|a|YL<^1VOseRyX7jZ!=QcGJsyHPW$6I0g}tWm?+pq-2a#HHH$ zx8ki>5)`lam~cG0Y>Vv151ij*r@#sm5)Bk!pI+6^8Il6GxfMA%dHU$q_44M0&C(u-7*x47?&QcC4Pq_#?bYP<_< zZWU%!cL$`+I;E4f1J*puwsW*QZ}5p1!#7OT_Ex%JhVtu=;43D}3n*=TpSX6SS4 zvlCpi^9yvd%hMAy_~!GR9IQ+Ci;tO>)F>`ZdtZ>4Ay6*C#U$%AB)Ge_r^;S=+ z5VB`>DZ?&ydhi7WnQTr7s+|fZ!jSyQov@N;_VG$l0JqN!xmCrp<=&Ye;=LuaAt8b- zAB-E&HhrZ2;IDmJ#cE7sD9=}Oc%3xNI0Lqb1|=h=4>Q8kRtHCE4+hwln6n`p3O)bX zS)ab*4HGgOCToaRa7wflh+cex1?E*%c{Wnfj5pGM18AJGg#oz^>I`~l5GPbq`+Lp9Ox8Izx9jkIxydy zq`ll^59d&jA($x0NfPi1o%I9HZ8XyxeqI|?l&8MyC*D)M$UZ~!>o51P9rMD!Ew4t0#n(M#M z1{V7D1}K0h3%I@iiB;pP8Pt&P_aCQEfV|vfAwSwgn2kD#m_+8;vywok0LeQktrBvo z7cXN6w_#=aM(v}bVX8hRZ~@JJ?PAmCWxdhN*yn@$V!EKFf6sMC8R@>$@(VYGPd0er zhFk|s3xs1op^%Es+cdh^U7JLClwN_Os+B?)pkm)*H~!LFEd={;-x`o zF`mGIDv#k~OHqg7qgWlN7I-tVZ!^{*#&%)#XSV8xLGH&;raQ3mjz(pHa|O!ZLSHbk zu27MUu9rENU^W=6P+%xc&A)2a?$?Gz*c*5#nn`4(9G7a9l|K+U)~9?}8o)YNX^M9^ zpv$Im*I5=19ZP)UQ3apDc2P`$Q|pRyxn3uG10-f;4qjPt#?s}?!!p3bxcxXs}Ml5 zdpZi1BTijPBRzm!Wq@ba|HRahG6zLz#|-~N^cArUvVu4A66;4 zV?FKwT_VuzD_;R@NWDYdFzoLHiH4wK!qvI(b^4mzl8>G+V?iadTt zyNTzG8k4ze3hz^>527vcJ|+VypZ-(C{fkv2H*|Wa>x6E-7W5-)z{Xe$c7USp?N<8N z-2UP$i_~P)N%@ndkU35(0xaHQKpn@BFkwABnbzT;Mi>GWw&9>jp>+$u_Aevmd@D3- zepXLH=zS!b3y3gg0LFpA_g^q%u?i_U(%%>6dtD=gGbbA#lCi32>cu3I^D1}NyF1R2 zwLMQv$SvG43>NdG6T`rrBLlC-t5wl%eNuys+iHh1`q_Wu{nssW*=Bs^bp{$jE{ zd3a<*G6~#IPI8D(#Md9h7>Dm4r-x|63_V7KVe(tPhXl+ur-!_P1t%xZFT4ySOe~Ka zt3C6yzO?kTqOI-x^R%w~;=1(jvG&~EJscihi~g(P!&z0;S6N$o$yVp}IzI4^9GL{p zY_K(E2o8ST6s#xReqKR#{gd1p$>n`Y~8Ni#a3giphg1_nBnpF0{ zP`g&v$Pfw5^vOOTn9H6?2~E?q2Q81pl`G!fC1FZ!)@|cmi~aJN_3MLuAD_`rJrd8V_c# zRsYys0I;m!SPQjLKCa{5z}L1A**crt#anW)tk|B}+f*&zbpW(|+A3M}il%9{uMX?X zdtUJ){}snO=*kmynjFX7hgU$w9)k@}dH~)2)b@AC7tiEKUB@R@Os|2}(3-^~Jij zs+R7Cs*3!W({^UbiVK7~#J~17M4Jc?!G@CF`7*ryv%$`HG{%z0)4FqXtt}1R1uYFF z86K&GZK%0KJIg9c$xEs<)n@;ZS1%W~Tc)O{B-l2NL{(L0qN=GT*JWtc`OB6gXqWV{ zQTQ#QJGmpYzvvQT=+E*q&nK!U{rfJ26*cHq^E2WTtJS#BJfQ@C>!$|!GAu!Osc2YF zq<}riNfro1T~b<6jcaRGW`?1n98*@*F6Fz=S_7A0+6<6WLkVv|eqHyDuKo@f7SqI% zR-HYLY?h%2d+(QyZwb(NV;jSJ7WJ+dOFC|nfeQkvPah=k{8RvTwkZmq6|aE|`dZ4i zw)~v)z#EH=Q$aC*3{H730I0!=wy0v}gUWC|bceWCwEn>$pzV2!Y4|FskSgSPFD8xA#enQSyD}*%bxRC z3wIez_f*KW8%B4~6PG)Lh6Tu^X=utM zfkK37jzA#gVs2=EEV9ljho#!6nv5km{PZX~rE)y1Koat~m!fvDZ&p;UDDltFt?H!N zDo-Gh(0wUt266)`mCNvjUtnuyGtt!>k-27gq{ZoksSsU`Kt zwSx*zR!q|?|5+trwVMPne9lsrb50>kqTMdX#{H8&krR-frS4T`X<1bqI&6JbbWJRX zxrsAFtrei9g?)rfPq?iy+WjLFv>xdn@p-B0TswjTHc`mWqm1ro*iAx_>mY zh|fbDg+!wn2f@dsYMKgKIL-E%guzl=CF;IMwT{0eF!cv$vlHpJLp?V_vK!#5EjONjG}A+Inv$*5LC z{VlN{oCqw$@-?pHfPk8ceT50`Fq<#R;JdxsjI1H;i@sJUf~)A}R+FhNFy&v~yqZFq z>~;%FOtKe%fTSgCRV^Hy?15O(TlGbhxs|oQojbNi^1gt>a)5U`W+a^1lk=w@nK&mA zuH-y9B1PKGg<183BU`ew+r^_lf9a;*JVmu7P(3>5Eymz|DQ*+ufC!JW`BE~JN=)rx zU_xWHeA&RjZ5V7%0GjhF=6A6ng3SD_Hx6$v9P?*l%+JIV@5L*EPt_hNhfhTAnHxn; z$)2v$C#6r#fr8dB^!A)RP0EFu|AW&jNLS6k%^n=4PyRvbE33^LvA`Vy$iqu}e?Z2x znlz)jUgVBbEarD^jPBl!^CxD{@7BK0ci?iwk5M-*!Q{7XAe4zn|YFDu7-yI7vUAD^lNGVE%I#bEdd8YTVwxZO6bY?>;8h2UtYPCGLKezXp;#ri*_ z76joKq>Km1+C}qT1TefL8=Ro0=Y;XX-M1k=GsXmB7f6Cmdqy$~vHpsij!G`@BNVz$ zeiUi(k&%yu;Z9VhIW!>!%4jw;RsDsL&@>_T&TXTI6(SsZQ6k`Q{YiM7z(r706t&S= z^tvVY>xr<-69w+R5hTM!<#-4gCU>mc~m>nJ%G}g$fbwo6AGpO<97S_Tcp zD-k4O<+~clvMa28Bo?K#zj}esS)2wxu?NP{3*}8>+1Hdq*GHSi`7zIr& zT!aeh3*Dy*aoLmJSzTJ}jS$sNN}-*jZKd&%!{W6pTBIaoxd?R0hqyRA+>V@3<=Kdk zDA=h!P6zh&hS2nku`Srb_raqM8j=KM)i}z+AwX1o3`52ZH_{zw(osQJ-ZPKm-`)+F z4n{MGpJ13DFpn3h%4uxND!Ix#9CVI08_wHNV3biLDJ#VGM0xsrgE&JM7$Emh+QA0~ z27-AyldTzW58M87cRJ|l7G`sV#wN7F(Lk4aFM!@gaGo1l=o3=%d~*^JexBbpH-{F* zP!tm+zQ19K2&mKSz`wEwOmN2t`6C^;1#r=Sv^COdM)Im4#0Za7IFiS3jN7r-5D+a$ z;)-z+qME_Y^%fM$cm{2bt|P0V#jW^R0#YA+i$E?44mX>JAPemeP`TyJ`QOljS(fg$ zi(|(1@sAxxyByM8*L8vYKa{;?Ol3i|CW^beyF=q{jk~)XpmBG1cXx-z-QC^Y-3~PF z&^XQG-Zw9EXI^F|ldPRo_OG4VE48XteNwQmRsSwrXfhEOzDIYmz+UF>%a{FkKdk6w zb^dyi=;-R;2Yt!F_;!@Ntft2DDoSwHIb6t!WJ8~DprGH#Ixp|qaN)h*n1nOuG*eZU zq}_%C>tEE>=R3H8hR(W*GYe?oFYuCyM7s$I`adJQCut)aV;xizp;#KO7!8NMac)0v z!5_?fK2EV>@h8!o1dCrW$k~X0IfibeSQ3}bl&CRPR9cnSR@l>2RaR+3bVhBKVE#djwx+APxWJ>UibaMt`J5?$8N)@7_sg0| z#m>Bh0gokw!XmPYY=(R}U$BRA95pO;Qem9yN_E1=ASml9A*Z@D_=Y#q{;)lhG0ty< zQ~}D4F5|#Hw4o$TFeL*Hf3>)UftNMi>?{AASxT2xyuqWeIAGA3(P#DpjR_N&A0giQ z#r;8W4HnW>LG=r7j#5M|-7kW|*L3_*J zP15lDQBV**j*LD)FX zo0EV>x}Gha4-NsG2caGGTIY^c@rdb3_}0QAJgojsO;^i>Tfp&Zk4`$FyZ;w_+bWZ9 zMb0y1eF8gYl4N)~38sD+f(N9;U==fzA7aNX{`oWB^1wwsoF6>m@^Sdy1SS`HTnTfW z#Ez^QVXS{9O|Fg^dUzL%uTE;DWYu>Bh9hb$G1w^b=7{**P(r90;?BGf7_x>nf8e!P zs!-SA^S-9--mYCAZwF^TAlV_MlxtaysQl1#4eI?Xfs>oP1~0wUpS%S>0YRFcHFmz> zMH+hfJ$mEoa&mfE@spYnpmEJ^<*K#R-a{6BYoH^;1wC690p+Djh@p!SfzOH17#Bs1 zT0qiw>33N!07Ey#rIL*~PX35dBZiv^IdDb`HS-v%k23R6)d?k3pfuSd!*J1p{UTSE zqT=7BqKg~kgMxb~N7n6#EmnUHen5#HW^uY!z7ss&=5)5pX5rd0B%Z^=oBC9ZG)Hc4 z#R0L8B$)KM2RW{wdQeODtQ-K`x+WVQAt(1wJYG-a09c(Y&#Hf0RSLB{ z1C^1nbW@GwXemGxQ&^`-h?2>?6t-a)$Ek&H9nVEN4LQ-xxrEz%a* zA(yVH&J9hYz0c2g#_Xw1bcyk6Gi3bddYdQb_@AX)OX#iFAdUKns!x06|`lH~I_FsdK^G(hjKGQ-wyR_N7mgZX_cwxN)l%%-MMGH z3Kt7o2>Fyof1*ZQPoAjikxT(&ykGLCkSXbLY1+2L8Yd%u7gW}`*IXNb7PCx1);$m{ zv|&cA4f&Y}xoL<7fclbE3u^AdhHl_9{fQv3%)UxIaQ)`iJG1^e{V)eL7cB+$&v9<~ zPI~PoAmmQLA$bbV4}?|YGT89Y+pv8RK66<{4LQc+8>W+ZSl5Tj?#fj@x%2b!!vmG# zU?k*&61@9fO*O5eltER#jvrHy46s4(kC2Z8)s<}`Q{>Kdk|cecDBj7ycwu!vsZ$GF zz(^0>W_>k}&5q;;DbhINhpCjj2wW&>eZit@pdW#iX{g00>r`QLAC!y#{!7TlGU$=@ ztcfXy(vK95Ye$bqE_~X#J@kRc3P~+jzpfS==uvb2Q58_n}MJ6aqqtf z1wl^sgX<%A-HqcR?5PR0WXJ#d$_P;oS~3#}lG8;JyhvG6O_-pVF0PcZs!@$|WlMNA zogLYQ^+{>YVRZ4S6aDp1m9QjN{Q%&Z(q-;oFYd?(w%k&F#O}@naJZn|m_fMOkx=wBQ5Dd=U4PWVhcA zFKv0WGfh5MMLWK(VOGDgVmdRT^4<2(YE-6vp5EjKJ8426{5w{k!+WSg@o0R^vwb=uG87QVnCQhi( zwv)Pkr2qrf^HeLwIytxf)HAV686DQ%lw|3n!-^<7Yc+9s9f}_O!#nvkmC}<*w=Q^f z1zg*kP4&RMD@Nx@-|I5`?$f#kk~$HCA0AX%1Tww8U&%1kQ6$*LFqrHhz>*B~c%ey# zLL^oyXi1EcYwB6YCn$;Er3lBG(`cPJ`oON4GjXYy|{LAz&TAs1xv`iZ}ewy#tnZfVETv@ zCM9UWycWVmjgZk4ok$xsL=KA$5ot-n%TZuuNHH)cX4sOkq^_POSmy{?yUfenlO_X& zaLewoD_-zw2oSLoyz-7}lrGhqwyox^XC~py+@O0nxjx~Ywr7!ZiQ;~9(N1J19m&hy z^CownDbP3urSD2~+kLZnQxiFDsWEf`xHT9j-b*{zY};qTZ++OM-nrN8ZA}ZZq3CAq zOF_+lsxi*pOi?)J9>#S^{(wyDByz^iE)ZpWw)4%vno_9G+s1mRT8uSf3>|HsN$<*) z*!POp#@IPw#Ih5AdtQ7SqBxpE?X+T1Pn#NPg&ZRzq5Q_CD@J%kNaAB2S?9{YQOFpZ zk8vrRe@PUko~FiuDU~t?&-AaBb1n zMJd&&Qo_3-Ah&pTepmDB{TIE|y;&kgso!yXgvHhM(Ahj~qem2jb5ylxnTL&%UP-%T zQccq&7CPAI*Xpm~+&>{Y!FI4RQA9LsE-FM}Hab1t}C%qAQT6Hai@uQ03Hb=3?;MC0p=<{ie!t^|inQ z<1>uKsFu#!KfwE7@wgF0>$XdMDi&+cTot8HS#L!nEGWsYg`6um1s|^X9l1oJ%s#)+ zoV6W|JQ~H3K>l%LrZaH{^(#qB_L>UDSqz3w44-F@nE@5m0^_P)BM0e141-hYy`vDF z5#wUts)5K3(|m}?5o!C!Y-kUVf1R3hpa|&Wp#uP6ieh|GvI$ch3B4s=h$Z1HP`4Qn zbA&aEkadh{Cx{+d;a0U7@dV;kW33tGwj-rST{woWhm}QKtuxs5N3^4^MP}b3IkN4N z+YOA3)VyHycq?p&)kSRG5jNoOVY&m~jgbAQ{NfBEyF&D~f2a%#7{#<}#-MwP)wUa8 zMEV+~c}PJF50Nntp_WC1lTi_2nn#QcQ#mTxpvFhjkDvp+?uy&B`6+u*6{By4*<_+T zG;qm?RQZ9BrYSF}Nlf}GR8i@vDtA$=lHHYRQ3muiKn_YWeNE2DJvzNdyXco(rxFj@ z4bt5-yZ5~u7h1D7(UgPg$S6K*dCw3Phh7;eHKG*QWK6*1PD;|AETezB6Cc&YMO4Ei zlFY(uCz)gil4^uZ;e$JUDOxHRdMZ6jY&m;IF(6Dd!bzmT36?ifCY)!oFh`#ERjJCT1uCFZ>4h&Ye@v zU{x_BS2!At!#Id4_9u$X0W^++E+1(@nVZ)SvQ%v;P!yD~ciulj2S7)N>>^XXv;7Sx z>a3Yq+X1NsuXhX0UQ9Wd$dUgmbnD1al41(R!AqKwmAVLipt5B*PT%s}GJ9$-&*b{p z()!$@vT5vzS6G;$LJ&SRz;o{+<3__oN*9lZmbJXXB~m$d?S#>R_9QGxXv$&sLu1Tx z_PNfL=S5-C)H9}#D15BI!^YK$I2{4m@ov3cEj#K-)ZAw}f7;Rvy(@%_QXk9l=XpzQ z+&LDWknuZ=pSfXVmI?I4v17a~aZUsAYE_$1+JfqtH~Uxv+XX+_mh>~DQxm}yqsg}ZT}^ES!QrlS3<<2mSoTp6p20qH?WL%D;L0HD4XOZI zmt%a9GCd%wMf(c{zi?HfeuYroF~NoP1v_IxGHR%`>ooMsM`2#8*wp8r$E&=n%FyxG z6%Wu)qIk$U4pKjUh)e|d(+x3;<+gkD3AKhXdX1S)-JTfURSWqSajo6*#$R4$_7)_VB6DKlejB zA@kFhUEZyG87}#n5%`nFP*F=dc8mOHGzI{kL}Vbb1{g}P=u&yhRnHI9Okp8XOi@bS zysUmoY9s1JA-B?4|EgMq={oI@gzX2P)bY@O9VCwUrxZDOA_Kjd;>;Wic!l}HKdr%; zSdkx(`3R7*rC#bXm1$!?yCBWvG|gj|fSwLKlUQ}2H3fAP?ak(_EoR1+kbYP>3&v`)5yk=EGJ7fUI=lKv1p)jd%KyLbCl0O>71>6n?3A3F*SGOHAH&N zR<4vXBWhvGdYYa4_|^_Kki2!Qh?jHPLoHpX74K3J&b$$2GWVDIQ-J&ie8r^izS?zo z!K5H-HS{kEaX83HQD)T*#jq7o#$N0+`uG4v9uPy3+8eMyEF;D?blDj82K2JY3(?YU z70ZevP=ET=V+i83NfU3H90`g3HmxB;NQGogByvMqg>=nMq<@x~1-<4xZUrX{)Bs=$ z!d^}Xk5XZ-RBD<_ENI8$JsO`T{^80LBa`(0duqxfgr_;pKnL~CuD_~4P@gajQ?R%v zq{|<5oYIf1puD{VDuW``cSJVgQrZ&vpyG9^(BfS#J0UY%Y+EDZxVOH;;&%LqX3cr4kgCGeu-c8Cf$QcV@?m?$u*mFD+l)}b)mis^`V-afq>oj~mL7Qp$S34U3RKM4yEhLtOitMUB` z@q(%_7l={inrGaA5kJplmKT6OE;knq^<2d&iav8OtaqObCUuVJ$$%6{@6hql&J4%ck9j|g z1AVeDb4Jj3Am@o@ff9uFf|f_hh?)^oWwMSED#9PiDGf$@q{ct9p3Z~@tzrKPx-LG| zYnzDnOmy9yGc5wg|2%Z%a$M;y8-It|Go8xh4DCHZya3dk;2|hgQZZ4rr!3l)F24#& z6pL5A3GlfWE;-L-&OPNh*DLjROnCPf&(ceiP6SXv{egnwgo{iw2Df#1qVC*i%u;f^ zwNH*seT`LI7)rq%@)WPlIVi(87DR9-VPAEFO?p}K!z^QgIUl09CEqVL4|^+rEfGt2 zGhmr*FueCBmO7VxMVue#)8s7eo^Wu|Pj|&PF}p3`vw66k0rh9PRM4Ct#UaK=_I3`L zOE{MextfA zB_$?%ziC2|CtZ1O!5BUm_;Ne#lG-P`yFrM2`ZJ+IWRy`$j_}RE%a(PEs1-iSf~I7H zp!T`XZ3|cv8atp9e7{-DGiQ6@9yUVIR8G85`IAcB2dv_}%!DmpsP+vzqxxTJ z&i;u~iJx%Sx$G&$o1E2Nu^;7vCH0iT?_ji&mbqZsbuzteh;p{gbKBcq=UkmNHuJcB z*?n;J2f-=ACXGU&AJ+A*Kwx?Z!c2<2jk9BG(8S9Kooe z^W#FeAnsK_leR-;eLFP3wV`t&;r?}$enSE~f-xwP;s{d&iCUC*sfG&rxavj+YC55o801hlr3RF>#iZ~TjPDE*o?UDyj zayIU${DXy6C#xI=C+?RdHQS~+C_q-93^q42KgqevS@`$w;Q>1UY8%X{J(=1$eMW$@ z1q@*sahvN_NN8{K`Uyge53$doU1G0N=(>XVWdaVe#m&2=R~oX$K^At}{X?i{lh955 zQO6BBh1OL>5sB0E=)p5*Ik}e@9z!4EAa7gBLA+5Qw~nW;REzG*9wPzu+0P?9%>Z+=|mZ&cU5=Rck@}+LyU2VBB^x z)~wO22&gAKRW@5acbi2&suoW!=W@I^H#qKN&fn{}d$hnYHbk<7iUx)m-1&B4`=Q^O z$-&tmWP17sl`94LRKistX zrOT_zpp0xBfpz=m5DZlN({1R1Q)59b$pOMadicS6Dx8wL%~Ppwq{9OZFOn7I$6^@C z8F6APj=l_0(oFj}CD9$Zjq1|O`WX^AoLEw$aGrQTrvFGvg93yn@^9`1`nNF6 ze^1K)S+nfNciP%JnKKzW7#drcG8x<3+S=PWGuaxtSg8Qu05B<#IEKyQGLfiSooPz2wpDu}@Dc;AfC z?hu#}a|n2T2q1R26J>N9u8&cLyB^$u!vYfF zKGSK%Ty(skVm~`N_QgPZtOm0ZsnjDNKMWI3d4%x!7ygF$X?kJK>Q~!8)kJ>_&*(QX zW8ipK4&FCv-~Lhq-Zx|n;AcF1X3g6VRGjpX5vHt7zk`OvZ~s>m6bty09-ylIs{S2z zQHHtf_=ydvyRMGJ^>0#G<&!Hd^1Kf|;lmaYY_=kPM08h3kz~EZE4bnMT8sVQ3W=gi z!yA1#taG}xU3NyXclDt96R^cw6qS&p8(YuCrtR;7;BC)m+( zT4`46xdtfGr>gIg*?BsiPb@$qm%4vZNmm@v+gm-luCk$1qrVduS7VTDQ^~U)T39TSydi;d}Rt6~9!#0gR}rZLO_UxvlM;`i)HDHn+1`wt8jqokP7a zq8RLw25wwfGCqx$yCa{t0pW!jq{&)%k(IIivmM7S-a27H-u9aoGs*(6uyxl`+AS0v zEUN7Hfc2sT3&nVT%IOu>FV~xD+FH^ZXs|^6RFdJ`Wfd!AD0L&*B~yOUDe)p7K_c^= zny^7-(4hEZv1JRI4e?xvKYNNpUciRg-Cs$9%8I@WV#A%Zyr7u{j~157$fp+~RE8J( zVCV-_Tu$Cb0zHW!$rfBtvO9sn09MG7F)g&L&18}L*XD`Lqdux`^LRYX7Eb~pIwexM z8nNG9)P-qyt90koV!8nNM~MhOtR{v0e7-@ho~7DAt8%P+&8$k8sYU4`2oo{myK5l| zA1V1z_36b;6(VhR9R##)D=6JEvt`aW>^f7V*cdk`U@pgbU_BMCGSM0NSFYbq#WxvW zowkHs&`C<3(;`>H7Cr$@81&)%843xaJ5h-Js3y+!83NcnH=c|mC@Q3XZp|cp^OthP zg9JBviEApaz0?0(UQ4pbOL{;s53K+PVpA_uA%6ZlBfYS25e8BS@Df^Fv^(ig1;2IfnM~8S`i+ z93kkBKh{kN?4kap2dFQBSjMbCB!L>2#`yEy5%Z71%<EBpFW8NT;4aqdad)lIf{kjs7wGQbFrt00U@pfEsdvY5!h2Vxvl8TnTwU3J{3VK%GxE#XK>n2i-|p5N)LI=jTVvmEWl6>6Fo0?`M0=G&vlfDJ`+4!lCv8EP}e zyK&mWaC(4G(?vAZN&;Tl7NBb=`}B@w?ux!PpE-!XbH{S0!lv8KD84jHV18pG&kI9q zn`67E2dnv0s7}pG;7EDv=iSx8EeB^?%XOudWyLv4y{#L|bv1FmV@rM0M~(WAny#$u zk6sP=ubQUdd>po-t#fO9t~R>@LUaXoC_L4`8=@uLU{^f#%WPO<=`#x4R zr8>Vi&v8Q>Vh~V4XKJMWxM_`_*)`@=2*VU6pCgp7i<0B~LR|Tf=RsOdUvU=S*E_z8l_|4g^e}^)2RzUFF5yqBkFC9gC@%$+<#Qt-oS1w$6^Zn$WJ_u^-joG=Cq*uzAjI zNToJ@e`Hu6omt}FnkjwMH~@B`m+@&w1u3E_|PcgUsuw4mvej;FI;J`j5q*Ub9R4r^mT ze|?{39S1BSka?AkllYq9np{)hidE-|L-Cl5a?a&k#nG-4u^MM{;cjhgFJWipVq-I{ zci-Kn%RA`{@*55?4jU3K*WCy}2V-GjBLDj5v2JYHHEY<>x+GJtVXvH`p z1BYlx`ZuTlz53A{ceqehC3EPH1FfVo(2+-qU(&LCJI{WitxNQyjY-RHqOAdwp^eZn zp)~&3Iovj1wu1u8i8gKaQHkz!UeqT}%#Vok4ifE6+$4%Aah=IH@r5oevd*yP1&TA$ zzEIc)o^PaWLHeo($fxu217nuggJXe^AdPg`P!Fb+k*Y!*?Hxr>JS{Y&100N5jACr*w~7Wp-G7yD^IFdC6b#yn~_)RUj=LVgH$=Sk%*N z5@^mrk&$J`2%Aqhz%Y5zBz^ku7<+x(VWOlsg>uzNtn^?GW8IEzSZjh*3b$TXVLFkO zCI1{!1u0Fc!$Fp@I_227MlFE1@}fjUKHx_}{fGW#kpJ&m}OBhwW;D> z*rus0a#&9LXo=}~krQrc^^jA=oF2t)DYAr?v`$5{F*S)MP0EU#a9{3bQAPXIak!5) z_AvT74{Z4GQw)rIY~iw(FI2*DXQG^Yo_AIMeUo2nqFs~}qyf5ON(QWQfVNlE`WCEC=6baD32 zT-}y=Qn5|fI(_~_pc6)K8PEP3$AD6z+xaalLb~Nplb5YR)GPgfMW;q|fAZ+^3eh$b9Q z}V{__7-YcA2Wc2G0N^_$gq z8b78GBC!;ehAcL1>M}%Z-Ug#3#n#GZ$N=H^4K#F?Lb{~ffu~&AjMi$|)VQcwwo0Y5 zRh}xLB$dbi?!%xGo}UuuT1uLKn7fXC@z%_}Urk)2fl*w=f6l)9o_Oa!|LZkp>iOD) z2%!4V851UEC%7k#X-971R#TuOl~qYg>BdR=qfcl_>@z-|l=>%ufrl{MHzWG}2#HJ5 zr+lAtB&+m;cQg>AG~4E6w^s4s zt-bnev(}QgA2R2KEDHdmzSLdI>-dM_PI^qX!>*a;AKoYP$%M^pc${-0(YvITiOgk{ z3zuK@cBnN&YX`l&41)*B4#&@UP-Y|llri+Uf0@c64MlOxb4Rqn?}n-55eXl1{y;B07YZ_2K>8I)^qPkA;ZYpfY#*ujdK^*pbMd z%%_5@JIj`I0zETi#+}}Bc%V-&>lVw~4k29h(MVo%)=WEGFS@L+4K*a1TvGobQylwh zyKO=xmZWXnFT>S_(yOv)Or1U*sFt-O)btvyw0C)wxuV#Dvs;e)L)oRkfIt~z!PHz# zw=UPDnLPy=vu?KQZPQjYuC_$avrZs^y{Us8(JDg%*zyw7oGL}w>Xv<%BaUb_&O6e8 zI9URX3&*!%KX#;{y*YUVR15u% zLId2oUL#E&N-&TLysCb)pRiqZmJ@$HRsk_vP$dyoB|1>UhGm}A;Q+tnIn9I4tvurp z>~`qF(vUDxTU5rUE4Mxgx5AKb$h~18ZbB36p5bH+L5Rkc87*EH+^m~JAc5Sd6{P4; z63Q>;B*S$i!gkMpKFZYfW4K?@5kMhOcW4gf7l#g|-ye;4j9t_-GmXFsgnIf_7nhEZ zGt7i=DJeI`g!lo+gx`*@$E$$L9m@ta3&aGk1Lg#xZp2MG5g9}24`Cs~NA*|!qO^34 z!S^7vKh0ov0L4b^j*Q0B5!{?M`d4{8TzdUilI$M91#W&UEA18G+qbee;lo@JmoB&T~5^;@48o^ zC||$4x&OFFPgPYYw!1WQ)v!5TAc41j>Rf%dpFKBT z8FXcL;SZK$GkrZX*D+B8Wy`S~ybyj7oeWC%Zn3Hns6tI9P=9T!GibZ`0JekhNq(&O{zn6UGP0d)k}GidTTj z<5fjYRHL=`1(a;F6D!x<7qzTwfsd=*g97 zX4QF@V?KBvPv&jMopD`=-4zp-zX){pXaGeH`3Jk9e*wNeVED>`^4*yysV$l2O5E85 zIf@UZ+j=-Sq13-~gSk-n!&wU+$@G781KI|HVJ7dS)f%LK2&E6!&OGp~i$v~bB`pG_ z&Pd9(D-j^z&u23$uNlYtX+<=!Na!80^^(H3FNKg$7iUgbOFX1pkRT+L8L?u9*04P= zca_!Tj3r`nKG}x~t&!*Nz-5k;_;rMjStU!Aj1r>R!!yWzQx~B!L|NWoVwNCrP0xMG zhp(LB?CeFmhKSu>dIo={z9yoX*#~A0Eg9}kY!%wHu(s<~6N;N!K&Xoscgqq}1JNmu z)v>3mMm0?JasSwm|4~6Biwjv5=^kZii&r_0{q;|cBfmqUx|LOUn0K~;Kc^Lu*E1k_ zAaZ`#IfF0mT#!_%F|JM~2U^V~7$J2BP913Nj?4rv287F&#Oy9)Yu5qltsH}Ke9 zx^&N}dD248#V3?{jFge)9@-}!6i!_R9&$70{&F?H{$LorsV7L+a_=+G(l@f}k-zys zrTu_K-kZV_7XG}7_f`PI}Y znX6Ex!?Sc;rbI?d`ButN87G}=kGwO!rX6-Ftc1vlbFjyOd=g;{1*4BC6Ia{w#?P~; zg`Q`w7+YYZM~{5bG#d+Bz8){X@1X!)ZrbEKUA!+%vpnbPyN(n7xsI`a7x{Z%5Dt(JRBw(W!ytlZC9djG zu(Y+(cNG}V3rE&xVv%pg^|LowH?`;Y^3`bUWJjMEc=yQG%gx)7MFa`ef=>rSa0)a4S=vzcrJ>2q zq8_rdsf`+pHD|7m(W3EJm>%Wu{9dKXiWoqCb9DFF$yt$ISMVUS2^r8p&DO|qtg;>j zP`)$i+VxZqo$8wHO%_M8m%fw0GH1>hv7`+v#z`}RFvpbZOG)CcwrRPUwPOrFP#L=W zM4|$3YoaNz`NbIxca4*gyqP9`Ls#CN=SGW@;KHy6YqbhIW~@^l`1=*uh3Va!8k6-L zyH17&RUb?4=4x4@(jfa}%4_U`LNL zn?8n}hrC~~Bq_)jAufMAgg3FZ(@>E=@NB^1&ooN?v)V|r_DQ_Af9M9n{=tByzb_<= zh=;b>>u8$eTKSIr(X+?DC*ar!9i{rVR?P7xca?WTjRwo+r zb7qcX``maBqx)yeaQf0YPth#b8|pGk8fe-^3}&lCYDu3MsCC95Zx24~Hf(Ez5U+#g zEu(SjuvffBSXIa~Ek_;`5L^dp&p=F&@`0-&=XV?h5}%<qwy@Kbm!wo;?J^GXRjTB*+-EeA(TVTyOnXX@E3mle~i}!adijo4Y9m7{Tf@m!8ED3iOi4lzFJMfUnY?T?%}YeMchV5@Qai4v z2Mo2}8)T7xKi~_Iy5xkm5m3fG;XBvPCuB+AE6$Cq^bibZ`#=zS}&@eyGC z(f~gy2Y1MtE)zdtN_q10-+$`a%}DPWJ%NLO%ztaz{jYDL{?G0?|8>3jpI4V$jU83| zHOw!)<|@odFwWNcOER0}(Gj$UAY*iJ7REHOBB+pPX4(V|{b4dJ4IND#R0m)wah#># zX1bth>5^Q=naL)vYZfe39QEvD0h8~P|Ga;J!P0EAyw~-PcoOJZ8nMewhx^>~Yp(O( zGA6+e_}|b!|B^>kNVxpUVq$~Se-s^b|8RL>G+_1Vc*J3!cA}fA;DPKUraR`bj@x6n zwTCLhdJU)aW5+!DT#u)P43*Gouip3e!%)62LgehDeVCKY(b2d?8_KJ0sm4UCNm!BO z=(4D0c8S*-0jPCVn_@p&tWKWPh|p%OU51twl`7A-7`Xt}PCPF%Y~H z29{iXl7yqQoq0v4U?PhrU$uL<3udxhmUxX!Ih>R5OPaiCH{c~A3!eX#%C?#9s#uHI-F_4!k;O z(tRqc^7=zr?009hn;EqkJDJM18VEanF1U90Udk3zQ93D5atnQ=Pqp@{-pJ)Ptek{| z3yDpXgfxl2;UdI3OXxGD&`coo{xHXZB2wDp=}Gy4r$b?5}T}=z1G8}!)j3v zgNk#!sq{{|2VSuKJ;|t|wC@)0QRB2Flj})n!WPp_l-(}!E&kD!!Z+AWqFO6YS)=+uSI-65{sf_aaDAJdZ+7GE&7> zr2ehQmcz6RkkKW zwYBN2m<)WcLWy_@UA6HuY|Y9c{!=n<6aixpP`-G27&=x}U zHy(vLo=Z!+2&2%THH!1J!UQo-X}45b8MePkFE;{Co<$xrP?9YKWG_hY9OH)j;_4P+ z&m#)p$1G3ihA0Nq^-1)RxiEUcE$JFzJABc1D9lEl(F@@XacVnm> zgW8M4ye;jAR0mb!tcTjl6G-x0U zxSjB05mK@oxEKB4{U+5`^zlt}G^NksD9=nUhv;DrtmHiiF}DakvaU0JR~|^aEK&Jz zw^%#y-9JO|{5$pyazT09>m|T8qriHz11su`!oi5LsKVv=y(=rNtQbBvP@KmRQkf zT6{zZkq#zw3;rcMTns`J*IhmC@^Vd&-Txm<&twgSo2$>B+h70MBE>Vsz;7Gm2xBJS zt@hwg)ohqY*%@D_BgSxr=NPWd9ed{Q({Q!erwk9Q;T2-wBxg(ktOHYDJewk|wO+T%s6y?GlU(+DZ`rKz6V) zC8GJAJm`ve7W5qYNS9+#(j}tEU^&ewl!_P!OqAw|Xx>hLM#d!_$7Gw71{ITks3Yjh zrZk(}6;RD*eFSr6){gEqFZ($y=c-OPr4AVS9dmyRD|-UJ4qaNlVlMB~E7owQ&36hG z8T;T3q;$qm%c@Dss;?B(MRnD8I6F5CX)a;1Hk2W>sTG=x2ixk63xK+HTax_1XbjKb z(-7%}!4@75VT-S)ukX?g4U;+hly3Z8#+^|9ccuLQERytJOS#f_kJb4bbn^e}vF2)8 zyQ^v9`nj3S=9u6}IcG8_NC)aOXG*gIL`WdP43nCTlVN8=QWD5=!N-zILXRv6QN3j03gO;CV>L16KC=lASgH03|< znEQS08O(sLM-guw^gH14M~sg}AT1%$E3Chw>4ho}A6*s`8b@46rI1FZ#5wX^a#Lb2 zIq{K0Hu1Vmu$YfQC|qzGOLELkraQNOj(;V~DoV#HN>eM!-YHJ4JvcqZ#KF7S^w-Ck zU#*9fx%x=FWj7x-z2p!g%f#c~=J@#N+xZBOVMEf9Rk&=%;BRQrZCINuHL!uj3RJi( zo5$cMDlcJ6|3`CmG@ZGzXv_CbYmt4iH^FlFVX+IcdZPCrCIALz{b@L!C%G3_dWF%GjXF9=6mEr(3gEYNRL%jjH6Th0nVOL7SCQrx26r6LK{D%eI^c?A5c9wWn{wn#UeRBodv; zl&M-uC$N8cpa3bpjKFk~Aoe>cQ>Wm#)9Hu_n1MX1R*v?rt!!xp$p<;xXzL9=0P<)E z-_Ph3oZr!nhaJ_P(I)ZLF@*HhD4w-orgAR3dm1APshQd>5kz2KpGws7C`wzIaW0$O z^h#u&c6_=XO=U9{o6{yKkJo(6_QI>!ag?KnX65ZdbJp0WYx(y~aUyKV8|=B3nOf`v zI#q?A-+p@TKrsfiL;bQ!p&z(1xwGR7`BBcz;i?@j!-Z>lYXwF%j}o5IBdcf zPJOg>Kjg<$GXuAMK97mOo5?Zd=82XYo?AG5SCSY%X#F9Kt`&j&=KkF-kYY9onqm)o zhM}Hu3sg+bo38njjTk7PBb(KBOcnUv7(B1O`#!YCP~eouQXnz#2ecnWgT7#AR|hTx zzq^55cguRh_@+_oxym8oniJEHoX~=|tyuXFJDBmq`1j>dTt4$Sm$F5SUx?~2?@+uV zfpNe4F0||={b?Mu_7ne9eIPw)9mVgJLhkD5?rwF3d)ZZkxZY@I+9z=J$nfRKQecB> zPma`z?3E)!m>_R;S6lz7-x?oZ<&o*iRJGKHUG-XdI}$R-67>t@Chrha5cz3HBv%#| zd!WUimisJR(P+eARU_;+wJ67efj^Sck|o6KQ{Kh5kL&{Z9`6d})fIFgM4ViqHO`(e zou!;Cua}>It-c3axnMFUj|QQ^B_RRlTi@H{Oq7#Ah9O$63uIh=7JJc>tbfSpt2TpMI{?S_ZrkEJ zwr$&XvSZt}Z6|xjwr$(CZQHh!oxJ?cJ?G;5-@Wghf4#2iRb9QRy4G4>_59`>bIdW| zjqYQEEbjV11Ra`?+RY@=tf*4Bp~K@GO36D_bD`)ZqKCO66^6VFTR^k>p;`PI(bW$I zl^^!{h=fS4ja_@ki5sc0(+klwXwR)XqQ=x$zjI6&GM-N4rk@D}f_q&&+-6Dg~GcU0Pa9zXf z8}96u%^2OK4to@4DsbhKonuAizCLFHSgHC!ZI`?qpwy z@GXQ9$p$UeD;DtC`PvW-S=Jr(HFT9E>ZV$tSA@? zBV3K?!L3@bpfLAPcp*O9kYhy4oYa@TS>lGv}ESv@l z$AsQJi!N%iY_brbvhU*yP=oeZl5a{uyd4h3TyfOvC}2kowWCPq-G#Dr z?XR^4VWpaeGZ}4%GVQSwiJ?OG)}rb0=t8Ad4rf*K-x^Bf6J*XNUs!>?;cR!}%y$A7 z0)b{j9=n46D}Jc8D3=CU@wWU*7e9lpOw&Me7($9m0;_WNIm)~PBR zR)8-C5-OoVN^1?b0@hQGG;!BU94vePhD4(vV9~r!KHTCqxU{)sNmz;nz`BPv8)53n zB>TC^4S-6Uj44jOTO27xxX-%2F=cuxuO>x3aoNx0X(EkGD{04R-=WOgB{QOEKZP|G_be}17Dk>ak zU?F7wj5%*HjGPi6XqztG)Yf}SX`UW2$q@dCr@JMvf%b(=?o^542 z@W~O(#m5=Pe|)AmuAlLAy8%WFS)$nI7>$gK#6~1WMnm?JRwl$}j1Z?KM}OH*&**iDh*HV=V>$j->m~!yC)s_1m=ptnH_N4&bhYFO`dM$V3C@D8XZp$I9TD*@0#_Tgzn2r?W^oY0G zcIZ~5?QQYGQcS2X-fO)fpM#&P_hTILY7bZN?)oR>Rep}1Fu3VwcDr9VdNJ(Gp(IDF zSh#FZ>^!)!+9f5bV7HGKS!sLWrb64mOn%tbtSZaLjdMiF>62nnId)gBb+EpYH6MjN z&)$LY_zX_FpZQrDBTKSRjgi8PY-dyO&<{`u={XAsgts3Y@qeI`Uj0VM)`aPWzR*v9 zTr)`dlBkWh{9*`k5uS)oy17aF_SkH_An=HSpKL4=e5jJ{3S@qTB_a-OB(6<5z#lOr zzah`_%|XZWXHQM4rjJt7?h}IN3Lb9=i&+A$(u=#OM&v|YfvPOs)=&(P22<9OtWqpu z(ytshA}afqj~9(`V1}J_wG(L#rH?c_x#Cpl^#Wo8azdpP@h1#<#Mk}+{;N`n>T8%S z{ieUqg8sj&R22Ww*>x_E5Q6D zjiA-`?X6DFF2^pjnqDougoh!=iTW%H-&+`)eIm2U6k$o#F=xFt3) zET<+=TNQrCDag4_jA=~SgIF*xGE8ae+6*bpFk2Z;r~Q zUlp7gRpj|0P50ZP(D0d4fD0+2frJj3kALH!2`&>Dh@B-l>NgG0>u(Dc3&N3Oi(|$* zNq#wrnG9%CI&ti!uwnBi(#6}X6f5%d)TC@xF&ed?o&hUZAT-3Ut?!VaY*E%kRPvd2 zR0#)9bOl1Q=w5rE8ealy6HpTd@OU%yDy-Ue#-Mre;^uJ}{S3%2q#%CQCZ?ItKt$PW z^&6G(vtQ<5v3;siRA%afZFQI0v!+)0(%YDU1107whmXj3#8L{3utHpQC$Kv?y{oJ|JlQJpJfJseI1xkN!N zQGZSr7(nW-y)9_#>r6w93OhwB2)7HFwp<{0%yEKamuAB;aL8uSfSGjrD*O&OYt&~Z z0Dp1Jn_4lo$Dk`4Qk_K24SkiO)ueZG zSbw10-$qBpBY01=!v=yvI7Zx@0)Kb`0UHuD0v}?v+L4J$%ixLNZ1qS+tc{J=gwMpx z;`UJ>R&0X2hjhF6Y^@uTycpyfzZllqa@;5sGXlJGm5hTA^pPwmBQ+BAFpSE+%SQtM zW)eQ+NVSziACp+S#)q94cMvYtCT=`r$5)Jb_HARKawOMG`*JHpH4XK}ddiUrkN``r zI4xFhe7sMW^G0$ZCV&!A`O_JF|=y%3NU6&gVP$9c&~ZEFzz(5p&`+ zpW!lIt>}P{YLI&FX;a<%4bwTpsXl)nlELCdbrYSfEB0KXDxJrMKb(5Y5z#z%B5~dF zp=k3|U*VFn>v`CFFk($+D&t5M&8W;;8iPJeSq@m>bo=?ybo(t4zu*lMnX2zOrM{AG zuV>8qEP!s`jeR$M-t(LwG1BJV0!$+62#6lUtd%jYAcQy6ku|s#aBY>jRPO|qQ~tSA z^EiGk`|NC>xdBo44h7XRtk))+7Pj~k){3@juxx%wGWrJ}8QwQ7ial@h6nEdK#1*QR4ZbT?CL%o+{oQxc9&SUp;X2Np0{(wl4SUdM8qD>50A+ zILd2RU4y4tD!Kl+Kg->hThIrpPVvE8ukYUgD#bXhsi5zPr^at4;D7X*{y8Q3*8r;j zO-l3+5+Ib_H$e3{HM!ZjI!U@}^n8_nsH`&yr1m?FW|suM1^_TojyOPtHeJ$Tv}*;7 zL{8(Ix$V`UQJOcWQN)_hw1h^IYi8js)wpkl(zsa0er7f-nmN0qk{Pz$>It!nGi2;= z?fZG3eeIihpE-X2NXw$(X8hhh#P-lZC__;;yjY8p3 z2j|!DNnHE!8Pqenh<;*ra0Wpv_QZN$eq|R){ol ztl+*jLH;BaOH#vpeq?YdRiw^{N4KZ5M?y1D7|_`H5es<1IF(j0$Ad+B8Cg+ta>K*W zGA?axF*P7|L+^l^!zIBYch~?uobH-YmmacKUVca=^^}$Ep08Z}846Oro%}!Ynk;$)^b zVB}V+4eu$j8A;$ZF8eTO01T_3ABoa_?*jqg%VhS1j?k=aWS;D3MYnbgTu_+pX8b1^JU{Y zn<`SM6;^SAG8w)TZ*`{8Yhw(^Hoa$;Lo!53%yXNyNm8-rN4gd219w%Jl2}6#N7`Lf z`XThC;iM)&-#!>7Awbse5hj56Tz)5 z;{85&SN#BSy^E|bb4H}Io;Jyn5zp^-e6Zi#(QvPqAH3wwOu(o*sAJse;uV8?pX1~E zHisO^Cm7;$!CW`EzeiQ8bKvm$f(xg?Mq^m^l=w%5b$`zg1uhQVeRL&S77mQ zhlaghfMLzqFZ#)DDe!nBiFmpFM5_~?)CAb4H`glHCxM^s_ZQO?&IYY3LcGNsisb31 zAH{O?FB%59Mo1rx7!q+$qr7cnv9+BmEAIerB2re`JjBrt3vv%n1*&AXm?|ruc=9iq zM$BeH2Jgn$}tb~a!w#rBiIm@Ge?fvYM@c4ipyxOe zo934Q#0@L70CPxjj+eR*es0t>Wx{PMDCJV0zvlO#Y_(A&DDzqg_Y3SCVwJ+n6Eibx zt`+thck*xE!Kader3UwKU#*IPqKcJ~L_0ZR-v z8~9_(2`r^;oLA&ai7c&7$yK<*9l7$VvOW1Z@~*4b`!`dL(+kR*DE8Su1EH7-3yGfF z2YOPk$J86!3gk-N9FAJyO>_OGd3~U+MPQzGI5!3_p7JnU4MDDYIiuM2bcoqa^|Ld_ zXc}xpfNe#Q6tSaUL-tKb5eBSNM8y+FBNob+OOuD%SRGYzv!%6|5*w3@)#&Fe7OR|$ z{i%QM<9l691vYx=DM?a_YAMYLmo9d2vx~AX8*z4Ig*!&}GX>!ZKZ+~4h}pv{Pcy^P zVOG0b;t4ow;e0v2q;DEar&UGrg;B^iS7iot=gTjfz~!2VoU(+hJ^4fyzAGW8qpsRMA0GA zAt1|}5?aW*38dtZ=lIo104E$ji-DMth9!Whn#hc~sjUZJXJPk{f5$VACfZnkn5@isLjT0!3 zS!tB^hE0aljO#M6-|`6#IIF>9G2Q%pZt&wi(>`Ut2K@Cgrpon_ZSND{FE4uEEOXz4 z(#u7ETArEuLJD@fB9=27SP{$g%~?IiN?bWt77)-WW{*7pTP?nIP}1HD)OGyHShIsY zi}Q*m-d}5SzYI!cSbqi#LeKBl=aUIoh%pHQFdZ=Xp`+btns8g4!`@-g!#z!f2lasw z%@RnBc*SznNnNQk;8Z3=+mZ41eM#^Rd3z>Iys9J4A#GFxaf`{uK=8>TzC(5^c0mFS zyNP89u*o_@`mcl%;0_|W!OPwo?h^9`SI;`6d}Z}E-%5A7VS`cDR)Dt4okjevrpsI>D?a8 zzJc*b2i4EA|DTw;|$1q2w`+D!dM1g zvTBpY$ES|mO$ANt^m@O2pMON)k;~|G9%NyD1g+d zCY!0N1Q~zO3fNe&3t*K)+avL`znS1v2qYh8ht($mSKSFaXOn;o>5#czszhdyfz3vA zVzeY4Ml0N$>OxYT`Ji#vnCkj`IUtv+Pa^-Cc>#Yb-H`P0t<%x_4aQuR(q&Bd<(+kC zdZG};-)mkJ{~m2pu^V3R{sQ=`FjuIfJ!SX?t%?!;rwonm{|H)%I2hYI8`~JV{{xXY2qX)!H>0x76G!eygZgHi4TS8hVI1-BqIVsi zfBv8sMf_HeK-$Y}RU1@SXV8yP=ham!U%w!)j-%HySH@61^Xl)S4+i({TUgN=iB|%F zGCo@~BeOUS546+qxOI#;28NGoT(U||bc(_u_>&?`;!NB0PDCY}@#>nx>CX z66kV*%1Pk4yLTgqC(&;E*Mo4WSs<(UzRj!e_kX0StCsd+-(URuOX>U5|2&{?WbA0@ zU~c!9xhEaJfuoayzM<2H(^Q{`D@cCndTJIoVkz? z{AE$vPrEj(P>!B8CpU&rH%TDSxHaBNo3*7~e?hd{q+)t4&z5)OWXH@qCn8EYJL5L` zR#t9$b6{}S5S+<-#c`Ua_4&i+IKxxs^W(kv{fCF%K+Ml>zuzKSeK~%)=!9+@peX7D zItY7p@Eim|f#~u#7SPoMbgcOT?TG#8LxW8@J7sbnP2QS#0}i=Y8eV#U~YquSu)Zc7D}ZE`bryb*$Nv zhasgkc7EX#^R%oVQKO?I{1k4P{JDy+9qeRu_j!l(HQbxEt%?tl0}IsEo#XUng;Bka z;8Atvj{U}F)DFIJo+#^Zbz;bvG{a7>l&&L$<{YtVEX>B%?WhY@V(H8#v(KpVN4Bca z>3vcbhHR0}g3U0+CA!*Oqte}c&Y7?YK-vjL+tr-umVIzuadLZ$XMf8*K+gLSrJo$SJ zPNgY>Sd>$QrFmG#N@ilEVnqFNZZ*}4y(}n>Ema1%Py+3_JJKlOY6`c^S^DU_yjuYD z&_r-Yg^bXPv9I=P$JXg+k$*r+s$EdF>mKza)UIz)2xY-eFtR7mNKJ~+>f_^AIfBB2 z`TB^sXW!fNaGsmc7606WJ;b6r^FDvn0F~BG;hu5ZaqK$G-+lX~mhq&yO10M+a18p% z!_#DrL$D!6`U}jsbI9nN!)MhS2(sN7s1X9u{jTOr(%9NqX zSC-iZYL}D%rXj`x+>d8hZ2t*%L#|8p@nQa}S2dN5uF{lsBu3zv=&B z$%!<%u`Sa7oI6b_Bn~^1DJf(`e&gNd(S4+8cIlQu&ncE{b_spcX5j|AO01zdpW5_f zO^#(IVY@Hnyewv6g+_yrks%5V72xF$r~?f@uM9_EU1R2rNl|^J zcd4qyd1AbS!W(4qTx!8aePle|nALrDx67@jzh}057OyCi4bm3Q*t2!m{rIn8{6ASa zDb8adQe;y*9CN^?GzUe291DHe7M_k`x^P+5Jngchq&kASq<>h9%&G3V7U=Lrn;EqY?0+((;o6rHWD^&Q+* z^sStY|KVn=qUorpjQlAR&rD_xX`WN~>nA{=xdsGUbs->4?#vo0a|3vuLmGCPqN90y zyv9vbSWXnv6#JA?N7o6vBJcq60*2@?o9~bPcs}7jOS}w~)?skmMwgG3oy$7g8lII* zuYaoXd_ilFl0R0$THtuGkr=2Aga+&pWJB3^hsC)s2Pyb^nS8jzkA=8s`rsKTn*z+l z5sL6k>5qiRqLo9=Yn&p&-#VfiDll-=zd4$uPEuzh;i~+>mHFgYiaH%TgAHh=EWl7E zTa0r=CS7`mb^YE9FdE%KZ$Pb9y{vUlA+fY+S$IoZFDFmg&0jM+Qz;@zrfxFXj3;T* zDFMu_j6)4#k`Dq5`MFKwW8X^6FkN=kOL*afYa(vFzqR6UslX~KIFu$L(q0XR%+iu( ze$w(2I*{3~o-`?{@C#buC*y@j5$;t!ocOMnZ0(;wP|xcxe{owz-`zc(Guynfj3NW(}kmiL6cu~cZ&BHOw{ zp}jz^PNB+gFYV~ta_!{(Fl?(2ye0x72&>j3(~LVx$XJP%S-RbRjnRf96L7&D{t;|* z`+m=nI65Z0Z-HCsDD&mIDLttKWq;5_<0(GdG&if0-&0znIOiYl?qDBm$cS6%>cW-A zhNQv|BQRqAr^|{^TdJ-{5Y%*}KR3DQIl$A?_)qqEKrcNCY>cK!Pc8wFo|IILCW})* zvdj4#MoGiVo81?VtKs;S0aJIfro6wWJzj@eu(erW5Ix@sityH^Rv-L<^!xXA-yS z@*Fq?o8L04Fl-)T*FRM7gBIDvJUY#K3F5dTg5CD$DegVEBSe1`LTF2y3#=3}=U&LC z#kg<>G|8F^Xqh>#jWy&O5xBY$ZudJj3Y4i}1S{?Qa?HV2i$AT{)2d%_Zz*$BRX$!D zoGLEkytkAaT=h1Nb<8Wf?<$M!3@3_Kb>7mo-%@s2I=yHE@vi+k0QBwL+ty}jv8=s! zTHN8efE<2ha|!LZH}X87a@(lC?CyJJ;I3MI(%r$jNb%?E+ooBV+yR&WMV=$aCeI_^ zDbOCOq7@d>5}3%eB7sc|UA8Hb2bu>O*l|_8>oTblQbnYEqj=g2(zGnxbWQ?%ON)7% zMYz2OU(s+%y#9)R%62F1X&!$8SDTs{Kzr{5vrN=04SPRxTJ_i~P4P|2FVO{8>8OVX zLGuFzo0#7$G1*~k|3qTmSA_jE#a^9$&C%6^*QFejh7DvqH`ulP*M3 zo0?s7HXvPr3(f-D6r6Tc6SSz|*uk?fA>1;lZ@pSKRl6{)@4e~}ZFoDa$;zJ8(_x%% zxXNs6Zchz!pEMaoqESC!4B8) z1)dG9V@;|Rn3Gq}J}AWlXUkMSs!Y{WK-lf>Zw+V2NU;*lZ*&z1>VFF8GXH-Ay0o*^ zcNY6^<3oQB?*EpodPh&n05ZT27l%-1hlO?hLTi~pkH#hN0b#a}&KhD=muRAKf$CMg z-vN4&8(J+?z0B=S9i902y8m7;r>ze(HVd081H(_+f;7Qw(VToyO4`qQ|R1$~1#pXFCG@4v6{B z_MhD;b1H@<2bhKMR|Ywf{IFS+c+r4w85^-o1DXq4a;qse5x)ZdlFuMyR$313dfcDBQGY$>nzF+|!SKJ=g9!0Q!)dCm+-%GI`cxE{g@CmQI@TQ;ETEt%}Ou|RQ$BGdxH9F z*L~Ap&ZhWQqTBv2YIOg+>ze*ci^Okg>R@d8J=OL1W%>7A_*?n*@2AXdO#eS8|84ae zm8NBp_>n)0+AjsPa{z_I@hkHhH1z~Keq%xe04v`9iaQC_=Q2-jXm4p34i){dUp5;k z57lakAt%QD7@XuAdogLI5XlSWXIoAE_RI9T_S~LYx83IR0;UIGf`CC=%iYUs5Mf3> zuo}rN(N7>agql8TB-wp!I^W33Hr89l;55-1hHF8hzSR&MK;VhU4OXShD!KVd4a!~f zr>Ds)h>B#nJjE+gQ(0fbrcHg`R$sdfbIl zR1f39eHdX&D)PMxfB6k6Zl0#oClKdTQ3kOvGI>1rV}Oy5N;14!ls3OQ0sa}YL&RwA zb&gW^*d&q*<^E`_tj4djPaD!sP;<%KC>x$ceoX$*hXqk;6zvEjF5ITSejtNp5aW&K z)jqT|AIgxEbEb5knGtgcbN_QLHt7 zg`h16C&}Lmrc(uQQn7ESMRt3VC)Fb^{ty2z0_ z8IYa~7*Jt z=u`4%ybwLC2&U0F^}{E|vN6W8zIid0@+0!4rUH-;{AtLn6e6)-S$Vgp_RhsGAZL~X ziJ5z*C2SG1-UH1sNf{!ioAFsiHiF778pv<4_>j{feU4@qAe^g`1uIkqt14ndSR`h% zDLv}Y@^8$uBXb%NR&ChQ0`a+U1qyKDrvr5eMbgxGN0KAnPox7&`75L@(8vAuDH6$H zitG5Y?s0tIX(|{vuY28i#W!_8|2xwC_i3xd|D!+9-^+1TODp7Ml+UWpbA8>H&MY}L zy|jj>s(w^6BvdT_TTp|#CIEk=_ESS{+$Dck*NjzlG@wvHJn{VkaXfKw;5Vi5?1DnX zPy%vm<>IgfKJzc7#5IY;yZp)NvdRT9<@M{SDjdNiw^;-8X&%R`)?=>Y4ae!u&q-h1 zFOFZ6FIj#Wcz{uOnIn?4bgdYCSAP3M&%)wSqoL~JQIZYNv$i27e`c z64OOjWBd@>XXy}nePNC$D3hu3V)rxP*9sZ@S$!Rc=r|{l2B)oCwz{j=?o;3r9u)IY zlJ#XX&9H+>G0blq@o|~K26O3bW`nlGQ9Ebqe2#ccLj^uo{R5}OC^I#NK1beg&$eKrQ$h2WZ7T3k>;;k;wy=Y2c*1A9EF^+hX0 zaMGP|!kv|>r*Q7*56t3Z#6}0ak7wL@7}|UekZluTWl*Ks* zz)*s**+EG(GATyfMxdMSsM1J$E!TjEJq0IBfC13gI!VdjZ+nl$&9e zew=5)MjUU>*At>}*}~=ukpwIyC|b(d4?3i z;ZpJRULtNtMQ1gSR*ljxLfnra0ML;DX_BX@Z{^#W+m;w|232w-O=|1r&g&*92g=rmNC_BlsVQ#l`+{!&q@C-gXVcM+VFtTU59tu36tLa9jEUkO66D)T!ll6 z@KITFj>W2|J~_Jn@ac7$R)T$mijwHNGPd4UJDgCen*cM(U7 zFtFJ|7GfQD(Yu9z6xet+Xu zKiL(2nkaWC5T7|i<;DQs)Q&YI*-j>>J&qkY18$G&rRwLN3UIH<6{?lSc#(nNzNmV& z6;jnmgF*k5e?PYld)m4UxEb|kbZxH}=cZ-xUEM9+b{aR)W#~Yc5aBK_qLZbE3&cU2 zf8S8gk#?Opi zhTBe8w6YhI^#F^C{dGsEZBNZtv+};;8GOkUFaHXIsK*S$$at4qODl+LanvJcASu~U{pnbii9 z?=vvW;2Ff;z%(g>z{Of`elF4M5X}yTU*|XH`%`hb5jbfD;}X7UIEA#KoTMks!WkBX_{6N)NOpxS z$)END@}?b>2+{37oeX|=O$fzmwn9So#xoS%Lvb<1X1FtYM2~8hr*p4 z##%pG6#28d2_n?Uiejr$syAo}B~uzXmy60$&~#!^zs6m-BwHG(xG=My3-vX><~5xu zoC6W-_6_`5`}n*rN${2gt$l#PERJidS}wk^E*5(z2V&7U>RulCWU2Bnfk&@|Vcwbt z3~Yjjd*+0(vxZ%69MW2$Zia;8oS^WWpmEvDUG$}#1k$Z1G+Yg$n^6$k7%e_#w=^N5 zQXU2_FA{utQCktXoa7c1ZRr~)>-7|iRdiGR!ihid>R8?i6sPUM{Dg{%gPP6f(+kt8 zRFn0EG&?PnaF%BpFHz6au<@3?f36u{eIY)`5B%!9mm1vp`kVGtGAD;|+xJ-1_Wwx4 zmHwA921R!pLo)|k8*>k1qyHwcu1r?9Ll#CK?k4p#PK^lx21bApje;5VBggOkf#_g^ zh);~3V93aIA(N5`!Bo${k8lep+W{|oBSJ&7GpMFPqI{#5DEoF)-t}5$%d6(IePP6O zdMT`Up#OF6o%!keC;jv)bxQWj>lx@rMIc?i99Xo7J_)zTtbN?DxJ(Q;zeC)CcwDhq z7O8vCfqI-Gaj|$7k$ctwNF18D4xxMM0rV&padljW$Q|b>7O|=L7BPqD9qQ;h@pVjx z?+(uT;|UA*o%;4%bE<#iK1A`hTex@NUT$XT%@F* zjF~W2F|Yf1(=N@zHV5$Kxhw}ydOi(2agrj1^mH89Vz<7!FSAft`vt>!4HF66hAbHlh;Hs0vIk-jQx87 zEe0?o$5iTsaTbjThhGPewADGx^{Wm%rUpq}4WL25$_K29IpP+z`<1vNS81Z%e;*}U zC{9M4sl^u(My&>?#`fLbhC+|$J7^_GDseA|xnd|eDL2)Gc`#F*v%e-bcG+|a_LuE3 zFJAV;7GcegQM_=$CL~=t*;MW_os3M2h?)QwmpKO2>uZ!%t+{mPM$Y}=wD9q>D=E1w z-(bl`9tMRqjG zFmV<+KjhQlCy;Ec=d9YOuYaaZTTIp%VXa5KJpJ(&<2XKHqiZ)l%iC;FE@Jz5$VO~d zuu092y(Ff`ui_^?L)>f9qU%>#Bkc#K*Z$oW;1bgiUlUss=M>`LK z4p`0LGi7Ga?nfrrSw947(;&ca*p`E`T<{dgqmc!UQ7hzy)7jw|$>0z_(tu7;{C1Ae zQUsIP?{#uph0S2^kNgGhVRJe9(iH_9%V)I4(xr1-rOl%5jzj~FTyouMZFvcpUBM?2 zZFxzUT_GopJ6jQlJbO&K|zy2jx;RAT&I|#!kZxnwS#OoTr%O+!o)_iAN1xawTPEJp^gV!4^z~rOY z*{oLo1xxvAdc)-5L*an-zC*CRey(59rW?`_Bl@Ns;`B43Aw={IhNl~ipHuCZlURro zR`f$Kyf`Wm%~9;9(6p{_Ob}!YGQk`o?x`(-f4UGI148m`E_A83ggwM$vyXk$FfMpSGCuPIQvlYGP#<$)q zOXi=_{g2`Bo5*G@UF>$wjaXo+y1LjM9v}!*dI-2s0KVfJ<-k-oYTz&7t;^WU4%lcZ zkN_^|s|xtF%u4hyl&kbgwL~*LPI#6?5gyU`2z=M`GEOM#F&-6qL0!K!e44A_aao5q zb%sAd{;G_xJ>W{LzX|pE$p5)A{%3Zjz`wN5sT!M`nmHL83A=pvasDQ|_-_@lbM&-C z|4;a#?$X9}6{syQkWTh*!At}N0`8yP9l_A_5Mg+*pxt!7 z?$p;8FHf+Vfj&JOJCPI%vaZA&V8=%3rcq~slxp2dTmhZL$X*V8R;4+o66><2rni`P zc8AxB)^We9rR@ZE`}$-V@Mh&pHCO{CV@(ucA$tM>O?xEb8yPIkV|(G^k7WLq6N-yM zr;mp^RV;AVFT}@V4W9_kN1e=<_qE2rq}`XXfS>5O&9fV99Ia$#+OivQ zFk%`-jWTF$VKRnsXg+|e=$0@0VxDhx#{3vb^4ouVA{dE95%ABKIn7Mgv3U8Mnhu|o z*gagvC(rx(NIl;5{PB+il4T%E3YDhwy;Coh@Y4klV9Jg%?hE=IJW&|EN+P4S0cJhx zgo4*V>U?Dn)f$a6%(cQQLw{|+^bXaU$G_24B>u4GGJP+UDDdm5T(W&G+Pk{&ys7GZ>8hSa-F$q?{aRh& zqL})W4tUdX%KJI%o$oly^Qx8ic|3U`xf=dMJ0? z*~W+B5961thd=dp+sR$Nu}5HA?Nj|9vV+}w+uW#d$xj?KkXh1d|wBhw_7kpuPE`tAyM-TBc6MJhj#(^ z>vS0WJ*6qWyTrH0z<6; z4vzw+6iEADBH8I$leP1Q_m6ZSue@>m(xYyopVu7+&Rj1I`7g1fF*=9^3CsjVs)%~K zVpi~5urS?^$6M-`k=bRGP+hRpL5KT2F{{+jnITc5C-gfdOgup7=!Tb=LO{Q5mg4e* zIjpFYi2TXu>E!uK5_F>WTe3o3(M8=5<`L-($B2g@qzeJa+_@g5#%%;;pHlLTuj@JF z`;Yw}Q9q>3Y|J{Oqygpenp1%d%k)gjdt--*3{X9EX>p7x21%9g0GrQ6ACd~PFfD35 zCi@K{&M-2yDRz(Od(v^Z+~lYqi-#T3Q`y`O`qYWoqDkWHiHMLMX61!~>92UBw zRwcD1zK2L$XF%mqmmN9B^D+8?PeMsnB~A23>Gy9^vJPmfDT8VaZ(O2I8zZr2wi-rt z&6@sXCQ6>v00lo@)Hri@s=$jcF*>M7xE+iQo+mxH)V9n(KbgZ z?fQ{VPo03Tr1mA%4aSYZhTxoGV@%>Cz6%B98L2J7BLMxm6-dUEjy5(BQ5CrRm zjM{;PIleKD)Hu+{Ft{RKzaAd!Dwn%HhHkh_Sv`O^})O+KG>Z)3-z z?06*^s)ECJo_wKdmU9o%%qJAeujVChcDrcTd@W};{ssB?T}iWZ1dD|`D)OaVuOr98R+8MCNLM%%he{kvkcbfYP7Lds|lkg zq8vyGI8wwMT%N5qtYqKDn{)LN3sXumdbj=rgp$;B9NSt=lG8^9z#RutH|>bQ zsl1ErNG@U|yHlz&fNK3|0z!ZH>7-M#KCUj+Mq} zd{G0hqn8EdgG!`U3eBmLo9y#K0HmhY)7O7UNtfxmcROK5y(}%w1op4|<7d8EZO`?K z(uT=umiA>8?$FAUWxX?nMt4eut$wq7_3Dwk4eDAL&IicT9_{_n=4pxNRrI^~$?n>DQ+U3GDr;B3piM}2m|J1UGs^Afx3KRX(EJBO@@X!b z99C9O+)NhQj)L>nieLKL3d4>?@A#t#NHS>R3;Wsax>;YoTK}^z7?&Oy8fmj#E8~Qr zg4PgrZ}CdY_Go(^qW49?wvpxYr5Pu=+{Mtrto%0-;UOcwW)8S&0}zv(nN4|cV*X||BD zqIQeTq2!K%Su=(npOpt~b@SRrS8|Ith9f&RD!q1u>Rpx`Js%$Oqx<{$tv;`d*O0t_ zbPX9WBN{hrm~s=uXN*t}ag~ov5QZ)#V}JH@Z~qiz2P|aQX~|AYJz%%L9~%w|_g)45 zPRP=gw#~TUg6!~T@1hsNBUl7Nx1a*2J3)w8KcB0x;=5M>!)kSi9p5LIW z9Ou}RaLX)) zJ|8BZ$R-^hj`yb^k-&!7Fxn=Ik8K6SeqdL z7J?Z|go2kX=}Wu(8qvdMK)ixjwe>eadby*+YsS zlO%9Lp0+PCM=kq2kk#;VSBqPe)kal=%3EYPLH~=jcZ{(u(6WW=lx_2rZQHhO+qP}n zwr!iIY}?j(b^G3zba(RIq`%k6PWF$TtRFjbO^h+-m}n{Dwr%AxePD9 zC_b}O76aZP{+-e?QRIy5^dp0WZ!qSWb~8*6ZCg}~n^(-sZ#Z#g)q97X(NmQ*eIAfi zy?q`~RT_FgES^!T_oh{Z=;UfW35BRmP+U!Tj%O-V1wd9$)@>H^3a`RF`BO* zzj1^DLZoDs9=t$4q-4YXw4M~^>{PdC^BQyxy(8_-E#4+&L-xj8<@$|!Q+#5!yx0+m zV_N18NXPDzNm>$xNuR+>S|bjXH02hnK)5Qd_b)7b90_gm249QT`yb(=dQR0M=3WpF zNtz13;YycFp4LkNLo3oerMn$Li5~BMUylJ3P`|=O4Uz zn=o260%;L{_Ou_+yfp@Dk8MrdQO%SeD!8{QPX%vDU*E2g3qi%BCcT!*7DnX+NXQ!E zW>Yy>8E@Aor_o&i?UAHArY9$)p7}JYWb8)_Iyh8%*8?B^oT$5Dew>w>%B7W<^7jhs znHr7&@owyvwIH+lg9QZASK*bv!k+0}KZas~TV~P2Y6jZH7<1c&)VB6(n_bkcHp%bA z+3$rq} zI{LM)|NNHfSIW`1F>*^lynBSb`xQ>u)dy^2@7Fqsu$?N=2gTMGN#ErL;bz#l+kQw} z*>dee17@^kd>?a<=L^_eTJQVgoZWnhg1vf>vQ55;njQ3Qp+E01ZdfDOWrirJeMay) z`C}uh>-FJ2!tS-EW5xOc(Pi z3DFs>%ZDoUeMQ|gy+-jTl{T8&8>fG66dM+zJ{HZ!={x|fo%lQbS>E`yHl3m{V9B=m z0+Jo5UwGxA9SPUAg_Lsj{84jH4SB}h@aYGpBKq1w3g*9wlrs9K=1Ie?Mb6(z={LFIwMX5l7(< z8p9>EHiITo{RJx>{6}b{IWdwG zG!wKn{MFJiVjLeD2mViZjDeNHI--U#Vey1EkruY#Z9bo@b0A?NF&2j~lxN2|D_3MaqQ3JR|&mecS%AS5x;$a8NWdo?`jd!M~BiU zvJ%X9NlFA8f=uWn5lC|K_*kMJ8Eg<1#yvPEJiuJVE#|GI=5tCCk&o?~(~DZns!7O9 zV8=+l|3lovKO{@f{DbBA{piyFzwsR2|CgBkzX%SLR@R^7zdN?LJ5#spzXsq*_`HBY zKmmu*D~LoO;29xe$0!rj#*JS6=m)3R9{7ixS-p!)Hhz|0y)iVan^o4$Dy3oM3=NwL zSiIX^tUEO|Ki020E4Qv}T01p8XR>2$Lm(jJGj?cSIA3PEPd;Z4avW(&zaLk{0bmLy z+@0a?bHSQlyRbNK%dkf2s|`ektH3CFcKwlJ?`BE4Rwoum?}T%5oEC3^6?F~H#Y=Jw z&L^d~rw6fRbMJQ5xki^%-L8_rbca{c{$RuDo;2Iu-b&-BHeYmB?75L%~c~6MAd6bm5|>De7&`J5Ac{~U9_O`fX9 z&?1 z@!B2n7tzlTHEQ_LNRlZ@;*1>SFZHgqBu0FF976c02PskqpO1vBh`_uLcX~l{k6xwU zDvh0vBv%Tmjk}39u_c| zGw@5hn>%o0J;QaOHhbmKrcf7IAfa^!{c66@V>OHv#A5wmJpNsd02%ks#o%2%J)(+i znaIjYELObPSIpFLbddUNf7jR4C`6+?Z&B&MxY$6L)alc>oR#mF3^&HI;gEW*S{bkX zY-F$jw+MsLDPbbuMXKKPB|&}s`;6SlC;t9khdCF~S|atBpGI0N+*Op+P;`=C11Z_= zCUUrN)HGmA#ktQfPf4#Zms+#fp~soKdT);g)~485w3gAq!x(t>;N#ABO*j7Vdc-*K0)PbU-p}>U#49#V+OYt z60916B4T~=&7$k0?EMI|TOu_|=FI4a&Z9ipO+`C}9#%u>#NE!@;tGo;N0Etnxo3V^ zX{6x}@T*1qV22T(^FF_GHf4Ln#^BdVLQji4rSKwx473L?st1u-S-4q*ur!~96yOr+ zGG04J$2AN+e2Gx6s8JVnfEL(iyRj2|MhoQHqg+f(U4nyG`Im zk(_{Psw#9;(xhofb5bxOW|X|LP=D6t#Zgzp&a{orj*S?Y*l+wSo+}fRuP{rn(w30s z<vjqkI2gIx6ZDH@OuqZu}F z!E_hx0YX=8$6P9OTw9$}D@du%gd+Z$uG?xOO5J4aPs=9_JyV&=wD?sq-;&F*>TOMOU2MXygcX07Oub)99~{3N|I2`KwmR9R(UX4jvpis<2z)7^0#vDuU$9a z6MH4)?Q!GHRT?c&JBexghufz;Vb&}A3DD+%kKQV8j+Qpj2ol`t=57K7wmjjdG5MY%sFC1iArdlh#m^ZuuyFz5%sD_l|tbmzI`7|UhsGew>q0Oki8@- zi73M47@|pc673|*VGre@Gtz5S#~>MPaiNhz8q!Mey!Q2NLP*I>yZl^5d$xBp{wN-wN(JyA_U3GIW@KL{|tU`9)MmD?p97%oOe8LiJ1#AJVq6HuGn~|Y09m+ADX&6OO=!<=O5z_ZOL}D zLs1P-w2dWPx-|}Hu*d~X@nGu^}$}tXkr>xan^RUv2$K0nQwF~2|W6Cao?rSgq zS>ar5cD9pL)it%8-EH=s&hGw6W&PjB&pj;uC5%|U5X)F-X~oPuG_@fVA6_=UyqCIL zPi%Id2^vRou;dKU=TNwn+6N19@`XU^%f%YY>DH9QSWvteDW)>z>u*hl5(Pi66K5eT#41x@ zZ{OG^8VR_T#P4|c#Vy?$cD#PtE>A~w`IIge&a-eN@o`I?vPDL&49Jmzd3!(>0(Z`e zvc#R~7eUaf=p3#ft^^A#N%Ta-H=7i6iAuyhX1Laiq+#;Z(%E<$%-Uw5C%FU_dwh#} z6u_0f;6JB)r1RRly-t@!?yMeF?zGb%4aZ+(hZRyz_^MWK#U9kYg%MP}N+oBSBBo{A zi|8flgjPboYWNU_psjKfIYSR~V~{a-Ku~T%WRg<0L-nHo5=P0c^l-QA0{_Z2a>%(u zKO5R*`8n=I4W@@DyGyx(MTs?NnORU>Ubil#3`+Dku zx-&P<0WvSL-LQ3iYTIMKeNwZ<2z=LMiO5eE-f{!s`C9$LP2*sX+y_9YERj#(NBwQp zM=EwsDn1Do7fYVBtJnr0DleSej0=~Kkt+-zYlOdJgTE6)CXaDw$fUq(OwgN4by#GJ zLkOpoaOlSdyTh^2Z+p_;zg}gi{OO`Hbn~0pVV+x@E0@617ej~Zr*;oga0%jirx2X5 zEA3ONg(@O$85@x&nB-S7UQHm6hDs}7PW?^#8jPU3f!h+krpZvjC~ z@B4+cYNCHZzuK45zt}ov>J`F5y8Xj=Sll;iPD2<#1Kp7!_5pVv;HHM)SU$ zRh2Q40qyGUE5xH!z$ekhw@=nYgsjnlETJwDQ>E!(WNy{%*9B$i-~{iizPvyMkwMHq zsGGjLfZDuVT~fu1$cyHUL>2i&QIEFw3AY0y8@}avvPH(}4+R#pSAf_7ZfV_EHilQA z4~oVs?}N5PpmlH8{-smKYzzZe%C5xB&c0resnq*$sBO213L7Q5_r&>S5uRN(U=Gai zKDI&VF=o+ChTv@mzoH+A-iKlU#}au_FAQxEx*BPNkicPESS9L4osE<-13@W(STZA3 zUwpO7FaNO8G%Jo_5Az+;P@Q3nu={&k;$w~A%S6v}nu@%+!kujN`-h=<(NODB2#H(b zLZ#J48M$|9Kfoag6=aa@MQTldY18>0#wdsJ zRBiyf;V(byn9!O9p@=n9K9)djK-}lPjo7dccf+$7!cj*nT2`oWiH8!n!BF&nGO2gS z<+}nPUT}^*B(o=yglHXKl7`-vo=WQ{VN7h7$&0zv`71Q@R;Zq*^~#Bq1m)ZNyK#lu zz?8F>dy#Hf`OtNyC)ARSlZ($aibwjHTnc+IbL{zT(X5Pd?Jsk`L%>N8qok zf|#5d+TMb?)`)55F&ax6)St6p^{#Z&Vy4XDBWaf!5>+XA=cZ!}Lgt^?Lt1%ZVW4)!pj=QrVYaEs|yV|hD9jS4XM(T_x$LGY-DE~~@wMoH(oW|p(?%4x7fmT3DgEHrdCuBOdX zWFz_lD0gKgBR&)piA}^sBPt#!l!WH)lKcf554L%?iTk9rRj`hx$*sKPQF>L*t;`4w zQMcj%R1G(Tq+!3|IYd;f?LJgx{2j4&u#duURcW-olb_O)8nL6fMig7|fJ2n^unP*c z{*Mn5rlNcYAd7f+E*V(1dMMl+M6#bRJRU>g!-{ioeM0wutk2 zvm!}F^07|FtC9rzu#f0S+(+42fI(O<~FT;G-q(QQua>Quz|(Re@2TO_V%DcOn@p`-28Hegsw%`((3Y ziscE_%8dNtWX+$m^-^QxU3o8HJYrRfPghDtl2P-KUvf4iaa=ae93{KS)v}`0uH4P+ z^`%Sw#Y=>`=6v-IdgXb%>$WjD7yyWnghL%5|y-h0-hb`@WVMi?di%jV1I z#vi>-GSeM<7#%xwd%WMFcPUa9P6v~jsHD!IbP=MN?udtFDVYjsujlCOru$$(y;V9G zvP{X4&u3prTCuNLs-NakZ5kCmk|}sh!f4%L`s1o4RX1;1a>4&1`0m3yHeIi6x=(qR zf8t`mX)@@IQGw-KJ;-@n7pCIuPiI^}`i}4M|2D&ce(E@3rQY6ikyLA0vGKIgn~z^^ zLJ8t(!X&8kUV}I)sq?z#X~hNKLA4>np?^1goIisUw6c^Ce=i0O339?Rh_uSrpj5$7 z3nfwCLipiw;uQ_WT8cGOtuZLZT3zy2#f3nokXb6Qnk}wgDmsa#JJ4E|g9$I^9w;f& zd&aYCD%e{1bvg)HyXn+Wx(d-JDxJABq(HkFp^^T^`NeQ&Py>lJ2Df|c9dM_yVHfQc>%_jxxo0iVYAXIoo(9U3G00Dtz+LT`AiTtqbk z1qH_=jbYgX2QBi5p>l2A&m_A0&U^}1c z%l*s+Hto}!N?s^r?mfqZ)Uk|boQ1ECY)NbQi_~6%oPa5SD|^lkp)@=)ap8eYP>fVc zdu#C_rYEH0aN%|6h=AD2hLAoDeVJE)7K?jkJEVTHI3y}RDO+&iLw$|TVVxYg$*bs6 zU&+{9Rz18yH!LZcP9nnqp+m@{37ot+96UPS1&3WhyGS{(i)jR+*z80o>4AY{e1vdo z)GVhcnMZ4M-Xh|8K}~9(G7OhHj7j$f?0!{j_F0e^guCDv1%ho@_XKbau)rHp``H6R+{a)vp+Ws3#8`!QxNafGD`#QEA%~)) z{9A(>&}}RPFadLni1nTG=27a9_Hhl3g>pi=!=m#Di0NpT(lrx3LQE#jd^zr|(!9Z4 z=;He$xpU##L>esp4^2Z>XkCF~~Shb?FQlhD9vlM)?5RBOw3;givZ2N*D-UUykf9EBuO#d2k1R6XEn!yXo~o z)XDotZS4*Kl|Ftbbj|4`Z!W2z?l=7}cCBG%pcR-+y}27n;=<6M?EMvRV>fwJVOuTg zuk@wzLiT6XXl~s{mJZpfd}uMgl{f&V=LnI}`UBRL)%~}jXYNvgKQzXDr9KfiuDGss z7dE1;OEMz=#*seRDK>P=6_|Gi{LvhiXK00D$*(mc`*N$jdAgqNVZP(y)Q6Pp6Xbf2jO%H|$ ze7u{%%?{pzf>LB=vdk70MKKMWf_WG ze@*E99gSV|+NPvO**iMpQ9NR41GxfxIH7xzY*6p-V_#K$GaSLa2?FSM+x_^0bm16| z2jqOPv;b5_$A?C!OUBjGq2VHBQnaF-eWpFf4}EtjQt<}1K*R-PkCYjb@@+XGtpaU< ziU!Sq<5y|wUthc>I+T{WdA%X=JA%b3%j0grQpT=u!QryjoI1R?VPlF2MLYdcy`xg^ zf&|Aj<|PbZ2J39G4pb>~AX-J>NH27PSt6D=jX_QZl;X>hZBm^nV$=&!UyNl1bK?uF z1@#I2(hc%cpP>Ipp{KzT_%uJU>ilnGmGghzz(^Y#{hTTNXITDGkyJ$DhyMl@0362z z@7XCR^Y@D+=#fJfpA!o+gTE_a4k8Zi}gwg5pmKBjW zkd`*lSbJnuO)+LktGS4rJaA>Bc&twxg$3pu$hgRn(!}tP-kWRAaNdW{S=;a|lMZJc z9@7m5+Xa?HSXLTOMlrSb@5XXVLM;$j;?;b>n}Uzr#}E;%XZrBS8a20>LwZi_zIFXx zxLLmPkXSX>=U9N>N?skT{7r6YZt_SZTY{a*N$|sOCjz?9k!D#*pc7oFwP0DwDG56o zKCChVOWDvc7@}MK#vX9%5=zH!hnd~=B|SQGNNEM!B>9DT?f28gXZACDA$ zh86qQAd9d{YD$j74Z~Z3TV+-y6gg^VR}K~WNLe=dA$aBH2S$ypiUm4Nt^Y7l^+5r25_Bz3q8oZH(3s-XxNU%+-KxR=VY%6JFs45@iR{QEpJ=vL79D@ zT3p%lLS>5O1jK$@c$$}>{Fsn_m@A=!i3#dQ&6PQIcgKUcRUpvh2QwiL#1yDN@K3`o zMD4*(b2GWjd%g#z%H1q@!bSfYrdn9(^-Hlh1&&Unak7AlYOc+<5!#?w3+3jiPLe=1oiASkzBpM3u+S)%wgqVkkW zFa^!bIgF!@v+XO6Ul%X2xd6*^H3LHmC@@-$c3T55Aq$4(M$bw8&R?uvxt{o{g0_^B zMVKxhq~*`Bf$a!zz<~#n#5&Ri+VNHoTXAXbys&Od3AwMk+u0y!lC+kyQr2S%rN^l%~rQ2S&N%IET9r~auXTo0fGFo^6khdsB5HP2lu z1Q05z*t!^o#?YIm;b>*!%JB=hA4t%M?Z1lbcNQsbu_ z#!4C0wjxN4-ldL<*+(HZXMb8LC4Tf$qXz|}LN_@91i2JQ!Hy6r-N*96$gJV?z*rQN(5;#qwklBXDgd$yJ9G?~(+ zhTg(kj1=#%;FLo9c6+-p_ELRVSPjqqR6^3sBt0)beJ`Q$*CHG|1%o2z!_$2(nnMhP z4zV|Mr`lZxdy=>9A;5e@d)20Mf|>=Z^92hgROgz>v-8-Db-ksp zX+b|HeZ1}Ho8{Q^knL#mywdCY3ekt#mBP;%QxZQSc7N5I=i}f^HK@-NNDw1=78FCz zjyJt)oK)nb09$$}w@hDCNKi-I1T^YYdiC4M%eF!Z8J-kmUBsI?n^h9Vx7#!K*!^($?TX0+xcj5 zQ?1cV4W^qQz>i5EIqEc3Da&mdHJ@sco!|_N=^ILTL8UgcP?cS+@GRj@__S>S{mnaA z2<#~vA=v_{H-ANEu0@nFY~R5K_uvW+8K@$hS;)(bE8(D2>WPhg0>Kuo4QMy5=0XV0 zs?PX`G+?vM@-h%}$+ZMbMguDkmlidOajbzoRRZM*mXQsH$*rL*Y4A;F>srj|MSuP8$=>^tKL5+U5jSyA`o3TogeG}~#C%;is&r+Y{Fg+yU|)uNppE81y9q~B<7A;{ zq8m2-L$xUL!~CdfTSCTifE+ucvtn@17h}hHrdu)>^wkhpppAL!U4Rg$EM_`?ai9}A z;<}eTj2|8EE=m@w-7iK^le-EgFS)$?-4>DK0W!Mk)4yd1r%C+C*u8Y+m}~Bp^BRFK zPlh|xuL8x_9fbVNG?m?Jpn#&de9l=H2^Z_ij@(e1$RsO|6~P6%s&0rfYV?%RIT`WU zwH8D+h&GQqE9Tq|T1U1KfSseeD3n0q)xh^oHM;kR%)|Q(w)Z*o-34JsZm?u0wvU_Lf4Z%ST^DDWX;X_Zdb0jC6 zbGE;eFGwFZgEP&>)1r*6;SY?81yE<^9@ms>J~C=PZlP!2=JI>T=i}1~ThcIv7uUmP z1WjYn)6|EhH4`(bKn)B*EXEsyfWNF4#T2YFDwB|;kFf7A$XdM`McjR~k4*2hvXXPf z{b>|u$U>U5dQ49k6j-FJX>XtfIjk@--E{OcjdudWR6f&W?hn`4KCo+ZHXwo@&~E)T^183kPve zXma>o(bPH$pm1m`r>v#HlS!`&`*c{XgL+%i_31E4molG{df5nknAKLQ>{8aoLpnig z<`iCiPaN+%Jo4(1yrIJ)Pk61pK|#CoPz?zJsN)!#}I>w3??AwlT`z z>8a}(6PJV%^8}O30DjGewI(ZtbpUtd^`Hg5jF6)05)l0kPVo>MlSS_!6-<^FQ<1oY6D^mFG8e# z5n(xW`yNKm=^R!FEEglYateILxSFLHF&Bd!;$Sq2c!lGJcyq4VCFP?Vg&G9;q`*!t z!~22w)_PozH}Kly z_<>GIKsb-FytEh%Rc+3{t&8sUsYh3FTFgPHaAq6@Vv;8xWUX+3H<8KG+%F(c%MzLj z7haUv#1=AZ_)PJGQ8f8;nyrN`hy-$+qcUL3JOE(&^O8u8rvdcv_GnvEv=Ly?`JZG=sCzGjRCC`C!jYPGPVWN zY;qrPwB@4EAFHB-Sl8?rhY@rYR>kMdh&-@4U59H-Eb8Oi=H%BDrjb^Ke~DEM@C2-h zX1F^w7$yZY63jU#v;5@k40iPOjt>g%EGvDP2<_;7=`ee%*}dO>Z8>7X;e(t-#37fa z{L2Nvg+tEN1`iNyTmGyDGo{(bViaqsL^*q?EbRsIZlqP+e&>pGNEg9|`rbj&@o{%R z7_y0+1M_L(36nt159DXkBd3;w*jdy1iWrJep-(~v!h(W1`xf`-rQ z(Oy@NCNQ=(G+8i^uN}spasa?uN&r`w)omAKz;S+(Rhv3w#Y6SXTv^kDKWy|eGrYUx z9`<6tI5o`nkj@Q--q%<^PiQ?{-3jc{!Q&T35ogr%~UpETDTKVgS*R-~j-(>~&_tD9EAvyv{{=;LNmigiAi@sSrO z<5uxEu@ggX%jE%%g}Rtz-q6s-dXZq#ylt7d73{zEbl-@x~2A|q}I5*`HJompDQ7g)y5WXb|@iZddDy`O9 zhOW+%4Rlvp-c}aUG|3*@*J=)mRK_9<%#>gFd(Jk~`81cKKOigc5)F6)LCPGehD|BR zAJ1g90Z*~cYbB-*zPHlQx^lYeCIH=(=&B`&=&_m@#id|HS3b+XnKxyU=tnz(n@8&D zw71tI>+rFbA7dIlLR2!^VzNpHHgl8fHw_$bP~WPxN5O`oRK_6jQgVbtA{2_+dnOYm z4UZBRha}XmW4(H{Lfke&cyndk7t`j$Mw5`5V5?_1?bC78-ACGmVHs0(@paUgC#x+> zmqv*+GX?b@VC@jqhtEE+-NZNhXV+7V@R4wiz3w`CHmNO^Iq=z&!oB5|r)ZsFzt8ja zFjVxJouN(VX>Aek-wUZss>z$xA2>{H9F85U-WanWs@wl$OtNigd^}XI$z~<3LAVoM z)%ZoK^iAwCCG8U4KFJDZ3(!+bnzfrj7WeDfogkyi=3kZ(mt>Dfw3)Z#(b!{04qens zbwN-LWzO@PR=|WoQQuKnB@$jP#>ojeGDAE7TbAxZE=%i+*G+H--|HoF1xHkc8Q;#` z(;(WjMhtn%5#S26yU~Vs%px|XDDyQFhNz+;NY|-kniH#6&Oq-BHzh!1PNWsi2sa_U z{bfEkmBXkiV+?Pb>%ObiH75}7{G%B9XK{yjct1esF18j#kTf?491b#>N=jj1B zMFmTes0H%q0ipn_EUjY#lhbc_h2Gq6WY=>5l^Rij#00$Q#ZJO|aKGu!QB?u1lBp9!D6frDWO^mqFsjL)j)RJAC(7O&)VQ zj(qoYPL^Y;_w__pr$?socisRuF3+rFr9tl~EpLzo#I(d*t&%(5fCI!Q)92J_#)vr> zLiPPScg;wD!XwHMNp5B_U9!-e(q3mneXDwNd4qH^jzzt$bN0}gliVh2ARN3^x$YC% zEM@ZmH%vT;Da=kZag$eIz-6r(%{Pqne&#B{HxTEr?>^?8wN%*O0sOliHkzJ5Qlek8 z;siR$L|w$~Aj%2B#tEuri4j30dnFQ9B^kQVu?~U1L z`pm`16{t=L>Iys(Kg>;r>+nSC7=!IB{CRddsVW?Pp5N~(yxdxetNon~Azu+p1(GM> ztVRJsZlIFSuMs`1Kv(chSyK` z7DR1AaQsTNPgHii@F?kU#NBwm?E{CE*Q)E1gm-iG!l8 zL0Z4Su(@!Dk+o)uC7Z!t-E4?OV_)iOC826Eib_3u*%jk$3V(V*`@}|ayaj!3LRoe~ zX0{5M;&DgswJBe>MsAR!_r(-p;!SNcNnZfA!Xfgwi=+h&agz9O;I>0MQ(6X<9<9g? z^VWSJH%$RTTs6zVcB1YtB_7(DQCR9{Z)z|o{j-9l$8*yMtzcPX_XW4StlVB{1nK|Q zzwBt3v_hwK!NkL}Fk|E8h3<-phu5RW%+u8o6NDNM(-TI^E}$6}`gWvub)?wN?pyQh zFaq8{91{IztaSqrT*YdI#h-yU5(C`|BZ%hI*bpb)!6H#lN1kWG={xCSD zvOnT(V`qRbc<3#4@=<+9vXHwNAQrrbE*vOO{Y($~7w#XB`JLl<`|lsC-d3!C$N7u= z&#?))|K6JavnOv>b63;)gYuUg$JY$S54cb1O9)dpT7d~tx)jYk*JG#zp zx_-!1SO1W9r<%28^SXtCbv4#{2eAZz{Yr*KqAM(3LE`_s?uWN0KltX{Pq z+wIPmAJ59SY{yv#JlgM*c~XF?Ax)p9eIy;Pg;*}H3ILQg72Most!I`h-gNDgHTY&z z9W7nI*k)#pxWFX_my?M(z7mYOCBAt5vslLAYI1{q8@pw7Zcy zn+p4uN=JbP`81xGzXtZRv ztI&{L>NES#GmM=V9GD*G8ycLQ=Ng^JWYdtxe@Kzc6(!R$o83faODi`aVc}SrmYqdA zJlYDIE7=$3kZew^uFb$5;e3b9xsA>4rjsm*khZ1;whwt6Y|k>eZL{o<Eu@cMqr?o2c=ETrRikUG7IfOT|Fc!l?hcFqC zoiM*3rl*S9x|~MtIXrP!5Wn*67#6WsR%%XA@v@VC!?{kCUQD&<5a2FL6%wO$y23^r&(({Iw=;LW~X)P_*25ytWT+WH^|C~Lrm zIo`zYnEDkcz=F$Q1E?H=d9&uX z&2S*3h&jd{)Uy5Xl-AyIjtx~Mf&n7Z!ED}QvTuJ*v^LnzEgq5F*fJ3#L{$ujNRB|{ z7&~K1!a1E3f2t~nST?a{so1{qr#7=X1t*g&oH*2lVpZtJyj86pSO z3J6Z9)l?M+WrD8Ke6S75iC$!c<9vbMA5Mw|*P%yzhyyvz5aay7>t(DGGaWDOVbWo%f~4CnIp7&P*C+Fr84yr4>6@YXtBx+J`Eb$fEuO7vkt5!r2W z!pPJ*pK`;od`7ipZYclgwCCRxyG97O8TFJtrSiPd@#OCuKLfC(Hr9>L3NH=D=6_{g zN~zBK%b@fQ)por$cli#w9A7$~!-i7O^ueO^4qrg7Z=b{|*^{?ayy9%j-FbfU4<8u} zC*Qvkei!Y}zD5R=2&!cKalzeIvPYm%v0LSQ6jVvc$UtFc9{5lNsRpa_n`)gGAdi_fJ8@IA2vR~=d>&iSll6vl}xlw0d0N%ov=U?s=ycx^~CeR zgx+kS>8dKLX(%hIeQ^c@x!mRW^^RAd*3mVX0Bx;VY#dT)qN*M8m#Lav|NP595W_lb zsvwaa!L3&BFlzaDtbrCAOc;T+W39be<>TC8MoB>P{z8G=nzZ`})(T=0q~Np1qDb+`*dx*A%9XR=CEALAXS?k)zOAP+~DMsZWM7hO-Z2jZ#oQ_ekL6T$w9LVg$Wi ze|l*>F=UevxKT@^g~OcX0Jz~LbU&R5q!iSI(I)+1f-#kC8z}+8``DToYD2JfXP zR?WvoHq)DfR|#`5)adACkKBu?HNZETV_X(79^Rof>RY}ZLxO&KvVQSHVQ<4RykN?* zr~w=*e^cb12}I;gCrU_)NShuIlti+q>tGG`827gWGK%X1L+FQGXh=;5}GA#ef2J%<%&5u25 zO#Xc6m%ZCc7I(Y{kq1i70vd$~&VuWTn6l8pdrOYxw#lsnH7{LMVGLuSl{xx!7R%NEo$s8-xHpG%i|T$%A1f`Wlq4t zclXmjvV{g{GnGD&DAj<^?#R@wIyz|9PJb$ww*Pk|Mh_&MP!) z!NQNDU?~r-2R5PYF5^wc{2ppvsiB;w2b^a+op$KF->G`Ql=g6#_OynVJVm#D##bH& zIs4ifk@;DGU`aM(rc@ zQUTgVDl)rmUSsFb52SBifDd;}aPJt{p{DiNv-Bu0j2OB_YqaxYsg42ep38k#=q<3C z@ssI>%f(Jb2F2ONqDKP~F9+a44=)7~Nrcb%s~FB}NV!rY@?UcU2PeDrgwE~5al%?g z?UyL$ZYY1;s7c8Q){1uj{OLz*(3+`B>g(a995O`Eon5<}u{my@TJyqs8`^vpR}xD9 zyFX(+H4}!D99eP1?T-TagwRImqP`Thu)sTs9kz61J1(jdm`QJDgTLsN}i)A9Jz*1QJ{OrqbK z7-7bxV`D{-EgZW^3enXm14{w zC~=&l1{Mwz&2kiF714MiEhN~=Q5HnaA4a?O5<8saz)GQ!x0?tOAtq*_#so8&-x)~l z4~N)Hm5pXH4s*z3s+cRl)9EtA6j?*$^LoV$A%75y-WCytrm|2~%$iNr2s_ignLNQ8 zTu^shF22?5aRi?#timW{!mbC)7uEGl56;;ImPTh-Q3@uhg8I6|tHNotI76J_3N2z$ zj1~nn$nPyAf84|Y%57~(BtaZUM6XcFUdps8^(5~b<(2EKCVh1&?KnRF{)asslf|dG z7bE~c4C;UGcmFrIIDNN&cDUI;`Vj0NE{^6=3NDcZJ_tCz3^-X|gfT$~kR$<~gdZ`D z3p~v)#XQ61bk0d}iyOJa9!VD}6?KF{TdlZEIVDy?Orp|hZw7A{&i+W^>pFXeFHX(B z{M>Wa`(ISt^o{S|M<~A^DozAQW;q`=aJ=pnCPIIvQ15YGEkYDyHc|Kz=17nW`;)~Q9;dr&#vaa9HCl_3g zz=)C#i43%)v79+bFyKoj9i$*l_`WHmFoiLuXp>NkE_Q2K_U(&I=bBE23m7YRC8*Qv z`F-*7yktky!iyP=4=KHMd^>L-j2WC+q#s&Hk_0#53dOg9uix|T6m67 z`aMwTp<4-M98b5^T9<$_&I!ml_74{avJnYRs~FchO!Y4=uAxxUMa_i}g&tzAO;HJI zA*F$s*<@(-amq>GNN5`#wiiL6*vzntd2v&EYBi`&d*xYT9-EpfZIXj#uHcBahkP#c zY#W1i{5L3DFJXX-gayOnq(5=v1m&ZTi{|SnA#a^FCp0OSskn-`QS3tul1R*O8fdGr zl_l1hJ;-eop(L&FDp+l%WQo7%yonxd2K1$1rN7SOMVr|!;s}h^NKjw?6=Q+nLLX(D z!7fD!wA6vJ`D+>9-JUhfOpv^u#{6G-!a1tIF-{*JE#`&?mEz`i+|$t>)!R3NHD|Cu z1$7nAW*A@@uAp=D6~Y?J)TwGJCJL#Vv*de_-l|)otU5DPN^WLiPTfCZn?#$Z9(jun zhiwx(z#uNM{glgI^RYx;{wY(Z9jyM`@55TtE2U~HabO#hO4tUg#}@wcfh9RkKz_$g{EvPb~2KM?U&j_E7eyeg16=? zb{aib6ARlDSE~t09ApsKc~$n;hcC!EG5DHdWLVkSYnozJUJ)MbJHb9km{w1_Fc3bMsTj8c|Goi5B$}uuS*ndWs$TC<&oj^D|hx(R4ZO$t< zjplH$CKV-fh>1>bDnt@27B};<$|y|ZHw4;`H>4*VH7R%_Pxh-mB_N&B9Yp49jUBH( zR^mFsd$c@ddzZH}t;AbydY{=D+Ea|+);@u&t22^Rc?2tzHG^r;zSg6Q)V@w)RjhG7 zeigB8=PkOb1>ZCrZx=qiVBCYD=V|qYLaqb&UlV2pMiG`<+~8gey5;-@3rc`3Co6VJ zQ=qQS89+D|s!SP#`g{c+&dQ36tll$S((Vp?G-DYJnDp)?=fy)fgk-$G3u$5<`r+b= zWtFwEy;ux;u+PUeaj15++24#;^s4fCNY_ju#@Ow3E1SyOdVWvPnmZ*|-=oC)PLI5r z1a82x$P-_~wk&uDZ?lO3j8?9p+PAFKd2;7Sv^4&mZc*?t51mK?TdGF-3;2(LKcUIv z|M2z>+?BT5wrC}(*tTukwvCEy8x=dL*tTukwr$(V&G)Uf+CF>TcJ^)iw0&-ybN+$% z?a!EfJY)3U*Z#j}aWek{4L{L8W^oSxD2pBHkd8JWd4FyvU=2ssk&b8n@_Anl)4v#+TEni-qUmsUKCb#=OIIdvbSnr%6CC^%LM$ew$ zk)3e;sCL}Zok&8&o#PYG>+8dwIy;AD1UQf|4earO^$@NfnJaJYLXo`78A--i620dQ1r0>W^?l?)>zN=Q{P zQ_53hD#Dn-LmYk%Qi&JUCT7;EoQK6W6*7ha$sVl1vOWgJ=F&3>jan{rvaSvBMlVam0!B$}G*)wNz$aNqFgnRWeDxZ{~RZf7aCUPc3?7LXefa;d>!$oeL$b;JIOpcD%ut`n3Cq+!w2$B4F}v~dhxco1y<)Jrf51I&n`)ECu}K;{X5+EStHIr*_ripiOjCr{we zDS(@(WyBdXqpLF-5J9Mbl6NDpNC3uR+fLL2X+_K&SBDhIX5P`em;NS#d;Q@Z+uMo zwCo-_^pyP_R_0PQ%2~2gN*F3rdk8cjWR!Vv%vOdeRlOy#0CGTj4G-H0>TT z2LoY~@IV=cchr*F20wDw^fkv{77l3Dt|tLAZawe zNTIK`e?j{UdSHC|b(OM}@7R5PN+9qi#UIjce)qxE}R^3d~mH;G()JC zJqHK*?CJno4MheC+RZ7hhzTfv-n$Hs4zHVUg(?QING>u|n3bhm#s{3WbT_|`s%Zi| zl<)B>{alg{9ImfU4=OX|JGAIWxFSB&a7f=4?a(+r27O@DL76j|DnzoS)2g?qbVXK! zx7lp3b68$^&(9=XLY=x(qo=09%)C9B9Z%IHhmhqBQZ%dDosCK)N}WU3&+cX;UtFyz zZDDUDYOHrU2x_e3NUT)rs5cYz&@6W{8VXW73yK;TThmO0NOyDO{R~E6@I05RA5ch~ znXvhBYFtUV+Iq~AUDkB~2BYD833}dlEb*emQjW>pJOrE5M3f&#im4YZW1ffqCU_fIBLIr<>4JewcdfKY>N?sG5Z5&$(Aa+e>ZM=74a$1@!Smt@y5oxk8N-gtpE#InV^)MQ(x@>bma-Z@ValJ4^%o&yxaO>h@e9Vtwqv z5J)-l#l3IW=gEBUnCTkr{u*U8wxs8xKPSq`fhhJ;dZg7@R<{O|1*W7$fsPMc<|_-3 zBg(WsfnoE3pz;jA@hl$2Cit~!74n%cB#h0qwc#kI`EOn85z0b5m?N2kYXOh$+9K}r z;trMO);I(bJmo26+acg{8u8Xode9F(;f-=|$AQRi&YVEovi=SW zCiF+s-0^`+_+BiZ4*`hC8{&#^y%bIG148S9T{tj0xHlCLEt2KAMd2y!1#jrM(KwyG zuUmPKonTG3%AHU#s4I>g(CHS4wp2f8u+v->N@K=TU(hR$6W=y`dA3H~G!N4ZsUSm5 z%8}5DV&9b*M_hx<=Ai-z!lLg6JYWleG&SG`mcvby>+^Nzo}uXnA&osNG0FTPx`bD_ zeh`$9b+XG*GLeXA%c8PPa6I{H5t7zKv8#?&(uN3d)w}U5x3LGd!0lJUnp=ALqp-2| zJg(r~4ALTqNh(O9*V>Q3Spb<;5V1+uuQ>s(16r>}(md+VJ;rQT43oz`7p@k3f6SjA zj38f{Q{dK_z2$}x@U>L2iyu7eXg4yq+DK^KjvUpD$1VznxaLpIiOXVFzB=oYrdI=O z^kRwUw0y0D3z|TR1Q$ihX+*PrTZvd5bp_Y~+WlRyJKTiRp5;HJy9niXo@h-TG-b3` zNE{@r`Xw2xo52^HwTrR)$C=@2xmO~c8sM`&s^@e1%?l*NZ^TE<8sM2_ZzM+}R>gjk zbB5+hjIwc-E$5~PIZREXFe~u!a{*_$rv7#dB6wDpLY&e|bj5KPfHXy-%~fv?aK2$! z3{kC?Zx55+W!~@SA7!nQbSX1RTsZ`6hBgDw?zKsc+M_fZ)KcyQ#&<#;CCu>(DPO@S z6YXS;KcR4w9KeT2WF;HJ&b4x%Tga9RvyLH8&u{jXxT=T>`e{XP0T%4pgb$~1)gACr zdo__p7;htmnbI&Z4SB* z3GBl7Q`D2pY9Iv)&!(mW1oIyRa3%s zut|Fc`>QN&49Hr(lxB?^&{^7~p1E#N3)3$@!}W%r@QYQT*eW zCEP069V?640N-t%U44^$^UaMy2_5?HW|L?8n(hvskO5(}fui&|sm%U)`i@yVv*-Gn}4ZjC^3|Rl`1;_u@ z<#(okF#L*t`K@hSS}&~<d0EfdhU$dsv<*{0+UX#nr!ny(7VxF&V@v}l`Q=F|%f14*S-c&vAgIo2G zLCR{8j9|23uiU0sJyc6#%<2aniBCyUe8>_|CXwG{&-R-WrKmOPo%*+2v|2nFbV_>rI`3wJ0> zskD4_Fy?te26rfDvIJVe67=*8Qvs@a&@kOGKOdD1_hO*8O5U-VrT|nP29hxbX&tjI*^$bw{ z{8{9##mmOObBEp@Cvcdgd$fiwOgWb4E+S7n%V`FYKe0;_vm(SS%Hx0Ufj-HV;d@?R z3vt2DQ6nd~LTOy0J242jl3eQp^j8Bqi|Z#q_`MBp_n)@m{~e(JCk^QT&JpmR@KiN( z#8gH86d^PdiR)1*tT79T=SHnR!+ou8^ zT@~=HjhkjEIOjAgUt~a*?vs(!Y^?30{j~cH1Ud=uY1@1?F>i-ZL?rZTceUVk<>lh$ za=7Vs$t#-yG##=a(1h(j=*iUww9yqJN2uW#s4(gUM!ZR^uO8mJ!qBw$aIwC?3{RsKIR(UJ_ni`#up|c`;OvOvI*9BPVe!qNP zYF)x;JZG;i=tsj6Q>3LTN9GthI{@5v5k@{bbVe=dNWL0q7u~!_f6(i^;{j%V!jY?!DbNF+op)c240c zCE+Z!fRe!b!aUh;$c&2(S{TYoWcJ-YV8z?<0E{SW+d3m_7V%!FG|)sdGc=?myl=j0 zr%{ry^dPv1FG154xzspxjZVojqup|-4L>KZk;+_r%3nrQaMQaoHdY?cBT_mpAHq_& z@p|X$tpj{a7z0AybB#iO$q8H1SL(f^(C!XL@Xp^IdJYZ9Dt$)RMyS3BLy0s1H%QzO ze!Wxq+Q%yxId)Sg-8rK0_SKPiMrM4l0PoU!ZyMjfQj)?i*aa(8UiW8JAS6>&dr*Qu z%N1eBWYb<6xjAjMY;Oe$C?W_0I$#>|kZzV2)^W3QdxEf0p3%|P+JxnZD*UxWIInaJy!`0n4{55tY5Hv2Vo=a?xa&G>{2&1x)^Tp* zabVm`npwAu8Q_;HWuj)|0@|vs3Z?CYSTJcV3o>u+x_2lzdQs(>xq?OFI|z`_NL2X7 zprXT*(P;=_Z$AoX))9uv5`5^daT-8hLmF2AZKx;sbv^C+m3g!A(dV^MbK~Ea;U(BH zlWE5T0@=Jb`h79Qr?~rpntn04|DvQOj2@v~T3As=d+aVfCRSTg#4+9GS(R5bVZ5!; zp-*^nt6xKUP&WHhwAH4NHpA5O8uq!v$Wq>7N&|NAxk2I_FMYBu1QM^a~fV2xRW=k>wh`_7>PiOEvKNWl)*s5nh zl~7vya&rxX5JWCK67&EH{n#vt){XL;xO3x9eUzKRDHO9a&Hba0jL^7ukWk&-*Qm#ND^^VYmxxayOvCZD%R#w-*!7s@D!6HHbB z_a%h$mBRH2sS@rppmAeUjQADx`x%xg{7b0lnO11P=g!oaoN|9jfhkYSAjrf5iG+b` zQGWFSBoREec39qyZbTr{{=6VOD^EGp7G|5Q;%+YO^rcc5fWO-CS*Ct5-xSx2ki{Oe~7LA{9pbee#rN#V{q zptUKR>X~|XD&&pDIm|AH23US9I7}IchA+r>I}#yVcJJR>-f_pmfAE$VYk`wn3Dr9U#H*t3Q2RWH9sTNeM5q!oAL+$!cPd6iw}V0V(y zo}S`}dr7K=e%0HSA<&sX_``=RM`LL*OhX#J0l1t}ucOk+)}o4LcM#B;B1dM)`q8ur z$<6}cf!K1sVXb}jLii^HSR&kP1Bm#Vl2G&S31T5ftMGDWl$wU$g$Sum6$4ibjmR|} zzZVf!9WP+I@-N78JAP*npU*ZdJsVZzg-ilECruYvY2@B8yv@;ef4VZB3BM#+ z?DzrC8ivrT4|lOEbB+pXC&pwa)DBD9KXmcV}O_75+UhNm`D6MJ*&>BCv2;mxQw6I znKsFK$PnF&8wB`$q`S}UdjiF*sXE)*b3VAZT z!(pw~Y_@~q{~|_Fl0`Rfe#z-QjGa|hSyx6_(i*vFR=R0S*Vr4So9tYGKnvQ_8S?nt zDLWp4>Ar4rCr0v_%;YFL2o-ptHul>By|m-WYxj=2K&bxUjt!+A24o33ud?rL{S15v z(jQN$Mi9T_O{ToXnSydIIsIy&5-oJG3_c#LzIAK1?0ilJ_SJiFfTvideoM+JSObYW zfn)9Ek-lClNSE8<+`;SjcNo*0$?Nm>dnzi%ztp0P?Xw!IyaR|M#%y9~{RBBY(L%2z z6CA(327OHQOw)6ECzPdTuVN#>Q&B8W$Ek9L`Y{db#wf#GR#dBLPZF`bq*wjMEu`Q( z(}Rq@tv8TIb_tCCrNM;7q>F^T(?)hFbJWQ}$JpJNR;VLtKe-Mj!TcO z9?K(?N)TNDT0QdOkW3h_Y)dDrrJw)| z86c%!RahEM7RNk`Nj9yOjf^PSJUw36x?E3g3{JM{^S73{vmwoo9ek=UFt@>mkS3K$xAaDQo;v2x{*OvAt!z)F;_G))qy8kS-%ly*jmzkWAA zg|PXu{cQ@f5~h)(4Oda{Fd6kUF}^z0<^A;xt_xJb;8-3nKLm|fMq8ZsNn(is=@>Z)kvD)$_f4?+&=aMq>s`*eAI&zZPb_<=gtue zF6hK5ZZxcjUa|peuuJJxAk>b0O$2|B1(k_9Aea>0!i!Le8~E)BlO!P$y-svc!U-3O zJ7z}#8;I%PwB3nVL#spqH1n+4ag*OCmt1KQBZKXmL$<&tW#;Vup%U#IX*O;7QviAn zp86H4K#oE-h+zURYf{gRH1*GkWD52K5BN1*9lo*V3xE8d3Cx(NTz+8Tb(WdpZJ0}j zcAhSvR8xj_4q9$R82{%c6t+Iq)#0}yXM&Y*61TWyBBsNd;V$ti;i|5WEgGl{Mxygd z!MrY_HVCFLx?)CYfwTa|%~ltm1AsS>N9HYsT#rWJRT8RR)msKgBP9oTNEY*!ePOEc z0-jllGKce5D)TevHB*|CE%|4tI`@EqLg{BjiH8;V@z-*<>x1PI35n@ey85H)deoLZ z0|*g~p(q#{J$gx@V}^qnvMp*YVws|kGBpB2I1g&oUxQAm5AUYP7-MdW%v#6lDX7!b z@(&ntlplY)!ECxusKWohq|EsC)&W%dZ(n_-~t{#c!LUO!gz~sfVU5old~x z>|cJN2MFfP);mFgX;6Wp3M2R6f@KFCJ8$dI%@{43W>gEstZd>9E@emEWpqyNZ>RhA~j#P*sCXD}pJUC0o46XTRFAz2U2r@V;ub&8chazC5gJLU}Nj4jk9NF{WKC7F>JQ#C*M z+orlnm`rJY3PjG*0|N!=lO>P}rWpU3I;^fomL9n;8J8%-BDLlHhNR-(kc5nh%F{!4 zE7vGavcrT9I{HgnPtsTSt*xKdhx=LtEMhB&y39JQG2~4>{YzWlYw)eD-}=_pe|&4} zH~-Ss3r2m$o->&4%V+K1$y`A|+tNeSo?o+!-!_HEL{@6p zcl$=3K>S!$+?DZ0%*dzhN#a#O8xY^+}E#qlLj58NnEtXbb1Aoe{{h(X$m zr$4g<1%zE7G~4=#usM?P(ovVnS|pSCT&lK#a=y)F8cyI#rYuf+Mi`PDbI9puYbmJJ z+WpjF^3K1ko99FNG;UhEq&X8%lb5?j)${p%djwla z03KM~iiQZr`d!jSF2$OxR%v=judzJ=XhT)uXgz;q^;*#0uVU_<@Zm`?QPihoI&_|R zZm}~KeLR1Bfc{V{HjWXY4@Ve%jgysAML~`jcy9Iu2a1DwB|I55&CF3N@7m{FcWho` zTFT{XoiM*(Qd-rWM(GIBJ+72g<+`eG5~`kT!V+*l%bdu7#u;Yg0cKCgioRZU1+JP7d$N<(GSqNU8$$rh|Z)8}`Bw2>c5dT&Yz# z0`}@~R_MmK5SqyW{8`?f#Ab%aHr><0n+EyW17a-< zY?F^YoAQ77qB1!;{Q6C_@V*fAZfd#Qk;OrPwTLL7y_j6Y7P7@i*RrzaMD9Sv+I?eu z!Ygx@^49JvJ6y)oBUcb~{z!Q$pBp6ze9?RG(#+|OVs<0XipNeWhcUI5C`Ti4Q;gzi zlBo_#5Y2G$mC`b2UkPr#6-3xbm}(QNv7u0GV^mV+09tPsQq=y|B#Kwkrpi>RMR&e`4+9 zpURK_wEa;a-y;J^kCYB^PC!6_r?U+}!!nqMiWm|a3W9)e75!SFwp?3D`V9C(J6$JHVHnRFhSwT<#@*OPRolQXDy`=o>^431dlz z!CPf2TT7HNvSL3lx&=wZj;ekMe41C}+TPY6Qsba_%fuR3NinBpR(m%PS9EVD|O*yV>6K7DE5d4_*0BVXy!Grz-Y8@oxV4 zXIc>X{W|!eg1!K2t7DrhXE4jXax&8zRo&JH2p^m3Ba6 z0j>m(#$TlJu#2pP^uqPr)wZwOk0-tpi3`8rX%amk^B(fa+@b};8`thwdY%`TNCjH} z9?5u4-QsOLW!Ty2%0HcC1A1Sa#wZkNuI21qew;6?hx(<&{PK70N07-u>iK>sWdG%3 z)<$e0oD<`(H*g{jwC zqiHqS&UI50T4UM`_5OmygaVa$%82-o50}L%2!_eB^&!I2i5#McNT-h$ZIeN|Tb|+a zr0mO?JG`(iccTirLPr?F5j^aMH6+_Zg&I+48T!Ma1l04#W>l`eXs>fxv>o@4NkfSz z&V6%Y5bC6ss&oS_#w_1w0v=}sxU@PtDB_O%|H&#+u03 zNCq5+@-#Ts?VV|>vdei~=6o;^r;3Een_(^w%YMXov_~_oCrd3C`btjRCFZ?WAov#z z8GUxdO7x9iEQd;H-MSunWcPaAd169PfkqcHUqa9HeRmE?y2bCD&NrBsI$hsBp}OYo zE0hV*XD$Syt zsd*Vjfw?cD2KfHr%|aZq_WosZ%LnbG6!Sdz2@KL(Ql*{B(hC|`^lr72T#~?kj0OdW)Pdgr=XgjC& z>8Q{!7y6Jfel74_3c)18Z^t=cJK>NF^9^f5;*>sH8hvhc*6r#KfK&ySYA zX^m}*cDxPfUL$lsGcyU7)E?ZiLDXTx@?72HadE|UiloEks4l#KVx&gvPUBuxC_F+e0jNf(^5&` zF=$cH32N3UbdFkkCX7BFXG_VNOP+yJYgyZa;0ok91U0p3($=ZhenR#iOC0eleW9}7Bl%uM})cXlee!Y=gBBg(|7`W3WE(m{96eCGcN5w%W~H?X_HJ&xOF(EQm%K`(&ouQII(gbM;M z!1<#0s{cIgi^Gh2%ltaiOg1aINig7PxP~a$rW=|Qecf@#=XKAO-@S^WQEvifHU*#4 z_6d=G{$tzCUnx;9gc(j_CWJzo=muP47szw1KY2aS2h{t*Dv~Z6!j$$b zgn&60EU2UlV#b?FBOJSE8N6yKZhz*mY+ln)c`9_@1&W9_FOWafwOFZLWLl99*-Lo_ zk*%0C-?iRKsDU-JFh-&vweY9R9#oC6nG$_Jct;hDyke1DXlg6bLb0of-DI5s+pZn` z>LxLk$T90*!@;5&@;Z-WHfX(EH*8z#_4>$pP>FAy>^G1 zNH*o;o-8wC7(5Z!@8He$Ib}i?7O6m_mogB!&{mnFG#?eA#~euKE2HIJb4)BaS~GGX zPlJc61C&-YT7s2gRb$BrgK`;fe^}FcnB(~-p?G3scWT*muEZP~) za6$EeIkL~6Rkm^XP1SXWtLO7lb zEZ3kj(xD!to?hTD1j_rU4nF1`w=O=5IkV|yTX+*l5K_3PqPee%7=WEB%vgB(r z$V%bdS$V08nlvk!N0PPmHgJ2DKUz^4&1GgEor|NoflGiRSCt^vj*g$+#0S_#P|Ekz zMkdxH&v}B@{`#QUo?ewYH!(}z=L81Begp}U{9yxthev;BO9+u?)1|}3qBgT9YcXLy zd$Wy#k>w(O@dqShq5@%y{~&h1;_0YZi^kcdnXh)n5^2OO3O_F~Vph#MuStq`&D6z@ zGy~QvfW~2N;B}6XACvPELQ0Z`pwb>M=ZVAHyplqgSs&4Z>sfOed;i#fKqJ0z`)l_h z?Y}g``tPO7{j0>u+1nU88T^wh6ewH$WeUjS;$mFXhP|wyPPI(%5O@j6P|-fzC|7O? z8CcsMkCGE6Rg`owy^>*U+!z8u6ttz=t12ue7Lh83pL#t5JJ^4WdmS15`GdD)s)O@a zVgp>Z)!`a?jsUR=bg=jBQv;|TYbGbLgku*f-Hp7Psz7;bWc z?yO^}*2PKN!$@=z1Gr~7odRkA0z-sB+eH{Q6hl}cV_ZbM*CkXZ(a<>rt;*QkI;Wlt z=X8B^3rcS?SkRMP$UDecn#fx8acjmug1Y0jTes&g-P+qh zI@C$hSGjic4ko24bls+O9e^$|4&i4j#BKT<5eR)(nplZ^)5lgKc5V7@?c)T$ryhqQgbV#VIwDw4>E@Jju7~H8A50{ zr4j<0Vr!EF*V!gl85Pfv_xnG^b~*d56|8hu>B%4)I*w&@4V%hx)a6PHw*Q$MNQid~ zEP}t=C^ZQ^{7r1n{;ZTg2(+{Z^YjrK)`6Ewy}egm^U>YdZF^kOoj4>GG4@l`a;C>U z`E~K`(62<1)aj%?Q-Q-O8`W`D+QW%MT2bFkG|$C}L-6XvP%cycGi5A)Mm<9+b#WvY zJ%cR+G3Jquf`@&7x*pfH5Sgn|J7N(+CFlZU?>4rYw>a|Rk~G>ufrT;)y;2$wBz&e) zwDqpwgfUEc2>n(&#jySfTnl#3Yu?UvL<@!=+)%Y)*o`ZLJ@O7JShCa7+wix! zF6Us#2`C_L9M6?@_i`bm{SObED-tadJY7?#WHkq2RyZj1f?0#w!6^0b;I6`{J6i~Z zW?2YhU7Vw%{)sqvmw>}1M*^xt@7Pwmq^caShB*f$;h~BGBzlct+yF4{XwXP9qkDo! z<>#Q!{#JOKzH8m(xE0R++M6|`5fU54dyA86f<cg5x#dHu;W_L?OCie;G9-Uqq zJe{E6-&j33@LeK+3`rf5qd@fwV5EK&)nRkqq4kx<*aYAw$YK%Nf#tee5kC|V^bQ17niVTNgywDK?u;~6PtMw(9s=Wq`) zS~)-Ek~GeZd+3d-M!ozdd}+?oR6tpP_m*f8FLSt1nV})!4{}mBa7%l0D;Mhz0Bx3z0B_xp?cwMHE7Jwi%B z+#?F`2s0vTwaW;1%MSNw0jQMQ;t?KidRcm9gp+2j0e)Vl(%I6l8_p^IHM#2Qvm7*QmBm8mPx^D@-=5&?|&%M2sE;A|=%z4btayypi^1DM^#u&QIX?4xtD%65g%SdHZ_4NTMWtp4nk6z^ftV zl`Hgj9&WNBc365TptoVqm7}Qux9L%b{_#_d38L5KR)Ya<+fm~ZVb3gk|geHE1pV{tUJ21p21b3i)DxV zJ>E9>P@a2$*626iuUVK)O&^=AEN8)9NGj0_o@{HZr9pY7gepu&`d*72&=3cakSg#j zfPh#?4Hexj5Nq_aoFzpaJ1aFdF-&+@072c$G9k4;RoB(rY6r<58e%+dh4_ZSSK8$+ z*KaQ65(uHdO}_UEE20KyuHwadh0zFfI`KtnOV#Yo_Y7R~`7_tRY9tDxpUaAhw^~Yt z-Calb%^?4cAkazHoCDbYatTTn7QNF!cm_`w|g5y!iP%)p|wnq zHrd)^u`1PAP4Oh8<~@#<$up19TCVANuC*pcA+G9wRgwb=XOQ-iik=@nFCUAGMbC3T6GpMltLr7-F2 zp0;Q*RP}2JaVLs(uW;9_me#CJ3oE!X68K+|`N?3aYZ8q8*izc5mwOq^+(lg2ts54e z93nJ{oV=0L**c_tbhS{vDk?3aN6HY{@FtZnDeA9=VYh$cTTsr)6p?j=SgV(`zp@Bo z$u@Slz&?dB=joXV0%-WiU(9WANqKlOTC z1U)YqoByTPk)(dIKo_W|GCR7rBwkAbq%v}mCvB6gi<`N#q(=52ABI>1Iu+~Q;66_J zeBBwE%!bG;zZYHnt20W8C(VHHptB<~5?0x~Dr2ziphO0njLlILMi8t-s7(d{5e0_}oFs}rUDQXz-tZdBh0D)?`+~3Mc2P~Ft z;q5N5?PQ1mW4jyAcE zTqdv99cVn?mXcgTinFv~6etTY$;AvjF<|xGS*{#Qy50WpE3wAw8sAHJOOj+@aTK)%%C z#ng|2|J1;y(}fp$ND%l?WyXo&P*-eAj>W4RuGs6PtQ_4NL6TZ25(8N~vh{6p#&0Ok z#h99w8XhrwNwcb?7{@~ZKQBVGwsBQ=ylcixBk;KVKTb`k@3k;jc6Hrt2K zAwnw1B+JgjjhidTL^Lz=t3bE_RiK_P9A6_BRnRe0d-phm$m7eFa4gE=Ea*+=C8juo zab`T0g*0`mUBPT<$KzE`^CHJ+ERk9NXsn&JRGM(+0$@yD2>m8Bkk<(&U-E`M?B0=RQBdD1(O^ z)l5MWM4dnFktji&xlGf8zgcMhJgU@l6VY&ki06K%#;av@yT-z}17r~k>k1)2X2o?4 z@l|Wx0y}-%rkbXH(eslSn_~%=MiI>WM{Kv`p$%}mLUW`i$NqRFRc`*xHoicoS~`vx zzuvR_WS4RCf*t8m#%ed)7D{3VuuE}zLWidPqrekdNfG%J4*Sts7s#DrvC~;W!Jc4c zhTJCBJ)^akyv2YH4&2eP^A?~%_`r~8+9rSB0^lUC>nmh*%@Y>vjk4PfDDZ&<;+SG` zQ=qr9cZ#$3iyUq(e0R1O7NK1kaV_}kM^wo1tLcwE()=R2cRs0E`TSp%n^)N(Uc=#D zh-%R7yRPRF1S@OkG4Nh}P8?`5RvRymE7V1*h^Xn{R-?@#14dH9d*b+9En@m0^BhO5DaQ=O0Q#kh)prvAmpiofRz8 zmTrp*y&&@Wh-|$3t$#usZ<((<=UG!=wVm8=cx`g{{m86*jNN~jC26p{D<;5ori1rW z=3B@2Fyg9(RkrhM*x(0EzBXy&t|iUtO)fSqdrU#H&hkwyB74{iET^^|fhv7h{hq4K zao9@(c9)%gt-f}{UXu(G#Uby7>qMx2JI(mjxocnO$#VytPxW3`dU7CZpqpgaSK@B8 z!h1B5PwcK0`KM}_OTO#U$bg6QyZY%KAUZQ6GPF>4zZn==yu-SV+e28J z_0@(iqfa!VWB4pqq;n0_(+A+Z0Hf~)%O$dCYVYD^!Bw!MW4)np3Gw2^7P>5C(eZ^~ zv$~7+bnB?>g!y&8zJN?kU^uMb9X!b}JDBs{y?1H8e!#t@D{^I6yZ83SOs%WT%4Qt# zQTV4sRhEgXJV;n?=5}VP(`WX~N}Uf^2KQTw0}P=#j1wXa?iE#YlT^><1!TpYn_tRG z-~BiR?$S*47A1z7x^q5;JN+_qBb5hnf|IS3UD;b^UjXK8e*xtiGNlBUaMw>{+q8{%t<9^xF z!2J5!2tUUtN%Q$^IR*55ns|@l8JW(XUYn`Us^=sQ+q~rK;-HihVg$$exd0UXe})#7 zjV+tGekMFHG+SlqhqC5d;#3S&lUzx$o16L{*uV^oo*p$vmp0QP;9qI~%CuGOu)*cb zh#7+jhZsx4@!3MVa}0d(S9KbRdaimvr-^bV0&GlffzIhv>z4ZykNT(%2E5Fn{sn^H z76Qen&uy1a)@)v3F9pV_&*&s1XtmBY{Kf~r=G0`8RYbB4?z}`+5@1P&QW1W!dH{)N z9APepdI#F-si)r3sjJH8H!cu7fqCuL>=PBu+W7;Byi&@n(fi0ci?ubsG!8QW$~_|RV0f)V1`fjsegF1T-0 zYdZ$MT+z+dHC)U{2`=9g-I#{*fi)vq+a^p`z$R z3tz9=P|*!Kw*38#2xrc|uqae}4i(N)XvN-D_uIhtTCIkomcIpfIKz~h<2(1K9u_zE zo6~pJ>j97#U}#uW^bRg#YP)h!Z)UzbHtvuUIy*kGFg!FgN97PeuhHJ5tdL}06y~)o z2am7pDI3`UKDl-LuA%}~;w}lfb>go2dxRWoOxzqB!%D2ET~$<-m>q0q@g6`9PW-M; z!821u?VNc=s%?>sg>6;F;_1B9ndACUR!QI@Vqv6R)HTZG{)EpwL+OGUkk$SNkJ=eR zZNe0iOcv4{NrZ_{g{0A;!jV`l(a)^V!Z$66{5`hI10&9K0r9-u{g+dTQ75dp#JGiv zz5*`1-C$v@Zo(FUHZAxD3L$Cv{&4`UUwz`gnXZx!?h#8p`gwe?1>6+=c#2OwdEft=88geA+;4O6AEu@ zvGMX**1kY{e!|%#+Yj99lp(B3@^+tV>ic$w*}6z^r6;=uiC-L-#bBXQGRW)E+=}?H zAu!XH<>pyqafqzD3X5ACd3~h5x)ZKgy`LGgT!-Ik^SH%k z_t)>q2@%#dY^AZ+?t6B48b?n;DnY$^QM5Wqo+nH)zhrfAkCFlc6Y}oHX3Q)YC^LSw z9Ij`bO+C1Mwj9;?%D)nd6eE?6H6rA`6R_F9IZ{G~$hI5ZYtH~=5g&j&mTdk?iFR{+sR9Tp6ZLL=SKcu~5kgQ?0 zEWFz`cH6dXyLa2RZSA&g+qP}nwrzhsbLZSUcYfT6bH4gjRZ&q2>&) zG*qONuAZ*0Y-MAiGrP60v^CINu~yrEK^xIuG$yNF%TBZm(QcQo-W_hcC5Ah4OnfYp zQyCop*l|D+9_~*xBT~1D7&a!4v+u1(H7s=}d%m21K3t0>%Htr_&^=)&OG1V?&9i?> zn16{qoH5M47&W^lIR_vh{Y?e|-bY{{0y@oXLQ*3uB3#l2%qCD~OsZ=2bknw?1S-(XQ;s-U# zWOGi4iiYSTS5N!aWb{R_7*jKi>gxAX6ebG@qgv&U2jvKyys>D0j_CBVXL)QAg;}Vg zsSAwzWXbL_SSWDl3h!9Sm1KK&>RErV?Pq&7%oB8}%VzxsS3(XiiW*lUWWKJ4S)BV| zSsIcf>%w97hAY8$tev+$FBLnwr!~WGzXC;(_ZM$fF~)J;HJG#7 z-QkZ(saJgUX{x^|)o*^`9M+&v$|xlK+N?7vSD`Sh0S7U=k*tc&gF}I!O*uf z4){>w&po1|nP1%`ZclIv&2Pr7U~vHw9_0|}#2Ny8Dx`i&y;SlId%(2${@S<(59(>u zh{e%Zr2*&Eaph9Oa4P-q1%@Zkjlf4w$*Y0ivw;B}%^~4iH&$jjV!p0`WDVNAJL|63k{iDb~er7@MRLlvg z<}X2oLHS7-W7N!CMy0vDxw*+e(iu8(0m9|PDfTw4NQ?ot46(HMEFs~_&;3c=?%wjR zQp#{25uCii;;vbhpAK7h(|OR{Vzu6Z?7A#I?b{7s$%ul@>4MY$NS_($0g ze~;~ti6i8IiL9=r)RslpYhw3VY4pH zosbu7EDQ?%d8}^UvLfH#4*?S{1q1sdhoX_b-j12ujy?Hi&Y+9F&~EA;nA0e>L&wEv zoD7s)YK2OM-MIt#Sihj@@S_Z^2cTjk9#0HtMJXzf5#JCWl^|A2Nm!s1H4PfFCWk*gIGQHzhd6R*a^KBltfinn3V&cJr?gH9KguF>Th}Rao5D+zBXXao5E=#^Pz|i5J2if1pX2AQWf=>2LVeouLaUbFG1K2PxgzdT>Li`={6x8(5ShFaJ?XKAs5TBy}D zvpxS^BIxGZ8#-JDCjpIvB{YnnIr1R@L9=gx?hros398b;hkdC8YBGH#>bz7Nn@;PM zLF$El;rN%-8wm0QiL6Mr=;hjW?}Rg=+F`6$#YIL2#~}6P+73E3-fL}R?+GQLM9pfe z)=`;XT$W>B#)v{86{J+^F;~%AkD{I}u~c5lUU{*D{;&1n2)Ey$Fg7-IDof&wmBMC?hqn>lI9l5x%L*~bO6mdhGqv>{iz|&@JZeoET z=lG1ap($-7z~v6vKb}642!6tpG?k5lnM{Pe)CzjS5q!T#n}Ln=d-9Sry`Rf5W05rF zMZ;X{U@~2UHnd=jEuX{yT8qrj;WmP(WWrWYC2lB2no*ZF4eXzhAQnHm^pZr>$A^Qw zL=18z7wmvmXjnr|34}-q95QktnlPc#ODgQIs1JCxG0>=?+VsPQwqfjVw}*zp!2!A4 zrp`?)7F^eZxC}NBq?8RtH8Q0SYO;YgW&Qa$gp#Hxr!zd}5SPOSg5_etPijF=>_N`s zXfxI_{zaqPIZ~JDF9Auhhw6pmh}`c?9L-!2<#o7&OVnxv*aJ;X@hxw+4|+Do_}6@; z&MITTV-tD`mp4@2=4*PD?1`hrvr}$MPe*`uMJeN&u` znhp+!aK+}RYqE>=0G;E_*VxvtrNDiH8J-gkj`jr?pTaU>8VsH>><`}_webdR+@q{`y(n=cWN=b zAvkWN2nuOdN3i&$u)*g0y1oYR-lH7@bjImn_!D6UQRa-nAP%6l8e0kjP{x?_d_Vk- zGy+r@C_5{cFPB}^YEgjfB-@>0Iv45z3_(o96xfdO9T9C9KWu>l*%Hn!8FwVc<+*AZ zcNobfeS<}`LHQHR#avhD=NeKA|2wSpQdhV~1L^JGCm?8Z*vtI&C4JCNhe?7T6n`BkI*DjT7~>4NUH^J@%2WXdFxB1FthH$^Ty>9l1mpyArJqz zM&6nJwe*LQCsZ$;cS7#+&rt29t)gv<>lw~9k5Rni`b+jk(^Plw1&yicNc66o?|;nK zpcmmPoZx@`%BKEzj$_rr?jOSE|9zAExo2Z!XW*!0ZRV_JZ>HyH^uOtje{FFnSt%f?AbZoS8ve+W z_Mn<1)GxzfLYb8mD>_V>_*D#Y#Q6ZMH2a9DEbAQWa~_%<-%1%j_oQ@+K#H1HY%))E zP9CZq-LH(*^#7u2@E&YA$V_=B2Z6kTV5K!syfA>|xDE9K41?rP7+|1Df&h8G<)eycC^D2{ zB!d~Qd$kmCaSVz&g%&iODZ!kg6U5u%?8Vz`FlHAtnJT&eu(t|YC-xdD7}?EGnw^B$ zWC^$iAvW1ErP~-&b7n52Jxz4WDpPGtQ?e;AZ)4m}HfL*#PdkhZv!Y@jf|M;Z!HB9< z$+&H+CFsG@E+mU|`R& zh4aOQlL^3THb3*ATp!+7F`+6!PaqR-WT}!X#-3rYJdTUKVYNVyM6eqW;Cs?HC{a zJc_F!oyUe256~hPXQHhy|3Ue-KNQiCsEu(fX(lIYGV^D!)%NMyl+QBgg%%-EZO8q^Mr+#xfft)IGr?0nX%+@V&hO6 znpSKbBFmB1>u=`wRgwcPVP%(y_SdT~S&40rp`%hzrfH~7f$KvXX8|7ZlEtU<$e{h{ z59jd92wqTdG1AS*l{T@-d6}~~QWgGQq9R~hMa&1F(>utO=8OQvx3HJc*L&R8wo!GQ zro3rlU!bX8FvP7vQ91}O2y-k+dq(+62Yj7sdrgh161G~IrvUy&y?pz;Oxue(kVBY+$ z*s;I4bwXkUa!sc}7o4zM5$*-S475u~pV(SoQDnG8Ndw_xC4Gok&0?2k9|;iN)ku2d zxbxb6VRLj;Zn6uRQOg1B7iQ#cV&=V*PB+eOG)27)(GKFc<~Kt|3eXBQ z#H$I)e>Rh~uG(E;F?8U`n#-wbnh;Ia@kv(cmc@hcgR+X{(RAc~n{!<-IDjDT8_iPH z1=^fmOM9skuB@3xeOiQkHxG0vA$EP^&N93669C_1C%F`8*hSQ`BzYA=$R^uE66PY% z)5-;-YLwG{B*R5a;!}t-35`qR+?skdfhyi}px`O?1E}NBq};Wmpz+{5&KXuCu7JOk zOTJgNB_)s7oZB@{lf`%x&*w2)AdPe{=tHCi)4?dfPu6>}`3DsDt7uyOgKi%Fe@Y$x zdlEG(8!IDgM_T27z_7J}(ZAqV<=jQ_Ck-Z()8%MtBXxqvw-;0V4={0RDD15->>o=p zK0y36;Jm*er19r;bg7|?ta7E%>bD?yUN2#?j(Vr&jVpP%iA&z*?Q4x^cMiOdg6(a} z-+ta^m)98{4yn*NT#y!1o5zjMUzgiF?-?Jj-PzutIbheREvWGbRJ}lTrDH|LJ@g0z z1*2052}OjKIMCc*HYGlF&oNj&sw`m8o}_-FHzmHqQbac`8&6uRT=VE=&mB(t!F=bpoM~U>{KvZw1tGA+H^O0zSmGp%NOSKDj1FBjrxTh zUO75^mZ+v@^Yq5at=&eT*N{CG@qsWszKJ(vE8=J@gH6Nk@hsh&pq zewYkM>?YUJ=+=%5`_9xl)G{1{W}N$1qY*2w5^kR5XB7w`$m6e-SuC{*cybk$v`6M% ziROz_oKI|#mDEY$Qyjj0Cd(y%w^Y!ZTdiwUn}Ul-hAz&UHdI3iEBzC>=np~yylnos zJfT_uTF`9C7M5f*pYFd+jR%l_F8w&ea%OTCZY;Onf9Ke361N=Y$3gZbn%DlJI+g%D z3JShsQIYo_7hiN{pXGc%l;W##RW&pKtuaOL2{v~wzCu-T%U+39+Q%jNuRDt1~;QTO7lCT z^TAx*9VxevU1P}KxwdAxwDn1Axi6u^Os=3vlZRJ0($~%-txYj{1EeHDt5vy*Y0=q6 zqlAUou2~VoS@aN%uucJ+x)?t9gvl-Swh`ptjtXyzD4nQ1%Y+YmfJc6-#?LF`987WunyK7`Z*u1pLG_qA8r<<-~3^)2Ek>Z27(o0!&&?C zX~TB{S~^jpbFnXB;TTr|h&ODPxMKo3zRN_S)gIsBc!lREVc=E*8VD_H_eTL@J5HQQ zS*jPjKu1_8x4JRYGp@Xu#pyB;gTqjTJK_ZT*pVNQ1GqR;?F zEvrGMED+qX8U(ruta<9Y+^D1oHH zjP113S=LowbtbQEr!6Sa8L{FFIq);2`}oQYBdpiPTXnOxAhF5(%818ox=wacT&7W5 zv$#reIgZe_>}6Z#4lnei(1L7wBB8}#oSv71VPKE zbgS5tnotVXu*2-0Q(R(fjK*N{PR9yP8pjgZ2hfNM2K)n{@sxcDK9 zexGf39qh!C=7l+_8qI^U>1}z#gjs1L z=MTh5-|f6ZWObip39z~BN&VhX&`qD?ET5Q1pQYN_tNPig3A73W&+L{q z`0$D>iDs7x{at8l@kxT!TwGzIti|a4HrP+Jq^uzVoL)-h;57mB%tU5+v+)>x4dvzs zM(;vhMCD)n2ton@HGF6_LTHjgz~cd-)(C?X2!hpOWZA6r9GhZ$G8@7^%J^Y6^!`MZ zpFC0Ca6gX1^m%`t823fd{PAY3j$u0i4oiaXY!-~hK9b1%OC4QA<+BG98C41GNSuC~ z-muLjMDMP#7l@?qR%&IyIHaQ}XFgfZK(gd@W}14;5-bstztyNd7?iI3MbRh3{p+Gz zxe@?SE1ZjMOi+0so?r^IluZ)IQZcoSwZ@NoiFb7*t1wq1KuH{`L3+iBe5DI?<-xU) z&PKSL{-AXzGmKuXZg%xWDQ;61S_~&q%a5M*V ze#TBpo+rrb){-rYd4E+^UI#^X=y2|RtDpJQu%oy>hPkrFNd4%`lf`n7iZMG9J0g5v z=ZhKLlLXVH+|OvVbj6!en_Sgy3Aog=w}T&6Ete6VH9t|NOF&m#ma2vUr9A#Vffk*{Ovt;Y3t{=1y!nFN# zS(0IRbN!-(BdLb_-ReLu>eRPIl&5uL+LH#vT}I3SX57cy&$ls@$`?_W#rF|>;1jAm zv^oczWQvhw0Z=jHSkQo1wJe~TkA5=WhqgqpGWpelD#&lqmw-BK@PV_SZmViBC})Mw zGe?E8;?Gsj-2rGwKva`$q9#G@xy4;9Ptcck(;yK_hU+3*mS8I2i$5hNF*5U3knteS zewzIdAC~nuE=Wm2Oq@hC%|&OZ{oOAv9}XkJvaAIm+6;q>1KFM6Q=Z97RR7NvTcgqdU=)z z!s~I%Pk@`$r5mP2iJ3+Sb((y&a@|^% zP@^>??Rww59{c{<=4JVnF(4@py`v6D z|3T*K|5DqKC0^&I+%IeBLk$5WImcjBU(qX(CkX4Z(}qPZX(6oceDUOy`xO_^h97J# z@ki88*-&9|$6R&sM!{F8w@R(Zrd37yJR4Mu)m_$HfCxg#$`?azF1?pPx??Sxh=+n6>Q7Z+D^cgcJ_f?MA12%5yA~ zc>RWCBTc9=sns>M#R5Ph-k`SLdGTo)s=-7A6_^0&s!sUZ_@YdyOeLveEq*AjKXwa! znWz(Z$Ab>-R>e|ezqa#LCYmr+c$6o8wV6z!W#BF;JDDN;J>1HA(AhJ(4n=pPa@DBa zoDFbvRHLYoqLd4US!CEzB^wECJmP|VrZ(+x5nE@cu+w}CEZHDSqdJu#x+N`bZwaG* z<%T`as0t-)5W(0@Dr%H***Vfi&TqLz5t)5ob+N9yFBvl150r-Dw*7P6L|nGVk71(i zTDzOZRxRp+a`>W)fQDs{#1b`Uk;pw3FnpX>9rUQtWP$!Kcf-T;N#4A)}6an*{=!*Mft;RC21cBfZWD=G+X` zVK1oG_+&&^Xjt&22^RPHoQ))1lt0G7!(K^HYZ$}3Xdg9e{+7#|#`X=9PUZH@e;vEuI|xZP&*)0r@iO%MHh#zk4tiF{j2hdo94gz_{d@<(CJ>+_BZvYyI;qR|5&rX`@89$$Af;Rp!QA?9cT5<>a68!!8R__r!BNG;_ok!^6 z6fS4d(7|x56Iu&Waq45H(^eJv_tqtNrD$K`%Ph$Igg>c{dQ`!;Y(ooIFa}si=8trc4QsEH z08;v45-g9Jf84#%PRJFag)r9^>Z7W{S2sp(Hv>O{i?0ZYiOOY+95AdPSEUFu0g1dk zpuFgFx&_=rXVWK*oE>mV&d|TO&s_LY%j-BP#ZLQeBTt z^Bfuou{q-#}fo($xi^u?U?*0B8z7Q$s9h*ZeKRoLT6 z82FX7_s+NnFJ*@o#g^AsJLaPoUH=m;DpHuDCYv*0j$lGhwad^St6Q0Jq%32Htp(eE z6sULKSL4RNQb24Wqo~GUVK5e_R&E7#hLi$RCZL@tgh%mwUA^uibC7oBZ|aIW5%}Eu zx^pnBe%3u^)=Nk%!-{>ZdLl$s@hYqD4Tc}vtPzm0E;l0Js%HtY>dns-ASE{vs1-2M zuHYD5o1xVyI>Pa$9zYlJ3>kV)WU1XwXbvjY8UEmLVj}JX_uQGkV2%A$4~$v-*Z`!Z9*%wE1CiETxU~tpBCj zj@MAYG(sExwuvI5LPgN0E^SDZh#RcpgQo&!4=~U8V# z+pPp5zEi3sL71D9n-aCkVqMJ7RML*B^s|vIXUF{fAl^@{mL zv7!zWoD`8w%PR~UrRS06m`*{b;5#3j%-2yU-Ol0qYx( zz&0KhO@SybUgA5(?t?*qH7$4zh-Zlz zH}@m>?R@H;n10eTyL-0D^bwtZId{=4lGH1X0#5P`VCaxrlx_5#Pim`U*a4{HKF{Ry zt^IEiSr=QJ+-ngqk?%Uu_`Kh`AYQ6QgiB}+iE>LGM59PV`vBs&*GN2}f9f#@bc&+> z;C#M3Bgk?E6iw-g$av0%qun>Me1NMD6Wma)U~}I*(KITt^!pox$M)^0wiRi5g&#QM zd#&6v4`ldCn{OH7G`m(mjF@4*z&Lb}d|HdJTO)b1_%U}Q4z&FqNEmC4p&d3kS$-$f1m_hh zMA`ftl86Y$HK)5oHpFIWNMc?nk3QDk`6wgR#<(lh;Q-9%`;GH2g5o`!Z|y{6u-KP9 z9UYAZ5`pv>1Myjd*s)P6!lM9cy&Hu=-Nd0C!hPLmR|#&2BYAir6)FlS0d`xH%A(!@ z=+{~yJ4j>B3@he~oaMXS;u8jk*VEPtZu9rYd76OiCp5KbVydkdYnD8lJVqHsfw4bK z<)4z4E^X_DWv3SNYL5+eZ3wKr^$3B^&eSm0O)~_wzGBBsh;iWKVKpz8gxgivqgtmZ~4G;gB%GRz+@&j7$Q&V*$;_xtm zsmIJe;l%MYlc9}kf5bSmngnr{9X*9bVQ6Js@u1DX-Ra-STLD_^goB9tpsO!q}<&m(xr z-`@=mRO0-OwNjT2+F#kcHn(bFxS|z6vj!aqsL@qLW_yg}ej;pca>Z~*_4g9`3{|k{ z=pvfyTJ&{6%JV8l?bmwNT}Acs(s{_Zh!0h*dqVCITXdSMPFjKF9=lZr)U92&q*N`y z{~Ygue{M#K*pGXqa2AOmpW^ZX&;4q0$u>Rvq_Q46?`z^zTt5BCq(={%-`5=u=Da=Lyr0b z2we|hG%pMBEiLE`R1t~ilch`;sO{S>2RacR+ZpxGA^CJpgZWIFpWw*e2SGP4@(q#G8FKbX6>~D)i&e zvpQXkq{&tf1Vp>DRgh3tE!v3Y!~w?#N~WxL^Uj3fM_$MwYVbS0b*;_0)Fj<{m8_u; z)CQizx$oX883aC#4JlM{`=S_}bp0Xu*f@&m!5(bR7I1Kc(f52NUCPn1D+9OL-|_c! zQ#d?#bX(j7jE4@Piyr^WrmTD{bfohKE#m*L{jdK-i~rG7NYcsP(Z<2-zt&$>)*UvK z(Z9_)DKCXBIQ0}*egjF*8+K~6IjKuDoB3s0YOdcF4us~?&y3Y|C@WL4$1RCtNI*%i z#T6aSLBU);0B|$_Q77wP@PQhmW&QO9(tI1|R#@MfW#48$e)m3Z zm;BoF@xG<}#qG)*X+2R?gIVM^Z`KeP?w;mPoCNb)>x2J-M9GOTXDVrT7@{Y`b8}7V z&Dr!)+zi~0-ulBtjdZHUI)G#q_s9}PtI;zlU>zy2g*)iGkwo6R3SC`lCb36DL3WW1 zjC_%G5tR%N+_dz(*X4BO?LdJ1CU$fWvM^r?*mW;5$i}LWhzTMxjAm;(wrJwbRg)&H zeSTbZ@lartL_7$Zr?b@QD-ObLR$e+{@>(K0m&xb%wHLfMxu#N>p_RqVx=M5CVz)^U zOttTxcl=z9)wSaj7;AWp1()U!K6#f~e}EG=rF4`P3&FK3f`P#9FS3eY!BhzH5J<0U zsdrkLEv*&lY>i^s|Ef3@XRGn9jFKZCX5=<^Y^f2?57??5(n5r_`c+yO!Y9sArN(GA z85hIjF2gz^4h)hk(A_F>((IZ`(Nbu}1FcnN{4xwvZT9N>vvF&sKMAF?%CVVHA(|{E zc9N9a8jv$#+B4Nc8tDeAc|Tf)Oj7Re4-hnJVkXDEuT7&z~61V%y5y$E2*g$=SM1j zIr+J$iHFuVHE8~On^#C>V&SIEVtjakCC+NMry?f-enUJKm6dS zP#oxW4yb`i$c;m`ViR^YPIK=4Zf2#eVE3CRSDzPc!#|yZ48VB@?wu|4^7t z^&yze+G36Bq(_rY^Iy5P(E**;5OWXGoCxmcXmX8M;U(=OY}Uf1jlL^M~a-GBOYkG-|g zoxqwdNS$+~p!C<&85js*Z^jEgi00TYwr*Pe7Hm7Y7Bu?P=jh7;Ny>cOD(@TvD};u zC3H-gNzbJH$?uL!0H`{M!Gf;|7dwt|+hx{-F9$K~FXgtbM+;k76agTeLFK4L8Pt@})7qWdPC!UInCET{&9qIjYC_jj&enlwKj1ig( z-}r=oPC|>2=ull-Yz%?Z8BEu@JAb)yI#2^%zfNo(@9mAcyaRNm(Nz&%rJ>C`$Ka6{ zZ&YDuznZchzdCb&;ao|bPG~anxRam`j@IsUd4t~5>7%~Tdv-buMueos$dF9A|l=Q^yJ{q+FRM8SjLb;`1+6O9Vdx6E$ zl^z>t4cLz;5@>)zBTXbYV$Z-!#Fs}QeKibK=>aZ<%`3V^m)8jJ&_JmTn3e}4&yl%} zQstA5Gta-eu2B~DSF0MGzTdTIUM$XYw#RNqPtgbpCsy`49cDe4x<;Sp{gcRBH7g-> z%8ixaCE-~pR5=j#_qpaLNhP$nB}C(QZ8LJwA`c5S|IkXWGJ_M?Cg4YESeN8RH{CCv zL75Mj=AG+u>n;D%kq7RX@9tg4C%NF$krsPJGze`iReEx%{VXN33~*_PfJhj~_$-JP z^Y4F#BAE{Fe_a1`;W%*r-iiO`ab4nn!g(wI*Ku9Y=ARn4|0BLo()#fSLi08@F)r2u zH7yTMv?AXDyS!S<9aQF7gM1KFU-#2cH-mziKV8XmZdWid!TkB7M8>^I(?R~$$BTuc zpA7&NQeeLAbKOr&);_)dlg-#}87h%5U^zAXp5?H0-!c83v5M={-3XWifrL=ezh!^2 zLfZD3caE%;9CQWVcM`foj-~3a{UCh9^d`)jqxUBQj2Ub0CL$m#fRbmcV`Di`Z0_(=A7*=suRMb@H=j6?SOu6kWehpUXt$4CS~ zJ7Mq4E5DG`#tUx5v0|*MFi(i;|NiXx1jd@F*@FPM){^xbULqT_TF`3VY+DR-9r+}S~bev9G25lYV-aIzOAw25ayaqHWB1020m|&zPBePkc$`a0`CPE-z zO(SSk*-dW3h9i?6Nt^p2b&B6W?U8#mQE2LpLbd$EKzZvS64;Bbe+1sO<{ND8EgUzi zrvAq7rzO(J(E=7TL7%ck=)n+jWDO#~Idc5|M4kdlLI zqnLKa7-ywKcx9Pn5iuOHlg1-x47K}F_txj6FhylV>Ot``o%fJJCmvSv5g#jk&;;7z ziY8^s6L#D5>~pR8F;jUmXX(~tu8j39+8H_E6Ae@I(XEe>fG`4(47~Qc2IT*} zff`Ez)g@NmTSicC4JfOI$Dvkd&G8~^9>;DBO&nh#*K8C`M{JZ&ztxPemQX>Lx^{)D4G%5>ERKo$^P3mBF5VL*t4VJK?<9b zZ4lN)_@OB~R|bWsJUdZt)ZHYGT}zk z7sxiufxEaIf-;&i`S}WPEErZ0|0O0)?)GvjbQsabvpQP2DgyE;l;dy=v$jSw<8QOO zdqmMn)$uR7SU5qhC$d%3A+m6uAlL}T{``?0G#OpM@P_0QpJZt8D)|Z8etlk%qVW+2 zo1Qcg>uBJLKy))dOV+q<)GQQD2!squ2K1qH;n@>cnDy6aN}>4(Y~f7|Uziet%V~+2 zeqTl;z8NUYFaYAD>O$9+?BuXU7!bSoTqjlpgpE);B_bs%tQZ66Y{dido<8hY)&zoP z`R~9HTqIw3Asu0@^f_%gm3SJ(+79{GQ;NRCvFTwOkHJof!K3-=Eb7*SbX5fg0beU$a|0+Hr%mvJ}XHB1Tjzr&I;pl_-=RT~6Hf7$mcE6ZIU1w*=K zf=?m-(0{Biz3$ZBUL&zY1RqcyfW`N-b zu=qA5h+<)KwCv8##SBSfn4Y!7Br7U`lf;KRtlvs8F~VA@Dc1O-gjBWds}Ti|Axa~N zef(Ogc*PC@*=t``AeB}S3MI~VIGS?vJmx%}vhn%;p!~})buiiI|^L{;x33zwyqV&U*c(VyO8iV1>q#^p_8tz z({$81ouTpO9T(R}<5lvukTk|L!EC19K)4EusFS>M&R|SomQ5ClP?9V2L8X9CR>`ey z$&zYZw^!TQZBFG88?`|#Y5G==L0u`g$8{0zEUD9&vwY6}L&Tq~A_%)ON?iy^jgr9; zuo1P?$&C3U=z+jO9Yl}G;=%whvG3|91tHTr=WMKA%XecmJgR^(-teZ3PuWcduaOl0 zcTq#LDn9;}10eZuqBCE1Tf~v!iX)*Qh?&G)ficdA<=pKu4TKc3i1WGyM@YHms?mIV zF%|aPWY4Ta0VBfXhKkF5EUuVJ&~9Gw(xbMJeHITzM1p~_JMXCTRBSryui`}QrY-6l zxXk9|ORk_BQyid^@qL7gQG;q!e|1$hD!L|2KL%IoXoZx~eWo(EiM*nEdp+}SZVMy! z2*CBwuSjxV@68{9mBrSEnNzD%bJRwCR7dBga^-1TV$RmW-*rw}I?w4D;{r{Kq$2{D ztqm@%3@B#axl~{r8buhi<)^cy)WiEZGir$_6}_>j3-;HjE`GveS8fKq^9Yp^+b9=E zuovGmfa3t<;2XR*Q{Dj^O~6mFGxAxPGk)|=)+K+D(e26`c+cxrr^I zyp`yvbg@Rown7Hpl!JFNu-GEc%+oEr5O#qSlU$H4jREhj(dIdXz5Szl&H(?2g~Fmz zB#gf_N)%rKQ{dR=QV!~nWc`t;B ztL4ixY8OjZ8HWZ_OJ1`trbTR0nPulwrUjy&EX7{(o?~p#D+7-3nF-|s`61VUqYiFc zd;mDG{lj(@=ow(pPoXSR5bhWFWnL3>0+L9YmPlP_NIZ_|$I?^RBpy8t4>SxdV*0dp zL&@xapPS&hk&{u#c2ipd22DR@o)g}>GO4U!c~=lK%)xlW1v!C9yVg-ZcB6Vb%I$7W zT?e?k@jRYT?HBb!4QMu3SdL{!E{ae37O5SsLg$_8R_jt7lzr6qHr=xA*2*Uu-Es=P z2Vo9aXO!mXMst?P=SrQ@6wNbR{l}Nsc=yjdWzL~!u9C5)RH)vW!JIR>J?lYa(DQHE z#$CUr8qX`?SD>uggrt^1+iWcJEgr1fq;A5$8B?Alht5ZM{{cT9909LzKNde{KdD&% zhY(}-NcGqhW9L+Ni zJG7aY+8@`EEbilsPcM(``f1kJ{qAjVuo~RwxRb#{;5J+0pmOns9ftH)qR5GQm&nOr zOCJ4u`t)=06jj}6{rVA+y4K#J9^=qR?0yCygac{hRmxiO`;7iA3Fu~hTM!Pe(=}r| z<+iNL1d}0qKz+>|rvY-0F106N{WV8uRYkZ5Ul%=={ zb(vBj{MEQqTI><|l5DMntiv_Ru1<=2;$ot4Z)asNI7p%Bb)$7&@|n1^Y!vWlw(x+} ztmbk1I(hY&D`JOSF+z>|DB)K-yw3C9nr=f6z}Dkw-Lx=urp>_&%|_{Li6X@yh4h}- zBn9n^KeYaud?ieHwr3!|z*E*F$)x6c0eevvzc1?4kj1iEtwvF@ZuN7#po))Nh1)M- z){9v8TB;g6#fvGAfJNjTX!SS|omcINyBV~if`O6#_yj`DWh)-bL?-1VhtHKGdoc^l zBb1X#pG~xA7H%h0xTs`8$aZ6nxv|Ykks1Veva=egR&i zQv=(=`P)n=nbqTQ5PaIIGYietnXtt?ke0wuyn0lcV1b!n{|n5CJeVms6g(5SrqkEp z8e>md%u>2eN|zO7v`XETuTCqzW|;FgL3V@KJj|@QcDC5IsHrSU=rFK&Vr4j6N81Gw zfUV!!PRUr7qI5qDnJeCutrC$B^h}=lhm2PJfWI+5|H5ss<42PEM-mvFxB1_fGFW}d zUv@twyPu*EFK}tduZtggn?>4RQT2J=Y*QB0z_85JB5wHEDP12pU4JGDcA0r5q;Jwp z(;APbktJ}wxjyWPWaJsezO9LY&w763BD1$-&#GVTP90-q%8VuaChy@w(X#Z))}ocXOCkWaJ%O;AcDkF>hP*!z=WIg5-># zW30LJ@jSYG&crl;DdsZy32%WZe>pg7Y&M(IQ9>MUQVEnhWwpf)k9SW%XX7 zROOAza;X3uZXTW${CY?!6m}kFXI^nsB^>Sv!<(&L=ZX_F!gT`;S@|=ofFmbPvfTQH z)aH?h`Dyu%WI8m7k4R4B*zdzl^#r@8@&czcGNpL6~bh}d?){(gM2>kwo zVtsHo>PXT9Xq^ls?&paw8TIo{rGqPT##3&`8P8r*9$C)@Pv_lTZ6LaYG-s;*`{a(g z^8Mo+Y38)mCs^8v)zzcBKYl(662h%|W+`)eJ1tljN8vsKpQDvX_N7FHaY1J63ZuQ^ zJf41H_I|#I#1qje%3$OE9qH0xDVBJ!2 zSk75>iH6_Wu0a5UCS5I*SSg=O>Rx|tind`<+90nqLE|0z3yHaRDcDmKQRZCpSgbDO zHG+1FB-<>XggwKGThR{&14yb?SxF?uVdK>Kmtj&Mwjv#mrMT-!#XnK`n*|j}o@ZiV z;3Q%6?J`Ow=BR69_%M;Bf3<$NHcEXx^iWN=JheDzi|kvYqQ@`#a;-TEljf*@!ol2;)9cpAzin9d8$(z0y93ecZ}iNsSn8G!Od9m`Fs@kR2`TB` z*CEdJ)UV(p7#BA9h||H?&Djq1sAVwP;@F_MBH4($(2nfp^sIajV^M+T+NkgP2utS( z&ZWC_e6*a6PQ9wzXaJ6iDy6O{v|A)rLE4;i|9_;tQ;;Oknl9R9ciFaW+qP}n>auOy zwr$(CZT6|zXYS1G9rw_B#Q$qWwBow|qQf2BZljN}h_?_I5%c5;GD-!z=%u8TRaCAj1DOv3~Ou1UgaHkvxMeH@Uyi%J}8Sx;ij< z5!V+g zzW<=vjE?9fg9aNh%Ot<1o5-&y=B?nhV8-iq)F9+O6?@bKlO-;H06aa4vNoilepmHi=VQ88&SIdrJivtP1j4Rzk#`m%hNuT|xz4!MpkjBR%L6tNJ*p+ctl&8r$_*HS`|l#Ek4 z_-h)op3P|H0g{D%CkH4qZ71gMj|Ee`JG;Z?>)wE-Xj)&vz_mO zxI3j~e2m_hVeq{2`_k|?NHErL;n^o+U8mZ;3i7A$r8ZgcrzQs6MYoRkU zI$aUMQ^zD6qaGea8HTc>+8rI$fx(4h`XE5hHzEl}0$2*t_{6?ILeU-Yw;s=_V2<}= z)A~+&CX z-fRfkG`P%Bz%keD&3{_5V2IO8wT01fwTtPGQWBTzdj3%hC3{y@FZ=_gWB${&`d6Cz zeq{%VZcO#QOX)4~2~Wvre=`Gh41CamK1JPav%c0>5Rm zVw7RjV#R{p2PGnE+p6?9{x^5J)Y)nHhe)Y$+pAKIp6P%vkGKMfN?ZHk`!Zj+ZeG~m z4svpQLF`a&M(&V`310q++(zJsow1EY+BFE!K)DN!BFAM#M84Qe=tM=9w3xn)x;4@x zj=94?0Wu?xFn5wut{AtM=H=>(=e3x)H_NNnb*5i&OsEzkFJ=m?Bwj3f4cw_lN^C*O zX8%YzzP~qeAhDP9CFCd=EI6Bai)Yius>uS2H<=~#NNqWn1-jZT+$D!Cf+$7rtHr$n zG}vruf#D3kZ@D$i^-l~YHJHeA^EnVG#dt8e}ao)R!ur^d@m zEEL}bu(c}HcQqyZf`!ZXF=(4&9`Kn=uIo(M@=tQZ3-!5jR~Rf=Ohk8)H(hIjjIT29 zu;i?kbkXkz;Vm{aGtKU0rJ-rDvP1#P>^T9>>=^;p7!dg(W6ADPr*%^w2FIq*r}j$k zZNuL~%1~-qRX{RrO6+QHq7>agxJ&CdW$xFF_bwluf1Tn4!?QJSBY|0&@NIY zLDZhm9k$ z7H!+1@po34Tq5l*bel}|%mZ(q_&AIq;K``@ChmUaUZ>0z!gKBGo%BSiSgo6>s7}8$ zu>^*93>NMd>4+=(ou|`J#;ikS;ZTN}Y6koD8^{=@=IO)FO`~XO>}q4|`2VPBR5t#N=KCw%k#g1wjeX~B`pswOE92|FCWZ%~7Kt=pEwFc)Rk*6K)kyy;?l1rdOtd^p)Bf**%hcwkt`beZdSQO61Z(zc zlQzyqgCX$WIiGhQ)de5f%5W5G!~+hPON05);Ftpc(r3V^hiV=(i5jO ziNR6#EY_`JGKMu(3wlu|jyH@z*QIAeSx<+h_gX5CW#ItVl50oKkqYF7$R1yPY zBG%PA!INyCri4t|%h6(Jq@4_-B~-R?!M5C-U!TFphmVznAP@^SAXRp|g}jrE=28$_ z%sX}UGZU>CCjb*7Bb39KRGXkCfrh|%NZZWS-d~e7aYjm@g@~O!>v-&}ZPQmEg^c@n z{hlTfZkV(gt)nzf`@LOAtw}RphQC6CDQsZfB9*4Tg0_#nU@xtWayRrR3zLw82xikN zd^uct-RBC&T1wF#rdoN2wztv1qf0Sl099&l(&<2L+=K${_<)c3pTLrIQf<3mU%0n2&6O zxlzj#0XZuA{nb9zFIuG`=7_ba^aDtux&Dvw@6vM=M-7!uUQ@QGjp-Ody5@x4Ksk3| z+Q*G*I~jgQ&zeYC`G)&7zdi2YYnWX!QLUC^i-2L9ye7fPq}qc!HvLky&2_c}b_Va| z0|y^rRQ^8XQetOfl!Wf^oMVi}JHm-?JZw1Xe&r+djo=$9*A22fyQ~}@AmXY_5or!P zjHWXPU>nW=yq6pCOk%GYzgOqlFtLi)id;;4lzT3#;}|H|Br>(&BdwrdzwL4`PEwLs5zoVScW9gU2e1>m-!LSL1z)Bj@ z764h+{=ziRw=*7P^`y5fo?y)ooMZJwj}tz=@Z#LAK8Fh;UCB$`dVaa6+(`FSfm6xqNFer#NXal&S5#)lgDNYmaHrIndqPn5uB0`ygd0I# z^YtYtVRZpjHFD);sdw0#6*1%(maIH>T$tFyw2+y2A5|t)PQRqK>&uF~d zABV)5V#b{5-nIq zU&jM9Wo)hA;s`E-V&N_F_bnp656LHOe6;dZ2jyDAs=h%VE@LqID3fe*#9ld)6!E96 zjws^ZojQ7D-%UGjWF^~LMWyKn_h?{XEyz7aj+W|(#!Z!}wNSC(cz+UQ{r)`Y&QU%s zjg|}0pf?p+fx3xDZ^7nFm19dBtELbt-pW@wo!*GnsZ?HRYO$(TB@;i=j)<0OKX6q< zgJ7}J)hD>|ARgFcs)DgrvuTpJ5m|y}5rGzgM-#r%%o&=r!J-g-zWr+7a~MsimMN0RYm^Xkm&Xp^9S^(FQTiEC;-ErE zE6AK~{Ysm9tI?p0R7YE(G4}ALFYs(j?V5om2UL$#=@=UZOVpTV=ts z@UTqa&))^RK#}`Vu?K0Pwf4iIingIY+BQZw>P~D4bKOm~h#fh!71(YGlB%W{*`aDb zwDnoPlX|MDq@jnsm!ReoL=?tB53M2+QMh8%NM_(!=s)k7Yc1MhN?0 z${Iv5Ac8K_Lq^0Kq>BDz^J-AWFlXw|AwQLrdB&&3D4bBWkrfTFtxS&Q;+7Q!qP~pC{k_SP#i$Ko_E~v3%Zmrv3hY|H)PJEB)7}}b^Rfx`#(MwO zjrxo&TI+}R>a2*{l5Ul0HfORjO4*c|+H(tW$zPgj6GLRA?(Gtc=O9esZYO=@Sq5kw znB^thKY4rt@wg+7cweH)`C{9l^5CVp#Lmtp_wa2~wpgNiiec+ckSbUt{7da@#FModi~|=Y z1VZBnZveX~xzv~eLIpIsb*x;Cq_=yja zxH)dA+bEp6Hu)h63c3MQ^9c2h3rIjRqQB>Za)ZhNbFkL-6Gd>Fp@!yWt=5RW@RXgD zujPE{Td{4T`_%m<_RjWE@BxR`tB4<`%iN=tqMFwsl6yLSd+n!5S)bbX!00miV%&bh z=edF3-jE0sI$?)N6V1kG$&<=H#e+>6qtl^vU&^^mm}kwDLeh3Az}`K{K!=mh#wK%A zIXQ($-;0%e+Oj4Yewr(F14dwI8-ES>!XCpjEb|nBCDcZa@hP{cx{WriLR*jVLakcZ z?@~S0z_S(Zu=L;g8bKe@sKklOXS@0873;l4sEJK;z};l$GR?-^GYW`z{+cgT-;2px zF3hCS;u|03m9?q&++$QbgQE|1YGKK%P_e$Y z67o_6zrkR}wwx`<1LJbfL91BpEAVIWDANYgVC8oH5=%3QL$U7WiwW8y)y!(XMfwKS zCr1V+5)S@`hwWq`Msm}5#caz1YM-zi2WafaU;RFtlsW7X@b4PJi`s7)g%$zw#LRM7 zPps0z!gloT`N!6FQcKlq`04Kj|0hS;zfwg)|C3*fsPT`P%*nyr@IN`DDwUld^zEk( zJKbdCN`Nw`T<$!^LLAXp87}Ug^2ZIrQn=1Eq)}+ooZ>V=g6YDFEXQ}$hyGJUKZHKg z!v~B_tt8@oyAnzJzWaBtLN@xuCOI~^QBKmt;byDj#OH)_hx_I7>ucx6=hrPk_2}tv zU|?kAFA@#-{z55fmHxz2(sesP+fWk?Cfo7UzOmUO-`%glMa_J6Vk=YQP8jJ(hy1yr z2zL7Pf-J!Y81KIXPjls&HV2@k_rA%4^)}NFps&aaMi-6* zqBjyWrVG=k$t6jf0smxwjpcIM!etd);9U#HJoJX8ED( zrymp&0T7=>jYYV->Ij5+!I`ZOAda2er4SUp#s?vU@igPatw>41hg>f5*^bvZF}Kqo z-#CI-Td{rMh&%^lRajl@tHrTjrAg_%r{xKZ6;*~+QEm_GkE74@)$U=RA_Ke7nnk4h zo6e2U)%r21&PJFbbq3N04`40`^{a!>8s_)|2P1Wc10h&}{MG^iI#slT3qdNJBh9PS zgTEnT3weN~+12L%Gykw#4*Z(6pNms+QfPkPX#!d1)?_8-Cfg^hl`lcvC@)==sygBb zrR7SjrE<%|1LxsQ=5?hn#_LvFmwB+BeqEiE2(8Io6I^7{c@t=#r{M6y%O`bKZ$5nK zrEaDX6|y(_erWcG?$b^NOK_*0&v=DyNq@>71hJg)Q>#p2wUp#a!!t=Ot_UEBZith^ zd;(d4&I+pJ{H0bwzqFKyNi}1)Bq+g0{*|bNL6kUFqM+6TZj2jnn{>Xl_e6}80T1U( zu};Z_j1g0kC>Wt3KycsyQLy3e?$OSHh%-(qX3~VjFkx)ch+*1J@9DuCm)EJ0btj6} z82JGySaoWIyn6c9%-7=R!mmlv+0d2XFQ^FyL|DnG!2(QhmQ%rcG!7U40qI#YQZ6fi zJiOVajH8lH>6Wl;fLT8LEPNXTN?TO#qcoFu#IEXgIbBo67+@&ASo2kAK~8q!IED~h zkie&!`rZf;o4huhGdBF9xo~^fvI>JM!mzmqCWBS!1H7m5kZ=DP7Z4Ak z^*^S`D$?-pVal_fXZzx~it?0Rlk~U^Un~Mhor&Q>Va|^t*tg`3v)GP^jTpNwxUC=v z&mN6wWQja>nag2G)^WCQn@y3)B%8*Rp1(k!pqT$yD;Hb4fqZcDmACNhip#>|5&TM- zlVFXg$T1W>5;rN8@wM6#*m$avt6l-IPxi=o-mY335_3icD_57lqjGx2V{PzE)g_9e zUCJF*MtaA1ZKD(P3RrZ7Of-9$Hf{u~dmxO_LZ&&S?m6cdrZ`rH=dec;?R?2%lORXC z6$xOnC?^ri{C?EF54$1Gz}PPwYT}U1VJ6~^j01((oTD4+#_L%j`=nJBuQPO-ye6?j z{YpT4dMoR$o$}v_;;@ipUQGAyRk?$BDLeAA;C8CS2@Cf%g3wH!MXwU-NYV${q7eY_ zA;92O4F485c~UKh?pd0><{vNF5G5CmiviRc1{|qa+Q-J>6M~V46GsNUG z)!^~<549OTB_(#pkFFr~pZ?U#5hy1vuZg8@2*)3~x<;^?ufW{3Ud@oL4@=ksIZ z=GQLzD;tEhU05%P9k>=?j9#{$UoR;*xPU)FA3X2qO^SAOwK)S2kwgJPc`} zwo={NMT^b0dh2u0AGeqz4gH!wY7~r1JovfYI}_vpn4(mwQOH^9M>$CiEY(&RcTz~n zWHIjUbv#sRet+)ZXJ$%{I+>s-tUaOwmgb|Op|s5_F^U~2=)5g?8c~!vIxf>eb{wlF zC|ETb?W2eUlc+hOA5$7ycOV5Opxfu(i9ct+S1mxkbj))s%MFtUCts4#%dxg|5N7cl z+vXGI9Hn4q9S2bgI&CmCW3jXtkds9pL@u|x2D z(v=Z7eH&Ndr@L19-FLn*LNS&r;X(A&n^*=Arl-vI(CdVFEALc4>r@L@hS|q$ZfM6U zBXZM_39KyMUq&TL+hZ|f5pSnbP&{r=b<)@6&QL1BB4ipOBkhhqi?V#uL{&NNe_q*F z7C2U^`Y6q8G$(bc^?cY_>yFrdeB?})t8=xX!0WQIfqB(|@s z%K`77Ki0QsT+u6}bQJ-l`l!RN8t@zT#6TCfuy}KI-XoBqHIf+|a0zZ8t6=t@&RY?4 z*JhYpAhJM-`7&Y!;KCnvve?N30sgA-S3{I{2iTsfxiYHUzv$W26s)6Ml$8!{vAAN& zY4x;XR=!HZNo%Z<&*g{IMj$Ic$_X%Nsh^X8qs#==YolbWg0xieS9az{N7Nazor)bU zn?-o0;yu+Jv`A&^4+*K*^Ab$e9B?IVX2(F1y%LF8&kx;`BN6}LlRDocNaE;G)~t-F zs@>yBvN+wtBy$bMXE@!HQlXP#32x^m@EVV?p-&uEQ{0Pu1-wD?2G6JiWR@HI2`=Sm zHGDgJsUJ9E2GMu!hy2_EQof$b3fs3=R=pbn1m z;72?^^Z}h`>WVd-6nSflN!%4PoE3TTPfjq3bqu7Wf1Y<%?5Qm-c30GNQtTl(Y595H zL@LWvnma$^J&W1dkF`me^$E=3yHfugd3X`p(jvp=oOU_!P}+J$DhzEI} zeLXJ?LAtUG%l2G;ONlalU11>6KuX(4`f5@7%1HXiU9rPS(Q{U*Jh-giyBJuF_T=|uh`$LSwXVz5u?3IWy z9wYn9w&Tp(*3V5oGvV`XrRziJ5z?DTG2DT{S!D=;_JK>E2Z8AVkcNlnYJuHPVO z$Qk9PR!wpq#szGcqiZ7l#qG@}o+p;<2=b@iR(Y>A*t&{pQi4c3zSMfSSxdH|Q+bLi zf=!t>UMMW$Cma+Jfw=@sg*bd_RTy91bGlZjyR!>F({eo+LRxfs8K43H>w*vcfdxi2 zzbNx6QOR0#fiBN=B%XWJC#zH&rU9F&$l>7mRg0!6!Q?JPRy!}9#}2L}?&es$iju4v zMZ_qAHzZ9}m-3Q>L2eHT^-E27ieJvfFJ$*U<5o=nK|-C9WAJsl8k4R{jL0db8p0m{DquNFL+j#6EhE ziJ49wv@tRUiE^G}C1&0OWS0mk5=PMqGKL|&3@Wlm00~mM(GGcfve_M)U}7OmkP`(1 zVIN=^oBQDHC#L^v$z7?W8f|JZnfY;|BE?UO4;$P;ZY^XkG^u)^Vfrz8MA5zteK8S;ZxEJW^>GH=mPM~%JnxB&u9avXhw_VuSzdfn>)PWT6f`XPhR^rDuobE@R_M=(_SV^)_y z*=P@9APzDsx(2~TonCMAQ0Eg_zso-!h5tP0kc`e zB1jcJg}_a!5J5ENf}65W_Juj&L^$~nTzYZNqf^%$YsKW;D~`S;h?zEygP%0t2u|k+ zbI6LQ_J-Xqc>m6!#Q^?0B?t0oHxr$^h|@ijB_?4u>i1y4SN6p!QKfwPQvoFmVSGWi zgz=uPajI!iaP#}t5_VUEOx)22#y)Ba%=HV>5b%Ibq8=y}JFTfGWUc8_kY{%+@5@#U zCj#cmbqELg{o!@jNAf(m%amxa`TUm zDD4N3)^))<4%RM*lr2adR&fh%)ypE18Z8&fM9!HKTe3HNUE(b8s>R(uus_6X=ef`y z>`w&xzZ1Ux-*FKCao*`${d)uF|BlBoj^>sDqK6aV4Kap+;3bc31!PhSO=igF0}M|( z1*>UFGqV=eF$GaA_}Ti9^q8A_{kGkAlL31+pup{@Bv=T8W+f#5>)2+~+4q^U;)Fx59;#0Edx<+I!vN#e@i z@AqrWExwWyCW}@Ta5!L3`dTqaa?w$NV}>DH8GZOI4HCYu40D;ja z4K9kuG)`T|OY0FDH#Wn)wzOG-IDs39>I?X6*SxSuiw2arSMlyyJ5#4=f7!27@$e6woKFKlD#6d!f%XH}{ioOG zU!gkT|EnGU-|Y1%bttdIpI+IVH1Y1VF;M{lw_s7YxY%FtaET>>Mu0$LM0EIQaszY^ z#F0`a{a%cF^2oSHQL~UwP1=|3%VwIIO(cJiW}97>mb@3YY&12uY;Y|)Y`3a3Tjm{m zZcI!V-u!`|UoQ4(ceqbBJ!igl9H+TovhSK?b=bi4Sg>6UQF!d~5OFD9X<08x9(Evo zE<~!wyb5=HH|^3UZ;-q$gDn{TR_wmmAf--{LejL#8_@v=jYh?h7%Gll|A;T_$r2Al z!p06M3R~&tj4~nHHdCz_Y*>Bo(csGbF-Umc{Hft`_VyJ^<>CYgwUnd?kui>jp)sfr z4F^~2Izgi*w!YvaeFc>Ei|?5DXohw~vxr{v6vBTVFrFmc+KrxvYPr}Ek$wMiGJ5cl68wP{l^ku-8=1z0i6;xMBc z)$)jKUhn)8k~z*qNX*j`%7r>M#g`10F#6mwl_*n@Wi-e&Y7$h!ewwPz9a7vEI?7$+ zXT)Lrt(@jD=Bkk)KLK451THp1!<94Iz;Ij5xwnWsH15rStd&kpf^6`S+`OA~a$3d~ z+P5z%%++M^X!X^csme(K=Y$;b;ukMbUvc$YtA_^s#2Qdm2I@{ZY++)wlN$662y3*Q zKi*%!4L`Gsmzgihy`;A}WG%Z&%#8)5D{9KO1twu&i~3>}+90 z1?#T9Z)u|RRxHZFSC)qMuaf+x`RpQ8&?B9l=px6X`3xpD$BhWE%CsuZ_O$(`;HyZI z4{epXa8}3CGqE-B&aX}*;cT$9fNaU+(dQraxHi+kUCom&^7pEL*^=kIwNX}*_VcT# ztX2SkJoIPR;du&}8R%Ef$_7LO3=16--ht&oFZjR^MNOTX01x!#j+#EQf9r_$2`m44?vUi2RO7 zucsWwL$Mp)-+Q)Wf|Ea0IR?y&g^vcz2Kdwd8k2&FzQSRkt>G;tTe%bndq|hje2{-U z`_7`QKGVsHFt-jASMKInAK+Z*GI@-Kyuv}~x7&*h3sgnd9e5g&3f~0JdwqWW| zWy0;K4Ny}rgs7iuy)SU)Py2Y{djhtVPQq+UT|fXlHQWhRZ~jx7X`@y9D2#`1*~BV( zh9K&5D$S=Zp3~4i1a;#1Y}ygq{%=_!#AoJ!NU)Pynmw{Q4a0M2h?^-AscA8+?o?j% zO@$ib=0Sn9?K*Qua8+aI%LgO6(dScM2O52o;nCJ*lsW$}i62%IHW6(JDHJLaJt6dl z$&|pPnA$~t&8fnu*(vm=*HU{zYZzIQB$;$$or&dh6@ZdTHkc5fnkKp!1;)O36vD|x zR$wO!*T54W|v!p%$uzD;4x8^>J zY^c$r)G!wVI=8o!eve)fgLiHv-hol^%1pdbVen(>H$u~m)AJVfms-nO#&DVeR-YQF zsQ6Q?7yD{eEau9iQ6P}L3 zJuBPQB>H=V;1G9f3f;|o%Pc%1d5ywgQTU7j>`4T^>^15Z#WN%|RB&Yx?W6J~A|&X} z*DsJeJ|{}kT5O7E-Q`KT03JG_+2P5@GzI(HdzUTOT_vn`E)ee$`Jp|0kC+`7Y`@oO z37&Wu>u>9^U$_LwFA&s%;JMJ$6w!Jy;kJ7K@WZebuQ1=r!mu977Q!tO8MnkqfNp_RPPc6G?gHs?#Q`{ z=B?QZ_L*{&*Cp_S2q>K8l#0-9vN-HzhSW0^%`(DKgYb3wTa?rBn{i3EI=x=&h;k4? z%%PX!{!~*Y%8`p}Q&^W^3*5*Axs*Mkw`b9vDdJ#LZ1LkKT@U`iV6vXBrHz`axdz}h z(LUf*))n*GPAzmB+<|ieTqv(+`^PO6#u!?q^IebXKJ&t;$&m2{^dXYyCbyk*pIwcr zVt|~1hZ%0+j#Z^~z%PZnTAu{eFy`6TO=*CWaq3Zdq9~K1k z*Xr~$TdL|1V~(9nIwP1AR|SHf#h7O6e)t@2vAXNR`Lp^-*9C-L(Wj*XIfy4`V5kwF z02YevtK!G>M<<~G+*lQln9L3CL2x#$fe(k0B9+hTqen4b95qqG1jCw(S;=<=^hnDA zTC9Z;NNYv9>+QqNri)3Rm9R_0`&@rYD7u4})5}R{rcrgq5mywTdazY=56ASlHPx)< zhTAU}^|d~UJscP{x#FbEfPRvxB47+=nNfSzEP*@(4r%T_w@AVhyyQ`dIpvFPR$e(hkOpZF<3*1?nEV`^-9Ma00Bwa%}-R3ud=BQ~OA?nnWS3kdgm6Zj50f}dwL|>c! zEvCL(eg3m)lV%+9;Bo7`P_b43KxJaH7Y+K@Y`3G#3OIIplKrOP{p2UK=fBX7?G%7wn?zh9V(gh?6@zxAr4u1Z@a>b`meV(l zWM}&(F4tBC)_l)c+mabr0LCtL%ux2&J60GW?h1RKs+5Mc9NaQmrLz=3K7)aGb8;ha_`up%Tp9pn zDHlm1)$fsL2z0!MLN!2ADFQcTCiqKV=(Xo6w5~6nZJ1HnQIaj1){e6ITE+(>8)f?hhm8=?u(i`kPIrs%o+dG!Us1HA73 z>e?wK=JYeK_1*0ntL@?cjt&8Xh~_n>z{Vndy^;44KMo?KYJmDk;f2k(lGjq*jxhJ% zcKn2YUV0c!TaKvDXlIXB#MT`oTchvFkR}{^q#+U5yE(AipFj&EWs`Mr%=SWnYQ?DB zpC^cNaECl{_(aEH{CqsgY>?u$j`QQxq1rnYc4rk?%<79wKA~IiL1~c5zyE9yfwUut z3E0;1Msj%Fn5bW%;)alSN!|@wET`CbwHF~dj!L61`;*J8jU9WVj zYzcx$h16+VwrfcavVyq*7>vGW%^Sv!BEd5$$3Rtdc$OId8{JJYg5I?#lzQb35sea@ z74c1Kk~8RyvLh~`$3a8mjqRtCH=ESA--1>T=^{spMJg{7+EgkDii7RBo95sgv#coN zaQreXbT1*L>W{1}tCPp)TZ3bw!0PIljxbt#$s1b@Y;cyxa@ zOX_Kk8o|^Tnh3ar196@XmG}Uw4E)d@33gE;!T@QI}r2(D0#?>6bsvcCzz(uEpMn$zTgqwF8rngBbE9dArLeuB`>79MD z^1BF1>FC=uLbcWXQ8W@!rsm1Zq4Web&+g63!`)^>=$#s7HRDF>Qr7h^v)GU9Arhc0 zlbW7C^iC+sj~EuG!q4xLW(7C-Svtc$9w1<+%3gjtte1}187l+okH%gxPc4j3sBS@J zK$kPBcjOep7srin+6g#(vlj|W5ta`dJ-%p#QgZ=pg94}Jo>DVUdX~% zXG<-q4gF{8Eot#pWCb~T_+LoQk1RGt zuCwC2BRKEKn6Ic-ySn>qT@j?G+?fOq?bN0NSbAXG)3Cqv7aQhFWn{{Hqk8t3A6|W4 zHLHIKDSYs3H-O4eJ)i6xfT5I)r+J6csuh-xy@Gwp$>>nnA115b zF0fN7u5XUk9U1=`lLi=L9@hal6iw#4um7_ePVM)(iXo=M5~~2p;0}l9NgUfk<#%Wb zMBV~?k7$Yaw#Ii%ANv;YYmLtTrvZnK6f{tjzerwyOWT5K`m^D`}vFd^#!iDIGrX8Um# z#HQNQ=|o{y3|<0bozsLnN6C%oiRP=XkbyFENg{lw>{we{SF}QXRJ;0lZ&D1-O#Nx{m_C}R`b1r*Oy9MbE{Wa z!=b;00l^`m&kHAKeAO4Q|Avd%QYh{t{6zF$|5NGhzf$0$|3?tU!PwN{$MN$cAEf;U z>uqOcEM;zEtnZ-kA20lGn9)0CN&<);DMu<%>4{$K?=PH9m zDN)DO3Gp{lh+hjK)et62w_SBo^B<^^9)v-bq)o-hNl?p0mYSwr(Ge)B>tK)?KJH(- zas6z{XTergrZti@19JTOf1K{Az5&qT7)R`~hGsgWvYeymv7)xzU~6As{%ySdd7ZfD zKf{aoC)n{{$NPVdRs1jGm6cNb?ayNc=K}o;(hb5y@US!TC?;0yVvKF!(YdX%O5z~io_H=EupJ2HWN-! zX2yJUBIXS|T_1v-)+i4I1c^D3AhaK)o{SSUkj>M)(#l8+G5B*3ylCAOdoOh7IyVu{l8& zBSOSwTgv3hV2&m!L3kjGH0{;Y>aOEaE3fhPuN^EN?B#b@IMbdz8FXKIm4z z!l+FY3B$vq1X+O4Wm+k;n9R3cA(JtS+_1Vg>x!Jy5~&zwBz~vQWHhT~9CF0QR&s5;2@ikU6xC!{=}>ZL)DCm8vVC>R<{u)$N;k} zT6O<+_O>gu@j4SEV(^7pidiYg%*Z}t*=&#SoG=fuhOyFpquDNYQ3&=(tCt>=^-q{p ziTL5y>t&?}qj84_z9M-xM@pLUZbccGq4-m+5U$4J;-vQq~>=-24uj6$&w_4sx~{<;8{Bj84T2_(plKy-!!_z&xG3aCB$y5OkL5qhik8&_t2r zH7`YeZn>#=zTzV(K_8IAOkT<(E4ShOf;Yu9z*iR>-F~*`Zpb_Hch-Ghzq>0AJX7ax zy|HWdz%Z)MU-7HSp|{%X9ZlFT)Gn)t8PyvjOva>5PWj1M_r7NDII7QH;Z2;hMq-?$ z_UW-p0zZLkPE!%COJ380b1q&%e98_$w@V3S$`&&A69+Rme1hnM=KhWp%A?g_nz&V8 za)>N^<+%{-3xJ5LyrM*!ksdHUkt5kT+sikSw%mPsf zqUvr4W)kopQxdiK>(|7>)ThSxbE0j}|D@hc{7bTP^6g#YYx>}iu*e2hdq|RS#pE^)w zP5_KGvBh0N%8V@}Yt%CwvD;1A9*hTz?7Ejuuzl)4WK{fAl>V4f1y-&)%ydRUegN_@ zv8TB@FN$`U$CljzaW0J}-FZci3`c|iL(g!4j}7IzJ-ja%fVw#DEF#Eo-7<8jKT8!p zigmaj%s_+58{4C|rKra2{JrO|6S36$N4J|9%!WF#rCW^uNVoix?XRjr*@bFTxPuoT z(&}8y8G6|nMx%+xOAwPs;mKPdqv)QKHr;*KfI)oeGX8BY5m{yrw!nkK{{0_24hdHf zB3j8`dZaseT9&NH!vY#%bhl9R5Q{3uB)5ZAw; zFPp7l*o+mSV4Rez?uLrP)pPkP>KrSU;hwHdt)vwkBAuXs8sJND=Z0_2Hhgc~_b5{u zW#p&Hzl!6ki{tJfJ<1{3dbQ6 z?;&_WvE}`?l5Vb_W7Oy;+&%Gq2NssGr)Wcm*9U?$o_r|3(r7+|K6TZ{d@JlP-Si}& z81G6~%JAP-p(8n@4~|s0=32r(F3i$<7zO_B_T>Gol!vcjk>0$Jm$wfdI;vnpBI?|- zjRYg=vUJn6?(zUoDku4K0faXQ5ATG*Yx9MITMoK!H){!lotMdFxw;h^mf>bs?2CM( z%m0Gmfh2Ri_Ry0)2$j(e2HzAg7HXKYuFeP^3WcgEpOVNMaXOI;?3dpF_rJeO{hxQX%>Se$QnEGtMb259{P!1kk=%rIKOYiz0Ux~F z?U#B+Vicm2**;+z30kjUK4b^RL{lP^)dI|*jl&+;tK6_e02zref{DXPrpI*Jh?j?t z8;ETvH)IA%Gw`@p(z1X+m`ELbYKsLdAbXA^CD01sMEOFSnl`uN?A@&rD~gU7J=2Ch*IhA#87Zbs{)318MBt=uV<72KW9Yy%XO)4A_1JItHf- zL>h4gk?+PF8GVa}nk(s^MYIS$vn8{V2oQjP4rtVrBLN~XyXhkM6)54GI=j}<7GY^Z zi9U1^s?&|giX&Noq{+4Mb`=Vn7zIwk4y&*K$p=W7tG?;}7Go#>pGU|4b94Vk1(}qM zp^>G6t&xG5v6;bt$bv$y21d63Ta+e#N*d`OQqW8gItNsbzb^)A?LTiQWc^J#V18pF z^sG4$2FNwp1x@#G#ov*f70`Mk$tJpEkhKJMdqB6c!y7>D2>Ov3?Y!(K$DCqY->=Wu zy&TypbfIg1900Q6Nf@1lH&{9*3&*?*q;p>a>(tW?wMo0Htfr5m1|lYCX=@PrXN$!m zcL+RH&5LQ|+e-#$D(IpN>`GNXt}%y7@LxJN71~&pnHOX=9Ev%UE5N1@zmzB|5=6bu zGi^^RCan0&l5yzu^34#wQ%A6!b0FFE%5AJI{1V^1)$X+t;GJeyEmBIhXc+5!ecYT$}@)v3m2`>1Aij-a!wL!YAAYDGhC|NBGzTa9}t9AW=t9ut*F74WI4M+i}-Af$`u@(b}bJ`$u^ zgM$=0Sz&$W$Q!J_e6&vf?%8R(!)(l4 zwPSal^TpwI?)1^4UC9qRv^`;WXh&dg{Ufy#+i=HEBp5hoVi2`I|I$vJj@-Kn4T#Y$ z|NX%D6g2jx7*zmtSHh_=`(MQvX;%~UWte` z_>h5^Knwp?FwV@?w)pNIw=k2HIwZ)kGoorX)4*7xo>0_WBcM?Z;7qeBL-KZYFS2Tf zh~K(C3_1jg6CBnU5h!$p3T~uBasEJLyl9L5eO8X*0%2XEf5(XmLDKR9{sdZcq#}he ziNI7qS!0pNLROk92MY!(hb3`G7WASVHp{#RawTMC7e~q8YMVW_5z>`G`8fTWS@_3^ zCUQb<19j+2L@=!cCYYyF@bc~Q5~pB-*&Pg+iE#Va9y%X-Yn*yiiFXZl>GS}{cuw|W z4NuAtc4X!Q2E#+GuX+(oW&?t7`>`Drs$MAoep*P62vjb=@6B+|wh?3HkqpLx$i-Bg z7`bk_&NfAslV*>N;UNN!jMVY7DeB|YK^F8Wpm9q+9C#-b+l)f+ zVV-7QY3P1E#a=;U;wJXVn+z4Z6M*%jecL#{A8!>S=2iV&Z?EAZi@V@u+F!+EIY@%L zY!Cn&)hg6?>=rSaI-Mg+gc!rBF_0D*C&{T+wEGOgr(pmb29Z^Vw31HxB>WcN3=7f|U2-SfQX)QPX}U7&lAl7&2# zT!d?FdBp;YERES$Ps0z{j{<|~_e5c;8EP_x{`~h|3fkuFmSvi()c^o$(UAx%26N#3 z2>*VsWk2IhAajMcztS78Ktp)?lHilMesS`I=pg~;m?&;jsHO}Q*4oUA{pS!vBrV}7OlNG)G1TR2*#l*beV*hCMTz;xWF016yY~LK zSPIQIKylUEe$ApQ*B#Cz(FEiK-F;$0V1;@izH+awO2 zKoxoMHjpCSo6?p;EZs_*(N}KCa69$K)jnX=Em(jt+-+rlFP(c`cBk2U&n<78*?YNc zY7Jm)$1WOrs~r3_*m8huPORzY6nwt0f?ePi%or7qosZBBiK>zMtW0O@$Zc{H*>>e` z5ff$lw^#vY6zMb?G`D!|5s(vR-|ux0$+F7TzA2O?^DA$lIyveuF`t<8*J|k z#B`cC{K6Y#A+Ohfcyq`>>7`Dh=eR>si9_UKz~F}mLU-Xku|?=2MeJgK5EWcA3rKH~ zevEixNbe{_OkR0rny8}pVq8&th8>zKU}wW<3qW1;NPnV9Y+=z|=9?TV556T{DXyCX z+{6B@n}MAm2s98%1`+&>4%FpCZWbU<%LRq*p9}&#d5|fbws|mwlaPyC(J_tf!la3R=Q2 zXYlu{18MvS@kOt-@KX)?|I`o2zSd0{u<(Dr%D860${#NM||+ zqGjU}apqz6MDGv%nJF#wJ3xXz>yZ1QYFdJ2*#$o2To%R5JOf@BI~t?4`2jIWdScLJ zR;n zA5%TN&Q7W@JI!3Un8z5&wtV#=XZA1_CX728gPMDql=3hO+n;6H5>w}#{*o8Dg?k`O zwZCL)4Le)`9(7LE-Hs27ca<1BF-@2~2W`FrO&Y&e!_f8z~%DmZj_&#yF$-@0U zs{{W78RXa>^O0qHpmD^sJ~Fjq`(S0=Jun5d>6wxN*5($P@dblLHZs6=+Dj;n)n6dp zYMbg7#rXD@b?4yBU=!=;*bcLi7v+Q5XHi(1%MZLm+WGzxt;VyyR^HDeJfr6*#%H9U zr0uQS>#5~tm)C&HW7y9`Z5KB4)#Gy(oHpBG7dJCC#^-Q`x4wov6mOo_?qLSzGu7oY z0#V}5lik}N)%7R>rt`2j6p`|l;lX{#FXz5qCCju=59cc~Bc~yB#dY8UrgN{C7VEW$ z&xs~ZYG__7%#tPveI4r-JTwY0$to>RlZPeoCcH=lp&6AEg_XDVGE4=yvMsL9T3z76 zlIwC=lzY8V{2#{IIsxl2g2I4s!lqY!aAcJKRRJ0(@NO#=d+@;u8{{xhGjVP$o>YR)ZOGR z-ai|R$fFioYXanZsWm}{jL|xGskp^mTMl@Zzm#EOUbGU`($GT-gkRu@JR+4nJE#*Q zqDAgGF{o?JL;G(*?meQt^F09>S%r|$z)#Psx3>DFI=MyPw0uMLMAUG$#)tuFzay6h zw0oQ?`tju-dHGg9khKuflHXnEtk-2&>=2)2ao?PohLM_77W(=vDoA{ap^YXr4y-30 zkNANWM;5@3x(o?$6>;)=ZJ|sMzsg**p-(LEl#_WFLL-t>sYE2a%86l9=1N347$v{c z#|Ps2Mvn;T_4j9t8P(#sf=aW}JgKZa^*;qKSrCiOJOnn@>(ex?6<8K{5oQp*K<6To z8E9&3Z=6xDA{5i-XfdlWJ%&paxw6Vg#BbS@MMcEC7wuw z_th^WhvyC3Roz`V-G-NP#*Z4xy5Xn5C3tyACLuF8yo%9>OpzzVi9_T!iTC;se-Ogqd0r0M(<1ML?DpZJ8^PQDuF1JiueESZk^S@Sm^TW9@p zA@QwQ>>TJ>^{fg0w$6?fOl>;qMflznKAq>DCq_e&?vKM?ViBHTy(U5agdZr1p-C!m zuq0YSJZU9|o?yE!1hw3<7<@EA(m%G{!bEr6(y*FkYe&qq+Cn?C-(sSELw9Jp!uB}r zao~7G_iXh}eQ<3}6>x8QqIUq(ysF-Y0XF_l58`R0mh?pc)kOWq9>IRa2KwLz`ry;O zBL^n6`GQ5Y*5~rkb^RI3Macp#)eVkF2cN}V!`OPI1^eCz`q8`544C;_$@Wxg;QVvZ z|Fb6pSRn%_4>kpK=171p(PErH7!a1%3BD5&DC3Kn7Yh*q=@V50!IWd4hgvGv7eCG< zv`C-XF3-6JNIGTzK$itjmS+e?o=I@*X+Ka}S>v z-6HxEm_WvgP3XHir$)gA|DLI>!-%>M8-_aS7Si(vpjB3$t)TAph`zk&@{qk73@t@z z9gmWM0q3JfPz-GLM1v!mR2c9w7|;cvRaGC0Pvh3kkxh=Gv}YPTGWNphp%pE0f>E&a z6a$I!de%iD*?GHi4GmODNwDzQcd98SI+mCMQ#8q`=XJzW(R>-#(!1Fm;(~=ll}02( z_`1SE(B7g~Jtd1#nYTrm9EzFN32940r+GW>9CWFRLGQ`KQ#oZGbrR&Te|oZG9D5Bj zmi1NG^ZNk)y_BujNpNX+@bfbn<^1|K&iX#7$@KEF5MbALX-~)0&5N92le0*N`heeZ z)0H)F?kJMOXv2Z7Q~*$iuiH$+a-;tWZ)<>Fw9W$B_pvY{Ya_-O3- z9`rnG>=?pk249u?DEl5D#sF`c1EKG_>{jsRA}ygP zCQsU~s)CZi(vEneqcV|6D;>w+Ggf(BdM?r@P>)Dc@SZh?_oE;*lQ&ZI8Z zSn3n~zjpT#zx_BlhrghPkh08dXwC_~WdZ!hJ@Wu$qxn{A)snhyN zVR!Xz-rKe?13G4eJ84FkJLN{OJLg7_JJ^~bu6NB6A#YuZ!lqmq$@VbYYfs7 z>^^DF7_4u!>k+y44>oUK(px~1TL$(Iw(P;1TO_U6Y!n(#oykE)eVS|~Yn!}6n-Vzv z7LC#=iWZG96Zy6+=}cNVYgz+VluhXZ01P{h;wVS1!jglJ^oHL)ml^hY9)Y&ZB$wyI z0X>y!s@KpAl!Vks*Ipi!B*}vXh4{iOm8nQ?J~0@yhJ&#JG%F!FSB&sqg0MdciCa~Q zJc4Uj=QBh39faFeN$E(1s&9@Sdy%?td?9L0!qqlj$G87BY)|3h7qWFx%GlOn3D_;k z+XFRMRLh-#dqC&74BRJZPtgge2c@KTsu_`4S6m@vB$1Xi(OK1@h84Ekpy1*VJ+lU@hx306?W2_A)&Oz#$9nk%qU98N`4hn*ts z1A-Jy;c)vco%Dtk{0EO`xoNUG1mWK>20fvsT0K890mvz@{<6jNs_E3GLRDcUuO5Jv z7(GpCxCW+X`I!^NXz9Pu*G+}(N$*EdGqNyJk$HLy(n4Ec6^pa#5vE7|?)_?lY(a0K zXJn|1vx4CDl8YFlp*?;k>}fWFX*O*PIYtQea+-Pgh$n~)ET3J0ecU(bY?!3SQkzji z7~SL?-6ngnAEijA%b6uJCsIhh>Kcb2%Vx^XLRJS%7x^Z#eb{E^3Dg}`hDQe`k$TO; zPUXW*ifRD^P_#EmkS9_LnS&cUH0is5(^}&f6ml}t?6?+#o|Z^br|^)qNyGGYXyA3g zE8$12a!dx1?;eBV1>uc*l1F@$*wPJ;@aVmCTV00j6G>;+#0ycei_A!FoMiS#M1;lU z7)=!;bZN0uyecunYeDS{2J)>-rM4agi)pBPOmoo1x- z6$+9^ptj4TI_}~6GekK8j{PJo1LWW(`xTpDL?GHrFLiSk_J31F6k&741pe!FG~1xfvtg=FcgrClLN^Ks0rT z3qwl9vNg<>@)ar&m|7gw%akD8uTEjq?M~)Qde*cOByNdT*I&e^J^K7Q2Dvx=CeTYk zdG13l5-dAz{7W^=zC?<{ zV8&JI(>^>h{s}z@e3I&ae+IXDe@oaiqdt1`*nb1K`y2pw^X}U_$L$-V`xkZ z2N}VXQ=Oz6($E`v&k-$@-;WQZvdTJ4!)JEXO-tb$*|h2#2#67>(fCf)LnS32rJ9=! zJ5Goz7$bAp6qL*?Q8ZATC3b7iRAQ32MXz*-ZMtEet40}Si2*%1HaNx>=APvpvb3fw z5aN|GoJ)YtNIZr+6=vHPwoNZm02USv!6FP!s#s5m#T zrAy$794d}4zh+JTGRy`-QUs%)xc`fyHaus{t`FfWUC`(}-w~;`D6I0Kaf`eFFnVgk z9O(vMi*Md{^f0u0*Pp+Zqz*grjZ)y+9wl zVAn94Msut^luvT9=|XA4-H;XxQPb(#4Gna13z_Qnu;c_M34R0AmC2k1Q)!^4$zQc1 zFfVqkId*eUajkE^Fr~J>a!nKB*AVTgqhxN!hvR@(PKcUPvh`^%B#E&F)JTIh`Y%_u z&?AqV{;1{=Z0>ld6|C#Jdh~%`iZwu2r$bi*wCVV8MwPR+CNI0mqhL5J9Z2Uw%;3x(jB8pM%O4N(=6t;o?&QhfZ#;+h>eCT7hp~hfp=f{8>VH$slMUXd7k%i zwe^b5F1v)j`JC%gXn81Lx4>DIIT%`b3sikMc%!Oa@@jH1aB?A#DVr};k$;f{WDPCL zlyI)eXPstXizWR!tv+`ckix-tp*G?`|TiqcM0`GB1r3G7i2@ z+ZrWhoF*HH&Vsq!ZT4x?H`60i4g6sEL zfBrKCNk%zYu>IGnSxfZa$wdD%tEQQyrIG#r>rVLp$wltqx{6CnKkP5vYK&=>F_Ni* zNV4^DXt_Xouy90Z2+;5#m1D8!{F0-(2rL`s6=qv4)?^eE^7%>?rGF{(HJa2dwyM-W znwFG5-qcoTtdW0u9Ck9mRj+z>RP3&~Z@N8Zx?ZSy9In0G9(%bz!b+1dyG*?Kj(hN? z3RMCUrD{OaK-Q9kZ>jLV99yn_W68yi~uE$@hF%7HLnH?)v}KAJWoXUBK;$;KNJ!Tzr+h+ zCmn6eBo*rBLJ>{jce9Y77Y`>OC+KffEuH%pZ679EB#%Whgocaz8`;Mjdi}e{th^eT zziaIHfq^_2^%&~?w{YjP8;=tHnZ>ov=6VNl*v zf?Wd^A0Vl$W1a-11{DniH0J%NPj|1U+i})Qc^kMrozT+KK^vz@S~+{Ywa7EOwF07s zo(*FKU8&Q7ej^K=2};mN!ZW+dntFL7Sq%iHW531cVp9&wZS4Hw1Uo%UF)^N^xB00^ zFqXKmxRqk5-Q%oO-$UJ9j!OL|RW|KEW$V-cv!+O|#ubqPCEx z-odiOD%-%q(`sx#)vN1STgfO%n0Hy+B)_zxYaRvOofIn;i9hzj>@JVR)2!M5jXXHLb+PAcK)ng zzVXUI1w`DH%?9D37ObfZO!HO&oa-zqqp-@WpcBr#04bwmC^S9;ROra{2v-&J2Deg% z$nZ^<98;R}IiG1xt*PM=~d4(M1)DM(H1v4yh zBK=LVuI>BKj6pQm_@6iT$Wsa4X%ih$9sX%OqQ%Npz3LVX=DoF~vr84c2exE*V&W>Z z@v1M%r22(oLZDd=)E3@E!+XcaY+r;m9XS2%zsuQCD}j0+ytC16xj_~P3Jw_Bj)SfT zg|Dx%?Z#Pdx&tZMu%InTdt6q|m{dil2tb7ku$3y*?k@|lb%lyLjUD0EfIO!4S*_0j z^e*%QZda#yG1s*g0FURIa9E-Z>@_RZjP+Qid4`Gm%Ij-fxHtX<0uNFDl!K7EY(Xm> z`+~&;Nh_yn1`iy%B=OO61l2lq%0+efsdXoUlBF+l$#PJI*yr*h?yZY;d4*_{tm5Se zy$AI)8b9ijCsJtZ*6MhKM!()#20yIRZ4V#aQ*M z=#ZY55+sN~Rbr?GC;Yz}5?~i!lyw@nj{rvhx_p#b<*f@)85Tn;Qxi^YXRQWY(__S+ z`uD}xVAoLTd}s3HkkUAmkW*E2h&cpv7`X@}t9w^KW_s$^7kG5voeoE>`UVdtmlC^H zsNi>3{?LimOmY?DnzN`Er=`Y94(2uXP$65PP~(M6IO>G56M3)DV=;Q2a1ePW(Yn}Z zaJdRui6T{^Av;IUQ0YPvT$SKfh=}7b&Fh16xRu*Eo@(ejqHL`Eh0>i71^!Rs=pa{$ zln~c+Bqy@c3~A^&bjRYDk`PzWna8_IxEW!>nPYbR>!|jr++-At*y;$tk{a1 z^v>p!my2STP(Q|gLQp#oSL=VSOz#TODKmI1Vi|$UNImgs2liUMRofbTbO!7sFf-I+ z;jorhJ1e`(?EbmSL{U#&Q9mTJG}2VqSR}%@5h{p*E)l=(Zou7W=C9l z)tsND!qiyrF0?y~e{X(^SWjW0VXrO&P~gviJl{C4+dWQhehxlPMvPW7R9{DJZfs`F zsWsFVu<)4Ze?CyhL}8k?VWi+a*SWFM^W@u~#t2M$r9kABJhgi^bT4$Vt_p6-@NMod zG+*vDi^oK2Y-((zEwj<~4$Tu=W%MKCs-G)PH0%H|ihx!2XW|EHizSh7M2^6WOD=jV z3G5MJ+nckt)Sk7K_fYV}G zKdj=o^%KZN)!(f$9PaJO?2y6QtO=_jA9av(M0O?G0MipxFq%S*10T{s-lq%bo#y{Z zkLL3zn%z_tp9fZ#qE{DKfDb^Cg?;QmNk0qNmXAH-IOpHw$a*&m1wGZrD4a0kwkm;k zWV9;mFh%@IWmzydy~8?BIjwkP@QTtdVLY>X51yMrI=u&&T=je7&WBb};2)YB4pt9h zPs-!agT=5Qsl-U@oHL!DBinYpmA)iUx93dqjMmZ&_0l#x=H5I@OQTLrqduK>zQvlr z0~vWXmzAJ}cfJ0#l4viyZUsnAC(yUigwk@W8i9IPzfJB|@VL+s^mKHzjF}KQHcxgY z@h5!9DPFg56dqw<+@zY9ffcuFs$B0#givc)k8$P=x?-ceAt&A2OG>Zd zaCoK;|Hgm2&y0;<@zyz0Pkity$9s5yU7V=&S$>nlePPWqHbvf^I@7=TZdlqGKJgVt$(% zrB324uw9xVQ*G-p|6yhtTYFG-nSo7^flVOodZBn}Gxt#kO!{ak)^gWeFQR-R63w;$ ziEacQ!KL`;mV;AclA?UQ1A|&km8Gbp?tzNUUbtsxQ^h<@dDTR?;g~|+ z74k$~1cGut;W73xKi9EX$Ym&P{E|Wn;@#3(+~sXDrK!CT5odgWFkSToqaqQf5^9*> z^E|LCQ7;)LwG08{*mIjS0VT`0EQpR0)^=fdXdKSn}@c=1i} zRUpkR$|R;v$6VuP{gY=dXpwG^g|NqF*es-Dh-6h__0nUY)0Dul zst+<*LMq(CioAn~)3uU?xIA~g2~}tf5l;Jlgd4ZvEmp;j$aI2?bpm>Rz?<(-s1B@l zFF6&ZZU~Bhy%Rqmb}u%eWj8=xyuGckdH}dUeBS_IufXm+e~`WsyFq>@pQTmn3vsUH zW3CCb)TLbO@?IVM`SK5VMEY&LvGQ5jGaT4MB-mm`Y<*)60kP~L+(vlAC_Nscsty-?H|7+v>bM6QP%kFLHoRCyT@sMZWlnwnrQ`^BHI11SKWXic-Y7~u=e2k z+sh2uZMTa+4MLulCB}JmZwujorT&$-=HM*wYU9N$wo!Cv!~MG7fncLYsV5ow3OU)+a)VyTa$k zL$#R(X1*Dwh_rb%b`5cxWVhN-7H75v_vqD~iCA{n?6;1h<1x(>b?2s8Ad3#Q=A2Q< z*cl;Qc>UVta4opskFW%2R=u^VE6g!m7=*dt#20SoeN6HG#B$hAA%WNZQ-_IRyD1$WSk|KsVUq?%#+oLfSJ`_!ub7 z0CFUwK8-lCW%80XrOB^zYka>!Yx?&*iM=uq8-o(iJs|L0&ggh%g%QuNWO)pYq8zK^ z7VmDe9wJvJ`K~>?&%nUj<{#!;qCnJLV;*`i<#EAea#oj4j@pbHI88GbG|vPFPfv=G zzN_e>xD}DNPArz`Db0zA7?n6rErj85QPHF}uv}NS!0W`r!76M|Yt&+atJR@~ZFdN1K=OChs0VTkyi? z)4RinVHE^&Bbe+JH@Da{Te_RU@BQV(O6m=fZIi=k+|Av_YMzlBs2CW?u&OjnI zArFT#M|ucg9b5@aMktL!7g4c-yvB)>v*HPB6Mda$nW5t#?p?a!ieZDbjEQE9h7;h8 zAOaW<&fU(!8J(y#rv4POVx&8i4%p8Zz^oOi)Sh1Y0P8HcCt=nk>l_Bx%bitYw#(eg zn=?nqP42|2bi2RH0K;{@hpnzx;LChMuFfF&qfvK?_KDXc%#O&-gZHv0ugBX6S9Fa) zq4%unn7ML3k8fJnsACX~%jw3!F`SnHqw?X+5f9g&%T5O&n$z6VLO z{i{rnr=5Qv~3|(fx;YOZX-!)&=%;0iE)MgYqJw zr5sbf@|5&>PND;_I!JtvQGXpP|FH6cvwA>SKQjTpLk+#E{k=Cc-_@DZ_vUesj38i^ zCLJ1ShkU}TW19(-B6dlw4yzf82Qj@k^hEwTcBujV+34qUm}uVp78?Gl8uKly&zv5{ zhZKHjuS66jzIe&hSxzc%$d`Kw@e^8u8z2r^23SZs>c1 z=R|wJyk6V&F37@$+|X;(F<9?6#jFo-ZXKAG9t3o5#_mqOw}*NRvQThR8&FieYyz65 z*ks{^T9~PG=q*~d9Ro-)C6eG+&cDS}J6U6IDw}Sv%=-iT=0*m_>7KtzYH&rTY-!>m zSRZ>zXaK$OU5d>j*6BkQ>21e}HsoH2&z2Y!Y&O&lkJX8$hI^NzcV|Pe;g-?=34?ss zQJem9Dmt6=$(laoBO>XOqy7q{-iJF+@eM}&hUnT0z!Ak;^h8(1h`it?KIf8HT#+Qi znHXZN!sE^date-Ih^mCrRZ)LdLm_!naD|vO5k!$QLUv5JM8=a2Ybz-fNv|3CNe;_G zJ*>OO#5{DE%kId0KRxjeB$nBVl?8h^BWD&l_j6R=N3WAu1Bx)gXu0hbUHG|qX>dYq zw7!O^&JO0ASLJip8}+$yT6&PxOzEQo&M8uVga zGw@@{Nu2uwx2aH<>SF!a1G3U#g=UU;`z1NWT#{K+CE)`lcBKl4^co7Yu=4zaB|&qA zCCB{oyg-h0`SN6z3Nc5&bbi!=s}2g`m9jEfPvS4xr8#PIjxBJWmtQni*#+KclA?)X z8c2;a8VIPJ<~0K#>?~U85mteCC@bQh8)gc90WC{is=sVpE4zX$U!!P&AWW@eseWMO z=g`7d_G|W981$73eNITv?s;T*>9*Fg`OzP=VKBp;x1W8fGiE_QA6wr1U|1Ym1mzP^ zTux-RjI7Xx~Ob^ zHnY<$kQ|kQO!OPCp8u@0=rAZ7A+P+e6cNGGhxrpA*x{&@Otfkj1rPYch8sd4^uT3= z{jWWp{Up)A)5n6z51aAQQF3?O0PmglPDc@JaAFV+YT+9)(pDPTksSv}zW@C77q^m?0Xbz-!9=bNoe#?SZvnCgs-HGy5hl58H3 z{Nc`u?}lFUcZ-|leHj}eR7S0@f~Oy(A`F3qO^21RJ?4aeK#rbNk@XnmQgY5C>!o2@ z)@$Bd!w>*l(P8p>eT6@VYSy&Hjz|REgMo+b^h0> z$XrgPLb)-kuv)I`T%EaadZgzf>gETC&4E;kWn1g-&!zpB3#z9lrzdl0;gMqi7zkFL z_(F{@?Vnp6*zsc<0xj0yCE;Ao6fl*fsn;Br4P2e@ufMSA&X_C#3ho!~4CtouzM7*YBsRcy-WWKD@>n$?II zb{VCM)l<_kXFh?--f-k(LBzVbfkeuY3P5Da$mHEMnouF9%0Zes5gV1Bh5|x*VrZ#q z4R+`{x#mBTadlIsSNjkz;xh^~B4^Yp3eJNDrBr zk6}%Eda{UgMI4p!;3g|96UDYAqGcWkK4zkBp^Z{}Ov=o=~@>)igC5`v>%~a zt^hkqs1Y6jVG=#qfvCzaRDl57N=gB)+JV?21p_TA^$fQ%c1CLMJoO5$n5x{`&V0j~ zK6sy^a<-G!5n0(3iDazBtave!)Ax=KR6C*|ePI28ie7S6leAGLLlzhyb;uG+ctjxUS6B2W2iCK_) z@N%h1nao!>OX*2meYfb2a!)bkl7wT%JM>nbw*;?BPeIAj&DqMik-Jcrf8rCYsM=4c zbmv`E>{-tSKj?>xt^)aDN1iKRyI=GOd)#z(4aBuVMlJh#LO5yB^z6tQ-E8P~U9l&~L#&ZA$NY?hh z7fzMQ)vSp7T<=RwO8@t;F>H%Poy{+4`J2{{C3mQ=#B}(Aa7Pqw-{!g64Bokb-2B>X z-g$vsak_Vt$661lSlC$mq-CYHo%U$^EE`8<5ixzRWOs+LO9b|Cj_w`Z&cX6%x5=R* zPpR^H?xg0HcXf)Us(Ea-n*4R3&_zx4ww^+uvZC%aO>1t0>1vOsQLxc9Hn6yCaS(Tm zHFu6=t^nbSG$!epdmdz_2_5kEm1Kq%VX!d;ArQY{PNgD z-u-P(C!_gmn#_)9dNY?4@M?&B?r0ol0DC5CyBXt1#ubBV(Q06owlJUEe$RI8{ZT`( zv48K&5D!=Ni(mJr)X(Rc%i>y>PCUFY2`%>RfoM?*4!Nt4@a%TPv2Ef|qDbTA^+0-t zb(Dut+#8v(M;xlsa(-8e+VFMdm%3NNtn|q#FSX%^!-jq!bRllOn2d)wSnvD5H&eDK8r!$2KQW|RGY~R!3)ew2L@x`? znRdcgMFk@FvJZahId-#P=03+jPmFA6oVcZ=9Xc&Q$1;f5`Rg+bY&UqI04aTaxNbRl zCs@kwY=x4wCfg}(qv$T9sA^{05(&vPE%|33Cq5t9?yyRGtZfACA;na2kK(1YV?j>u zu;ju6)51z@DnlA$SOrteb)qmCaHkK^g2!48fE9&;nX$t*9B!0 zPlH7a9V2XASZGI;Bqn#7T_MF=%1t_z-ua0BKYx zsT}7bJS5D(x`6Yj*(kq2-3*LmqFHdiW$KQ}b*S_B@@}@V%}}>bTU+F_4OnvQHvc~_ zcBRt_)A;Um^(UuBNt+U6cQB{Zti)N?*|PVLM&%vB5}=jfM`}ly(}+i!cEueSkv1S{ zd(y33mjx-;?V^`?t#|A9tnL`?rH?b{F9Ua#pFo~DUZWas--o9FtR>hxRj!n?9NQ-E zM2n{bE&<-YhsT7?!kqo0cQft0oIRW`ESu$-2Q|~4KVCEoJuJ!ZWd6PFlUE-ua41tQ zsHrw-eWQ3^NyQn>e`@?BzQxyF88?^nlKYRc!I1Ys)lG#1-Ef*xXVZohb^)-Dwa=9v z-TT;%F>Oasr@R(A_-1v0%)T@sTfD~XY<~B+XI-R+9=|d`ruc{9+KU1qpZZv$SKT_V z3N(cFh~k}^KlOys`J7Epu3kG_FAVc<@}NA zWrjGKzScu)U7~~&NaDvWdEUxUC0SV|SsgrZK-Z|uJPwxgo)pC;#j;@RR#|Xxuv@pm zPJK^H-pr$X2?j!@ks4oP-unaWO(6C-JdAD}oz!^KXW#qv$8qA1@2pNb&9oKICpI7e z4-kMh3-0?LfKVatjT=|fGCN71C&5oBm{(x1PkY;1JJ$-9Y5lh8eY>ookG5%fOYpz1 zMG(@kXfrvX%#*YBSELKOd6SYUL1+GO;`pEJs+MbNzJP!HvX=B|KC+p8Z*}WLUO}4v z@I_|A{SPLxF(U8q)PS)6FfJj}&vK>Ln14*-Ju!hiwvW7oy<@vBz482C|ap?f{Z>N+>*e^!oQKkiUEF_JRFP z#GU8(g7^GE1Re!)?D|f0&i^u&Sg=YKa#6);AGx0oNRGj2_NlvA$AN60VLyvVHuXODfAg{h6b5>W%L$ zmZ`iK(x+}T9A15yRop7wna9&>hBcte*VC(t)ftzlEaJqPyGGNM@q?UrY&TE5H=gi7 zs^~)X@P&B7y z!nlrwYI-B4W$4PW{3NeWtzz+@I)J0Ry&>Sm;mP{ye$dX8x>0x~kBkXW1= zB_KMJ@pkFk|59Q#rqj;^q|rU=R|m2{bGR-~U;<>cs}I#cb38+K7jPq!KJWf3j{~s^ zKKzLH=T8pne`mD#A29+%{;$v`<^P%hY%Tg1T!K8Vn0j7Z$YK>(-cMa)or2hR@mAjz zKD=2g9=Vxh&9MRevEaRr_dwEVIQXB*=XoUW_+4Aa1j+wH**ivA0&Q8kkzw1mZQHhO z+sv?SJ2GtBwr!gkj_A0zsz+Dd9@X!@zvtgMWAA^t$GlX*kJo zO6d9ex`G41+sBXi<&8OHA}w{tAAv!^s5lwIfF^?efI!QeXh;whs^EO!L{Yz`KA6DW zNDWdxR7l@E@FI!ds6Fq-;;+2i=(?aOGI4Wu)~P|6 zeq`BRwC06$R-mxVLY2MHv|nJVHQbl7rd_354?o(`2BVZZ;l$4IX?t4dnW- z=~PCH=D}sESs@LQ1#Q*;2Vd%EH6i(vapH zE2Rj}Mcl+ItK$X5#e0Qj_;8fz!%{oaM!L<3oFft)FyICTC0J1hO_TX{rIh3m_uAu} z*RWm(0w+?A)2MU9Qb)xG854a9I)@ghS6Y~NRq5Irkd9#^mcG!;M#&I>{}D*U6ifZO zwwCTHGC0tC9>I$;<5Eo?kun~ydt+IcJ0tnYAmAHYj{=E!#35}E&L(W+G`_$ohUerA+ zD2jGp9{-z+Lj46sc1VQAkB2ky7bK*!H_~u*0MDj;TuOg$G<^=miz;mdIR&|qwtsj; zzzI6sfTDbGRbEJYfX^Zb4{R>| ziX~J@W|+*XkQaxd1sEg=W-Qulb}1wASnv+3CF=SV5Zk6X)E^YPi?N982N>HjUEOC1 ztYcrd;>L;G{iJW(c_OOKALH}>NUhd*>&yhcfn^;+}Tde|Wh*E4BDnq`-n_R%{&Kpz<} zw*%q3=4x4H=z_9%;{?_7-jKXP=LCav({)x!+0!KvZWJib03mm{xqvqZ?I+&9VS!(< zm6gUo0Vzd7Gc55-OGL4tCFa(mIC@KaN0M4zL43hZ7=qca6SjH4#9WL#*cIOaAi%uf zi5fw%X(VI{9A!PJQ(6<6)84rHwZ?>;y99+%YT#`Qa|_|8fJXm?UWa{-d&4v@DP-^%ABTm#gLLXxTW*CX;LI z8}VFlm~FY|!>M2rkSVP^l+SV)@@P?pTUF87k_lUdZ*|%%w$~;EA&z)0s5-t~lo$xQ z4+W7rAhH+VMlAm_=j{Rc#TDQk>-#YanESX_(;)u`d^t9fddce%x%Ec)Hcq?m(R)Rrp&Dp}=D;uwNE6xaZSHmY4*G&JgarX|g@0g26{d<1 zSWgbHmxpa7l^3AiwE!A{p~hs-*DqT5lq*h%r7BGlbjsBs=P>QVV0kc^sNfkqtW66m zFO4Y*O;v$g0|8y6i73BaX$qr8~$U>C|98p$>hA z%qiT2rA-^+^&+s~ED3lnrEWTuJR9QBL~%-=+|){q793aGYXbnRns3Z8d_ zl_tw(lPzRL{w*jR>6z=T=*WUB@6~ z4bSv6nLCj_ai824=tz@EdoVR!mo&a?*&F|X;MvO(5&b4;~KqC{m}o?Xn(;C<&(!c5F?n6aPmYkEsZ4cC<0;$gQDTU^$o9bmE@W!0Me31s9+4Bh2X)(!b+FToyU&F}2 zWPti1LE8Y)1>I_R%fj+v^s|S+WI^sdxX<-U5p+f^K*D+3J0@->yAFH+NpoMJ&elt~o7>VyldpmyhQb6ckFNZNepsT_@G86&%@pPtX9!eNFR*O7#j zVEukBdd?&fLrm@PtvqeDmDn6$`=IUaS73IEG2l6Zxqmbydg`!x^eVM0pSvmk%E$a1 zSY%r{#mnCguP(%+4~rtJ7wbXiV4b-a*nEI(NA1BT}z# z$umU1ZxFqb`)^f(XZ*`P-A|<^D7bd~MXyb*fi)_8LK?F=rtTw5K|s@s`R7?_=Ix&Z z4fl(AkWGYdSZ`#aJ=}~Uxsauy=WlO>sXLl=?cX(MSy#M$I6u#1ys7_={T9A!J6lu! z5$3Wm;7Of=vR=_E^|C9oD>}}wb;nI(b{Dvx*g@E(2Uo@;_N=5^2OT22Np|y72Hz#^ zIr^5XEAhPd&vFD)zvskGwn?i=?%L(((9u;4scle0L$%eAVG4n&B$q!d&s&^<1=&v& z5Ox}&RQ=^G@&tRJ&qw9yN$MZ~Bs(xx;YWr$;K-@MVfjE^6rCZ0nLXgneup#A%)yBJ zFTZ|@qduv28Zz~dC*w;Y?1A|p$v|Pm5DFR|=@^g3##rlnONp1Gg#>!qykcF%zFEcG zk|1#jNf}K zyk0V@mBQGD+U6yYBQ?8l{{1c$o=TDOzH?0Xz}IdKp{HfaC9n#O?mlV_CTPFk)P-{u z=29-YLWkIVGV8Nn;~vcNSFO|v<-b|;{SUZ+owL{I7~ZiazrZ%%37kF=V0Xzd54SL1 z?3)k=k|i%oMt(Il5kFt{&4c z&^q5@GTVkDJd8@f+1<>vR3bZdz=QM<|JAEY>p32~xySf~$sO5Y4BeSKeinWQEAUD+ z|1Nz9Lz?OG)(2@oyLg#|NG_fLO5W5wV=F4Fbe9RCs(PW-B0xd^{?c6X*e6Xv0*hydFb8p)oK=`OAp*mQqj=Hc;N)dI|ZPJlAurH?SLMaKM z(z(-~SEt>YR5}XH2Q*iPVc~{R^LYC)im_#Fx~@GiNe*N#;s5%?Zd_)6ub7VAyNhsg z8(Oo^ZJB6kwX1YsE58;izka@W3|n<^!&|$oQgB@qwkQ+DsDSJ5fD|sL4J&-w0;<@= ztGM_Q_Hp~BeAd=^mRoXTQ*Gl@TKSaVR=LV4cdfabr)cV~q7{5ypxG( zg_>!zr-><*nrPo5ne+$PKf-erf1et`g988z|2GKazXGEEzjF~p9ZeiuOl*xjh-D3& zT^tRph3stX4IB-e?HvCjlQ>&hMhQs(-lySp6&?`+oLrd1Hv!%l;w8O^oB>s(f`S{q z4ekP&x@m1_Y8dbnEQN2N5RFdLvzGgzklKqi6FnhW5LQA?*R98QYa#t$htC&~d`|(< z0Xb1#0b2w)lJZ*8SYoI?A|V0=r2;xV#a_nN2CBt`^DosW29VcuTs4R5#6fe*R8?~r zj-R{cvQh3e!(c^;ji(iKythFnfu@r#R7hRBMdXyLlUOTEw-ExPf*W+fk+5tJ5dHa8 zI!(x(%ypBF?NZk9FSoXnR%nW?=3uP`_X-m7B1N}NooGCJBRTVs1?vRtsCDFoq(arKbA>opvi}w$j6>8fXO96b9vYX^8D&Q~HP$HxQM(0R1w+9} zPq}CXj^NSGvd)3^5mQHXdHp8=e8Z{ZB{?IlgRBc$UvLmWa>3B~-lE!MrF+Tc)a;i| zq<1m1k$c8>O4D^0wdpKl3LJfto^Zn!O z(?kYL$Nps1@q+$W<^8WYg{=QCf?msj% z-x;g%#EO4T84owMAn*?tCcU7uiCfFa<8km+U0U>a<46)YsPb&dd7@}lZq3}uHCNN zo^!meUp;QxK3)P(a=_pR^}HBx*u3naY@hU5yA{K1TBiopj<~3&u5{5~GQzKP-R(n} z_0ayprhmemT_c~%T3ja_XU>15r)JuDIIvwKSpKPORV#g$zP#@rwmsXtF|dq%hh+cm zbO(Twe29bQwKl8)i`CCXi#6;C2h!CJ3uL^vvFIj35)h|GIHum-M#spGjz#Rw>4mtJZePzOa!aH0Qrxtc zT!jOr7LwZJhDa_=ZYfIw#uRUCs#0V}er))v1KhxuAVJnlP1d?xX)*Ss#)uLv>}9CK z?I@u|iDMTAE#5jZ^AfJ@Jhe*vAry0xSFRyWuuLaLAi`q&tS@=_ft0G7e7BzY@7 zJ3w#^$x$|p5(vlX?{sQjc+_63E65QhO^Go^+&86R7}Pb3-XKFhnxg7J8mpfE64%o^ znSDzUCeD!*eban5{H!Csv0V((vgDA5VwYSMtfuY_I#DkF3WdjZe}OAyW!KBo`i{)L4b;MXbLBz<_=edqA_Q=OA7vT zcM?RGCDZU%x!&nOo*2hzzrjU{nH8V5x>I=0}l) zyAYELw!s1ng}oYTYhW!S@J#B?h(uJ?$Qob5DXaO;m|RVFATo&5oC^aC_?b0cf&Qpi z9p)s7M;2*qDsaYbn$(+Am`=YE$anE({Fq_$P13t`d>oYIvJz)82}X za-h|Sh1c_g%jzqJ%Y+FA0wz-v>uOD|+H33Eo9(W5{q|Z^k=YM-CmfOd&C+MatD%YM z>e~DBo5W3H^|t*UEPLzCv6H(dD?R}TGo58gfKCs_93}&sEH-~mvYl8S#hQ%+!-=9< zA8tTtK@G9f5K*r)Qc_UEWz_r#!!5KYWlki=2VcPrVAV{V+Wr{ejssVx(INpTaf8x4 z=_Gx!R@kNY)|BHBjE*3t&_6*siw8G1+d?ZpGdC)wptoAe^CSF|O|Tsw5dt-x6KhYO`l^k{^ds zu5V&#kFv6=XZ*C$sxywi8Bt`9+7bNJbq4)r z>8QeC_yj`!J6EGaWb@%+6-lXoM8Bql0r>c|nzT^y#?tY93(hk0;^R7lA#2C@O{T{S zuiPYfXY15W4-5KqCXaEQ;gWZVO0=pOyQj_RwYE8jTV=B|TM+z}9h30i&72zMYV%zDvX6iVFsdp4+7YrL5j z8ry<=#0|65FxeFEPDz#xD=)7?!rG{J6UOu8ShZy~l@}_?=RzmN!ie2L(DD(dD%}o! z!wE=U1+i))uZNccZM#mR)&Nmi9EWiIo_Bs#M-f#Gs+v@~w*ER5vFgO+%i9MMJk^A? z{Fu{yxNzF9u+x3-xuL{@$Qk^%+1hs?2cGqd!DnBhyjX+vpBUf5qKmxU!QhJAVG$CY zgO{iaur%I~8C*BNoh+ri60k@9K6F~!d+`~jxm%I;)W*FAyKxJ-_w(eQ7meckS%q zdj{QZt#Ccyc1U1$h~QuqAYd1mvGXxL8neUyn8W6jkZ4B_-$BDT`GF0e>0%duy2t1a zGQ5FZ_e38&a&_|G9Eemwk~PA|SV7$;G=uXkYTng11J{^S-IcrY$XZ%-=GzRlBm1D5FlVyp4$bNaxb0(pA)T+hBna)XVCuIgC%*EuOG?teh!;*^0BI=* zE}Q~Z8k9o|J#r4HP?7zm^$ZZGK+)Z014MsnxtJ;dN#bu#a*@$3Qvc)~2WQ$aQd%zCtNqtXgJ(g1mtH#QX=}3^LP>JG*YUBcHYyV_}$0r zf!2g=m%0y^7W}_7TKk+w5D=BHhoQjm+9MG)W_BnHGE0F zHZ@h6=I(l+@R}$y3LFM)+rkTeGiTV^DO(N9I%sbHp;G5TR>q&0@wKBGz|;twSGAdTIYZ@) z2IxZ(1QbGk)bcWLm_wno@!F_y2ObrCS>Mgx9W4vUzX?;LNczSccx0uReEZnGk#i?{ zr-C0?Izet{Oj&yiKO{K|&~F_{md4*bRmx&ir8$OC@@i%Kg9GW>Rf0SEm6_LruuJ)h zcha4~*+_T7TS#|<$~{PO(lGSJ6y+Nd_$67DD~C@f!l>E$8YG>MI)4k?d+rrJtft@l z;@+LCH8ybIQ0Nutg4pspUJ7piG8WQaOE0aA9V**qchjO@fuDMAlQ+0G>A<&iIp8`f zPSe*5;dI{djx~QtU{IE-hdnSThdqT*Z}X;3h8VlKmRzMk;BC)o>^IOP&vk2yVr9)K zeGD6m(uq=R7}9E`Q7Mb=QZVB!nE$dogRIO8J}ne!4c4TWu3DXL88Jd0rZcD5&UgI? zNjYd~1neREV~Ml7VGZe99k(?F|BMv84-y4HM-l7s>Z=(g5d7Z5&%qe*zVDAs*;yf< zg^c3XIhyn`T}X@^?O%P|oi@T$)Nt z%6l}1AiP;!wH-12bE4hx*%P{QPvDIth)B#&5k>JdSvlzPH{2dOI7;l2c$0fWy;AzT zjgrK-0=FN7j7AbHtn9WR)&3JJ$%Mj}mb-n#O?=-(|uES`fRNMGC z1Y%6#3$T)2>PU5JL}iwNRi;!@+BuzL4c15{P^$=yBGve-zCdu!QyXunU$<;=+b^T7 zB3W6zALM#n*KJVZ%2GB(4up!Wa^Db$Q=8Iy%85l`#2B|t))z*j11M=z`ss<)!L8%E z^k~MSsN|B(fC%&b*CeG;cElx+22of`G_4*OSVY}*o~JU0G#iu2SQ#6c|Ciq(j?BgD z5SB^pjUdMm`t3oQEKiyUM36a9b&;;NkPmvEuXl8Uc2sd~DC<5zaa$+$AUez*u}%Ms zIaA;l%nON)$!-q<-mJ`FL1tNmt;x$bq)$xqoQX5m)Snv0TR0^wn?F{ku$Vi6C@01E)HhV@^|8Cm5WFlhg?C2rkZ1P|FM8zswcE~Eo-&@yP*=NrBsi*=J z_~J`j8kdW{zXdh?n@=SzqK8Ot53eqZxs2UR)6;FvBY$4EKsrn1eKEtsAv8SvIvYbI z59Yh?-5vhv>}=Xh5hPUI>mOjalV8sRi`!S*_lX{W?hw}}`e2ejK^DC|VhzQU3(Ozr zA_q;11xt>?#RP$Qte^j>6erAStkqy7OjBs%rB8uL%d`c1fq_iuvIs3ReG||r3sC<@ z!jQ)-G!Q)cG?SUcK53btd}xf}lTZC6RG2;G;;WaZ_M2c=9pNR2j$=z_3)Ls0B%oY76GQ!s3^Ok%V{zGk7J^NEL_kxA zB%`SVAG(Ed2jJ+`NPc%>Pfjn(@H$Yh|3Dc zL+5m=DEot3^UA#UCz>cM4^W_+ljE^rQo5xAl};5kz8fm zEB@|}y9DG_d`exHlNFfqw^Z|<&(<>&wV2)z^KE$rkq|Pbe3`5#HKccd z50%CqE)8jsPP%IjH>-^`s8pi`x$g}BWY;%Tr$J+|+b8L?-cJzJ=_MS957nS~k&^kt zsg~&Sro8@SnD(h>*mhv7NBGG@XU&S~3qLk)D1;IQyG~CTL@0E2RuWCHvW15ECWbYj z&%=w*1zN$F;X-jmFPkPBf(w%!HBqo^JvD1RA#W>_irXxbLx+~)khGmcFl+9gDEwJ4 zQYDwnyB)feGf_63kVAlX4()+QaAh?AW=^Lu1Ve8H<)i9=R0d;jg>^q#1X`J5xEbydGw+Fx+3WN80Q&b9i+vCX**%N`cMn=`0P4^Pk&R&=UAHK^ zBKQ38UcvuTI=vRb`9@@$GXhjkV6H`aRL^o|XbFFKsP3y1_9wve3AO%6$8YKcKv z$b@Frx)WEl$tKt|XTZb)y~=yc5#dg`eU5c73CV?>ziaNAa)!Vk|IF5%WbzfP0RjMs z{{g!E&l7CUf8&Ap-?)c=JQOkp&W;xD#4P{WK31}^`e`5g{&gH<85;_+tXeNuDI{H4 zeZUb$XtW@Ri)ci=Jvgps)uL@Nd8R#|L8LCg`}p-m?(i49^d+AZtcB@)bCPLh^6Km5 z^@{7aSF4gJ0+wr=ssO}FMXP^FXeO>LgS!$gn@S3!^P41I$VZx(5rU{Cqe3_Y88;3e zxKTQI^?*;`0Z)$Q>mG#=1&-80=fv&pVkeqVq9tyz-w9u0xO6U)aFq!7F~SBeed~rL zG5WdB+Z$yjbg=J0CW#M$egEPhb(sY0~iMJqOVxjnsU{JVu;w9gCyNFR6By!9Q7VYZ3+O80py8 z;m(z!xVG=+`B#Ne5pZx)yyf8B)^Df!!C%XSZy35cDa$A~?x^4KPnu9fk4Z@|)+dro zo4Gx#Lg{gX*i=GJtCmeCTt&etI4-x}9MDptMO+f)e1?Ix(&4so3+Af=fW{W(sQE3B zxiMnVon(!4aaCZMWcmUpz_Pa>!EzqE7@AVZ;ATObudLyMbG;g?4=%7&Oc^c8)#A;l z-XRU$%U_T!VLQYqT1)Y_*@ao;zpVnzgqOKum$EuTpbk0O+z?X5wSHM~%y7~sx;TKS z)nz%=cM|jT{F5cKQFFKa_`?*T{c%YApR@I^JzDO6<7_EAS_oShnAzDHSpQ$0+H4go zYo!&O@9e?pr-OCb`Brw8kg8&42HI+!@$*|+e^%oBA&*89>!acB@a)y@u_hqot73|G zM$juwi_$Gk3v-zLMNsR$tMg9r&^sMwP68MXT%ez(vlAF6I6>805$4+x)$LC?F z*942zyG9G-x9Es$zFOH{6{N~V7idW4s+rXLUVn9R9l4r#C!O^p!vQzDlWX@|u| zu;{q}=<=Cy^k9R5=?Sl^Ifbz!jEzsWMn?0Kj)&n^6-LOwW(CSv4cEEGGe0GTHB@+! zFV9lP%}RQh3NB7NS_D~&kyVkL9*AQuz4ejA$=6a1hO`H5x|_rz>4}O)p}(LWuy-G` zBbF(wBc;uSN+{LI)Ss1Gg2)l4`0Xny$hXkyOs>P5IjKM70KU`;vM8UB7?jll1L+ZV$I6Ll z#?}Q&80i`GW(}ExW*`iw@`M&i&ikM0l%fw3*%`S`R}5XsMYvXa#1VqmU+%nBCxDB1 zHHwDwT0mP2!T}~FhCcy%M#Kh@FZ!_ z$`qPr8*YhEY@=5}e~feVv+J|7Yiv`CjW!;C(#G-fheb-Lnp?+UEaO*{?yis<`PHEv z$W4g$k%id3-FA?WLOP+!pVcb=le$9`X5Q(@Ko2gMAA*#*XOrg+JjpV!Y#)k_rzjVQ zn{ycv6G3;jQ7sPKuD};x5bvWt z+8+Fy1elThc0Q6qQ(tIZM14TxQrMoYtc$R3x;|kS| zZaLSXT14oJ1iB~|uF~*hx&2gHT!W&@WM%8_QKBfx8#gUd+jKQtsGgXVkl$+j7P^Bs z6xyNHV7!bghhe-iah$E2FydF?%w9481+F6Ey~(^J#|50Kq*5n=Og!URn9+@<+bj-m z2njLpRsy^;8Ry?7+Z)>vLBDL5$;h0U^%KVL{=oD*Yl zSbRqOql%$QJ`aS6=y-93;rRMPL$q3qUK`bNnl*G$VI4=~_&y_0q(!634Tkgq`9+2S z<;ZI2LD7+VHuth&fJ^p|IpL5JF~vUaC32G|ls=kh@fQ1e#w}bk$<*nBA3Z0+v;uv12e zHI^*;Yigmz4eA~s< zY%4?mq-}yp@=d%j=RKk3(Neq)xtC`AG-v(DY$drD3Q2s9jq&!(lH*n4xn8?zNVnh( z+}ujd{KP=kC(+|6h35C?+q1?jK`+IH{VS8MIN=H88-n)`xFFwY9)jE-2VfbV8` ze{_e&2kY{Mv5okQc{%Z96MH3T(nA>}Q7FNc9LEv6xj?i?N3>8LiDGpe(;;LVyYRF| z^pksTR!kT65n6s|mQ$0`5D?IeAg-Hh=`l`|rE)*zYB8wKcNhv-*2wGCc zigBb~vk6GQCBC-sSS@zM(9DoTbLj^=%TI{f1Gep+BKQH>hxJs$o1J}@-}o}mjH@3I z*DX`p3rFfWoqS)-9mq$B&>d;aJ`MH&NOj7N!p;VJpxfvtt#A0w!(XuK6gT$co4p

H~ z(`dDKYT&X+EZ%N{gTpAHC5T1i+BDoYrf=2^1LNzmV2|tEx5?#UVw3?^8Sh(bI^F;a z_->}QouhtN|G?+GtDwZrgv??NVxB%gyS!VI+e2cvWxxAXRB|$v+osAFx{ui^+&5OX49G`to=SJNwh!u3^nO zMMgJ)r0B&z15R?2L`NFF9NroY$h<(Ex4iSm_aepmzJCph^kH6CS0Hj>CQ$jibjWoP zq2jl`k<|#{TWHmS>-u^+Y?V#+T+c@#&YzgSZade2Cg<=UMmIb+IZnPOn_j%vTWowh z+#vW7WS{1PqI{+Xc>#-gnA9xLuMAO9ctoS;wV$^J%Hcm0+Y>PoP-Ls-*eOoairCE0R*;tSRv8-KiC8S#3)($JBhxUAnT4i~^jkTN zVxpJU-9CfV(9?D^@H>-DdRrUWq(+O=S|AhC(-eR-$jTb8$*#>a?gKca8hrgsJ#-J1KU4=e91t}BV9 zfd)Pp*czit7;Bm{)TaxxcV8`qq!?Wt)e(F^lt|L70=R8D8!wyc%b2qt?HjaH3GPFr z5_0xTG(fn#vy&;IDGQ32y9U_za&sD)jEFRjRYZCKPa9bOER_citN3(EdrVE9=8erl z7eR$nBT>rrc}$tP;BsCg^V?gLu}^a*7ecAD_wCiLv>$8R!KP$-5Hx=+4Mf zj=#}S74OU{XBnJKM#s@wIjP9njn|vXAXmF9?M1O-f2S?i_d_}by9K~SZp?)^xYwS} zV%NYJ{}STFh1~^fW&3?)x#}+lxEe0z@_rsNMwdnC(C#2vg6i?Wdu^S)|Cm9r%@~W zh1a709uI0XUon-uTCDX|&yIpc2HjQ?*S}f}_H?fFt@xbH=&5qt)yF=?fGbP%t zJ+FD?n8`YoqBYHjIvrtV$+e4AJ7J&W*QDH3x@J7a^r{TOfGmIsVRmr5A!SO!=C5j z7z}h^xaygh^t?Jg)(=vPI@RD&0<^*e7>hVkVLH&2#f;v}+(qUA#KRtu0lmOu;{}bzNXid3Rz>+7bbkiH5nXUoHC(A|f@7 z(gSsOrZuY_cl-laO57uxSyNM*XlA34SE_iy!s3z9v{u-S=#p6R?&7-$k;7nHAxB

(7ge%xRH?;Jf!4KrC;8M4p47aTpg z%v~k3V=R%8GWs_e%3T+*j*NavY4uka>W36vYWBnG(O|A`T%1&YoowG z55cmE6>zltcqwL7F0;FA(eT=6)ZVsum4P&70cwFrhaUx=N;a3S-6EF2k$biR-jy}J zw@;;23D>qcGb&E51@rtJW+B7+Y+iZAoI_{M0al{GvU+ZLi(D#>z$YdsdqKl0rY!14 zPnuyIS9*w6`fs;%|xy)mbMH)(C4xRbSJ&$(8Drbd!DVoh&~CvQ`dV zUW+@0-r(-3IB3O=fINhF6O8WbI?o&@w5lXhL<+MqSl1KSWWu+`JKZ_0L=z zPS5SL^d{8XS=@71CInHl{dejsRn9_8K)<=%xEAN@L!47s4(sbfCTXm80dm|lMOk7D z*{buj!R2<-78nEW3GHGD$H_=KMPI|*^$N8Ey`?*Al-x=>#k7|+&rP6Q2?WYBeCn=;ic;O4gp`#bsI*i;dzm{Ve4cZO5sZDHTY*@8c<2s{RWFrrIlq;!pcCx2kV3k`^-qs0(VfBy4 zl9rIQzD^%6_!SyY^})FpFQn+LEOfg7y{l}Tv|t7Q=9cU@>`VTc3}*|0V@ujb=d~v9 zV(_NVW(z5Ji!Ta+q5z|rlG5$+)Aq*k3B5t#TXqs1eb)PjNQA|(CF+0x0NDBo$^M`F zank>Wfc}sEu8OmTwG*+Rg_-C-Fuy-C`aeDvva|hBj6Z{+|IpM`%35+r0_Z#qUDh32 zko!2du$qv?jtKH`z)--5okiwIyB6l5^`;$GB^w2N!)QM9Xno}9GEsEhFNIM%vS{;h z_+|NHuG8M{Q?Ju*rmnu#~%{VcqUwM9pp4?9IKVk=8+Qmw4JdDoLFmAL5^st+v>B9=sX;hj3aG} z_c@oWgS|3|G%_t6({1RvpQ$_6otW>4g^JD{&KL%jBG3OkO1VXr*NT94ovt@U2sNZh zPIhQ5R@+NL5-U^xQ49;{e`i;0DMy`)LA;tXWCPS#BMndN4v15Bi2$?Std3V%LoFM< ztH1rbLBrB+mL~p$W3?NV^zn2{-IR{DX|UM3^jq=hunaQj|P%WGi_-MjB%a}d~5 zCaa$Zi8O)qI&eAaE0&LU0$HepB%HK*uRR6~`hm=;6vL5BpVJ)69Z z<*gJd`arVfmkz9F#C4d;w~ZeZOaj%H2{66+S2ujbtP`XSvIQBlsDr2x^(TZi+&ZiQ z%%8KJJcM%o&{NNP7Fe1;X3Zdpx0~*-1tjIo{vpE75N;m zkfzeFu`T`zJGEmn!;Y{U>;m@%;W|4Na34ylXkQlC-K_JdZs`JUr~|rxT&kUX1M7_+ zBXaP6Ga~uG4s67UFjZ)WAOcqadFV~5C)_Kl@JgFn22%u z;`k8$0H`68@S+Ln&ZYtSRyui_n=9?k3Vr43=j)*GP_1eg^CDNKI^~OBmhaz7mZ?1x z-`Vde=|R63PiyW|-mg2Jvu?b9hOF0E-d{VhxP%25`y;gLM3J{O#;DrYnHtG1gb0ecADYe)uOhtq& zyF_MWq%Jo?W~{+SyQF}60^(!}7URraUz-!_uH%SXXQ-^B!~_A>%^%C>Sy|vCK-uXa zNAHbs3&fP$6K9p87NN@6AQ@Lgg9-(Nugu#|A%}++A_x@VKDY^YcyLmI1Ka`lxV<_gtzF1=s$*S669b!Ew4=LOHlm4{ zb-D!t3(Koww}Kk7R4P~~=!6&sXb_+CgZd;Dcj<)N%dN0Z&f4fi(3eC%3qp7mad_%x z%{0x?X4%A}+D>1G2PfFAdlj4n8&XUAl%zcgGn|HnI00z^7VG$nn_2h}Bb-AI-AY5q zAu=oaEoOqdB`=c+*6|aL&j`ce+JK7z*4a!Ej3UB`Ao>R}chr}t%G(lSYT!hOq>3CE z1pdlNinlbZ>unCP&pNZdfVBqkV}=F{o~<*MG38``WCMvlmwU0{AwBasE2)+&bY=-z z;1mjP=O^s7&TTh^p$3^D^@5jqs>H#x7I@W8mTU7P@>Y5yx^{BtAxGVUj|lQQcmra~ z(DY~4GQ>7Y%)GSzQkI7uHFpMOfK9E>htQm7w zbmLw`ITsHK;DktKxjZ$^)T_$`7eEW%H#va`ja35&Z>T$kiV07HVj$ zW8%b&&yY8i)&=t-%ycLA8SIhLc?=MkyyC7m-ZA9vX1_O+!BLjO;i1UWFqB_Gw&Gtl z=_9sjZjZclq1php+M{n`#ZGE;zaH$8$I?!p5N4BTw=~gG-ya{N4o(FoPCp18X!nTQR3PVKU$^8^RoY*SkfT1<(0+)D7d zbjsGc3_3gZnKcxVb3@eZB*qnFGf2B9LkANg=S=Hj^QjK-)I0P6QP!}r^IViZ{^_Lj zq0VrHob?1i_=#T$0x-=Bb==r3EWtT%Chjr)fV0V5!>sUQya#guyH+all}`dJua0)&I!vG~##m`4X<2V2WGT7&R3hN# zedr;jr1>6;fj0abZdZ0OW!-1I8F$z|Hjw?yM`={V@nQnh0Iy=v(z2b^3!NQfTeMN_K z((YqauAw7w@`Xb!+x^Zg@4%LPEp3A8#X%KY2bQiq)Ri!+J*W|48(RmQuHXpLhXB)g z=#YI+HXlj6>~#R9tw*)DQ5su#w)?#jB`g!v$U7I@bD+WQM3}rDW19cP*gMB~5`F95 zZDXcw+qQe!w#{$bc2C>3ZQGuY!x zbG4FafoXqV2F;YQ-4z7>`UknCeaLzbTO0>cgncSiY2{NU%XHfz!ZzYEbU5&*GlCVi zK7?yyU(yOnxhSz{*iEV?!`>y$Z=m1;_%W^97`i${*|wjjHb--f@RWrw zI4*WQEzRvmrX90skB_$4>#(U)^O~l;LPu;J3Uq2A!|R9F&fF?Ne7X6J|J5HN_bVV8 zIiK~mR*Q$IyCw|3RRsTYllCd>)5cyv`v@&2JkSPazAfEtg4Txuq3zUmW4D$gKWt=k z5Bj!Hi-$DZCBkg5A^jyzi-$a$KQ1gLqL)B-ZwmgdzD$fB2RsQr07|AStT<{?o*T0r zOa(qT$l}Z6K31`YHszAemfwBg#HUlVVLLis z6x-J7YuDWgVvhuSZ0>ZvqKynU7T(6Twi&o4wp4RTK22;vv>q8mA6QMZkHKjfQP;+( zZ&>4HZpHGK8w4~55kj>M=HFQ6J&HGa#Qfjk;w9(tbj>rZ^L4aptyT*SrTzY4Rl%f@ zly4HF{$EnEK+10|?t%Kc9_NRrm{9Yrd{DA~k=LcKj!E)i4~|08tlZy}1|$<4Ae-~B zWdFp`4_iENjjFOFJxgWo{yilsnCP_L$sWHk((02vkcrBxg5JW6FZlxKG4;TRA&IW( z@4!b7>^xb&xwMt0rlYq;rFb1l@YgO3B|v3djmD z_RqwRsP$!g{t;rk>zNBA)a_DQc3ZKK6gH)^oh4T;x8UuIRyu-tcoc4sij0Vk7=fDB zLu6&2y8hlGXQE?T;}s_cPl?u!suy*xRIp*Xk+cmw8Vg6Oh?Q~oQ)}>-^#((Wy7>_+ z<{P~mD-LVod%N*ZE;vO3O2LS_>kKt;#fp3b4&g+u6%*SxyEY>ti@NDHFprv2X_rm0 zqM5(?=)BEYsS6pUi0t*|_FUXzoR}s+D;e$kl9bOny{mg+ODvD^zi4kdq)-_nt z&JGjz9}J=>U#VoFDTh(chLVJ|3Mp!_zB0wM;QhCV$N?NJuOIJuiujyI`?)IbFkRjU zm5pU4E-_tpKU7c?gqVSjh~k5F9+#Mbkr2MIyZcw5Hsv!8fmN5a-Cxfi$7v?X~9(gkJU4lQ%an!qxe0Lm+^Qk}B~3`Lnit#yJ9&~(+A*Vg)m z!sKY{2humDMtcQN9Rg>ZaQp56YE+{fLG-<{$+?V67X^>5%^Z>IDZ!I2gm_51CSW8N zfo6gS1i|a5Saz_kz?t`rZ?P`=Vkx+%FO+?5d%g^nYSW}~E54eMVaatFosu$>bg_HC zD5LwlVzK*MU`;v3$V$PhO&;`39^0r9juMJCGe=oE@II3MMCNvqc4gc7`X{9v@lURO2Qi#Qtl~3vFDAl^A zEuc^>A1HGyGNp_RX~s-D)(_K37^R3MuxxE8>~8D^jM<)~9&je8<0Px|q=t*Ia)?o! zTspD3xxvF1Smqr%J7MX_i8z5ibj6v@%bYwr-#n6OO0^KAZvk0Vi}Ab_51JEi(Ui=e zGMQfpU2{IL?(CBA?`1@>qP$zVbMf$wFe4un-+r3sm6G_Q2OLRX|DgnO9jWvRM3+eqcigzo` zg#c3VHbU@&gG4t(i4o@hxv=42Tj9GSpl^t-diCUp@~Z211ZK8kMpf*1(SW#nCvLmN z4mVyG1W0Bm7GpOb%+RIl?%7XFW!XbU(Q_WygIV`6!2?SUXnQNS&Kap)5vX@h(9u5E zkJxB^3*V`7-QiNjY#S!v>2J&I-y2wd8Np7m$Rb6d0bbZ!9Z5y63hI)kyyW*-1Y73* zbYqd9Kt|OTK5Y=RCO0p|+lPa82j2>@Ju_i#H+8Svncv)Ry}j^n#R^ z{j+47a{#v5n*__VTwGw>%*$A%h#TF|YgK+^dLrpq(_@X=NdL~Q$9(tFrX2KTrgJJSM9)BBZF zAYv&VJJ)C{jY)2++C@li6dd1ExjVN2xS(sGz=9tcU83Bzf%PkBtS@3cZjt1hd_D`d zBbp-KFO#0p5|DP}3$@){pRjnME)g+fsHKEWr<4i*Zedq!hZHHjUZrip^o8h+qX)k9 zk6xgVH%CbumO%{J8D0QnT7MwQuIo+a!Kg~h3p^G%sCoPqJ$V#+lltluhq7U8_^C8epRRG{W`}n6SsN2$S6NFvj-`{HRM1ul5 zBD)^ciBvAc-XQhc5V)b1+{NMg*N>t1(d&DBDn2l0Y$*gqd+xO-g;C)2;+gXJLcD=j zcm*+py3pY8A-hvk$`(2N(Rh0hUg;QdO!8g>{5a?lD9RYBL;JlC(7)G^GbJ%km=TMo zv7zV_m&uec*5|MR0^6oq*N1*4Vkhkh!3XP$X(2pobXeZ8lIyeO?7hF<&EE{P(&qOc zI9z6x)kn)*CmOiM&Su9nUVzP(NOVmNLjv#|ExEv^UMAl*YYng4VA^&V@N};s z=F|;r?>h-75+K%HDoDU03$U4&f!*W+=PvKufwxOUASU(Qe}-I) ze8S($b;mx$Ddbd-8-G%GHQ*;ODy&>;+pyT5>9v!&@x<|4@!_W5N4*qC{4oMA%7*z| z3K??Gp6`H@IVoZX0?QS~?F`xd? zNXMy(k#uCK6T3(b^1Fhmv|tHXl;!Y4Q|m_V?rbhAwkXm?xE92YfY?U=af zOiN~CE<(s;MU!ynw8Wuj{OQ$@kv86k;6RJu#K$U)Aioa-ePbHmRx1fllB~(u{ zJ*mWe$pWxsVLq%TCx{QuMaOuzd*INAaOdRVseJlqn^)Dt%fp6xLB|os>jOKw?RQ|? zk7wJ5XFKqpe4V|3Cr0CW!Q;=HEn$mD*_Yqc?p~pp0^fudCS-M2Bhf? z<@o{q^aAztg7IJZpzw(!ei)B?eq~?7xVqh@vti&X$lOV^12HuxEI-dwK!)fmPBGy? z{r(W+NlxUF(_;(6y~bbD87AW0++QuYdCmoU`=R85LPEo3P!l=l8FB{{_yWeNgn~s| z0noWekdv>#Idz{z1Dhl9k4(m^oYuX9wp*3B##eBUnVVKmkB5)X8E~WE5FI!jXLRFE z$;$^(p?EX9TlY93Rx%TIg9+`$(`$xug9-0743q=1!wm7_CKo;($MRCRKRy0{EF6Iy zHP)9BSrZfkNM;_l$RjAye6h>Lr`{*L1rz6qb4Zk6(d5h`+tDsW(U?OJcD9y0Zzz1! zuy@Y(CciarKIgnFBkZ#r+%wJzXg14E1me65`o6Y|zzU)VQ{Nw$QKFzA6rLLYQ6 zPpOtBsB3~IqiQ-2mpPuqB=u%bIXB%@m}6;gPxpz##Jn^==Wv_!pnhI=k5T#9>dsS1 zO?b;At_@y!40>*%&x^0VoQZNyjJCur=l57~TF16xZ7?an{$^Cg{Qjbz13ro_eCMIx z1*XmpbY9fk4y?|e^|KvND?4(&e1abQLAWz?=PCc^q9ll8kDq|M36zK|Xngmt7JxLQ zK0uVpno=clBz?;$ZH*XQ;b4&-FamVr<9s*DUXtboPo@_!Iz6g?r-#q{YJ1{bfU^}` z<{o)#)kwu_L`AcMiiJ9r@1i%##{~=SV8P2CUZeuTFbk1d8W>C|$R!h22*tAXD-`xC z3nEEW>r}qF?gQpaCzEiP=e5tz97C!%e?u_+60g3@6LN6NP11x%q>qv9a3Fn=*%29J^)f47Ds z9WD!s8~TE7Uh>z+-s$S30aVcHR!sqIaUZGFETvufw)CJ9)PqquXxTQ%^US)of_}pB z<${ki!s%I>CNIKAsQ{Xu#EiTnTKRj`mu+kLTP+sZS2h_Hn-arAgi?3%te|^E6ZWQj z?p_5(cvNPDui?>powePV|8ub5Ff1F<9)PjxPWomT z1w7(Li6MU51HIS32W$As6`y8>O!#S45#$^0D69wDq}(I-%(shink`BjcEux2&}hke z1{DjK4czg@=TlJPjc;60BY99tY3hgapyu4OCU8XgKvC0d zB|!XSOr_vlMgQ)zxGZjNkxRMV*b@&qIr2oEnu+9Xrl?0@1gE4_A8RY_xc?dtdf_6bgwx zC4MgdtglpeRna%&OLP1e4WTgxACtb@Z=>72#t#k#7E*(oGzJv$Lm3)`8K%Sum$tZJ ziynxkl#+7V6j~L+j`Dn@rdfOe%{hC8a}(+?Sy~SIl;luw5b- znfo4nOY43J?PnngqLK+#-kbBLqG1LCdS4B8l;kfRo7Thy-J6M^UksE=1jLLAM*+g1 zWS*vJ6}KfZ=@cG^j2!0?HVNehMks2(Wh1AaFOf zGLF1iFQF+&xQ1Qms$D2&XPBgk1?NtxR8*_2$h(E}mc)MVt11phyaCP&%Ra{r>%Kr< zB&bU@(B-h|QSM%EntTU@1-;)|lY9q)1^pkK(!jMQ{k}aP`yDT81e{R@1g~@e&drJE zp1!k5-Up+9Bxt%eE+@hc6)D0^7AmA}l9Ml&H;y`lNlM@qEsKgZ_@){GLZjepQmrlZ z#d-io?b~1b+?86!Z)t&TrdOW*-jcLoe-e2<yE{a#TZWFZ`mWg_poJ`h!(^rDYrRLC!jA%DqzH6#RlrjjFIJ)=eQF`tZq^mPNE z>3y$6o6KbYeUfPIsgYq02ulF6riN0>bdAxrSQV&PNADeKwbTOYGJb&mxd8McSjb5UEdeUBzu4*Z6|#w3rj4=W<+ z9_WXq+y24Nv0`25v(AW7O4kLPXRc-1pLkhiTZr2pKz&DoYkuc4<`JdaEj|M(QYF}J zE~K>#mWO!b#k@jLTLiZ=Sg$|!k*&=doUcs8uCKsNSlZ)l?6_SEifDD*r zwcF8-?y(74YH0?q4+8d#o=n>@++qIX)yAy}mS<#}auS%DQPQK;01~vfe2-A&M+O@2 zzrm$3^Wu-tRPs565@$-v`Fv3#kCb4W>8lIIx;9xg9Ff_e(bpjzF@P;xNptvXX)QAC%HwMAGOw3=fpxq`K0|n z8+U(mK{{O(Akb6_ZuugQezKd7ZL^8ZNGpQXScYSO=$YW%U!OntnqnLq?(+EM*M%OF#gYm@&60CO3=ZXM+BBzGS+!I}6~0!!65eb+ z6cnmlt7-YHVqN77s8X>!pOdM2+WvOE?r=PwjAuZe`SQ6rqJ7@Q0ok_GscfrSG<~g$Ivu2B)GH& z(X>`E+3Fh93}|{9XRGQ+pW=%qybJqhp$_ zVHwuSVDB>)u-lnNMpeUZTJF?{+v~$2s2OZN6l|BOM@)CxSwFo}LBkWmTj@3!8 z?#nuCntkn6l_5D7hZ*-)G`+LWtEIun zAl|%w9HuR)FzZ+&MXN4OuV6je1F?C&d~79;BlRxQxjNpML_IplPYe>b71xnh6b?=w z8=c)E);!wVXSz$rkuOs9lrQh!)+;`?=xkkUBNaRnY{gp0SMYE4u9A;TGbLB2G8oc5 z0%T{LmY~xU3kHhJQ#7y6pTJX?(&K#dWntNRW0QCLXPcD95TF@3E=*$OJI$R4I9aZt>a1&R+a&Du8ZNzqh=x zgi9^GaFFcvTWjzhp8a+8)LnkR-q|H+jt|OcK36RJ zps{M=b%VzFvWEP|gt@;F_R7i9%589v;dcMfoV}$3LN9M^m`ElcD%Dg17kpC9V2@Mp zoxiyZ6$R+xh3axL=&>)pN(5$j%Shk=*$>_`u!+sHoB|dK=lj41dMmt=COI4&MTAYL zr_ZE8YNaRZyM32T=%ME^ABBQI6`EV`+R_y@A;#5qsy6~Fh?$T`_HXlIM#LxNs0R@O5#Rk{fPj7Tr0F)zCtkIwX!rD!mzP`!I}~bC$qi_uZn%{fBFhe zuKRm}&!Aw2r}UmERAJVReK5-zoy1kloM&<#;a5gNB|?0o%=xJpbX8MRUTc<>1?zZkpD@<9lGY?l)b5$O**)5$-XSHz;47 zvg&(Y#RewpCWXa#2-`9?l92*#G&M-KzE}$Ti6wJ{^7-i#)=>ewNv3NCyOlOqv{0~m z9DO86Uz%R*i&3aD3tELlMrY4#gn`v1Zyz%#@8#!)#6VoS_JJt95hF~A3s@h8v<+v| zEUJmlYpC$pjhSt339^|Wnff1>JBUOv{%mb1N^q~^`$rG*FV|gP*M4ehXWIa3>H=>h zfKA~mivz**NW2^|uie#1isU}Q-n^HJD?@F>h_%e#ne^=~BpZ*9C0y64`-kD<+$K3n z$szi}PI*bo@_N*u)vYtOOzb6G2Ik~s4W>LuIbl zP<0x8+H&~n;bpq&wEDs3SziZTC3J*~mm{XQbB;*b)Hh?V_l_L?^B#ijiCoF> zMF@v{vhHT0KEJ#%uXGN5ag#pWwmM~Fptqalvp8nc)UdvC>Ee;GRX3mUfNlhLRRB8R zk73x~$Sm4(#J)Yi9`XVK$}1_yFot_2=$EB&;=yA4uCPo}NV@fy)EWhF@rcjv4Zdt? z;C?x>wEB7J&8e${#H47iT{APt6+Uj>Nl)M4>|Zvov|Z+Au612r*Y4b(soC}O*QfBJ zu*eRJonyn-UG7Nb+&7#I(*9P&wtoAgAdh-c#ND^0;PAcZ_?rT|G{6I zJ~O1p3B;M3&9`Cm=YK=F(@N;8s|+l>zS&h(5pQ4)X8}x}*V3}Q$EU6eU@xsuxQ)%2 zSERY;HDI=l)mJ}Thw*^ywgk+KUQBt2)sV`1r|MV1xW|iJ<AijMl_Wi;@YOvPo znck*5pW5Bh3Hm7j4rUNUl8|sAI#=30zkYsf`eb77O^DWdJcU*1#$ zPurx!r;x$Z89Iw}ehN_?nV9}IR^AY0X6NMt-aw83yss2Tf`@rigKH80T5qiS`PPoA z5>*AiNJz=r#8zdauBWxyo?rer5nP;pln$>lP=gk%AWq}!HIvt%2?C3F%QJ8z9j=ad zhiHpL?-7#iDyM$Oq?z)f#tn_V;9bs>@elKgRZNCgysFgN+KQv1DZd@_LTz~gdt{(z zhWE!(u$?7}Y#v~o7j-}wMK;T3K`eUthvRt2ccGo*DQsUBYaG_Vc|(MC<+>Q};(1RR z)}wZ3`OFCrIEY}NR&Zb26gDqKnUt&mq{|9qHdf&WjH2HQc z`L-W~?1@hXU1WtxceTIfa+q@3cx zH@t{T`ab*)NPMEmViPZj!50z(umlwk{24en``yZTVNfXS2=Fp60yQncv_Xx2bvwf4Qzb^K`A_w%-ILJj4 z(uE_?xQ-s`-k3KHy%gkH7!K_=xMB-*wK%j!yU^(rGR12eMrsd8Xi42OoXK2+6W3?3 zHijLeYJ1W{r(atyhIU`2;)W`vO$C^~%!Pe#d)Ofrc&lWcwuvDp(wj5L+auDO0;Y?~ zZlmj8vcGAAvwuWkN}K=OxLfg?{{A>>cZiXX4oZJgU-AF$MuY#1Ir&hz_=I*Gv-JDo znk-^xXy`&Xu`S1#5Hr3?vP#dg1KnH91e#>96~Jl0fZis_-K5F8m7c!NKniwAC4)ZG ze=~3xlneM4NcsLd`yD{DEllLT%>pf_a3tdo-3N7FOmY9xfRV{6xe9bo1vFP5yp;sP( zLBW$;fWKaDm@ALmryJ@On^h12I!i?Klw}89cdBm=fsroZ!WL1#ddd=VI8Sv{h<22Z zJ0SyFIg<$LLKSlPm)ZuUdIef-18T-mK72FCDmRaXy11jx?7;6P3-oNt`@cfg*^K-u z^5_-2KWaO2{C>ead%V}t9fZe~WYFpoifdE2_B7eJow$t$ z*My;Nai<F9efIi5*7{~0HE;tkxdoao=rl*J z*dz)R3~ZH)GzxA4L@q94;zbMYgbJwsVFmFET?)^IK8zSN;{2&Isf?z!8@!g@1-8ox z=oOAw;qB+?m=#E0#W2s-$k=?RvUJ!{=GLp;~7klr~P7U1IHwEdj%);#oJ9dYu$ z&hbn!<`&rheDJWocTo1sFxgrYt;X8G0iwW;^>@*d)FYV=b~G($*e00|k+g||JZ9z; zjRxA3{Rdm3`X!1nhTOs?{`w3}Jojshd9sO&Tj=!ScYR#}OS(69*uH{8gHfslzDOy5 zaq-G2MfY>~ojZ)G!w9%7n`TH~H*qT?xxd}#Xp?p0H3}7bh>tO;Ch_K7tKB&A9BohR zn9Z-Gl!bT5>LwK=oW zPmWXrw&3qY@pYh__BGnVEEK8m^;{EqNV^D*4DA24V9`t?zxcItZTLM(=)8kdhM+BR zzQf6}+cML4Kht-e8;JfBdH=~N-{f3wcMB)INwo-HFzB7&xSjC0ouL28AD74rea|P9 z&@ZiE+Keo+A^n(?kNj}Jv+8f1A*9pq2m1K(gg(a&h^U=)EHZr+@;6kqINeaiQGGBh zSh_(0BU+cLReQW7uY6CwxjQytZm}sI(x1Q}H zN{&_F;RsbB_oxA0VFaCS<7zI)QXTsm?*no1yON1;Qdm)Sg$Vj-R}SFl}(MriDiT~<`5VriH&=Pj=xPH`DceHHS8422x=@1 ziP^wM#^h68=`9(rK#Dg&@<-eNFY~KE0I*WO;5SxGnn?RxR%wCs))629buAm~0YSeVAxgmg_YxN!6r0 zk0eD(+n_w_k!e|1sfs$xbS*l0bwz9bVKc|0*MbkQp zt4J}(hZ>>SY|So3K|cd$G26t0;eJ__VACjj!Wpr4LWTAK>rG)ohY`_I4C5f_UWIk#?uxZd=Dun%XPQS_8 z9K8CiO!hgC`7En0z^e3VGOck#W?-zjNT{s{K3=Onwf4*te;IoYAM0Z=_pHbK94vY! zay|}zS*1JoJ zDD_0qjmGe$QoA%^%-Sa*jdks3&seL`5 zg*mX_T-t&ai2+lpFlUM|O#EEYsxzySf=45R2H>{~S_MMq_PdH@gr*5)EzH31Ng|dM zeH-s?iJcf9Y7ifBZOBFtbyBvTOm1|ffgAQFNhC{>%p!q6ZRgF(d6;VXd23ie_cP8YpCa8Dp;U#Li4 z#JLaBxDr^K)av0Y`%51TBO|2ZqpC?yR0xyE|GsO% z4N^A%PL-}+SvQ$aTuM@@F@B+Pfv1qSYB1eoa_%{Snw*rHb({)>1QpmYih??NMltJ2 zJujx@x$v%?iky^9Ix=l9CU(36DuF+5%L^WS>AaMETfqL&?4XMs0PC}EchS&E+BqAF zhX%Ar9UF_96s%xel<%`4?Tb>MEVl<`g5%*SkT)%{DBwsEBa;@W_7oR8vAyRr1P*i}*m;EIJ!}8+y7Z zv^M~h7SoaQjpzoU7!N- zinODM#e{Yo)w{_9ono-T9Vy3n9+$B(O-GIF#EREGR^efw@^5P6+tq9~i1P{QdVtX) z)vRcmq{}F2f*puEI`kleb%Hd(@H$*dEeVoM^=KX&Yc?&J!ODUg+o%zTL}vtQBjXnE z>#$8+d4SU^TKSY4C@NJ{{Sc1*#3IX|Q<`i?^Lg`1wya_RbE!ZEz+=5x9J4+2iwsT7 z2%sumRWF`4@t-5etqMt3^gHWIFm9W(YN9KsM?uTq!-`bz3|{f@Ha4v-aPTaM1(p*} zdx}qBU(&h6D7HK+dZWsN+hy>B4|UXn&eTK+$0Bu-1wCpW22ig0$FcF1MUA@nbxm8d za3B$rMO2b|S~EDzP`p60|r4kU{7J`qncu z?s=v(PdyVHlSrA{rVwAe3@aXD%(9B|>o!%GnzW)Bte>_3t}1ibTx!uc%l~}CZc3n- ziAM=DTjE;G+dsX`ZEu;VN8r=%i+1%@yk6Yeh>tYXPWItx+X0IuORgjksSWie=T5-cJ;>Ncyi3vCH69tl&|k4&c^qv`X%N z{q>GN>sx4hl}x<~!j4|lmlxRpnphQkuSB>b4W^L{LUYDoO$=fKYXZoi(6S^9X->Oq za+H?aAEqJzhY|M&Q6#7j#{BQAC{64)vcMO$bE}Byx6^Gg-yXNwZB}q|)LbK*(wL;0 zX(6mmnv!Ze7LU$}WHHSbLdy4${)fuw*@{Y7GjW+p*wlBWJkmVXtuaRw6|{&WOFmG3 z>GWR;VZyOci8o9bh2dYM?=oI)#S&KQCT}?u@m2e(V?2_q*inIknvOhY)DD+KC*JHb zGkliyX8AuM&UvKalHW*f1-|cVMK0DORbId1p1MS5e`wLh6;Q8APJ=4HVcd3?=^j#c z1+{2NvIOqypMZrSLW|HyO)1g=!+B((?gBsAYwPb)b=vj`*2F=f+KkqqY#Jm&d0+@o z(A!3*roU4?l|*MV@D47#GHAP_w!h22kVc1$%OJm)K9nH8Mo9N#&1RNT!*DBiC*}+0 z{+$B(OWT#O^eXt%RUz(4Ch4MKX6zpphMWOK9L7tw4j&qgK|y}^F|C5RBuTn_JwG{$ z@dXP3c9q*Ifk@gII_i1;kk7)PcX>Uj%Gw;hy|sW&#KWHXp-7K5OYu()g`k7cqcJC= zn^;1rposDS0OPI+cgJEPxK{hmnN5_a2U6`-9F`bm6-DuY#4LNxxFJ|yhu-)Vi(>Pa z)M-TQp;YYQcwcN{15;V1rJl6UN9% z6Ae7l@#0#V`&@|xCQ>B2DYZS~SMdKbtop#eUV}0Qw{kC`DSpGQxgV*n5W~jV<`%IJlr0QWy0ai%o6qpQ9Kzk z49TRwIu!yJIdxnW!+mBRQNUb&NrguZ3$0UV+Z>V)Oly*1$7pW2=dW=}XV~m52U+RO zAua(RXHO~8MJ?r1q)T9KJ3!n$qBKJjiJlX#hC_pl7b7Ty>5CQKgs>`7W|X~u%PdQk z$_tepz^9R?Vi&YkCL8|C82uG>`o>WK&RPwghGnqcc8BygyqZIbu*SY1}T+ z3~NID-nVE|^#oFTA+}UIDm5GDT;h7JE826%Rvki?Kc1wPu|FupDNc?UkNP-=qCfdl zR=ylpy__Iyn~V8EJF{G7I0{7Y{DXAs8n>NgXAaMu*$*; z?EoZ--ytI1P67n`J?~O>oJEl>LVD1e#)QM8X*N(zBhNG9%^l*B8GlqvLjw?yQB@^dG3gs-#$+|8fnYW5S@bO0YQ?w&E zfKF1kRd{8TbR_NoaFv6_|8@Y+xX5#$o zrL@>r0ou*tbFBNyMJjRCWm7VQ35{coOXjna1G+|i#ye7yqS7mRth{5sTXm&qaE5Em z@GZs?)6C+!YwSH)T*`%u3}X4iaUz~$uuhswXIwR1Q z6%u9N8LCe-s-%Z2JmR|Yc>Xei>DsWF)}pgMnzvH%d~Jj%A9yg$!7Y;~lM+r+XZ%x4j*@AD!Mznox!=8HS2Zf4*aLRt zne9q1;aqWtq8-IuZXmK(Wr7LrGNm{1d`t`Ukn?!HBuN2d8LXO^e#XC0fIJ$iGbS>a zGq_BcpE8)3YCC}RGO54mkTqQ)xbIW{JE#$q#Xc1TGEh=xqKTgc4ok*avt2}}#HMwwq&e#I8O0vttjC|va_2;`E7upkdQH$Xk;8%m5Hl;q zDRzty?-RcccD*SS3SyZTr%sjZ>jYWkMWuQX=5>o2pB3&by6^g1CVF^YlZuU@I7IZ1 zWTA6CPx6w|-hiRp$9~&-z~<-s?Ip&no}+gU!H1wGtTj=65XFeFd7JVJp&_=QB>gX3 zrPJG*-$$+lFYG5r+k0T&2<|?JpC6uZ_xN`H+asuJH3{AQzJpl4eq7rE;UD}3mZrai z*meKln9U0Ju#CRh*HdB-kGq8>%aXSKRTIZnQX8&NrU2VGFEjymjj!JYeul8m^HU0f zh1{U*kNDN>&u))}_1Y;?7pS<$^GYel`;6T9fwqT(sF@N;<@Ti&Yxmr&LERZm<4~xk z|H|8&KOOj4N3PBUbS|QYT=^^0AIg8|>N?<++3)u{gbc>p6@+X@R?{Zu$73h+Qc ztqmBYD6+^!M3MU(mpX%_cE4+W^CA=M zT5K#d;V*(T2_^$Z0Y3o(XcE&plH7k43?!hK2@`+QB-9tE#+39n&s5>%QU54WqiTy+ z!k%eaZML+lSyt>dL_Au%q&$C5@j99@fx*2#j?n)Y&L96^7Pi0F>8E`^R~U)XX;q8l z$+`d<^^eWnIzv5}W&>xm*sL?_A78lCU6#buT_X|CuPu5vcc9tc{~B7{o}}>j_6}>@ zo-DDwrE_jBl(2D+kw;FMu|LVZr>=dBinj0WUA;!HUuV!eKR~Cu8)p|E^msnl5x)nn zzfwZJ_Yc)NuVZ*V!b14(Z_x3+#s zz(8+>s(3eQO#?UduM5;zX?b;-w$gU}?#J1p47O(aS%sP!TXku0uS&phH55euZ(D-; zrS;W)sK%PVtp>6iJ$!qYSLT~W(JgKRl5=k#`&8{t!E4kj zQi{bp@FORAS&g!C_u<`9_$s_<%&FzU)QST%yBUinw+~@!F9IgOn^Zn*eEKLTBrWpM ziGsWgC@KGqrnqcB*<9Q#Bl-%`U0kPM=pi=q&^3b!MEtd(_%;2dClBULL$qeWQ_s~Hq&;CJ1?xEp`b)B zZ7F{4Qf-^s%9$+;%Ydr{9fOM7YGvf!PfJHKqvUybR@88VSO%EMqA&1K)ry%+k5=_v z;nL0#g27@NqR9CCg|GNGGF=B$@1)#&BnG`h=lKuY9M(mpx%sWXb!hK$__zM~C!`T~ zW@i61n>Op%fd1T|05sRR6NC#EQggHZL8g3dRS7GTrddGBdb!sopq=JKEQFr**=o-A zAT(H>h01>NOCZCR`vMxKIUJMguv~rO&xWV~KCzyIF5s|t`RF{-ZJNUnDA^bl#O35R z?H+Y&VLEzN_UtYogT+S+dj-eS_CBQU$apV7x(|H#Z80KUA5p7h72oE8tzWyNb2AAC z=Hji8bmiiFBXWFT`0(lG*NY^q#Wc$kseb^T`x4V(woF`X3hnR`Xmq|)RcEY39|}}( z`wbCNC0tOa;)l=_#OUP>A1`Hkhp?Z{H2n;73BR5i`%-t6cr^p6m|$iVi*@_26dFUE zTKdRKi9Q*02O?eoqBtb+Wp`|~sD{l8F*iy04gqVXysvSuJqbJ}&0fBcWP`6%FZL<) zYo#GsC>70l@Mg~o9MEJ+BAUuhbo_6(%U|!0ktE7+oC;h-dYD+qolHnaDapw&XD^T= zAM@ng*4)*NtdO2URoz(pY9g5A3iJjqmri_DE%Oi-#|8yiUt!&}=3C~~CLl2@ryv$} z^E!?AQj8JX;BHW>r$}$nIw+w+x;70kDLSpE8r(X6(6vP3vaa$xtMXUqB>#@kNkV6{ zzefT$%ojOl^}IweC5t|}d%tv| zMP3nDzjR{8ZHx$-`1hg2v=>36hmcaNo^@)byA+df9 z@cCFQ|J>GL#ETX@!X?EQdclU=gU?ap8lA&w7PRnw-x zlhd)7qFi1$M&G9lZ(Q+YMIO7}#?W@Cfgv1f;|+eXJu2Vc~&ZKH#ez0W=O+_P`hy}N4G zs#&XQ{h4#jQLDx~=KJ*bpV^%+oyW7(4hRpQBZbaBRThQCTr=dn+a-1C_WJ8GgAvGa znia!ety?Rjc#K&vl=vpHR6>KST;0Ar+zSC-y1|1OHSb-lBhE~n79aHGe; z%IW^X+tvm)sw_*;+^I>LE}TJ$SpK@2d>lfT>R>bAT1_+ZV{S0-6e_Z1$9&=GmRXUL5pK65e#4N_Del;76r5;ITPizrk z6`=m*FlaTDT#=Ln;Au6nSm9E|d%ZCu&BjQSMV=>5yx5Ie3>sfek`Di^g0j1c=}1N1 z=`JyYbSm#@(G4|mF)1jExw3C&kj^VTAtloR7q2RN5sY9LzERo0fP5D+8;K>sjzn^>2knnDk*Mc&{Z&QS5&@KP#qqxwQmYoqZ8%M<4P>%B zM&lNV`n(aMXAotkIu(P)g4Z1 zN-qo9v06@DAThd+?1Vas1v~$ zn4SSAv)4AjM$HDmVSt=F$i-^ng4L*l-N?7|VU`}FkH^Z1TL>laILexNW3aBHca~$Y zx{--kU?ya;3GXXG&+tXfy<%}S)U1mM4v=3R-=hM2cIgno9CZ+D4p zzQN3}g=x&|QBfAbD6quKa< zz22wDF)5SuN)vj+!u&=E@dORO%i6Uk9KLFBt>6!hi*#<%2#2U99#C|wbK)u{zmblD z*$7D`8-2ulz1!^YwAVC~-yo?R;-E#1&wr#g4-}rf{5NiWMx_QUgpkc272(}7lD168 z5oQYA&NzZ(l|fNRbo?<#{>+xLD&?O34={;eP(#K@?dlx6a0`_8hhF#+D4oXwIh*R} zF2nXvP#L^VVuk6_-|`Ogr(0u=aSiVUx;oMgu?Vl)e>f>ewGOXF6z~bp_&1ppH=~?4 zzUAfkzZcC;Dmdd|_8|Upc1Z&SmOad)`XAjfw@xRSyK6&H*Z*pYCa`9S3&`5y6@L9l znRM`)s79Mb9}{ORZp7{jAE%d%$aa78?WyhkRUkEc!U zfW6ixG5@7@#0z^w{KrZenFCV}z3FzGVURgB*TmFGeN-vhgjLbvDl}v?8o@bI<^VmD zUBhgiKan8aa1!Ba3jNu1mt?v*+$xF6OEKx)p!}s<>{g3qvBrWh>W(k*RiSEp_Y`!J zeln52%Vnp{$k_vRRJuWs*XSm(+y)6j}w79m)<=~@5R^u{0B zGhNez^;(RdY~=>Q9ga(hSTy1x{+Ht3m*~wl=qDeIoa+D|SPD~cLs#uLyss%NuGnP6 z4fC$?isV-Ry3~)B+S%=oNaIkdfH32+Anq4;=Zb*1#Eev>XM${==xgWvV)(W;{xPu^ z?rqUDI%3EXeRE1xWPT?<@fi>O>OVlz&>k~Efoo{T1?Q&-5=i}+jvLQK*04Kk3_%L1 zyJ}fS#@#T*0qV9$e>b{yS8Q68fjR?YxwjK!Em}9Axg+U)kCtq1i7Zwe+#mu}9Qs38 zqliEifLl>oQg?-(dp4>0v!l z>>FIqg(fc~=xULRWUCC9^(SP;{Kdo=zc{{Ea={ao0y83(NrIA2LMSdp-q+;zM+CJOkdVi&3QqSJX)*qRK7#6!UzK6( z5idpgRH$soF^t>cjUa)(`k{Yc%GPv}mhHh+Rgmg1{`*HgdTA4eAG0NJf^}8zhD+xI z?i8`~p~@;DJ{O^zaw?S0oCD1v7aAE_Qk{BQa5`)-C!?fE85v0g7(t`J4;F%p?NsQ9 zv{`LmtI}R3n{QNbn}gXcp}7ZU5W$TpC9qVGR~5@7o2yW@-4G4%9Mg1iTBKFAiOUjA zMShipW!YqahvkG%`3e6AGV^G8Ekg&JN_Iaw-gCiGn$&kuH32Y?tkj2()oX)HC*1=v zY$)mM1vzo3F^O4E@{LaBe}`f~7m{l6LSuZv zUX7zX+Ux8>BX(;;_Y^NXHU~_Wh}CK47i-9^uFhnLfx`!#jbvM-;k4Clb=vrpL`mTXzH*u=jFv*Y^8JN%cFU)+HD{{)b ziJY124B56>$)f0=Nq$Px}nEtgSuLz!cmJI zi%L(bIV!2uN4kVN^yWwVi36Cx)%NDWqDjz6V1RkeqkBRh%jrC(9bEH3((>neK5+*Kj`*O%I1vn72vI5<=^6^z|trIr*vy|v?ZJ@p!d_wHl3#syUhmfq=Vpg{W%O#X)G^qq zdHEEzLBD}}U!G;N`MSB*!reWgyl`XMv@Sv1(oDGXIUsylm_k=g-{6uZ;|9AmREkyy z5A`omNd&s-wnl8~Nv!$M9_3jn+6_%oE!54#mNxpfrElK&3hqrSX1E8Vxy|uBJ%3E= zJ)&4PGPGLMfboBfhlE0WLHS?QVO|&!$p~Skoz4~#IPFY!2 z4a^fp#!2%>L~)!O58+iuD>#ox@^vB-A{vNVjvUh*4Th@DJV>nyM_@l0%AGQMBplLj zv$WP9+mkHY8^H2g6Lmb!aGgdUSs=}@dwFt3=SzcRUTJ`h@G zkS%iOt(NiPES8wfALbMN=e5cEtmqY8!>0PL89na~BR#vN@Nc2!7EasiQi!}GN0}S& zh0;3EbR{owGZtD?iVU!%{9{QS!u{*;f%yz0+r)P22iNMK28eeU)%wgSErM4_X+=WX zX%FNYKY(}T;hbEGnpAz!Ph8ExKq@6)e6~7({-+gJNTXgswO(QQI`z-)+znl#;4{K1 z;M2&faqGYZtG9ZV_V4+JvE~mnZ+V?piL)3DlI$0><+s8KBT_1Gu9dkQ6wU8Qt>xQ| z32n=-!POV*#&Zuq-rXhaFb=?%3yY?p6Yo^@pH>)}unG;>up%@B<*=7qE;(l8WY~4E z`~{3YJnfu$>gjo?OxJgM9Hr<wqNvHCF7 zg3gj41SFKs2cs|xrUx%wI-uBZ39~ozCEpP=` zlEy^U%3%LRyG=Y^eo$>O;G%L_RCTZzT)I~d-BQW3#B!=omd%3Z9~W+5(P;R<23=wd zM`@vu85RT9@Yt1nk|$f*D@A=Gs#-lzn6|(Tuhpub;O_uLs@+d=XUl>`c5C$~q?ao# za{n^ymjnyfTlQO|{!LeuXYFpzD#z5svo0cV;|TWt`b_;qq~;Ag>zg`J4SGTOhzu=8)41_WAMeDPaWss!)`F`H6VHd(6{$ zJn|qbo}G?fsLjML%n_BJxH&45P2Em&iGIKe!pyO8NY9Fc{ z#UL1b0y8|gJM_@Rt6x<`6JwL1YRygQ_!hLQv=V>uU>J%)5V(5QvXpv>U(mHc&^}61 zAm|df*gC}K{4|c;iJ65=WmDu&UY>la;cb_pL{If`J*@oxQ!DHd&-tCl1j7;y&Dn*L zWA~MTUu)ls1L6}a$15*>0p9E_;6IA9-h)5}ZVV6*TGs!s;_QEiA}9f{G`IghC7%DA z%_3s|&1RA4Tc4XluUvJT3g#$o*$50?lvt8b`i8Tx&JTyM1`WB*gF8}(qR46fZK`$f z6CzRy_yVDocRt{O6TQWI?%i)ilK0em%{ojrxNv8A9gxawe=>rtr*jg~QVqDD8@7wb z8YF#cZR9)0<@5$h$domU-5UpEwe@z6{GkPdNoGR1N*^d2j#4(v%P=bC6v|H96!z@P zH&9G{547R87S#w(oIy}p%Ws8yoRdi1XZw%U86>x9X!|ZqBmN(7mj5b*eP0Lt|1DjM zn_C#W*}DF3#G7S@8ahT3F0+2QY|m@yTE|%8 zEh2PoRde6;IZzHTZ>oy6TD9B&RCU1bYq+Yb3_l91u41*vT50de&!k@L#MSsHvyD_u zzCHxa`=A+!R^HJku~$7wa12RG8TqWRsA=eIV+2CLP#SN7M9wu0PC#ns(wI=qWD3Dq z%l1;{Oxz~wfn{e)XThySHqq~298${2b|NBXd!#bEaZbB=JcExKU9(2PrhNKfaG_sD z0Vn9naBFG%HQHCPl3qAi*pe*?qD1vz9iI#6oT@)tvRyBCVFd{%3v~&+GFOxgl??5G>*ZZeyj1;$k*wr)tm{!l6ATZ&j%@jWD>{`OnQSdVZxT+>)PAfKhh zmB90K=4$=6Pyi@%*dcxwbE4Fbc=2Rb`3dISF$4?q4hNH&;hrdH1RbWe)!1ho?KqO- zQ4zY>HeHh41S0i);a%Ichva#g@YPmrcKpxqZiQK=edgHWVOX!V949cL@AliYa~ax> zYTDB+Lr``Csp@QO3U)VMV;MMe0ZS2*tK>&FxwSyQmCry@lyUTK^snaAN(= zX~%M-$pA%Iwnq0V!o4BCwKA^@`7Bm*g&>pZl%7ZfR=v?EkZw^awoMx4@k%u_rdH5j zYBp54S0v?pM#TvT-9|CU*>cE~!s;Zr%|3a}6}ecci#4j3O-(qAFzkBM{pR19%V(u> zezEw!vKg^=}ir@4CLS9xN&)Xy`ke}mevQar<3#eZn zAQYYA7c@tIX=ydRzCUL4L}eyel@){DoC5AU1R^1~%May*b2ni);F!J3z@EX5c?tS) zgPpbMgJ1x)pHoTQjT$s@(%6jfmRY8qpRd`bL(vs&Q>BKo0&9-mB_gd>k)2RC2SXxO zm>pUI)a&po8&~$h`1gqNa0e@(lf>?8MI_?$Oen?)8uIxDE1y&ek#9qg(mE}UbUuhY zWgL6RGDBawqPanHc%~QkX{rikS!vuY*h)#bSuq#0RKhMm6&8|ZKjqLir+6=x0!vBO? zOL&@^JN^gP;C~8)xvC0sdfx}fw5Y!9mTZ3c4OSHXY_PBcpil`>jp~OhW5Q{WGBI_- z%6hGkF^%T55En3R4~Ovq`XRNMvQ+{{3L(V#yye34Je|vS|L?lq2IRVtIaa3U?uIu+ zMBdAD-#E*-hpZO0i_uOh^QGb;Ea;Lo);6nSU;N@sl*;)=>7F(H%U^JW`9Wr6($7Mg zfnfy)m|aGLGwO>m6+&(;t%ruFklW(`mV`mB_)?bX&ah-m{W2P^-y$)W#LuiEZh0%+ zv5dP?LPlR-#Vy~`aM;!|h|}$cJKk0d36GFjC1Xq6uA${r$mH^ zAH#icINFGykIBR`dvm*5&20OSo7ztPTdAX@6(NlA+iJ(`;)>eWGgNdh#p0{?Ynvi)vXvs9Z-3w!w=-oHS?*RJ-5#nY=|%-?U%xeW9xjgjmhtbxW* zVmH)%#O#5_RoFcFrQD*qZY339O>{#2s#@4DQHv74cw||`a6IMSJ+RN4K3!Pi^_BRx zO%>n&Gja9}MHXayC(ixvK=|K@^S=hcf5%io)Yie&=08mp{wK}ifA0OEAFQv&QtR`Y zWrs^rc0#hFLU2)}BN_y_A+snl7|b}iF*5Wx#j_|FNf7z8Y!wu|hEsuCO_5VSC{kqezX1DJ@vHaE$0>fJ0uh!?^RO!gXi7U^&*UznoIeyQpmPj@qD*?3vIS(Ta zd4Cne%Olgl*fr&!)P83SrdRrAj;1$*cgP>BQN1W?TR~MQ_VjK2h1Fw1wa7dFn*FA~i4OCvhmF>4q?Ya-HmR@J&!OEjj*6s5W>-ygEheAa2%!pt!@CNgdBUrh1*gHtq^s8kSfO6|yETDdt~EBHGt z#1(UWf2dpk5~QV1Ma}FDT#Rl$(op2~s3B$%QI?bt^HX!_`R%3IWA6nF?fC}-$3=l> zv+vfN6sORN_{c^TE3z8(w6!G`arl#_3DWCmg+ram9(D1n=bn;-oe>}VCvJV6%#Rv- z?IwsNM153;IvjpSeY++`mNv#ta-D78F5&?5%fUC#`@7K+;(tB&7SqCcOMe?smprTS z&eE7Fr6!qd@)%vjSPc@r4{!|iey-~?o(%g-S=~RtqP@+E9%3NEwxn`Ywh8i>zb3s- zjN;tBx{Xg{E-J^(kFZF-FK24HC@|>K2)J&#RZwklJF-8^wz2VSZD@DH4K-lhD2a>_ zRGJ3g{jl|U1gifN>)yO^jBLQy$ny-en{Qo z-nOb4eYI^oSCNR#>fbjABpY|TVEDiHOWJR4#dqJ7&9uobu%>8O>z*{$YLp?%lvKA` z$ySYx;+gfvXbz^8i_d?5V0>Z-PNEp0x*%d zN(rJ2m;s9D3ZS#eW-YsU9Hv;BT~W8e-Ok7wIlEAaPkk9K=RRzY@27F-s!a3dWr;S_ z6trzit+y&{P(WE|vW@}b@;L`U#aF`D$e_o6w?DeeQ%y~xr*id>rp_v=0Cdy#eH?!) zN*mKvj`*zBf#Qpi-8CVG$5|}blVTQ?;h}WXp|N_OFGcB&gCT!=1G_%F=tIHL^LA7v zwo6Bf)i~Y0JBCZ$Up2jQEaic@g-C6yUB$Qz7kF^!_NP_u+-T%Cg}v%x;b+-lV6Byz zR)Wbn@5p-$$Gs2kBlxUIErpFjQzNKDkUIb4TcH+Dv?>?JUj;-FYvU%J*SpYJN}L2>l9* zCz8fE(i|L`Q@d{oj)%+Iwe#5GtP12W9GdW~Y>&ejk=_|^r*iD29l6PsZwa>bOl*&I zkEqX*VAIKS(&zKPNJ=HkP&dw%7eGPyI?s1?trw?`rwFxgM@I#1Lnpj9Vs-U{;jQtq z*L+&2&C6p-a=oz>fGjymX=*1`3K&(XVebl;er$N=QD^9TxXJLU91s*$`axy>m1Vtq zlo|POeGdi38q}Fpp2~gp*(pSft!;`*HrD3VI5a1Q;tn_+8Q#}iH4OHWZ!pXk5WtLI!?puSMpL3CLm_BuX zn709x{v`;t{qA&Xy*S)$@pojRdPwhm;ONvS$d5=o9{A87kdtW2M{^Yd&rqATnp=9c zIcK@u+p|*oqevATq)L*+c&LM{b@xQ3SmU6(HaBdm!BzNMw-WFMipJFZ^9wd3y=za} z=fF-o%XXMuY3_lsd(QquqbA{<-f~RUaiBDA;%S`8#k}W-c<`2@ojf^9j#>K=3I<2U z>*6v~j>ft=on7U5mVTij3j4biE;{=ewV@KuK}Ru83#SszM%ZSRm9A+M&1%P<-bDTT z2`;L-lR8ETIoIb2R1RbJTCwOB3fSroAX^&Zpg9dA+AqV$CIC<9h*ah06`~0+AmU=3 zFTc9N=nQzYM$u}M1gii;`!2`uQ`ZsAi1nv+E?;Y4I$X}eau1}z#wA4)*$=D5cS;^6 zA?i>Sc$QW~aJs{_fJ@wXBCn;6CSxyCH)nkYsbs~mn`1M7I`QVy9ApjP3-X_xDf!>i zds8E>GLdD#7Gw@pwDfAksO%9Wu{}(uYAsvXsP*AX5*E!^_^4ZxoC1`HivZSEYWBIq z&xuwAPfdgUI;=v_`J>WS5~qlc1-dJ^sO}L>`+dUt4leR5v}dxxGy71iB05+W@7-O@ zDp8Yc&we^Wgeb#3?H*!6R9BPq2h1Y9ld=R)ZT`R%Pik?G3HW1yV1B12>>Z4Cu|281 znFMMSaM3-LTkS~0;+0+#Dd`LJZe%ex5i2!ZZb?_Z3yfb8!)SXlX@Av7ZrNi1?SIjV z>QR0GS00o^Eb(QOW%(mkMomc?v6kSNsxS=eo+9tkr(OW_cv|=J()@IJ@KJfBsHixk zY~<10sdTKpd)uNW`JRI0hR8xcqVglLdiToT_dP{I`odWHWBJ%1M98|y&8A)OY^t-* zHBB}3*7dtdPi4VXY_O~|x_Z3Mf=@wo-eQKjfh`+5S##{gg@w*CJ#~zikH!Yxy><5L z`-6uF6D?X|6B?IbsIHn^Pjc}+7^5OJbuTYN4CdvN&wOT4hksh#5XNw$2n=Vl`g+pwInoA@DZH#-%;T@eiarD%QZT88D1 z<1ra~^H{5O^f5d75|W#^p&r5YOV7%#c}<$iY^qJYfa+xh z;h8yTz3#!#jUq2Am?i1Jg0~LZOCTb=e{*x<%vly-vg)vo1sY=?7gr@vYg+P81{dI> zViM=ROc95#-sG$#Gr1gwSH8tD6jw>8r_lAYEf&R-_$cXx)^OoKg{(@(PU(3z53X(eLP5K176E2e^TfKnNL{Qb>8+gBf6 ze==fm-Uw4sul&mE<^w;NNm6_AGmN;a0;2~Ne(#hETvM#DCsio3-c;Xt z(2i`D^;j=_BrHJjS;hXUOeTxjKYXG-pd=a;xBIF67@nIiA5FCdyhL8fO%6Dlhw2ld zJtJ1VCqXvRRY6YgVsXrX;rDnVH>``I4efqd?oV-gt5H$K z@u0F~#mE>lZX9aWaS7I3c`7oLsp!9oa}!mo5^kWlFV0Nyy zixV_%tfal14dUcS}Q=IuuXE=29#5;l=;h)WKe+t|1K7iYc%1Tp95FON_U_mt8H z$LiwOb21N%51)kN2Y$Fw+oq?cb3iK3W3`hrHthZ5gnK3c#z(a7$x2J2znIoH)yCq@ zV`oPwD3r+x>mw+yLTbXxCuzVbj+v5)kC6qU#|A)>dsNPp{ypDR68 z>i#?j+rQ%ZaB8i*AzQ+#{3YJPlgBzQ3t1~k3vY*5$kBqC<&TO!JU$-2yCORsHaF$w zN}}rDvm%Z~f+76tocu?K@EiwfgrH<_31r$d5&I9n2fnx={0HAM@;Xv)J=9uAuMIlb znQ(RcB=XCkZ%Beq>TMMbd*B{=oI)bY5-0g+7n0H)m z(LgKSiwuE4{xSH!e_VQEX^4uI27bV}`bKH@$3lYA_A?$qbV^6gmm5Jt@D_^Gqcz-% z2La{ddSsC$ZIEH!U_n~lzAjO^38eOkT~KwjN5VifaJz=<5QHt|OrE5*(yz+)rpen)VNN(u`z-z#1O{+G#q?NZ`vkK*FB|_lYg7X*jbXKdK?Wxk6pO$eAT|27SRQi#yvQ<}?L8Rh`OW4wogF5w+PW zBts#4gy$h4Lu@^9E39YJgi#>G9aA4Tt(KuR%B*6_O2WiQ&Rn3B|oa=y}~)rNSx7Mw{g zW3gvhye8#Y!8gGVVX$2dtjl_!n~@@95{akUW97)D8vI*{b&Q;R-`Sgw|9yB%pj`vh zLL90**J)s!&k+7k4{8_%&Z!vL6cPCy9~A%&w3Tmr%#uN)^{{B-J}IVZ+dhN2rT$u- z59R33mMnb3)E2y%i3FS|%BB(L=tzx4shTp>#_;gSR(5@Tm`g)(7bm5iRZ^$M#bwtA z4|3n#)}%gJtBl1&$Ww$Q-X;L|V~CJGd=yq-$g<4mAdErgvIwiKC&~?hjR=c0&o^>O zcjG^YnYiY$Z2Ea*x7)CaloZbw@~PerK+70yvA|V8?flcXr_Lr!@dsh-lPvb72J@PY zaZ9#w%XY-PAyVrWNO3QUqz_u`lLhuAl5tCWzm-GSynWF87F2OBfn+zNqz_%}lRft3 z^M8Ky{1sr`((Y>Ck}GmT9oOc875n6beVNR>w#mFEz`WMWyk=?CGAr6WJ7AR`Hh&d9 z|NG`EXMRgo&(%>UFpFE9_xgsEa9(8?Xi{ngPoj%77E?NMsXq?&P>FuN#oqXI7}e~F zBQiXTEZ!qY6}5sw@ms`vPa!MThvM!y(xZf1C$cmn#E_1}8&$kum?z=eMEl4XGXZta zs}6Z~DE84EfdwnU7K>C&eQADgc|cU%VRVygeS=HKRo2LZ_NAn;$%3eb}FX^Uvm;INcBF0~Yn)uYOear@RSBQ9^?ZAF%ePOpbB^ArPO6 zAtNgp5g*BtF(2%p^n&XkG}xF7thTzQFDI&G(poqqU0dS?KC$xND3#tx3NeS3P8Cn zcC$5Ee7H^lzS5m);<3u9-FTzwn&G7TOa|V&NH?;Zq2)HIs)pfeIqiyj2oQf?m$J{^ zC+-k0a>|9o$*Q1wN_hljLIE7KS1U}5K>X9n+?t>8Bsc1=B6-5Wta3!!+%mJFnb`+G)vRstl8|UOxW*6c@39MZyeH48!OhTR zWU}J1pr4&^dAEC*4{Y+K!fH#yis|1{u8GqneNAMhXH2>jmqlXcoN22%0C&CHv263l zJUPge5`uU4)J)r6TM+fHpv7G63Lx+(ii_63GFr)f024Sm>U_ygM4*cJN|n4@w-c0V zIU4BsWpfF7zcpKU!sWw_{zx)E`8~rb;R)|XX-RaVT^&`9#vZDucjA5I3SX#{78pW<+8&yqa$zx=nDMB12?^?@{Z^u(JI#xSnF~z;)m?^`GJAKGf zk-5fWJHZ;2e_PCu=wr25xQ=rf*53z1;W~;QkxaE>-`le`{oOGk9SI#*;yGM_&KC#R z1MJh^<}_;aJH(ccNHZC{e3jcI5c$7%-e5$}!;-MgR&%4j)qBH|jc zj5<+s?F^e^hcYm((3r`vCk!Onc;-r>U@r`5ty5x^i6X=%44GOg}~*Ff+dsZ$n$`kvt5MT~1C03+z!(14Fc=Uwt2dVh(%Xc{S5z~*Dt zJUe1jE_Ho_^SYq$6OaVx38 zeh1DEK4$=$U}t{X1FAg1`1S_cqg41MJu~XXlr|6!cxhr&$VX<)!8+y$&SmAw#HSyM~Z{le^j36q**b-fREk6n^@Xg)LxtbsqeO=dvr_=Q1yY?Ing3UCY+jo#h5M- zwzzPEAAKM2ZFNn?hsr=r?_5K$C^Ygf3=+0_vN75b@-clCvd7|Lzzs01Hw^fRQvR`H z&`OWrSW4!Z`b^+?O>^*K5nDfAE+|Yq0J)+u(Phk4!C>q~R zyFmrYI12{vJn7`@P^v_5tl9OWw8KZIv8N(bLXoCB(2*$qsJ}#qazj&H2rPLBcBk-^ z`woZJ74>qq(+>UAco1;1GVf_Wc%dx593t90gh3-4nc|MkwJ|NWPZw!b%Qa40nm}Dh70}9uvT|UR2Y|2hx zy@oz*6d&GJ6h-=C>ALu!{a;M(qCK=n5MEQv>f@!X$Ppu~2dsZ1 zE`5faQLVEMI2a~bSu)uKT!T+bgUWs>a(uAk_eo`oczl&1JM@r1#>RInOv8D;wmQ$K ziU_UXL1H|l9gV;ZpX?u^1jBhty=s+gQMAhGi(F3}GAj1gdtA_-fYXR7`cX@qlOL=A z@fYgcl9=Co7STO2ESH%nsxFe(*rLdmYWmP6ItQQemo(m?OOCBh-u@*av6T$Fh{Tcc z@UfR7@np<`T`OQ5(Ul}tFqOYBQgWiJmE(RB3(#{8n%BxsAeHM z&SKYQ9eFzo*iFkH1qMgL-ZS{(LL5qkD}PkIXYu9xSR&@G{}cvK8TUZ?VqJeIPT2V%xCa+*KV=GL;Sf>u=?sbTj&!FYB@v*ng|UNOnuvmZSu4tx;?>K&`H{XRoAMZUIJ3 z1jUy+m)}a`7e*CO*mtI}nP2#Ue3u`Mc~KxzNjxIUkniNGYS=$uNm{nzFZ%#gc*Ds^ ztH=wTY;CRJ3qt4zGUJ3g5tsEOEB=DOpSoS?-{DU>>|mTOF>||OONOV)0DmRCw=FdV zZr|UdA2#t0OA!wa^uJnONC1-;Q9tnl+msGS&p3&x91f6??~gCRdL&Ny$lFqp z1{k!$)t+N&uT&Z4`BvP?XH-s%(dlk~3BTFAm2W}x;d)R$Zdi##>A&-t(?OQ)j49Ik ziKEsNnJO?CO$b=HfWH3Gh0BDe8LBBHJR*Je)q(P!jG>p`>%6LPd92`hL^P-e2ehu| zoT~~5b&J%8H$xL#Jb4N|YbQva1nkl%rEjIc9CoUD!BQ$L+o2El{+!2j&MO&k;rqI5TkEgqU3&w862n z)4H=AQ!(6w9%)y)@aIwZ(wu$rol$|E3#1b-XyaNX#EYkvy&eSmr%d*=f@`uDh8q2wyp^!WztlD>5U%#WQqWc-p;+yRn?NptVjI3&uxzd=fkyN+JodDZuG$X!bG#^XjlAdT zAA?ZbKVjC*>&G6|z2Qyw7avMF&WWF*F&p!cAR&i;9?MXhSyM~t8!HufP^L?t!}9s-jaCiWiR`=QmTU+q*R z=->jH3ZOuW&^~XmZttktB+W%jUXV=B(WQXM$YDe$tX!i$Ghoo*3&f>R@Y-?3C0Fn| zW!EJJR2j5ZX_T%pFe=zBvX@SltFH%@y)0yk&8ttBRu)DSRZ& zXT9A~1EODIh!96+Z&UWq4N#+dYRCXp(hDg|L1oc3idM8|+OaBr>MACSdb&qkUK(1) z5APLdMzK&!)^SC2I|>dZH%DVeV_3J{#E)9lq%c0aymEAhf}?U7srH)z zK71GxZUpz{Mh_Uu^VJ1KE5Z^EA<P|&f3~IVY=dK$t!gYl;4M#+1L!z3U#ofDWMels7`3#z zzgy^?0Vg863+yG4F@O`&C|$!xm5M`+d`TH;!z^LMqy%3WG)!sHyY32uN)Ljk(3~hy?=uK4bOfXIBpCw7L!-2h;3@(PiJ9U|r;PEj% zH8AKs^Xnizjp?-P=L&42pDJbtPSzOM-o@FNV2ThlP)ZPh2H`Ju+mjiE9#YLUgQu^a&PQN($` z*}8dnTTT&IE9T0OupO966`}8Km6p~?!Am8dPjFV|liE1)lI&rCe~>e?FgR^A$J1+= zZJ|>y3lC!2j4Swa^gNwx`ef1lsqNu)@WCj|r!_SxS2ZyYb$QSmy_Fs4u;dSw8&jpkYJG75k0q6u z57q=?F-||j-%~Z2XnvPsFS_z->Nm<91hZtv{WkY4!5sq3|ObXBr(oZ>+kW6QT%Q;*vodt-qX7z z74*U$#_Ei8m_O$~Ul>%wx)LF89RVvCk`e(ZqzKU z7*`Niun1NEmw(G1viQ}vsug`w8;Z^<6oY*LPIC}W^ZU7g3_oAgimB;Hl51`teyn$H z6|^K;?f5g|UGp5(Bgi68Qx;j}(5Mn!DAcvbu!?4=hx*ZOVqgn~W`%M2tm6(syeOu{ zV0zx^5V@8R$>cAM_m33S*;ieGAojkJGrLoEc_a8!iuk2G0MnYW3B6W|It&BG36h*P z1&}vI&>Ak)Uw9QTJd>^N4&a;qwYye>m~bH}{p8GDPdDCJ7ph*LhDxVZ+nGe|fm5VE zIUI7B6B>VCI)ix05A@MC^LQ!~Zl%wxHt{bha8 z;{ducc#a9ap+mmsS} zoLW?mDIG?afKn%{xCn+L)450P5vOW*sNPky%d5>^rA|ectSbHSSt`o=+lAyZFu`3^ z`j?orlCZRrsI-!pv=4Df?0 zmdIo;V7tyRV28zDse7E4@R*B_Z^i-NHz%Ou&59Mi&k>$)K)WsZPsG2NhuzNxeG|t) zUv2u0EC!^-JIy1PO0*C7gQ!m&@HK!93Q=nFlZeQym1-lk#W*W!NFUxohJlT$3nW6Ge=%{5%`Pzb-JZux*pt@(Qz zl6Io@dA}RDNb{x3E0uruvr;GlVdDPtEF~bteqP0q$(!2EbwXgwVIcDdjBz_ ziuV=0Yq!~11@7DdIuOuRo_sbPzx2@Tbb*UNWb+5!@kgVD?>xb)3Qwr zdG!{d^Z=q-A&1;6M1d4>3=q^)5D(g;nJn+`UDW0T+ArU|Q_pdhVh*cT3thcu2X)N9TCFjEqhp5Jc+PN+InNpe*ki2-Wg2x zp;5DCPC%yJJneeflr557OYeim`z_r8~nyS?8*Y#9X)A)N{?8U38jGylWa4*aoa7OK#;x!k<8HDg84%hdku&k zgqk5;oE@hLJI6gv#LlxQK$|V}CvItkNq?mYKzMSqMIl=404MUdNy(2%Xw$C$!P+~= zi1Kw=!`-)e+qP}nwr$(C`?hWSwr$(CZQK6(H#2WC?@Zn&&mUiMDpjeZl1kM+Is5Fj z_F9!wzg14j#2>4mI~BR(NJ#zxGa6d{8BPueaIXSTGW;72uLIn=i|@(C26Y};NC-&wirB~V0^pGy8(5=)|}2gTRq5rBi^vdsW(t}jlA zFFt(gO$qoh`=)i!6;U^}uXKK?^MKPM&O{52FbuzZh-$MPW07wNtG%3J(T(=wVzeb- zq;?Um_%ManGi)bM&A?Xcz-n)nK6z>F>u$Q|#9Z3hZ;DMwM+4P$#T;9z|MruD9mbiJ(e5?nHb zoqu`iMW~z@4aU;%@|nCeh3C9(ten>%*7_D8(jkHuQr^i4`2eAbWqI_J@nYj~%;4BM+6bDp8No z9L-xaU{b)%F#{NLcEbk2xDmqvh(qgG&Ix3=dp=M!K!#-WfIZfqpx}oeD zM`5vGUdek?UuiS5=C)KSL`XYrt>JW>;0 zwy?c^Q%Y;JX2$qF$l(%*5)%Azh2ic(JI>u6BJ!}?nOg?TBZRXpnZpP2+K;YuD$Rz^ z<2LC_NU}bf=tCdz8}Gshb>AI^Q~@}a`XIyzcT~9cdL(F!<9EV52ZA3Ls)4QqV0)6s z>bZHYH~QekwL)vBKgl}gDb~BE-{9ebkuJaG1?8!NC!%#zwE(yaGq;7Vpy!3QhL=@%oODWQ=@9v6r;s;SsY(!BSZY@igV-a-!OX&@Z!qiIN&L*9K73Ha1{ zvHxQd7o+Le0_4~|-s3*d6OdBQLXOMpSkQ`Ux)=;cF{OxjOVpAbX7%pVq5clbn_dg| zrgDol2b#_JH;5gjSO`W!tjO9ig84b|T(bDzBv&H*poVq-1{SzarLM6JJ-j&UxP5e;Bke>V>aE;&%m-?jdFpAuY3N-Jch2&|>h z%yl`%Jst9kVP5>)L^ap7VBkbEN9J2YV^w%9b+l~*WX z6{BjUipei#(>bm5nvnD%m5aQ9BUR`?5(6QLOjg~gAX2iK$@y~1C2?Pw^MTMgHwQ3b zeXM_;8GX{hu;CTlzcl?R@MCo>b<59fi84Rk1580SOo^abego&-LZ*`Qz+OKh06ai# zhCJgo={j>SOR(~k7AO{m2ZqWl;L7UZ7Jaz|#Kbcx*tRY7WN1rTNSf3>X_2;X13|lX zgK^MYuIFUYAh}q~oeHy#fh0fK`YJ(M%o`V%Uu1y|k{WKj9Jp8RT!zHRYJupw0E4JH zYxfdgLePk*(lGMlAxGEPY>S;fp_HyGV~_HkJ{`|oYR+7)&s=iOT(-|#dd^(F&s>7d zT!zeC(&nzm{EWPH*%OI(#Wsx7^Vny>_ml>Z!|T5H=k;#!`ODfW8?e^4tfMoRhVpd= z)n-BMO&UAr_PIst%JTJb?M)k3=XUK3ciOiv{x)hy=l0FT%csEnc>3?Nk^u!>cwnt< zyH>8_B#=(fg>9hvmzh&Owy+++u3bOdL!diN_neOg02)&y*<3`KSl*Al`I0NEtV-U9 zf_OSDVHHyO-@e2(ns4F3{ldh)e$_98JGZ1S;k^B-ULd-+s4wB&3Q3==J$u&+df%v( zb>IA$7uBaC?>TgjwmXzh^Ehy~m^l6=M!fm)z62Dnl=<%bI1-T zT0n!9$us7;B&WOrev<^BA*U?4A!o4jo1v*cHkU-+pbOn6zFZXYm(3%#er*^@k*}(v z#9+Obb>E;Z(7a3=5OaAhd`bw(?SPRDNBu&?*;Ej2eGB6W(m>qoNcRu94ze`TPi#tu zqXihUJj`w$a}=_FSlpuXFu6gTii=}$9+3deJ5P|OYacM?Yze;wJMPiXUMq|L>m4I> z9!>vJyT++p6HuQLSQkY!(9_ISImA8jq9&C*A^)fa7cG3;8@4=Xn}z{nn{}1&o!7s$|&SgGeut# zO^uiC&kVx}5O58k#VCU~N6J)^7}I5IN=o`G)Y3D7&J}St{BE!@%>Mu~$Y6=G4)DJI z{M;iV24BJLdj7iNKIWNX&vC5Q{eC$h2e5z8EExdhWyx1Y&Y-dyLRoAZ3Q=!SK^9kT zD9zVK#x7g2sBMu!Ud~{f?t@+_VrtG<(f?uc8{7Ig5v^z7ju=5|)}I=5(Gl2LZ*Ni2 zfhxA*^QT$7i`1Qd$dM?oP}0qpI@z+!@F+^q+AiPrBJYJlv-swkQJicak@mo1PZ*da^=PK(W>qwtEt3BDpb6 zMYFM`*Qx$R9&gKRVh~Yn8mX?!P#0Qh{8F@$Hfe8FvCew3CKhIy?L-t^3k#X_@8hg?*;C$JUcuDqyCBlE|k5EXoryn>HQEyN|@|bRsUu;S_J_=jrx5 zjLO7_*&)Q(gDQo0Nma*ZZBp)1%lDaW8p|lY%%K7|$W2=TkTy%$kHh#8IihKL#FQy| z%F++Oks<}zIX1oYZfE^N5l8f?6;Y8E?&pVSUS%~(yVYShCg(rqsYo2rJM|u`uT&Xw zQx3#XLs7Wpt)t~FY0NEfmbGY;El|1z6CBYxlhx2>^1m@NW~T1EEOabv5g_dVb2U*F zblH|cwf;o3N)VfBj3h^VQr3i02ktkP)Wd2tf${(Ys;l`TbuAN(jX7EbQD{RKtJJZ` zR+d$ zVny{`CZE`A0;osPL2Cv&#g4O?0q13NAioPC&?$+A8!5ucU)*^!;b0tb#r%{~yb%2d zecCsBQqUU!&{|wUHzfB=J#UEi8_UQYShBrsJZv;LSPx>qP6o(#q5w@JK%04;?il&{ zXv(Ge3=*89^oUi69oL8Q&9&*(6g~35H=K6kW)+`!U zbdCy7nyeBbv^rVg2soIlnbq?RigK%KI|9!i`$}2+6cG_lE88EnpKx7>oPeKj0p_sw zcXOD?1;ee@E!!+KSnxQ)nz`DIyDn_+65rnxUAsPR!tFV9i#79#5M7U{WKuwt*4SCW z;Svb+Z3bTRYV)jR5si&@m=JMYGbzujr!CaiI=dn6*HZaKEz(apW8!G|wLI`9H3JoJ zlny*;8EC@NYH49LW6=d}24*#bws%}t#E;p;Ur^gFnR{Dcg1{6GN&@&k?$lE>Q~1H0 zM58&KcZMy!*!+0)W|BWvU13k795XL1JEJB$*C88MR*W7tO$VA&7!e&`X88Avtkff0 zDeEt#j$UN9SeZ^fqwH)LZ9>`nf*bnuF7gKyZ*TPt#Z;Y74#SW5qo^A;?*8%KP=-RZ z?v&V~S4bf%I|u(F3loRZAy%0P8UdmbHkCYa;mwO#07Vri|KciwayPmBBT4^Ek%bF+ zhHnzWlQWXxWFkQG-Pzw(uC{yY&QCvTIR%?OWJa=#V~TFhg1d0^q|RdsU$%lfi3*3r z>I3^lH8rqy#B)UauL1UiPs=eQebYLI$Lu;%$4v=L)fpaI8PefK3Jpgg97?6>S-GcJ9R$WV0p_xaz36a8Wz^%&tSOzve|Kh|X6{-O52klTlM7o+}&Q2&rh z;T82AC=byVO=KA?oH%+O;8RN+tEud+;*0QJ!6_^PX2s2>gepSKtI-w*yfmcA$*ruo zG1D0_(nIo@DaJdiU{o|bam4Qj5m91{g{i!$h~H_N&7G#)@SLsP3*dDb_7uV1+L8~# zdEUjoYI5F3&pux;(|;X?<(|O=32IeRAXGs75wxelP$-6o4r*Ch6{Fj$M?FX@3a8YU z!FD=GXnIM_IV3csLH~Yv8%>#}Gy+fnjcJji0lmgWgugZLf2sLlWz=;BxGK~Gzw*{& zssFwespuiI?O*?k(43Iq>F$XgOV>60w9kM_>Mr@ER(2CS(XVOs9ad**%)_%Y`KsCq z@SOxXNQ^2jM-#hRCzm`*V4kRQ-U16JW=#VpTn9DR` zSdmk-K~H}GB7WlL9Wy;fJOQpsPn-JJ%YOLcNG=4$*VK)y2eg0|5mS9%&XHp>gPYyv4!+RL&e?XwQb_4cwk zk)47d=I*g25xrR5<<#mhPrCYeUE#7-z$f=US+e%f?l|r^^T%&TmL0u9>a)^b&C8E! zD*xkDwpPtsDBB5-aSZXQq%Fp22cv@-VJnn#FUk$Q<%(Vrtct!j&y&DvlhLjv!(pDy zXr{<{<_#mg;_eUc8X6Rs^T=Cyg&p10VE~2Ery)Of-IqC@%s>C+!u98$v;?2cnl=8q zdDfUdu`;_Wy|;6xv`VUrEUb&nDZUf^cvDIqV^Ho&lQmwY(-;jkHbu?hNHWeD>ymsY z`AtO}E+?o6Qd+h%sG$s>MRY4AREVwXL=iHdm>3RPN1(BH8#zS}YmT!{>i$7)OE7}r z;Y01cC52NhqO`Q{WzL^v)#I=lO46jt*k=PjnT_vO#_6CdXly z`q-isvL9JH?*Qb}`_`Q3scF;4IT!X!90Xek`MvAw5o7c>!1wf6ta;$CC{2ovIx%}| zIxtD0E{72xhjA>oU|qkC4Y>Fqu)%xdxhRyd_mhM>I|Ow!vG z?W1$7RmP}F$OXVQuI)|E2G$hTKBhsX2^YootQ1DWBmZP+2FexH?5k7Q)I2eVZ1TxR zo?x+F=acdH_kRc@xCYck3_}0_+#&w=eEI(;F%hQ!qlutxi}0g~&|fE~r&%Lh-t>rw z+|;NfA@va&)`THmLcee`hZ7ftCxw#U$Nq%a13$Z9vMQ<$QIyE}f8@`~= zNT7nMP%ZA=N(xf#(^C_=g8g)i1SZsDkiAUXbioVk2eM_@C^oN|CviDY) z!C+?#v0F{Q;UO+}-dnNH$?!B9PD(L89&{3mpo63fNSKwvUIu?R;R5H@Z!(7ML>$;P ztyd4;-z1GDpmc0ebVwGIJMu(icXklJ3pt#BtgX=)4ujnzNr*)U(w-s%|0ob#V7M{@ z%Xl}2_#7x2hf_#XCeM+RUteT`0nJT}oL^L7k;!)4IU`2+N~-hj2+GiOKy~to__TBr z?qy#T)$Yy!EMQF-O!31+2Xe7sPvGt2ML>Oan7^60-B#CG-}=J_@Rn^+!2f0@vbNrA zR)T8$?#|F(N(dQl51cyXv5d@-3RJFYun!dBlupPI5@3}e%ku<*0I~LejmJf5KA9}w z+qd(dAsl0bcXft3s)~xU>+XFs06#L9=8u^IL;>f-P_&1Sn7MaCS0!P>CD+uwZlN?J z+KhNYdtx8X>Mp%3#CDl$RyTmjM)$nIqM3& zOvc0PrO=5JwJS3&)w8RKE|CqZ39~9oL_|vyZ*E9iN_keO{6I zP`4oU7^jpA(2s=+-sv&;g18Y;Ee!#mpk^Z@Oav-OEMouQr`yj;g_{pl#4Ga~3xM}!rkEpf&rLW9&U73*n^H_l+ zi?-X6CXJrl)KDbzyXXhU3@OgehFHCVZs zh-QxLy2ds|hH9d2#|dNQpEyN2H$+erao4KPCxziLqHl2!Y~#+-ohyeY)V*a*lrCW% zKyNE56PVgIQ{)Q>;R4G)Mr6ixKFMCo;{f#!7cF&t32AOJRTL|=GK@?N#xwP{BC>~R zr#inB<%F>=MkJy#)T=@SImeZ1i#u2$ILiL!Y6f$c=0=E(J#MI8ae{0^BL+A6n#Z{b za=Onc+mHTMct1Nz897I7FD!9pvTyiH!20)|oH9*%k|UXN__4*fPN}R&+ZIq``iOcT z9-UY}(yZud091v&KLUScgTQjE*41fkZ1$6(4mdjPRV&k&Ji2cP)57WbFHb@Fihpc) z`%IAm=bD?^_5gH&0pt}@vWF5^ps8|Zk36!dP(9G}tG)Oj{eV)WUQYP&Z9q7xup@@4 zQpcZh3Y{TJE}Z4U2;Ay2H|Xm3+u(54+vM=(pdi;9nuMwgM+txnReRwV-L%&+h4tSq zJzb?uRVwU3?Pb16_a;f#0P=H}#)+T_iR*icQX6I_6FV&gMAd;F?AEFg^?Sr1_N9sP z*gDxh5KSS$!Z1OK9wr1{ZccNd_g?Mx68z_9F6!2Q?AAuoAXtKv8|Av4qLod#(v}rJ zx>g#nBIh@H1Q#>mLkJ<|d*f!>rca#D<&@ce+mUv^v)l_VM1aae>v7l}^s+>&YhSR2 z{@Qm0T2^z?S|6Qd{BV1?L0?!q&NJJxya^pD*A^WFFZNoNdrfF4ueJUYW6ipb13VMK z@i2SMZI)s=2jh|l6x+E8KCfyzs*%#}(i~B%NpNNl*C{K6?A2s(*_-VC(wN(`PzPFs z|6&h7fzwCL7K$Q7OfuPYU|``)7p6nIcr&7d>$ydcSxGasgpm0xmiY-YMH%gorSXnc z_ELSsiw6+V)k8HzbCDy@9+Peyi_6a)ogXH;fHDwzMqDtNfZqVmW)s&tV&#y^V87Fc3x@7P<#6~SqPZF} z4@|5O7SM~iJhQ_~v``S4;Va||^eOXKY+je$0C;-VPRsAwYE&FB7BNrnqENGifL5}z z#b~}$jFdPi4q~ymQ0XOrb?4dlkdDyqun0%mJWuAGQk+4)+wi^;pI!K?we24e>{pf; za1NFfjc`wfkJlVYi4cu4`qqjiJ^IsXr-eBEPEmW z(=#2FN+F_7}P~Ad8r%!WPQ_E1<+WBhP-;7@QdoLg8KFq z?bxlh9+~I)j{NCGNW-UjU~ybn$%|F)mfZyT)_g~9M8O!aqLfS$&5Tnq6+gnr;;@U= z{E%AY?UF!2nx>S5wd_ZeAGMP;DVAfZ6>&WNj*9rPmqR>@iuFi3~t-jnFj>`*hTnP>*l}X z!1Z6kgW^vAC}Wws7)zPk80$Oyr}>t!i?NNo_&l#*ZmhRpF9rl82nf;-lVHAyw;88x1WLc@ z-|i+^@4b&FRvGK>AJ;=<0fy|jgGHd2^8x!AB1h;b0^tV_(Fo8Y_9T$@p(>4c(>FAb zZC0Hwl3t;J+WTj?E?10W*0(5{DFjFrYHnwckeAVd>!aKCZxE)D|HL_l3!gEEZ%{^J zCYwWEVMq!n9B~b2;f0Rpwm0pgkf(fTLd9toS$iZvRV%DY>l_9TUP2q%TPN@#-Vg77 zt9GXKDuY_DjY0+|QzfBN3^MO-?OUQ$Hkf8%H9FiyAARK?Ax|*$Kg6vY4RBPeZFP`p zU8O0n{J$4*txxuEdG;$31S<){%XufYmtOOo2C?(BhA`;z@c20?7R8} z=w4runZbOR28DI{Sn@y}4WkuB=)c6KVPuw&hfRvk(2Y#nAyw|4?9nARVUIk$Qz$jnuj@hX8b{5;2sO{CxhcY~O>;Xa`6~QEz_+-i zo$P5Q0$57EL%LmN9tV9djUS=@q-YH577_C?E14GFxKqiH;=CW-ATCV_K_zXWtW>IO zQJLgXByp_1Ys~sAxns1SA`PK*8U8hPj}YNCwIpW-jF*^PD=bs#(Fl(LJyZ&mAi;m+ z=d$$g>B4G^V;56k8?l0HcgPn@ES!AAxkbBMW$$+ME*H(qjyi58UdDLjvD6=0uJqEZ<1{r2H zh?AFX9*hS$JeT+(a2K3H_1ZZ>I7?Y1E_%g$tB3vCCrAsh!j8>mSGV@}g#6B7tDfF1 zu)HjE+ICl{j=c0Yeqms@inus^{XCHaHoaShdeyLoGt^k#13f&rW3{?aFlcOKL@;4T z^0*ZCD?NswIHV_%3ex9@<^kGSQY3SZ=?0aRVJg4C&o%}n!Igw>rp1Xh*9}IS4r_~? ze+M)*c+5fwA-CtIl~&=~1k9LX~K#slkWawJ<>i#L*3q}c=Zh7RvNhOHU@ zxdSP6(l)LTj-=c#Ju+dDU&XR4=Pjr!#ZL<@q$~(io9|Q8Y}4;o3RqUQ8aJRCRT!_I zA9vTVmSncqn#YKTwq^uRDl9fIgEBOCRA|I9+WM8P-B9H&P0-2IR20Vk3aN0bHh-tq z#viFoGHH^4I@W{v(hoDE@x_EN(e&n&-^jB#P-_`gtAe6}A)LIIZ+`eNLrk@ZwO-T0 z-qGUzt9O3vMWCWFNLfQOy?=w)sJMY4KYk~8>4uc%&p9Ry{Lz_ONoAKme{mMm0&y#) zN|GMBPG)dZuu{BZ1?xBw9Z@x`J&9O_vnR!*%A%3h0ZSSR$|`4}aEn@snc=K`p`na5 zJ-2{uX~FdPimsElgg7NOp#ud`GAG2idhhgS=7LA}^sD8K*bCzb)!e2$ z_Bg9UteVa>HO!hn~Es(RC7ZV6AZVh zq3N5BsDk`gcAc7A0v!awBAp>gP@URaNFggFLW3RUAHG2f%Teywkk{-4@?_yJx9nV> zpk?UYUd)%qsCwXH?96#{-PG`bV7L6A6#BG6*7-g3Cqbd!x&QQ81BX>K8nn?H+ zy>2%ScuUEHBNDB#*{nT&)HDB5i_pcwcy7CWNm=wsL|X}B_CpXaqepF&rI@J{>Qa+v1(Jz@m8yKh11f-57M(uIAYSQN0w?! z3rjQewn)3)Qf|pCjUT3cU zu%hD-;6X%r+^LuS>!?ri4+VARQx^ysbnRjRGP6;Px%%haw5pj-_G z3B^iO#@G`-x+efd4lP(NJO_P~)Om1-D90`UR9_#1X&L4ggJ=V$393k9X|$Gz&}6un zetm@%?SyEQ4IH8ly&EWxaU32)AbC0=;~=3>%d&9wBE*%CS^|`^T=v>$4XOL0xXBC@ z20v{KM-nRVW*DcMUw{c71{3LP08ide{VU|OVfQZA_LuAXZj8%I$$5RVmXF@KwVE0Z z)1Z;wy34`yoW*qz+X|pMx{IkI%z|h1+nAjW*BiUFbz`}$%bsR*^CWwbp?~Ng$p?S8 zp@G>51?(HCSV-%A5avF7dH=M^)^GL8s+>|Dj_8vyJC$a79A_s8ZvGslyC7`cb!=3T zqhRI|f#5@vk+^rDad*yB1khOXN$3JGx{<*t|m9sd!wn7h*R>*N$T@CH#B?gf!KLVW;7wMh#4S>3Q53j1e`CyfD8!Hn`|3 zsgC!XZsSQ9RwMz50rlZJEbs=(V0@_Zn@@yS{a`lhIbA zMJ8p|2QLlfoh|M%!#ldi1$>En4^pfRb?c3oduK}L%X6TgvVxqwRudWb+dkJ`=Ptm# z@0)v0PlxT`IDu-8mhmhl+>Sy>b*Dz)GhaZTG+Yp5k7;Dz41<_RG4BH^gwkHmF1KE8 zHdd|79}%sZUTG)RAj6^U-B|P&HDzKBC6e>2RjVN$?ZYRwdu9xX_FAQZGZQPG{ee)=VK-i)ZX7h9Lh`wCI?GzgXq@XuO>Wrb089pPo60({{mlpxS!7tk1$U)&4f`a?+^l~z{hey!R zwx%9rvd}TbsTf3dVB#CQw_@}OK~Zt=9UKJ#1%KMJ9`s7sm;|V#e@y zwv@bRm(N^?H!D$U;|ZVFAW0=S9Si_Z;^>!C7s;hb&vWOjZ-vV8httwoxYKhlqLOT_ z8zXJmfg%617Z-m)rnIz0sFeQm#lS9%L|e(mX+uZoX#`I%YYofT&P~+YIdk@Hxz7Gv z3LVJ7L`Raajk$|l47{fG7&RuV810vhK$qu}mQ@IuM+-INtBS$8M&?(^T4oABAd9x2 zFg3^i@)DY~KcO;h_cT-Ab+K=-l8YhTawbuDn_O%jSbKsn?D%tXkXN#3so&{+?ydk-kHjB4c#%DW$bJeR+3?%; z84RE4uzjtCIw5R?5>X837EnujAPjrP_?0lED^W<8Jq4^@4z8F-H|)!o(D&{DT_Jn+ z)s}#8JL050if}t##O0aQmS~mSz%zSpZGX%YiVd-hnm88+U)V0e_S!U@Vd)2q=kDIh z2f%TkQ0j;66_K1>mcbb7F#s!7P{R}lj4K6-+0uz4AD%0fsX^{B;g>jt7|$e^jbbOe zZunC;zgIMYN3cXX|C$6(1Nq)8%JkU9i{7j$updee4cRK64BfAHwqoqm|f^c z!4Hj3$mg7$=8w6jHj^D{YTWMm;9cv=U&9TzZlW2{+m^=;zBpU+7Pnn4@AKAJJJ@=Rx z7w$RXPOwpPU~*wPVg--*OlrJYV~@2;c_HQIO#>(vh$CfOoF^(^$-0&rsx97Z}UvDz9D6gymPB>!%op(Rk;&yTDiX$IQS^q?nh#@@$%XrP(~IJB3uoH@y=$W!REj z-ed`LdNVhSH)memRp!fVd%We@LT+BRM_k=r7U90aD5hMyw=F-@Y?_un7>*awQ0A~` z;(N?c6opj8H7sMuZmK|E)~n3;SW-VzKa?!Wgj7mDq&g#V>suERs{E*sT^1Er^glE_ za&a4ehG#cM&pR#+bA4fAHzL2aV&|e>2zbom2-2=1x^boX=*t$WUZOvwb7ySTl%F)a zMEaO6&#${cV%K-`cQ;oTyIxK{@Sxll=yT_g6Vih-t4)wjMxafSj!3Tznyt(JW zxx_2ypKvraL`UL*^$9AJN;_-6s27sg6xty-zd@3_L#Fn^!yYc-y5HReh%0Vo1I}-+y`a zWWTra#`Yw30($FI-|C`rCSkeLu!D&lWYgV)X0ozM!T5}X%h@?*OtOU@l1NjR^duf5yB0B~G}Umc2~qVXR&?JY9JA;uBsjVDRu8+=M(zc; z&KTqBswDvTh@n)hNiXH!ib=Zl3KW(z^GFit8YUoP2n?TWRtFZGj5WB+Lg}^JYUfSJ zM!ARK>0{LbCafrFPxd+gok?EGwI0ZbHMTY;4{`mOZTN=K%8=}{GQVr2<+VOsu1@;p z?N{odbh|$1<=NGaI`;(E#fy6Xrez5Bf}%a)dJWw)<$CJmW>^16o}M~aJO4&oRgp$# z*ZqjIUB|eqY|F&$wd|1P;ZurxfT_Ab6Q;YGX^Sa8+UdrKxP1rhL*_WjnEC?iA2Tpy z^!(TF94{;D#>Fsn=MeyOpdHuySKwFluQyW|JAITE zYDlfiU$6$T`qQ_8nQj5AF}s^+By8S#$Uva9(p?6JJuqW^Rr?B#dfi8$lsQ{Cz2>sH zEwUpLbYOjB0u4EIy29Q`vYh%|ESYq=#qF;cyGQ3vz2}%}=wK`;AY(0vN9PP$R{)F| ziai~cLV7Wia-`<`)@G!c&s5Z0={fq7Fw$O>@C!D>v4Uu=2CO1cTQLa7v$4OeaYcBi zH167UVL4SizztPy=D&CnOZlbCl|w8V!RS@Lac<^FnM4~}Ui-c)6jW=7Q~I>yQ+?GsT>o{kC5E2RkW=r8QAz0 z&}baj@?@StD(3((<3T!W!z3;N9R{$Ku z=teIy$|k-y-&ik45O+ZJ_0xyQwF-bff)7Pd9L3o6w?hUGRcr1I`@>!K|LM{+a+FCm z#8Uk1_|UQ2|NVseD1Y>s(caC{=3^6o=}IU5^*5hx0G*2bOJ3sZ^FMgV(Xo77PCuNA zFXDey;S>2cDt!OT&PUKp-^TQRoB3#4&dZ_sOqtJHZEiSaY|B(Ks6|jgRSUt_3TG+> zk$3V=8hDDt6Bds)`4a0ucie!z6bz7F8^ncO^zm&yyLV?l6TaTwue$=YyRC=-Jqv8W z&i=mT%X^$SYI3WZS-FZvO80h+C98n3&hDVBx8LJUx0je+n;9g*Mz^JGcVUSr%_8r> z;@}ONFh!J2AahYax>HX~Gk9Z@7&Y`_65~l@pngJ3=wc3PCjBfOC1uHpyqG|l;#CGW z3AzpH+k499Vu*4bK2Y_9(7%{t7&oUD+w0;yx)Jxm(-Zgd7RLwK?6$X4a@M0T2ipXE zeo#Q4-Y21M4KEX@NDzc;=53i99;MX0Y;~Uf;0!q$p(5my+#USJ5!`hUMlF00xgHJ? zpLosD8hDfCaLRq1b(j7El(vu&N1qEXL3Ws%qI41ci?N1}j3?Ve;dzaE= z-&8*624RzXd81T7QZ@uAhdJ^RP@h1^3(jE3E6#Ap~(}&I?uCKlpD0YA8IXA zpROUoa9@|%cV3m*7yKNE%?AX{_QgluLe)l%iQeHJPLQws#uZ2N;-rO=R*_C)Akzj6Ffccj$_u7G3V z6olheR-U!8-nHM?a=N`=fb}pjAzS>JVOcX$`>A1@xi|FHX#Oe-kj|lu9nki{0C|qp zxar;Xg>4WEq&Q6Zem53PPj}Hx@XEJ3v_m~ks`SmU(GADzmlivqC#{OD`J%03AfK?b+wPN(G{-}<~h1O5h|J*R^Bi@`G^5x zxX=!b>z4XpKb5m&NAcK>9+x`0V(r_Pgp(*{%8AnKj2qTA9OYBo3f(hXiHYgsPX+Fm znSm~_gM-@lv1{QCg++Iv@d@tkF@Kn5`EG1``*oSp$xFIrL+s`U`YG8^4eUZ)av6_8<~Xe>3r1jh5b*E z^zl*ERQ?1B{J#tmfqx@N1kG%%j2$iA|8M`a|3vBj3o}rWwo+0?`nu|PKAP-!%|pUz zQuzA2=On>7g#@;Kw+)yHp*+qjeCzDi1T^n%WC9_qN)kmsa55D{Lqx?yPlGp$V)YSb zUqDZzRRZbkj}aL_b7QMtvE9jt#DoDsbJcmgbb#DzI4yBnI0gZB2 zOD|@g5QJkSW!0po7m;bjY@ZVZP>27p=d)^^u<3&6jY2T@0LVqgkHb*gKOlqH4*U_6 zg<7d6E*EII}>;W<~m-BM!b=O(v2pX*XKP z|3!v;mhl34<1P*nJ!M_A)1fQ=Ieb#N#l~N(YvUN%^&mp903_r^qr$k`Pd@qm*SjI> zz_qKp39IU@#3nUs0Ttezl{%nqUP=~JvTbC1E*?xhG(<&*_yBxUtvaq}yCV7Fu!;Lc zIs-OV9N1xNqkwJWb&_|JYtwKRKSMaTj(&n4^MOj8@KM1;Z1b?q85fBdIe10NLz^%I zQ9CiMx1sAe4f%}wI9ta!jBP`rWAg#AyX_AU`P4r}PZ|l*BJJYYmkPT+utoRezo7Y^ z)3sTf>8bRKh~X8!S*@snTlYxE#_fKQI*bi&2#|{^wq=%@C0SxB%n~@hDJGQ-ZKz-c zH<+-U{{UEJ5`rx0^f_90JTgpBzr~Fz(%6iZo~Y*Nn@icB1HDP8mmG!|2aRh25z=V` z{MJ@X)n8@Xz(v^}Pkyi7H=#oH;7O_t>DP87{J05my!x%uiQ16?b(zKxD8swyWdVj+ zvcj9*MYW^iG;&wvY}}r6L=jgw#UyB_xN9Zrox)>Hc|2{+63c-^m7;y&@dbXf+Ni3G z7B@dZa_1<8!!$K9pyX>~>9J$ZunH|MOt+EG%YosZ1dypF+r53mUc$|w=C+?pG9xa= zs%T#AHxdVrAY9JA%M^-IV=Y_+AhEboGCNgXGsTevGimtO8dS1wrB^9k-{K}lFy8)k ziAFf;%PW+_<>t%z%$CkN2VmzZ@q%>kO7VgC%XXgLlezikQihCSy;8%YQp&8!IaqvD za3yJ{&)BF;cjb9Z5s-_Y1+=xx4qx35BEok!BKPga*TL|)*)ru*CeBOLt0N@BzW`9Z zi>9&GAg#$8C2ZX!jwD!`svs*bcDer1A_YLL7EUR}}MqWWmmHJay`PPg2`odZ_VFRe^9t!zrEYKm~68wN(-pGI2} zv#Hl9vJ@Pnl*YGUnEO-Fu;Xr6)xF5Z0;tX;oELQ@4G>Y>9ad@pZR&NvHOf8w=mE} zt`%m5UmUp&Mq=5bpGBr1BfVECr7$vZjO}kBp^K1v^96V(*o9afK2fJ=qHEaAR|~&Q zW~P9VZUIl&39}8?cm*HbT3-l9o_^SkVG!Lc4OImSz7?Fl6*Bxo7}--OyB!-$SSwkC z2N%uJt~fm|X;2g@TlU`Dc!Q@j)xaOKK2HO99=M3xFtq?$HXXQeJMj&FN(1&H;d<~; zPGO+oK?C&nAOf1ba8=#gAl`vwy(j9(0&#J9E*Y4ONtC_>uTyacvPgI*3LW(ozhR{B zj}-}&;+F9ooeSb+l^br-+dq5h{xKFK{97&ISiQ&$G6b5bBo1KKf-flN$PRGVw;AaQ zUS9w}5VU^vZ1VktK-CT@3RvYtuEL&C?UZQMo@C~cB{@`0qb~kTD$8dJ7H1<8NMV#1 zIsKWx7qVVGM-i}>lPbg()w8GqwV7j~8jaH)hBZm?r@jhyyeleFRG3Y&({O)$JtWMb zm&y=2WYnvM38EhpkLsM5=*gZPgtT{P|5>rhL>@*3et0DzQ2#vx{-4ZZ{(ob|`VS_i zl=A<3!Rl1Cv`bt>_u0BQT=!}x!z&j-;G>N7q~r73fD?>e{1d@X0h}aVM}%wRvadrR zM_HnF2GYAk*%Y3;SBYFnG%%s&<6M+wUzFvtcG|EnwSJn2dztf9&ufw6*k#-O$I@l? z)W~7#b;{lL*gNN$`}*swJI4of2gS?6fTxZGMXx2bJY=Cp61sh{X1K={ska}r3v+;Q z#ZoUP3=fC-CN<0)jpdf@3A05Jn+JY?%1ag+49ZJ)QZ}9LCK2PQZ1*=a7xn-nTS>4f z@;yEf^Vxol|FP7>AZ)-3ezs~k>cUfm#QP8CNN+dLQ~qlkh7#o(apGL8=Pj2ZjqGc?(dcymfaVno*UxsyQ4>BUx0vf}5aYC<;DbYVsIX_AFo zyAH-liE2rbwhcYEF-o)_7;qHXsy(u2)Wkaa(ImdKC_JE~lq$(9^p+HBAb&19ugOTO zhR)W=-2=H33PF)uFyQWk{`Bz)Yl08-8S|6}YOgCq;nZQ<^+U0t?q zGt0JZ+eVjd+qP}nRb95-Wqma>_kQQxiF0pEMrK4t#{QFgzgX{j)>=;`u!>2Gp13}t z6%)+6*pEJc+rLfi^<+EAq{<@^E;I@QG!~_*0|qSAh}1m_Wxq$#*;rVQOuH|Wm&G5P zyk}&NgcW`M%*=UTWtg~pdo#CIF(td=NzfXaR48Ee8IntPM+g!N2m>t^1LZ=530&-) zM)L*kIRceeiOIV*p!Ii}5OhZ5A3;-4@Foyfs+v#Am{qe>(oMU7tFeuruqquD*HS%; zt;uB=_thXqZcQL;cP|lScCrw*hPbRw@4~eqt|_92+;m~_(4WO2_=e^Xc$Eh1GnE|p zkf^67f*vZ=Q%Ol8<6r9hbAoOlWy)gW5Jc=X+FT?282}3_W?mo*GosjtzD2Rf%v$Qz zC(U8vYRbJ>lgsf*lS6^O`WUaMVuTV)?#x!nuKZdZR)Z++I zH_?hIBnhj`WsMXP<<)W9q`pb$1SlAjeGE%-nQqWSG^py<(rTw>vV`z*y_dI2eaVMo z9L1D*ZtHn(Yv--0o#l5TQ=;@9k`ta zCY7#1R+8T1bOR}U?#JwUEMKNp0?yOUe(qY?rF`>qMeiON4KeqyNd@HPm7Jim#t#&3 zRF*P*su+*izrTpGJ!W&wc1#=OplTBH)Q)y2(;_U5a3u~zsP|uxG?9`EAZMx88JiSX zQBRZVhYM84ap}_AvX3vQMI$EE4;_}{7rLdXo>cZ!qQ@U0Oof@M?vS5jdT+A*R_^^R zt95b4y{t7xNu8uDc}+#jP?B%gtx`~|$xQt;p(!h-d(ila#IVT##2cwoD0Yc9}DQrrf*DM`pLDsToO37syV z#=>eovx&@9K^~$$YiByT`XI12%8!!sKF=lJ50s$eBlS%XhwY>hr}b1;d;$b~N`#|Q z+}{#wRqcD?iw@0MzqR1a9N0X#MZ_0W{1diMZ{3`?OLg|>nv1BCo!RnQo(gXaeg>aw zKHL6C9yQ?zWyK*D4BBUQ0n`FPi-vL3!w%}fF6zGZ zHr~YkFwk1wfVbi3j%s8c!e8W8CSlCeu85aJpW_bO(;Vf(RzP-#Kvug{!@w}bTiS6E zncsR<@qR%2o96iRfz-;1A~?&GOf-QkT5RQICA#j&2rLkJRnn( zvVj}s4aw7B8W6Q?11|8|_U{2I8tkJIU$*!QKd3lPNuA)UO9Gnv={6z8S%WWhfX;n3 z$k!pOd6~svsEomv9lJGM_ITZYFof*`Fb3~4W9+U=3vaRuZ=uI_9LJEf2A*S#)WsC` zQg~=fRdN@9E&wLGgIco_}I&8Tob7}Kx?p-H9oInB3iJwKpH_s{GudF5lKZ2|Q zvj@7@`SjG$|k_A0Gn4i7Z!r42F54+T$71%I!U*8>?KGT%N%qPw8stv&x zF)Dnx7laZsf(O=QwQw|u#J{%eGYpdjB?lZmq5i8>pQ-$z^XT{eY+w=`GnTgCL}K1q zPxqkR&x)##3{rVFWff4fup@XgpM?bk81N?Lq21h9RTX>snFh+zDup`{=2XS~R4#dj zW9c8SEWA6hU4etVzhC4hlSbAtOMlI*l}`-1MEC5I3`GcPk6UsUGPIB!d+1*s<2RvbpGWNbH*h!)Xf>|)8_BdA~R_YZ}9m z%Ecsm2u5(aYK>c7Ygs+nG61&KU!PVSX^*OQ#&WY=FOI5~#xhH=7LTwLho`A)T5dOA zpXlO!?Y9~C5qwjoYLY0iZumWoUXdxFY6>UWU>dVm?3@i|yUO*3Zn6~ER*E~&(z$v~ za`&mO&h$HjESFUjtKUUNWVInm;g7k}I696!rZnT#qb(cL#(0-b(UyH~PJu(l4rY31 zKs0TC6pSig)>+zOPnAQpxuUgQnTMN&uA?5O+7zzcYm4^cNI6(TeR=w0i~y;Jbcg%B zWrv0}WlIe+qU);!a)6AkIpOZ#B+~fy8l?&XZZRC>%j{FN)CRI4{4x$fhzhv2Q16Ec zn2NFHU1L3uoqr0Xt7}?1G`=lzJXrr7$o@M&NBtiFSw(kiYbp7Ekt|E9ns(Srh&%;d z^OY_m^(2yYXd}r|VzDF>mM?%%D=8H5LBe|CMiBrZ0mh|{IFX6#;6-I^B=8`d9{y1h z$opu3sb4ArS6@7|>LJkq75wL2TFwDmQa;jM5+%u|tIED`C9Y&r`Q*sfWp>-9_toi@ z=k>e()#f&k+0Y?Gvq2#etk_+wfwBmFI0Mc;qFQQbE)Wr-hpR0J>pZuSnzLJKC=c?O?HoMhaCT>=%nquq{5T+`FQ=<8EAAwlY=w1V6oqCYi z$dhm&Q@>?vOnv%Gl6pl=oedSRNV=Y56M(nAU!$5NQm{{6#)`@2M9zKZ8 zW{wfl6Wf*AMkXDFG}~$3TmVNlW9#{eO|j#)LoJB?jq@ zbggdxN|Pl6kap0vE|DhHsPOyA3rWi8yFwfqd`Tk0olh|DOiV$hY~svaw*ST{bLu8B zvcQ==cUu{}t($NF=b9{L`;xj}DAH;&TqQ3%z*jS7TxHC>!=LadNh})>nPty^fj08xBdT zZGC9@pg2BzbpdiFtuTsZ_h6&2b81hJ?QCSd?+Fyx^Cr_@d(~QxOhf&{KN=7788LeW zK^Km{<2-#qRkdm#6u88GxECSVIg`Z>j*s;Q`F*i><|f}i<)%Jb6{a(M1?C;QW{yH0 ziUa1_8Q8Y=A>%nH`0=ok>##Jfp=&6N(JuS8J4mJp50C*NPU;V%~Mmi_}0 zJQKFZFEkb}edAshCu+93?Idxsg!<==gtC0O)Arp1=uD*Zs18Q1t5u42S80m9Q`&v# zD*r~wfvE_QRd-q+}EtiA@h8weJ(o& z++@&s>vbGeCf&gRvx}pMv#WTzRx9WIdDalI&IFKlA*?fx?Q=IRSj;m_=x&l%5z^A^ z!~yLh+YzVhW6yfSk=X1`LxX9&BnSxYxcw>T;#PeDz%DVe{9=L zG?0uN|32|PfFsvf^2Bx4f|2V=+BdDbPDRgCle1cjfX*qamct-d!>W*;N^E@_+4x+g z?|3)TzQPZam*ox}93}q*IQsAns|L5@Gg(402|lPud(`X~zlnewElV6qY1#{K&&$MB zpX*fR%Wul@%nNI_W*t`N*f#u;pGXQR%4lYUa!Bz-GuOU_JJ97@^xA>i zWO$1D($y(DN}RKU)vnZr@DHQ)xtV@rst40`T(r+h0nV1MYFvg?ndee*jMQ1m75Q9x zPH>f3E?(|F=Z4=*z_jK3xE;}H6zD7Kd1Tr^fwYwObd-WW1Bc~sF-3`u^tH`^*cR?deWESA zAg%r4ANBd#jKc(zD8d4uQSXvtf~>NG)CdolgSaIK@N#2EenGnbXrV=_$J7<^0U1KP-#3!_D~W3nMClM>e*0@PQLl5Y}2Zpg^4 z$P0VH@~{W${LRC2B{u_hH!FeANc}uV6IeiH?vk;hrUSZ)0lAU|xtf9606+m~f$ScB zw!Z$*^2WuMgcPQe3<F% zkoE~5XwVu0z7+%lE4h|&pix#oszPgd>En_8RKcqU?vlO05XM?PeHm&bxk{aT!Lyr; zFmT{%xP^UJzoXxKLdcJqf^AfF7)ENfN`?tOxc%_{~0*5 zEIhMU?KQgxx70cHt~bG$w>0U&H~qDxWsl7zzK*gSLCK}!DZ#RsFJ=9LRtzO;1 zjOPmW7Ov`{AurKl2VD6l&AVs^o}ktUu)U(dH*>kL`I3zQjP9!U z^yf?q#wb6Q9S@;T_P7eBpP722QR?_-T z4(4vejQ>J3S&Ejji~J}&4V#;^l4#3h-Kg4jE#yJQpvaM7`XuqxX0x$3_RUf*5!T=( zG|x4WVM6=hzJ7e;Zly(Ae`>aQeSgx&gbz-OVN?=FpsS_iWx@p%GK|cginH82<35G--y5ThvELGA!=ZK3hk~kZCHTZsUX^70 z4msym?prr5_eB{5yr$}xxnurb{v~KHd<7AFi)(CcB(Gbl+KH!dU?uy?y|G6*d(N%4 z_#2~lr*f!Hj*37Q2@p4=_}8}4JWwItA&D`Pd1ca=nZlhv(<-X((KuC@p^B2!UJ-Y8 zm2iteZ*fpX3QAt?8JzYKT%5nrIRDZ@Mlwy}%Pl7a1J+0$wkv~%GwMt-?Yj*%n8$qB z_QUkmowtk%Pt=DTDS%rI?Nsh+)r?Dxe*l150Eg{_twe9I?;jvcJ-3@Zj2YZ+a~#Bt z>o)V&(O+Vo{59m%e2rMOT`Qb$CV4blPX@GSt5?Lsk5ma=`>1R2Wqhe7;Xf_PHqW`E*X`mna4 zCo)YYQ+jHg)QamrM)sf-A%(-Ym1^q$Y5V_A0^j~e-{QZ9_LPdXBDOGs&k?&?J+&){ zRDPJ*4GG6p5D5YhBmzn7$>}BlUyqzcd4SQ`YGa+m)6?ztknRNS<3e|q5|l~_gYT_? z+SBAInh2@CXq=L7!)iwAX+hR?=I@5CFW(DrFY3k$gP%RDs`DVdJ=8~Qu_2NoXZ3zC zb}`H3$;ohKbcUPkz#FFreTBY^C>`m+9!*x|QBh;=ZgVgfj7CsLC$(4b-0$NQ>F%j2 z8hs6&qP;fdhW>ym`-Weu(P{93Gr;SP5qU$*f-8}ifBK|@-6;7wMRMG273qngo2ew4 z#)EIJZ(&1JUZJyxvRJOx9dK!e186$N>0i8h;CAhLcHKo$7QKcXT@v56plaCE5s@aC zB1`_j3L>r8uF%v~=`nlpBgWP}3?V(a3&-;6`})Gz2sx_Tkr}nN(s;Xl{tdHQ4qU3P zKA2=5SV|!fF2;gcb9rYNJS%_!Hb&&m;0vx>w0jdRX`rkaz1j55UNIcSK_#!Se2(26 z`>NQw9MUU2INBr$(M&Y-9;$drZZ(|Hbp0G%XTFQQwgWZ=sG1da8Awz(g6Z^Oz~W&% zql3Z<1Cvl=s`V2NM4{Q!xnGSJU_J>G#Z0Y}*IiqvvDOmCndC$eWBxk&t&M1-Jl{~! zXll*UhdznMkaq9=`HY_gcBQ}6OD+X$`5dUfSEPX|m?KqlYS&^#Yr{=!6#tCLB>u;DV z^ejs_@DK(+ktR*QTTLj8lWOrBRy9`<%FH&~aq@tt?uuD`4dQWn4}PX= zL?5tZCY=Qs2BS2b2*MqkyRb6%gLcA^nNc5>DI29k6?c= z=-5g<*`1l2ptWaKRAoO5JHZbxSdm-KsTfkWz^RqwiJDU(o(qo-+rzoqr(JEMtJp(7 znY-fT>@%TG4aMSY^>t9DgSQH`ONmp&8&Fo;%wy))g}4NdiK<~M8l#}h)P#O*6wVg? zVngjjq!b!6P%5@cOcfQ9Cv}q}HOA{=R0=1NA185%lQOMu)BcO&7rgWwK3r2azAZQ0 zqYO7sAl85xK#5dbC>idHr%WrV5E3p#_CX(yC_EB*;)OXUezYhayCsW9m|Ic*#V^6v z%r3)KNrO=Y!G-u*E@i6p-6DPA341veGzCeK0hb2#lE0s)?28Z7@) z>@?+7=^kAtOgg0)Z0xoGW4Rlgxx8eK6mCuOyklywIj+%IqlY z2=l3({nzt6SQ3z&$v`eXF`tE@=%}4_L{{M`%On1Q=;BMFei_^$HbP%%)wdXW2@PMV z0IAhIU8})^^KL}tG2DKvkwQ1 zuJifzX`cJXe$Hur83FD49$2>NjQEpFPq_4roj8KoPGu8$g0VG9O9R+s9PCvA5I9hr zb45GcwB)U!ycka?lesazTJrQ0L*A2PZn=86;u!E4q?niH!3Z(@EG$$Nv_)*C&gdeT zBQ!TC@zH9pVWzqO|gP z?_m;fL$)FdkkdRRt51_n-PXZ%mh9@Mv5;!G2u=z{K0vf1@rf;f&Ol$4?W!V%P3B8w z&6+~GvlmighV_i#6^PrRb%~pyzoO~ch3k=h;_<|N1gLnCAE70`V8I_q^KFA(DRk_hotnQRil`6@YFvVV&oU1o?A$B ziyR!0@4L%MG!o-r+%BV8SpWWM3ensu?&>tby|+Ftg>{(_v0<(jWZH7OP$y%4Xjp>| zS|lJ7wJE7ozSu69(I-kIP{Ze+Lb=rh!VUOu{gc`^ko~Wz_wOK<;Xjyq|Ewtg3%&kp zgRfFO)mRrn>5}MWgp(9lpfO)y)sD?TX&~ljAjqSRQtUh28de0@NGHQ zg$;RA&Rt);ppeB;ITUaiXngdl zZ<^@?XWVmO65AgAg1H={km;=Ah=R=&356R(DV5<3ZzL~96Wk=~BV$+8>3{De`yi=1 zIR^)8PiMTYZgI86(XZn_$kA9|LDgLTvU@z)$F*n^C6+wBD1%!tIxmJx!frg-Jz7R3 z2+X8Rirv=3=<}>&{LY0@!zh!Ja!2hQ-LT0!ld80nCug9ZrJgCHdZe_ou-4_dGVR&h zZGxd%-BI}ZwW3XN-9C}-5ArHmYM9uA^pG;JP+zW?hT+>${O#;?VQ#3%7-Z5KQiPzp z7u*)~a3KSop{{Wa^RFSs&V(wHO#4jJ2j+rwkD<9-yRH!&b`kfyd7@d9f3jz*;J!>dzRYwli2 z3C}SNZq|d%SdDk&M`$I25w@ zdzAjKXy>ZC@n5j7uvq!kB@=vv*Hz3?n$`#fMk>x-`QhP6`87qkDb^JmoI|2m(H-&Q zb@$@&_c|?1`sZU zPWD>SJHm~y?W&j^aSLw=9Jo;5v34Sxbw=zzfel|jFcGd*)NKS8VIrtTQHha1;%>h=fx@D4putwk3&7Tow9K`YN3@_F>OIuTma zYXQ*{kjgYLfJgAjKH4{CLy*{qSs8*o1HKAopgU5}imWEQ8m`9!Fv7|fsm~^8MxJ;j z^>2dqM6C1{g4P%z>4{QC za7XlxQfK1p5~oWT+ukv~&+cl-LASfoJ7;_K{G|6D!u3l~S+lq4Tpt!Kfv}F$z=%Hu z<|LkXQ%96pODcR2dvn>(#*)7!DR(`5VJOFSDLDF#uIHaiWgmYM@#Hs3F+~0EOXZrS zz1a8a`2WB7zQ5Tzn9}Ln=^L6E(;3=YTie<=(pl>}nK98>{WHCV?!V6Y|D*2QIfe(S zpC2J;+ro#L(hbPcT5E7z1Cd%tPKd55rn+LF( z9*QA?AvwZwb|%`1tZS7CMMFq6OGD_INi*UJrK5fhtG7eFYf4!aZBp++Y3W9S>uVeB z=)s=@^9IY!cL{hTHT4w9c6k-@w6*g3;$+kp0}4rN6pj}*e!UH$(fBg%%o@u3I6r>y zsP>=R0Y7#y2`wxmab=%TAK~Kh{&8#!#YApt{QmnF-=F{cUc&Mp+@OC0asS#+l2k0M zG)*ylc;8k>Tx4lsd7=WknrB_uWfWGn(swJ-mOZQm*PWafB3Ul~ARiOE7`_#b$Sg1n z*1&*BA;0UVBZxt#;1kcb{sq(i0SF7`7kDTC&6j|Hg_KKRPa$YVHS_c`XihbojOWv{ z{?@f}{1WZ^`S^tPv+&jlB#RvrfD#kL!PN}rj-6tl7LKeCIT|oR^bC<5+mN6TDPb=W zzM#NOQI#3DSGm~WWEH9h1KP$^JrLbH7#J;%BmAwigFp{hD!;s<(rilCMuxz39Y?cL z?e*QNQjCs10s*qAHj;*VJ`kW&3(Dv5k;;9l-Ipn@G;fnZ&6F4_TUJ1=(DA}ord76{ zkUq4o@ER=dD2jlG4(yB=kj8pBy2#~k)p5Gin4^e+hIoa%qE?oC*aRvYw0L)lfiQc^ zwAakNq?Zjbp)_pfvWiM-Td-fHP&-7Npc!jwDO-vlG0FB3r5m~9$N*oEsZyfjP%cKP zBrgG4S4B0H0i&RNhrLrZzS_^$4@Q=%JyIZ$qfo|iA>_60K#tbrIGJ3uQpa1LT1PhS zzz@&^MGn{kmDd~4GEHV(?evyOW39Y%n%i>$R10kI&eLPIvkN7R%s5iIRZIVIb}`h< z_jKlYXxlRGC-@F!4$EwB8LJL=d`C3r#Sl*QoOt#)(Qa+8*ocbwi@|X<*$V3EE6!@W z$s@hyGTp9+A*R=XatyN(1AmgrC?_(+uM7q52`jbV>Hk&>2(io!ZugH`HQMoZ>+zpb zu!=LNK!G<1@ejEH05i4b8ZP$=a~to-U!b1ol9)6z*T>d*CyweITKl`C>6BY3lPQXh zOd|pfURnr>H3&n7r5tqFvWyWU?oA#^pmt~|*3ClfuJ?HhSQjgF?UQS{R#{Z}n`S|A zND2_fo~X=>eSEE4OLZy9T((#^d(g}SW8l}o!b!+#Nb`tm5UxlQ@m!;L5#1m+iaE5P zX|0#9yOJiVaBJdhxQ=rbv~5`AgwvRJOMs6~*?1u;eLQM>f^|L9Tnl;elnM;`aiB z8SKC0s~TJbSl?us?K9~+MD{7$Tjj&z@%&xrt~Be!kk3T4&ZU#)MS;!P>ww4$GNpSO zW)!Sar&-2h4)Bh+KRIIxIIYB8%J)#pp)_i0!~f{nLX&La{USk^zocBAro}HLUBjP1 z4-*b}F{^!eL9^?obD_k6l{qr}v-TN_aaPo~&}Bl-gkUozV(<}c?iAF97A4Z&UmSO} zZ)?GbmBv&UV@8Zwm_u<)t6U~l5EpFIoyUompQ%eRF5VB}mQFE^$Ujqikb|GiCw{;? z@XISa>Wvw0M;&JO9=%U>b-bqDTXz8Em)%d@l4T&?0Nb0t8E%N%{gT*pir1Xo1>syH z2F^(B>KY3iTcYen5M$+ROg93KDupQ_Yti&oc>OY4p$H1UTyB|(CAX|5C(6|Yri>!I zBEK+QDpbz?_Jp{yjK}N?W`dTzKsY?^9Ve z<(Dr2EkR)cp@F4pe>S^@c&ww1$5yVf_??_$X&1^_@1YH2J%#iqVQfOJWb3E6+f`NI zdU@oAQEN{h=etUf0W&QdEML2oT4%qAaO)Fg6uM-qyR7|w)E+BTg~dDJGHdyIva0ag zy>^nXjIzoE3`lZPJ5Xi4k<`#4@%`RCd83IlZNEusgqji=Jd+8#^i=IZC@-3cq)x<{ z&Q~I+g7KkDr+t9doGDfdl)LjOe0aaElK)bt4JKnl(p_X(%hwb2jOE4P`9&X|`Ujia zqpHgx?B1vC!OZrH)mMP;=9l<~=KI1O9WS5l9>sgchC6c3fbWfQr|?myGNUk{71s=vZlg*KiLjmeSLJ(YA=~(T@EPM%K(;pn!O+4qvevqFw;+`KC2N zcJi%5L0F3L#na85MMD*My4wr1wfHnjn%6nf^tc#q8aETL4Y0nc7OvZgQ!mk?UC19#s;X=njHD@$6u z-Y;-eMb>)C0G%VEsmYM^G`!xBuE~h0N%&p6d&^3y+6+Fwmp~~1*i4SDR^Mw9{UI`N z-3OdYYBmF28TlbX58E9UaSwAAzh@|BmJ{B~KQ+pxF9C)H-x*vqaQ__z{5zS${2!oz z|J^I(|2R~tS-N2>WBABEGLE@8nvWG*vubJpTh~)qCFt~Strv>Xn-iE*i9<84NhO%G zap}9THOe8@x`~1a(dhI-R1rdv6H`!F%ijV)guBM^jqlUl-rlz4Uvn^}Z5Gq4J>MA4 za5x@iUVHaUymWu}=jNKp0-B9v6KsWXO(6)330d_L;Pqh)l-*q*@B+(Os?`|aAxPY_ zfz3&vx=NZl7HoxonwSH2_zSwmO^(;Y4zAk|T>nxZ+*Qw4zMF?&af8}+R8jwuuJ!D^ z#!a0e%IrlHnCgW-#CAAY;IL#!fIaY?wF9-g?#3N>y%UDe9dR8b7ejVfUSf3L7P!J~n#WSBE`#3jI9Ms=(;X?z6p8;7K^HXjGS!g!W!rR+_1!cmFCWQlpXkbSHH zn22ig2kOC*UTd?lnUTaT%|d&_2zadaZ$o0-wticn8?UH9OU=4x%gL$muV@}9KqdgA=)#ovJ8;6=71ij`e^tJFa8)11Y*&W6T z^SZk1MOd{(ekRmfZ_X!^DW)|lwBHL<_VIS*9K2zgSZ1c_PuCUGzhDs( zS5fAww^?CnSLzGoGAEo*{PAF%*p;JAVhK@HDt0wd0d1dDu#Y>KDTZIrUZ%lVYtf*1 z{8MZFa7>K6jf>$qVM?ZgMW3j_$c~xx0}s{sr1f5Vm=|L>>Q0*CxVfm|k)SP=fBU#o2z zlu(lwH^&omU$w9=(GU!qQFji~nolDFas;z3a%_duv>po*?v&V(3Kd-%_Z`UD8MiIT z;?O*2xtiSA&X{ddESefvDldr`a+pc3BTn%pN;(GjN5o`SVoa(JQCif+qOy=ZJ~ft{#!_cu(` zw+i*9bHm)^nU>?knC&QT&753aiy(srQwL%{+Js^j6O%fcbS%zyp*>N9Be8G+XJ`H_FNUb9dzsY4j8~Q{vs>u#nQ(f zzSQ3c>j0@v4ZBr}WdCl-K|IFC6l$u}N>`v@xfKkw#2AlMoOGfhywpSY#B7!G2!Mt4W{3s2@ezZq(v6=$NTa>oLP&XwTm%OlQ z{@Nx9VvV*VH&ts{N*p(!gMD$yL$QPI%%r)S0~Mlzfc)PqCxKV> ziLQ5Lj+XBJ6e=UwEN#dP0`!`usKV34vs`;enG{4MD>F;Wlp&+jj_WRo86#u*2~9oS zVG2Oywekysb%VpWe|o#!#VVO#XBB;L7HA;{8{bOyG$t@uQ`N3@*M6outqnOhnGBe= z>s4g<&oXFeqGWy_&^r1&kR~xb(2=QkHF5y-(U`^PEzoowoc)yquQo8AD8Dc_CQeAG zsI0|I{(*VZ@rOh9wSN+XgDb~V&7opc1MqpRj!&3f<4-IKXXFu|#|+f|U(HDR2@$zN z8Sncyhr%I?e@Vl)wD48#2Q5}5`11mr+MS;2QUcHR_HWpv@eyjc!taV1KxX*4rpp>e zXNYiiIGeTK;Vwi_xKQT}M1w<=jtR%)v6}6l5-C-0pMGjx=5LR3v^fGAuk;gT^Bc)D z*rMwf5+ELCJsh*sO`07u`$Xu{mnVzMWQX!C9T0uo)Ry4^L8+rLB@=>c$LazWxkcJX9? z-52*!(%ph|gP5dv=yn7zYv+04xYD%$p;s1M&oG`<`x+;~KPUR?^r%y(v&RHP8$ z9X1-kKT>KI@n{yAS71RYq&H4PJ=c2TUhidU^(eJFdNWh9T>rI>6c&~5;$B8dC?8Jm zh<+|zU7xsrU5tmlVNB};a*ybSsF^FN*+c5Ab{nB+`t5EPVj%KDoAU$t&6!d)kYb;- zo@O_7#XUt(2TvZcnl!ft8-e0FkrVTwP)3?8Rd!}_ z^_M`IFO8TfOZJ$BUh8RPu(^jJ010Qu7NI!8)KLaER3nU;4mYb;0CZ*58N29q*naT{ z*)2-r#kJWM`3tXfn6D1u>n@T+nlniEe0Qb&*`W~+eB&lL%-Js*P0U@(;c7QhoHmX- zrE4l`40`^BZT%~Dnk!YdkyBoQpX_KZ%-zWVHw!&@T9E8=jzOC<&b*i)3s`$$JUunQ z4}yqzT%Lv!np}t*3Nc1tumHjTP(Jkzwg<4uudxdj&skZL&CV4sIx;NB5OmVuk01eU32Mu(cRZb3T9CO2CG(6CEC2Fpr>Dmj#TWojuwPDNh#S+S>daGLNfW4e588Cu5+Gg(TDVFRFb!_oN6$sjMTfu`Skj zQJAwymB5U}m!>_~^GWi{@cyJE%GPNcWm=AlC4+%(MtBjV$m*;fqCx1Ehd+~6$WE{8 zb}y53nfUxMb`RT5{m(T?T^#J9qPX)Y;uFGsa;X*^vsgX;I>smXNHChWFyOz(ru_s5 zFJI-)CA$Afuj<#gcI|xMA}z$Oc7wXMG3be;piz-3*QGoXl-) z{+FamVS*OqyK@SQ35;RqwyjEVQ1oi3Dj}};#3aPG|6M|MDACC^>db<)yZ5>_PVM;z zp58Uypuz@j;1mL@x9leG@kWN?!;Ob4ydK>C)QO-klsybFL+T)cpeTOhfsOnLKjl~N zmY&`^Ox5`~Jj|1HTt}W*CwKQvMahF2lU1 zmpaL;>Pm;v)C8Wa?;sGxq5A|0UUgOH9keOI3gJjp z^3qf}5oIu|R{j{8#tT_v$3qm#lYr{U<$Z z+k5hs<{neL&(w1|pTu*6qnfi5nUs7}KXK;S3Ly00Sbm}<;w%F*LLt?FU$4bw2_!1O zON*1Rt2d)G1}iK&mWu^YQh68{jfm-PrujHH{IJgX5nhCg(&QqoCB;|X!2jTncYebv zCx1Wvy>IE!|9u27{s*(@zvj>X7Sc7TuDLE6q4b>mtHNs943&vB>(6-{+l!jtex9))f0ag9pi-5<)^-}oyk>hnI?0ttF^JKzk z{+iYZc|4oF@zVU(aqil4-SPMOCE`adI;{u+9Nlm(7~JiR0*t^n%MlXRIXOVZu(PXt z);Tej1?t zgW?`juFp(|+Nmr{p*kes0-ZBFJQZuvn5RxX?oGUrpa~@@lAuDuP?|nR=|L?Lo4SMB zAA2wzoKeA_)65CNnqO@#mKjmlP7bHWe3RrcA}pWa7>U9XdyPFU;Pgsysi2Efjodvs zL?5O*3FKT`E#tS_#-O>Dw9j>-C+Zxz1$qZ;^_dRojj{(|(TT#Cizrhby3|vfTQ60> zfOVp;Sy-=++fZ+OA6 z)||>Dh64ecnuh#UlIkp}`1nVC8{TE}6kSmf;wSmzxTT@`(rRhh8etfm+Rxc|F_9(v z-yyc_JDwy3+DmunDeP0ib=&Q&%#8kjD2hxAQxcs8l^9F=g&a4184iR~xVzIyRK!U16NceNntzZ+W zhQNe7-nmkQhKNPn>3bS;zlvxRjA(k2R5Vg+i!|fwV&#wRer=#dfPkMzuR!MCMIlPG zClFH6Z4+U-Ur^;HVr$Vr$}E|+6FonqYX$t2{Y5acelCNWS|jN36oRbs zgEb+a`b7abA)b=f2aU3(ugVyKZ&3Bh5IzNv^QVgiizN>e6Y>aoKsupuJJrHO2bB)Izca%H#x)><0JYdbP|7mo@^SDNu$nCb9hTCnon7*~X|N>a z2IJ3r{Cuuzf)2?Grx%1X^bIb*p@Z8f`(=YVy$$Dze}*}MSQJOxoG#s^QQI^vX@Ej9 zEER^V7Ur8j*h8mDm`pgK4O=`lsv1vDzg3=j1)-mWBT#9OJY3m9R{w*EXJa#5ods!t z_5BYIpvC}j{0cTiX-Osm@kKKWDo7s&8s+J?1)Cv7=1jOKwiVoY-|SE(x|JN8>Arqg zwq>N!m9$^lvex23)4g>5sALOOp>xiDwz;p__5H*8UfGtCN>|qR6-zB19bOeJQ%rd! zb!V54S+narfRct>;BLTe^X^ZN2XQc`9NXEf?A#^l6MuUE(Ra7fCw=&9L6^&NyX9(2 zwZ(wyCaTLJUz!Qu)g-?CA-;e^zP<6B2d4>V>R$Qn?qqI&X?^a9SHPp&?`Z>o>@(O9 zbOq=*HqT1Ksps&Jw=uCqAaATSF%<%?=Hni^Sfl*y=Y_pztH1JD2m|cl$*-%UhBQI? zjE6N6cydsskQu1wORy;*>%Q$9^yE(qgJ}v>dQp2yeFe!8MrDR^j{&w<+Z6w3I;5wH z;mm!Q*X!zaP&_8wy0*BeDZKqblbBj+xSs(k{n)wj;hwl6||W_;@2}a-4SCA*$#X3QR-}5vcX7)r<@l z)8B+^KL~pji*-vMn41Mm&N2S_9+px*SJFgO{nW+C%$8SnE~Fkc?30 zS8YyErzYsttB=6Kb1JUyL# z`qV|Y{X7&gUDeJBaVpf$apBC;@dFP%?IHBLUx_@o?K)uDoVquuF(Y#0dGbI^|S zdeu2*T_;TwHqOn_)AjLkV~bYMLFLbUhM^o27|$AGK)fp}sGup}k3pOKI>Hs@b}hsy z1v{y@qXqxDx7=-c{j^=rPAh7bt$hQf(?Z!&X^zgmjXbRF?W06NDhD4EWkb+v)g0Bj_K)0^bx zo{KP>m8?==g+4YiCTFf?>R@89xfH|3+jc-vjALaWgt$kYzWbdlq3fqW;jXwOycVHu z*c8bK2~ZkQmmUgQisbOPgL#)(V)%WRuAz=Kyt@O`6Fa0ty+%vq0bgz5|W-%;wn zE9U-_43>YKQ@-7+#@~hy!~gN9Qlz*pgDj7tUDA^0ti<0dDGw0lDqw`r=`9azjE!t2 z$y*ik!XL1+3Yi2gVG8x}_uc7`9RGVUYmYGx7&x8^Hl>>f-z&LNt47@@ zz%Mx$E*g#{cZ2P72E=26R|uKxn2W9o#`OQ)4+?ug}_Q z;t?$v&O8EvNt7<_4WnD(X7kXtf79DCSr2e=c33)?`1v80UA*E>Pc%5}2sI|Hs9{Et zOp(2bDE%WotIQ+M_Krf*?Bq@Qx{t(gD3+dh!5n@8GF+(vwxwE{j@q6nmY#5*(?+b7 z;++O#6Fq4z8V)0?A6pPj@RRQ|TK}D&bsNZB$l|1V>O7cdcSSIyqpupSz;})ShFUX1 z#i(m1LNQzR#~&$G<90^fEUFYTQ`5iwUhcm)h=SL_=`P@D%r$ZTKg!-QND?($8|^N1 zm+dawwr$&8wry9IZQJUyZQHhOf3;`MxpQXjcTemakr|PZKUch3&w9X7RNVT#%07!v z9X`qW1zbQzT1C7Q_l5_{YZ@}|bT)(HV!$d9`~~;1>ZQ+djEDMs-CDaOCu>6%u%Q7| zWCKQj)Gv$D3%^23mAWHceL6JTLO>`c0K2>!-yRS^_>6ZCta<{eXMcUhzBAt}XuTIZ z!j3R6BU-x5ls~t@BwAVnXn35CM>KH9?*MQ^>H1jZhU$(8+r*ZVOXY3kQ$Y&GO!ei8 z7KaMOOd%JU(MUHcn(l#;mv{+&-NMC+ikM;QqiH_M<^YD**n;-GYtLb0v3C@<1}Q7| z#vsmSnr0sUjMaba0vpfAjij$#@cc!H`d6>^pHn`;ztO9GxhYyn>Dv5{mhHd(5wdcy zbNy$}UZA*aHTxxlLTt6&NhP$L1=6K}`!X~mv0ToC}7)nYGO~dhaB)ai}bkoVa@09BKXF zGNs1Q+jWsT`PyU3-krE=(|ca&((^u{utD?D*E$*v#oq8cpV<5paIzA)r41rHPXlt< z5Qv<#S&PN7qyr|QKPNNPu|}N0ypGi!Z7COJtZS{|qLFTgZlqBu6wzcn>WQhiZz|TG zJVHQnwL#Cx$$h^=3UnO3g3OoZEO3$&KLQQ$)a#>eCR(WQ>Q7}3HIp_G>4I3mf_|4| zb)>daO{GTtHf^=fw0ZcWW(Yl*Z`~&{+}EDeM3w0ez!7+{x_BGlo7U9-hi=)Iam}b0 zE09he6Os*i@{#1F66#>u2*Wl8snP2UIPPGrCP3z(D(3xh;M&@i5;#sPo{NvZB1%E3 z|D6`MLSh`isJ{Q1&?D4hKjQ#TL`#7MvS&A=fFyUEl0({yd9EIxGnHPZ2-`*ewOSPu zVY5Ag&2AZu_S}X1EAyk3W|E7RfZFpgQf0nRi$93M9hf5N?aiCO=9A;(VDfwN2uhAL z#fC(O^GS#I+59jL8k-AN%RE^&mW0-cl?a;Be%C9KAQs2AA9(|-eT!Dh^vbvm7_#{u zCSYU{uXeL;JqF>en}{p4?*dL@LJe1I+R|+(9eQyW*T)oLPMh=bj}@)LeX+0ewW7a& z`D^`uujs#%bt+(OW#(wC>tHBir)ywp_}>|A^Iwiyzf_PvDyh^O+G@-=BI}%JK_Oy( z%cbVmC1&tPXXw~i=>G}|DEyPS@UTKrQLEl;l`RD>YXVGF1&F^B%5mhd4C-ODGhrX+ z1@MlTqiKTzREoN;@+7^l;*PJ@6V7Z;o^oKGeYxBnFV^iRoF|$O)7>8f7c)JvyXIZi zq8hh)k(&@$hPJcQH;zc|;n_UqV4?H82&3cusf+YuF&_1SgqN39wm*go#Bd7t+-IXG zqGJ`+VG=P5iF)yHEO_{bhPuf_7NXGC6eHE1Z;aS56WefZw|BYM@MSl6rns8So4jSS z3!UZDrgIAuv7=zv8e*_7;lTPT90sOmCW4KO9DQqIE}BNqr6i9+$iCb9ILNbLML3|M zvq#izYs%oy%sOV93U(nj#>PWEV3@Ykq+!gT>srpu5oIS#jlqvI@3s9ovLy}=?|RT4 z#f~zY#n8}pN>C}w1`Tb%UhPiU{1kW#Pp1+AcE#P7d2N{v53lBP1TRi`f?)H zL{w8#TA&*{%I(sos)#ss64|i$P0oY7q+Sm6-TTpkKg+4&YFioLs_DG*?2{mzibhYQ zpTgiK07zVNqg{+75Tw5W3 zQXEzly_e4Dj@nc5Ah%=dbth9cg+{jk%X0xfxT0MCH{8(WZLS9=4aNKtqHf#^0ly2P%asF-W*G7Lcb0}P6~ZqL%)*Pc*`6kP7gS-aS4@5o6|}SnOf=O zRN@3v4kQ^z-r;qS0sYE4!!voTH1yI-IIM_A(|C{!ZB|fudB&9UuNpxXYKnHMnyLB=&sL`Q(*2Y>w;<34A?4#e3M^-h&^X+N z3gg7=*4G2OGAKU?HvJqPT_hrID!QO!Dl12iTy;zl4A-=_GENN)hP7(E z9b(t8xRNN6!nV(2!BH?6EVSE~$e3nX&(trl(JjVKt>B((<;_-c>!DAbMnq|p3R-X> z&jcckI4s1Toj>yTp_Y{C)3ylJHTCER-*4!fZ9I=PscIKGy2=lEoAN1PIhAd;%XI7w zo*R2_prWVcNg3m@w2DV6VsdBr&A^c4-Ip+C#_4ev)s5 zHu7zePl(G-KCdQ?v0QIw1Uf{tbu}TJ37Tv#jif}%yF6>GuhGIzW3mOt9lRS6?$tWP$XdBIubsf&pfBP7LcxelFcHlx)TVrMGh zTH~!&1aR^Xtt$Jh`I;;Hco=stnm5~Ftw4SVKT|xnk56Xb4GVSAJ72?~3JxKo;`?CsEhcHI!t|D#i+^jg`6CU&;Lz(}3AmI5)H`l7pv6D)X90ER&_!TdPvu zlSMDHkfX4d)f3mS0R}3K6`)0t1&+-VhnDT&T6z%}0o9wgCq=A2VQA9xuANh=c$v4W zC&x?|kt!FyFJ)qz1Nd*(AU-O@aI9x5b85|NpW;`Mt1P-KBljGR(fl>}^xYEe^^U1=dj4!fDfux6Uv`m&BFKyuw3QOYYI- z$EQ!vw{M463Xz@Nu5IBs+sK+-o!3Ag{y2~{Uic%|3~~`!VNy?lCIdA6%x~fjTZ_3r zJCXfen1d2KWNnn0-J5;(Ppzy$-odv| zMUqx>12A}ye-Js;P^)M&ss>x(@IQXE{c43H=J%2!lJ=^|Oza4Kq=j*;+eLe~<_|9R zKf*5<@l!1pm0w??f()L+mM5aV*Un97QG_LfE$u^Zv}-p(`Wi9L$pgyz2wZqJ6Z53j zg0$t4m+&sSwdK7Wf?KCVN)c>rIr2K=3|DAi^nDb+5#am7Mwj;R>CRLVgU}IKQM$M) zo^`_kmX)yKsGe{)7h2Z&@ILDAJV9Qs@K)M3#{s~fpnvs!HuPwstzRg|#=m8{{%7C! zcV>M5qW=q9+kF8X|9s=NtAKl?8KQskjAwY5)<#;5qFJn2u2fo3fUeN3+@oQw^EFml z1nMq$STfA!6CW=vMVr$KcH@OwY|WKO?%R-Z3G3pL;*;-uC&dpYA;osdJvz8;+e~5< zQ~2{X_uJdE^U-tT&?}2V2HSOu)(3RYafd*9?W9j+z3GdgLOP($lDOrBdU+AOuU~T( zx4&EC!JjBIQnMNH#dWLk7>MAoD2BRr^Yr?^Tii@Qq${5on zQFdu=ZDwk^;URYZe4MHR6(Mw$`DY_Y8Gg5k^?a%UC+2wtfy*!bX+e54sY*!UANNqD zOjuMulpv-$O6}8?h-m}WVnHpm*QYlAI4N=HDno2El~(BYkBm{g@@ig!TklKh{SmR$ zyk06Olgd6@Otz7Fc;ThRmK@j#$h}ZC_`{R>z520l=e?USjA2ajL?cd#;^!;N@imHL z@4yObP~P?)f?q+M1y=V88f5jbkmYuZWL@rV7o}G0@N%#k|HeX491Zpq`CO55hn>;4OI&>0 z#ZRRjjb-k36&Yp=Z~(!M!M;;QhNiswf}t!lac>Mc@PwBGofA2GBpKBx>XctB48}%d z)L@*e5|ud$Z4hyqWJ9=Rr1lC;TN!F+G|X3bws>~x_K{=_*Hm(r50CCww5 z!O#Olk!_*I;>ryeWeimTq?IH;2r!FINyaZZ9Teuq`bmMSi?OAQ8j%Qo^`Xb8TKH(S z`)=uU)&(MlACHFf18BARo(v{-pj^!5RoDidQ;|+=XlF2>kKg3A6W2GZg5*=u*^A_t zjWZcyxq#z)Qg!`^^PldZ)@+ND609YcN2<)BLF4!$0hN`++Rw3UMl7M0z$Heuc9G3t zBNQ|-cmA`+?r344W~9yvRxOB0_-x88xklcrDKTbRmw0&B__{y^Ph zOvDu^CGOXx(@3OIQv8|m#W8ci=9&3}{R`8DuQ%#C7Xar5RwPr8AM%tWNWb`o{>%_T zYaa`R*pd}24G>ix16{usdn+%;vS-MZ@$4QDx$yl=yp>1w*^nx^~G>s0~21l(X&Z z5@<7!4>;0jz5o7&)pNWc`5z#O_Fe`yy_~mA!A1RSq_Ws)!gvfqyZ!l7d+|zyZeQl9 z7SOp>g&DYOU3EnGjqwfI+T^Jf?E$u}WIO9A2|%FtEH|B9I_ z(;4l|&;;7m{*O3eX*;%|ikP6f@>iua=F|1`hJ-lv;^eYBouZSHA8h{aI&m9_d*t!U zSPItMIhJ;)(nrIF*GpU92KhwzVQn)LtfGgzl2#j7PX?Qf?>^5alw%rwrB~`I3M%l& zQo_-5hD;|RsOH^!Xp4Kp-Q%Kxp9m8$emYKX}uo0dn5sA4{7z1DLP56~Ou~jt~ z4&%ZpjH`~4!mW2d6joN$2l~YrjJ6AxvdM*WW(tQfuQt!BrI|j_?$sSa2lZ`lJ=C#{ z>y3Oc2)YGxt={Gtt_-dYPR5|snR0BmRyse}E)gx|SZuwK)pNw;y3_|Wp5z3O z5&fRbgitwl+7`6`9yW3X`2oR}=P7&+?eN6fJ>{Y_gP+fQFq{9*vRTWD*+I_QhGk@~oR zDF5B;QhuaO{vrV6njp#oDhp7t4$T~8JH_yiwyEjdJZ$ia8=dEv7Zz<4&V8!|$IQ?LNv+V(3`8+LH`!o8REK4_bG^CX9PIo^ z_j}C4WYL4Sl5eQ{ML*l1SY%luy(*v4P{3{};kc4$HjAMgC#W0 zcb}hIpv7msUk{0zlB{&1`|a1Seb!{=A>Q>Qc&r8o2hH@Pr4$JdW9^*?*AT7dzQ+Ti z4nmr0jwBaWn(NjZ1b4d-*h3|kM4rB3%2&EOYxpkv zDD1Y&$FqL@+>*Ej(Zc&tB1Mv>n%NnVQ%9D>Qq&E?E4PVV5gEO315OVoWM3n4LLO_5 zeNhGsrl-2>njijIdCvQf7!h0!%W#_@%nZA7w8rAVGEkSEhHdDHa~8I=s4Z3Oav5EL zLquIV_BlpT3R(o`D5mPxO==q|Or&dPCTy1Fl!@t@l+=y9W5Gw_aoTss~-$`KlNF^-IOI zpLAsOUHL=tEHDBlGAFjz%BzB-{#w<%4#5%@@Rli1jDOY-N*ptbdva5|Hv5=eyml#C zODCrZv;^F_Ni_!vF_mKEzIC*oh;jbyfK;)QtG_q%pj$pl+nQGXJ9B7Yy>{oL?b91} z=c11Dw_2(8hpvLBW{SvP1NiJNTP7On`j<@}3UnIkp_`VmMPQ(^QZ8V|b7qMcRhZ^r z^?@Hf0;~#fD#I6)Jp`<+4MSB4F7HC2JA8u}5)oB>#@LVgnVQr{ydjrxW{}CbR%l_X z&M&M#GdGX-@3A|XL+uHrDaoa^`%>O=Z`G=2-srb>A^zkx$+1VlQ9hgb@ zs8&qC*^e}(0d99w@=&q_KT5z=WErdq4VwbhZGTY>da>g;EBpeOfC`%;!_2C43S+qd z*sn1iw?SLLXlDCeBA9m^TR=oehj@focUBKzbuOq96&9zDUS78LY=1O9e}k2+)YTZ_AY6)M1o9ExkMMsT)YDmUYR0qMz6Iq zZ~V}<@7fVC)`w`t6mZVF*wQUj@`Bx5s9ON59yxukC(WFc`Rkm-bGNFpBCRf}#fKiJ*2$Hk+3yTG)dq#R_c;m*1|Dj&pC|y<5z#Y8jIgPul^|sb^rr4 z{sZ~#8^Ql-WBPY6!~d6Y$v>NdFU_kxq9Kx3gP2pAgL}>&G|^EZ39-1TDP`boa%M%p zcHWV8T#Go%TE;K_Ur)d78~%i7|Frc`cpigCHzYZ^?A1&Z`)<}%Ue+7r$*mRt$T(Sw z^yaARB-^F^gzH4>^KMoa%D21j2VJ&U?sDFl(Rr_GHvy<#J&v7T(t%W)Z$AUI#mfi! zZA77hJX!tn^c*F-ZFL>^O{AWtLgOH$$y^k=O~IqHi6KFIvB!@4bLHZ3qcoat0aSdc z2~)H&@!9$J4hut=(QxPuXUE0d6c5vN36mOM%C4%U8sO=4HChLbRQkKMVC|amu+?L; zAT?TvRzgAld$b44m@Vu&dO*N}Zf0cSZ5+T;G;2(5hTEdxehq$|xxa(lA*qHq2bR)P z;zWmB_sV2}Je6pc94y}TP#rw&ls^TIw!NU-5~)_1y4QoKX;Lu*F&;BL*(RPa?sF{f zG+k>)v?L%>tv9pg?2WrjlQE!Ow^t5`@r~B z&=w)Vu@gjQgHn}JeO14dfW3Dn6Nv~C-QVu9PEJqC-Jk1TNeSV}By9$g;SNFajWYg;U!mD)}oSwo`0y4Y6X5UHgbD#DOk2ZH##yqF>=0=flhHUzh*yU z4Y?#;dVjcIdMGCZIprU@hK2FAN(g0Sce;GNvZm}WIrQE9dB}Tx{I~)N@ck~)ZjXeT zlBivi!GY>-L!IRjk$wzkZh!1B`!R}}m*q`~N&Ewf_yf_j*KqzUpWh)FH<4ZqHQ`vB z94R}S4JfGnDjAN0$@7rhuRwtYCR3y_yM%=~qgKaHnpArKNSK(3zSsixU$OZp*Ea}C z(Jh?Ma7H}+jwCxTGn2EmZaJ9}C*C}*FHf5KTs%}1Pvd4=IIF{I)lsYzZ(R<0(1Z1B z=YTYlct8);ZFGk-(xUAh+YX3G_^i_T> z9XrPstH#eohKvv;7H0WXs+Z1_2mJa#FK5!WtFTLI&B_d{91a_*HQuyj4)y_R7EzYZ zcMhb?AouHq`8HVAP+?4c=16<*@EhqcF_)D`0Dw=dv2N5QAJdYV(LgkFsza3M>1`|fLdtPU&?lfPaxI1fp z$LVK|(i=jil3cO=#v# zu7JKM+~!N{B$ceYmC_7Dhq8&h)$%|Fg}O2I$T%b*)x#t@$P1rkl^KPcYYJ|(0l(a_ z)a>Sv1{9)I53E=i0ov}KAiRMs4I(haAYzzOuzQXUvFOiLb__3&V)E394^0rA$T<%8 z6tAv5`;PjB@-KBEWwMApL02GJ|tIG8ySHsB#ZE(Dq(Q|e*Yy3A~k<~kbl z?!RMj*`Qq|!EII+7)AgeKn$`m?g9g~i8pu+*=P%}i4FCp?ScUxC;21NvPc!My4I~(8A$3M8O8cV;H`o9`k@Q){PWyIR%3vGMB&rXx5j-(`VL-O&a$^9k^ep2r2&bez2#9Tqgi}CA1L}0s z=^%;oWAjFuI3kM3xKiQm!n5UY18u`li^5@&iWjZ!u1C((fNP1;#mUOD@cde$xe|KW za#`p109Vu;@|+W!juB~5+`B0yZ`@CvZ^1voys>pj5qm`Ig04~j0@sMsso873hQ&u; z-+z_oKf$%X<2d-=UYh^Ij);)%zo*E*zj#A%pOzZx#X*XFBRt6U;_iVcgco*YB|Pu+~HHQry~e0&7K*jVsb9QB?WbeIMd z33$_c0AZ|z4RqkV$`B3Rq9d0zaInX|oOQcq2*P2pP$?ZdyzIwD;yY=~+pgouqO}97 zQ6~+ij4+bMp=su3acno=y1vW`NT$~!c8|TH^cJ1Pddx|ZpRfG&?M6W6KgNeBfSq;F z&;|p1^NHg~(On{-&2D2ZGIS3+1{&}aKEEmQ-+&ppI-{4cN1_fIK^g0BY_tX@xz}B(9H_uSl$}A zV;p>jw`qw@#(+OVwh?0Ik#I`5e_4)}K+5d=V|^b&x#K#24VNGOSJDvM-=ItUo4eir zOc?x2BLYkZ=UK8^sa$q{AhV>6k^d7`TM2HCAC>bCMPRAWAdW~Z>4O>eop{N zjwP+Q?K8_*VJ5nH5vI<130Lxo;4s`G@3CL=#JQc`7Q26P*WE#0=T1`%f# znJ#uh_{8r>Cp?C`szrGwIYf#JU~w?|2Skkm#21MR^Fb$TCR%dK^9{Ugi~S=(si z^{akNUse9s3G$zW6t2Hf;s1M>k}U6Jv(fwG-XqkO?S3sHc~F(C9_714aQU?0#ItOg?EoDtzE>& zaee!t-}u{Md=*ZmCep#j??l`Y+23C}^fka>KYLgjfp~i9CW!FN0L^3Q)cL=~ly-8& zn38_}bsUno~GfOhp+? zX9^v1;)nB1!76;GW{9OAq{LQY17?)@tVkM%qlYEao588T`d3=2i@|D!mHV=5kWAy^ zYeGZ)AWzt^orSpE-nOrkUL%Ft-z2`7UE2d6?nX!H zV`BdLHG3@v9Aw)^fC!w`Qv~gDo$@X8O3jqJXjd7SZ;d!^b^ij3{=F@d22JxhmoW%x zEre$HM(amq&-#pqTB^Ijqc-|FN#1LLEAOC6z?eV1tEd$>=GSCNaZnC;)JBx}apZ`O z?W&mZH}XuB#4VF4Am5eW%1bNNdML(P{5GFa=GaAjkbynYlvI4RBpG?rv}mTaMI3gVGfG5+GYH~i(@+0hCOb4*tgx*JuKnEwDx7u^r|X~ zNN?f?bcc<%<^f5k861G053>7CaNbBTg|`J^-$h{5p*lWzYnYZ+}CEd~0@?xi*!vqz3Ku~U~s z_MpQqCB?hP5;|~^xc8ro9;BLVEYEplt9EA%Q1y_Y-E8pW7Y!MOB_r-V35*ScCnqyg z3?xd2gkdB^(eAl^E?#5R3W;%&$4@B6R4M38)?$QbiVADuMg6bL6T`2{2FEdF3nH1r z-$e%P4dStvPV>u)^SaqoK77VvXu}U5!RW+tBEPj_c$X5mB)n<$fsH0 zob}#qUlubT)k4HP>Q2#G{bQ+EjZm)dRt!q|pYG`e;1t|YEEU~_YtnXxO)f!J*drN~ zMYrs7k|(>Rlcc=J7uMs{3J$G|5ZI%|aFMz$0o9R+P^MOmG7vX!4i|n|sHsHQ&@V2= z^tBklL}<#KGN-5pbYmM!B1LeY48^>kKKc~sNcw=06ZC*&j0THvc{RbN@g77{HCDHiqe>rNA!4p3=m-Nlh{GdwhmGAT`9 z_r%n~?SOjw5Z0UTr-5tla(%n~Lr!5F*rrJ9V#Mi*xLEE?xoGoZX z>zyECFT(MtYeYor?IL0?VkwFhNsC@5-FG=?)btR!-HkeNiQTp%0ppgrY3qWShdv4- z2!Lu$p#ax+J(i{dhh51xqGN|>(YX+ur5MS<^rfw)QIn=UE<;^tXycjwd0fjQ|AFlwZE@o2d92!Gx0_ZTN*p#c{SC9uKJrIk)mc?_#-1P6nVIo~n(v~(c zj@tRg`qh^cO&i9^j$6no!Jgs^b$cF=;lIU@?raKUe|k`FMUC^9cdK79jcjId&gH1q za1HjyUMWqsjeBuV{^`0J6P^HU2TgRa)fDT2tmG1;kw z3anb zrA9jx(iYuVqX~F~(%WL3bDGfG3X@4eTPlLtK3)Xk)Ww*JGoOHEe*op;wRw?$Tqvu; zLMRJ+;&!PjI6RwH-VyVAOniF`a^kKZ{8$>HbxEu)$K{1j2!*VlQ@TG4(eDxo8j?*2 z%?bD{k=RcL%|%(}7*-nyq1NH&a(%WLulj0<82WVqbotb|$Z+(A==z{`Jdi$weg!fI zG6;!v1vcGqOjY3@<-=WnfQ$so%J?a+RI!GQ! zliBTQ9d~+1i~{fSqHOkh2)}8KN6mBO74>UdO++cS`{n9VvM->NV07zAN0Qmxkm(5t zukkzHDOauu-&s#C4{nXrhsJ|wCC%`=8oluWt-Vu!hL&b45vTYHuP2s>>L%D^FG45kZ2g$N7_$Ss(lDLBQWs()2mKW(JD8UxY%PEwM7A=yd2a?1{dk!zD>OmC*dd`+u`Yzuk ztuiKznSj1EYy_9q1=o6hTC$w)VH3alSi~)@c%TgZL6)&Lmk^pZE-Q_Ea}t^=4I)6L zc&&`J>jO9IPtcPe^3@A`{?4c_Vhyee^A*{u6mKJ~_q`2OR-+2RfSeEGgyGwK+;1j4 z6cf-rLbv7vJmWB*0q}zE;GvfJ7|bgX;--WE&nzIWR7Xn7;Ii8$=b1oPv_tLOwlG|Y z#O1{PC5;Ouv`sS462|>|?qig>W4!f#)=jLtMNm#h;h|zyh_X<)Uj(XZs7NZ%ph319 zo=cioBhD)0W@=19@YJ`4umSFQ_n?NLfsboZxo1xMm3U+JB!);NHK%|0D7ZKoQL3;X zH=GI$w@?EPlR$P=RDFIEgm1z%Y}OFIMGEaajsd)NJ<@dEL%QBmc;LLdv7Ww| z+M7qa-h;DiJdxg4jYnA{szGYXKh!7@LDu$$3qU&4%opi-9w~q?vOiZw1kF?Y`r^6m zII<;6;*2}#4Y}EzDHMK)?qVB?SMg>sEDTG=qqzvDutc$ADqZiS=<$Ah7|{1JrHsg; zs4<3?iuRK#hm0#WYl|^v4R7xrDPlv zR-k-(4w`j;)`br>#%0gVuGq#<^sf;if}+NuM$ssS&JRM~@DBqphE2H9QgMV*BMsHR z9h&p?bLK`@j2|nd&6Y9eC589NXNqB5OoFqG)O$QYBibm%&V@{X#tQW&OuKof{B|{S zl5#EOAiI@GbZwrRoyZ;Qk9Xw`tw*4o=2tCA(2Gz8M6C2^8WC-#pFy)N|FWxLnQ9e$ z&?^kVPH;}5RWOblYT{-Ylg`>$KCO*^q0HkREtzDSGX}k9OL|Ec@gz6SnT%kVB9ZxM zVZe4#D@6Kkg8iW^#m zj_=&>!TYa=u+pbHNB);$|Hr>+mj3f0%=tIk1#w+{Yduq0J41bID+ANNbmoS3|BX0g zC~EwrRQf2aSg)x>nGPo1D6^6b}ce4cy`b7m!n<8gEOlpPX0 z-G{RkMW2a|0pe$R+&huZ#&O88**t#9!{hZGZBP^E#YT$;^cS<0YLn?Mismn&cnbsC z+$clHMyhan)-+DizF%_kF>MpFm8HcO*Nzt~0f%Kq3W3#&dt&-CkOrhKdsN`ql#o1f z)0hIxrbA7%1GMYY7vPUdQXRnoRXt28qR0^bHopP%u3flm8@Q4DO-*CbDJtfEc)tre zC)LMOgSD^Kc~gB$Z;pwh^0^xm(6MlVN#!8%n$uuiFd=8g?)n;NrSUY(v;;Zv?h+>G zE)BiwR{l668EO$qoLCAm3!xzb1L`z1vsJ}-s{E80)^10=O4MU$uqCjbrgZN_Hm{_l zi=+5?WUHZ0!|+XunIJR$>B2c!edAyvdu^i!LHrj(u6jv#EL>+@!vi);#5X4CSIj)hj@@x%CR z&S7Q9KOQ?5Dg=LQ;D-$Oq&CUS2?|+>bHTAW*Vm}ifvF*=Fv16|7&P+P1a2UuZ6qst zcUIEzav-NOqQBf66_K$C%}~mVnoF4)K$a_R@R!y_+@V^Aepjz`fM4n|RmUPYwEf{f zrSAkIV3}M5l9uavMM7UC(y^_2Od((ADZ<KxgB@_<#djEwdZj?3hwheCvq37)(K$r3l)Ky=!f67mUo zIT@{mow!E}zlW8l(pIDqTEb#@qvH(T0rR}n0qfYkL(tPILyKi|yp3lD0*CwpO?^R^NJVhz6cTwkh3tc0;$+A%1?^EvAF+qDWSRNA zpOXl|y|~V+^56hy64tXyAOJ{&BmH3@(qV~uUoTa!wX6pKVT~-iI#-2|r9)g%)2tQ| ztu%nO#!}&TO&5;JW-hk~(PpB9mLohBD!~y^K&7gQoJ!t?I3uNBTYT3JfrEqwzaDKv zhxFy2shEln=W0lMc3!Ko04LHpZi07e!GaCnCm2knQEW)NjYh1g!00y z)Ya2zEj@2KO-<(v>k$8k@*$?0KT>NA`weM{U#4Yw>!?Bq<+dks9dY7xpB&gdwV`6A zoreU{4A_>kif+v!Bn0J=&W-x-5{-nMb2{Hyj&lw5p9kEAi@4*k+I+0`8vPq%r;eDZ zrK%da6>LwHVP+(b+8(;qv^2$_SY$X|_GG*wF-|4RVzmhEgyCmy!jr{qz=yijtC0jsr zN#)Npj6Ou)3p|TsD_61>RJ6xNk!Q*ZGApE+Nk>GNhDPZ{H@lMO{%zQj^F#QDMr;dF ziN;CZU!TMl!xD{)JPqknTDOR4Jk@9Lzb-eNhtJH)FH?VNsQ-zD{U@5v`!~*lf1v39 z%d{avcGRqw7b;y!uT|{#FzQ{)MUKSrIE=461}%tq$hGGw<--s6#_|jgP1tuIFU8_? zUf4h%Q2rTF280(j4^Lp1KFTgjA2R>Nx|w7iKa03KVfYznl%&?|-OTc1Z}k=$Gq zQ|Ir#uzBT+g5rF#zSTkH{fq?zOJ`~o39V^0XAyB>tW$0A)Y-zJmMGQ7Fa2U}?JBut zyu(f#Q19KRSC+4?&jf(r1w{Cp5G?oh_Z(nNS+0S-st!UPLzO1(fwbR$Raq|4#nbKdLOL^l#Aaf1SNwnxXi4bT8?L8%w98XknBVV#pXj3lvcu-#Oy% zVc?<`)bWIMgz{>!QGax4bZNG8N$YbOR+QTmp-|uo8OB)Kc`4}0unOu&!e^z8-v~l` zX+*r~+Ls?>L|)qtS1k}?V*?`h(jPf4U9BfwX-+w^-VYqVQP{3T*g3dQ0nc_(FS{Eq zp97%fa$X>+zqtp5f+Hsp;Yr9RdZ|5(#Ksbx^Zif*2F8xp$)bD}`uv^)gW<9i;p!sj zfE61S)pCsn^GnrgYt;(ms>$~f4UN%8@H@oDfMAd0{2=~uU5c_z1Cc(kk$87Ch1q}` z(nwlt$wsNDcfR`5uu@)X{3St^t&Q<=J0!rtla_o&74t>Dyozq!zq$7i18kOzw!^ItTVjW z+O#37;Q{B=l7}xQq>OlK?0U@7f+#upX0w0>d2G|2Pj*`4?!bYByNTb|gkP6ma z3^-vS3j4vIUfJG+F0BcO%Pmm~0L_IjM=q43K^j~P z%kWYCc0u)YyP7p>1-h`xqP9ra`Q2m5B`%EcVpnZD%1%~phBA|?Vj_R|1vEty2%vMV zTC}75S7QrH?>~c{z<}-@&zYEJA%_vv7UxjWgBAPnLpDkmGCYkM15T_Yj1<-n28s>h zy=yQ_kjQ9CueE?>T&}r1es5=%q+91Sy4S|Uo3^h2-q(#fNpE+=IQRQu4N3-J+rLsy zAN1%h9(G7GuXBO$XcBdslk5r3`pwi9hU7!YX_T`^x@xsKgASK1ijZ4Sc?KZ0G2`}y zpj>S+X=pc#ZoECok=fv^bU4uC+;?sywBJBT+E_ylp>1#Do8;X&>KljLq~%`dN4K05 zNs%_+^3T{C_s7H+^kv1}j-f(h0#T(jF3bDbLX2ufgVhD%w~Fe+IE}f!d@#AuM+Xq~ zRU>uu^OoXo)=i|=0u>TVps>g;M2Y#W{Ta~nZmm71eYHnQJKh!r2fd)H{ZIfBYGp}jrO*H zd%i4q)32IheD&W@*>h@$dTUpD)9{>qOtszoact(1a>wQ4iFZay*!!ymtlj|)G*nA} zgJ`MYx_2V~7eHVeKiyh&ZUxR+U>iu29~ojFCgFX-^Lu7=%eN}ZS_8703dr~jKHDQD z7a-pSzBKmN=S}_x$YiV)8Wa50i8!16-ng zukjP6G2GqiyL1-(f(HR680>B&5R|^OZ-LHKcETg+USlIPyXYso>^Ybsho^MQOj$wt zHb$?ts=5}pN|(IZlV+m)BB8jJqC*0`VyZnQ+yuu5hKGR7%u;sTBEaLz&yh5qHEfb0 zQDKRPTCfNvaH4#~R1b-1f|E*+cVb1Dw6j*~=RHaH^kH#1GbMko`f@2t)-(n_-7729 ztJ;#KUp0zx{DhCE$i!YQrWq4;CqD@1nhnc_bJDuWc4aJe94#UXn^^na|q_5^=T9PE*HmhDF`hRclda5a=H$c zB)Uf}|C;%c2S3btxHS~G3E==9nQciM zx5VZFMT#7m${DPsPP^#!sFS4vF49>0@opiTMQm@{-E@xdG^H%G`5)nkC!XnwINR|p z-E?}Mz4-jRq+@4PU%z`}ym9@m?^$`RowAGq2=~X3g7=1rH zwE)ogVeuF}!sp1RNRNoNCZ%$Vj?wU3yjI^k26n0LhHsieViTRETxC*^Lkv4Z9x2Pl zDeXs5n%N+!Tp`PDGV&7Uj6Bv)evOQ`!ekmJD{N3K^;SHwx)Eaiu7cF+X|s%dC@4U^ z7GefnU8$L2SR#E^L9wb}~$op+D>hZA8%^@*iJ(!&#_7uWRRa<%>t;K{=>oX?N z!AGXt0lSN%Jg0-j6Qi9{761y z=>h#KZ!Q0Kg->b=W3Kql=r+~T#QeL$19?6#W9l-2eu zCmVMyrAMjVQ#?3#0Sb35@lKwvi;7DgZ@|_9nP$M|^!p}aFbjAe&e4Si)Se~#8w#)& z;$|O5oZlZ@*q#wiFlbk}2AOZVeAof!h`dXwKerM1qB&;9LMykvLk7GI^O4r@s!}@d z-*Xuz#2t18+37RhJ(uHbaRIy%q&p|4cyx{ykFI_?oVCC-Y6dkB;;2h;*EP`PxZaZN z0>AvwRbbD4Z63vndV0hVr^&OJgD*1j%!O7j!f;$Uw)HuijaXH>~xgHYiUOR9+4Z-$Zkj4U_9rB6a8A{7Ro1LHyqytNj1}9;;t)jJ=_qlc|-lvZ=l4|Kp<=5j`s2 z%Zmi~JSM8XSH|hq%H6`fSdl&I;m^*VihfVVo*^3!mz?2Dhx~FvN07m9B2{IlO=sJ@ z`aHb3f4>Ibf@k5b^ppevC{<`uZGqZi29fy-tE6^&!c~=z7PzS_CmI-y&ZLSbmTqtl z7ZmEB40m_09W7*8_!-rbx>u2sz&_d(GUumr9^lck zopmF^9p!Mnf42q(_SuEQw$Cz!HBOJB{TQ8m{^+2#S?({x`K!<)lcHnKUuCTOxA*FQ zA_RZOnEiivHPHXJ!Crxqxy-CAniovnsWLf~Vw+DftK%=xW>-)WFo7aq1bBoe<%V75 zntF*<_%|7^EYe3eB@2p_;#Rs(#m$uvb9 zfR_gKlWR0)4#A(%5S2|pBa_zt{)F6lBa|17{l>}n3b6YV1&nB$wO6MJ3Vbl3W_#iq zIx2@PMIDcL^fTH&J&IUCmlgH~)7E8P`;eOqG|z|yqU|6Bq+kuP0LP*KkNC^m2?ifH zf(ETb;`Tfie?>YoD}l`JHrMEs@QI(6Gla(gQiwSRBRU*MG@&^%d4sunf!amFc`m@z zfJsv*2{77}oAZkdF!ouWtCKQ4y_AJZ0j)x9C!LX^L^Z_ zy=d31xm6f(VAD)23Q~(r7e`<1Q)l?tWc0!DsL`9v&ob#B!3vB`oh(2N?gu?h_&>0@ zx&-lOa!w~7dyCKtO012l33Y5YI!1z63E&dhmk_OGpHfLDsd1#1G$?A}Vxwy9PR{W= z_>SB;?P93iPm#+s>NAXU9d}Uuari_@o#8N%zT{Vz_6Az@Z3`R{sWIts#867bJI_&i z5o`6mP$Zse3egTWk547j!7flcQp`1dfePFf@F&7&oT(y!GV}K>#i8B%Kb(D2kS)=c z?J3)~ZQJ%K+qP}nu2Z&c+x98jw(Hfsw$Lo$8FCz0J_upPCGuD`M4vcD?w1*MY z&mbDV#H_L|S~r599@&qOH_N8uhO?Awg3A$T$OmYgOJ z>JsuOSs;s%kIw9K`;6Sj8|F+1=RG-O7OtIAk6rr7UePYz2uB0zY2y6Wi02JJ?9(C)HM^$(C#DE%Zr$`exOUGx1*6xt%c}_L<}Av$t3I}K@5h{ z7D2?@pv9z0&?XdtZ%N1`OrA0KLLUfqN=2WTp&V)@jwcwt*AGxMYA4q;y45G_Nxnqn zND0#7m6k+I970Y_i|{naSn_U{nuKS1rH_Pjr;VqBOb8Nl%gUdnh(H{&lE26oWC$fm zVi%#vIp!SV_F>!>Dawz!rrsG4OjRQWZ;o_GRijQ}A5uU|j)Y{bPS8~wuA(d{HCbv^ zqqTT(u}&yOqI&r~6AIehk^oonGMh%6@nW86b`-nKfoDc zSFM;yMqV|82l?W${3_(_uVF4cyhLf6Ne<*XO2Vq$gmPk8Ww}(9GTX zdthF>9=IGTRK4@dn|DA|^zUOe#1ohYRdB|8sO8f3TBA-ne1dy7Z<6ZXhXr- zjgNqaAFJ9G|Ccpx&TU>Oo+oV<#``oJf1EJW!B>7bz)fS8N>jkoUY+%Iya1M~kS!fw zGxyk zAWp;&FjkjvuWSDO8@ob{AhJTuH7hF(C3Lf@8_Pd@-P*TLXP~aj%$@0ory$uStZWw- zjd(|Y59`{c?S*iCfsXP5A}{q!T}Klopx z93pqXFl0@yf_WJ1k1w94wT`=bPcS>l!krsx23^^MmmyoSOYWhzEzUKhy^fw-@9v>J zq29dePZ1k($~;7_8#e~N;_LOhK(NX_ZDT8VkQc)zVb(7IbtgEdlSLh*zgi=-vv>NI zCri^C^I8UaJRkYL&!*3I_-(~m6kUJed$qY6}3Q(p))B5nV-|% znD8sVyGRv21@b<{cAMxnIDuEc0D6PNRcq-tQkmmEHGOd3%6=#i?M!;o>l<63e`_sp&| zbmg@SZ=VXSY2uve38h4nLND8K;H-gotbn`$?rt1y7;A%TymcEvl>7MVVH#!B63qp> zIS8k54SBSN8b4bIZ^BX|a3&q16v#JsViDmOKATaFu6`8|^EP)FpT6R?D#F~BEEtzO ztExiFGkF3#AI)+%7IukMF>6=#`Ty?dq3vZ^ZcU3zn<6+Xo@yMD!P}b(hq0-X&%7>_ zvAHFvlbG$-UwRvmXm54TEh(W~Wa%}RDX|HIZ!{9_a^GB^ZDB>XdI)a+K!7l4(6mB; zma}q>aA8v^@+moSilpV-E4H0)*?0iw89#ZJupTOy1haVqadvo?wYf|Yb&d2>v~rBR ze5llXpa*gk)%0&4g5^i*f_7kHK(J{K;N30eI#DSBZ$G7|OJoap`8qy@lC}5O3>uVe zIT`TBMf{Xy*cs-05-eH0EWUPZ&)^ME$5}c8UrpiB#3#=nI?I__TQ|YJ~=aCi#@qA{}MA%X5mD*xcLSgJkOxq~ib)y_T^r($o?GVEaTM zqN+A|t(iObdI?n23N+o*=zd|s+p=GXd`S3Xlc%}q#HM{%?D=Bn2dBD+UyZavgh?{t zuV-JekqUXygeq7Nm9dP|ot;h2CLT#$P&i=N-Q*1F;ZaG0qfWTG?is*+2wMgDK+HqB zw)ys{&5got%+b)E*y4r>i7Dp}w0Tzm1qijXr+7Uo6W3U(VI-&9lVj(>3TB9mUKkaj zfWqOi-cVQ{IVBczY0V6KOq!4;XNR6x1%1X#l=F&Z2Jaohz6oY@$Goy^t$2Mk| z9hN(R%j#zGsJZxTEoG|WoOOkDnRSV^#(Hx@qo=*9&cxCA@`$BE6Kk2ZvI3>?E)Z~7 zQoBA^m6tQ3Y+?^$V5tnVpu7upL|be1zUr5;*hoA6^+U|GZ1u+C@B~m3R`lb^-n0CT z1}wS$sxeHAvuavCKbNf|4d*$cqILd?+B-B%*Y0MZdqMf~qAOsAq+wYCa8tYlk~vOR z+Kie5xak!~Ac-elNnzrFnr~)iteXSuZ$@Sk z{ssMd_fRt|IT!4X+^Ro_z2cbga$sv=#!QXN7?M;i0gXtAwEXKKT(IH9g>f4o>66OF z)QH!5vR5gA%)7)S)nezsZJmMat1*i6MA=$n9c-cLY>skqT!0Rkxd@m3vt4G|z;S4b zq}qbP4+t4jsr^H|lmMR8O_+8?pjr~%^s{j^xVVaft~)V-h$JsQEc}(hQ_~HgX20_p zQ;*!h;1oa&CvK0Da0?DnK10|)wy+T5kO(49kWPF^Ixi@rzLxZEC^JM>ELatPdGZ5{ zEzsZpa!kdXfZC$Po5(-2X@>njy6*iwWFGJUZ>Z(RuSFGZPl@h znCRD5?4N9a!S~H1{6;U**yuq$$NvVhf6jA8HsSWWb&E5Z7h(oGX5=g$!3UG;H>~9! z(Dn1*hO!glc_RdAMErd5E*XK!Um%RozI!5a`uMEUY1r zUg)g7MURe;KRbwIFWZF>_egNqC5*??$+OVFW2 z@QzAs|7%G~S5E{b*e-za4;kA4Dpc%3pt{LSt?4SP!q56m)!I@_)=C}M4shs%>t%w} z5P86&`$pfs!DQ~Y*!dq*@-)<6K^r2p=qIwIdE0NIz(4Zvrm_-)Cw1Js-Mk#i%jr*;zJi2*;AE)s2gf{c# zK9V+mBRq8mH-3__ziZk(wUni7%{?6`q%@bvt}B9hK1q6>Et(M<9P~dWiTrg;uRmr@ zPLNFIIYkK$9DtM4*SbiAM-cuFIPewP_9ai>DuQ^xokISoLC$l8ZZs<_%6L`4-z1Jl zB`+KUzXhM4*e6VmN#X_mQ55c~rHG3F{uL(V2#!n;L6m{F$skSeXEs(V{KKqpv5P;VBICLT=41!)uys$M97O2L_BM*(Go z$Y_p!fRZ*r9e01glCUX(*|9YMaZ@VV3lTk-RN6jOblyzG@ILlI(Y(up`*Pl;TT%yR z7W^!a3FVjp2}Z@;He!YiHO(W7ao9|ab(Ok4#V8g6yCts>m|^XaHM7BNumuC4GrB(ty1z$MFJx4&WE4M3Q3^f?J#8&{D1SwB+FQs>S)?D%xNjdE)`CXMGG4(*^3Cs zF9YY{lVGFNPWuojHhDAWBXgbbl5~KJQh$EZCQ`t}mOb?$?}CP@N=>wn(rfv zhqV#pd_kV?lMx4FBf`Pv=WGQz-BCG1ZkYpN*CoG-6V8kU$MnX0iPIoX69;Ng!u-XP zF(_r20)>6{>~-S=xm#-?G_e8hHL4C z*Eyb+Ei=uW5+O%@q%;#mpr>;^$SzkXVc~HHVovj47X;VYuBN6(5cHcW5{pKqG zyp`(uJsR@h=^viuim9^j$4G=7!qTD|T=C|kR6}%9B@AZOv1gnV&McE{-+K6zhi4io zslB0(_(p&fnS;ZQf!X#VJ$fjl5kr%J&PtxyCPoQne4_06BaP{@0TsI#* zz4zacGv8R;-`6)EzQ4;}$dU`Xq(A;x40SXrbc#iT-#>=r`svStnCY6WI-yboYmX2M zAtA``zK}26GHAkPNB}%$XQ>bssA0)Pmo{CcdRFL(ip_Mh&pB!_sh5I!{RG1eounC= z!Z30C98Gd*!|1RuY#h->k}L}31L8#xqL@?k!@tYoWe?5hn17_wE+kxKhU3!Oz# zoiUNh&@O$5j-j!qm#{rhLbEakM5pwDxalT$X{UCpe+c)p*wgaZS553%E}XC>!~5`c zMs+V%TBs!>rU+fsxW4v~u}r=D(l_i-+(-T+UN>sLaCsVmFD(kD{m)RR+n9AXzH)J~eKH%HlZ>4P1^R*zDvQy;E4Y^kvEGh9LrTOlnEN<2Lj&|PF@={n)D2+p`N=iwTapex(gDNTHn7= zjC1f)!|_n)IcSMZvBkxBEj7!hfw*hbNWmn8Ku%(O&*>^Y)Ys&ldTC57jjl#H}Q zhK85IiY?8`?6azgA{jt0c$NSo?Jtf4 zQI4u19iGW^t(QPI$)>*ydMt)X9;<*)1XGOPv8OqA3dcg!`!0x>Id3C1Gj5^Cu#l3z zSGo!&S)-Uyd2(8~G`lF~XiS$RR_i~mVe?9VJ_XP#RZ!Ww=JWwJk$Xe@&z9+-C@bO>DCnG#a z80uSba(8#-`vUrLh&vMR&4!n|O6Dyk@04s|O8y4j99V`;2%lHa%s1S;b zJ_`tT0W`wg_2jL-O$*-0O21gY;7SZSB(H(*9-{gwmh)Bh=PU=*kTq3mcVtQ2sw6w_ zB3JdEvY3yElWSUNV;1(r47!Oiee;C(YsfRcaEquon|!TD8wW`y=}y%}`cdvYX%o;R zZ69E1S*RT3wTwI*rBMGe%6C$8@Vl%dSPJz=Noz7H$OI0jlOCqAW&}M!FO+F}WM+ak zPXM#1(`E)`vR)^aO@V}Rl{YtrT}YZBs;={JZ6Ghl=hlr z;z2P$U07yi2&b+7j$!??5Ia@W( zm``+xLBO;+;tfpvVcYvE8N*MrM{%9T#seemQt0C?xt2B_&^8h3in>GkX-VCMY9*D6 zTOC&CXjIZ`lyD^7G)uA>&4}Y=af`6x))Y=LJ#;Q6mE<{2B!);%`R2s1Mbh@s{v1ty zy`zX<$^?oett!c;x`?_V+9dtF6z~}Ho?An|x`fmb$eNx_fp6M#N+u!Hqt!k}W1PLu zoT3X7&3P8H$x5HK0Bu@7<;gtdX-NN+#X~##_V5g9P_TlQY3bvGo<^*#j88JEbqAfd1=aXn{k6(7CesWByQI+TZDJ^HZBmfq;$s|E+A6iIIWq zr-u*LwXi;iqs$g$1HA>#2d5RD&FZKNVl9$jw*G9(fP&k}8(a)#k9^&k^19Kv9zp6w z-h{t|#|aTfeRmX5p=TD|2NL2#IGol>Re;bIFX(yA&_B5g9-}Jymc8sMv!YgEboH^V zzQ&@g>Xcz@haXs74O$4_Q@U9tH+JenNj{A_R)DJiAft!22tF=E>gF*aqy+*6g?nW7 zQU&DQSrxu9R$K5Ew(&Ic{`vc0;DH*G<^M3&`1^DJ=W_gaoy)&ttnvSp#s6z2nWds_ zr#Xc3wVdEgb2`r27jZ~T%O_Dwy#US;jl;#aqvk?gFesoREhCs^`8wSFlx(D{&1H`S z3F3;5t|w{k@BhQM^+!X`UDyE@nxtRQ4=It=<;>!BTH}4Fs^Lz)xsv6wLgysGI>fr zDKZhj;*LJYds$A2Xpx(6gdqU-NP)tK^nltgEIYwK1b(35B1SR>vcfEkUI}T7G)O%p zYM2E~6XsPw_*uo^fYXOH(K4eHV6OoY&ps#M<{v?}XH0Q}VS2Zd94pH_8!NZR$!}d& zCe9R`(FYhf=%PfxfS%vBb-x{=1Go%U?~8k%CQ^97LPF=o8oUj~LP8XS#Eom}AOHR> z+{FaUHXLbPbP%-}&lHE+_(RK?Xm6-ez29cQEBE2HWmn=dY+a#;Da&n$`9v__T)E&0 zY(W{KE_l@hnbM()kK2V2wTu8@Yil2Ha6Z4m!<~c2mQ~4Mqu4;8J&ExYwyWl#E$^{O z5jl6(S)IC7mj5&MMNK4aF^wddXo>(ycsfkB^dFRAkRc^mq4bOs1f4Q00WHFoW`K3y zcbacB79L{urErfERQs43SG*F+oGQb3%uv=Vmg=SMBv;(|8!0fq^*ORg*?Qo;6i8kPflF1o)9vp4@5c0 zi>@NlRTbIbARkG+6ⅈ#R=>o>jHWVJj@(c$I94g&4R?=A|qE3n{FTtrNtbrc8tO~vKH&vXOlM`rJ)W6PXDr1_Uh>E81~oGrjlkMsCXfl5|c> zc#qRUEURPr2_^g4{ysfR{n7N~Y9V>i+Nbqd%Xp=!5=FWiR`D5WwpSjigIHgw;`ylS zTFk^L9!|sb=3WT#r0|_oPB^EG@u;i<$Op(aR`Si4z0QR$?V=7q7szagK5S@>-F7Hd z=VAyJ+)x*-^oYc}Tz~l)!qN<^xBz7ITAFDIOp&AcWOw@c^)d!j96E>64Tsa(!RDp0 zhiXuqapP#HLA`H@5|E0s{)S?OPEyI&9<{DoBw=kbMz_`Tu$v(Ix|gwlww#Hm zBPHBf)9oLE!W>m@tQP5(ilCDWRm2_}ozBTZ#p-4;(&Q+-_Qr3Oh`fJg!uV#Hd zSLct^CU-t(fjh2=hWR~B==@MOAJhrk@#gw@+7%+xLyx2eAa2znldeqnIm#=1gO>7d z-UrpQZ-FH)ex&;!o5eH3I=MMF00i}zCWYr)jTg(mO1)f8ue9Ih-6ev#snJxxK_8+@ zeu^kNq5+HEGSuq7j^_r~QZn%ReWX|A&}SUa^{`g-z`#{Qydyrmu{F;?x!?bg91XS9 zsmDxRPKDFjN)2M&PESHpyQ^`1TfLf1O_3TufvEn&b~V5^oQr)srY30uU1)I>9PfMRRi;H(+dBE1pY@_;nWYU5Psx)y@vU* zf;XT=cu=IXDQ`9qBrkt<_B{jkG{uPMkM+%8?w4P@N$gmCfw@k4=~;LmCMM7O_m?=m zFw;PpAm~sJmL-));05ojdn^s2D;a-L8jOt{%XE~QNz#>#)zdXn#;t7+1r_Vss7i_V zi*=w>IoZZ9X&|80Wfo9f$E<+&$a!l~W?~IoK#n9h)3HrRQX5XK+Wv!8=(Qz(f7@Q3ws^8CO$ z0mytur-w^(p+DdpJSpMbyZ7cAmiQyr^G}HJuq1Q#_5&~4{tK`0{|91-8#_80+ZY%- zm?}Bw+c=v1xZ@lDM*?=1vUU{G3d+}&2lvyO;eZV~qtVJoL(q^K(y)dXm*4fMa~3gN z$j*SrnDLsvK_D>}$zS5JIN|| z<|FC0qE5vuI|t_$4WygPwPXV43TJ=TF;E8=oAEJQgcB_Lir_*XqUW(pP1=rRje4t< z5*0G3p$J3OMD-Ec=(R_S+i)=80GT0=iQzauUbRZ(b4!qfTg|#0EDfW zsT8uTvsNDUJ&EJ6KMhhyE=}amQ$kg|%0}$Zn~M{1iWM9v8dOoLmy*^!nlxO>yt;H$ zD}ecvwrQwPvRUeCDA#RG++jc;5g(8rX}{(3s>%%XBOtQtKtATLT1|5>5V>23-|>dV zINvF7uH{iIYIJ>RDo|2i5$>9YrRm>hRa~1h99dBhk7B+t_sW5u_M82UTlxGTfMN|g zdOz8qtR}0hc-Spfap>A%JJ)&8KJQ#O+#c?-=ZUGZ&J3kCeFt&-W;AWG_zZ2 zID40w=%!|+EUh^xb=Nf7R~KLI#CV7W3$O}j>SJ_`$-X185@6sq*>H$zYeZCwXqJ^C zi=|hZg6v*Mhmu_T8-RjvCit%7SyDUb7F|DEFgDD44_F_6rdi$lCrd;vAixp?X(wIi zOi@q4Oi}TKT4K;kVI7sLZqar~{duqxBY1?$yb0&9eSrrgK!Hvzh+qAIoPn6K`L-<1OeJUsX%QF9~spZW8w8- zFQAMvXP#J{ZNKe@#8Vw}i_hZiMd|Mvcr`mj4d(Tm$ix+1TeCvntK~Zd5iWnl`84F^ zMlVW_19Be$n;hnaPr!Efzcz2lVcSUN84OLu;v5;vZ4em(HU=rx%mHP|CUIYi3vG>C z;0n79N6{$`$6QXwRGyq2iZnzEZIvaJUc3vl)mfda8EWpRP(~bSk*OLYrSK5FDmOEO zgjPaeq+v;y(%Z1b_GA(i;9b>) zl`$m@3yU}d73CM0+deQ74gm;W;kM-DYAWmVfG;Fe_9pOupXd6mV4*0MeI_;P?g!r(p_ z9B+|$@93G{p_$&O8|;%{oTH+hk}$X?IlmA))EO`a*hSkkXrSMg3llcnbHqOZjj%IY9nQAI-W*w&W z6yU~@v8)5wTr}oWr^G0(o_9jcYHM7c{dv@Qptj*6b*ay4Hx?R{&E2*HDnd}gOgS>q z+?=yO{A+L#)p8&Z#p8t?Qj{~4FGPl*B+Yq3F{Gek*B z0wU5ufh{Ns-PCoo%t;uWB_}|QI=jDR)SP}$e@VmvkY^>Rhc_i#TXFIl8%>+%H%M1xnoLg1l_Ezl36%s)lyGIMS&IUdm;r8z7e@R| z7N{^KtFXt8CAINkneQyIG>LXIKf6WQ?2N^3B zDGT_6eVr6iy_D0Au-%jyyT5zmTT4hwGSgbm!kA8@)>mpoS=15><%K_qDC}X3$cut# z$yb>R6_cLAiKe1gb6CPGMk29ODWC3p1N_$0#RUxBn2Vhq$_9aZ##)Z*M0r{BNP0#K zj4rMR)x2`dllf=^=2Fr0{ZH++I`Q@y4O;8d&#eGMNR=Te5ClZYNPfsFVEHY!VPeskXlyXaoOgk$ z#c~C_H-OL5a?=%3@Ip%Y@W!nMCN9V6$-%GB<72vCHM>diVogEVR!EVgI_YYNqrP{0 z;(B=qLpWl%5-sN(HjC#X`rD^tg&liVZ#uQ#v^O3)X_XL3Pam@6i2@f82N^ON5iEQU ziOvA)m`qYlB6}W4RS*9;zWYd>4%$-8sSxAT!!V>^z)?f7?CYFg5F|GYk+)IiWsr68v zn;>0BNdf`Z6-iUeCFOX;7yy+mKPo|}qCd1OtE*$sl3g6T?8#$`kZR|qL!a`FNiB)M zSUdy|yUgG_wu);=`S=`aCnSYHjHy+B2T|18AAU#lJ{i`FynGOh@_^3pktQ@h9(XwN#+tL1^Emb7+UN2oipSQU z!OH)x?Am%Qz%FKKPDsh|HWkFzeD|hHv{Wmz5@Su23D1-r<8%h098$tJK=biFBA)TdSA97q% z>NXhq=Z3t&J2|w0vinE~C?;k1+%2ldE3nL#@wp}KjTJ7og8g^^lY3VPr@LUU0}#df z5{HJXVqdvQS}K`G%%Z8Gd(Rl3bNXG$|&Q!dgi zq{>KI4rk7WQVc73O z7&?e)kO=!u7WVZj+asunt5(UsZ2gKn28EiirzS~owA%W!eV=`AJnCh0jTkVdJqv#& z!@1B(g8Mv5p!HLKn5;GI!P1(6{aH>| zBy>24ouOXlRip^@2Z=say79AswIL!Ispv~&0N9KrBR)2+;*P($9B9T0eOgB)vXfXc z4xlMhBOFsA1RjuW>VD6QM~hMjspq3O>41tbI|u~3JI zn6)YA?fxahvxX6it`ybXNgkY6PoF%6T+)U(x6sZ%md)y)u_twFN9f8>okq}N&KfdR zII%*;v#nnrSsUYB5}8s$~(QPtocF*1^va6N);6$Xor&6WTN< zBr@vWT*oIT6mJIuWyZn{cE++b2+!gLL5F-^DG3cT1YyArV+Lx2@fahjj)17|V%NGc z1#-a1`ZFGJ2cV4OUQ)3phxHhXXtnd=Z&x#>5a;sw{%-j~ zE-Yr7g9o?KU`LgTv2f&#lcbJ?GpG!$+oJ80Rn4OdQ_0#y&nhs{LfaU2Hu_W`M#@u0f(iv0j z>UulT@?63Lb(idoFsZoVHw`tGChn4HTS~l`lH;AJAIJH*^uDH_RuF{>`>+ zIHq~pFqm1yHq+tfEG?K_6{wK0Ljq9>Di>CkNVY^A2i}kq$7+$%B4O@^IdtQS_DeYw zC95J}+0?hRAd;D^_?v-={cypL;Zc;GL0wZ7N+C*CI83X#|I1v-j24Q8nUw=*UFx2< zj6TVDii$e%3L(J&ELl84`yfHI`L8H$9uC{oR33zzAk6-6q3Hdakc?q@OpDQ8HrXev z!^+@{11(%g^8M1ZVFxBjb7qJ>f&49ztMGhG25JFpw*LI@9EdkM@0P(fR!f@L29AGT ze}~7AJ46Vo7U!%7rAXLvr49NxFo1`5;&tH`R)uV)9YTtP09;SF7aiSO)t3uEZk>+z z|DKayWKno+$hXeOw>lNy2*vb&uAbs+F(|$i2HH{Z*n?W_o?Bg)CYELnvM}K|X)tb^ zGu0%H@t+m{Wfs@TOfs6#zMk<}c zkL%k@f15@-@U`ZJv7kuaCYX`2CDpulbmEsyxgu2sm2y*C8;zgT`|D?!wWmtXQ^OO; z*>gwFyhU-C1=^F)=X}9Qn{fyrR&b@k&YWLRR6EiPv~3_L49GxLui5J;na zV1A|J`zF~O)^FNei5+Cr!?uZr4ct_twmV6mf`G7OEN*}q5+%?izhl6D5_EPb-TiuK zm2gMX8t&}lr90BU{TBWui!e4ToUz+TcDmew#sF;c5jjrGsk2NTGN6{8vF_xxH8OcN z^gE=wTm9V*61q5rCIBDN+)u8M7ks0x--W>MXe@tx6K%f&S=_Qd96=UC?K*zXl5DIJ zaIaD+o%Bbx&c-1gqN703lcMg0-R!rP_5~U+$cB-y)1(+=9#Pm=J$&ojJ?PxoWnOW@ z70K~!y1FJlCbkNYMuvK4#!i!PaY~CAIc+?Y;7fSX3ciplh%0Kz>Y<3*hdo`@P0)3) ziFyWHaZE>genb7EF})q4ZM^fNcP~Z$-wFhgf1^N6$O4I?|H#gP2lG1-8q!PNBC&?QQOY$VtemOIO@8Ebh$+HfpIbYbFa-MTk&GA9OL2)hk}q(IC0iq#fhApg15xoBvYJ|La|- zQit$TT3X_J-g;(CA2UKskakn&cNqmF03ZYkqXq~U^drdigB&oD4xt804;tFUth?$6 z!-{C0v)H8k2?NosNM2U4s#vyYTGn`PYPvigfBumnr$a;ne(~a8XM0|^{dCQ*+KxYL z-CqBUxFE?FfxDX#eh$k#K8S)|7O}nFYqEXD_+00;oLFbOjRel%rFpCfDL;srxW|rc z9na*v+ynUXKFsEv5~0x;F88>d7`}y-^|YS|W`6~7`R>n@P`_PMANjVv!+m`uj(iO* znwpPPZMB{T#N$2R@<;nJt^2xt^hkfw#d=@m(VY;%d5`7npHiWDU*;jcMTd6hd9O;s z`vSiN8%eeW?dHw(JB2eh|B6t7K=YmF>7NqpM!-!SwS%e|eE`oHbqKeDi$?RFFOK^h zA#tcp9(4}qhLbUdPz>g~d~ro;c*V`2c)J_fD+5GTKS30su3r@*3-|f0^!rZkJEMK-P!A&G-$ z8TA^x$(b6m$w`!c9aBSfz0b=a1HXU;*&2yBHDCcJHptK#ChzGnfRS@e$oiJa;Ie9x z!^fqvtB$ad64@p~Daf#@3SNB<^UMrWaSqWsGH8wJY`uVG?zdqj&7wk%28aA_6;I+t zMxr%zbIpNwp_xiE%ToIu1Y6-}!rd4(u6AW9xQ@-mr>EIBd}6x!$l6${$qkrD;AA`( z7P?HNGqc!gDVm_q)0i;WG`wg!we2-b06Fv@gmEn!(JaD63RRA7&wMA98^^%2{AEK^gKe`)7wl0O4Pw*q@SK(5%;j0iM-Z(Nxwx6-sa3|dwW4tOc8kt%X779?U{xB zd|A29t&s@Ra^S2{rHVf6wPmDpQ0CN~X$^E0gmPoh8YY#3p+9Ji=pA<$GQ0*M$JLOupx)su%fvpTdwa1RA?4s1@7 z@bV>EmxVCI9ub&UACS-{x_m$9BZpZ`iG`HKg>e(uRwyqRO#dJBKk@CP*r82gCaQN4 zwP6|H)jpPuFt7ZUuqg8yf>l(Qg1;#iw|IeNqzYl8qxKT#X8-UZ0isr3K{ts7)S zcejLHyqvjcwu!`mTpfUGwSo38_xjuDTpg4e#_s%nf|BYZFvkwo31sp=+TVO8 zK+V*XosnrAqxHHE!U36#n64>8UxzbU)-ilnhe0sOO{9$6KAe$`rkI3Q{;J4?0TIvQ zc7Aj5s0hC5CPKckkBV~8jP5hc=c34ZalfeK#5}Bk)epa>6j@n^Gb_bDH08b|dHPX- zh{c^k(9~@Rone`3_-8&M;!Zso8H2Llwb-k~FMSgcZjg|wVxWQz#>=3NeO(U{L19py zn_=s0P8@$o1s@^h6h6Uo()D{DmY4)iEHn2I$P z8Q}U!EFMvFWx_svLDgM&`jwHeq6+l3wFZT@CZzkJM$t^#Nmar~P{Dyb_L7TuOu_>B zx(a)A=skq35edUe2q&S)xtYcX^5P$u^@8OjCM%HGM=Da%d{)0Xktc6pL-GF~%HAGe|(s^2mcG-3KgGqdOQj#tt28j%OcEnDU^!#pF0V zFpgPX9{q_FH}z$vVgWX5^oeLfb|wF10J3kN9?^|q)Sk-hW4Bd^Ie=`oB%9Y@bG)>^ z#=N@?xl{XN_=`zKPPfSNg8Ox(n($S}B8%Hd>qdKYQNv;VPxfv>+d1o;Zzculae0HNX7=&~@Qwz0M=<2mbH$SSYaj&~jg>@U%A3^?qDu`V7SEu4+3w zhuHk2-n^q7t1=%#-C1YIKPw);_r3=HXfZF<3jx@$B%W9j!n;+*PosX(ipnoAz51b=Q8F81`lB%B-9j=RrmYDJ;>qW+TVSBhKgy!SjyD789 znaeRqK}X}=^H#s;huBkk++GdaJqXkk05_*fS>VQ$KC#5k7Hhh&&6GG>5ax(ivGxV{ zVznsapgb1ARg=lq1n`0&RT3IQ9@Y(&2P7mln_dVunKm&DQ7>u~RVS0-HH)YZom)T3 zfl4r{EBR&;=T$Jn$NQxob7;>&T1b12Io}=O?trOdt-mMJOT#{Etg%h{CcfL0WG~#? zCRa^#D>bBSns$-DT)g1C9sLqk&GK#9L7Svx_%ut|nTB%9DD>JXTTj|f{$5UwxT%RH zw=bgU#BFHG2wlLvUC&`jZ0#@l128doL7ty2z+VJ8|Jy1T>U)3)d;)lTU%E(ATe+Y> z&fMonif7KI1Ii0*Ha>-LDR>s7b~OyH(e+O??eD(Fo8+G#;9a%yx~CXO-JDF>oIJ7_ zLFv-MT^JBJiw&v^CgH2T``y(`uKhd1}NV7-)_0g@AIwyWJo< zPb#^U8#HP&VP&K82*P@|OtCHZ)vA<`sS+&rv!zWjZmU>A9~ZkO2Wr34iH3@bIdyf1 z%Q8MJ3A+(@p*H!a9m~_v6%xZ0U%ogROU%xDCqVILzqJn{Xgf^Mukh>v9ya*Pw{yZ@%S*%f^sYD z7!HM$k{%O}#6})TP4@Yi*y;;Jw=)ZIlNlrQ<(N%fTXONfhLC%)_nAq7bqDGikJQ;X zKiu4fb-pd|M54e&-XQRNT(Zo>in`wq*a_wf21AT4$WC#A+L0E>E)3&gw_R(J(Zo2g zq=UC;x~X7FcKb%&*C;a#D}z~-#^fn9*98mY8e3akI!%tuEFB@CPTD#iMiDoq8%o}$ zBcvM@H0Ab_S*8+5&QfiP9=LqOJ z5Kk0BIMQNKPZmw0m&5TDYTDz^MbMX{VAo$Y8QOn&{IKPiK$pvO<-`$PVyvf`6~#Je z)h;g=LpHf;I6_c_WX6X~E)-Muqb;Fqz(!pbl@Ka)8!1nA=dgG(Zp;Xd+!1(|Gnt0P zIY+hwyKVmFwmU~H5Kffq!+ss!CXVLSoEs?NuCQXHdc#nWg>Z{L3baZ(P*6}tr3j;r z%@)+-OnRS0wusMOrhW$}FS4&!J}3Q=n%bU!A~C8%c>4B4xjHAG;D^9Iyv)^Ew@SOEW_ROwi020SwGm`ZGXQ6GULogX?xE`%1(+IJ$0KD1 zxG&{E!H2ew4LUETO#$`St8oAhv|m<}jcYnU!|sjN-kD+QeiURaeZ~&%&_x+cjF-p1 z52D^H@zNl)UZ9m%@hs>Cs%7CcN6YdJ>#cgT*MQwt3g*G0-}uEqnYegJGv4UQ7H&vz z4FT_#w7nsX9w%5yZ`wGglI|9rfX{033rtl@r$3LN#wM%M2E4D26Q{XLP0on}dnjh0 z79{(swzk`6Ylp|)L-R!DN|^7}XyZt7OE-0lF~E2)whsRo1FY;sh&POc2{Atej)qfJM!T#7U$jeHsNAyeeUkxMQNz?4ZQ%LH^Qq`}J+nU|!f zS-7@X-IV!DtaTyJ6#EO-_$SfvUCM2quS3mb+|?+YM>#slJmT(DKJ_FL^PWeMd=4G< zUI;+ZC6d-Hp+n0a9&>L5Af`v`OHGUDxp%tb_6Tv;)+6OhRgaoGWZlR1sCk^cFsbd< z!y~qjH@z3rq-39ra7xN1vrl!sN9z#Trb?UIFe%!kIk<=O2pFV4$LkQ^ruL)uBl;n^Nz$MCP|fXDN1d!%0(#5GBE?rqxkq%({>-RMh^s_C zVq?`GU7omSY|*(^fpto=N{Op_a%x*A$Wut0BwuztwNIQY=RRyY2Y$;wPnfGBKY~6d zeJfn2)>pbI{2~17N2IUpm*%zfGpUbtcCRj$yJ?Iv$sQfxRHsO_!$LN-gT*X3muipw zbdPJ?@EOz~)N9Q$#gAnT$R*xkukBxTy$7vTFv2ppMaYN$2tX^L%ya_GAthsgtZv6J zT_@BXc>IAMg&Hno6)@S& zt$hWa?QCC00+Ow1dM`6hn8HXbCKAx@{%e~pHFnCyHH5b^-;kb8>aq*r!=^3VA|CY~GNw+`Zt9&h@gbpF((D>9H5| zfKr<&<|E)IZTsXtn)Fjh_#}r-%>!7x*=JJ!NKYM|EK&94J0GUGbbUtp67`klP1v7O zcEss{5p95OvnMZbP=+^IfIY6y=8jN%2k`RVR#;sXXGDdiJ>%Ad8tKA83xM0a=tvC}62En88@ zIh*Sqao5JTH7lX}`;`HtbZcAIDQlF&--M;g-ZYt)f%<4}BwEY=g68Pi!QVESSA{5m zNAm7m`SA7jJ>6BFceLRAmU8s%T`i;nrlb4zdA&U7tlTGltLYH{GllB#C(6ao&Q;DR zm%UU`4NtvAhxXs|sA;)3`hDq@=+o7DxBAq|gmeCOwAp9|ER9{FDx)|vizf%V)mY;_ zwPhn1X9kq6kw3qd&tP%nJTqf3?#hkI8E7k8EyQs0u&w5_+4HyY(OrzjVrrh1EAMIA zezcD!921B;V02Xxh#M{4U!I_RDlmxedJ-(Yqe?pm=w`>IDzotG${n8pcYiX&K}2|S zSY*e-VEpj*?)$l(cQ~}}igiPFQOZYB(ps4*9WZ%a(1Glv90b;}VWFo)^l}V=Jm@{3 zVv+74GJ)7aCuUfZRFsEh%Xb3`146HAsI{Jl&A$Tthq z3BLY)qfZTnm(!KQtbF5>QKLGF)9>Zf zds&KW-fOw%jx@s$KL@Lez=7Dx&bgkqfq%Ign-SVgIe`H}&zgqJ-*+RJAwhJ{=*~QX zMh$vFRYk0Ht#yc}wMN5p+TJm}dK)PnbstlN6C~mS`+R+IAAbNS#r&!{M|1b)_x)~K z{Snm0#XIUpb3y`UoWL1?lo1EbICCw`0XqE7xTZrN_|$h;Y>^Mx{8Jh6cQh<>Xf_OS z^Y(yjRZJ8nhSavsh&%iC3y{IL3GRh zWEqxHa9`!PW6^ti`y!=sFCzfO@3POv84PPGm!zqrOr zo1*#WtI}s!RzR|tL+6;X{K-6O=5*wqJa=TA;|^kI9y~1a%`qiO=P}Clf$kvh(|>^9 zjk|NreTBSOo|~rQSe)3)$3OjjD-gA&yF-0T5Vg8IN_?Z*D;B$D4yIrpFuCN4-lp|_ z-pI~eeeC^Y$uD;9B(;8DQE=yo74e4f{QRF;wTWH-e9|$1fR6r&HUAqA`Jee3{~J8y zKOU+wmUgCwPX9MZ_Fs5NijuB83L^^dAGg&2FkoO*egOFZ0(Jm90DWoLB;}VQvOB>U z+>D)LX-;!ff82fuIg;$-7QSis!+;b6*)>UyvzOO#_M)5b_xn3;KQxb>A{m!GT!O`Xf{y;NS6;EYzb^8IqKo?18mpG!brqhk(#yRGU1Goh#`zA0LV*P~c{{)Q2S;Ik; z3|&Pkb0#m-UaMxx>Sdh_s0WU4JzC*%S!C-jemIdjDqJ95r#5-@{a4@>>ipP$Bq!eg zFQVoD6#6p#FW|EOw%Gljxou{DHfXQ3CPh_#iHcaFoBVULrvJ@qIY^2~7(kxtCX{CL zCu@s#pzk1xp3lIDFhOMdi=BjwFCAl!rUWHCqGiIxY&QFbdnd!$tncUh9kw5%kygS; z<}+pt5DD3ksdC2<`x`G}#<;<=aNiP#HeKP4CiWNEz6(={k=BSaDm_NJD6x1Dvq+=d zZjbrAQ|wTW=EkGXHFNY_*LJF5>Wp^+wnv+a6YdU0hM?nMJ#AQ4?py+LXHaGTqC zkxcrdJBwU>v1z#1OeI(doFSSe={#Mc$>KfAo82IOF~hacX>i7b>w!NF?a6&&YmX4q z6mjnQ*n_kF_vE}}^2TwjC*3p zlr**zbCoYzVD$5zZ<)OZ61p}ZEP13+59I%F(+W>l9(2lO?cw07PFS4Rgp)$o_!1`CFi#pTsw(eJ6ns;Sy7R34}c&w~dz~5(0MFt_66ee6{j| z(}|Kftcj^YLLY%E?-3(EE95Xx;TGz^3tPDmmm9^J1=mM1e8rYzlPc=~zPf7!6CdG_ zQ`>}Ef8h}LE5$9!ctXyDr{}4qPt#IDEj)SGePED;M6l~7VsVKCb=CnMEl!QV_*Hw0 zEGUg6O3cOF%8R!1G~Gn+e6^Rl67TH+WJ*Pf67jcKgAN@0{Sp?e43SlaOh|87rzF}) zdpGd^;VNWI4WRw{*Iy?8gmnM?3jUuxCiwrW$NoPwbUt!jP=f*p*{VsezxW53EO~|( z)Phwah2B}|?npY4q^HL;Ux9s--S0p*jY2cFFrU9XdV#7Lq8K6=NPoEw)e;6fW|m4G z$EdBWV+&^6ac`kJ-(iqz55Ah<)1~Fmh17FErDYt(xI&P(w5w$iT@3!EwclhiG}bM6 zoqbbPv8$TQ)KcBlS*ctSTdm+n4faqklwu26&$IugB0=yxE#<%EHw1ErL-^(xoVWi? z9LF2o_n!(;{Pi+y`gi}A|JMJm(Ent_GX5_r^j{QjRToPe=l}XTwP-;a;Fv!7*_$;s zt=TNFh$qb`da|#P!1fSYf)YafS_~$$l-9CbCEGCBn6X>iYDN)3uo4wi5GcqG^j8Bu zS}0{*-ybNT2=fQgqo9a{aM%C+v-2`@d1;er+~#-6_%OqM<8|Y6axQ8_A{;db(y_;rx(uXVWrjY6RteZCJ!$ZKlFUst} zEeArEB`(YbF8mFbPOG1Lgn}X*CQ4f3q&}+KJJo&lXdjw`h)yxbn6B~&QP8BV{Sq+^ zy2+g${=z#!z^Nf>XDqGVg0xRxCTw`KgiD|78s9;YSD#KyJ$#DK@hyM$Lw9K$f8k9E zofQ(`y(&t(N%ee-$k-`$Ql+~@7Q8sB-tk)G9TQb|6c+&)8#(1d*Pmk#pCS*g=Re!W zej`K2-_061Ld)SVc_`CumNZx$&I7!u<=7!7_R=QtPqkfmhZ!8oq1zr^ft;NT*Yejr z2%sPz{w7Uu7}+uM8CXUo^#-kt-67WZWoENvYuxR9@YaqH9#G?u&85MpWH3krI9W@f6LHdC6uevJ84HNO*n~aXZ;3d2Z3JeIt36+Rha!3;gt_Bl zG;ApUlT1rY#`IML=wC&fV#{B(-qJv%n*&FGP-wqBY9KmH7 z;OBq+`8g2AdU}nVhLP&|P}kX#333~Bd6;H0;8+){O(w3kP}8;tE&tY@omJQa1x{c0 z8;ql4M;Od3TYH|LmujvcJ;HwoGa7pgxn!~TFC+_Ox0Il2x3ZK~wE^o-LwF5Ik*QCG ze0}Q!ZO9 z#9-7`VQQ%zJyrghs{8I6oyWO_4HbSC$Y>qngpk3JiM-|PvKlMeNp1vRSiXIfB*OH4 zzhn#81tH&UBtLIxrD+B1;6sZqD8@Dv@^KoD0J;yP>dSk&?it62kCN;s$-BpLPhHz> zn`D463rZaj6#M!Er6<>$qR+@O)~+yg#2Vv>&k|Jy5^%X7<$Vd(d;Yku#+7}yB2ZDD z{gy6s*g5bi_i#Qk6N%jGhYOB1V_XmTJ>~8MlVxHi_9>`OQ@^o;4EIjltH56@q0wkCnym|genTq{E?_Vr2T)-3 z%cx>e6EFySQHYQ_TFe#eWTBY~t{UtpbVQKsAY6~P7R%B~+bfT@W&_gck&-kg_TVwk zD5YmvGq}fxUA(i=B4};3Ng!v?BWMr=F-fb@9>az?{G+(f;RjPbK|^il!ui=osy2x_ zW<~=7{OhYqZ*S?+bE_%67War@6(;QF`*^|AqJDvgInYN;ahbW%xbaQ?^YVZk1?dV5 z@ZEWRA>Bw?&(5vi8v0taAIzmLjgyN>2)Dm!JT6usfx7q>`LmoT2j66nNCwMM7QTsG zoH!A1a9-b|82_Kuut{MLH+W!uO%CnepQ#6CsP@|3gP7n7NMOTOa>Nv_Oc zNO&UtbxIHv5S2(3`%;YdGy{_F^Utfjjt!yqYO@uTIfuAGm$=~?L+Pac(P7LE+16?% zP*tsbkD*X$P31J<6M+mG;uG2KAR5Zpb{-vzMSW$%%%2zm3un$(nKy6($k>I2bh~ScpF#8$({733&b?;NpS35--~p({b0%(w^1DhCWQp5pWO_&e)Yq zq##b+w6k-ex?N=ZV?DGO*E?%uAks^DbY5qz2elMV2GcZRjY#m)0~A&o*XShzP55n; z`wX+|AG7$AZKwS_a56%?|t zC1pP@*teI!UDW_@nJ#ai758Pc(NKbsyIp{Hr30N+(-Omxx<4 zcAwx{BP~ZFN(k#W#pI*K8eU`qj7TtS zV&LK;#?~X|g7;nf_q^;r*|m#rj_iJUe)$i`cD{*uMq24gMVH5AZ-=IH$8NdCNjB{l{H2aLP15hu1hehPa;w)duKBvX0N9vp% z1Fe)n-vk=&wm*WyzSw?#$7wF#QCUBee#qlL*T;UpeX1oV^hV0kS}o)`HhC|h!EH5u zEG6#s?Y`UM5B-LZ`ao{ZDp1#E?u_?b11R)f;Qy)YWJ_BpZ`nDKN=yIbCpbO)ywbAw z)gUNea4+(lLUo~r=r5x#*H}n_Uy3`nqv|@IOOr?)rZc0fi9b~mtBy7(-P&=l2a53%G*373d(aNFfyu&M{Q9|oVfwFU; zPTAjAt=yDqQ94jdrD(C!n<_h-oUk*kXq>L0K~GMV(H{Pncm^8MNECv=P1hAk^A@PB zSyAn@7m!ur>kjilI_=7X!Pyy(CH)JN?;^szB4IK5uQE^k^n83yr#+&)=%) zJ4{(#o?R~P1eCAr-CU85vi$qd%o9`zjpTHl4e2-BIC*ipipj4E8G()Q93&r{mR4Q_ zn81ukNHiRNVv%|~t#`^QlO~>wU;&xEnX2?cl$e*EMJ#!pYO@JdD${h7 z;!m7dJg5F!+;Eq@(bUr1+1g%L>`t%uS)@KWi_0@>d&^;Eb8%^XX|Jiy)L6XXhKaY# zP_eJ2ncLy25%u?X$YvV14Za?^MMX>Bh0rXn4fg7b^mT_a1I^qRa>C2=&0!W$v!Ki_ z&O1$wnsSky+%S&=leK55)%3GTrX?0;+RXJYEgwL-gJAxXEwZl?K!=h)<#iZSP_)Ur zQs!+K6BoYy+WNx6jx)`&l-4WM=vxpVa^5A{dcHZ!BJEAU4+p{ppOX%BB`(m2AZ;lY zzGYiZH|u7pEv_xEZQP|Gpl@s~FRiX`tsQnZ?Xul9mcvrn;doA_>;}G1#@1!J#mU>_ zvvu20nwxseCw=S_qpKU!BftdL-#fq&t%vwyp;SMHzPW~W{_A3B@QaHWR7f?*61OrJ z84*IZOHsrIhCn!qIX9XA27A;d**gNxv66!Gslr<7jovr%4BRmbK1Iei9~@#MXmAEz z88z3)8@4juE|pZDB}_b8Uqf}A<~-x^Q{G$g=>wdEC=FvoeXt`7mOqvCmywK;XG+rQ zZnUHFZ(JkvZ{H>R-+5x06%`!cHjPe^Nq-Cfk;+VqL>QoU{5$w9E2&B|(ByrfY@qux z_Fs!8*oojmE3c|NLy7iy#Za;x)G#j4n2l+3x$*~KK0wV_F70e=&$L&-!zQ*i7navn zHWvU9V`3(>m;@z>!S6Nlar;U6kCBhDkxH*nR{Tdug$OD$&MnK781KU;zEkoBn9Z2s zk+JJEFC{a!p_qZh7bdQfP&A}JTBfV77VYXwNylTNrP&l91YA%Ty0)U7We$b&EPgBs zij;od$FXFT)08wr;l_*Uq2tbGHP@;5T#5xz#AKy|kTM#7Z34<2BY_pm20fgNL9d&N z6%O!`)rv_~FUIorAU|KXvMM$uoX?;#g+-t|M65#+#92hz=?6E(PpKZI)ekH=uPt&Z zhPb7?`*dyi3&PLVMNT806*+mImW{?(Bmn+r@q0@oOv zo;@X|MaB5VmyAwW@EL)@R>X`HlGBW6i?S{PiRsi44LFcSP+K-v@&a3dA7vy>d8r?t z(G#Kg?!Ts;Ziti5RMU8+G>s3>aZ9R=w~O5QtQgXW-QYDl;Uix%G0e!HbBQxLaQ3&v zJ(_pO){k7Mw?aS6?{*+5&{+W>lwlipBp9nnOrUUrtl~_&C_|W#6Bsa?P>*?Fpnsx` zci}eefZD+LJcppiHsk32a zxVCE_@CtZJ!zlElp$^N3w6#3bq3{beT{AnWiWrI>-KZWcLNKS!aqz^S45{uppqQ;X zUrhab)QeYnGP$HiARTEz7z^!358B zk!iS(Z~4z6SIv?Ps-HjPGOQxE>32LN6`T3by|X6=Dj(l|Z6P@H+aWvD7e!t1{D2;tfMjg zt#T#>OutDMlLrP4KcEGJsU2^Xb<;YDQ>SPk#c8Di_Q;_y(5huq+fFMMD&?zzi!j@R zK!6ARat723+5()uSV&LAv^yQ`KyN4|QI&oi#gJLZM<~0+fts)rQ{mEhK@zG$WIc&V zE_)}$7IWWw(4^HBr>TTJilH3{M3+MwCV8DjAg$%{ec5)5}=xgm_}(h&B! zKJ~sM!0h2nWhSOMdoCY*Gpl25eF|wqPpcu#>qt*6%c~;Qi_^*sdx!!oSt0W7dbQn$ z4Cc{mk*Z9kiMmWDM~qWTvx#H|Ws#7n2iIZ=9s1w>o z3h{p~AdE7l3Dj#ff)~aZo{)kZ=12$VNF+a-A{jZrNsR3OIwiyjPhOCd?rwQ9yomu8 z!qo5^oFpHrR8^}WRFQP(iRTD{!Y{hJ=dMDrlB;x^I7z9%joX%bdVW^_h{7d2Opcxm zSG-)SMA?=8m?_%PtU)iE(>>iP($#Td_=tg4v-@FmZk}dWTvcU*T1}{u9Q2J3;?ON` z+BWa+bpy>V%&@@z*Wn?&pq083q8~3m7e!C<77M^iZMDD!QoIn+Vq)m5HN8}d!RC5(-0^sa# z%=wOp6fNVFb55cyoZ9)gh=;m zX;{tPXt5_s)j&F2SS^yrO1M}%+yxpicY0C^Q9GtfFnLduO7oD4TY3aJYofO+P7#Dp ziq3CF&EI4o+!rs=WTM*d^q4rUGgvFKtqCdASFE2A3_?J^T0z+p(kN}nN{tckJZ3?P zV~!eLH!7xv{jd%cTI4d>a97PE%=w9vz3;K{ZAGJIC8Kr;)6K&PTDFc+-o)r|jsnvS z1Fi=QS|>NyFFnS13-z^bvU{NrTc6WJt4L2RY(s%nnWK=MJ~5GE-O;=<&y0i zyY9ca-03VUI=iHpg~SeK4n~t!;e;c{$2~r;RFa2j*a?vQ0{AmXNMTw^adxC6QK)AK zk4*AVsUHhtKv#%qij+~LEETv{K)lRIv0f=zS+HN$U)`o$^9 zf?YGc7oms|XU_3YDAYqE&`Y+zXgQo{JA9$x{4#<3MDoOSpb@t>C?-i^6zcXX?MoMP zZb0DzScaObOkCI|o3C1?bZ<-j8)6MB{`Gp*;eB`|%%d9(O7cx9Elc^?c1;J1r*&jO zWq=(9sZ~c}jrWhP86|Fwb0FypWwSGUH0hHp-VYG&3hfYU)~EF{v5Gg2PHoH31qkys zv!bs4!Y%`xEwcG9@~^4ljkqpMr3fzW<;uF z4=oD*tZ&&LMr-e)QPi7n>AT}ES%mK$k>Cx1R~zoVmuPZt;@>;J1|i5uKmR%g@5CaH zijXl=lkG|SE20QG_k@-E*s87(B9Y2voW}MXg_R#5xK4tcJO!sqi}aOsOJPphPn3Md zno-p$LS8#3^J_dsZ`i~i0l=%OCHLlzV9+3GL7%d7leO6bD9Oz;87;7nMPMRT@C%)> zCi`l$z8FEwb5G+KdwQkCBKae(#o0!VTrpRL&<~esJI${Up4@Tta_Fd%N2XI06Do9b!RM{<-*y0f!qgLIxVipFL2EneV<&(k zA~3p?ari9_os>$H4vp!}9?~KK9ylCet_?$VU#keuCO%bBm2O%XC6*yx)G-A`m9Qa0 zG@k*zAZ_Pr(ZPq&kfo7AZ9`IhMKKo2urf!bI#<|v`RP!#i=g)jVTW_6+AhA(5(pXE zz-mqckX%^t9T?qjFkR`VCF8uHD2IKV9F+J*M=8{0n4%Tx+DEfLUnVhxl%}fXQSi)Q zt9Z_&qPT0spMr-{F?H_Zn$k2+iKLP%PVa)nc7oE zvvuK^9exD60B7kDbUJ*H+J>3~S7E4uhm_$7j9QLJrC!u55HoNurocUHL3^CJ6jiR= z6YRMxT_N8C^Y4>C$UzQUuLC3UD9zUn57G& zKqPzva=@z{=D94$sRgCG+@&?+Z$`+Hdzy+Eu#I9ilo>)YM-r_$(g(h3aV&fup zO^39tn`e({*^0KC=U1?s)@+lksveLilq%nuPcT#^UV+Y#UO~vSwq=0~O5ET&oKorA zp!))tzXW!uF7}Oy+1)c1d<6LTBM>njc=yqfSY8ookwuk<|7_Qp^1g-%HB=tofyUvd z@t`nQWXo+uY~{U?hJPK75AyWy-^Z$`TzB%_;xz{>@mDy%qMIx8rWm}G2aQdLiwk*_ zZu}$RiR!(92M+D-D_-W~-$^6O^+UOCO5!SC7GusqA2FW<-wWSS-_fq)fR7A62{nEx+MHBt@6BcK>?nyX zsf;e(bTUmg2ZTBu%_6Ih`71ym$dtskm2hq63gF5M;mQl*&I#ep{o4xT()Um41&4hF z(<%Ew)xC4#D)L@TaBI{Qntis& zg^~Zypot$NwEu_X3Au72Nyqjx4KWKFOgtUpg^{lGGc6W*;ozkOkPd~C${S4}Yuxj` zfk+3G?Q+n7fu{<^P3c@xCbxk=;RzCzb!z6?ByrA7AF_)Q@g}FlBxMpOr?9kn z-zBI_)}lIvs1HIjL(5u_bqi7*g48F>ElI0oGkZ}j9^Lv`b9qZ>w@Rm9>3d8ANwGmDRIh!}}~0ZUMU+VH9oeaItIbqOG3ok)q}@(2&uPgkcb z$IK}HqcF>xAQu3J?q=3YZ@2XQc3fZDu`ZhwzI!|!I$^5qj*I#@p6;I6T21pjgyY;$ z7F%cFGjJ)`%h%yM|9_B6w@kQYZ5$w=XzBkaa``{8U55V!a{1rXd+-t_0B>rZb-hKxiZb)SB3$4l1^?}^{+ zTi!#?&HW=eJinO8!>}j%Oz}>8dDM4M7`wZBQdpad=Z2`9r+C>P=QCc<9nrp$oeqjH zzWFoZ+&6jjj0#8FJ|I6kjm#_x2H)h)5p`nrpfC}{F0XR8NVRt$$oKT1P!q*Tr!`f1(pjDaw(^_H zSl5ps_jg@1*+CcRgac1{^axl7D8PcFw~#$uA{aRk=e~ge>Ch%tgm|JP&}O?5Ht>?# zXvd;NyUV_dnYHd_ta1(04Gx%~`%)5ph(0uAxR+)cUyp3*cGg+tIMcjLZX?w8@eE@d{cr21zy+}=>_2s=J_S8Xe*G- zV+^#}%3E#OU3=^e{KIgo|KCJXp@tm+Bkh;&l8^+E@_4(=W`C`8GsK1|4%;ba0)%5bAUyA@vT21`=4_%q{LsQ`V6fiOc>%AwoJaQ z*An<*!?;L5b#^!uW|D>d7qjjhjPuYLTEB*hSvP{XgIGZ)B^PojO1#LR_9GIk5ai{8F$GO7S z-#UUrLlP7DqePP4B489YaCBdh^jkqN!W($#u3{r z1!VKFj-+A3*m5GOLe8vAL)_D~OZPAyI-O=N;SwdcdK4bfp|a>T$c4E5J8B_9cc#Qg ztGrlJ{$m4Vq58@fSGbHOGfLbgfYQTXVrIjt(?ijE0PpA|*zZ=JnzA{dQgN^wnv{Lr zD04BPAp+5M!niJ z2(a;FXi!#oK`cdWa3q~Z4X!=|+uJNe4H8RD`6D*FbnHG!wSN}B9*uQbIz^FT+eMo+ z0>$jRS!ZZd2Q7^-x2{Veey8e-Q?NOU*RfVissxRSpqqDzMrmA^mYq?uZ;7=*Tj2zC ztg?G*?I-+8tL4Ci)Qr|8JO`53k9}0=da2xCmoZQeh^ra*E(8cmY1i}j%s^%GuX8(@*H~Xg z>t_1OqMr~-4`a1i6bZ6lnPaEL2GMH5#b=ZGEAzrpK5&Fyb)Gsb;)dhkmYKUW{FPOY zq;D4`Ke<(%9;RPJwc`>b_jnDV`@5HMx}TNi;jXH1fw9)Ymx*zD6E~7n-uV@c1&=Z} z3W19oZGSlhMvEieTSO=>oD+Qsqpd)THI&tuk}!t2t*BNo1V#21jACK0>jB(of4I&U z34?MRaW)JslC)>5GvKuPh9O0CdhwhGma#yb<5s7tB-LG~{b_%p^b)JsA>pLZVB zLbIu(>ELsQwyIOj%}x*X-+UWP_wj9DZFoH@v@O{I`MLS|mhRfQ=-xcBjp|}MY*F}J zCP4ZDMUmNaMv~R-q5%DlZWU`y75&OC!XBHU*Cw0px77H(q3!+|pHlRKo}Jd(T0=)q zQIqVvN8aoax|t>3?(Q1#WFnFp7_y|CV>_4QKYE&G^L>~-6 z87xL#;_F2sX2!ZBZrh=FWJ1-WB~E1NHS=Q@xZ448giQb#?e`LI?we%IvM-q{K;~`4 z857d3gF!F6%k!TFG?#anBu;;bn0|7eC~LH=Nt=C1l*17l8bE*EjHqjuO!m9bb|}e? zr|Ezlg86i>n)!7j6jPS!f`HsC;@$@@?*zeed!De-lxhpal(51De9gU~Kt=CKK?G!? z?5Y{GswUE_LSE>+r2I2Ru@7=MA|-8{)ltf%Uv|M?rzgpeF{*d^*G8cJXwt<4KG6rE zlL<%<`rj?`068`^s{D>-Y;{XfIm%Zi=+2j z73W|bw$Hoj9&Ge5$~lk{fl6#9kiKnh!%uA~ z{2+e0r$L?ZQWd;Z1o}dc_Z6AF15JDuuozM%t1D3I%C7Wd;ExXh93-&HrmYw?&k92x zS#>PqHN^cS^}~Amn4CA$JN~jP5hUdIshRZ}WUg7Ib4HZn6fXRbOY;M7D<{MEp+i1` z2^Fmkia7`8q(VZ_qRW|{*_fW;M3vM`E~qUoc$-=R7^I^bwccS-;ENdO29UF4{DvFv z5oEXO+()1#WpD_eUh3wa;L72t3&EN*gDMReZxsuU<+>r$mrV z4^fU-G-cW>C={`zU|`ENIrxx%_~B=j%-ro*hm?tjlo57qtm`+ha7JQ{KJ=)b-c5de zI&C6C>0BXv$o1^`NC2mY@{lTu!zs#hyc1zTTSQvqOMT8FMv>&dH7+GD#+2?@qcmeJ z-f&e8<7wtUBn0c^UJ7@A+Je1mAv@s4%fSOZK90E2drhbs(YL>`QDGHhj^8rd#w|<_ zsW?VoWggKs+=Q1f%A27Wu`)nV$Y+a_a^R>&!bw}LPzJk_2|=VgCyAtoHQwUttf^XY zTY_hQ=sIjG4KO-C%wv9T6<+Rkk1Ki*;_@e)*&hez)lC;WBoDqNees|XLv5gO_mIva zkry`HEIn)!yZjXveh|`unsOt=>Ozc}LWr5F5V|aQ+m~LV>5blOH_`xeAQ0nJ=o%Vd zHuNY6+NyY^N%k;Q_b{B+$wF+{ICV>!hH$KFB8OIkm;AuQwB+|_C~6#5++Ri1>bY66 zP7%IL4AImP&wM4j?93$#wdyXB@($JGDpo<|d3FePzB))4Wxe0*#%w8U3D`WN{$oeFk~u1@fi$-}yf{d#B(| z!gyVGV%xTDCllM|#I|i`V%yflww?TA+qRRPwbnVc&fXWhR-LM^`l9dp>*}uVr+)AA zLhL*jDqI#)-|~raA()%^hZ2J|Nh!qyOksn&qy&1V{wydLIq(IG)ja%sDSsayObrE@ zygEejUr&_1{4#n>6277XjLRO1R`Aap3(9zFI_3Ja@u18=z`ow92bW^- zRpM})1^%YMAg9rhmcP+9yhvJ+>G`5wvr5s zt!3C>fdWFN_e)t!?&nAA;*TldLu;sxmShJ@QWo{>$)=Y06-(n~ax`HrB?HDuv>5MRa+HUQ`-FQ69R!P-FBYm0Z8v9Yk#{XwK=7>AM%hFEuUmjW|^jhM^sYJ z(wIrJF=u2`B=5znWyG!io`Cdweo#J=m+f(pVu3$ie$6PYSC``5KhH! zhLEi*!+I4c63X-*E7y~U)>Sz$O9t-pjtinpdMt(4XxWP)xeKNRKs0DLTm(1@fb5#_ z7a1~D+6Y7E71szo3YKk!mi!`8s z)=EQhU;5*5YOqOKf#l!*)W4P6GA!H%YQ4&TcZ5kbd0Di(5R!~q5WvIw2-An8efD5fL=m`zYAuRd`cKh6tWo8+5lY2wGQGToC7-3gklZ$m%{n%yRcfKrY7}C z=hf9s`Luc!rCEX=IpcT*J=PLgRo^4Xtg1Yt`Kg-b9sP6iWJ|X2m9MMjPY%T;-tXrL z=no>qywKZogRb^xKY>-vDQMr!s6OW#PW%#ltjZ&5OLei@QEi> zKcglLuT6)xa-wFRzA-Dr>+(>%z66nWD;8*=cKJ>gK_8_9SgyCNDkBHs)_4_ zt>!~ztGxLXt7q~d=($?P#sdqMUAHH?I=jasZVq>-v)4#+4M|xa;$}~mkB`|fpO;LHXtcpQL+?jpP zsB64PC$?2dzx)hHc1(t1`1~zAC{3!R@mBq2^mvY#iF{#wDN__5#Yqv?kEMpKb!jDW z+}h;ns<06`qPY5M{i&D?+qDA1g)2>LefLZK`v+q zIkiEG6O*P(tnb)=`j8;g(oFglwK@*^(b;JuGC>@>N6ovo_@Hq3KydhAaQGw)zQ=3$ zEwgztbNT_mUBB}F#Iu$)&F-kqBY6>}TFhn%2HgW#DIp+eWf&Eiv3#@f4x!?9Nk?yp zM{k@EcSW`Iy~cz>u_9ropiLSg5^9xdZ14kM8O%t8y-XpuvEyND(~RBOc(Ayc$$WT; zvGlM|u)dP@SlHMy!=1n_=sdR=aB(Wey4M0%D^9mhTqc^^(EYw+NOFl9U8W=hM2f6#N+yN=ef3dr4 zrFGl+ADcYRF#tR@REcud5h1SC29|EGxD1#~v?=LkwxBaOHM)UR42MChR{4cGc)@=V zgrHZP$W%5CnpZ_7#mv;qb$a^H`}_70$6x&BSaA@K=1NPEt}xikWTXER89zzEs7$7{ zid-miHoPx@TME;$%YS!I(ocEJ8CSW?Tuf2PXY{7E`eF9?+MN^Gw`|x5jp8dUbFP`8 zP{aOG;F?10eij#!o@e9abm>k&Pua1jZl zunld%TI~rwm8xr+Qiorq9DXQjG^OE=!F-=C*Z$0m0lrwOzlk9 zifgiiQoGI{4kOci7JnK5G|(^)(AtBOKa8k43Lg=!sIuZw&oDUu{!;=58^R^?-V>|c zWL;QVvx@-F#U>rVCA1b5{q;Msgl<7w{WjC5_*i7*6GP1z#Og5KNsGzfxjZwI z-s!<{z2bzCkj81G!Gy#hphcikE5DH9pbI$DWfBa?Sqx132W+c5v@6w$ZCk3ra`ijv z(5w{6_3H{&QmW72>o#3m)XH=(+pViRqGF-1xSrpcMIwPW$zG?pj`^p5%#>bw+sY%p zFPQ$|mOrZGCv*cOe6$-9pjeN8GhrjQ!3gvhsp%A89~!;#-Y-<}kdFw!zT`VpK;M+O z@-UBo{mp!S1lV3Tfe42yG&`aUdUv}foqIz99=A>mU#nq%c2e;_q7YQ;i=~=BD#Krs z{nbS$Yr#6n2ZDs~kZ*8+YNI~3p&#vlw-9ei{I|!B{4j1(V84ZX4G4n1QE$Aky6GzY z;&yqMKNx_%>2~};aglCn{GUNP8FoP09tlGBg@MEmZ;XKX9cO%vqdsgN5xvvo4~Py2 zfNhiFKLcvFJT2 z(+io>bxpEDnuP33x$0OGZlg%*_%h%ORla`q=zkCT|*5oVVSWeOjiDS&E%9{SmjoC8A=&O zO>&XV?>Sp)(ylU<`q*&ijKk>|ZVj7PQDDfIu2AQgb0|79PC9knx`!bNFkYNeo-K+QFLp{^O9L*2`d z7+0TK^J4rVu!?k%&=`_4$V-1h3``g~18s1}2eGqV|un1|>x5Ir=!t2~lM)&&(aGz@2nXT;g{Dy>KUa+)7%pgoa6Ao0FA1dIv ziDM${crEQ=k+661KY4nCJcv|m^MPYn(z&yI!ysT4!#w4ZLgp@^UK4Y+vZPSV)?g~y z_-YeyxMIiti*F-t=CZ)hIxxUfU|1-QF#vK}>AYze4lJ_r4^nA@Msw6ec^EYuwqzls z>^H&O6oVz6p#oaA(QF&*+V74H*Cw4WUTmWsN30s;xP-R*@{L|>EIq0`?cW)2;zkx( zg8SubzjZEJ<$5vfqXTMp$U!ulDZwlP1EyXo0-EaA$U14jbcphVe~b010uwuGNo-vJ z-TL|0KUUA$2N;zb{uwc=WbB5Ao0OyiY zZdZ5voAXF)ED4bxc)jen2d)N~z{p7jeCEE0B)T;7?L)J3L>LE^raU&oxi1vy-={Az zo4M+WouRB_jZ>n>n$k_sOIRd{+yelw-BnBbT>Y zI20E?l3rcw!&Eq>mtGGm@5`&4Mzv;-uRvdivoQUhCGZ1dxl_Gl`I~tPviQ_0nPDU< zsbMUQ7&XZ*pZ3?G6bN=@{psS0qt1uBFpK#9r8Nj!T6)jN2En)1DQ~?vgtcnKn84mtzg)KS@4J282Huv0}^W z>`kge#51<|Fv%M2wj)wj;1M<_)Lz)BPkF2Z_*rLt(!{ohh93B6^WIm1dH!YK_hNf0 zXdALwZTUyM5Z4^y$OyB2LHoh=oW%6Z$&oIkt{@jtdAJvspEtVjUX1@SmF9fCP2KY> z*(e+I-snxj;JA~ca7t;gu6a#ySrNot%TV=F9BSb=L)yOB7;;&PJ|7pG2(fxbt6`Uc zm5c3{77$|M3w2xzi+^ZU6EKFNF4GFhY^u;xxkQRUJXaZ!ZMq^5NH3EZHoeFz$UtS9fg-cevY%BZrlS` zxeILzdd5}8c&f8tH5iFLDm=#CiWr+7d7Kv6q^s%zW+b^fDGDI?6fcY^R9hJ18&xhd zQ^WzSs5nCH7qp1#ms6#hDq%rewxyxa6~AAoIwD@!9W1T9hi3Z}S^mb2Ot3v@v*eH>$ayXxM-*=6ryuWca?8yGx;GyzH{Pe6|c|Uz9TL}%`)5^#~MvjOI z0S0}25)@C#8_kEebvFM5gBh00lBRK9NxvO-$q1~*@!RW0>f6mKP>m+VF+hFR_>>UH zG+xtFXYy-5Hl>e}eYNA_^SbW1XC~(xsNz%@{-Q8VZiF$GUx=n>1dTU_dirHNBFS-= z`*7Iwu#a6e_&o`MCz&9Y8U#XxNpJVIvI5nvjL2O)dAAH(N>5d;P=zX5vBWjh*SEq$ zXRf3Wzi zWq?a(@)+%WOd9l!iD@vnf#A_Y1{vVs4->^U58;97&@I`1#yWaZia9~~4@?!r>ci^a zDfm_kM4~XreAe!L89D^?KLG>@tCb*_2V5R~#qi3Fq->>`5=d<}uhJoaLIGYa0Y>v^ zUTOb^rj#V{_~;9&*0l`36*1^jZEr%o-leM81y?FCeCS>14+Mc9p6 zQ^OX^K_g3a2ssq^au0XuspC9N5&Wh!U`r?nIU3bUY4ZXtsc1{CDdkjvV^d&_LT({_ zQ$jtpP_DX-b9E#Dt|Hr3mFX??EU&sE@k&ki0R*kIQ%hRD4D?gRW&WO8G)yG}zS89( zW*mT&Op}Bv37+!4El=m#<`o4CAE!onw_{_S>L~;C0snlq1JncsF&+l-(PUZL=dhBArlGggHvvy3%Y7y5|O{#=Lwn66D%L+o? z6NUF!&RGhsYzO~$*oN7lA9<&&ADXvcx}shWeI%QX*?OyGlv~aZAb)t(`DZ>I`4mKRhJ#(V;#40@kg;oj}HohSexg_CTVbbr1GM^D1;PUI7-xxI% zVy@$oy>u6%df}R^Tw}(R;*#9Jh?B)|idmYS?C3p`+v0T3ASe)vHRrBJZJ&n*wobW& zAe=23a_Y@*lhc2Be{=cfX-6UE^vP{%P4<(t-`?CqJTBkH*?KkCk-$mB>=|^h)tb@% z5lIk_azm{-PLUjW)uJ0%Q+OHOa8Wv=I7v2g0vkb%g&np2hJ$;8}`F|6AL| z|Euvyj+Xs#iok~a`KVOuqv!R9S%x1Xc>$ppSwQ(~WKJ`Wb*h4J+z;YT$+S0}4JGNm zdpL3L;`d8}DI8HW9O}0356wVjKeIvOI>XA#-JY-_#+K~NTM5)aF^ifS{knbjyK*o; z(W7d~gJ@<}a#qq7nCcmKE|oUtQu3RDtP(I}P?M9+R5g462+^yzf?9`+O{^I^o8Tvu z+;E`H4vws3xMe<-^TcT5lhlh&o!_BwxZ$^h6zA9 z9T9UD*Wi<$K8}A66oA_!EFluRg}=r2LFR}SSSa=W_}L2xNGY6DhvuKXf%xC{=KmJ~ zb#yfFU=~rbbNg=w`d?IPNYlevdolgHrkP^w4qZGVTY?A*(RyO2E>PCmh+JKSrc}-vvPtR}^k@mq&K@r`B4k9On_g zWuT|kBHCdFX*Mz8&#{?k2`+L7(-{}mzrd~--B zur-l-ZSG89_gNzrmgOwqGb4F_`p$drpNL-+mi55M*H4Xmv>1y%YxFSV?UBVGk2;(9 z@j@DXe+Z@L7(63THK&aI`CDO3f)x#BghND`q|VsTCr>!8RZGFZi3A^ax;x#gho4BY_clOO${FxBAUtumbA#SN$7iFd5*mw zE{hX)BGM?NFmg_`q_ig`J8@Y)OFDKH+%>FtXhBo_!3`tmGW^eg42|VJCq-6;jdXFp z*9TtTL5)5u?lp9&a^2=sU{!L!FKL(Jgbr@QfjLkR|0f`GM9E>6fru>4xm8ss z1-s5F>hiOWOIKO5CBN$b5elZNO*`gt@%}=L7>^Y{XbZ^>@MDnxce_9kH0@`mwVO63 z-;B>j83?@CDd$Ua#IJtBqzJdNOoz5cR1_MI=h|7y2Wh>^#Zg3&k5bYST|Y92aO?B9OfFFfn9U@n5eDW4N2TFu*Mbl z>thp-bev&CHKN#~bDZYxodKdGNv?{a3=B8>QO-)UXe8pP?I&<=$x*(tc9sw50t;%r0#-F#Zq;~HWKVmbzPo^ zdTb<7CBmGf2{G4g)v$MPO!74a^P4LfE8!E_#nlcOlAhvJfD#a>UAZx<^LRKG%Lved2VO(>AQ*!%$UvspLW1i zS{`p8jsNIa^_|k`94{#YY;Cr6TV)e&Pfph3QvgqU(?(sG<6wr@Wj!6-Oxtsl;}yAq zcS#t=&Ph%hQdxEXmV(3D>}T!Mdj*t5)=9X(y^C6b2$6vUJ$Dhy)I9~at=)-%*2^K742>qX9eb5B{>;Nm+X8zgH_X;+=jJ0UYm zqA0enXPP`n$Rfn&5`b}3Kf=gJ{EK zfa0I7fb>p`K#z;HWc&ii*?K324;|E!ElpyIMMPK#m~lAuy!H!_16MxShya;SuLuyWwoy)xFV^w~GgrZ>ZLbx91WiFZ6YtxU$Hs0IfS z%CQ~s#HeAX%9l+gjQqD9+Cr7G)0PNblqAf$;}rlMlThuJ)o9cmp?0mS;+%BR6&r7q zl{MmR`YjSPWTV&s#%pEquf2LJsBz)A`Hf;D1%&mOvduHP)Pb6p-4rd1-?MU!Bc!fL zKfwG~hDiRl>pyl8Cn_=gHK6sOQz7h7w!~RC3fNoCv)}S_q86AWL5n0BbvO-PWFXbQ z?lGDT|wdctXDCOqRpAoyuyZQgN7vYgyQwjB=5i9IEgUHNq8H$aWZ&ebVs;L_htRb^!}20C+HQ9XYb87hXW_mQB;2+s(O zhE^HP+FwXyJAlI*gBrKMus!!^{<(MLx$hI?-%Zd>Mc57#!hkk@fz|ELOl2BqqpstA zzI+e?gxa#<(4zldsR?So#K1I683YMWy?j_>cCrC=icupziMOl*flVAO#yq(@{kl89 zTnGA>nd0R0o}IEUV8c%o0B$C+#^lchgq9Nkm=W4M{=Igew@V7?4mA4*)PezMFv|ZH zSHkP?JGyZyveApM9MbN}2yi3`@Rq@5S=MJNYiOqvSa5F7V08-Gw1JT1A=S2>5X=}+ zVN&*O>5@A>(|tuYu1zrJ`H-D17zTC{&hLnG`)PGm;oJ;yS<%pFApvMGs)fs5t7sfz z9fG|PQ4C+S`U)f4W=p+*JMO=Mhrh7t_dxa9864T%0j?1rOMmb45Z>q_zEcdFQ`}hi!QfJ{Lgcb?WABeJP8?=7 zRUDFz3M-Peb4nuh8jd09AfxB|jr1Oe3wv%&w|iGRyUWQO>J^A(O3}wHw}aO+s`262 zTcXM2af`rn*F%*oR6~^c9d-}$HQRHh8m6vYv}0!rm~c8z4~U#0_+#C&=-r(wI3f%I zB2Z}IN?OF@Cx%R^8AH5UWJk&!l%Rs$}i)#G5$RDV=OIC5`gK&D~f{COPX0mqJY=HAzE?>(DUTMS^s)(DA^D?bS zsT>Mlps8%^yeWyC^rOQ3WY{RZ&v%~%6V7DBsuEfQmdmWxDj1T7`?I9u?bOAxyz?1C zX|{*WbUMDv5#=TG-S2WmJCelWC5~Ob-uNhutQ$vMPX!K@T^ps4mNLbOrL{XpSv4(! zF9j&p^w;lEur?i-@kp<$#AX_k1)3SBqD# zVT4)#NeeuufDAjmO~^mkQ!-#^+c^1@0M%oTX2sj~zzu(aPgJ@ZH3{o$Aq{Mq;5DZJ z227T`*YZi#0fn;-D{DgtX0Ter9;dYxPiF&&-WCF*1>kwhmfVsa=EH2a{OkL%*HE-t zkE*Rs!fgERAK2#Lwgf&q00S03@S!CEV%R$<;I#$(DB7&odye$zu+)HlX2`29nRG)y zsBg=lw*L?_ZZA5EawP0&86GN$BZPvZJSe zQmQtL|J|7dC0Cmn92Q8beRyb4&6ou1_R$L{q{XS1b_B|e&J!8~2jfBzQT!fdAw1A* z?PakK*dP5x;RJb0DTGcVbcRNx{j=aWb`(?Msw4k%c|f&!ET#WqQplwvpHN{EeEs*b z@glY>xFpC)(e2PIb7K@dOtW*K8a!;JalX80tP25ujbENiDKd42pU`%UwE$SlDfMPVCw zVf)wFdL#C8llv8F>4LoA#NWZ09ZR&b_N% z2Fn-B5e`n|&d^}9T$!5;R+^62iP!zF?SOl}*4KARXM#MO7ew2yT*hMv#^d+!_ir`Z zE$g(Ts4QEh=#+xd%XgZQ&nfCFKLn@`j}@<{)?DLa@`*@wWCMjlKo2?GjPZwc`)+DI z;VnkoEfO6wR0VVTs2%gX)&|clF6*jFQ!Ufq>6=uVmo8}E+Q>USupafkYt z?-NzHR#zt&DCU&_G8ji6=GN*DE2qt!0@&O1@~!*d|A{Vm$YJS~5r6%fCi}l(o&O2! zQnoj6bTSdMFtIjPGco#U{QWO((WUht<*set(;MkB%veOfkxA1bfdh<9g&-vc5esO6 zz#D!+>HiKPVu|ZBCYK{eau62%(vzXxT=MgO0QO} ztLOIiJ>B&@nVn9XNO(OG%X7Tt)$P=M{e5|Sr2XyvAxT_;#L-dqdqt;F)7%4d^>xoa z5*LFjIML40LkNGn{l(BJ!h82<4(r1Z`49PhaW7TL&3-w(XHVL2s!%uTZE@Nknd6D{ zS61Ok`$%MRs>7%-29wuD(SzGV+U`*dmir-E2lkoVsZ_2HYx+Oq*@k*KX$;gl1xoI^ ztnx2uqchi}9%z5i89mry(eH{wmo)~JKji9GM5BhdyfypfE$@fg-pr}wlT+_sny1N9 zB0MQ{k5MOd7YMQ4*Y7=?1C*p%ZwCmE2VY~icWNta-_jZ|sZ zQX$1qv;#Lk4aA>Wo@cJUCpw})xm?BjH;DurG7N9|7W=mJ&D2}lS(fI5UKjcLM3(o? z*m#Z7^E#VHbIcj%2oPYX35+~_yx!}un9nVPSBnkv)vm)zAYe2J}RO=8aDL6z6 zc2mA`ba&mo?A1APWNac`fR6}!hr4cPb50_EFAR~?ZbZ8T-kvpY>31^FwyYvw$qer8 zG;z8N(RfX%rpEYjDSt)Q1usz47ded#lJw5s3B~8wC)r3Vn7CF-w>yca^AJ-eD8c@= zy0y<$G57>csk2w)Z;o@!;pwc!Xxxpn<=mnLOK!x7X&ZTBB4>3C3vdvs7-H&$r!n_U zVGV4Y=vN13l7uj-8g=DR5Q4_Mb$#8p+*roClKnmBBUh&yC%^-nmiAhc9p0U8zZ%Ro zxlqHmD^iH%I9*+qr9WGqi&=c?s>K)_*KQ?*_*XI!o2`*k+A@~3-=VZsLc#V|A>meE z_)!2OV#r&JMBYO__)+$g6X`>sxX*pJXsm=T-Tk3#SN~Gp@)!h z_UaV;%nY4nhRq}_b~&O@)5}${D)0L{`YTC5;uTh?xD_6En%jDKkWMebrR0JK7yCrw z<~2;7#(JB$H*gT#z~e!8Me~w)rdAdRWb=SmkWZuXI5m-?hmi%-Nn8C_ad08k+#m|Q zDiQ|?9a$j8>IEyyM2J$XM9yf^YkxmcauLrdxDzy>&W0R^ES-p6T+A(4rPSSzWEodv zzuKN}7w^-Rl@K#x=MIFKVR>1ONS7C=%l~r&J4SBdH;-)!>2MR?ZCyl*SyPFgYLP(; zhd)ulOq;oP$ZU+FO5r(&mBKr!6ne_XuIjNqxmQsjP5jIY1aA3gJ(bUT+M=s@N`(-2;r!OiE2}Ensxsa&a@it>b zoy?UnWQ`W|w=5lSp^3$3u9q67)e=DB=& zyTALk@nYdzfrMjVM%+w{k07K-kLad{KARZcC1m$JX%;V6lZ1!nNpXB44Z8nJTzH12 zOhOKjs=5l>P^yP?0e*RQb46HSVa1CYivRp~B84L_9AN~4c#bbieMFs&6T&$`5$40X z8Mmo-#t;bQ%%zmPy{RT5i#W2-bdwc#xd+1<;%`QgLQ90&!wg^i=Wd(<+OET8T?I_? zLa=qgmr65I;~wg$ERBW}b%B2Q>TaR&Lh{-))hK>q}28y__}%7Z?S8qd8>zn%&QWwIKz=_ zkqu%>*EZ2o$Trb5&F)Z+cBu>3D87OTI^u`C%rD*FvWJ>feX;^2xs3Zhwr`M|XC*WD zz#XULrLB{6?V_>TB13vD;k!Z%fKS^uu&&@Q`@x}sBSl>o80boU(dX77w3U?Z!InR}6EL*X?s))dTJ(MBQ3}R4YM&{p z8s~W*=RsNd3DHxtpAmSv8f5iC>oK9Mr7w~5D_O?*BG$=IHd}}4@cR>P&<<<;c=6|e z?kA0^YKoQ3Y#mwLS&VkQ**jWvrHCFbK$u&$u3GmAS{l&i87fEXX>jWt9ejNTK~VPW z#K)D3XApxO_mHgnNXaXA*Hr3u$7!s!l3#ugG_}ODENbe$y&P%oE-s3Xf*PlbTW$FD zsTqxGLNvGoIz?FES^Wyu(R>pzzNGVGFiO1K#FiFVs-d)a#8hF{0rTm{9F)iY6y`&^ z387B70VWZnkzjQT0rzT}PhYMJ_;@tsBz@WnRO4gkQUvJ&@>XgbCUHJzP=0`ZBg-U# zZT&G-4-2|1D9Kzm%xeQM#-xVS`he_w=k71;AFVpuo9P?YVzWIj_5dl?)ABl)Tfsl&L8i9F9wK-G;)t^18OV;w~HU_4cJH*-E!6>y5hn zCc0Vt6#(bi$OzNZuNmb8$KUe1d|4IQcMUSr~U>3gR4BCak0 zDT~n&jYE>3tpVd%}C(nWOTs{}p`yiWEqoj)oa&^ zY9q%1J)?ol-uBRKrEA0=dLS-&?}<;=@yyA^?Jb;iPsx=igPI7kY#P_7fZqflUHjF> zAr)$RIzbsK1sCe>%thLysX?P!m0a=TfXaW2pm|yu(;SLF5Dw)DBvtG=wYh9V~?Y zDq>sct_=cZyT3jt zX}HPaZ>I5Ou1A6N607R`$?pTCj9mt86|-mHje4x7!h5JH@6I-CR-wXWGd=kCcD*Yx6dc%?xJj5B#^z^)TTF&dEEi+I{a6FqC>>){gSr|- zU9m^Abm$aWm85A_8p`tH9c7-Wjrp0k1bEqftI)h=T)2N;N;8_QT_!7vfW zaH&kL8&V=#6UfiMM7{Ob#+YREwOaO6@$H<@>R1KDp0M=xu)8M?Hy@%=@5|JhR&bg# zzo^@*MD4SRs>WUw*#s(%#239&W~rCO;o9^Vh5EI&Q_FT3+q(GEh86F4Pk6*kPDqMd z@kiGR7T2OKa!8!jl3Bsu<^IHfVrH8J{bFI`HWxQ{FQ%qCu`bJ*4dwyT1$sL^ePCm} zb7A~|<0j~devm~&Iog}LRN9@-Z;lOYsCYP`Vs}2dR@^Q zb$gyn00KU0|Vb(u0fkb@Z{=C7WXh1i0mu`8&WV0tD3H;m2J@qhbg z2xQUt0q@KAAGoaMayYsWQguMtHwcJcK_AZ2Iw*Y^v5JHBCeD~Ze&IlVkt6Tg<=?jK zK-vkvxalWdYk?wA_JM@%%mwCz9Wb zb?zH>?i+aN3%cYBeC`{5?i*-M{;Mb4c99E)Km5Q@exh33!ZrgZqO;2J+>8|FZ7)}} z8Bk8pTe~x_r8A${`Wes|O>WW@zr&&;Y=B|FQbS1YAstqh)m4v5#YyFF4LQi_7%n7D z$1F+28-Xvxik6~Fj@6Oo&W1_M_xBd#B;LRhi4Lz8YrjkspRBo_s1Ut;IK`TrX-1dz zk#p+YJ?+Q~zc7-h!doi!-$KJYe*fH}PcMH1;B0UFzsUEoh&1}M_Qe=%9L7%1tu*N>XHvgimSG8(PJBvT#>RB|J ze7gKc8lDD}#xD?Q_EsgFX2R_Z@*x57fcfOEW72RL>T}?v2$B1=MyabEMHd=hyE4VW ztoEPpnh_7n)(dA|lK2#>2|nu!@!5}^ZNU|Uxirrh9t zOKwR%(BHU*$r~cQ&UeOgH5n5(!!)GZ4Dn>qfi$i>E6`phjU?p@N_A-Kdi zBg4X(v`b;eHQgdjB3M21E%BFT95olE{+}6>m1XpmWwnalYv8$j6)Rx`kB;497#2<) zPUtZCSaa#c^k(N%uQP`~8R2A8_=^eL29iV?N|-5)I4KK{Ioe9?h=1^rdP34)9y?24 zd_--!mO0gEZndm*ZxoF3nkcgqTSF3&ha@GzDaaxd6BIdLskI2x_2Tt$nSCw}#gO@y z4Aak7cH*z6Etr(EvtxDhb{9W*rczUW`7i^i-F672gL|lu-s=H=rNHKV?Cy+>&{5d~ z%@RAHNrhIHYv>5G3^lR-(GmA`@J|Upw`gk(P>aN&qO~occW5{pPwf@#rdP%wu`sM# zK9R?>r{TLqo7j58S+OD4rGy))X?OIA7PgEo(+cuZ%f9nNJtR^%JMmF2c%}pCve^mE zoTyaxT3R!n$w13NZq*7CsiqgNbV28u+e%SKZzqf zpc*eLkZGP2=sm$&{BbwnrYBQ$fD;e|&>qV8>DA+Li@B(oEm_TbAw^s_w8pd5Qlw8! zo^$gIaInr4pm8A7G#PW$LdTEk#m-dmZOQQrqL@PsnwclO(4y_Ni16kG{((oUxEoko z|C4-lxfJt7eR|1lCD4B|@_+);^a*Yia+jx?eC-QAE}8S-{K)A327DMHju=PK1iCLY zB$`jn07E9QL~eB2tMRD1? z&UyDrfcRT*V$j!v#=A|?`ZXcDH^$}gGooD&g17JQA!XMo)uk8FXCP{v#_gQ+hL|?W(stb+&=AFjdyn^`PP>c@cQTC<}{I zal68OzsB>Cu0P-BN`VJUcH%&8vI`!vPa(fo|JeY{kR2($wFO6i14efaJwUP8ujIBG zfM5?(Qm{67WiZlUld(3c+{c5k@F!s9f1K1Lte>3KgX^jvYBfwEm2`olB-YwMT-M6w z2{zPIEok{VbS3^a;7u!1=Bd?_j#Z20!RJLNVlw}Wv3HElv|F}7JGPy4Y}>YN+qRRA zZQHifv2EM7ozBg-_c{0Mz3)9|d}FNl&-3#gt5(gLHEY&+qIEY6svCJ{xk386TMBZj zpAJOaQLv-V(VnW-4?Kwz)))T?l7P*Av{VlN5OMe_&YK#J zbW%HiOoW*Y;z8|GBzb)vVfuo=D3CS=iJWHd#?%SMPBdH>SG4A*Xu1Ua;(zGDFUld9 zV3_ZCWK5<3ijhGlR;hA=wM=jE8Ja7q;|QTywY`0yE=r*mVNL4~>msl6ZXl+biY;&( zrFT31M-`+X?Ng)1v0jU%mD{Zu2oQkTxN3F=RT0Yt)?b9)Q87!6L18w3CHgQKcaksDJw++(VPGxc`Z}M9R zq8T`{i*V9GKUkece($Doo1AYuiQr@F$AkFAq=|ZtNiwx~1J(VQnt?_!J_Ocr*e>xa zSL8iE`mrG0RET~m9DXR50sWNv7~6Rg(PJGn1f+n28hQTJK)n8zdWU-I4{?%GFO`7j`i=a=J9CLV2U z@?HU%Yk0ri+!EJZ(x)#uQ#={F3(j??*DWr&D!?5lJpyA@DtAsIeKYk$Fj!eTPde~o^e@Y#Nth6y^4 zsk&f?e1Ba$i)h>7bzCw=b=}W4?pi*7XJWsAvpf4>V{Zgwb7eWdYyW(C;-#)77P(7!Qy&#^p%ihTnCOZ^?;!mw;C5MBYRV=$6sFG z5`Oz6w8-Se2mOFi9@via|MGiykfjKjr(FW3o@Hv|Yxv$YB!1qcwN`pKYceU!+33|K z<)|3L66Vn~+9*qzd)`RyRKSvCGg~~XUln_`5PoW7-Nqrl=9hkGdnfzLhTm#dv`1R~ zu=Bz74NQ(YU-LAlep($)SK{*>);kKw;`_iX#mZnPCx#diS8JY$v$)nn@Z%Ek6v99F zR6YYBegXa^2Bnal&AR;F4~r`Ce|1y@{)T*5(cH$=*-GC*Mc>NV`2SZ)T%`EVv3Sel zxi*@xH9P4%5I`cEAS^e)a>%$}$Z;w~!tSF`nx^8Y)*Xv$upg+1D4}3HzhVR?G~(U@ zDG(&L(y%8pv(gyv->0W_f2^&jiy&w|wVvk%dg5H|_+Uga;LuS`wpv8GjbUu;){e_b zkTRHmkF`HGVT61{iXtJ1cyKJ*Bg(jQxMNaaK-u&mVZ<;FPX4NpasqkHJQXTd7^Vd` zl^tT(G<93l0uFVsfI)}E=0=20;sN<-GOwt=b+0I#+|(7_ifKo9>1{)`f{EU<^Sq~) z8oeh@FjC*mM-j!Mteh#{Cht6{Ln}MM{Kg1$9!EY$kukJ1JQN?-cA9lEA+#6OXm0%n z>*JP`hY*sYW?w9h90xblDPPo>>){q$8h8B0E3xjt5QG{RpgAm0I2_-A2I@LIhD-6Z zZs+V*iHHw70|A1GNGZ@ds5N@_moF@Ig<+h_!$drq=t6Gos>1l)xivdq{F^QHLrqUfuLkiY#-?_BlHU7IsulJSB(IQn zX4eh@)3Ber9l}9QSVGmM2G}kPmaQBiuY5kj@l88enQsYEsNzpRK^~g8x_a(U_Q&Ao zQ|&)#`Fe*YZYy12mhV|DTKUrxELrU%6rALz?OE(HjQpN_ku2Fs#&wIYY5%%;R3252 zkl#b`G{FDY%@h9{H}88HrlGBkk-3w(t&OpfxRbGizLU9&@jsUpE81GQ82?vyZ&7tq z21^wA&k(w8$7X5{lX;n@!dfFbmKvg1`j0&OSMg0uK|EoBGvN?pV9BL+r_SO7;&>Gc zS`Xz%n0Ot&M6swuvCb3coPrp+#|gJidT_w#@Wi#PG)Bf_uj33xQ{@N7-uv!0lsRj;RVz^eckg?)5QUlBPS`d3a1GhCkJfj; zY0z50e!C;P8w)*76C=8D?Jf~E2TYCMOM2)QOPTyRTg?N-d%61Ic})Zm3?H9}6uVq# zz^)bv>FbHD*}N_WERuZ|DlIh_#^JoC=75fJtXWES9p|ukPz}6H7K9KfZFN8s~F5lN-z&?4h0ekT={zG@WKnB6Jp81|q4a zS0?DErg~wz24S4`BB|yuO`tahjxixYyLwVUr5@-~MeWDldAi^IQ-kyU)Dxj6^tbqU zZ7|gM!t@`=a^sI_d^8WcO2KG3?WOS5nHO6P}mLnL={?US8;>OkbZ0Rjbm%l>x!ov_b;eGq-Se;3_JTS()H z=;FmmU;A?tkq0*@ot3*nSD_EH$4@Ob-k@%&kU==@V)wj zYj=o>Z4wQa@yJfUpFqejk5(t0O;x`THX1p80%_l3&(u8j^1yA!;;7K zYG7aDtqqYcnQJcF$Q{|v;}NAFUy>s**+git86*{1BcF?(fZa=gdiBD-Gsl(Vm%oAw z7f)(z#^h=d&0Z&*zRWWvf5bUa&+Y-rJJv1JB{*#OJkXr}^s{6@edxG_n&R@S)3UwV zdr(w2Jr^uH^l(J8menN^V`ZYamM7RCZP`}bh7&p!h2ACI=$VFjxDRJabiyypi8(pO zI?2gz6VVN}rX$jYNg(gE#Sq(=b}{Gl|4M*M1s4)uFx?J=>pE%p3b@@+IAWlys}sNOgfy$0I5bAqwhvfCteOx;C(zQUtxps7Q- zOs%*;*{Ox8I0+`d6cGy5H;&t zy}G_4H!COVsY=C2rvTg$)@x(R4b*g;^y=dCseXk zwF7dIJ@X%6wU;LIn_Ij1<@|+`BlFAJnKR@phhbzw=Y{O1Nz4h2N6S~;c}zolguhau z!?4BT>FRqBZ&GBzLN6w(iCTd94V^ttM@oSjkxll zLAm3@OGe7wf{&pad_nFDUM%k)I;}XGEEemvb<`@u)#CHB@ps3i+W>kg!tj?e87LO_ z*$vU51tw-p7UDKVgXX=gMFF?i<>SkIMPreKuS_NZx9=c1BmqlkVi8vlAgkpJBjmBp zg(!`a?jQ#Y@^w1W!b3DnL$`Fa2r76q4ohj9=QdI>R{$hou5yW+LY5YI3Kti?GeMvW zypJR*b*of?0AnGLlbEhKs~oE_U{u9Ph*_?Z2#;gBNuFY8@gcWSFspNN?TpwqCVC1|%eg565 zsY>Zu28kd3>$2$~w^Je@97RsPq7m${$KnGIpB^PX-9QS@%f(ZBo$-5l=yi1;=gSYD znGm`-^v@lj7rCKTK?LO2`PA{tiOGwJYgWeg=gaq$njgvbzR-lJ^OEcl&=l+|sjPK+ z`D1#pt-A5{19H|9i}r3g?b^Go^~(wTCl785RqS18;MJMVvM-k~IOMj+2!bSM9{T2C zyS-(8F`D{?tyrINdV^3MW=Xr!?xoOQuo5m+ulc0@CxO<(iOQ=cV#~&wbdjv1pHx>( zfoprzIaEl}rw+aul(N2GOvTPv=skMO{(Plv)BSR>hr4vbNfry}h9PYnu0wa|Br$Vq zmtXlT$N|EWcuh^h=OaB(+#DECha&rtR!(0E5?v;GFzL0FpRH&oQXAiko>z*OA>5ED z=S0aVdrv}3N)WvXbnaGoC+>eE=E(uko>*BXD^$tVD;s2OCe}F&wv}kgaaH%Jdi9uh zS^Axi$0AyVmQt>hpi;A`)zbx6f*=*3I;gSOPYb{(I!%S7lL~(FA`i=90cK&!6ysft z$9n80QXY5gJwc$|*VIkt5VA`1BF}2TmuXMT#gGf~QWVI|NP~&Z0XGJ1{iJHsaG%qe zaZNYs&E5uTsPLq_2$B`^#?ypEGn<@|LARxsc{4)P&OIiGHA}Hevq}*4Qib&ruBX=; zL>7-iMM@SKU&qy-kW%F(%o?&St(4L42r%xD-MRRj1haFOG8CD|zr-{b$=4=@EE7b& z14C}C5$nPdUu{UV)@={d4C{zO9A&!Np&>!^YEu#?^7)5kEzXteP5T?>o`C%8E&k6* zM3KL7ixs|gYWn}Iu>{R*t&ANl-T$r3`lo`eNJZ01Nf}xD*agS+YJ(^9Nv341LPCFS z51R3W4=Q=NQ4Kg;5eJZ`HA`nLkI`{_A`vhw)r=Q9jI7Iz3{k!k-GE5K%}j|WbQX@_ zc79+0SNdb-#niyR+Ob4B3ObeHxClq=i7ef zH`O!2)gUAcPUS+ZP)STG4NS#N?m`=}Nz=E#f8Dp4OYLQRPY1J$KAr_^#wkB#db1-t zr*7oY#N3X*8B0RTgaDIq+G>+YS?p?qnn&6zKEN#Xj(Ys4sRTCQ?2QszI%}M9(WWhg zQqAsZTbx#o@`~P*u{lI#-MooQg8InFXW*`61?;7? zh7j!fpcJ{`F-AA(u@HW)^Od+}|D43xtKt|QxgtCU0C9g2fg%-nY0-wAYu7eGLx{x~ z&f#ry;lKrv8<_6~c-eSlcsrz*r!7hMIt8-19BE_guXZ*I*pfm*b8Yo?oZ@K}^Xarz zsv_-^7B`}~4$q7Zfrr_2a@}exLu23=O0Y_Wa16OX?OlA(8UQ|EhuNGrq3nP+QD*oB*uB<>#xIS33-=D`u z6`Y6Y(k2eydW@T~XX$j}geE9fPUnZfgiRUS$yeEa|tg?M<9J7$$oMNs~S z<@;MZHssHcMJ+{5XIum7VCV_;-uH8cx~P|5n>c>s2eoZ^&r%fLm$d08sO&Z~0n zutg1rT!~8&rSM{{WZHn2HvPt})jd^>p3uvr8tp9vd6?z99AW98v?xucQYibr9|8@O zyNq6i*hUNAz+mJuZZ*_jNoOC9*wd}@V{ZV@vvFFk+9ftov&!$dL z>Br@PyEcuKWp%<(&+nBM*US3Wrd)bV6j1MTnr{ns|$xkewMM;>i3K+U+ah4q~>-;;kFAM5M=dnuV zCTIA@^dT|%3GEOsjUYu3AB}~)sff(|3&UVw8iPnG^I{7tNr{{4@B+FSPpbkI4gyX|R^A6v1U7oYdx} z`g1u5%O$?fII{P{fh~|rCm<>TeaQTxFNACd(Pf`O#6Ic7wib?8kJo2Vu`jA*5c&eG z;kMGO*U&{Wh+5NEb9aN$m7i4#VG(tz2J?vzyF+GaNe^X zPk$}C*9BqZnB%a;V43@+sg={7hfKy9A; zxb9)QE8c+UU;yqN+xK8Nj%XB0l>NyS&Mi9&m_KW6PA;kryj0`9Aay*|!_@jzbeXn* zyFApI9=VeY9Zs-b;;nyq7Ka*DUp4^a((+7}4CFVQolpJ?x(eAPuhUj6M|X&tLYzP#0ji7L(}5W=+Y;Dn_My?h51HD;MrKYB@f8ck1Me`k z@s(!!%1_6H(EF9OB*)R1Cbmc2a*f%{=L9j988KKHFd~SSUW$OI&VPlM=~~SBWf*Pu zT_(QKt5Ya$y#{WC7(T=>dFONH%uVColKB%|Vq-$IMG$jq@&f#Iwb4MUyNtf!(bE43 zkGTE@Jd#rWH#9`_uf$)LimsKWDasf2yN>SHroh@diFAEZl_pY2)On%(TA_K%BDI^O z!V$}9ypwfJR)nMC@RL=EB_CI=ut2%nFEk<+YcbDL5{gFrH9E))Ci(&1+h6dAa|1wT z2DDsKdk{op*Y6iZMIYh}>Tg|+)2~z4neSQK?91IB$1z(Vu>(zXF8WlFo9J-z>2l*3 zOTI|o$kW1fQ5a1V8Y=})P^j5(1t@6!t%2i^t97w0 zbfFX57aUl&#ydMX_ihaAcc82q(INsyAlB^0q3{5z?tcW1*Oc{bTulM@e85RnOo z>;hbDM@buDMT41|+{Xvu3ysl9_cHclWgch0%b3pYb)v*f#|JBD^b67yMys-^IGWNW zKjZ2gnquuJWPG-y55^-R4i%{DP8N>A5QX5cPKWETn)umMx^=NiX%_~1da~JHOyG3VEWml(BII@1b*BFC< zwSrSXRrl8tUc~P_yco{%SZr?|yvPV~?ovHgyk3qOcehU=N2x&3EIc z7OtI#wS_3@nWS}0KKTO`{#MvrQTqyR z1WnvvA%CdEAKufvwu9w)8t@2W2IQQ&m@-0Eh#gWa@^DVmUd=k)1qOGTE;eocS!h4_ zb8KL@Y8$B}36te;&fpZM2zDGV`HUXB$hCni3OvENW~6L0xu#8KQ#p>&(WdNbF=d%S zjPCOiCQ91eef!gpme-`69e-`-7%UoQxW=^NjJ>nrvK4Gc@!JM3=TI?D7W6smR{3SG zvt=g+w-tnN%Ngouec}BEd|8{0-OZ&pb`xA23n$j)B9_}NvDvL3_q`T(CO(`}Lm|#v zL!s_-!KI)C!#%W}10~|?$I*CgBo^HV>#`tdqCCzVetuNIBs>+D2NvEPkN*b%F5-Zj zYvVHuVAeMOIJVlnhK}$JchHx$&=nq2XZVe07H>1j2YEjWhpy;4|N4n?b@Qw%R@_B6 zKI@fFhY5Bev-?6L%)Y}|J+(y}?AlV0QHD5LxAo(^S5d5X-O0E8!&`-np$vPsKa)2t z(IdNH7Nseco==bw))(BFEalK9maDG=*z9S*ALW59jqZd9Dw+d%U?W_~8*~mMUYt0a zfg&{Txe$Eu9j0e`jGn@uLzU3^c;sGb@2X|*>5)4b4$w8@WLvTOFI|~E)2(0WZ`)(y z-peRLFCi5`V0N)V&SHr?5~wD(Y=~?^1ev`E*>X$Q^`J24Se4TKZ_b%E8tO^T3SOZ; z(6uH2A2=cAkF(dF=t2?+1l6NG9&dkoEqHody}Hz=U0<^Ggf*Rov1GrBiW|Ae*tS+5 z0W`e&gL#eDNXD5LY*tLZ?D$kyE+p0eD9ymS)LmTyaITCC0B`r2evDKDD{rbwRd=g7 z@+>@jkDpTK*XP_LyxgXjuAmH z2idd7kh{aC7-14$IiGbCq20!7^*R5Jv<(YTB@SUFmQ|SC^}gaQ`NPU}&#B&ndkD!B zPrwr={GlyjaKo#uMp3V*6AN25=2JF`Up9`kA*;wcHDdO40n8)Zz@PKPk# z1*;_U4o18q3^5^^L?Sh6i7!kHnv_Wb95-)9=r!;| z&`+?{W>T_O_hHXfaL*OGK2~=JZ;rS0d3o19xVn3mZ`Z+$Xxh(XCo2FXX;yv{@G&9y z$Y-1rji3(iobIwuIM%7kXAAg}bRez~9UJHyJf0G;)_9&6XnSurjRNle-?=Ip4CnkOkVJLK%ooQGYYoR6%dP^chBgz$~rcGHsAJ)zGV{R7YGcge+$ zlMe`!piDyq$Rr^f!wp}ZGfc=&)f`;NO?E7vpOFCI_0h}HHcAXO2!cXS!m znSLv4*Sck`XG;-u8Z22Iz4|A%lMZDbXH2wkjUtM8k+hBr_cvM|=Eg^-niGGjBUaY1 zb(P)-Gn&;z3vSYV#51S*kw0LV^?L(>)`Q~wT8jLVvSYOe^1?f29tgmH^AS0-zRM?$x+)%?-LJCF<=2B9jZi#!t*` zfw}y4tz_bN2^v!RgOuo9+8(H!nO7r2sDzuo#z#6CH3MgA&wuB<>3DRzyMx56VdOQj6`IY$`-zz)0D zF%daMB%dAd2kb9k+HZ)|8wj? zSXX9V&@+{3w2&0~gBkY&;1Ag_w|It0YB5Vz9_{4Ox-ISYRkQD(KW{KUD(rIkbo{&l zM=6lrGciyA@6Y!94waZK6g!8QHp`c(8}b&*N~_GXr&0Zs;#8$6v_cTnUTF2-4~#6) z)CJp&brEOU5TI=s&R#kY=YtOM?749Yl5AsDYV&d|Dy{4-v8HrSCQyHFBEJajFsX2K zFLbp@vTW4bmC}F{oh?j_=}2nFd*a`LRxm0KTqyWW1G6YeZKxI%__&j*#9@>Gi_B1g zHpvE8)(+=cg4R+;*T_LnmHFvwgXx8@1Xa>Od1b;H)P?e z16vf{xC3soHc|0HwjHuf?kU$eQ86D5_#=Ubor1dIxNq_1)Jfy#}y9tjl!uGK)!_!KG<9rEcs^mHon1Q^3oD2TpJY zgsMNYa12|hgf>o!^giMmF|}^)Ss3|$_52u_-hiipfX?#R;-RWyU^2j_{( zr~VvDACVRsB8-Dbg~nHuK0qaCA&ldU8*w6XU`70m7B&Ga2H0Jq#}c^t-InIlUPCYy zgq##6fFnflK*nR3SL=yiF?91+OnW9d==O%3=8^@RrbqTetDV8G4j(Z{X_c(~DfL9W zR-;FZENn?ogPD-D6S;3$w*s2W_BPyNUk>OVED9 z6M6@5NkzdA2m_ifi>p8VKJ^LoS9IEM&ZP5x_l7c|{xv%PGua9Mjp!7&vii zUk6#jWU5r!CPcz20Z)MHmiw+?DOz|g+)l;|;@+w-Ka|E`2KzB5?>4*R)a%D%Kk1KU zJ9F6K+OwV32qd;s1JshAnJ#w0`t}r&2j#RAN@oxHJB+oS(D&9^GSsrxITcb$Ivtf8 zZtrKWXu+%N3`tM0g1@g=--y;c$k0&*(!y<$p#x8E{RqYtN)7i82V`E_>#T+y#%3U! zFxBwMj{pOJ6v_CX}%!353A$mt_V`s^yCkIkt_ewT?W(Z80dTdZs@ zrG*U!Pe@kc#(FrXT-$@0RGmas~t>vKG`~eX(DY^@f8#gs*&4U4%DO3%h+b|c^<~;$CZ`r>Vg5%Jv z(rFyDJAamB`_=q9zT%aI((e3prx=z^M>TIA_zpy7-teb}_`brN2ln~8boIm#2BppL z*Q_`vn~+2F47Ao9`lU_wR=?3Ik!_gKXLmQDFNAgS$ zfjK2e^)9%&oEh^^>d=&k%%p$x7~Aff5Ej3E5HADP zokqYpQ%h^@-QAt}-k`nUE_jpB=j$Pl--alXx_<*1Vt(`(yFGRU zYwPGyXsSMFmqbKsc|{Xm#6~zZdw)x1hRbR-*)=8NM8l!UHORG_1b->H5{P&GBW)5bkn5X{X-kDB}v%|OzxUV>3d z6&)wcakedSF0QdVa~-i7AN!2E3Ojs|bda=WN92>u1S;DyHM>!7=tj#@RpH`}9@Fnz z;*{46XzjI(tT{(E)Mzc}W++pg+LEB6vjQT40$kA9$k0~>a-1OOuy~t>-nuvhs9N>w z4d7k%_d|{px6+CWw~A8%B1>7s*;zBk+!Zr2)$cy6MzYhb9p1X^+3Dm%4Fv_Z_8ZAj8G z=WLgka`$LmZijBw=9-f)2UKp#6g>@A?;qDrYDU6yYjs8;*80QRl5fzx9ld`{xsQ*Q z?&_>GIqN|@4f4~|K(B6QyJ*i`!wfkO!#u_zX>RYAU|vTp5>g^6Osd_N*}8^WM9lQs$Yb3OYWcnQ{M0zg;$N{8;!5;6Qo@*`2m$eq!uv=*^S!EPa=3 zd~ONZyVOd_rM?JBEcr$~$gD+qft_-S?LT=n{bdHlAWXr-1|``j`Qso@T7Vi&-U5s> zJyq^4{kML&nyqSQ_Ht|WfOn!7$r?6thn=IBFpb^AQo04I2kul#K2p$1)~7?*UX8~bzeIr)r zi$KXv=@R4&!1Q{;ZL5@BmiJo-FH8VvJ;ZXr>Q~--rLa#S;^Gr6j+{cADuJ6x3VTel z-^I0umV7XQc4^?zv)c*jV7+XBN2S$+`t^b)o%LX(at5@~B#|m2yz&X4BhIr=l6o zwsu)}YX=o{+|)a25L+D2Y2x>>6{@n9tQ_q!f}o=Nv|_9xw52jiNK;8|xmGGC8>)n5 zUkYRq=dh_!6A#xm2TTHxAW#ctO$Q{6Uq)E7w1!Sb1lOUgGw=V9JcA=V?*8R}d-MJK zA7uZZ*g^Vl{7K(v;kz)l`xhD4e|`ClySL}))zNv2 zYz{!=o;u|keLlY5cUg?S9NWw6?xH;i14F+NKV}V+l^Po(j-qI9#N43p~6Oirrb9WN?_cc_`?o`M5p|sAC3V&*{CdKb)+hjL6bXH0~ zZ6>twzESqxde7~uO0+@2E41tzhdZ!s-~bC{E?G9ea4_gub<&$Hy2#J;W;0HI&m+g) z2+BT!Xd@Issk&Uf_fdr4Ti$$QHRNG{ut3?hXlx^l>XP&xxJtQRlMR^O86H^?sHC~J zn`Cz4$r<`<4Wm(R&9hy7q2TcuYzOM3-^URF0>_we1h0w|>idAtXancJ_{Cu=<19qxu;t_C&9@6RiOGCK&h*45IbV1hEtjKRMO9s^R+za_8I$^sw$bwET2_TfTNguJ{~J{2@^PjL^ZQ6Iui7?X?qK{4OJ`hXFZ{2?5J3iExS z{C2q(1Yg-;>XWK?ksriSD#q~IWAO1~bnIYG`NRwl_~P-S5U|)$afz<>;w=G7EzH%a zT&hE7H@BGCpsWMiu(xkKI)n(ms{1oWh+{CNW0M>>okNU22oFZ(%n!1fLz)+1z0rod zeuf*BNAs_nib*LFoyPV;6NX`Ovi-S&XHy4@4!%NxR;dc6(@G*~6MvG2;3Utaspk$- z&m`&08goiBiad}O>iP%D_ksEBrTs=`8Q}j{r1JfZNR_d*QM7l~cQF260DhK&w5%dO zGPk0Jge4^|$_#3i4YKx)!3sPd()V&O1x;(o79+RLJi#qb#iPmn^WhtymEPciAW75@ z(7i7^!;Tt@zT#U$#&44+vF6Ps?|KY%;bV;B?qJP|}VCAUOT`8`TvBH}fYBuX4B zW!4a()_xzwumY4o>q$C7Wf}9f$KzU38w=cssg)JKFyp#K ziwU2(rY07e#{1$A-M=W)8of~#AT@U!$ydAVI-!~?2i!Nz7an8l|nVe>LA`A15 zenmE}DamMIs%6_pdE#PWU)&cm`$2GE#9Ee-##*0`v??jvm)w~J6#=;u&66G0{wiTN zx|Py<`~pLCV~v;Uj>x1wRD}2Z;1BXTdb++<{o{|Te#kB;xrp&tzGer&scy!E)qW|< ziB&abb8lGGG;7}c!cy@089>n9-u6;+@nXHacl`?ueSaGS967F!ZJ6mAF;#B>E)cBa zh)wahoIZM$RTaJ{$dZUA#QBwN7{M(JT4xu(;Fy<^K8##1w3xo1gPwv;g3gD@X!_4T z%-j$mulGnnV459bY=s!l}`FX5596}}x165XMp(U17ev8k{Fa1z~^zuZ< zBXw6%ADdn&16@IGL9r~gKYpr}-dmLBWr(Ufb<|JAI|)_BZb9S98Ux3>(=Wc^#KWov zuRvN6_lQ|SJ|61z@XL_?M z#glocYWlv&9xkw7EJe$0e|u36f`nYgAWU8a^C&%u@;G@H#Mn4fQ> z<7}vypXXz<>eiTLC6oHnu+)9^=hYVFHF<$qiN;o;FvpAG3L^@}(r&lLs?<_lK1Mvuif&O~^5ffU%|0s)vh9YfVnMip*Lfzso~oJe+tj%8?>@A&fqEb~AK$p&9stPr2c{x@2?#A54>in{@#{9C? zek9jM0r@|1kt*_wEz{Nezq%8oRM{LMnVP7~Z7NF#3jL*PE5nECs1EXe?{_C0+>`=V zD_m9=H!m=gsx0x}gM`d)`)GrxxWQF$h;@{K^Z}puN@;a0ud38-)IsVNIQF+}D5K{d zSGZbyHa{Y}7vbwb931ItY+7Yhr&+ECs|Sr^v=SbJ-bj|#d6+{L6QlW%b*M{-Byph~ zLB`CscALXQp*Li6{z`L5lMZUoRG~wuE>+W{K+9Eb%v@QiEo|eNoipM!P+4YWHP{mo zHr%J@nmzN#Yy?ih2b0404>4(>vWIbHgMMyLtG10ILw_Y zcphsR6NDc}Ym9C?d!rx^ESf?EHHolj$t1X7TK6Ox(J^qb&IiQ|Z{Bvy5dC?*+jvuz znDVwL(#?UEMPDU02`z80aW%TH4sYy$*kxl;nfMGWcLTbicFIQ*X)vc|$K0F7U+y`K z73MwP39ZEZyRk>Og%^4KUDCN`BgBmf5JNX9AWLlC#{=1RC%VHpjCwp>$WYM}ZCvYt z7U|(VMcTeYgl}!tL##ClagJQlw%SqRI8-TbAc z*_CUb7JOw|siT&wfKKw>Ton+1vgBL@=y5VO!fC^YN+V|zVTqEH-jd-S^gGHZ(0!F1 zq&a*LHHK^KALHuyxpa;##`CP!VbqbIAc)XZ#pC9%2f^saf>;w+&99jtM z++m?AoYOejF?T~VJkHODmq;#_UQa^A`B-@R5($dCXxP%fe=n|C;kLHc{n=q>sdFgKJmmBh`!9k9C z=c$KJ3E?-Z0Nt-e47uI56|o7?woZ~3MQuMX5&yLsO`V&*w>r-fOa*6P z)+JD;I0)elKssVZ+$(iD1jOsxr8{CqD;+J*!(zvU8G)H^kbpvW@W)~RY~fne3KZ9R zcDh+#=a>d<>hpYh=vpDm`=UF7b5~nW4NYWe#KIu_JHlHscoQPdIFHiVj%td~LeUvR zcNzTa;%vUVd}MI^hGxXB3<-K%7?w z_(dA7R@=riHi9#$>pRLnPE~x;N82W&J*}(o0<5#E(5o_@z;=&#Ii1AV&K&odPInt^ z{*@}6&_aNPsSvkN>FOYwIRZz-RP@YgBYr*=jkmaO_{^}^iX^W=oo(cdu@ifR0pYpb zeqP}ztetqmfy(6?Sh?_RSg`+UeR{l_?J)l^cCrb)3=0WG#`zMyn-mkNimE4p5;AWj zPH_v9Y)u--3^6a;o1G4|C7rRfBPOOvO=)R`q=(mlKDUl4YqPyM6z4&q=;T;iut&4g zjA1*slx{ur8!*-br`a_1WLTSj7#)Tficv+4*a9a%AQ}7G*5ZY;^yDHX+n!PBN(6k} z2GF+hl6aEP?su7T`5PTBzx~Qg<@ZkrC;wyBwORvXVMl=l&aZWKN2^bc5U`kB@)&xT z7vzf45@`G8ga=o26*W2k5gZlaN|-SpwTgymtlbeJaW zb~FPYU|xl=lRMITHkH`8FoA`hvXF@u^^S>+i_VAUh(ngf=QW;FN)NtsBA7D+eJo64 z8gI{zN(Psao7y=Mo+4#Gew}jn%ZwRj1b4WZAaCV}af%0dQB!%cQK+j75sNV974o2> zdkZ_Gs9 zx50hqR*H5ZD#9J{Y8@b4yrGKoOP9dVPh#v7H_8`6jyk*?pO1Jtyv+O6mEnJB3pe@+ zlPF?3lF_z$*~uzgh8ZtE*A4fqkjc8RVk>tphc(c-8A1y*-kRJtXuv7onJ}@2s|bF# zBICEhm-*OQHtd}oW7{HcJaKnfZ1-~!fU;+Dz0@k#81=H@gPyWBgP@63;ix~6!S`!y zGx3eAyOyrGcKv3;h3v#7u-O&wYQ>NAN@UWd4er@>_LE>D2wob5uNk=$ z>}G(fTzC|Yj^xG`a|@)`J%8(x+_|MdiH5p=-HDvKgrn4rp{l3bT+XUq!vCk*I>oGn z9WBuFR@fyLcEH@QTRPe80z508*?8ooWkG=f6-ToBQ&i$u{e($g2@i$Cn{~8tZFsmk zwa13-tK*tk!eI<-m2pyTcO^G+6j)U*N@;k=gWC$E=FElx<%BeW3b1tjZ}IRX1L5+$ zGL;dDD(?Z^%w%(ou8GD~4=xLky;GGo6sv+Qddkj`aHC>%c}i!vqWdx~9Bb)exvk(a zjeasK%g6mzmidn9`7MuBgjvSeg@)J%$JDR;nJwB<-cF%_6XVoTN~fRIq%$>m?YjLR zx*_6Upz*#y3f>9nCoSM~+X6Q)EZS1t0W8}^Sf|`4uRtfyf@|Wqv-=OC9lL@Lccc$b znh$pz*)LK|pU}>Oo^$3!W=(L|k`+Rtu8O)ALgd)ovcsCi^1z=lB_@dqH_7x1{t6UZ z%!w-Vn5nzid_T`w!_Ou7WzY+>B77tBI5spx6yUuV!P5npLZ;A|=%YFak0fIIHDS{M z(Tk#rp(8U-r9zCdkp&oUzEA|bNr)WC3)!U2MvCK+J3zv)B&<#-r^gFk=u@u}7X3Yz!zz z{%h1Kx0V^$xtk2MoqOI)^-U-=3Hc*)uC#)IOfzjk^Oa2XwTus>R1L(u5^~lEr8td3 z018D)xJV&DqCjM!MtB{jJc8_oK+1;1OC$l@3*W6)Jy97VsWG&ENKjZ(cn3s@m>UFWEwB$+bb}Dk~r_k1nEGj0xW1Qh>PuO$Er% zI;>qMGcA=LD{z!kcnNu!w5P`9>yh8^CP;opH@?WPewL2v^>aR_8#8YcGyxhk)}sFL zldRfcpRd@rpmYV-5fWhBXu_}h7yDJ9K3aXA1yGzP3f0;FL)te5X99HF1{2$MGO=yj zp4hf+dt%$3BwuXX{$fpR`^gw*=UA1@jUTYcF5TC$?E=!1O zaOIhoYN14uE;^K&Le``V@NLR&$Zok+Zm&T_ADy}uQrPmv4dZuvHt); znoL|oJqzN-R8hhJ?GvSz9|qk{bOq3q30tH0>4=n`ab*?7m#o^ma*6=Ds0Inb0)kdR-6Lwe6K=7{!kqC3WiP!J7ARH{N<@Ff~J zp8#Toqg~T~Vh)aN12KdFa>xV98v^8rUWN{^E&c_y4WyG$hQ89GF%(R*M_wEJu?IRU zio_#VD8Fl4kWW;21X1)z$rmUfj5TnR0yQaI^c_R6_6^<*$;Eaicdq)Fl;ew+eejZ_ zsy4OvBY&Fj-L|t@4qTq4pUVFQFTkh_392H7f6S+rCm!jzHN*qCOxl_`vnrTQUEEKN zeXS%MvbvN_WLbm+hN?L2@4>dQ5-FS~CL}lPl|>Vi2!q&wF}o!b0&+tZ8(5b!jEuk; zqK-Zz$1F-dZ8&UXP``sP1|653V34l2QpkxBp4i{-5XgpyPFyiKcw=^WV|sXFe)xS? z>>)_(AsnX2CX#O#L*&}IehKWMcBV+80b-7RVva%LnGoR|q>wfcNGC#gV^;Wm)c+oh zz!XXQ)yozs%gY%Vul=q6Z{j&fr+?iV*h800k-Ub;9s|Tz!NM1TB3I!o?tR4e5yG3_ zy~fDt^GERq-diYRISO=rERetj>^)!(rLT677dDv?VA^thL zR2hNZ8O}>&ONyV^d&2@Ccgk6j_vlNrDhZRDltv@sQjC}F&x5^06R~i}E_O*c9>Vz6 zq96xP=6q02YpEIP=tkiP7-1(jXWt`y=|tXnf}?!-gM9g;dRA%a6Oa3=CmJ9K{9~$#LacDKBLwnq!vcTQ-GXzDa*xHYzYF4KPHOJ;PIt zN>fHV1IaqI^)ksQ%i;kw08bBEvhBe$BR5d>r#~#JwS>eIR~nim6Gy3JwJTRu%}}al z=4;UmbQeaT(aOs}40Ruh`}Pj@U=s)zOOP<%J*6fz#O~PmpqFish#nY3KREn1ULKil z+0lw;!^VJuy)(b80s%3$50u=JFX*q2P>ssj6W2#9V8xe=W@Ya@!kG)O>`TF;lJSJ( zk)rLM=pp4TI#2n#1Z%1HWc6(4A?htlK=c(3;kLCbrSPjzn7{we169^NR)hRvV-UDyh_%d_~iEi80WxwV;ldKYS<+r=6DnM_D&vDZKZOQ9N?y zUWllKTnW1$Hui2w<&R*^Y5*${uwmOC1ei5*>Ab9dz(#1cVo^S{0aX9yGn_#La^N;Y zAOiSUJ@@IWV~Mv-SUY9k?h4GG_r-r&a71Cc{g4;TG9KKzM{W3ZZ=J}JRso2LD3QGQ zb)(Gjd6sT}zxtlIbm@5Vm1{AzAP=TZ9epZV?0E7MtHO_U{3U28HG-UZp&0+Akt-UF z!bEN;G!%YbXQU1wl>p(5M0p|R6ikqeN)M&Oh%l51KsX^5dpNw&DVt!ec;~jl(C+HI zHwOZOIDlC^joHf(FD?6-eV&>I>Uh&v^9V4$2?J9VsakD0F%s>%hPq*swCw|~G{N>^ zvz5?J;zwilwfyk^S`RWedfStE?TZE6TbVG*E!dI;+NX6gQD_NT77<#K>$K?`(&6zF zB#9e8@q#T(fbVY>ay|w-8HfA8-6E-T;j)!vI{JtXo9>GGl?Y>?GMmV`>_M}MWwblp z^vc^jSgoMCC9{krc%?X=Sh)>^Ya&O6{Ss`YJZ({DGYLQkPv#w9^Z>vtw`ksbDB=j# zpO;v`({4DcO|2+yK2Yo7&_I|Usf^OD%qo;uf&)aIq1$CtEk&chX&?Zjs+7;GSFF32 zAniKV=6Z$VW(Nk=ojc}Z`ZDa~>p{{v3sYcnTK9I?)|TyoBpgd&Pb5!m!WU;8-nzC_ z;LNk5#-f!c2b{*DR)6v>hA1TG2UU$lPt~AG9ME*KgT?B^YfM|t6Q2m({1H3 zXb2qkBB_F6voC2xikGk(Xa$Ft*cxct{7P8PhX%Y!{T0?`gmX`|W-{wGG$#pKcL;7< z2nfk_7VQ9AS}B&I_0(-H2DVs7yWjeXDh_tAK9VCG_3}#^al(eC^*{6S2cJy;Xn8#y zGT7i4i~mWyHXDOPIE+f;IM7c&-+ViQy@PMT#mPhr#|8ea;nG|#F%(+6JCP2dMmVE%ic}jB? zZurF`ss_dpH0tLdNCvc)yhdLY`Vjc(g%SQTcovHg*w0VW{%L#Mt{2iiKD9{C>W1_v ztqob{m>wkFC6L_;Kc^;ywK8}>rXm?GrhJjoT&+VP#SGQcb%iS0aw9ewkxVtKypks8^9Iu4!Yj$dTh9O2i9@E2@3muYMcb zhjvIC!;(dsk7C2UGmF7fV9kLzl!mU;kPTlz0yb-AGl0@=QkK$rmSWE9K(BNy!3zzTQdSxss#Ev6L z6NUT=M2pB9D{vq8bq=iFVvz)=4$tO_^)N4+=L&VxoM2hdKh$g){bVj#C*Z98rQsfL zc2Q`uc5ZH=j&qcj7(#~c(2zMCvoC#+o{v zQ-VpLjAkJQ5+iE*EQLR9G4$0c5y6C!t$9ak8JQ*5N;`zhpN?Dkt;Rz_9zYfF`o43% zBqn}s$qS$HTD#Q4lJv76aWM|y)Cp90=Rp(;-*TdR@1C^T>$c~u-8-GW@bxB55}i`I z^2j-K=P64Tcp}2Dmns=}odxl__Xw?r`WYa+7HyaSphsV7QHfuHOzz2qv~2CGaVRwc zUV@wvuqk&Ym)UrbpsxuZ0k@#RuZov}pRQ$3AbJJ-Qks@X^BQ(oQl6Y5LER65PfYwp z{37-LLPa%yk;kPxjRU~((vM4swzu?U2w?qkDbQgF^Ae$1(?_Sfu)BJD;j19=siDk< z7f|pNg*ksU#{!t`VtPXf9Y+Fx*;>NHwMpM~uSW|}EM7hnfypj*E#r~Yb>h)0SQ*0# zgYOVwpG%;iTdS%7lc8S>+9 z>r|gZ`o?Gx>TdbC#84Mlvm_ zjS%gnSBwu$!Q?S2yRsr{FozXSlYe-=vl%eVD}ibNod zvK@;f(L1y%rG`3nte~G0{VX(tD4nZVItyt^CuHg&Y)sWsbuc4rx0n-Fe+M~yn>YD7 zKI=ZQ?B*PP5MWaij4nHqT-5Dmq!(`2m@W181F2m$ z0SM0)%fAtK=rR`2zZqID!ksE~M?Rg1o;vwq^T!6oE#B-D5b0VY?gFgG45WNA|!`gFMraF8ZWX zhtn(p505!%9e}GpXm1V05(q@|*YVt&HB8@OW&{}xp;$YCG}mH;M-gA>88(XK_~CsG zeQ_m5^WnoB&JPIM#t`TLA&DBqm4ezJU>CFIy(ghR_ziX3Co zuoF_beNmyeqMHaJlC$K8!YOC)mvd_7-}1lvBnfRo=SEo#9|fbOedPk2)8^|X1yMG4 z&?bSRUik3XSGY8ipcMc9#MOp#6Ea^LVb#=fx*+!8eX@o5sFV{C8ilww!UFP-z;XJu z2U_PUrhc3K>et4OQ*4WPw`NauJ>FVucfw#r%RlJ3Tw;A~C*J9=d%$-1+LM|TpHF3An7W1~X<7vbYI3puN$4$*toe;$jnRrwJRwP?v_CCUAFh;`Sen^6~vj`4}8uIvh7OlW^+BI-l2%p zk2P*#wixx(7q{9#DESf2D$gHI3nMKt;0_B1Yh0q~?vt=UuM#*)fp#2=x>dGvYSEzpUqFt$%p1?o#<P{kpV!cc+`1bmP@FEA&& zw+^Kt&q%^hL!EmB6>5Rp&~O_bMrK!ttU|5>Py2%shqQ7LOsqKP1Vx?yxX6e9Ua| z>0`A>MwHj|O{@)mG-!I(GJ#Y7#(4-l)KtI7p%dfVumyWUmW4jTW?vwrXhDttbn`$Ph0 z1?1N)2^QEqB%ClTZ6$DYJ_>sA+OF_=$^`i;$Z!jHX)Y%bGvy`pMCZ0y{8i+{TVaD<6sPjIt0 zQE>S7uj!cntQG<-+vpU;FNUcpv2Rl0AO>UJZSI8u{^nXa69;8aXp&F_Co8sFlh=igt3x^_GQ&UGm`}3Z-7HJlBU}bW%vg$9?1)}>NG?4Rya++Nx})Ov3|brF7K1<{5|89Un}8k1Jj$om zk%rzY;{Z|j`9FH-&vK4!cEKn^0q>awpv7!THlbA3p_SQ*` z6bgF!PiXglMMcSlKWRi!z(X-uL$p&8J8IL9T|)77;(e`n4QL;)N>{sb1HP@L-*v z_`4;r>yYj7J^;MjrIjB2aLExp@eD0LNQC;AR`!!0nr9{=9!g{sVyEih8L84l^%b80 zFW!jZ%>mckA1Z_`TqJRjsT@V=P>QNCqcKi7#U{3_e*~Lno2u}1#EA{b4KB_p!tQrW z*DK>4yffxzX>Chop0L6Vyz^!d6I#FK=MIZgBUN#;U%}V8^ee2x5o_hJ`j!iR(}!tHIpV zL}S^J_f(W5=_|-U&wfFo{1hT!FNlA;79toQaIGu`4jQ&g5>R?AF)tR!TjeTAu8AJ_ zQVwospd))(nlkzO{2;I77~<7ex%`uBz46*g@W`bz9rBxT;ph*+_MvPa{A;*)PY&a? zo#YAEHopZxsH-|?j$P|{*BXiow$l`{#qqU>-^wFr2_dPR*~+Rp?eS7IK11B zs}P!U?!?=#leh}>h+2oiWI4LwJGkV1I*V38xLs^mGiiO*g5L`>@)l&b)`XinF z(xA93PRL$=qQqI>P&ISm9=UEBy;j`L1=nc(05@;8>7YzlXv1V}LktImvBaKJo7%JX4)U{Y+;$>eAiloYvAn4<*YtosPD6yRm|nT)}3_`EqDCtpn;8(9pltX(tb zhlPRDAZ0ArWh}VMo&GC`a;FTQ1q9Nnxaaa#HJqgl+bJVe@D?(IUDOz!s%P8dDIFi> z<$#YsYW_&-%b^s)ffRQm86T$7Zb_!nI!P{y$*t!)C*MKA6t6TKYc}3#=BM)hLjv;_ zmoBnXn}_9hhaxut$?PL2`?6);4Y_K9woG?6KG8okdEvAQqwCsusiD)+ z+E!NyM%#&sSP7jQ);6ZHYdIxbzLTEWi491m&s1Yq%xBho3R`iMLhgzK34G#YvE`Lh zFWl2id4=L5O=@<0lJX<>0H9~k42yn={0QTT@c~80jAy1jvwq>_NVO|coyY!HLaf1j z!u;&P$@TFFUQvx6^3joNitWBkxqM1}$2jcG@JvfRmF2ysMfD}LQeihxGhA(Z+nN{L zsJeUE9p$a56{s=zyryH9EmZNOv9Ww({;&3T4Jkg!bFDA-rCNNS`eZHC_!=KpBxl;q z*S&D(aB?fpo%zWy+`H%@;DxR`YKqA z@TsCZW|c>p;*Cq5?ehD0iA$Nu*SLWDYS|AZ+tx^XMr=$Sj`JhBM81EsLk9M)IVVz+ zM3dN~C*)-FB=uUcl81D~*r*_VSz_+XZ-q^^hxS33iMreFEu_dUc0Y`l&TjW$SRvrl zR*pP55bkg97G3rrKRJ>KrE@xn?-t$H-V6*7CdzD>)T7a*k9`GAm9$ladxYTzloi}k zGksv4nfW3{Jb2)m`U)4vFxCqB>hhC9;#)V2~wUXfSF`fX0~>InzqwkK9ht;Lt; zLOh=<@z=r#W$MA+5qwuA91saB(sJB$9>42^P=AU8quE3g1adpiDo(L03Y;=vMz~;) zj<5SSV3!;&{pq^pBLAs6wB7+D zD?>LS;A`sz$FFY&g`0RGrU{p}E~LAs@F&=Pl!Ml@_sxlLO$fygri-l_*V7eP5(;VV ze_3<9{{tEX0B!#+VEhFE8jo03XG+?c3v8JomLyDxyiL&+F-{deG;_;|Pq&>}#Vh$u z>$3OpNnm7fTW4^O6i?F^^i7MT=?KTd^KFNDq&4YWi*#&9Oah=c_an(2e)>SI8kn}`C5$W*nY9u!2KOHKJ(GJ+2RRVEjFuwOMfm)| zzZy_6a|fH$uWG$l{?dOKj`^$jx4m=8O^dyLKiOXGvQ*i>F+d&C&`$V8Nhc{el$30A z#2l|ymb9tVo^*#gikYWrBNLHZLjj}FXHHuPb1i60Acy3z@BkVM_IbfFIpbf3`zJj~ zZuL-59<887_0)!}33@ZsP-B;Uno0|I-diRb)ohLw*%X>(4tG>prWxC8j$C;L<$|*d zY#?*0_Oz9219z@HhsB&7)wNJ3)SN$3-j2o0W7;a`JaZ8cdU{aMr+XLu*rNzkJDzD& zW1>>+gdDRLx|9^2MxGxf`Ec; zh45`m5r=XihnRxa;W-`d2My3}`k-x^!d9A-T3qkypzXAQ44c!RDXqm@TbAF%c{?_B zQVTi`iVm#&-SSTl9Kc1Lp7Pe7ylrd#?%KzPmhr`n%Dn9sPj8>8#SN1=9Ro>+QLdf> z!R?t|y>Gse_YJyaPWv`ofX&dw#jmY9oG!BBt~md*4IjJgP zT%78BVz_u#OER;ApYRNA5?OVoSkF4BL^;&t`jpW`>+@1aE~QaZ+q&SG25^uDP>=?S z6n`t(miZ7a{CLp2gR-VrExWyb=9=V*r)OI%(*NZKEZUYzPRBh&dog^X9&ye+5%ArE zzP%3d8K8e-hjxuJufbRFkVGf+h0rOF!h+|AOm$0Vyg9?zX3jeV$!JdYoaM%!mKC?U zfmQ+K4kuW`iSLK6LhF-b)U+`lf{|UJ8gJ;2d<{ZxVF?`u%Hm-Y*0#BVan+#*(N&ClaqH-^Ih@pQir7 z88brntEWFM)e*VXd>4GDM#rj1y!kw018xlN0*`<0DpqV^=)G85Hk?A_NlO6JSu6)Beq7;4D z9E7*z{}u-hDRiLC?pS;+-DBDC2^vTa=Fl1QOk;#K9dikz6AJbCnV3K_FnhhEnUvAM z(yIx!jRJgw06d}s9$5g7 zuz*JzJelkw{=61*Pay8GRrT89ild?qdtS?m zCs4){$g{J!0-o1G=qT5KrI%Pz``zflc`=3KiSxY))tlmyp}&aDwBX{;d)1DW5BR??SWFKF{c`~!9^d%e zpY=Ca`Td>WDBGWYp3n6>w^x@vZ;(H1;~IU{;f?^%*tiwazj(nQ7}0(?O0@|YCc-Au zx_qU;eXqHlep6iMz3)6-L4llXeuD%`5aIvFlGkTDCCx}u8Ww$_udi6C4p}SHXC)y7 z1c&`VX>K8`su;zNdYG2qNSAhH3!8h?fQPchHh#(-!|4jVemD;m^>E$0=Q97X-$NU;%01Z^nQ()>ZKHm-+#~v4So`9ukqREME@dL!iwjG?XXHB;vlhox? zDj6gPbc3q?8LF2lw8!B__xTr5{>yWwNQ=4I(cEX&J*oHgYS>)=aO0G&4#LI&vF4bc zgjMxQDh7x(a~tecCxOaGmqlptrfSqD$1K;^r10*pM=_5(;>n1`M0|c$$Hi2l84#K{0F9+yWKk9+*WUEZ>z_3d~J4TCxlpeU_Dvx#NSvo`|`xGY%sH^ zu0T7>NYZyPUl#d#Gf`#G=^QpyHXL+EvxCZc-+=;6i>b)COtOdOD&AZi1RS(GUUXT? zWLG>H-1dg%LNUI7uL(-|R^%}*M?9;RP;*)lH6ZC9*@?LQyVNQAxIOYSo> z+9?>&wEXmfvqs~jMJ)_kCP=P_O5)%9|7-yQ(?97&82=4@s4#&=I`LFO zG{RrGMJ8NvqSZLF6e^Biwp>9;8pP%PF<)YWk(I+$bb!KlHe|v>C@DOO_7bg%>x-cX zD~9>Yla}rcbwJfN0YV#2ZK5p{Rl=HWiI>lQBqQ!dgd|j5Lu;geR$r_p)pI4fy7BLk zazBmXmd8l4IZbt+Q$B^-uwR;wKxP(YBd1vLom6=ZBbmimu7n%s)?0w^q06n9WlZ8U z$^dpZ-k_FNd2Sc8_nxzQzzvb%&cnd!F=cv z6~^Dp@O1NWvjCjG50qRT3!fLGnHWXs4roZFrD6`=sgGK}PNUxiXvX9bs}p-Vtmt=7V)T zf0*wgyfx>0nioI~!}~f@rHh8q8$WM+0@yemq&ZDzBe=007)Jx&A(F%Vsg2AB4RoxR2}%_Fe-r{fi=dLGv1#{i5kaQd_v1 z2L1gBs~=C1#klIVn=x&l_Ao|LIPE$>zGlMHWt*6n4*@TIzqoWAfywInlVzP7>iVVH z+oxqu197*wdz~HOcI|}*-hHaJ$~zSl`e`al&#R3osC9ZC+VQTys5^~ke4={oH65Vq zxowfQ#^k@xLwoM!Gu@~0hLNrE_yB{j>3RHHEjZff>F#06H}4Q#^}JBke{s`KQELL? z*Y;0$JAa(Z2*hzmnSzd;kS(}+gX#Qb*2S%- z_K~-b^uBoc0tN4QdSeG)@CZ>6@iBSgBWL%Rl@msX>8TLPMu&)dNQ_^~r1sm!_Hb^Q@-P%{-mUm3;}1eJMx<~3_!t>>A(&&Zh8=G8ZYgI1 z`rBTh87u2vSknw?eTw5QF1X^4ERQEdKWrL6@m>e7u<`B`TIymfi)Ci}skFQW_7iCM zk+gi3PrYt!Mx@T#hy7bR7s$4qM(iP;A&vgnaSq5{bXqo{@XXhVMJ&8yfK9B#Xf@#H zo&h|DRYrUv@Ep^Q?GyExNaA-H!ZNpbRu^@(_~|u0RO{j608uK62Uq-E2sJhb{J?os zNSgu97`+_K+#z=@)%sSb^E3Uhe0kdqyD*80j)>$e=vbc>~NSL}a;Fx(@mxy;W5D z*2wT^G4LeITyelhZxoGlZ(?KhVepjT&Cl`A*x&vN&REh{SU)~6j~tRWb;vzXHg0CV z$=zL|ezl3!bc@**h}E=;U1)j#aoQFm#%TIwfuiF=-vAr4Ca*$CEFSdN3nq!Wx^1E` zuNm>ll-qxH@mmNneQb|^zgrCdnszf^6C0c&mR1&~!!vO&@zo~%L!nRKzhmsT$2JTXtwNB8uicV{-1UZk!0)Hgl3T?ILGy!8**%!MC9?{3Hg@Y;hJ~7A zgI;S|Qkp^n!)a~HYr4ie1EDSZD6!zwu~!zTx?+YQzO%2QCYJ3s=gr}RBgGIF2_I^u z)BSJybkv?>!T<0IbalXEvit+#ULyXVPRai!!{YvbKwbV{q!|9kF`3qdF;rV_|C-(8 zmHi1G+6O`c^PV(C4hjYdkK7UnDH2SMI!KC>L=qKBu7E03S*u>X0+GK=GrR)P*`;9s zQ5%K6zGS^z<>$8Av0NJi?9nK-*4cT^_qocYNH&E8Tt{vCT(uv69Dnx)aDQ_jBPM*F zA4f!4hTFAeyGJ&uT6V6Tpu16%5_7ayN-cFtqai4uxF)OST%u>c$`@y=h@qutsZxvP z9AN5*#U$4qylYTyoj|5)^Z;&4a~Y5CC{kp?e8-Uq6z0c~^mM!9Y+CNkpak|t(NfOmDL6#Am~RFewv={PlFUbnAi}BTLilddMn!n zytUNoY-sbA*&(=cOy{)3>P%szs4Q=;;htQ;LO{q97QA+yowZY(9AvC+0ynitr6$Mq z$fOJwRsy$0C$e=yF!XddAw-vh9gLYBZH zd4k+RA-{5bZ?gi{r7m!jgvc^4{Z8rD7cuB8RQV|!XlhJ0ivkTuZhIatpaL%_C=sG|OsmyCa9dU< z7`xTQ{;IExOo*A&DEQBW+j(DB0m6M%%=^5CDWhmw68^diahjYN!|W?qm|O-X-3GG5 zCro5|sOy!y-ZVWzj7VXhSFpxUV{_>WsR-_Yk(_XtqC*CRmWbfTpc&$nZf37>)Mj-v zT%77oZC;}nn=Ia}z2z8foeduFi5tn3e6%&pj1^Q%yBy5F)(kq2fy9SD5rc{;)_`m4 zt|I1H8G!cin!1sK({wav)IUR&;2bRSL#jluV0dIhFjjHn*y!~`| z;a#)?rbY;yG@SXTZUI8zAi6t94^9%YX`BdOfwVc`$_~{9ALQ?yb1u?&aym*?d)jBx zHs=G)H)20_a#F^u&3O`obP4pb56Oc~3&C9+hyjr#2CToEDUnSNg4x-PG?z<=re{tC zy`SjU4MlTO_2_e_FX{hiuWD3NWeN8d!%eib)};y0BbGMr*0pLlxzUg+wUu{w+xak& zTY4)j)Ri^22376$5;M_}PNX)wL*j*y02XMZCHpD$=49-Iev4}?wY7x)P=p_WG zvPs5KwjkyCNu;VrkQ=0QY>h}7Z)g)jS2EE-!Sb`OSII7wci>=J+Mf?CK9l==VufP5 zs+?>MwPy6eI-|#q;JDO$3zd~SBbm=GxmK7@UW}MWPbS0DJ$jR)nPhDqrioLIKa3R% zL!F<-kC_O=4iU}9lj<)|Wg#DmXezUCNH8h%AJVvD;#=|!sRe>ZnIn6$S@lX@ImDA} zHLu^1l2fPS)1G`Y8q4ie?K6Ao)5tfbmOF>w5-6(0FZ$rBR19G{|{m)L6e%v`v zBspRF^!>_io0IpFiXLVhZFbC5-7T%nExadB|Fr7nOgC$nz}zxQ1j+y0U5`<`(JXs$ zA&aW9S2cyqln(S(5WZUk21)Zo3QQBIAG&HhvRaU!~IOPVzdf|p017S3MBxE$KKVm zGo+YX7kAv4bQLmZnf?u!YukMctCOP0NKxm!VuJ!%ZdyL^lEFTF^wA4-X+x z0f!~f8DqKr&R~+ptG+5vTtYu_LbmUcHQVr&SbC1gQ}gi8j|_h78~u&IHR^{xqhW#P zJflG=ZsEu$vQ=8Hn`xn$v$Ye08+vs#WVPo08|InquU4-a)5+nG2G=8;-Kni@ieCe5 zo2ql_Q~`fwX+5}4vN?e=bU0+A=Aa<xXwHsU}q<(&yWC8M%fMr2zQxAn+%oAo|?=}#1?2gl5OUm(2xeZbHgt^cf=(rw1P-4zJ}da&dFEb9RU_ zYvLLE5iHp?R!TI7l)F!Xbcw=vf7D9YAhF~*^ox0hY~(=XTUziba&O@LALw86hrEK6 zA|bO%>|Lbx?;`Mh3?zbK@fr+vh1)90uAlmn2wN1E?#6*nU`Z67gJg}v8DAi3RrQuO z?2T%o)yiW2$LJ2;Lpu9*NL#`l-b1|mdgU+Ok{`k!C=56j@8L#Vxjq`sr;3EPd7eb4 z-l%_%QHUZ1d4~=7_5+5n6JDx43FZN-kV%psaq5oYzoye^+Wx}i9Ls0*=lGwXzzwkp z!$B1px;C;rq)rof>g}LItev49mi*=o7|NMKV-o~zejW_30C_V`tq_aF`;DccE2e#p zQaLc#<$HlX%D;aNf9H4`C0PPD3lq(eJnlD9gyA)0u}?(EEG~zUvTOi(T^KQ}R{l~h z`626j)sQIfY0JSpZ?$;SSEou`c3T?BIP42*OSV6oK$vac#A}C`Finl=Wy_!wJ^B~( z+S|60Ba+;G-+@pNUStm};a8-@J{xue71qI@GX){6RK48PY)z9*Xe0naTF?;3kcljs zA{l`qRs5}!r_-aKY~@im+^Iqhj-$ukDT45jb4;A2~EG|5<6tq*WUkUn-vtVZ-NPt_Gs4( zAwwpccb0Y9M;*+PyuFFPt;w!|kCvI$)d3KuJ?^G$n_I9n!%^cXa(1CNJAQP4@yiqc z5Hw_E?9~z83r?49idA;m_nJ!}f-pFDK_M+JT{sXaK7R*gMz=N1dD_le(C= zlvb2-_>dY7^YX8v@}eTuIyW!x!)2#Tr^p>*X>t7m%Ys*bY*u}78JHWGM{9jVsN$w< z%ctkU38^mBfdU)arG+wVt_aq_xCx+4_5`oZ09V}w=SuF~dCnA=?bxaX_;j+I6@T|C z;5S$xGy-S<+D#q(t(H0`Ydj2^OWw-xpJC??ovw$HE2$Bjcx#P3a z8A`qecHM0SZtV?-k#GZ}M1?$d4WZ}{D=ND(I_sjSB{>KHg-Cb#LhDHf)uZ$DV;gG| zB2y-qHe}~c+QoLk+E&5ZbmX8hJa0I}1u<`~q*Wg&pD!e2C$qI@-Fj`fMUBeR?oR(Z zzbo3A=S_1#g|yFPXcZJuDaqbEe$osB_XJmQ>QcIq>`qu3JndKBl5UA!Q(B~b8hxCy zL!l1F@P=t8KS0w-sgh1$INgh=l%TY*0e%zT=!6;*oZ7Y1l$g&}Cda6kh`nYvj^xNP z=4Pn-q9;F*-hFI??056?ola+?q)8;vX>e<@Qgrh~{_Zrv4c+3w7hGxnf?haqm^cF* zZxu4XH+#Wvi_KPmVNljrYkljGex;eTb2YCy{jZHUVm+A;BZldTe&_1mfh=d-&HX1x z+|mh1T;sg*1eZ{;TgMQI|HG>TL&L$FVK^b?6jU?v7Q)|v@P%%+(2l(#ex(b)6gX6j zHq8SsdV-{Ze8j&$7vQmX)IrSH=u1AS)=Rsyt~x;Ropdp|iF; zt7UiL@7E2vS)RoTlxw}`CVn{dfSn7ZAPqs$-XHc&$e`Cm5MK>a@q;z^!)OqNVJCpr zjFKFhfSfA_J}!OZ{qa|TO0^1rB*d361I-WN znlQYnR?$I3x@OfLJR&cP!FGzw zf|(@)hkNBErLcC7!3Iejq3m%82S(1TEVLa8;t=%M+CRe!a;OJ#=L2%b0OAD|*!3I$ zKc+mHI|F6ba-(;lU_wrV>{?TR3Ry0td9p@9C1la0arnR!q<|nf3C$~ zS3=C##G)V?{Rjb?VX{Bz75gCpvwJ$Z20Vy3*hMWW*XNF&2?}mGqBAqaWQI&n8a>^q z^BCj2Ju)BbC`m1%@t;wK*tzTIBR#0)1n)c94vFO}rc<=Ghsc;BrF|^dgtK%f-3OlL zMOEWXuL?=16puRIsVof2{At^7e#fW``j((lz0)G95GK|89+|&JJTIj9*86DyV|A=d zzl`d;g&nAz`}Xj$YqDXjODwv_y6=#l=K#h&;d&-TTWoq3s;031EyUf0+2;7A1I8AR zUs5H}dLN{NVJ!;5qhF=oYDVB?C2=?X^g^dd--;kiCj92GdO_$S$W(BMQO zBa+6@r=)QULrl2T;frd_Ngu}O)0mlTil+0V%xP)S_}bLI0Et88+_7?VWg!ygIEKFa zVdI~dsNw*fslx7kH6Ug5X+ef8(%vhxvPdr`+^JuKl%;WlW28#up`O&UNJ_L-xI6$; z!d(tB+K&x?ah9LS@Gv?f_9`gaK_uEwuEmE4(lORQtm9bu`3L`aB9eKr97Jik={5lU z=Vv6_b*f{G!D4_YkiFm$&s$r8iT4yI<-*g2hV+xaz_-#>E&{iA6t_1*UO&DM(qhhY zrs%dy9NY$y7Ap__n04v~;^vO@F9Mm0V8jYOES5_S^X2rI>}2z+mj8+1XukTdLX1=W z+*%{g9<2EZIEsXd4zUQ}w`&x_D%OY5r~L1a)On_cU>0%iflZkS3=F1-RJGWSFyrPS zA54inq2d#>qutC0osuP75rBd5qWk4afW8^}@{6U1TSSr&0+-wjL94Eu5CX-0Wde^>*ugI~|gaB!L$g89ox zO;Rz;s!kA6?=|PI(TUYF9_x}sG>xuIb|pmD9dr_%Laog}jJsHiiSa}twK2G^r5v}_ zcQ@e~JZpdL-XFV}P#g>9cwqllJ0vRE*ETq$JDfc)Y=^SUi?hBPbS`&sXh_8`$_=U(TVJ?hjskvB!e(LbX_c0pRqmb){ZkONtd}NZLCs#nf{N$+ z&-abp;W!kSm!kutXi`81(K;A5^648sblKn|oO=9#on({E%ZGk9@$5O(Z_uEvJv$uC zJlF&BWFIF^xdTF6lB-gDCqay8Q8r2Zvf+Jb^*#NVj<|hcTBB?@SA#U?*}_{XIr~ss zf3a8-*nA$id7jCFvlL;csQJa3Uq*9l^kjOuVOqIEQ%v-n6*CDebx6YZWF;by)|`cm zHqO0*#xa8d8HG{XqBr2&c|OIhJcp(eUK>ApS3z}}b_P0mV{E$JUpGZ%)V)CNlaKMx6A?4X5(bH>ZDa zR|YJl_`5`H)h(L=g7XP=+3=SQk~{EDwQ2yv67|}X&+k2$rZn#fyZA58 z-Z?t6rrREk)3NQ2I=0oZZQHifvF(m++qT)U?L4t_^So~YyQ6nGOKO^qzkHyV$XPJRPe4PPA&Tgim+#c6kl z+5mXr&>(q6I-0k?Rk558`-0&U@vm1MOCZl}rFtVhtYJ7TwP=PD!Nvzb_y zxS`d`%$eJ{$SLk!tT}`Wa*Uc^JLBN2QdEpWyF5g5!oNW~{mc z&@>ynRN5<=ZWs*O0K|ay8httGV~cfiw97*Ij|KscSvwI;HvD`%vqUGthir%RpxY}$ z`z-hjQ=lUOY@2lP1Z!a>y>z&W2(z%thZ=iBY}t6NY}?Ut^22V#gVS{1x20!oQn@ryPQlXn7mJ_;N}_y+Z=P-5uKKRH-d87 ztwB#|U7|VcH{c?wxefx7FV&nq8ZKeC&NN*yezsK$v{m!FVhFfmd_4vKdTwFLxeo6g z)Bd?ap39_tlH3cuB~pAra${1648J75rn3uI%e)fg{B$em6M4H0N<2EBv{q>vT(v{Ia6XRD)R!`+}rkO z7#DK+0l4%1=amh%L3;?J)nngVn|WGg2>Ol>wpcn@DvT?$bj?Ix<3gXaU!OCyG-|@} z#}BP>)T*I&K_nSgb*v$yP#$3^WhznLoTH?@scZGn>`W{A>QA}dMqMFhsO(tknAI28 zRB{kS#(niL#mhG?nEb~#JcpAG~Yx)Z0heAEH&hzon@T%V8&aZ4&gh8!+3Rc9EpqV+9TJ@u|RPWct{=UbUL zP`X2uBx_28))OtX2*(nMAzB^-x?e@>GG0UG7)<1)e2O7ZyX}{Xw3` zfXtti1j=0TJya7|Z%N^0@fKbZyu1wT0vk87Hu)#vEan&QWSz$_+#R{+ELoo-22qQt zQV;BO>Q`z!2T#+hdBnKsV)}P3@#F&%^;!*v3=*!c1S1M^dyfn99g?elabDkqH!PVO z4EE8jZ4!b$abABA-rxk>kOVJS@@Fua8={PT0#MG;u1_v<;Dw?DFHw$B?as`CHU#of zm3HORQKewjm>VRQ;Ba=C_)4#VLSES8HPI}|O;P435pzysGZ*Z94zu{f0+31J+eRgg zT=!!sYs5v%fUmj@0;+pHnXHKqIUg$4ZhcdMiux&K6pLY^<&NQu{+h>ev2Zrqy#t&1zWP_4J^ z0ihv;9+WzPIXftpIfr4nQ6!%PnalAU$@3JuG=iii{5?c{dncOleTPZ`YL%b|!*dGD zyT?@plQ$bmw+L)<;2LQ0lw^mosU;g!%aV8}-aIrJrp3#59HHd~NR@Y+G6#8G640TQ zPNcsZ&`D84ixTez6VF5~Hs#A+PfButPEsuV(}0A;RBhMsl_UA7SOO4{v_=P{^ad`F zAA`WCmc`+7+c8}dhn`4k+P-FEiN>^AYe#jLe18&zn=9GRLt zN|c0|kJzlC$3p3$-`TbV?m)zSC~tHw9eVTY1^FXVFRPBiu|klMlT{;!l`{R**_Z54 z!uP23?!nP+=u&+ip~o}`cnStIgF+uJoAyuH{9tpW;k_DFf+dYLI1mkF4jNDcvTv2Y zvogpGv__$_dh~H|ExOq}^^C<=OANBlgwlut|Eo!ZnGq{dq2yp2J9h%7A^1wfN9(Sb zyp6>J#%UdYMeF_$9-#A)p!UfG52*mxvfPP1+m1ckiN!(eo`NvKLF)d~53$q>!3Kxf z{h$drd+Mg}Ng~1PuA6*HBHc^Ld?Y!ycu$mjvjEeQ_ASS<%LHv{0;)nEsHX8f!&Ot$ zRC-&r9jxBd6?mf*XZ3N9N?>(UwolfgAALGVEQK7VBmY%vFi7W9x4Tq7x8Z}t=VJ{? z$hB>Aq*&F2a`}KZPz?h#q^i%wrO$Ol?Bm_J^^{b69>Nzu8K?LDD^!L{7V&wkqgMIbwHJBQAriI%a^1p5Mb&q%O?F zld$DNiUIsbu&wsQWs8g8z-3GS?sRUV$G`Bj*{QA`hli5dKf}?^irI#fm!=hF(;9kT z1YCBKGW_hVg}2~kB->`MELX1yB%b6^59&J}^cQ>>Z&|vp7t<`CNk_jg`Q#REuHgWCR!E;qNLUo6*oM#1TMbLII7!8*P&Gx|0OKIloU=|X{m_EM)~u}U)C{m(al~QrTSeoW}(wcmw1Y zdKTJt-J$52N-NMl-Y9y4eZerUxin+se5f1AFv0YBRteW+SpnBXwE&^XsZD|&LAp(q zFojZRKyiJmSg#fw&tvcl;86(G%g3RrCM&9$#VhEug)myRb;2hS&;{IppY@fUDKonXRAvjZ*o?TfStPy6wcvZhQDV9DVdi~P7g$urV#^eml2<%kZAhN35t1%>Fy|nV+8E$B8CVG zmKPffL)p81c;{N>Y$I0=YcT_F)Kac-qO!TT8z@MTjx@#x51c+z7tYjWw|u;_7+n1{ zE>lr@rf%8ikw9F;y;H}$%V9i)QNvSM28{;8+?m=o8K(eIarNIf0j-Gar`rUj45}Uo z&iD-7Dt(LW`7GGZfQML~H7m43Rg>Rs1o!Uye{Rh~b$+7U3taOiK;Nk|OY#Mc-EsUe z;c2PaSF`cvZC-!zvT414UU#^E)>0cgKvGDvPd}(outd&U;|OMcAs{o=St!=tB2wMl z;n7O)PqP+%LwgR1i1ZeXM%(nN?#%h7j<73S+VH}6c)wv#I{O{g-|3q-R_on7g|x0r z{=Gw5j_Mq)H(JuRPFZzPqX*jJPM12H&%{zRuOne_ZDhL8o)C))c!y#t=~SZsD@8z7 z>}4G~O{A0g??s!|MVrD!T1wEyt^!LX-MJt?t4JWmH>{$m&xx3{oa#6rlu46nz&N`n zRblNUcDGYY(1p8CC19uo`q!4u+<4X*&?p(@TmaGo_nLvTOZC;2six!odFs{Gq+@S= zkIhBOpbghDoZm(jUE)R~dOO#3^lOwNZq^X4$70dBd3^Iu2OZA%QV_G)Cuh_mUG%nP z#^6$mj#pIu6E?=DDeSgnCP}!nL1%|;&TSYU%OCm^oKG6LM}xhG?!Tx@#K3!FN+du) zUZ(#Wb?Ki7O#iLp_aCHc5{7@VmolUH!$J6Ag?}y7Hlm$Za$!`_2mwGi{pkZ>06@mh z$F!wY@l}8NCk^1Ya|c4#)TITGeV*J~`FwnUCm5t+NyMN|h_o#GHP2G%H#J@1;>hvNze)pLf&K8TX+e0+mZ(3h7o8EA|VZdCMf&4g@&P)R#`_ww+{v z^jmJT&Kl<#97v3+*~ZLuOWsc=iioH`1*ggSY{{LK4|K~qocPSd0IXfsh=-W7&*g9AnJCG=vnVUF?+nCt?mzlm~ z7C;yfy+KF%!u>Jj01*L@ciaAHn1gP;sj-MWKRZ$yYa}1~o%jK!?%x612-l)mrYTX7 zd*EwQTTYx;jR{jnORtc=5M`Y4CC6g9dHSOLw0=caY*y7)bYEw-?a4ftD08Y!rZLq} zqpLfhM2j~Bq(ob_Jnn4vuL}1O0rONm``I#r`w_xrTQ^IeeTxw zNg_9g1!3=KF3K=1!($_HfLI{VhTpL z9O|ADpzejmOB{*|TFeDB1+aH!3?>Frqv(4RA`Z4j08@Gev5w4wyEL3SJ1lq*=E2Gj zj<;Z6`oz$B4isd%^kfE%@6xo>D2MwaREETP)*{cEYKGKxDFdwKXKJQGM7MB%jqBXe zg|o%in1cT|akKwq?Q#8sapiY#(06APQm}RX+X?<92K%oe-B5S;(p*g9Rb5LUC7m(= z$CV^2H`J8LNL@xGXJ?mT{NW}}&DAR|6>GhM6h}%tzQUQCU~mi~_&fOo)l40PsAmQp zGqgStu@7}jVbxCt((J_PHPbc69oHj|_UH{6dFC&&=jX21ONUF2E%mE;m|yJn z;i1W4jF8H6it8CJGxJU&`H~JlVzTUWo;_{4`X}qxxsP(L=5Db&V+HBvB;g(A9$Oyk zM7CVzXy1L8-ay%^?QY9N`1X&?Z9d}C3G8oW*E_xv3J>jkwx@&Pw;Pnp&Xa=dIlkMo zY33J>`HvuxZl{^mB16-No`F;#c#K>s}+1qB1XV z-5PyP;N? zZrt;G_?u8Ip6eJDSzv<-iqx^gBR1)Y^Lwh}p(1<7uL{uMA5b%;N}lZi2J! zZY+eDHC8Ph7p2qA$*hK!6;b+|!>Qk}+k9ja_Iq>AyD5b)65=!s_u4BYCo({fJhko- zUI=-o>)WdfroaQj&p_c7PeJA$oQXEsyTAh9bH4=fTI}j%R9uLlLpipJHonAfuudeE z9^w!Bk}>lf@1>Kh+9=rX2=KFeDP1GcC`-a90Pl&r7Fv3L^NM7twO6z-Mp&7?mCE*3 z-ktUBN1Up2U-#w#SO<=sAKd9F`9_tb_!&K=)AVnlIWTy9=EC)@GQoetTf+2I+Pyzy_2%6*?BwaEb zq#ktwfnmQw^s`^!*6gk@akvuVu9^8sQZj!4lv@?bi3UDx_|i^Rk-mBMJaYs3BSSoV z*GxgPxLS(}+L?IyFAOM}&eo#c6M4jpR_}|w8@)Gn72Jf?#XIj_rMq|Np>P9Sf@l3+ zgK0b#;W~Yq+D;UU4)Zy)SK4Z&3-XAsYi^37%LOx`q$eE0ZU>$t1-m3C&{?HXTLMMh zwC^}xIwVoUVYCe3v0v0C76-UfQt8lJ1_b2ykt2j^$t11?bREJJc2Jyl)KhbEI%X$i zXHF|%Nsxfzri6^PhA_QoJGe;eb0X?<=@G*ghCCtEfXy}OGR2THpKEDgR1>LXLiX64 z*#rqrtW5LG-`gX*yGhYu?jVTc8ZHJ6Z3x5yiRVNL-t&O$oL~cqwTHBycdfeAa*8G! zh`^v#&1@wqy#^;f0(u4rywRnpWvMvdy{gx-PS?TH^$MXKFk<$TEdN+d2*fArruV%H zYM&X}Q};m4TWGp0RF}gwoSRu_HRrdQN95T1-+}F`M8`ZIw;P+8P?*3Q7FLyZHRd9b zder*JF2{Pea@RsU&FPo8Y`QgX@4ws@;9In}^-cI_S2WY5ev{1B;VccLJfOywj>yN_ zv2wTQX`wX1Jx@vy(I>csHJQSQrc3luU&js~Myv`K<>|8P?8X}Nl?HQRW^FvbW_!_m zYrOxcJo|HLrn%&Qp1rysLngq(_&ScGjA9d0AO3z~6op1L{Henf9TvG;9C@gfDY>CF zq{mDn3HESLF3>`M1jZq9oGl|EDj)hQk;ptmk>pY=@xx5@TkWO-bx853ekUTMNf{YD zA89^B_Gx`J?G9a?!$C}-&$Ddz;SIGeM}0S*>8}GJd+HJ+0XB&XOfEbldH?S+BpU*{ z`Z<+oXLEB}WBC#wZ$^15PDt93AJE@Bl=l#naW^gZUoFx?cqw`Amh_CMvdFlt3%iJr zWAaRkI2+(OG^ABD#4Tsj3#;>-8?wY6J|byBNk3~^;Vdp4zCvv7YG9}5jsT$LXOlI@OroD6vr;M}Lr>JS zNSo2Ia4NC{%nIrvTSjbX@+qQqrJxYi3aviRqf*K6W03Y|`(q0}1sF z6&B7UQ5t2|=1FS~q1&)%%XYin%Z`X?8{sMP9ah!f~0wU4Vg#5JV?TefSSgT643X|JGj$ATk(wLu_ZaA z3*Up)n)aY7focCv7F40>F-A(%e2G?h!Pa#{?n!ftXiDyUiOE?c3mKv{qPPp(NysA5 z4Xoc9yue|y(L12psMzz6Z6#cjpa~*>h-J6T0}HP7qK&H(J!rU;6*W8(O+08QrBc=F zHwBr?@9gW^XwVKBnf>@-obFu0X9di0r~MZk5g*%~czI&jpFwDP9XUEle(OfBfc(Ty z_T3XB6)E&@Re&}Ei5gU3IH6aioTWsYNKz0>AX;6-ToXnDuTZ`Wcs^*XRRXsodL#}v zO)t2%NPCr1#+6Ruml@d;$a=u{I`bwOMc76l5SS$BedG;{-wG=8AveAnie_QX zegSrZS5cJ*xn(_9mjXRDUse}tpRE^^Pmu&QNZ+VlXe6-r;;FF*%I#FpZq4bE#g4^@ zv*Pnw`YvAytoZXBQJXU{P<;Elj+fJ;2; z8V=4?MIr(Tyr_;3c5Om6s6}|kr1^_|EtU8yU!M##g{Ud$ z(ozmG2~N32!x<>)cQMNOT&gRE-v?b4iKci}9rt!#$c{N3?sA)6KWu?p2L;mT!b_y6 z^CaY@%7vgRQ3_EJc`Y!Eoq(p#29RGshHQJ=szaemC*FbdnDpM6dtAR$=m`Dt8=C>X zX2pW85|WS`QbL_H0&O0z;Td+^3^)>X=; z?=x1#Jb9TAgGo;H%lx_+{2r)Rf_Vutp|lX!uj#b##+cG$>_L+@e0%O zl*Ufbl-y_(^RX%5voI-9ea5eIW8uHUM}Nn&5P7nhB%(1fjfJPfs@U*A!wtZjIeItHf<7H#-a%(qB&l3PCP#5x;k%3%~w zM;HNjXzY;yuVhgvoEK1T3&;%dB#Rk?hQ_Yf9^*4>a z6*>5$%>^AT*gjIbHfDGDW_O6vD31z$>{5ffJ{n}va*b|4X!8LL;@p82C;V+9+)|zl zu9Z(ksM+1BTG9KX{NwNzEFuR^STsrIs>B5G`gJ;-CDi*l_6hahJ5RzE{e()${}@>0 zb1{@JNqR-iow!i7EsYj9$gNEC?_CyOoy(NR#{*x|-d(ALoAuxp?|`0!U;hwxix0ns zR|NB|A_(rD)GBOcIWA_`CBte~0VaLE#;gKc%Yj(eO^~QLk#OVIhVnRp2HA!BvGXI5 z9*i`@7gH$vT%9!e{cXrzX8!CSUV=w|4Fj7lG0i4MF_3_e#H56T${#*udl>L=8@m+}rtC zbrT|}scI5-J|K29;$C;S?GAXmO(1qY2zEYTc3Y5)>^vv;1Xew({3my8c5vtn0r06H z=nR^#h6vDylBowN)(2z%`wQ;oGaUF78!7u1qn9(j+jh>1{3$>{;Y_}5W|*Bp>Lrw! zC?;@Er%g=TWF0*^+UBg2{`;i0XxvegBe}T{F6J+ySr6X%(C{ZA04u#m2=t(5gII^G z|0C5p+w|)s0<9L2)0OBlmdJQRU{`Y=7&o>&^^w6Hc#gNG}4=E?G0A0xb*VhB>1=I5(StWs?LJINlh4+i3r4h2EvA zZA&((NKf&nRWz>)=&lE(>q+_RMyjV(xOyC@EkuzRX-@xM9I6D0cCkV$Ba?_}xZ(qu zxhHnW4h9)8CXP`Hhq!)baB(BbNwx!p-{#oLX+;SH?_`mUX*Y=pDtStsvSgdzDdSpB zkj^*j!}T~DZNlE&kj~W@{b#v;hN?o6h3fq*p$>~x^*87tiPNvIE1UV~m!BMC#_2%? z!bI=|fTRilIRa~kA9-{vr5}pRS&*PQqM{x^hx__}&)HSZ_wUPw2+}EpKn3zcl0RKG z%1_k%DPVf?s^_;wt8Z>s`;1a86@Jb*aY?iBcdVsQIbHLX(TE$f2B? z+&7ur`*Td6P|_^jyw#yTDL8H!DM&KXUmw4cKJPXAyF?{3>@aWG4`(T13jVb96;_`_ z34OKXff*`&$z;7zp%QULgJYdZ=0bO`*c0TRs-VZT;7*OcHgHlU=wwb5Ea`trPs=9g zi6JaYLCU557K;oN(*O0+V<8D@nOsW=CBMcV7YZ}FZ<;2`Fy5d-Pg}k(>LVihxjCy> z1whBm6Bz2%)Tg~YC1B}5D}M3}{yqCclAk_(ke;P4J#EB#RR~{^iKhSdyJAG!e5PsW zlz#<1SkrecT~b?DoAtFzB|hNO@0IjIb4M!W*_1XtTTu60$1XF6iw_FfD_)7orf(od zr-YLWzaL;?wf(G%6R^7dSJ6VbQ$EggULd1s!V_%g6K>p3WB$S-RhIzP#Hc_(_U!+T zG5;qP$@34eNJVoSQ)erEhkt>P!fuAfc24HDHva`M$8SmC@S_fOi|1JyFq@aX@9`me z#@+Stca)G7B3seSepRl`orz#vflY_1Z`Ws}>K&eeJZ5TO3-a$glO`y0i*J&H&OM#{ z?Fip}J2}C2yLYr?3)EDTJOqM{$33P89fQYhf1OCg7b^m_5pR-{cU|$2=7+~PaUr_X z6F$=v7=5tt7-QeoVDCIi|E>@;)@2}uE=d!-;Ij}1%b^-{Lju1#$1JR=SiCKQKMIXp z{Nl=F+-}iRb0#u$lt>!GK%~Cg-5UbuiCw0|6mS$$vMl}I+{C~ zyBG@@o0!{}I~o7KPKQFJ6Px*;h#yV%2H0BBAi3aUaLynLKgSmni3i{rNhmA?g?B^` z$RrK+-Kf?m(5`&lkVxR|p`d(-@u3;c5*5G^D`N}qC(gZ?wx%X7o3FCFfY?J6u=8i; zXJRjgRrdECD5b|wd@_1dp^2mF*~yb`%_9v32EoxVuv`MU?eJ`)A#T2_`voLdcnPqb6?irzv5@mu#=m9O|%M@>P2JldrK0Q0Q3>UTmDAz&08t&v643 zP~oO(I?rD^R?X>dat^6IjIgL9IE|fuu$`2PkXp171*oI*&)X$uctqeh&)T4%hjEewT^Cohr(*Dh*hrM#`2Zz+&RjOZ@<%ZxyyDrCYkH?NrAMw86ZH|x-@nu@@tQlR-+tKCYVXVaSsu)5p#zmeZ(IfU9dZaQwW=u+cJzud`%#k zCMPj-(ZPBaOG$9i8RiHv=lLp)L`()@%qQ7&%Pv&CPa)OQ2W|irAJ542um^-FNjwlc z7{8wpN;;}RbpB(II}r7PplIG@1?Mj1WAv+Jg-!*j?BI}BhR_*j1(`m38-v|W%(fwW z7sRC|C>5P&PxHq&UL?=Vx4+9v{Q%gn!hf9y=|lYcI=p6S|CihSpC9Yjo2`Q>oxYvE zp_wtAp{=#Gt&Jm{wZ4-X6P=a0jj_H1ouZw-gQM|(3TOvS@Id$dL< zLb}o;_vh$!bl(q|v{@DcSfS(h2!@H1F0<3md*6ESWdXUUVHQ9P>B*=a?qFBqQx*q0 zZ%UlsRqRI34WD*Z9*_l65BL|NX;QAuF!#Eyi|JmjDC>~kR1;T-jLLZR7E4w(kz0Lq zdU;C_l6+Nj7EFat*L(Q8vzUPc6k%Uo>HqrwKL?vD|35nWS2tCR4V`QqNQ7;i9Nho4 z+axKj{k6RCtW{hLSka>XXgK(TT(TF)*?>%!BT+&TU-*sWr~6hx`9P8(@o?#Ob}S+? z95R9z5J6C?vlRAy*vQtTT~ zDgk4_6HAESV_=)391({H!Us2-GT0)e&bDZ;OM-XAM{LA{4PUNM3Z!$2zX~q?DB*`R zFVi=^a3u%au~8u;ubRHYdnx}8j1bC;Q9FrK@Zwn_y*i+l`C0s^+vj-a!-Eem1EtI9 zaYtXSF52d;;d!GR9mrMtdx!CNCU;tJurUxcZZtRF5RgZ^t-dbbkfxk`F2ox9sN7Bq zDp;1vs~|>f58GGM#4+l4qQ}q1L%2i#wrnp#4g+>xX)rD)KMAM#KgUGPKP!vYz7GK9 zZ+-Ueo036sz$AZ<9%^3j|@*%A^u9%G-hB+?ljQakZ{H z8k}U0sA2>UKf(HZ$f%P5k1( znA2TrkyMb%)}%c#wmi)wsiaeVJEwhSK=(P`cf673{XW0Zp51-ES=`#+>4CPn^#$T!95`O zl>c>fS(hsz-DmWWag}kKdF8cr^_Y3J-tkmzs|y<2;|@AbZ>Gl)?4JlfdYD<~o}%R@ zHLMTH84SCO`6rH5Z#&cv5qAZ5k>UI6toz7zs@0H_Rid|w%#qVRoSI!>sXgeh{ESCT zHrJ=pD-H}Cs(ienF(`_g*04C<)gM4$kH5d6X|s_?##>+}4VN&maY@Yl?+l)sBJ+8G zh)ml)I=dA7g#!$+z2~}23@4x=eZ2MAfZH@hWND!OcZVUyE)ER%s}bKM!8L0o%FG|r zo8NN~ewW8`1fPdic?Z6}Z7V#xGyU31D~eNaTtV*-cF9Z;F0JMkt3i>tOJs|4X2F*h zuj}W5ih7u(UYitFQ>%k{kro?~v~GlV99lT85x*6NCi&zV2i@L;DWG6QOqm@$5gp~x z5r>~70c=FEEig0hDBdokhd#knVwEG;Y}7NXqHGRQQ9A&2$o4f_G)8h0EGy~X#gUVL zYG2TQ`P8RxkZj|`hm|Ke?BT*pOrt)wJbV9s6XUQuZ-73tOxcA0eYiX93A{HH`+ka2yY6sAnOr-kAGT)^MK4s*&anOsaFQ4tuTX z8+fmC2SP|&hTYv@ncr#tR{6dCKxh>!Wym>$5x~n$G4q;?o}oDg=#rWm#h|#DLTydP zuUw0(;xXQRfAS53mVp^K8VP2;=Eoyo1n6^{?-JKN|CkyvN&h)qQ9=6pvN2pdFPiq2 z`gOygXm5{fY8Qo**L+v;sUd87yPh+P6~K`(4{%5S(@tv&0vDg-_Gc<)fB=hk$PDby zgwdsRvJF-m!x)!wtgGPfgxVEVQWZy?G0xvv;G0yxn3Lj@_oI>?%eOcvuN)(&5r&YO z8=ANADaMa?9jVsp+OEUlr&h-)y}ingzhQMw&I)JfCs7{VG)qIUx032oW>f_A+}<6_ zUG#)(-t;(7Bt+RZMv&sONx(WhK$+)M%VMiNe>Pvxu%AfXJAK7=P4zdW`+s=VsTOwu z0^;9~)Gab8b}brW=BT5X3!b&*9c)C2hzx%lu1HPsB-qjM{YtLS*n}ZKRX2J%C>-JJ z_lcusId`6_L6oN&lTRj2dXHZwNmM%{eKN34$r)Ou>;3F#ZV$TPxvrP^g;(|j;lKM` zV3&g$eVTZvQO%i8qZay_#J%e4U$-lMV?|)Pr>4!L?nKlh%f0P%&e&i|Zwvj>Ljtm7 zxaEJPVS8o_MyxB;j~WRqn>EmJ7I$^*>6KYlC_<};bN`l{b`A)6Ptkuc)91TC9N$Pz zvuk(OHJyQ0sIA?A#+P6|)t`hW8=8Ah%6S^=)-5lws+J*Qp1DjP@IN}uwdn!jeAGVP z^;9F&@g?=~H30|?3`D4r`UKJf47sU&`obR+aZ&mD^#P78=i^$Q0v-GO4&V4;^TG%^ z#U&67Y5wE{AleWMSwe*c2auGZXp<28;kn`5lY|zZ5oU?7d3^h#=~nEO^*sluO?N6I zdX^JX0{gRPzp!1w?kY2XLmU#uk6erci{BOSgNr-Fs1ZAn53`KfS}Il7xCQqbT`JY& z^lPU(Z@yEJY;Gu5I~V+=)_7M?81zELS=(+eX+1$KAo~E;2P`f`zhM2uDLuZgp_q>Z zuXbomolBE&?23bykgjXZ%$?_itgIS+4U_;GOHGV>xA4kyq1pkOU1erPknYcds4}|3 zGoNt~#xg)Rx>7x|Vmq<|M~%@R(#cMg29L_ypNSXS0iO{!4lz#eB~hARDt+|JH1XFt6cIe9NzK zSZlqDO{b?^rq{E_4er2$bf z=zORUk2Mn^e%L2+I6>x>(2X`hL&W#pBE=)T$%yv?*80)f?7?9N1idC!heeL6h?%jxhmAq-1kDlw!`T8NyHr7oRJW`yKWry7bl zgJM?Fwna0i3VCa#;W<^rR<%cJ5*kXRV+khoALBOVGI5+0NLNN(v|uh=(~52zC*-6_ z^<2lYjhxQcTI!iH8z%;pwifXirfhMRZN7d@hek1{XLp)D(M^GEEV`yW&~i4nRU(8Z z+7Ti&xK=XsweMjJbkCqrY#WuzAOnx2MP1$UXVp&}sW*h57HeqCvc*qi%yN;8P3S{^ zASBI2g~Cwo7egtbND@gn6IqUxIYVDGaErW@P6VPYg-GOJ5KCdmRJ{JUuKWj#v2URiM?*6zSX$ z@)?n#hdNQg?Z1n+H9|H4@V|<;xgh>~DDt1s%g=uhiu@b-OVCW;#`Ft`Q8E8Y!)^a7 z7KxIRmhAtD=)J}o6{UNR;U>-9653pVTA+rg0fytDJ5Rb&w=!a)`DTs(0{SMuO9GA{ zKm^)9!F|}tHt{&U1l$8^i3E@`oX^FNHOaMc-4Is&Dg~rV{JXuAouSzPfU9 zQmH$I7GUH^;&ie;xsaJQjPo*XR^mXUB{K;Y7^}b>S)TE(aD`q--<5)nn=zZr9M{!Q z`m$)$sTR$%w~?OXm-p6K#VoYS;*^O)74wGknnH4)`aK7gne1<`jkkijN4OLs-jkxF zxW1ctXxP2a4?&1v{Ip|)V-!pvB_3F)N2rUP$U`Lm?&pk~W$o>{O4YxKrqx=C!Ovet z-1u)S%KuC@g#Lk<|1H^IBvH1pwly+0G1oV+GXA&Jqfp7(a$XMA$0nVXE~+S<)49va zVu3YtvaJ=NjsfBA{($3J#h4JinAp_WZHA++ zOxNer8`@7$98P9xoEdvjQ7Bh9#w)BEd)+}$P+@K*d3kx`A7ngyO{&TZm_2$;{y&A< zz43>?o0K&7AI}^JUfu_u1qJY94qW<@cRDv;LHdhcO7_0u?U3plRa+x(BojQ1vI^$M z!)aX5|7h1&rB|~K=OciF7rIL$xEp2Kg6A1Kh@-n$C>@!?I(!J=U%uax5%A-$C` z=j53&wHT+?U}NGgl<|1#0d4>u@m0o84*s2fjq{trawq$ugH{2n$)_pMx|mzLWXW(j_f_zBd1SAe^RJ-CT6Gfw8- z?(2I9GV$g5@7O>Loi1+OM@V1PfN%1Fsfbtajf@?X)F>k9{r*vObiAm}I~#WuwrTWQ zoQB2+bu>$@e8R^l3cAJ;x(%c1qv9vpa)nj5zw3ewwMz;9kdXS)t8oo4uAd^ZBgRid z8aIwFT)LSkqAX-@8&NMqbj>CPmY}aPY95PSi4X4P#z?f;{$&+~-rp?9xg7WYf6I;I!D1UN4Nu ziI0Gn?IP0L^vA0;^N4GmGNR)^m9h(CpNgA$`cM^jXLY=)-tU`G_>b#QVyi zGk34?hY!U!(q;iX{mhWL6-8ilylJQuOr59()SW~rS?#%FGQo=NHUC8Q{DzqFr1)5z zj{P~A$241e*91w?N}O~CQeaTbNabmiy6qc6#0I7<3I0|rWYRj(aQN&OWDnW7)h&*K zKga>%gM@9h{DxYt(1I35%AXDFb6bVG@yVA20#G|EZOsZ`@a>d3jvyi2!=tybW1@x7 zi8X2REt-X#3c{x8ZS|B;&GJIuiz^7;>pLKKIjY-+%RRpf6B6zA)6WEXLafFz#)^b* zib#6*$UPw(FibSXX6E+axIRQI&h2SfL+@k4uL#*s_(7;9zFY%0~zncgukI+WuBd{%a~E`11WVa+Q5zpv9sx@lw= zBuAcrc24IrtlsZ%h46v_c1MAD%~FFZIhaF9bb_0pn%F0?RMFnh7RmH#W@_^+5&_{n z9ScsYs4P`P^_wuW0-7jGo5YWzxH8_VS(cJ&_wJzzBx!r2mS|jIxe1;4?wj$nY$U84 zB9m#@In-wIa8cNKN`hBk{0I4ZCIqjv^SYK<(PrZ0Oi}XbZ!F~SfpE45blRWQw;n*ev64uyd@ItzT z$yBM84Ruq~0KPGdY-s40%NXPHTx_Er3WMGNyXr^`#%%} z_H_Gz9?M4=VLg|0xa{1H>KA|gDpEuHL}8v>-CG^8--F4}VqppRgTi%I!HmYsmJ~eK zZhZl{*C1%ZBv-=gu&y1kZY>XKB4#%GVhuMf<$ZB8A;d`O+73x&Qjo1fx-6nKqW&O(&0SO{1W_Yl(d zLl#>5Rzk^4mj1z6W-Q-V?wa$O_Z!k50a~lG6;d|tYcA^juoke8C~y%7eqt4QkKwy} z?33|A=EN@-1*yY39DNQvdTuwL)jc&VwW+J{(~{y&u*K2uH`rq}-4Q$Jly)Z>MI*hW z;i(rf59(vg@_FDbIO*f2df5&$#;X^m5Uk(2!Z_M0qxDmV{ofm$GzZYW*EW~8Kom<& z$B_C?;k2lW(V;QMgiRV0clWqE2G2FaWJ+Z5jj~u6PN)UA*=X{P(d^0e)(aO8vKPku zqVM<&>ZQP3Akf+G2s;!+q;0!L+)SB%{5M+il2e!La#n{*_KC#z&8-?zg<% zn|wf8hN!#L1F?vQ=h-a|fwyjT%g1b$kxi`{yteFLn$5jsBb5)*gMmKW;)=5%SQ;8g z!3x~0e=tb5aI}{K0R$;3iGC|xXeNmTD;^(^HRNrm-|l#RMuCGNe42fcQqf5_|X zDN_*1PcD4=PJZR)Cs~$79tFk4%3HcNS`%yG>PTQ-tb&6HK(5VSAhjJsJqB@p3+%_^ z?b}WvcIR7UkXik_!}-fw!P*V455KJ9|KIkz|Fj#`|EJxAt&FYzk7GtDtjT=c-O2oZ z4zj5Re$|y)G9H1m7Xd8L2TDSwgTDDH|)M;afl))G!#d z_71qxa5&1yTBlBDI849%`cgQfbkDaIQI_QK2ZiAbo`k2`h41lnV3ZFV3T1xJftD=> z)LJ%uP%;JVC~?qONoKqD8%SEaaZ@$gCEOt*iEu6b0$anmc-g1DQ3-Z4$2YPHpg62? z=4>8~gTK=xKjqmX(f06&01GO+bII#ReqCubP#K?_4kBc7FXl4aE`^D|v?FgZC07)5 zxEaK&BYs{G%s~#&klytiY1AlLAri*=jiyZRru$Ln;pR~v!qGE~ktFqvNg(}UU>d{; zWz(k`T!Ydnq%K4Qbp@?xU4?J+DX-x8)c#TYfu=QY_J2|KjzN+}S=VTHb=kIUyRvNC zwrzLWwr$(hW!pBpY**cy_q%c9otZBt=0@b7%zv3rp1t>3Ywfk*9uq!xkpA)f=sH%~ zOuwHU#6SJ-|9^qUM&{pxin)RFKd5m!DSbODeM4iR|Ml7bTWnRd6|t1jeOLpj17q=L zP%W`3Ebe9{LKl)_BqSjkd#?$8Qa=1*%b2e7ss^?S`us11atMj099xN^@qcAtLhHci?7`g~yfA%0-2^(5HWipSl$I~{T>Rb|rs=~>v?<{^@8vce18wq5f7TH_78A+AE0Fs1ai==C^XBC1a4|hL5aU{h zPef%XFCdzxo}N#~R8g5Wq`*nSpPoF!qmOB<$#8Bg?5f5TA|9~HOY9a7>mHlJHf$yA ze^qW`_Lv%YWJZaiN%|I;W{N0)F{#%e!!TSaOj43i#AH}bTo{X8RUuN-Rh&c;X(Ck- zD<=`&K7?4VP95)&U%Fx$5Z0;EOha?Lf~-SWkmw|AT!y(`8aO_?zng4uFlk`G@3mXvH`RL85$2|B{NCQ!# zRC00xysCGXoTliIPOH_IUdMlGiWJpS6c7A$kUS=#6&b(C&zY!RjukdZ9|Uw#%@T%; zMOl&BAX8?ffqYKdV3Qgh$7`fRnWW{YMulfDgH?W+NI`5r!qp@LHiKCrS4>024C-RICCFYoF>{-FPvlrZOV`ceZM0+Y4#URXdj zkhP3k`<`eX_siM#_(}1Dy z)=o@STZhx>$*1vO9B}3jJTP18Q9QK*7Nw++46)%C!!qFBM1^KkGjVZMheUtUW?@$k zc8|n!VpLjmK&?uca|56EnxHLoE`;gn6NyJmp!s3%_{l+()Sb-M_&rWx7f+|ezGY*2 z2;4gYUgQIc8?^+Y!xU!T7YcBU zxaG7Oq5N2=SHhfAJ+dH{x=vsdj$MxeOB~?OCrEV}7pOy&x) z&03fH!VH%NhOMazCvYJM6=giuEWOK){13IC6IsMj0$oMw#I20RC;%JL`3KdNfT zN6Gf-_q~`4>VM;4|5{c5BS7;{RaNkt5_i(Kary^b^Y5j#NJ&%ndyf4qMpLn{rh?qM z_7A5itwigQM4-zBRTvD7KZ!`Q0aLSfJ<}=wM2y1J^`04sHN#Io$$%Tm*>AX+Xrz{; zsSAVa;BuUL@;+uXeH^};*8Q0|;0Bao*NKD~%zOfo*)s|(v+D#T4{eD)OFtHCA7prY zn`x&t-+U<}%~)$5OoP;X=&^Bo;$A=H(68XJ>8O1crKmtula^s##cz0uWkWsxIvYDTOT{z#nAN>whI%QX(*9Fx{=Wr;02Bt$Hug4?E zGos`n{?sE{{hoVFN>}=%dFOC6mS{RRDey3TtHFb?-oFHTGg$X#e1pkyFWC^yeU_R^ ztj2t?RE=SFZL%CXtU?w>K4~ve*M#3q3EDYKqLrX^5PotLf4v`8Im0-#-F>M>#d?@( zMK;iJ@Ud!+^KR3Eh5jl1Qg?@9ocxWJq?m9ME?}vYKu&e17+1aT8W_U0wNoL<`qCwk zO6ZieMZ)EZ-g3jtSsvh_NOV^p zhOvs)CB^bLp}D45Q}M~jBpdd(N&O6TZrNtLNk%=O4*x{X!$DEss$XWuu`RaEr{(rS z4fJS6l=rvvyB2d`Vows+L%qfU5h;{7vUqZlTi-_wTnbCcFgoh2ZNa zSqjxZ2N=W@MC-C#xDSZf+s#3m;_ID~YJYKIPG$(MM^+^loB-ce}yR2>YL!^zQnCUlR0&A|5CuAfHbc>vRg3vVOe7xOnm3>$rf_ zoj~p}cqGr>NDsZuEW`qw9ihSKaUqxS0?$NiAX`$F7+ytAS3^FcB%B1smG;kq&R%qt z{YN=-2}a0gC|}e9uwN>Yg5a4D>EG6%xYilZdml%hG~?lR?P8fKOi?_y2fSt&k3U&c zi;^dZtm*NZj7-+49_+^z9G&>TUAjFEylRU`_Znt$YxU$(+m#vT3m|>Z;r?-U4}<03 zztdHJOo08Tv&;9NCfa{GyHd8M-@}l(;lH2TEai1aBxUrkEauT>$(4m>KE7%lF-+Pz zRKGa~3Ta51Jc>f(aI_68xYM;s8ZG^_2!)GF9o9f~XxRhwS-< zfzdk5Yy>t)m9+$PdW}&Sq=b22kZw!zf1jRkJd8aR<==|lUx}#oqJXGkv|DblI9n!n zu*}!hNE>0S5ce-J3|G6iUrhc@o+bk71&#Q_6iCTq99oGf=rqtMeFZH@oHY43%@{bG z={^NNoxz%OOGR=ybwUzB$n8FikCN4BwgDd81(Kj9avQBVb)vkfwu8}MrXyW#Wu<7By6a|P*jcfDCqv?>{HeXe>gqggA97~GrPVP(fBns% z(->cdfk1!_B>XM$a8jrgvn+I`xZ9{s+rrV%r=&Vsfz)^Xriw4#Rd+4M`HQ3u z3t6$F0o~AAy(0qc*h*ox9i`9qI8ck`iQI|S|HdxRVS^+9vQ4#7ys4;jjOK+$-ip#6 z;(xgCwfzEZ$_j={Gt0-;S)tXEO_HlK$H4x0do0=`W0U`*(9rl`luhi1b;kd9mqHT4bHK)B3_+1qQ zaQb^pP)iDOP1P=G`74!7^8QY+QoNp4jeCl@nD8-`Q(}n1^t=@*VPWHgS-_mbw^MS? z?~D8N%O2WuK7Sr8E_393`IwdN`wb!&`VULy7Pz-lpWh<$p#q)TP4`H(ZOVc19~CFh z@&>vI+cEH)qO~X`H=NuTWFWmapj(M}h|={;FT~GW#BaTzZ>9q{MPEvT&neCmzTn!p7IZh0%*hm>(2_NH@D~!lt{=(0l4_B5Pl_vzFx*7>vrXi(DQvY_L#d!<%_ z&^7Urv%xy|yEGo*a!&a4_6@U_LfUmU#`cW3DI$@iiyr$_g*I#~JP72ZnBkblCYVva z8BPKU$5a}XBhw^JZ`=7)7=NDNxw7$DQwobMod%8XT6m-_o^bK=x$`5zK%ps7_`Xy%`&Y-mKEvI|WoOW1olTPF&0ZXy}vra+usA)B5U!!LF<= zcs$nYbNfG^k*gFYoS$}4)aAavMMM=Khwa7*3_u2yT>yi$%X8ms@W-q#_}BTUi&_=R zo3Z9O{7dyWFZ?GJ%K3f9|Ggao12VQhgU@FkmE#t`xDoEPg6ggjJ@x+UAH}tRlUVxd zdoV)%kAu;F)GGZ`ah0<*cXYJ1`S;pdr0VXbw21PxDQ*&+2F)Zsa%+$auP{O{)Td&{ zhwmqj4@CfvDlf02gWDgQ=H5>&ZYNq)+GKHtDAd?&p-6>VB#_@o+qks3RHUM5+4N}n z@f!1Z#%q0H`r2VjDma1$PoclX^|ayWW7>9{?YTX!3wU7u&G8&zJv!Ch;hOXI#*Oi*5$CbYi=^^*6rT5tMOsDgZ-aexK4Wn?=#Jf zdMaCF^V@CnVP5y+Wq7MMwMZn-b=Uwx0=Ttco`4tGazMJ{!^})95^pcTi`zu=dH;Q3 zRdeOu-GiSa3dKV!Qpk-W#A{$6J0YHEl>&9u2Rx`%lb`;erlqui2KGdMf|~>+w&R}Z za~loKcZPfw4ytS6#R?;|LvbNQ*<0g+w}{AfWt9pBDtZd(x!Y9qJ`joDYj8UZ%^97x zwrg)u)Y;kcVwJ7d{2DDjCdjv`SAJL_rnHSxKZSM=6Sda%($-3SagxGMzxO~~xU$_S z4*&vVJ{IOEqVy75wf9aN*4JxJ;BOj>0U`@EJ^2U(xTR7C<@M@iGZA8e`}ENC4W61} zrbMwJL7XyT1Pcx6mmcsX13y3)n~Bha86$CCau$Ko2Sky)TN{FQ6yreX+Is53e!0=S zdIzp#U>~Td)p1CE-hqOI$1f(<+orygL=H0u;fE!qLcy3CRj$4R4kbvn#ZMl{0mQ*#$j zN>rx3QPcv_7&Icc%j%gP% z+?j=eh8>t&sABWYMllG{vysACM0m*K%Ik^*i{b!LCghVX>77=Q_3f?r1(iXy2b4`wd<1zuJ? zlzw+p&D$$C~0Z>)UihoN@pE|X*Kxpa4F_J-%I&?I7rbZ1 zL~^bs?anyZwMtk8;@qXfvO_yQ`o5`Oi=K%}To3tKK~4O;lE5$H!AN z`yhlMk5y}u9GeaWkNE{)$2Aob6=Gwftq)w_ZP9ogFl3drk zwi(pe;CfV83RXCOyqUe@16FMI-a-XlsC|4ubrt4buoL2U)kIg7m{?2@+5y{Cs1F}&4#!q{bBEKkU`&m*WH&cTx8IU|{p*`zB+0t(&LKY{s?Euy%zfFeb zO+=EXsw1hF3yqAL<>Q=92rZ8yg&d#DO(NT*TS zvjRwS2qo%J2}89vKUi?F_50JBb|=>C()ABwk4}^Ms~M?O9m=a)X05ByR9=CR>n2+waL(js*{$-4dxdDcrm zTBZ*H+(ir~Fs50y#O+_A?z@F=yM;wVKGfvfa4AlmApsbNo?tgk*|%Ns456dFgi;iJ z3;bSPlJO47N(E1Ws>i7rJK`Qs$QQVR41XTFgG&(f>R{2rGO~lEW5ybgxko*=Vs8L^ zKJ5GM#Ah$8$(@Ng8a_W%o(Se$D~{z}bYe)m4yGq_OyTEc+>{Ma=b<8>g(NeCAPuAq6@VXlDB6}Q7Z#L8chLMmQ;pMaRzE}+c z2ByXDtEppL2-D=M8QF4V$2;Vc)1qb?_32@iM{O9BnSJ5~N9A|mB5L{STu^RI zPG%22^~oMRkzKZhgLAmu5y((tj&k@QjQukY7ha4o@0-VUE2ZQB!F#89;Y&qQVvdqY z21QB*Di~pm{kqkOW6Op5%3nq;fBG(JoZdgTXR0_89oe6Rj^bfu1VzQK`s{;&32NL z+-yF5Axc{yPnjekQ^aKY+%?8LNYzC}UA+c(q*=C57?rq}M3|(FTLtc{uz+-a`-Yse zr`)-qlcyF@@t7{BfmWr2B$_-55$JyKe9~C;6_FyQLK#iVQ<<)HksDuUDGBiJtB6l#$dMv|}Cc+2Hm1%7MW5gHcTs&WqRDU{MG z9XNP1W2fE+qb!!(GJ?7k;4PH3NG z9M(FdKV5_U$dIrxyAyJEOX@Tft!2ij(u7B-styXeTz!uU=rQoHkH)%_;`E+y`` zN60IHE!N~9%mVkMLu?Y2LFc*}pCyH%@^G^dqoH<`F^mm4tbR}-yh40+)_n9hN;p4| zX5Y=00FvoRc1uUa5ODXzQ%yA8Pu(4LCXPa%LU*GxFO?G=(f>?ZW^nZIvE?-WEY~Y?)v#Zpi6Ev z%tXcaoj?fnKY=c?|260$ZSLme>|iYIZ1v6m>pPh1JN?i4(7)dks#LY@uvAe#s~hLm zZii$t$=S=K)8`b_Sy7@j$(pf|*uodEgn9Jzt*L_z=zu*8#7};*eaTq(99r1)zGW(HCxHXqsp5K0QFH_T9ZzW%! ze+7Twv=;8&zyoK4@A`O^!Rih%pm>1)l&TP0<`*Un1c%n)m}100VInX~HO5dJ41>qC zQxH}WrVXU2ecn`IP>rbRk&lBTfL0YI2*h#APiCID+ZR`H3xA-yK0D>~LNR@QpkRGs zj>$g4(KU3QuB~dI?5^I!0_r7$aWq*%xt1mYZj4NG#c^!kNpB{pj7zRlUa0zx{E0h{%*BFt;no8x# zDoPtl%vx&LZ#TU4v{$ec_?;0+Z2 z694(fa1z{UgB9rKBINZg%3m7xkjg|dMCk6Q6^90U54D;XEc2=70=zyl&3kxXxtZD<=&BN zAY|6isZy>+IEP<9-pJv*lwqaOSFJ={U5~dKgV9l65LE4D`q^%1{5)+Yi-S$=b#`{6 z9E*230MkEoX0ELPbhTf_oKcGAhBDudIvi8->zK@Ujmg>EN*V^z+q2i&A}wv4dzjrJ zP(Yr``n#nUuq4O`crOgRdZK`=x66*H}Y* zKAH8!aNk3Z4zh3ddd`X$Tx8SZ4ha6nb{0SMRIR$8s&P(%c@k@|pRTlp>MaEkvTm%} z`~y80VhOIre~r0dyZ}y}*X)f!;MaYEvfxbdu=&$B1ye;-$Dr7d0bA>-)I{v8ZrHvkEHY{J(N``;OaA8F|QK)8eMQgTo@`Jfy@<8Iih zcF=!{Qa^vrKSRwugJZm71z+oHEa-^@U$cWe{2-;seUlgLwVw%@o+Xe;KjR&Esq2<{@E&-R!!AY?6#MxL0z2Q9TqcZs(ybX(tj5$&G<(Zi zxGR&i+aMhvfO-PRB{MzdN+kXHdQmR>+L2h>=jG!D5f@6Va;it!FA-@-2aazu8 z3h}`d{E|bW@Gen+PV5Pf_!z5g)jMz}31z9sd7gSy)G#&CMienl|`DNMTmwF6Dp)<^&k{tk(n(1}|L1Q%F1XT@@kS zUcj)kX65ZgaJ`%}^_>R%Cr%=wnRq;3etFHZT6-0fgoFDaemwQ9}uI+k7xlEuHP^V55e7lR0;l`XS>>I&H<} z{o{S&Zfi4xy7TDxeXYe=brMwR>uA3b?eN5`ABS{JZ9KJz7)8@Xu(%DEN3({`wY#dr zw;wS}Nu`5_kd3I5VvF)}{hQ?yrga1P%+rdQ-=?ep1xH4ByJjg$fI{XSa#K0EV*4pN zZ4k1=(K8!=QABd3!DY2ikP3~eWVz+U-~MKnG8s&gvJ`b9zWxmromb>Uh_rdC=IXL) z9+FyzLW_10bv!ogfbb*+>2c+*dzT}+(gut6!t}v=px{2O(QcYq3hR5UCg2AgVMi@h zX}{=PiO1kFd9}W>52aES%H)fqD#>>5mGX4Or_y0c6y2^NyUPxMkwsCtpx^jF7KDz* zZ&2E%H{SWm)OOMac>4v1AV<29O|#zewR9e{+P%}aj=GcvL_tJzomXH5xQZ8wE~UTg z9jg&r3jLp*Xm#=> zOYN6@J^pqYf$2j1ZMn9Vm|suyFdkQSTM?0t9toJF`AaE=>U|micrnyM%dP-x0-oDW z#v?oyvxv3dO?~-onUcxNE{}V*NV*8OuCE{8FfRPrUgA6W6PVN@A_WsXE%qd|BKoFe zdSWoB@-VlIC}v%_bC`;UC$I)(ZwaY_WFy}zgCzei)4z^3G<;Ttw%Z!7JVAAcXSKLM zSSJg7Ulk`UrtfzRX2+kTZCRRHmk@2PGdP%x8j4P9;>o}l5|p?(AZrPa9CGMSa^>On&sF3bQd5Eg4_zD)5Dr+0XL3xirpTyJ7A^h}_z{?&J?rq)0#lp5C>zv+(d25ST2sR{=sU=$3FmJL}UDQ=a6iedSX4C&dZVCYwQQE?qLD)LN zfZZab{zzAM3u@oeK8$*Pr%i@F3!V?NU=N8h2IAC5s`Ca`;t4Fl5u63}Ad=BJ$kKPz z4WCijz={Mb>gGQLU&#nj@i7Vm-b z-U^X)qFSAqh0b+v7cTn%?y^1`a4i8|#;`qHhcKr=>Wt~Pf#FZ1fEa*1Z+#tZng+7_ zEdskMZ8-KL5zbAqJxY=JqIG34;#k@aZm1^U5$a}~P3xYB@)2yTcB}!j=&CWuUvi;z-Ol6@BJJvCN0%oW;(`Lr^X$^AI=_a-aLjJZ zm{`!v-pbcs_Rrg#rtcm7eLCOMNX|XSsjUrag1lU=hT|>A%Wv5w$JJY=;}zZ4-6h=* zryUyIr}9S>-__fWW&ahR&6s_DH+m8-GXKz?>wTkN#c^=?zYXAjrowosK<;s<-Bwd$ zX-?HV+kC>-XYxp8>*^{X8r`!0IZIYs zzf7HMU1b(y{t`|*qqIaLI39DVvPvIOU@n6Yur;{~gXuBU4y;m?&BG2z#N^DBF^M)# z7=|qZ`5SGQT#{=k{L^5_gxb?%74Wbl=~5)fV!5>P(u--s_;%+zunm z-y~-xE|qz#*;q=+iWWaEogz)R%gj;Qn`Pec-sn@qM`Ch1riF=RXAn1rE#xN zT`aP6+^4HlGu>Ll6Gg2{ITP{3ZAZ^f&w{ihrI5AS=IM*C=J`XhU0d4Mn|Y}Gne4$} zwbry^G8mrXe*fYg{!Jc7jagzTRF$qkX!vR$3#OmC8Dng-S){ip@x5J=xy&P5dGe zwNHi~|5IPYU1Iu}i<8S0kez@aYMhWbiPjdD9JP2nnTpPMK^^Ak;`5j*K2A?kt@!b* z0IoYE>C=hbNA(;Y=*==f#B?;QD)@}4Kwu?G{as;K={j^p!ymihwsyn0y)sF2G;$NJ zx50NaR*r{T1l(Y{2#9NG0&(vlt$eS&BztT_?0%wsJj;NmTzi1q>ZyXK+!XgDd@Vx| z&3OCXY{0X!`E%#ffv&vll>BzuLwbtSPC|6<#5BDh^_kxT&gRPgRdx{DlYQvU3+x|k z6@Mgkpx!3LvIq#08BH0#w$Ek-1TjXC(VJc4N@}MoBs@#bQZY+?Z`n8KdDd=#J~Cdu;)Yfm+8?f8!+3*DIsxW{@^1qj^w%Cr8;kk zN*b9D%;az=A6**>Gki*>*gag48gMX6N~Y-E#a94XxubvTWHeh)N94USK^Fo3hu%vq zgxp|fv`+`8=By4Sru}1h<+ym?yJ6$xZ~JE3rQC7|yDOPX-R7hYqRzs%h|R4K!~phz zSD8MhA|{Qq8I(6wW)EVkO8x`X$sp$LbUrUothEbvgCFw#7BhO=-_#3sOUw$kdoXp{ zkYtK-LOL99ZV-$k<-R=F;SuynTtMs*e1aQ>xQ(f7aV6lBR<2XV58FP%?_`)G081Io zITFJPCkhl!bZXZr@xi0BzOQ+_6BA6QBXUOrJXDiM;DOZ3QRzm9+Z8RB*_E{1Hls4_ z%uIW-@`HDMT*w`Y>RLN_-*YAOs=`X(KNltSsR; zkdk{R>I*urg0@W-=2I;$up9{+(T}GvbH^TNjIb(7)F#)Qe#u`MjkXuB8_4&Z6j$SS z#nC;c{&w}~sfOy4#(jmwOKo^fj78I92ebNI=}X-8AlnYv_~M9p*|HH*wni>Qh4~fy zk+#BT=a7}FA_R0Ru<)?e8Bx82-}Md(GYcoO*6@O!m0y8+(YtEoGt2lbR^wia4F%AF zEY-_^1I98}WR;K@R|FQZ>mn%{&LyqGpXgw*{UElwM^ud=B4+W_FA?M9#jBf95@5|* zk@AE&88(q(v#e7M=d+|kpXv0jY2q(G&yQc}hq6kyrmDuBBE~5d^-wu-luxac$1wdc zeK7mzB34I~0bUL~06v7OD?J?5{;?WUa}C1f8I|ogEWNMY(_X5UFU$xQnL|)Ri_|h0 z@y$3jn^%hun;NXGQ_BZu&?)yp9HOe9>Q*m8!8MOATCHAh-YDCca&Gg1_GnwO$3J{c zukf_qc`06X&HDe`fOmB$FBqm==V}7SBEyV?;=_j1*XJXM4pL&HO|pOUEQA`$@$Jfp z(_Cd`{SoZB3P^p_!AchK8^Ha5f=($ZGFbbG;Vs(8YucVdB`|KoM9%~iqbs~pGNZAp7=`9%jim7Y>s-P1G1}tyHygxUv8+P zStB`i*^M%A7t>j7yqS;Zj~ji(H^s>uR$Kc~taEc%1)3_JHvh0GIgvD>?V7^s@{7s3 z3;q5bTc*X@6uLjHT@jjHkY z%7@keMU9-Ls%eL1it_1mR^MEoY@{ik=(#a-vNupJo;lzmb|&UxK%iS|1vX5g-?cST zPEr-C(yRzcv79`|1tXrI;}!sxJ1-LjgK^RW?X4HA@0Qz7-;ed{XRx2BN$St3FUy8_ z<2L7vw9GG$si&;F97mPUMPJ`rrXSjFlkUYuj_aHKSK6)wq3#go-;#nrI#exig8j}% z+fZNW#-u~S;h-sDoxbCAIlfttUnFQ7Y6s&aKFt$@%Cxx7yLWDp5p?WdPc`)n-LLt9 zmbB-+`%{+69lConx<`9dT3(AmHM?hCkHBcMoOqPFL4menZsB>{tn@3qX{oIMW=0nJ zZ0yzzUsjIv)XZFQW=@VRyetzvhTx;pY${BNsZ<3cAyu`F zI;Z!OU#`AympSOzgYG0XH}cAi%$MYU(}b&LcqI)-XI_C5E1?S2Sym0a;T;-->He^oXEh^mBRd=zBnz zlMEJxv1wCZAmg}sGwHpjikY>|TGWeETpnE>ngRkzP3fJ6&|-snxEOH-`rR<0<7vLU z*mN>CX|WNt4@ZKZ{~k4SQskmR+6^f9@ZFpb8T3ZWBW zD~BEb=;Z0@NGtl3IY(74x<_7()uhTu5qdjMBWwR?3=jo9mSTDwHE$OUdUzVvA$IIh zqZWg8tmLC!WKNy&t@r9gZ1F8|4IM*kRa=@!b!2w<=6tfbyt8|U#@KC&44s7`h__0b zwCMngCO;GUql$pW72>$!n0wi%omO&Yir(L_*j>5zsUER}y8hT(WA3LD@}4 zQMk7?-lHtnBEbBU{*x18^Ch&tbmW9Tk>H)b%z=O0sNKUOI!mc-h^>u%dT^dGx}f^ zA?n0^CzW&$xE3Rrp1h2B2kuTRIZ?#HNaz`ADOy0wDafVaeqDo1Ey`FEa0VuXg|epm zC}m(RKsot&WD>b|`&#|Zb9LN-tL66|9iOL-&zli7@DOJf%Uo`g-E#?T{itp(cppzi~FR=8LtZQUbDZ~H!JWL0jGM|Pv*ghWSYB^$Ssuh*&ajz|Gr)@8k zD%YKCAE@jd%+3lk_hH-P4(r2Bl|P#sux}SsW>8?NJ5X;~R4Y1pzCe@2IfNrN*U=jS zLhnL`c-cb)073I>z(ptDUD*!!o@)EDjT#uE5CgR;2`bzLXH8tNgAas6W@qEHWuFJsW9 z&p?xKeM7|acZpE}*QfURed3FQ0kR5ij}kzMV3G3nz_suhH);OL{)ca^M0p%O*(9NL zi&;}fBW!HYEk%E#@NP-rAVnl%(7G9Jd0Dd3wm28WB02pV|PCJwlox~HX^ZQGd~*R69M)%+u)e{ z(7M$k`!@$Z0~tWdKZZpaW7`=xMAFkFHJ zvkZu^uKD}vGhZFRXf7h;_htNE`;wbeb|%(vIx_4gNGzIeE?ez<@Por47CY}dFZeH~ z!zklt>I*-F3O0egZwwK##`UvZ>t1}0g%yEvgmWM^mqfI4-#BjRD>5+6F|7L31zXl# z{8`E*+>|K|sp!P8joor5Gne+EV8Fv%c+sl4#hj{zZq=n+QuXFsR**$reZBVElO?n0 z-~1`-g~mk-(lZMS&7Mvr)w^)DqW{C@6M#9weSJgwk^eMn{42CC@ZTdIHqPG(f8QLw z(Z9p{MXH`o$cHFj(k=~xE@Th{2f~PQLMs40={&t3zn~ymV^tG=1S{#+bBTkxn)aVl zlRl$1s+<+9g&=t>(f}^JvNqbmwYZiHV$Xc|5@AOVzP>#6ftm| zx}0Epdh6cq`t$Z`QvG>+&+$X~xhwQ-1AgXs$oj;!;Db4;*e!fKBT)yd>_? zu&5B=Z!lQQO+PN~1-7Og}8|kJKt3how zahv5H>0gsVIvKpeCR|7$C-Fk)~7v%OMjEY}L6@ z7uX`70@J!_jXg^S+cOmDS!1H|8u*>) zG7VQX1~Urt>TQCncyD__n76-+sr+{sRTeFzSoYcou_?@5^;OowFjb@Hiv?K@C73EO z$^@y6u#9c^=rIHR^?8>H>BBM|D&^@G3*aLUq-Rv?)IDvin1sfw59P(oLqu8OTcobR z;*146n8Yn32iP9XK{5rRBopajWg*~ds$AmYN_UIqH{gz{0!;-21HH3Yr--qaI+Ze z%DC8MRSm)sCFTUhFE;g5fMg-BBNJ75FK(jyEdOrg0gv{dm+@4`+AAJVGx`DT6k*jk zI#Y=-9lt``u0A`URk6p#WDH5mvS^y>h+Ulwaen{DL!#5?GxvBe5xV=@zcCwc93oj*FMFB?0wHuN(O2-2SmoRygvuit*l z2=|4Pg`!?HCX1^tk9_)$T156eVFvWK&i?y~FbJJ(2-4mm*Z4nh2Mw8hqiAe*Jp{}F&F<0s+Z;ZREg zz1#TP7|DQQ*)zF@!Gc-TkP;6eOoSD5*5b?RxHgc9U6O^DW5wC4Z>2;ONTZJ<6EDDa zF!Y8_taapBk}Tv()*tmIIFQX=ybq@|t`?Goa4X&p0|&9Xwnk;&8iKdi96^=j9hn!Y z*1{oOg96K6q}4aGKNReiXInAu*=CI{LDfc<#3ndtiM$0)pf4NKHT zw(ISMzqgF&)Bm(B@r=WRT_F>Bja2l|{K)O62I*b?f92 zNk_yM$|xs1e5wd91#o+%*Jb&Q8n-7QzZ-}O37)0a^T%>TWneBXG+9|{v{Wr_&uHl` zON6oCAh`Ylgey;hH~cms-we0G(S6uIXmsl*>+~s9F~-F%a~wx9v)Wo{p4^_>vqh`D z`3lI!uVUX^4n9Z6;zXQ8hbQ*G}9zHCsODxi1* znSjf{ugbW>DIrj<+cSC1rp&$iLs>W!Sskf%@%o@xYY;02oS4458P)#WUo!GwsBPO3#46`Bj47D)0cn8pTv} zIe_Q?=9l6MgSPY%v2vnzKH{h<5j?4waD?s63WmC-mZjtMi_E|ODJD1~)sKp6qRsdC zqgb^AQd^x4hwqZ!Va@s_lK&u^&MB*J!aJ2CveO0km}@Fu4?gHfXqLwxDhn{?s0>o!&dfEf zd}6hFmVe=keq&1pd5TH)*b(c;b1TDZ)BAzE14ga}7oURLrvi}D_WzDdZri631s?t_}>?u619NL1?J;o!YNJN;OV(*drbbV(PkY6UW zTKBk;=}j#|+`p|?WJpV9*E&W^%nK+f zWAS?{4us5I=g322rO&`mO{QPkY@}qASRbOfB&>W6QTng1g+#){g9k~J6R!eVSId*T z%!Q6M25*3~yyj(X%mvr9xtzwv-tu@G8V>_-~WyOI<{@w6WhkbzWJTIZ`G-DPwm?E)?4*-cUAuZ&sS@GRw`d8_)$dZI5WGY zWCXl{r-{Y$w~k6L-2G2qWwNywwZ13plMnL2ZKH|a?hW#OYeFSZgK-0Tv9$f^Hv!h^12$ZTWK#3EX3;jq~_NhP(;U zlLYZpp`O)=QF3J|20ZgHCIz7`^Iv)TaOOeX;!{)+W$7H8|kabsV zy@JHJWU4E~;yMG~>jP7@%soM5*m&A`6oNaHnq3Lw9todE*_}YQnzwvKxcqBf3_w0Mld}+Drf$VD!x#&%Fl)zhr%^=~ z9O*(`iQQyPTG)$y5|h$_)w2kB^q_#6bF|j2>Ur99qe5|QBdt*bonUR)OWUA}Ob4Rd? z(9C;kvJz)=lE;EZHwe{=wU**%J3z;p^FNxB;&;&sCIb0gxOq}#=YIEls*Rm4y+jr4 z$g}DBFt759d5R{F8DMtKa3d{+)Fo$gB>H+p8_e-HZ8|&A*meG7F`B{nVo=NzZqGo5 ze1|g(9g#Rw;Axzd%($!O<6%zJa{n=pvcO7Vj+u0}Wpy!E zm!$Ny5o_GnU90KuEMlP9*gghWFl9I9SfK@=-{UsOO$G7oOyeU z#MZD3RnT56tzO4Ug9UV}mL+ii@mX(A{fiqwbeaud|JN+P_MjrXVhwryn7Qk9k>z0;=uQdRGg zyQ}s(QDqO8pqzuF>MRSUtb^E_t)8q)P*w-Ll?Hk$2zD0ink|>^nsB^n!xh&k^;)2s z)rbsIyQ>UZxhI9)-TXbyHi=);Ky3@;D>j7Lqng@t0Y|2y)lUg$+rKVC$&;gM{!pzj z<=`nb#C7Jd&>K2AaM+!&q@8g;CMbA7m4+?#UlYJs~I zt)N05uj%8lO=5d6IbAB#lFxx0tLVz*ax>W~slp8rl~U z;MVe+&)$NxM_f+eyx{nzMyN#IJXMFt3;p-F>H&?d_deHSwEY^uSMd!By#{WZ-7i)K z?jxF3?CbCQG2UR12FE|cbUB5o$XEf8GClP!FyLl8uqwT7Xp-WYgON*Tm zGzSS@uuGFAq?cruWtcbvGgDVlj^b6gnNn5o3FT&3RX^?eT$J#ZFj|}1wXGQ0HL4sJ zCDN8ZS77l8g7z1sJ;QPX{b7&fov9$SkHb4A!P_E;MwdQS2*5Y0dJif>>Orhslk}C> zg*gb@Jylyt+(_Ho^!t1FQdz!#E~?QpvBNd`@m*nr(*;wANl=UsI>@9Wsewc+2su}0 zk*ny)mbGOnyJ(aKo<|B3m`x)mR;Kq21dxVA=TfMr@92H;CFn53(o(t^67^uRghaGz z_O}h5uw)$+FmG=D8le2}cGN&sU{{R+k}0Cd4>6q4ACB5>)0={aue+4KIaa!h?Eus{ z>hqxMp=v5T50y&bDE#v0^oh(74dn7|P~4RBnkH2^-LD}p9~Tja9Kr^k-PTZvJ~OXrGvjBFe*%gZi4{s<@T`dv+k7`s?jE{Hq3>qV55 z$6x3b5*Y!Kq$~)fEV+0!BkH$nWy=*!Fbs_RG;&^oqUm8$4^2>yJWB1Jo|gblETCi3 z(#;mq5eLmL52q~r;w|{v32j|&C(CK?Oer9(1>D^}i)#?axd**+J*c>8#gTvo> z>m7qLtsEBM$0`pl>4kJY_5gKMuOS>2OE-wiz_QQ%zf4 z6BL$`m>@Sfs>)VCd~M@QQ3DPwV;vr1v5kKYaC#5H)*bBEWijEihCe^im_f6KeRH)} z6^`Q77qzOONuiJYHDD1DQ}Yv)8!%NULn+34S0{l~bZ?CDDp)O$mKm3F3mr~Joy_ka zi@7TsPI8+cKfrXDCFb*;{dS5gB$z2-?nF;I%ohlPf2a~Mrp>9+XJ1|tTir|ZRAwzg z10`{H3klU`yhDO`5@tn|yf3^S#iNl3y0AEYwYzFmlG;O*{Clv`_5skU?j>MBr_R>= zKr)6lY2qB*j!%sMRO3~5<{aLa#ljE_QbU58|zPvd$d^}ug>ARW%|^4ru(NW8z30pBKhjdaFPCdSN1Eh( zA=}L2qQ|(;)#mGl%jWdv+l|~em~F1_1NNJ4_7@L}-L}t@BAaQ@72i5)Je1({A<$5{ zcZZQ^!LBJb(SPG#JmeG8O+ zNxjmmR+GSg#En*S^?q>wCbuo2`kv@ttZ_yTvK%SL7+w5yuGH0E!sxsDxO}E^INh*Y z|AaHoSH1lcIva5rMGgluO+t1$N^XLzXfCWZZuZXD(KH>+$cRaa*r*s>SX+NGRiVMU z(R{k>xsGr*ZRQs_zAzLU+qYb;&(`1qP;umJ)xaP8cRBP(~`$ z1sbO>A_2yLwTY<|8%7FIeKMH(+`~PV1p~n?{FwT`{DuioR>{}k%h;Ax1s2|c;|7@& zO8L`sc5Kx+zL;;y%upiN!U6&wbRP-Ye7#d30|KnA(J?Pm?czK?n=#76g*PK*c=G2< z{+@I^a_AYU(vq^49>Q@J75as>K+dG5M)=T>D#X)X)y z{0yLIYl}UyN0GAQD0bZYEFe$3XsUI>`&i( zzVuht2W(DsW#NukgZIoTb!=@VP5?*PKLiLe+bor;m z<3&paDTDr;*<$JZEhtfdLr}Gqv|xLMfOe^FFZttLGFOPc_UD%t-YVaGEO>Qtt%~v~!gmbLD#RdZs6(%KclmRyTGzISjk!-kK zEt*I0_3G_G0^L4ggsmY7zn#y#G)SBd9@{bX48}j%b7$b^ZMTd^SX*A$RfMq5spr5I zvHKw6$jzpfG<<9cQm}{0swW#``C8Wnlv;)44GoR`>9Ku{Q;Y@8_@W_MhTlpQJ+#_Ag3H&iW>tqgaf~W2-Vh0 z6fb1IP zpLbS}f!x&QI-=L24WC$x!a~_r<`Imwoj-APjtfL&+k>mjN8DgHR1z}^2hc}`QhIz` zKy`~2UTFKC@C;fd-E`xQ-9{m!+m6L_?tru}3J^Ti%XVEE=j?t^v81S4snL{bll(G_+EYg&GAPqDR z6MG^f&X6Q-=eY?SD0Pk#Mo3Cn(g^KFv;>OjIZ4I%R^3Dzq)}CKqzAWVpS&bH`4rPX zq0Vm16yH+PzrnT4{J=54NCc@zTJ?;NOP*mhtOP5ad8S0)uZI-Jy!kPu)f-IPksxqL zt0Ul5aPikkepNTH_`PhRJ6e1&#qA&x)q29>zU5PNZ)-H`lR&LgAoL^b!o9wTa6o6> zVW}`c`FCUnLpIqk(-0Wp-Iy(E^czCP>0hBID`BcCaglVL6Ww{X`_xHxV!MvDxa-^r za?f3M)Mu^yra5l(=-8FBY9ppUyBqr{s(;1H%`hL=3Cwi-`1)w~KAI!lbbQ89g>;t! z2zo^c2$d^d0wy8mgj*AZ`XJzGK4vib;l{v2ple&k#GN7EaG^?Oly6MbrhN z;MXvMmu0XXdgvY&3kH6ujeCkk;GgAkX}B)_X`Z|hQt|;sGGdW6cg%`);ArN`ylV_y zye+bH=b^pgFxIKeCtA97#66N0s)XMfThX5OC?YhwWOY7;<+!aXB+s&cRD@}I4~<7* zJjBVfuTmIsf(-SR8S%o+`);WKjv0xDvSB76z4?7{)NbwJ3YgLdKzHk;ic{w64e2qV z(-#ja^!+b<(a2oVS-_WwO7GuxJpZ|rTgBGG^sD3f-`7xus#{-pIFt|D418u8t&+k( z**~se@joPKL~nZ%62s&=gy@ZeN(MOv!YlSj-=6Da;Uw-7H*RRiJhS%qtCj>uyIN|v~8o`iINv{Tj z2S=c4fj_%i2vmVk>Hsw%SZpbsN63Bp1{{nsWzOz+VqSeWXZn; zVL&8!YX5jyo|PpFJ0}%$Qab7|IJkJO^qd)rn0RGkW`qV*ijg@I!*fN^+3L$s#!cU{ zr~i)sdg(icAo7N(u4$<~6D7ns!eOoTt@(yvGprH!enl#+x>s-S!)XgFD% zW8jsRk*=7zW12=&zZW<(^#ZQ5s5L*iO^0P?pCIbxp%Ll#U1q65Ab3@M2`0d9V8ki7 zD6!}ks-1ay(juq^GhHcI(f}1&)=BK79*u>_iP0oAD6p=gB!W8+s}M;+IuXUHmMv~+ zEV*=Y&EJ)%-0Ekr#+ZF!>fLczBVV#K^wZ2SY7!ln7fh_8Wd@5+&_lo2`CM$-YEgdI zs6BHNM_K8y2QYDDWQTdFwNyQLk#i7xpZiKVr# zMyXNCHIAySk6gw`H*G0=uE58p{ZH}=qe^QJfC@e-J=`&xx~&3#(B_7A#PWm+wQPu1 zb+M@AJlLX87#Rk;Dce^#3zcW5WUcY4ZURwI)XV<9-(B@uvw(up^ui=!XPSNiS9qjq_IX~|0&74LPRSj}743}bmA zh0nTOxbS3nd_Fi%aRS5*n=w=yBPAD%0Y5mrBXqRi{d*k!1A*XVZP2mBnk1ck1UHhK zzyNiqdxU{GJIcTTeKP;M>#lDWb#QOxGyLSdutH_jcQ`(u{s>pTrXXbmK?XuP)C)j1 zKJiDmNJtk`5-(r+C~R>(^60v-Cnp=XWV*Ji^+*zAb;ngbRzZNw#e zPrqoAtf>W0P{+2XRBq)E6m;Wma^=G6GV?>>KG%xUVV4N>fys3&>_qZl_RwZNzoYzIX&u5O5XD!T48x9;$s6Fp>}Vq9MmfkjBH>n>@+Z7 zKU{=7eK3u%RRaebt9c#^SNTQM;sNQ6 zq>mbD$*iAxVxQq~5>K2G1)`Gvp>mS`Bc|7#vSnMuHou21pFUJP2Z+1Mmk?T`dd_1Y zhinbB2E=k!RTeg)hHZ&ZzUGtsUr~k`&c8B3JB9AOQ_}Z*ECb<7;_*Eh7cUeqT`Aq# z6WejeHnDJvSj!sb!P6r;T!r`ei0@Wd0)ymz@2Q`#?UGE5?r!Z|LM>zHI26CtVNU z#B{bxetJj#re>kw=;4_aUDeZR2xDzNW9_R~hX8A$Uod=$*<5Tk0alQCI>Rb*muaD~t9VY0Kdrwy zZ{N$Nis|>+@nfY&h9BQKr?+^rS*nh%(YW!I?{QZAk8)Ia5-wGlWT_ixRdb%f0WfC9 z^E50XB4@$L3->Nh5kuWPF6K^WHMl@o+@XT$lm9oolhBt*ZU_9^w+PsOH$zMO$1}8) zowbdfnVqAZtCEd{qph9m|6egvsb=N;g~t1kJ)Bxk8~sBV+Y5uhkAe)sh(Hhz7TZH& zN`Npy03Et-ddS&o%$Oic_TBrB7>bpT@){L|CKz<(*F_zfK%`-@d0ADfGN#J4QgiLY zJf+F1Rr{js!tIh95<1l)BWdL^(`Rba?8@${{;{*#+jZaK8`BLo+hM-ipeQ=4K|S`; zwk8|2eb!I(9Z$AV*yspfh_mTh`u9L=y}>BQ3o;4Y*vl9r7qg{O29 zH}StNY?lK%ju*D5k1ad>Y$O?(UJf}VTZ#KxR9zQC@9sTOP|K$!J`S(IRiB8d1g_>% z_Zf!I&a+>yQ)^-nxIcNH?n>8uw?1maTOuOhCF*o+z0~8y_V2hH8-(J;NLMIFX;IrZ zo@gIh7_hxmyyXTTRk+FM^Vh`FJ*|`C&RLOf#{Iv4uNB^|7z}fFlZ+`=J*ma(|7GoI zy?C6=#@UK-L`SimYBn^v0P?+%o81HzKLQz1sAt}IDC&SG%SP0(a1)K#%vgy?`khm5 zhr3@{@xrv3-$#iE^Zrc7vt{Et1UV~g zzBnzC+!Itt)e3z5KBG@GB~!i>fYYj(j+#p36LyU*e*^lR{P{lP&R()d7f;=&GJQRp znSzAEkZrEq5O#3Sv?GP_?`+j@%V~{jieqa)x2WGwIXmx2f@2Ba0E+>lac9l8Fi}pd zb|ma5lIasm@l%8EpC_o=ld#E05fkP@rqZZDxgkdJmrD4MyCgD~aL^uE&NL)0)^ zCX)xOR{D~sykMW@>fPVLy~nxvSq13iDJ;4Ii9 ziLrj%7;O%Be4DXHk+Wha8)b4=9h76{4#}}}$D@Os_+Z>Wi32!)8u~@MJxeX48Q(+3&phgZO!z!D`jkIjsW3)+G4kX- zwX|(5;d< zX%#6hL^KN9@w%77R;}Hg&w-+isjbre>)B)+?N4)sovk{4nO0MNDX;LYtglwLFh{k` zEEJ0WO(J3vkH|%mPg|OgCG)GpJi4pAwS-4kh$Mwo$g$*+c_rA9|9n{;3iI&>B@|t) z@q9g&tvstXsdXxYU#SNQ>k8exk5lj+O}FSyBv$E*J5_6%Su(^liS6j0;YeBH?0Eky zp4!9}RG|LBSJt}>rJL}C?z|_VB@^&Fv9;@1*CYZ|WGzgsd=gcGzNwH6YZl)yIz^=V zJ0;NXS%QY=F3OEoe{TQMdh-YAqQF^Hh2hhC>WAymZ%27v0@SCFfJX_L4Ngw`Ii5*Y z)#`Jz95bbYj<*P?2azc(ix?m`f_S%8RjHjtQTych8Mx+j>|!yD>_@M&>tjP<{9=1v zf?1Vag_Wg#bCGpQHnS?3arC|w7^ulSu{T%cgw%|r(jll3euM5z|3Fh2w_FYlz`5cC z#*Ku+GO!3N`zdzYEc3J5qE67b;Sy14&UFl6Vf& zw%T=L6BzMxmHWZW0c}94;I_khYD*L-((=8W-4VvGfxnB(H2)6MLzY(yAUw_q*X#5M za`Gn>Yp_`S&;SKBcj&S{g$nTle@Gl#4?*k?dm`1J@}ir&XB^!|{6WV>c)KW|9BB#u z6Ap3sDBebl6NxD6PoTu22i;6{$`kGfBabI)5_>ebd)A6m=0mrM!OVzpYJZGxm>(5j z;(0CoMs07Cy2TQhZ6f{2a%VzxWW`aZbmXiX;&S&^CY@jCRylp4Ijtk4U@@6bR0UKf zRCCQiO6sRDh^mF}YhJZ_T!o-78Zt=Gcfa6b7*;*F<2*300~$1oGi zN%+=j)q58{9XHgP$X?FN5^?K}U6v)8w00&N;0>3s*h!l8%xJff_#W$#A>{gP<&uNLJERp}bhbjL_FvwQY2=HyoFP5B8-!aF?U8h$;R<)YFx^;r(Xrs~`7H)+ z+B_pCmP-NY*U@4qFo$JfEOnVS4~4FqotK&HVa}CQu`tnglpgr!0jd4SFJv2cAn*_A zgHY=6&NS<9r@ux9CQM1u7YMWaOCK&jjHo9AQfvhqTZ?Af{@zK?x9sY=ax#$BSf1w zWwJOpu_Bp)*Yc(`o+@tamv(CMv(RN~kn&MgL!m|C`moNtP$o4>uC*({5{iYwz^Z;J z$DtB@-&PFf7+j)>>uTM!WRB$#tZ8ZX32EL!h5Y5Rsg_D!bF66N<$!k`^vMZv%M2~G zrD@yGJwSO!P?}hwnh_Yfu^?&&un?Qv%FA>-s0)?hEk zqQpysRetx}Frr8#Vg>aZVuM_Yq}Z&C|k3Wjm10JLzdT4CnU zLc;)cfTCeki$VpeTPXD)Ypv}0-mS#nX!{FH#3tIwJ(_xjv!$syFUm1}$9-dtYy%w< zHe1r9rQyNpv75ArJE->t(Op_e>)1kFYvVGhFu~bT#q3u5UH6ARhs3YnmGdBEu?njq zggl?)?Xs+=^$-lH97&Sod}N2!zv&3pdpZrdv!}h_G?fWAsO2uC&u2}dlubk*?-2i- znPmF?Tq~fzeM9}XY&ib^xJ6bnFgCU}`65T#I)7Q|4Q!pha*O_zQIx1-|8->={-hpP z6NJoBB77A8MPu zGUJ!KAX5UR?2m-_WM&!8dD&t*4@rckHEkL7xq$`=M4nJA~86Q{AqXi`NUm ztdGY^^|I$G`Qk3d6FxRx>Vo> zKrhJi!}flCtn@L+lU0T3A!W-J=`?NVIBnIaJn-d>slDMPdR~y{eX5x6bDuaxKIdo5 zWAqn>`n0qxqjT*-Ns#AxI^XUY{w2_JS8s!L@8QZqxeLkhJQMM>0BQF@BYYrd(>QNdq>oeyP{wQZI;KHBrXfqZ!AI0+zvmiv zEo8#U-7x3Hf-Vkrt5v_^_?q3m*AJb9#>>*HgavDL15F42!ZL+`MXJPhrP;?!uA#k{ z2gmZtI-)7CzrBA0$y&}yp7~UxvqnZxW4pE!>6|O7D==^@He1FS&crZGI|fZ^zMk87 zpz%%@P@M4|Kd*~1bBlx}Bub09@T2jGp9q7E5tBFr-n5~wCs;oxn{NMZSzdsxuGhA* znl9^@@yqt2HY`Pil&^6++0mI3d7b{8KLW+hjLvQKL0u3zsWBB00wA(V-78Czv)Rz z<0r%j;>Tuopel@=E^LJFGwHDnv~5uryvvBa-vE!^2+lYKoHC+?V7}X_xu?G{o641z zsroPFSe8*=aRLpy8NN2gn{suE38RJmYULgj)~2JS0*j zib>2eRVB=`$CCWGpI;rccgu^`FHKfY@_q}Hy|tc5p}Ekn4hK%ZfR1u-QwZHa>{2e` z6#@k){B?l6rR=D2miD99tStbFaHc=<0(65GTl)&y;jd#X+!ZZY>ym?S1W}f9&%fXK zXG7UqWIYPf+VLIMc>}1r`SepqKpcGM2E1Z~${W)otm*QCkJ^%lUlj0;IkkI5wFgzT zjouR?y)bc8`|vvYm~Lbi87D8^SgE~Hjh?CoOLMgJ0`T_L8}*A2{x)PzED4rjiJj3j zVKw^@v&Pi~L!0`7gfM`>-%j2#Q}RX-qlwI8HBv+aqB$+_0XOT@*%1m$oeAp51hVm^<~ ze3CuU57o1SKKGO{8#fKdoQu3gYzrglsAQQEh;|QuY#DWD4_cngs9OSU}g`2>>ks8%`~wcATrfRiUkrwrK8fUJYeXVrTkS} zJaC5rZAC1$vsv4mhewA=a%vXwX zVWt;Mz>gx9Mpg%M`9#UL5j!M!n(t;V|PN0xr|F)xnn zUQr9yBqO}+q@w6KnrwN^@_VE)&GYXO2l0nFp(#s|XB?86BlAnQ)(mn*cZ*BTPRk8fYp=NRbQK6+D`G(wQoo3aqsUJ8g8^rkCxW zYQM?3*Yw9^EguZu&e04*^Q9N8MDfBuJk_GpJsIRq$NaL8#>Bhs@5_aN5`6s}V2Y4j zM3KT?5w0lr%`y4AM%QNNC>tN$i1{o?4zDquW}MtEuVrm!F@#}M^_TbyJE~f4SPM}Q z%$3?W1YP-1g2d}f!|1SjsODO0gK-$gGSqa~ZM7a>KVh7`m8xPM6^V7yp>#yMc-wyu zckdlNp@#2*DM=DWK(nt9$y4k0N9TvnXfD{FzmTy4WkWO&(zX`%UXaUs*9Xoj`)ZBxKj?$2N{Z8G%z zu%4`KEh#89Nq3|N64PT{07XYr>Fa5iUrKHWt{!0r5qFp)A}>9Z9#Ns1WxgZQMyXUANgU1}s*Cm>RIrE#SL~I?K-XARUJR z75lcqtqDHrgC!s~$32#!NpGWPZ{=dBjM}|Qk@@UX=CHun^9N=lwwgtQ^Wfc5cQd^C+}#NNN)^&v@=ZbnIJVpGZbUm3|l6xx@ho`3B{HX8n%(ePJv03 zs=!O+E=W@`f>dLsLMS?9W^#iwKS;c&ZHA^kvy8uacyH)O1`<}J?UJLmsYfxs-w2nK z3xty>sgQ|!P^!{XUv!ln+~0&I+SMo&WQ3FC1(A=DRESF0b37kEZZFLV3mORWixiXQ zWE2=ObHxI2ECP!P5f!bzzS^{~0={Bh$LDHxiVcL#!6GO_*e}GmaP=)B^HSjQW8e&8 z;fx}qx9K|rjhs=;PE53O)vggcgXKkbh7Z)*Ve|8WiY*MRdc+Vx^`LsMNG&QdLEvuj3ClyR%kpp5w`3Cl?Q`N)WC zjWIbKlwsrMSh!ldq1yqwg~d-WO@f1B(z|Y@kD?xDNO}qD5tt4}?mn29w~m`0n2ugh z&`hsJjncZvwPmKqqjje#w~x!#@~w}flx`6EaJ$!`$H?=SvtB;!+dY9y)EfytZuVi; zqj&b-axQaJ)4_7D+3)C2_-muq6i<2jEAXgtjDGo7-Jc~6PqqF?#5xGIt5C2eL#3|< zxx2%<-odldLngJo55RDiA>TOIGwDZCKD<5?#4lT|=71TvGpVX_CwtziqbjW$^B)v~ zLKhttuQu&jDT>1gA~_~gLndjw3H^@ z{SM12hfoVG$Hqv%cOjE@8pkBalceEjlH>)}N@Mg&OQ@NZANX4ye&I9{FC+61N~C8R z+(PlZ3Wc+|vl%7~rK?89!m*Sh9n)ZOg8%Gx~B1G%_>@#5qwBgou z=0*jjWR%BUZt)_lt5*{5O@KHVNAro2aY;7)+`99Nwx=TBf%ux5J+tk8`>D7hf1;NJ zx9~9YD?)`+w>iEH_ZDUH$J2j>cF|H)HmFwi3&`V**ZVkcEJPVj<}93oiG=6P)6l$< zEL+P)T`gpIOt8RP<>%P9c>PCh6SinMfy|1%@_$X0HOO)5ii_hWoXV&ZW%Kw&#>zvI zqE!G(?Dc;n2k9>&9TZr|Bg?wpc>f9(?#5qHYiOm;x87ESud(2_ueSsVFIsOIg=9x8{n{j#$+NiZPH8w0%X&mZ!6FvbsK%^pPN0W0>_b zA&DZyAsF=&vPKdS?P@?x?>G_h((U{dmq-WZumeWJ>!W^~d`yk-&o;Ou|?0s3AP_)iQ?%&rmAuJsdI zcC0__T3I7inII1fD{0EOGau*i6vz05$%r?Al~U^g#-_C8&pmWwAG|!M zc5L(foQaFa9DSHyn>h_)PFB|V0kRWQ@iH}i+}Pml=z=wCme$y?)3ea?XzR1Lt8Fk| z=tOCP!}sB)n0Yw!h2sI1hs+5ciKWo|1PeGkhx5|;xwc9)4O>s*6H(m|*@>f1xj9Yj z{_NO2*fvWwAou~z_~i)PEM}!x2(AJzMTqkE3NJ-nyiJDtMp<0uKSV4V34>*#rJeE% zxjv1n?Q3e3VefZY_P=@Ayq81hi4f?8+ga0J5eIA9eZe*=Kxf-BSO{gg_Rqzhz2R?o z!~2=>@^pR>b(}MiVd0(n)%ZQ+IHbi~%Vn@)A>Sb;4j46fe!Ix@M2X?b;U!*2YBE&6 z(7sItKI3qTv(2D(!cNcq=-A1Nbp!1(eK$iGKw82toMzZ{yLW4SX~%iDc8OHgjdora z;1m+)O)otD62$H3S_^0l(Z0Br1I1~>1CibRf!CXptsbD{yupl@x!QzpaOn`heryC_ zT*h%|FgM#Q=7rxUnO}%ETWx#v+O&-(vDVUPu$1w$$=wbm%(jK?Fe2Wgz*6+To?*Bq z!(Xq*nVii=3Xw0@_XenOgv%J%2|&)C0D)W?L3-AN>qB@{Vo%&A$yu-o zH4R}sR_q8SqSizs3$q0^04?eUN=5fmKd5WrE@1(Ww0MWg@0QDrOks(jjl!4p{P!aL z%`+@AB5g-WON2i*gV-CwyiSvs{=Q*(Tzd*NKD6Fk^pjMR;Xlm0YLzdRa?yj76R1|I z0kMyvAas2|vv#(r?Sx1=&UU^D1gDAhs%;5>+MMgWaCln5J$kSrT5k1p={Zg1_OGn; ztms8ZARm!kX2I#L5BL~y`}Xe6P^C}@ca+n3D%M`EF+gKo!v*bfDT{51z;}t=-}{_G z^5xdMm5Ta`6TTvvUK^F&Js!Ia$;l77EI*ZM-I}b&B&^$E6BaxJhz#IU(Hvhp6lX=Zo+=ImL%;t4J9Oi z6unu}Go7?BIlfqjFXkq+R_*WyUJ3fa2U&HH7xtZVEA9mheu{nUQV2g^KmI`f@hAR2 zC7$)T%iH6Niot~N@5a3Ue2*z>U}a!tU}N#$N4@_qYklJ%<=Cgqt%{)ee5{}We+irn zR?YW_re#g>1Qd{y5E(2QBA5Ek0x8yZgL=yC2qxZ>fM`0-i4vxl-H55&=qyHO(ark} zGkl*rI(zO%)A~T>AVV|Ht5&n=D>vTD&ZEOeU;OtU+c36X#V?`{A3S$Q=)Z7!Bfmm2 z?e~!MjNjP9$2V_%1>T;3PLY{fld)9uP_wV8{PTderhmc+c{rG(j-Eun2 zrG7ZaLfbiBc(w`uY2ny))DH_4PzXs?KM(Xmq@mk|Fbk2 zOB&81RIWvnN8zHRdMR=JW!tfoiL+o%!lD(oCy!FeznU!L%qUk2pO_dIiDJ&H$cyDm z>zG?rZL4HyBr{;NN-b>BPD)}yQ;U=gGK^9)wz6UFDqEyc0xSZ;8F|T54&t>HlmKH; z(Ei>(kBnxs!lX6ySg3A97<7y|nM}s%$*l{<7o?D;I_R|p-NH0lSz0AmTJrlTwFFAz zcM;HGqb!>{9lKPDmXsq%+?WR)=5(OmB|877}Wj*_(bf70a!hNM4uUu5`FG(S@1u`zAH1(?o59A!jni}z)6eE<`bI( z7&W}oe>bI9^{t?H3*(^edtojaccRE)x;V7^oOLWsY!x`kh;gsk@~4nv+03%Knj5ws zVjbac4R*=nX=>kL-h(!A8l@WZUyw4h<>+aoPMiEq6Z9lakv5)JKFzB4h9eyGdB$Wp zjXZp>60+p3&%^x+agWrlH?@#>RbshZ&SJf%QLh|BIlZ`va4ZzuSW~i`pmlAg%9}PO zwPYZZ6UU&DhbY@%1;ET9J163OgNNH8#R&-9YdFn+ruXq$(dhO^;9DdKc^XA?5}xQZ zMjoV(V$d`>iQAsDx5lQ7*M8*&eD{e2=>!Q$ZU8`%9h&mxZ?B6J*S03Hu{~D>-6rG=2TzD9-9Ku%i?YrA#1gK z4f-2!4)$ zSJ&;u^VH?xWB0EQ@E!@8G4`vVz@NJ30~xvvI{-}3D2#zvbSN0FouSak2wiQ#xd_on z*15iBkAz)XqwMa_-%lP4(GBRxE$4$IMaI(Osc|!khDAmDW@#F8Fg|2yu>?_)=6H;E z@rB2W74dXTkB#I~Jl!A9BGq8sy0pfrY1ui4wxpU_i8b}+SeT^11D3OZyEkPG6^$@C z#MENFd6qMOFgNzJ& zSt)tZ)25^c87JI>TIUy>kYu~+ngbVc>WA14CNZPs4>`?E^KJi{XU{DuCuod`vX4g1 zA)UmsIU+YY$tGwZtuFlIIHI{gTccl7G~m}%iXKkQPcUyJi*wa6LA_OORcDr_Hd!}4 z%vD&d$DUvs%(sF23KmF$7Bwpytn+_Sf!d@5T9;W1?{QvM6;Iq`i~&Rh@4AsZgAQ)V zUtik1RPY}Rli3V5wc}>m3+c2JH55<=TMT3{NTZI7pMn&IxOgXa$|Bu-+~Jql*Imk@ zYCP^aEf;LBDsIu{~y}UF}m_-%l1{VZB}gC72CG$ zoR}3mso1t{+qTV$PExU6Zg;=&y6@}P<9>M`&KUo3zVEfyTzk#m1PvXmI2|z*N)fq+ z+T#K9Y>ns^I<!{0)9F2E`#_`w!FlDcD?FR72{p$K>n+KTWCF&~S)Nx$qYd z1%*#;oyaq@F`-i2u~Ld#Ouu^^|NZ;a&blFAzq{_wS8CYuS(J8%O;^{|>F$w?On^(4 zF{h$SHpy@%K%Dh2$=leC9N5)%=!JfslBVzXR%(LAd2}ts zqeT2;da~c4;dk)c;y+Zv_wpQKg%M}b_8;tbiyWQ6FO5c9Py6gl41J+3oRO5Y2uB+oO>Lh*j$kxz3!yp8JoTTo&LZB2) z(hksckSca?rYS46B#+Ehu~7TQ)ba9^h!f8A{A6hYsEwWy-(qF0#o_ztGYr&|cIR*c zN^FbdQQ0x;!&x+roiRB6yqiXE%QkPD+k_S7ert5PmIgT)HQJT1b8MK`N8Jzysnm_q zt}w6zIRT%9ZC;_@{h)5hMY`M;9+fN4^;~+>h40Iiy|M8j6~I?w5ZCmdXv01$X_xSE z2B`dwQAJD|Xj;2#!I2NW#KtW6@cTDJiD0{Uw9i+mAN?=M*8hws5&xG5c>fzwB5CJr zYHsTEe>eG6Uz}ak73_~?ElCa9=I^jFHjda!g#D5)oO#%BD9TZwD0zzC$ra>Vc6(v{vDcbfvcZyrE=LGJS*CPKCSj)0f+-G_F}ox6Q_hHi#D;tI|7 zbe!4BN;{nQxLPpF$RH2f;G>)(eW?8TZwm{0n9Mn zte|-T+;D`WF%|`MX);nPl;Z33hN8<~pujjUn7@mm;cNauLOTdi@+uAZ(n)!p{iq6R7riwFNxG>G4|HR# zIPmet#T`jE%+nRm^U!s#hY-=;kc{=d0>wZmz%!L$v>0jg95JGdxp{l#mgR_k4?j+=7$r|b>w4(7<|0kBx8t^6vr_&lk04F;=YZ8zDbrDd)Y%yi&{ zhEa2Ts^LZh9ZjutSbmkeCqgTc?&3ldpE}5-tWz-~QRX!GLG9S*F6C{$jQX|9GeVY5 z62X~PBQ}!GsTdrLKI&q|8|z*n>mB`DbrR}33ewg#xjtWOJzneiLE_hX10R84YQ4|O zW^|NfeLU1x8LRZme&oh~WAJ$&{_??`ObP`vvCAAJ&BS4=HAmhuPi+{ooUG2x5!_>EyL}CoN7c1%Vb0a*TRbx=M-}fYRk$8HgIRwp2$@H-6bc!FM zdxtIEVq*>lI_!O~9LBjZ+D)heBT|Won3)@xCb>fPB~a?=?^eU~s;uscv-c*rro1rp6R|2vLw2 zi9O-B1_mJLF2*H{6pX&BE`dD99OH)$Cz2r8c)}Z4`R~;i~!i&M49q zozvcNr(6sbx5?32zts5=*OoNS8TkCGj$FpLmGK@_+bXH9+`cxou~ST?_O95?%3*%U_E^_PoR23 zISz}!NoC5TZZnbE;6CqcU~>|Q=xXO_)t@jYS>hP$)4~>=M9*}kfxoNlx8ZT;#fJl@ z$6-B=j6Zq#4!svD0Bg6=ieX#&0Cw>p)1TXCDKmL#5UXc$Z0+w?z1la=TfWb>lLtmW z_T(;YoFU)s+Uv)ZkC3lOyW)Irp0=h=?7gMbF)lF*A#&LP4jAa(px{r-Wdj{DhmWb% z*UCALAjIjyRALdi zbZ~k>UTYK@`yk@C^%L#})VOzLj&Y0(Oe_rY6NAB`{;*7^i$5fJlVK)TFwdnl6&yan zmQWB^WT>tjOLOFCh)uzL116Ng>BXTnRRYxWAR-jPwd}(?n6b1q|Y>WS?ZtY1V0cWfm|!TGo??NbI;=9?!OnwR4&f~ik8uq zv;u2*uzONr5Si4Zo@OAe@)j>h?7vs#q0kV^35GAS0ObtE&?`x&8OC~qE_0=GFSB~f zt?!kO%#d{p-~SqM z1^F{#K@3>*D`1s4umov0VGT=Q6=1=V`~qreWgrchI6NVa=IlyrG6i{+BeXb*!;K+b zg*e3K)lJgr($P9qRAz{gbM^IJF)zkuh^?u?dnwYXxc~fC%fDk9^0V*lw{|0yq-&81 zimQVJhx022*Z!EvBXOYL=A>hYg%rn=Oi}95azHxW?-D9gE0JOpvMJq?9lezaIAf}X zahfmC#&TPJ+7L07LPUAjcFE!2dfT(L2w9Y*sJxmqH73hd-kGZK@*=^Io5SK^X(OSq zm3?txt@1dQ$nng#&0~lbm5oLS{CBqGIP+6JS5{%&G3EvY(-+XI!T5Oz4GclwhSI*#L^(sCJmG!1C^Qde5r_mJF}trr$qWq^VsQ^B*aDd zBqCtB2^~-WeDtHSEQ=jh;G;r@5*%6_NxL!=qdxcb}#If$cF zXo`D?9W+trD`%9fzvdFUjW2oVVdW%yHPuoDRF(E#mKCnwYdd5tiaGW z_;5^viH@755m&{#f+#*3w^s|ipL`IGF_nO6yL}!8eIP{mbRpS|k9&fRfCotYNx;M% zbig5aJ1Sqt%?Nk%+zW{RQ3=$ruUKiI?|TO)P@DJxt|>gm9O_!yqCjDn;JaKxCU!su zNxa8k-48M{JOg|AE28JY>gk6;`O-WGS8c+4y1X1#-Qx=}T4OuV8|0 zI`O}d%`0F>9o7ORJNOo~vNCvdbz}3N%@)$DsNc$&iFeCZy_gDEAh`EOo&a;7Y{!8p2i%s%z`_h5#0wG^{ zzQ3T7n|Un!_jX3OO}%U_L!r8c$lUWTEq^&kjXnkbQ3&6S?Aw#TzI|)@FMA#TEDN>% z0tJswIJy~{!lWtGBtMoT4R^Ab2WAP$3FXiS@dgC)3(P|Mfw=ltT7(pj0Px5 zL49B6ekfj)#R0JuiYJ$gSlAqmZVc*QUt5j2)V01$yn%fQcv)4WJ_i+|mXJUXp!^d2pcZ6sU8_v6R+RWe7q ziUHJX-S?xzSMxzFMR8v(SN`+SF37k$_kmDYejU<9+zqk`)=3zDlpx__H73(l04^$c z!RR(~M?z4D&3q*mwl+iM0}8@Q<(i+^ol>ZiSv9lFjaWkXDvTg@%QC#sf%7zLxq#-p zGWbJKNmZks#@uD*YPE8i2_UoR&ZxSv&cFueOlq1r;n;M5zM;MpQyP4L94w*Oa`gbb zONX7)+jPC2#j&ffq(O|=7CkaqGY0cs>OsYuPrZ7zZ87;UTzYx%`^cPMFt!Q1sW{nR zaY97HKgaE=Q4E|LT!F9)G|7Be2itQPHMV*l)2h)VfB7A$1A3NSuM}C44;-n$X&T1M z8hG2*7pNiWQ{79uD-|iRUF~K6kbq%S(ec>I90#fXDS+pyE7M;NJnhR6#2c#nL41l} zgd{8|G87e#_4V)&6k^O@2@b@df4*@=x()-#1kvwTh9!nIhPl8!_m)b3j?}h7D|vP1 zW~4poNaaJhD02A&DQq}6##ozapsgpk;xmIf@I7o$=&O-(7AKOh*|{=D`r~Ubr1^$Q z7ACUwnmaFOZW$pyaQ!k5wS9xGYcUP65v&cRl7`*>0WE zW?cofoFNISj3HgpmqAQ1t&Ghe`DOpK&Ii1(Zty_eBtUq)p=IP>=QA}#3gfN*#iqF3 z1)DGj4=K)_^?0(xAxam7oFWzjNX+u?F47&V z-F7~};LgX{pyyExp1#l6EtR+bbg2@PIA|d~1zER%&vJ%FmfGViniGeBumm+P3xd-f zAm4Hry}uJ#uMPShDnVg(!)y(sEVGMVTn3Ybb5AUH0Ec=%+T;Yy0BB5kJig*%m1lG6 z%9i<(zsVXOa#fYToWuD;Quw)M7ml^|%^;Iwv4z}|nz&;Ks|BN&f(AoLpF08up0ytv zDwyG4Hpe!PCrMN$@SIq@4wpNgo!(%n+A2D8glo9rknn2h zWp%dSVn1IMgn|Y8{`_*&AN(x{#B)Y480-Trh+0xu) z#6B|@d%64;e@yJbcr^<4l39nc^GEe#VfKULA9WA#wF~F)RrdtGn!x|}PP56sT=&c@ zot-W1%o$`|Y@97!4V^5%(jfjF7AI@z?(E`Z`eo($s)2_8sDiSF?v}Qep8xj!?+@Z# z8t~pas!5+a9BG|n6B8!IV-u5wXT%DmgtNaTLdoBA^A>(u@wcZbL02WFjFF_dGACrE z6;fSQSBn@fsjdxyCo%;7q9jIJF9buWBvw!~aeJN>ojqEJ6%{nq)iL>eoFxlp`E2o2I!SZkXM78F(!* zS@HJ-RBw8q9ktrGvZtwuMh~M+ucRJQb{+B~@7x584lu(MEE;w4iMcMt>;4m7w!AO{wweV54DSL$oR21P!o^*pc9P7yI$@xBaiU3 zBZ#C&jvmurxju%wHgA#MZ(qFYox)^!sfFx$U}KCq*x#_MrVix|@X2PAdC3~d)wHMt zw}U&GN8@!*&m5}E@=Ol2bK1oZGw7ZP&pr3HcpAU`#@LM zUC?_UpbR_yHU9Ll^4LqvlZ7kir868wJrJ1(zokLWoSM&qg7~gAS-D1}yoaxQN^%fV zsf^#hA024I+Yu3Hm95thH(t3n22ykhEL`B?UHwzYvDyW#gwa@H0(cQV6#mEp6FKeJ@aFewX=}o~V zuo0Mjhj>IRikD-S4)ng%zC`ZGjvzhXC`;Vz+zNk092J!v7VFy$Ykb?39kIIW2oCJn zA;2>^MK5!6cK<#9Zbe(*>%+a2Qh+UK{u*kg3Urv?TOH%gYM#@OlM{&03cZs#+dNKo zUf&jk2G3A|aW|D2KH2wIUqh(__;m?SBT=ACowNOw%5m22Btp9Zg(Pc zESFqm;wZp`Udz2$^YNm#_rZCj79aExy_&{nC;z`OT z!!;2*Q&qJe8$$?PDbStA0J?KvQtv30JEaH>Wy>~#?WaS+-cbI-S1xnq7(0q$Bi?7a z6z?_!ARO2-WGX~oBXu23K>~vxX?)Io=dX^X>@Vyu1MRd993MCDloPBqMJpUAp^EGUptHD5jCv9A;Oo%pPwT@quHYS!6ko0q;C&L{> zAdWeQWiI$0geF$djFg|!F>8H@MJEz|QZg|<8&kuPHlhqgQ{ZT+6%>*rz`+l+|7vps@nK)cK&_0UfH};8&{4h#o80v^R&DsuT{%WXk)7 z%p2l%GS0`?AkW1?5K=moPJS<%9Tznkw|cPnZl!T6z}1yRu6;*xIMajZ&QOQc6s_x| z)v|@kTJCo**{6U-KI{P6P(K>whWF4q|=zevD8;wVdYuoc`_-*N4P}a2QR3{Hnb3NzF zW2B9=S(Y!wR6Zl|>ua_2Dz8d|20_1IXJh$E900S%s;Z;CO13)%U%2y-8*wdbkiq3e zs|ZqMWYxoWgv+|4#pd*U9p%!((jL=-pLx9}lC%6}ufQ2CbjP-$`xxmJp-6{Pwu+y7 zdhQyuq3Q?h+bqJFdY4u+Q9WH_ISE@RyDIHsrNTDD7 zozuq=ikQ*r4=w2W_i)^1a%D#Hz+$^@D3JlD%a86c90OR!+|yZV3?#dJ;SOs)ovc|O z6E4fN{0d#Lrqf{^iI?-yf8i!s3~<*%@5%`C zoZz2kW^fq!UlcB;vgvlMRRMJ+2=cj4aJjs)0GK-|OL9LKJ>3K=GU%~F?P033+s`D? zWP16OwK;T8tTKI}g4gL!tCLh+77oIeRoSR-qbV~2O3Yok{qwQ8Tw@EIV8mwR&?cxv z+n%L8j%6;pW-BBn=cMzE(_1gI>^G|t-;i<)6K~c6L2xvJU=<@|OZ!DjhlW@uhouHB zF34E(388I<^bzi8b_zf8UDBMwdd*_^4xNCO4%7WPfRI;i zB@7Vyf(UxbB>K{EuiRq1ZR_fZIVX)_K7BJ&u*JD-leWUq+4K?Iw#TTTgK_OFOzO9EIU-U zTX8AaH3eBLWcLd-63$>CD}V8J3ml%5qvvAyLl9tDWNtXzHs>atBhb}?WZ>TFz}MNS zb6S8`^*d(bP?NNvZ}z0_Sc2m=54Dd3EZ(Noeal&iO1ev{gilX?y+zY4Wu?zqSak}f zse~z;8dqpj?L(!(AvJfClg@S#8m*@;Og24V%GFTXl6sLJp?=z=d2erRGn%edDD8)l z*-Ip-P|(|dEr@tN+T_k^ATx*J>L5*-=bIe`1Vkrrx_~TA5k1=@T7f;}s)1G|9a%;)c(WfB+TrsT*tPVE^DLuQmKyTe2t6n+I6f zN+^Kh1vCa?WuwdQQS6KIQs@obX?@RLfa9%rzRAbvm0k~b*RdU^|KUKN%_?B!1?pVj}%U)u~G_4v}a$Z7{!4?;L~iEJVjP zLH-TJ6zJyCOEwiCRk@i{< zPP8HdH55gqNkr|`32^C~)UMS;7ndDlFyd>YrO@>XT4a{eP^Ym@FOOl^mg}ifEt-@Ta+G-c&`AfuVgwOTJ&!x*CRN z6&=}}oL3hDPq3iZb@wO_kDTzrkTVc%xQZt;+2bUqm0#-Z7ik^6MboJi3o+FY_1QD3 zaF6Tf10WmL4pPH->Fy~_SYsb(?7_U!?&Lcz-ik0}HO}9%u|5lvCEEjpX9@oxq^VgJ z9KpVHjCiZ;l`+*|(H!k=6sZA^$`r;()nxZBvVU{=FLli2GZwA!1V>~mNRIOO1Jb31 zU(m+A0-S>xRJi@wypZe^38D-DfxS!w8uN4QBhO!^jPym zD}RbqiezX+(;qK@@8iMUWT7FO47RNjE$=bUh0lcDw@QgPf&zdTbAdcVW}76y^QXE(1D$thpS= ziy{53nYOpf=WJ7>uHo2;J-l}BPObAWlDacu)hWnc+2>6vc}q0&@}iIW1pkMKZ3x{X zWkLA%?E&w960tV_-$g8`h@rEg(id&T*v1e5=u**^N0UVRu(F$Cr30bvfPvCeGjC7Q z`>D(Dt3C=7rPqXw*TP5%4qSPCVd~-UkB%8~@>h!}#R7ht`j>!k@^c*7u$R-%)tVKpFqFK&RIC*;p3x^g0Gu&{x^NeX7f`_h2#TECTtD~(iUsj2v{1@I(rf{45C14)~nV<%-8XFsUJ ze@oH$RyoDS@5EPBysf283_8&I?fnTE+<=oM)1zAQ{5?t4KG_-OEUDbqd48O36Eu;X zaL2DM$h`T)QD|o_qb|ngV9|BXER>dZ5@4l)R#Mo`3HiyOniH`jgd0L@^E1-l5SE0~ z&X7clF0;2Z*zV27Aj;6rC!SfMb~Z8rLQZovc!B!YC0tc>k@;$;+NFzMNl*Vux714% zMw>di`H4yc>~jYrT3&ig0`P!YHKo|Jab^R84`8cqxBmW z#%{GqTfxHC0v+NU7yQjg)hUe}hCJLi_#R4VPXt-Nn%gO@(xcAB2J5naLa2AJat`&Fe?;*gseJ$?5w z^5b}rr}?CSpT0iNTwps{RxIDzUiDy{X1A_5)a$iT`7DU}fm=Zlw@}J!)5X0iRw0QM z2-VX62KJ9b&p{d3q7C}(o5`0|3 zzEJXbSaZdt$VDdgwX2v;w}Vtycb?RGy^@Ntway-&o;f zVSDYoIpA1e;1?8mgJjS);+AUOA)xpY%-T&?_h_PbwFvQr6Hq3%^ z)$^M{m)BUgp4o1@Zs8$Qwc3H%5JMWgqOwn7qgj=JHZ>_ib*{F~DCy43u-^4t$5SHE zRcataaHP7m_);!CxE$ScW%R1HSdYbhyBedU>UMQ#FF>`?CWX4OF(k~T=x|jBAc>Ca z9^uJiw%2I7j>FENT|yIRMx;!aTAg(C42!e={w|qtyowzuqBfSi1FL?ekdEg#-j=Az z%)+8ZeSj9($fwG>mDW{e)4iX3x1b6XmEvVt{IU9xUCmu7C=lOrccloQC*oOZuO#d+ zJ2v0g9M@?ZO)Z|uRsx&o9L4DdceIWQv6aUA4!9whD)Vg zaI4}lMl8BvL-tAa!QQgL(;4Pewf~JEFOwMV2 z&AlsIny*52k;B6$HlJFK@-U~lo??nwH)+P*9}}VB4ca8Go~tbU3*z3S;xv9023VsO zI99p5UgSk_&MwPEN96`L~~z(U5>T}R~*QZ zF(}?GkVcuqdxLZIyHEG31KIpNw|ilUpW7w$SZ8BnvD~rB81aKGA?GIA@OK$L!SG)2oI6pq<33876CtEEynw-=; z+7O0whT5+K)!TGpC&3 zGG6M8lZ*~mo*Q2f)1<%~m@Gl-@!S(ctw1Ejc(w|vSJ6-jh=k0<#zrH=W}7~i5@I=( zmqWXeh2YqhhFkW>xWFsaQcOm8rArT&9_l2EF&5$oqT;4Gvp3CJ&$YEc6$5|hZ*M${ z#pXit#O zA)SSCB-9{kq{T~GyPJfMHP~VqygNuJ*G2?6S2W2}>C3!@s+xrrxhq)WLxFe1!;XTN z#1(}=XP7}fY94q{f-G#<;_(!7?8COm2wkJhJD%7z3OjB7{fbXj%~OAKH<=BZVZGb; z%du{7=f%qn(7*!8FEU)aErnfF@^&noPfC%zlL=p-p|44n5VCPCdTgN)-_;$~NC9WD zdlZcr+j4&?^avNCQ%$e{JJAe)ivP%)@)=@X{}FyZ$wAH^s|l1K>?=^D2k(Z#ZL+4- z+jeS#;-=M&YXD%hGyPOy5f1x?h-{T*AGw2ME4_M1DoPnC>dftOUq$V{Qud-boukaS z#irU#;<{f5QyS8U$a(Pnf#X{U&m0?JPhHR}J?yLv32AU!QYiztf8$+uX#ZwV7@5@&=bPF?d? zD0B*{y%tFd2^@_)WpbiLjp8&*h~hjgIB(43-(X!nlI)&wU*~q#&_DAkIm;gqpQ~4| zJB(6JBJ3XKp^qY}7TJq+;(pLLN(H^X?cWTb5lM45yZpcs$aOob+3(h;{)6`GMvg-K&$seFGjjO<} z7qNF1-9CRYbe|TuTxR`cwN;`wBY&-b(EIbctmReX6qqeNlE%f1K2b(JVWydkmXDIoT#T%~uO-z`y%yOh@}Q+8=G3@< zj-X{JudY|Yop+Y*q7=Y`6b(i}+Ugk%hFp!i=*&(l5k&<=lk^S@ks_cxgq(^LN@1&t zOF9S)NrR)o7R@p|jAE>}{DfI)a+# z7WK21G@_*Sr^MuzHH)*qL$O++5Ep7lmp)O7D4MEwxqShF=B7g{B`Q8;uL+PC)K}LO z#G5c>4zYyC0Zd*nIe8jox$`E}4e`@yC(g$$q*>Jk<@);X6RH11+&} zsy!J=NP<~8q~o}5zn~~i%cE#yJepQhyK2mvO zVVvQx-yC4bDGv9Gs*|~!dHCR^#n(pLEgP&MDB-&Qx=s@G0RKZ@r`q~TOnh%W9~Ot2 zRLzA%1x_CZ-9n>ax35TwXLem21wP|TW(_}=I4^w^sGbB>Lv5!wU8YCiS?gL87h}yW zUterCBH6DG5|3r+8RiMk&Q?^0vrwf9dG?(WttyIX#2lGvLru{5cfwi&l_&cb4;$){ zF>+iiYb;*nR3`f{ppY6V{5Oevx}Kx}U$))FAgX)3-f4-&aWDPTQ&wSJtiJTzHQj@4 zeu}02H^Ft>{548V2St5ctq|5WFmY=G=;@CBWqu$hPia>G4&|zRfv&^t7U!?PePFd{ z>MSV}x5xwj->GjZir2-l-(waPMP9N=?aoJpUXyok{a|*OHxu*=#&bf=p|!6dt?jpk zTxzchW@hW7&c_T0^eC#@249w6i9U%B6&#S+h_uReMRX}SQ^eniah9J#!k9{t+RDIG zjWIULZZ3vh@CwrJc(;WR?F_!zlZ3bh2@vhQr(VurArvS-v5@lu!jK;)+xl3_brzjw z`WFH4Zl}1T`fDoXK{r0%Nif;b3`zA~ZA?R}bO7dow~**b9S)tPZv>YIZ#>!peaY*m zwiotCc-5^aodB}i8^;Fkc<}=n{2Ws4XGR>2fm>)?jkPH%`brR2 ztC`J-4(GL8E@)i%)O*hJ$B9IAc5^*AWyMRqw2kzOWgd-*1q@1FvBdEuJk2^x#J;#& z`XW1;0lwpMx1^T9h8?W-&`a~OwK_(mN^9xqMr`ZcrhTh-30yzo6hHblyJ%4?H(>l6 zCTbfhMyOIhEc@gTu?zrPWCian@@ZSKND_>Mj=5aDF_;6r>Y z++~%bd1RSaVbS@;)lTKTL1f9Y;(@px`Riof zd8&!|URnD|(3gj$4}ZhjjKgteOUfzS*(sU`_j z49&ZRkR|7g(F=N=5iEL(dp7t!JR|AY%b9ME?+_m+!C{(@d+jlPRMvg&ulFYdxe(F5;{*NszMdTiCudI=d)=K3ia#Zs zXqmVK12t@%ItAG2eulx8##&nSA*mWmO{UlXDh{ZmF>;k!hK(qeLx>A!yl7u+0<64y zx%px4PLENEs(`n`#HW(=76&9}rQCmLp34efrI0FP7SWh^C@7*I{Qf3h3XuB6Qd~6J z$&^=mTbh=UbPw&AjLb^GYLt#5nS8vQzmTd71A;)x%7>4Bm(NNePDYnPVqU;Cm%4!} zO9d{hZYCSJ88s}ToZf-LpnXn;C=BFOc2%B%oQjaj#yCt(qiJhnXlxImFQ=lz#6Q_m z)J$@joBg{@oFS~f0OBgZruFl&LBeS&IzEl1AwO?&V#LK(EmO5VLNLQ2WIu~mIR$*N z$kcdn99cA5&DxSoQzn^$tO7j7q43b-yKPaJN`cF1yop5i`BUL5ioF)s9Fd?n$W4BP$atqH$9Lkm?f`mk_$A{*=> z>(1GkQvpijWa-+6jA+exJP~RgM_F1sDIzs3|3^|VS{vnbB>#m7ru731lmL|*#gUDx zoBT|+T{sbOC0B2HB*=@}(D>&F2X{HPq*6-MMbZHdS)@)&;I-gzD6JDgDZj-i%leA< zYD^V>kY)p@Hs7ody&7~d1*4j z4S3)UGE>`NwKEHze#KW~s09_X{Tls-OByg3wB|V?_uC?D4-t;ye5^(L{Ivk>&d1j4 zCpgCzO%aXDRmBtz3e2J_)eLHgH~qbRU66U?!TDqr7aZO1jcPNv>FjXag>i?yh{7?8 zrWa!EiF{>X-rEEvPxh(Fx{r5)I52i$`$3-3Gq!JD;KSj!S% z+ZN;!d9wu#nF(8p7>Y5AgwTpPt8rV9C4K;J%` zH0q)IGcv(@0$&e+Ip z>>;*%6-_0JDgbgpKUvq};E$_U0$A}lMe_6VS{Wo`vnyd}(3i3zxQv-2ZJ*8B$?BFb51 z&&fQC$ZQxiO73gNrhE%($Nm8?7JKvKj5H3GSihGY`|a~;(eq0T! zLQ5g((E`Na_X#SW>^~s)F>^_x8CFQqKs1601_vl1hzbT{C%l=SjGQi|kn{tO1k}|b zPRa#WOP^;xY+px*aWK24Q(QjVZXTYuTK9UMYq%-)kfHU>In%LcVx~`ylgW!Qht17K zQp9FvjsbT7k*MgYnWz{#=2|%6kyJ|++o4*_L?u~cD0Mbzbt%|%)g@VD-vE)-!s{{t zzndL%{-4LVo~zER*U2Vy)ROPxYxnC|Golh8NXiDlr?R&@>Up8B#*k6Q zy>-HeBn(_*sbTF&Zt~OT(Lk;&DpzQQ4H7^ z%rW$7Hkg%ZsbOB$RwTa?sx6~o>-S=ZEK;CPnO3RbVBv5(Y8~P1>`rKQdn=3KbTRYC zeh+Ez(wb}bBImPRZ#WFFO0m;nE~_4OX~`q?mL8VnrQX|M?hYK`>^)$P0sQiMo}Wo! zijsP&j=DBf8Ai?YP#RW#>W(7ZwZu;Oox(JeVtI%y=N&?Cj@8CTSI(YMKAHU`ZtOsv zjTens=8)2hC;Pma z$`2**8D!kNNsS^ztaL{&!~T6V0x1b=hb3_I#ChcUgouHSf(o^RVt-E>hU|mabVC{iLTr| zS-u|f8l5{^Q0?+BiVk;Xg5I!R)PkQ9ksd#tI)KyM?tY~5>y|SmFYH7`p0nM8T=zCV z5?3Gh<&ivaZ})5F;#T{+Wt~6h&yPyBrY#r$;FX}@CKi>tf$El(`hmvbr@W47&Q1d7 z*lvlIL<>%SWRs_46OH(aAbet-0BPy>xzdGZB5UO$DyBLNkG5)W?KC_nXyt%GFK*!O zUy-c0-w1OH?;0VMfGx9K!Py)-D{uXW6Ck(07;zkkKo8M+xQ5M3jn7HuPYd6z&SitV zYIib8^CMA(yPq%+5G3C~DL}q{LT{vchn3^cF(#}EGGayfI7u*y`m8D{33D;T6qZG| z>q3pS2YbkhegY)+dV(Cja$SF^`9t+{5o;7@YhY*02j6vF_2{bJBJmg2a52|?kd7c zixlc>M@L&uw=6Mc4gT5+`WV8;H2BjH2S2xD%4h? z`CLPn*!83&eI(Iv8%h^vu5%5wWi3)xPZ#9JVcYFd)uSappgt+X_EupQrPrin7p1Za3EneC zcCNJ(!Aip5`L%HIo9BaAr4cqC#AuN|MRW?OGs9om4uZfri}z|%X`{QC#%Khm-x^S3 zF}HN##%jq-X#2l7d&`(e!!$~}v2L8k9U7O$-D%w2-QC@xad&rjcXxM}!ri5Chh=6r z+1+n;CX+9DtA1Bf$@84|zRx+=60YgYeOsFf&aNSqQ^V)syo0?|fTgTe#(NYbpMU`?KWSQp#q!1~Bw*G5n=Is(cXH_dd<+;~fh0l3Uc#(^ zVgHl4y>rD<4zO-zv7{@3Fr}G;Yy`TwMrkr&*cgZ2=h+T7ZqE(VzHmeu6i%kP^LypU z117mI5w2OHM0PtwgU)l~ki7hLqQ15y27W7@yLIJx$O$E_avUDpW@k}+6gzS_`aC9Q zzSiVA<%+MaRA0>niQmB%tYR^!JD9M2%BO#1^k&WZ_8VM2&Ri>@$k9piCT19&nS=)s2=4YkP#e+b2c+#XE#FIhg2v# z*bv=2M)r@*@OJC-7q#!(w<6I0G=t{;um5WiJu9pKtEl~d4h$-lJ!}cm#&u(gq(&;66E{(>a`awChOiH`drRXCTPK5pC|-M-P;4pKIl*SIQQwg{c*x2Qg& z9{!8oOb$pNW|hg2Da{!XWgzh>H~eGibV087D#N1{N{oEQj*NZFrR%nH`qAsL!|@|9 z{+qeoTw|HN9N-GQ<2nT!ah*&r85`a+%!cP;2zs4%hq2K0Tej1lgX>Hr64yX;yF}=Y zUf21~I8jwl*<+7S)e9>GIGNAp;x^ZT_ee9vrFlu!vx~~OR2{ZXPrkJ$qRuXC^z}tD zdsDK(>(dR}mUkfSs}|>{JKx*WB~%yAHqH+%IG*vI1gB>8qFlwy8a>wi4UbMIZ!_Q$-bGsCghSPdI1!_1EX>fd$bqZ=iOWpuT;*nh|3 zmb#|BCCZOAmEaLss!PkDHCP(p_jcqmmzndFm#krG{@y!jsSSIBX=niV5N%MqBJ1v$ zbye3$mbo_r&=f{6OE-Fxr$*~n;fJyYd zUuVQdJ|4i0Nw;W;6(%InCvbdsIb%^82f|U<$D;Q|mVNz>Nwdl4g_5s6;^gLdrMY+a zFB|J$XX;8L)G?vV(n_}UDEbBMdZzvx1pT>&(*0)ogaM{}`czEWke`t9b}bqWlFACG zlpsN;k1O2X=0ZXCJgRNA*cT8O=8o+{|Pa$-HWATGJF$q!&qF9n~B^tXB+D=dQ30WUCwF~{|faMcm zGEC*j{RcRX4J;v3)|dbrcOW$v(astkSNN4}gKlBKmAfs< zJ5rPzko(SKW=bZ?!IF762vT7uTa|sSwXCks8IcFq7CLc5zv9<^9kURyYAO(`FeIKwHG+Fseu)MX1E|nt6Gd zDWP0ylKW&oDM->aQVySG8@nNfx`tb5KD?(7sJ`|q4WD0S+0)nN_METUcVJJGD9H`( zhkh~kkd5T10PhzuRS~r1P|n@lWX%b4LE2I3NCmg7)h&luqgt`a$fs}q36FUUsAvUnyKZIzq?886JX*lSX7no@c^FVAOET`}%^|2|< zxP@J8GZ@$f6FDWFxcP0~kyVBJ-AE=6Ni&Ey6e!RcT8E8CA&dL~d-sVefRI-+bBkQd|B;<`ZX zV)xYy8`i*X5k&Y*>;n4m7hB>NYJZn|I3PK}jumtzM5BMqE4|FImeL|GygSJ2DBfxG z`4n>{BI4X7UwME|-4Jfmd$={vgGi2g2p7s@e9L}(9S_k*ZoObQY0 z<->o2vKz7xPFfJ9sOIXXNxo6%A)QUthkDd{NzE9lkk246I{+|d~+TIonOjs8H zlwJfw!rO@|$)TiR+wtl-)z3G~f?t5~E;^%fCW)s>_M<*l<}d8VF^wZX%pXn;7E zwYYF9u@|ZhHtmON`Z{8N-vwo)a7Ji}|((PGlX37x>nBho}F&4`AQ zEE-+t*tfi!(s^g(x?{HhOy%&q`6DS6PQMSq0SeAe#jtQFAXr&10CDs%Dq*a!Zs2HS z)87`i%hpdPm5L34K`E!%Ow_2w$nQA4N+zPnyU}DW)Kh02N<7JG zIn=#8js29g4H_eb6)ztJXJqL)ddj5s0NlAzz{+pcDQ}_r9i<9`>K)|=4tGFxtZp}- z?>ibo&DIXz0~(%@PmlM52#&tbklX`$hVc;)`W0K-=xP`C^~a|1)sEH!ZHCFG-aNnu zz~#)Rd4QK-zTR{19@wV`w+)GBY%L?P7*-O3y69sp0D9VPz^ z3wh4uHF}9yXL8(oXGieLf)!|qNef?Y`(VJzLvV-N=hd>Drp75G&GYR$xqKdD9W|5`2nYx4D9=Yan}J8LSTepnycnUFS{iE&y5GX*w{r%94Z-Topu5fCS( z?k)JEE-wJI<7|}*np)?~6iEx?8W_pn_7C!g-M1Yd;M61 znbPh#Q&f(v6lyn-ZY1KFKdp8d6=2!cqIksXYE^Fu7 zC%B=e5?naw8E1)T*k~l%>izBf)||b6zF)&;UW^*;MQJT3N*L}@j#V`Fi;+zVIu0@H zBue||sHtQVQ_t|=)XV3^%wD$yC6(QJNTfS=$5)&wS6?Jq6;4*fZ>kCw4?ZvVwp0@Q z7PbqK)|d7xU9lJ{8P!{5|0Uz`N8r5!*UrR;tF%`JXTn}FgGsBQ@8TL{yr?Q(l0DUx z05$nQs-%&CF*ZIRVLGFpSXY`wXW?VXag}T3=Y=!;#BLmKx}=m`FRQLm`;DZNiju_Y zINLl+J=R%S+0n34=T;rm(Jus$XCgUiNX+;aEg_!KMhN>i^(tIjYC z1_w{mV36%LtPW#J2|R00ubPlTUy_oB;ON0r_MqGvM)xGJSh8KJnFkNsOt~na?9Z!Q zgDh%$31?zGFOg1RhoKq9fQ4rK%Y-U~e{z=kL}Fr7hbFey_e zAhYL2kCG`15N^FGF?D3z4P}138n$3l3&L!D$+?+hdn>q*4g_>Lh!n93J7#5aTPNu$}R51B0 zme5jUl(rl2F>F~OG_3*d_)tZ8XuC=w;F>3*k#5^f*ZGCuf)=dHip$2Xi(Cr#c^(yo zP-(OjCn_iy7f;Xn(s|J;09*+0?|>y+=l0ZbLsy}>ruaBi(oV;h@A|4V7Hok^ZyXhS ztOY*~=B6kTB~+BJiu%&u6+2l=YNN9UzTg!krU%EuEjzpIRG#0}uh_)R3HNL>w;CAwKz4x!y&s26pZi@$uU%6(8i=nu5OoJTq+r@ksDhR<})Sq!ou zjNh{rAx+H#p4 znqLImXV7n=37B^GqIiSu=ruP_9hhJJy=S##@;_b_N=%_z(js#R93%vIXt2h?kX3hj zLwdb@aIbHl#n}piOm8Fw+@ksICcJli9C?4u_%qj%omELma{(?z*!mrtJTKC`{ z_iteAPX`iwShv7D?rG!n^}GI**(K2S4Yu{m7vu8F-jREQj^1G&^BLN6MGn5EHShE% zN<)w_%Tf?(bqpCfcEIaHx|0&#+UuA)XH&802!yiBb>B)6br#C~OP zG8@jiVAyFyS0s}a@%v$1j0#gW|I_!bz$%`)0g(?bjfrZNN#1-qEVoR4M=bZ6_L}a} z8s1-2={=}ehw84@L4ki}`+{dQ*z8^8W#Hu$TwztLt5P-XP>lL)#QQEtR2#u9l-HZD zP&P&I4{&5x(W@|rSG|VAyT(%CfMA3EP<1;@NxOrXKN?D1|D@Z7bL8MPL5=Et{B2u| z5YCc3IDkCjio*{zR~UqGSHatUWj?oMj(~FqahEao|vfUpBg2f{r zac6WWLwG?Ye7Y(>dh8b~9;C_aYYw+TL^Je&HvF3i88UgI=g+t1C5h`$LggM=&PalZ zG?4D1;4Qj1mC^exr2cZlyDQ9{GeaOg#_QL2HcA$CL=nn33Ld(gG|?Fq;hMJKQcyId zVWS|albzgQu@MLWyMYAryfk$pKdgqGI#O{-aS8c%Hkg~H4a1wz04hOM9a?ia0Q+u9 z-U(ozG^~NYv(=>d1@eN*wn*w=(rFS<{)|C2t@4%b7FmyxWZUJ=FP^PeQ( zv2UW6YhQ&TMTq}NQt|!Ql1jwL#>&Xi-pt@%mDE29<-S}y-but210)>@$C8*d-W)!iV+z32?W?=iNM(asUi*EB;$k_!Z3V!S+j z6VVi!kNv@}xK=3-d*6{fS^7;_pDmN756vGx0-mlHJC4dbJGn0#w}%O>uXhwMB^azF zOeYv6R2ai2#?Fdre_|*9k`gPyXN>Hq#Cpg}qoBhNj&tw#5j7oEGnSV+#oYK{sAW)@ zVM>~gM|f^DnYfc&EFL}!Ak8JH!af%!NH<*SNSlZ$ zWVbdKR3vF@aE{RSP$G*dx0@FiS;#1>tP3$Vt{>ouQ@U8(6cwLdOUj~JxpR*dGd9Mg zZoFnV`#C!;b_|0Ht6wTSHX&?0XcdP!@ztM;g%rS@6q_`2yEH|tng&=Dx(;X)oyj*+ zckt3*C%2kIjsLk)-4vi)8AENTsG(!>dLD@q7*N0z?>R5YOdfhbnp=`vo99*)GoG4+ z%gUPKG)aX)!AIJ3wZl(y#ACU18|~HR78a>=G^%X41_9c&;68ZLlQxHrszluCYy-ZNJ>);ljYqaeMca@{?27yBCL%a3u{EpV2w5aLQs7RMpeuI z&UcSiz5Yj9iX=ThDuCs*@yWt@^{cx@bn*Gx!Mp^v+_eaItnYx^LzfMaxa{!4OkE!7 zgo~U76&H!edt2VhZG|+F2dkbN={x^trbvz<_0X-k?zhn?L&iZKys4sFzTfn9nL9TtD zQWj^}{z&_?Nz}8{R*C#1xUMZ1LH890WjO!i9jy)uA>4Q5ESlMqPgVlM{00QarQOkR zk6N9fF`TA}ay?n)+bFj+#r~jEi?$Yk3TAPZ>yG>rIsi4o6g9uh6hD&Y6Z?jM@W$EccxsE=<^W0B=} zaNqH`g|%WHB{{EBx4VMO+=OJj1*zp=zMJmea@~Ww%>xzF;7+s}yz9f8!#;2bZ+{BpE#{>QHK z|K8D}_^;=0rjnK=wi4P0>4yYq)K~kO-MGyP5~s9=4Mkx=AdA^~!uMvV=fWOqXNE2( zsdG$5ykNASLc6i(+BvA8%CDg6X1VG)#O;aSe8G{bL-3)9UHNu>e>BLnt3y3q-qYEw z2Y@DVJ+5;eWn6LcK2C`6zP(y~^8mU&%@l21Y(03rR77b@3ey!5g_yOb&e|~=6Qx-6 zd$E=7d2{9Dqark2Z)ET9P45sa_;4IvCj)n?&)R{q8dsmijP1J|uvDT_3NPd1l{0qG z5Ut#}JdZjupX-lVzguB zAz$;xS*?GmOiLYU3JAKK_B%+b{t)9(4Q@vv=wuZ>kTYC)mb-u;W#Vqy9<%m#;B*3& z+AdF7`{z_ct?aIt%M=Tgbqwg^rrr#;D>{GMzt94q;h;;)X!W*E2O}AQ!4TO|yZuD)k@w*)pmukj9*wKoGgf}Vu2p5`sd?U9O67`{!;^q$$fFRg`WuTV6H3(2r#Ah2=mUeK(HSviAy=RL zxiT|<`R32G3u~x(RL2S#0P`?PzR;qZ#j5e6z)&3GAkF!FOq+V(p6Ghmp5)3T_ z&STBy>Z|Q+xLWj=owyk@TUd11Tgip2uSzFpJU2(`r1WHT^i;I`NCf_}t*!x@irvWC zDoHz`7DEL;hr#lKWf;|HE&G)AR$qFeg>ug93N3gSPeF$J4{XgvvI23Dt)QwhR6Tp^ z;%Kacy4>8varuKq#K>(OwgSb$R;=FxFK4a3X!;H zk`SMY89wu0f|`JCDLN|z-pRg|=37A;wJKi7Ybf75V(eoq%I!O*9k_hyw7_Z?jKF1R zh!T!F%nvWw6GtvxkT(3 zQNf&(cmwCXONt#%5L(cdaA`l}UXyzw zK&0hC9M9lgn}ejh@>@$vWqedQ@FA`ymZfd2c%Lx7!-nv!}q~G#NWGZ;|ZSz=4{&oRHfpQ)WU8P{{3LxZe@umhkFTQ2Z+?#;E z<7faOhIf*2{^~IQ!~jCwJ%bNj)7@Fgg2NGYq>hHM{p493z?# zqg=DnrVbtRxjo&tl%%T@7RP1-6cbOE)VR;Me41o`lh_(rQY^|JIK;J}3_ zdH3G%#`lc08y2R?^Gu;7aQcq(cHX_~KkKe1P`8#Z$pj@AsNCIV%Kpju;qwAg4Fb{w z5NR2OTuWc?-Tv*8iqC*+duey!u+`uDPkV)e2Z$@em%SqH>+`>Z_y7MRe*d!`@?WLJ zKfo#2DqrA~q=ux9t_AW?q`7r0Dh;!IO`K+Hq~SUeGI7+kdupc~`m=jsfcmPEi%JwS z4YiA@SuQJ^Vc!H;c zfe@bb0l)B|=GsL7H-$gH5Vhb@9bg}{Gxc__KEm-XLM!dnbq5xblgpUPte_I`=$u}R zGx1cJ7|YH4uCUSJPtK4s+oM05b~%0Vs2q5Mt{AAlsK{wMuA~9VT;n4+z{iyv&u#xl zT*&ASoh6T2yscq`lumTP4)Wc&zZav5KKfLQ9I1F1GH}raq{y8_{;9Qct9SR2aAYr} z;E-Y5;t;{hN#h2Mogl18&Tw%O$Ph=vecA3lUZft zFnK1UgO0yF1X9cA)*y{m7kh@q(5a;cb-%i*}Q9 zQ3#!$}!??1LWLS?Bj5Krjm4O4u0;v6b3BQ33s-9XY&{G0Kztk zEQRkn8NaJcyi}8D8oL+Us(&R*T84`iR1iYt*Gc`fmmPy4)Y!ph@`ppadqBQWyER!nWTXAseV#04jE45^cUoqX& zSBs4dndoCAVadqiORpXEnYh`2x%00?DDr2l9>RWd`^kQ6<5f+)j7)i^Ax4y#qQ_6c zY}y;d?bh(_iivU4{j+UllvO!8P3Opt1|Ce-_iow8eQZDdIG1V+ccHQ3x;t%sf&=!7hR=B@9;XU6K&Z3L)PZq)VLI z;EtVbs?kz_x;Uw!W<&21Wv$RmC48^p5s_rXYW-;C3HEdZdIqN*{2SmTH z5R-{un0inY=DIy8O-o`jilk|LW=cozHo)K(qz+RzYuLF_$aB3O^51s3QcsVNo z1lHc;t!w+M670OZhIN0%!=J0dfIj*{{g2kbvgiXLyOu-v$(m_NXA$ z0Te#^C7#KI0N;D@9a@s z{w6icLR)8fS5C8!9LIpDL2BE0d`Ay95>zs4(v#@U(4cXegl}ZpHz@I2)J3sneUXWM z)rzQig)fv)_(c_U9p4RR-70hjg2W-J?I6xtIr)~=lrt)rz@6PV%N*?^P}h^lZwWm* zGI!|P-t+_sKQLcpj%=GMx?{1s_!(46!K>ZG^}{Vp!VN?U@I3z}>mt8P0+CQ`#~RZzLAr;}$ukR^uGc~#k=1?6j;V87-cg;cVQVH4LYAo%2Ie~tTZA4G zhSx4FVBL>Qdd1=8^Mk0v#q2b`Sk@C1sDl55|ip{2b3drfa zd8+a*Zl4s5ygyH`WgL~lxK<0VneFCd%m#^%o+|SB4k3iLl%uY01uKh9d>T6UoqjVL zB(O`fmp)SGSeXI#XnZI%5W8ndn%dWXk&qJ#`-Pi68X65#%A8j&25azA*YFy zDc-Ki`b@NTz<0=*54oIi!-ctX$tPzKw$Wt^+24sv*e9Q3%B`FI1A}fdQDp6vHx0l3Ryc@8QFhzV;lZkBXOmwo1>x%?uWLqTl}cR-#?&W zMc4_FEQEd_{G#ckzTj~`#d3>Q#>OXz+%6{4froGqZ8L%5XRBpam6er+rkW+xO~eJI z6y_Qzl}E1UcIH z^Z>tnKE<7nUuD;S!+s3z=Kk_zOPU7sQ}Q4RcI8kET!V7?i70u>Q}K|XWux_*3;+S3 zp77DA+jgGXusX8WgP;l9Q1o0BhCGG45_|!`hA`S6wV=}_t}G#oPvSp~T&uoK@0IhP z!RWIQBt?h%lMMh1!q6d3#HMFML!qYM8?o5^LH zev?~DtBQ#t)1@fR!%+7@-ztl5RT z^=zyQzWex_rAp_6GIun4*+>lHL2MohCcL0IrXzLUQNL(`pv8 zc250GRh;3lIh#|K6u^;8Q}&s#9jW?dW5dbKV@mdN$HQpMQAEIs8K!%d8$wU+8b{fc zyPHngRk*tb%@Sn7IVV+95VjhQdo zlwv}q5_J!2nXun&6kQyPe4k=82Y7>Z21uo6H=yS2$v4rND+Du!=&`)bN>-REOYB7X z%&d!W@G>Tns2MSt6|AS?s<7>!k9tpF+G%K`R=&^EHp@zE>`xF)|1#7N9jwascVJBT^Q!^t2FJ#&<8GH#MD3S=#@d{o z%*jQN-*;j1ggkSNmpV{S&%)77HFL$RE@7+OX?Jys`^71ZrQOd5XF^w@Cpa;suQ+&y zH3SR_yE4NV-oV-%U~g)}#QGa_wU-fuACe32_>rUrf*J4C-82}1oz#-fIY~TC2$uSr z5AsQN)IxFnLte7JrC11~rl_7)@s&$M#yaqg>S+ zN2*(t4F_sCI58c%E8%jI0m2P1!pVcICgGLnV@x|J7IDVtFb2&isD0_XxcNX!M&>2i zNeYvo{Q+^{;P9OUr{n6S>pyhV zuO5Zu>3Sh(VY!JU3|I(}TGih96+&YP6iUicTF6q8X97wZ)HD9m6-?+BP6;xXDB4>R zXWa4PI#w;0pat1q!?}1TGg=ei+uyYG8Pmi*xSWn-P%_=>E35Ew1-3 zcCtmhvT=^#H$Uz%;q|z2g}}ImJkHX;;USFYWc2WlsRdrF_&A_&?GAU`m#*o{Y0(BvD9-B)&;L!qsPm%_*x+p=R zy?Qcp*_n_L5EvaReE|3?>HCeE)fW5Y#*XtKK|ZMbesAGad`-lRklK-zI)xZ7RWLBs z9HY1HWDtnKcw`6Fxj-_7p+zor03*faF$cw)CjDfUxTmx?ZP1Is->I~hxJRV=afqRO z7Y6vj!5wLoxJOn~=MHPsnP_B@BC2F$F}+)csL35>ag!pAC;a5HSZ%oLhWd4X*?OXd zhgQJSZo3QbefQR|V^E+|VI-Av=S!GpQ6r6E+#w3oOuU=(#`0*VN*T@czHGrY`0GJ> zDe57r*z&DXsVk@lI*mQTLT8F?gqFyea-3a#h#l*)0M+w_C@I!C>f!m>>bE)iO_1FN zxpEzrYS4*!2`Zx+oY8$(j15NldWFt4VKs7X*9VR=LO$0V57V{v(?Ntwl0<9uToB^` z??e}C9}C?W4-;vn#&m|7RE6DPq>ORR2p?ieQ^cT^S@`XU5yN>ZiOKT%T4Rb z0AU8~m3T$WuMX87VcI_-e^`t8LYyt<9Z3w@B(i^X_T{BAz1uKp6~rqnC^vAEp*Xs) zzHR6yHErqO-N*p0rfa+PoANc=E(DMTP!A4V9%S^K6kgC9Ubt5uB?7L06FxKd1F;F; ztVnJ3E}$DCxM?5~gPt`R8MH~=4)+MFKpFjK^xC&{RnkM> z17L+}6cE(DR&m_9H^g1$pb3M7oZ0NsOudXBDqedf<&er=OZEgbm8OtQLR^m2<1%)y z^EehayPA>9PwV6D^PkhqZbmir%`fL^Fxr0-mHhv;s8sx-tyr5lS?c{iD8z{>8xF`y zD4$m8(JVz`6cFlyC?cY1ez|^$VYK8?yvn{QKKva~QKF8sq@ zm}4~36jo*4I$x$X_udz5U$XOyOz9&)E{S)y8Qsc3%;kHXXOgDZpLy}9vd*$!zyLkW zOFQUmMao6y${tq3=@aNYv;MhZ@xY2p$uhP0w5EnidhkSFU}xT4D~zyQ?{&k)e%xtZ z8TGN)Bn=9NN?lGHOmLio@T^mW<*3p2sF+`+=BQ$(V&Y4Q-wg0~S{J$Y@kQ;^&?U}d zT0P9D-7{OMMq7SclS2cNXTHG!%H2A%CLdjKd%pcq zxx_HqSFBy&{xP5G29oSNF8_oKHWvMHiT5OUx?DnXav*c+D8f38+si8$Z@%xiF9XAU z;Lo&-Wys>PJh|G`TI_CtRk0FTvBxOtfF}k!6}Vo29iH3He1}CgGQ=ViceWl%&Cei` zpx_$Th!l(mJ)57-7~yP4LlU-qAqLfcn^F}C6s@Ul#>Y~2=t3P;A||Yl)5+r?eDU$Fr0w2jJ!T?7tx`aMQ7H_rH@drUF7|eH~wnmE3jT_G|pSu!nxB@Z_Rx z$aUQS#YrWaYIEwuo&hgH=xcRdHz5b7?3q%Q9-am6?Wo+3Yv@~&$Ia&Zs0yB=cD2FH zJJy@3-sc1Fu74lT@w%9|`5Hnw^43YqM0pGnO*DCk8ZP+#nl?N=@T5A}eU}E9$r*o} zhB!Grsmwej-Zf<#gvjVZ$`#oDl?Ua~iw=%Wc(g9pl!=W~EtM13x8j8lgGqDct#+w3 zmoZwzUI=@A<c}nJr{i3^8IsSxkFq9@f_0DRFiN19$x3|Mnu0V)gc!i|GuxM z+0TPbWSi`m3asB=p3n<4HH0>wWOheGn0OXZRhWrSw>-s0YcR>Eq0;6WF@Rl~al(XR zGG@$y_zVKaKTOZ?8t3qukaLR*O}DS-?3~mutpBGD96A>z&CEQ3*dT`$B}8z@@B2>JA}& zN5W2_6Bg~%=tWm#{()O%Apu%-wl0aO&3^8dfxGSrM)z!!JCN_!h*?9!T&*&(!>G(K{|-c)aA3*8P*s8%M)l&S@80#Uhq!nCS9%)T*k5ol_u| z%7#%Mi_9{-O%c3Vr$qrSIis`2W?rAorFlbAs}aK^b*cu5! zIHAtj1ZaeM6;bN5zDIg!IXd+mtm@t^BhktIm9|VNDO^CjJbFYaPkbepINfM4OnvsD z)@a?`d>QXlUQvkl=CVO~Rt*!i1 z{_l58a{u+!_`l#||L4B%->sb{m8BezMSgk_RW=xt^!Sc=vVoij{4z|Bd}64L0DI8? zDcT1?L7qSF${ZUsciE==`^V)oNauy5zp)7USKv zP`9A{iaR5w;g~7q%(54y%z6Zjh`=0D4EUr1T1qP$p@1!5BB>dCB4{!zK2Wyox@ay0 zt8P%1210M+uzcMLat)4)7O2rQoIeE7PO2eCuCf{n>)B3~EqEcDur?`LMNuHC=r^+` zRXknRqw7s(*olZ}UvWxD%+>3KHBfGzU=P;0mu6PlKq=2VoFP zTkcEi3Gr25-%D4=T~u7IVfRj_%h~Smchxv_+_tH`X!O190^F*P;+%#0YHAqA3-e(k z*(tmHj{c1e8lU*8%FHQtL;(3^+Btn-%ZZkW=6 z!uWt66bCx(XT8j4_yT-;?yvB`u05_*m1dhPOMzNCs>?`hSjjmBVoe(QC`=s z60VPTCr24e5l<1Ot0VNxsaHNu$H6>BbV+L!l^yoPBBm+AYpyr8$z zv9`1}K9UynP09+PplhE^5oFf+mcTr9yS0H#CUJ7cbwIxlSkP{k6>0xnl&b#OY0YoG z29yTk+>lMLK3gaB-?%4G-9nvpma`da#~L<<;bk$wZGrg~?ls?!eQY9G*LE+PVN=hQ z_3qK3`co~lA1=oXc7y|2nV~;=9_k7_5|_=PpQsO`>4dKkUvqiBn^MEeb4un1GqH#k z*(1j*(DrbIyz}>C@Z>EKLP^GV_z5hGJ4xAL;9HcSFkle;TIBT0U*!liV2f%Y#UzO& zR3j`sjB5>*dUM71Mub{ldLq&)$MZ(Y-d5n};CpX4luL_W;4JjQnWx$dC{isW-XoTR zF7$u;HOWBjU0^2dH0jPn%F};@wYd;b%fqjLJY=gLKMaJJvWzo>i z9kRF1_ZKAb28>{|Mjnk+6SZ>1(of0E&HJ*)r>GCl*wYy7>*#LP3jSEC799ivJ^bJA zma`RjAGvs|=ppEtM^wbLnNF;#ecix0;@H!8rAo7Vh_B}*2#ai`ZQ}Bqzqb`P1)XHA zreWkx_7t)0b+Wam#TT3mJ&Mdtt5#>D=Gs|+bgaOjhc&5_qP(OX_ac4VmyQ)HLp+?8* zGLh2;sre+d;6J%LN=S1-4Zc7eXyj#Ix;u2AF&W*zdO>`}NurJ2>&v z*LNMSoi37#6E7X;Iz2EGpM>$W^lq`E5TrT}+rRNVm2z0B59H0=`Nt0wf_U&w(0_`6 zm%YGp>&V{s1*FlKSGjyP0r@}1)-ZiJI#W`Y?EA^|2VFJCj~cn41i{Pdg_}~8VZf0j zxT~OCZ_P>5mnNVjVzbyNZ(T~|^ zTgR9odH~b9;20Z;fX|b;XfHN7Vmc81m`rs+RQ%m|Pd$k&przQ$Y9ynKEJD&%(Hq{Z zElB}J*gE^*kD9a$^!eM&E~wPCzHrcU0!tiY(c+0BhZ38Vbdw0j3#RIC*#%q_t)ViY|>#F$JfdJB7j8-%!=c)0}KiQFgJ=?W5^zoY~Fj7o(`UCaQ3ecH{($ zqp6HnR9;p~6z#r2?U}MigtTa}l|$-_G0M!p3K)rxY5bw}KFF zN#Q(qdpq~j0NQ!)ate;|tqWM@iPAOWIe?>uEW9b@W0x==(TEuObe>p@Z!ot>x<4Qp z_16z{-j;%$^p*)|-6BU#{Bvjyuok8W4CQMZGL#eLYh3N8op$K1kSl5ovndKO zR9NO0P!u=^KZwt5Q{tI=zR)a-w2~Vk5qfjUvf6b9iina;XYXgRLBpp?;*|n&+$5c3 zDPBhN1M?rOA!)I@u{Y+^8piJCQ~*vkf*Lm)6h5G+HeK9eH;&4`qcw+QjkU_ZnBlS! zR|Gog+YBMXa6Rz5)z!z?hq{nyn3IiJu!4tT9^oV9;1J{nhu*#oPqls+nreL)oLtBz zTbh2uNn<_R}*9;WIq%im9z}PLZ^B%(U@qTibD!R%?Wf2xTvQifKx^CJUNH z8D3iJeZ!ge z&ZjvL(b(8XeZ2R#Yhuh0m!iDt%u#2pIfrh^?_4dlqx27KuWWxN@HWKnzS}iW^o;vT zs7?PA?cc;R$l3y{@&!G*FL92DxB{%;wJ~CZPTY_CJ}+}+v3~<`YJuT74Hr!~1ojk zsktcBS#DW7>WT%7mfJXLP3VuaKHKI-r#y7T9%jOr=WI6Yv8!Vpx_VKfW{4}7nBZXx z$xeAZC*k0e#QPZ;AF)xa$kof|hPCYjaEh4~MpHq-1cgy4Exlr9C;~7~+_5-$VtA(J zQ65E6O=j9;%r0_tdVZY53bqsUAOFd(fyIj9_%(&LdnSsn$k&KJOGWG&BE&v&i+#`s z_YBzCK7(c99&hRnzx_Mn0&2du;e&R_%2En{BlWw(HoDP>0n@rq z*}PxV@fFkYhSTB`n5z=NRFIA1pzul?Jp!~|Xgd~*dmD+nWXZb=yN8(icPD+2$vgbs z0sKX~`&uq3$hgf0C(Ak59TCH4lWoFg(2Vl*R}&L{w1(ty|8V8=%LxgG4}4b#jY&Sq zaNJg1k^n<&OIQ*=`Om%wG?; z2&*>YnYH2U9m~TPEs^Q4x>p*YFeiWaies0>+@_QChrV{?1{9ekD4uj&$77ls6o zixTlJb;Rrzt9V#_tv>XjIyxr=9c$NPM{(gB(SFTM6~C?A{qdvl6Mr;-U(xKDIdM_X z9^N-GD?8`o=Y`Umtl3-6IZ8+=`>!}Lytp+{zl*%T%cU$avn6qeR3&C^it;%WD~jB9 zq8HkdH#w>^PbsaLON}+$3hVM_YUqwx7ut-?~fe-qSsM z+VK^)bB0SyUh7%hocip8Z7yBGwW@L$5qY|{uM#rco9|w|?A|h^0k-<;LFjmjP@)ti zXsVFmX>q|DmOp2uyhkT4)hw?}dz+QwkNux=G_{6uGsHIP%(_)+A9C4iOrl3NWtyfi znWX_ExOuGwSZ5bXaw`)3b)`U)&Va*Y1#F@Wwl4TnJ}UAoGpL%Z2pMa__CJvVJtU|H4l-rjf>lMF4ML5ssovy5FhKNYnE}$LyjigyG3=% zBIH;i>XP;6H3_Y?sY|3w@Bia4$CoYS-*ch5v|Gx!(nQGhrz$8D}Wb0T0XDpGol5h73#`m%l z@VdF)5@rECIB|a2d7O2{z0G;NwfTO(9PW#6;xD@Tsfzt~m zBZAmReW5)*wmu3;##m^?D%ruzr1(+^lA6W z$SFrLNOaw?%X3G9)N3PKjHbll9`Z^wOM zS+KsYdvNeI(mY#dzO#fe(-E!P_BIaqN* zmST*90nG9>j+?orWx5qQ>$#V8L-2#>?x=GC$Sp}+#TeI`U<`}SibPfsv1(KiO>mP*E{qs3Q*6xp z0tSkL_Spg|8}xxXPIcO3+~hoZn5P!yM)XgkEZSu6J3xJ1-%FrQO&OY$(rA{IbD1!9 z2G@tlCHYTO9>G0{snRwuM$<9mhbrsCtma73%aVosH3u<`rLNvyzknbLSADguxZ9y< z`08-9FEu*eQ+LiG8uz6|ix8bW{q72`DG>+29oLlT4V7+uL$&y9jE$o8FdOc1zWWca z*5f5a^RmCPIy+mGOE09`>53R}doy2~w^-3taGo^NVT#wLfwLk#WOZ6^_+L8`D}VdW zTA8C0)gZPy$N)n)$?zNXxf>(3=O@C`Z^Rt#&s+z5l0Rvzx%O2Stwi(^s>@4ZcyxH| zS4|=O$?)Q=&i>qju`UQSzB4JKt+Y}l5@9e?ZAr>$nmGgwyE4?qnbHCtqU$n(K0ZP?R`sD-UWokFGfh^-ePFx2}VqPRM)C5l!n^T-=puyjqJ#kI}g zKIu}Q`w!1IM2+rPy7~#f!*3}g2tS7R zYtysydAn|gl21BAPJU%fM&GQJq;>5I^0@8;?rjHb=f$JAY^4qE&kAznO0Se^>8#4j zHd%wcL*ljyzh^8AdcnT)#lH(kUMS8DdzbEWil17lvtiZB0uFC%qyCuLfRd~YMYC1vG)MEJ+S+GggRegO&ug!*6n zSpTY={`W_g$(XqQe+1bls{SX{b64vOX9Hys)}TZcM7C>W6Cgml{T&%XDGDvhhsvJ5 z?mTMBZp#L2YV5AGK)$UnHiW77YZg;Xya*HXVY9oBzgOHW!-40C%vwl-(V6Uc%jxlb z>Sfbun)hRWThHeQLzsW02N?1cg*&bpnzeXavMY>s2R6?Q`2hYhQ?Hlra^ueER;@2x z(W5vT%^nWAw04I2H6GoFhMGN6GHS(6oj=3Y@e%d+Hy3-Es>WK#400xLgqhV-l-aD$ zl(-> zkq>a{$AY~=PKK2nbpNb7f8sFfL_L-xqs~tiXT8AwO*9-_(9R#5;&xRV$119c!B9(- znl|P3O_I8IqFmar$xM7UD3wdUozN+wQab#_nDxTSblrA)<(yxjIC-iyY8Go@9Nv&7 zazmTBI60oEH0lcJ6Tw-05uWHZ^{Z6nc7j;!1?;$?Fg=l}7NAnq#KoFRD`#-U{E$58 zoUEvCvRcK#mCpVg2EK0h)FWFdg(myH4X0yT#QALp3Hu7$RlUV1WEs@%dM2P)DoKb%gm!&iFt`Un4R0_zX+lD$xG! zkWg=J9y!_#f+vwwbbb>?hB+HS09^>q=Xy~OJmg{(QDj!uMVGogqCn{`ncuZU(EFUN zu`EVQx9>T4#WC!Z#d?7=WGf__vz$d3{Q0Ad3{6FL6^#+$fC`^W`hZzNo_hXLAjVF5 zKB-AN$t*fBSEFsQ*?|1`R3oC5FUqv7_L^%X!+5RCFjDNwHO=2At{)>;@dMm~cSSHi z@ipSnV9U^OlXS`F7IWA(&P#$jhTs|FLYgPY*#wst<;LaN2bGabf~o;TycTm9F@IC; zxrKdCBGhA(yiUS!`0iQczBB5?BpkQEg`?ID_fzB?3M8!L3(7wX@}Q*q8nkm#Mc99Y zXOubNkp}!vkuYs&0~8lQ(9ImY5&mODL%+X3%!&huPaWRxH3Iu==TtQpq8nxq1bo40 z0S}slcaYJo7GB&?a3aW6)_c((&6X$h0~fv;-aLP5Xk+gdWZ%NkOf+Ah9aP*R1s~kkQgZ+l1b&pLFU9de9MY;64L@jq& zkB%Z9U2Yy-VZ7=9ylSg~i0#W0rw)!>E_U5KtR@!8d#ES*&;cDH2YC{FWH-jYr1&-@ z$=7V8f04p24dZjNGfupoSw*jWui=__MW4q+;C_0uioDwk}c+TK@jYxu*^#qOMAb~t5YYQ1XjR}1cQqK07cQ1DEl#6CZokp`Rf`Z;x zCvq;ioPne@C?e*Vf%lm~`nB)_-~9InlC{+^pJneW?|E%i&9>_R-c|Iy8?I#b3DwOL zE=u-5DY$F)2}IwskGb&Yg8%u=pW=3bB`zW}J(1V-*lt&mqCmE%|IliB#`)L1f1k3@ z|K*hZ*QnQj|CIf2j6q7WcJl&=nY0$Lv@=R+Leeihr06t(17LItKcJyO3;+DcSUMxz z9NTJqB<|7M??KoRCp1N8XPhw{^;z?{nvC3f9iFz^2HpYQkls-PX~wKr7CYuiE_Bwz zbbehWF#3a9Voh@&Sp91>Gh=_f$-XgL^lj{gu?}h@*D1JBuoo8q>q@T6sky77 zm74slLV4l7z_fyid&em+U1fSYcbC%JrQ*Z_K#;@E=+OaBXLh#x6(k0&+a*?ok#QDc z(zHI1fIXVnvwbM6x4hO8`x$wZ`dIdy|K3%Fe&}uSg@lku(OIavSAbwMJGX{xLwoY0 z5;Z(UY&u7jhD;l+%`*%d&TTDlLJzJ8wk=8BC5&)wcgHC7QNfG&ItX@f3)CZ3@+@+~ zJM`KoG^Ur>#+0(Um7`DPq%6;RKD<3Y#9|h?*teZ>z~p`ZJw?s<`d~uW-Eow1Fg+i0 z%}pz&C3Sc2^{aVoj_=X-Jq+0#vmF+rLcpDkD}mk_2vQyUoQ{F;lBblbpc}|)wpPwA zc?v!MNa;Y1CAqW?I6by?ZbvOZ9eX1fZ<4Qac`9{+)euBCWHZ!Dwwkv^kn5HGq#cCa z7x*9d@+;US%*eN!$?6+J{_okQe_x0pY;K|K;9}tToe^!}^qpH_=;CZ)XZz38*uunZ z<)5Oc!_#E!P?Ew@$^w?$MbG&pxyXnVL@aCv5K789P&+%)W={2F>Q^!DzWQ%F&pTFn zZ+q!iT+z{_%v}4z_#Z#+^{!{Tdv4B;9^#|oTe^U+uuK@>AQh@Ko?cVq?d5R6gwE z-mU(;gd(cJ^}_|3FLW%d(c5fqZuC~DS{#3Z#(v2B`-$foKKP-P>n`y-0WuN*w^>(e zi?6U~06IitN~OZ9UsQpXphu)f7y^jUPjR3|vOjsl5X&aHe$n zEjw#&D0f^QKGlR<**n3zrZ5{{fyG27$*79cE;njR4e)!%WTtLPd_9I|)tpb>(ui-A z8LG&Xr&?iwgLBKI3k!@3j}H4;abixcNnb16*KPCE8Fs!3OOL^+-~RrH`SL?<*hx>Z z!f)_rTLl-ul)UNQ;VTctVmq&ZJqq7%$~c{nLya9r*%U2EuXMbhesrVwK6Jz&{&QIeN(iZKQtN0hkKe=B z9p;XiGaIMc#*oxHtJtC$um(tngEYO5YO8gidZ#QmEP^EnzGx5mEpi8l^6zChabRn` z!R_&_XK0d_QhokW1n_mnjP&5;*)G3)kU)Y^8y0S6_yU+-{GfB$n-TDtqie>@kmee8 z$|1!TaOOSPC?PG-qn5~s^&kciVB}RjL9TNlbF%rMnrzKr#S+LPRV1EWMijdEr@9pw z=+_GAY9gJzgmY^xV{U=1!HUbrSR*`6@a0__!RRmyV8JY>QNU*iq*40Vlq;eCXbg^F zV2Piv4#yM5-YVrOV`NsKbhrqGt(uqy%5+LtjpnYrhk>&0N&lXGRi+YcqcL**-%#6r{aQ7hBLi`quH5u%DNU$e7H-_FD)H@}>KEKZgsI6^(or zK8|yeV69UEW?*BOESppG?M7=WVJ!Q&`aAzhG?ioqE4kCnvZ$At~*m~q? zpjY9SOy=_mEc~eO{C#G7FVI*0-XxECop9wb#;Hyj)i2up_{LXxV6m*f86oAVeafAE zTb!$C2Tv8?W8zlAj$%S{X$U@skW&BfbIz=^6X5@WijgGcS~?l5 zH2wKwTDQafCMPL0hKkqYX8RdpAqxtm&|l%uptu}ms@h~K~1OeDN zqLBRe*@EL#}`EtV7I8?WmLEQevOeAoovfSbkZ8dd8WGMH zRKu%UNprNj2BHja1rS*aIn?~ta+A_?t@t2jFZcOiZlX2Jbk2=LO~Iuu-C9e;%qZmKnhAQ<1UA5YZu% zvN-QB3IF{j{z;{p##s3;jH zEX1CiUV#Ujv1XgtPM4OUucV!*Fxhj8I6Z~!zuvujMc_%B3ieJirA_&uxE#4K(PvLk40~?%)t?)~JG#g!) zSc4X&AUVt9)}Ot!anGY&SI~_e4IuNFkhV%$g8UVVtihf(>R9Rtdu)&Qryb^=v9(RBC{d(_^T5>1b&wHfXbZjJ{|lHc7u$EnIg zKZU0iw&$_DrRBeB`?9{Cm+l)~NjNis4^t%zvM8{@;F}|7JI8 zcsZjkVt&a!GOkXNk@$fw`4d!c%K9Va&XW8F5nRC#g2lqFt&E@i6M6oq6cJwMk1__^K#|)-y}$-^L)V@}|d;)6?vWTHcT5x$VyS)Cscmw33YYRqpMNt?jF~ zOI+QT>r+Oc@|&#i03V9y@ND{!cMfzt)f?8ETNi$w=ir!fyRzpbe7@d#pl!O|ix%O* zOrL~3?!6lw!Ivy|96$^)=`-IYRqtktIM1c3gC10wgUaBC(D#I)!xV<=-{JVLwTK91 z&$0MsdoAJkZ?&NOl)b{wr8S>5`fsTkyhP@1VVn7T4l;xJJ|fpC`tBQE`w)M=I*OfO z2ydOxDx7<~Yk(`S^m#I9V%*r~5C zSYBml<7H2wx%gx2Tx`^>-Wpz8Odl7UN$PnWIz4{Cxi4cD#jfTEz+G9cE+U^Q?QCV7 z7q)WR1eZ3Oq40YCRf;-?rdp3MhdbUM{t|k(_;<4_-xIW=>F5 zXo$e1$CV)UYQQ75HHOU;`AX_d;Uid?r^-@dEHKm66CM%z*Gjt7D_t#;r3$r3XP z5s}{*y>U7oy--rYMSPBdS>@_VT zZHso&pk-b#+_!|N1epc^@Bw_Y$Uq=AD#OfV1Bu#TU6{4@IL6yOJbC@{Sd{-Evwc{R z7C-Ma8V$>YcgE=JQC}Bjpq)o{mIb=g5CK;68J5)rbj0-r)C<#eEB&nH5Qc2&%4V(C z@m56=auB*Tcm0naqbfzT9#L6q14S2wWq}4qHo9yKJ1Yy|K{2P4{))_i>7vsr=ObwH z`9Kf|<-*QMl;H&bD&(2uK&TJo&mVTo2+J+9!W+5y&UvC&)9d?mh!8gCWRs=L%JJWC748kZo7=a$x)g z^pZSwC7;jULNf-`ET*JWd+d>J#Wr7LU>y4`&q|7v#hd7IcqKa;&BqBmVur8EjT(?| z-#T!LyEsoAa7P5c6X;Y=FYf9@^d^tP>pjo(CvwjN(OQGVU{Lmb#!;oIDHYq}wP=J% z5fz6Wcx?kYGp=Mb;iErpq<;~ngzfR$P(tjf{0S!U5u$BY>T1M56ouQJgT!=pky?IV@*jVAD+14 zm61)i!0On(r<}1;m7*#=>E^Qlm0h;O=?;6r<_?*aK`!~6INj8F?U`?fYf_dy3l;r} z!3#>7CiIAAlAhv`!r28{Ax)3ZAj>^qygwS0Q2~?A{?x)*N|V4g3yO3usQ#JLg^oWk z+#Y;MpSBx@pL!dML0-nUi+%LTRK>m%{;YLNKnh~R{-(LY6jkbpA>8sTc-K?=R+pfA zIQ)5|H)arCdt?zg;(KtPq)&CC0kc+#Vnvg^YG6bQ{57>LVUr{-(*gK9_`}D%&eP5*C=dl=r|v4z3}E`E{doX*|w#~ zAwN^TP4OTf8`v=;&Ni}dc;@56MfNhstD<+`@>CRi@fS05^?(1rv;T4h#61zzkZL zpoTzqO~Q@vY<^ylIF*A%GbLRjP1X=E0faz+z*J!hpstNMX$cO+FczvFL@UqPhs1;|I8%+`Ge=d?l8<3duv!wGr@?WIO}jg0^-*~8z6ZmNy-w! zwGP!*rS>&>k4a0nN6FdYuy9CATP~fHLnMptoM=u1zP+LNd@idmv96)e9VL4h9YdD? z#Op#H+S)HzXI#NlBK*oOq-xsuhW(MX)p3>Bu`YS?lpxc20L zV(J`FKDe%f4OooC?XPQ7q&cn9Y)Jc4mN;#Y!RlWq8Wg;CCQ>iKI7^8SZtf4~nnKclNSYx#67L>QOic7r0Se@457Q9m!Qu70q%aNXn$RDu@ zvUX{|STBmlviJoS3)HShv;(Mm04DG?LS|!JW`}yNvk`P#3P3DN;R*G6N0Kt=D8*h7mmwiJaFFgA*cTB7PZ6&vJb2ox&e3(Jaw|!EO5qmw!ak zk1J%8Pfl;nT5{wc9j;1uvZr5*YqYxCzQgPDx)~Y(utKA6tzhva%I$ZH7q8*1?O~3M z2KUG5Xn?o|pZ0IANnk%@*fMSI629&p@A?%J`a*p?`j&xP%)$IQqx+@pGu|JEbLka??4o$LTdt}SqfcW4PhJ;Lq0hdTL{m1uvsAT%sw*JJaf%(5ei~W zwSFWc^H!# z`Vs9p8o|pOA|>}c6lrUV9<-|svEl^`W+!g>jy}HQ-)kQj*{wEN#BQ95IF9&fLzJER z7^h|O&>4Q@N>DTu+Yu>PRlFzD`9iX{GgMHl6rkqnIT*z3)iUBAjrIK^ZL^uUYWyL0 z1OgC#ZR45v83#D3ZWi{<$`BG>=2<|aTlW-S#VLfwZH0)yRi!bipKv&@|1%v-_E4`h zwL(=RR5}1Kp`%kQvoB@ZraOXOI1Jb9_2bl?sM5B!6>}2SWu)~fPhkgypPa9X4nUgX z&MJvDL?Y3eiBMxGh9ZfYBF)Oqi#anR_)_O_ak^^iJoUfiYiUx`f>ms0s0B@a&Bmdl zCh#!)7+vy@v*7+Zj;Eq8QoEe4jblIkqsWD;HD-OkMU~x*w7R!&`~+<~eB9CX^&jBe zt+jc<(|7ypjrspisr|oN;D0T&Nf`eVpi`Fq2eA9e=3r7B@X5eDaBr7(08 zK*T$3jB;HD_E})@8&C2hA3IkQ3OK{_bRzN##i1zSNL{@?W58r3e?}skG@=cn%{gzt zlUT9`k!#^(m*?D>7evS2!T@t(LE9h8Hu4D>d2QHV8)DlbA@h842BRS{+jh{>#xIz|4)-k_>Hhp5kj}G1U^HcC! zCiv(GnME5mMyL?D1WLQSn`jfB&RjM7-xYWqSS`jr|3@n3kFalU=o{^={2$R?=Kl#( zF|xCEL77yjp`sya(fgQCT2J+RB5iDgcV{AF@@@YoQ-kf*F7$^9DS`}JxI%k^o?iBAK3~j2zV) z2csFi3e)x4r4CdM^lz%iMnB|$rRVo zYSSNQAYynDqETyy_U8F!IXZ(iV}gJg8j%U_2~qs5Q+AVOG#hnn{L%@^mF=2jH8(d% z;X_e;mmAl}`RK5TAZj+-FzlrH)=W%6i?Ku+Mk*zj1W!_n61R6z%ERC8^UjpD@d>1I>L=_TT2aY2I_E@0;(orQm) zpQF%%n3JxaV86|ZDRDaraC1qp?=w~XN$#-DABDh;4&Lq(p5_B7&qjj9C1}8kyv#N5 zK#$UU%B>K4;AOFqTYY)K={qTozm|K{FF5(li zN&4N39g;4}t{!=Lq%jct%-M1QI{T>#pkiA5?-$rV2$0-?-&1uUKtQ73VX^-k&iGeh z0?Yr!mJqXZv@vl0=bot4fYMGs#Qf?eIgp-<@h70QsI;lHB7~Yz8w6Oh!YR}WP#3G< z`t(463j0fzRJv%nOx0%|YyIVo`McpK?l;=tlAJ#5?6jqPyy4y6KZ$EQeRm`+AtbP3 z?dyGqH+|!qedgW8_pxgv52QhA?YdGk96r5fPgGUE@43-akL}SS**nSh3*HOuyk58$ zk^XW0^ZvL5|wqrc(lcFG$Xe#L8nulBYv?zYmkjV@2&4!3JXl;Jzwbe7sR>=&QaFc;5o z!}k8J$Cj6$+4k`&g8O4$Pv2OXrM#1kvX^Y8nUQQ~ac0gcl7&b4#B9XBH$DFv(wn5?ifzb_3Qh18-LinByY$lpx^l(!_;*utM_l zFR2La;#Jb(U)jzL$s;G3#hYXGjhu3fqu+_BKxaS$G(x6y_R=ZE>72owC^nH*_D@?{ z1!Sgmi^9CP+gPU&cXrkEjIHUH6sus*aCtqcGMJMIYj|$55_<)OQgt0Kjk)}KHFq*e zocs0Nn(?F>bQ|TL+-#tNy>UP+^f7QyDY|^7dw%1cSV9jO@#AJ1{w9c)u=nq0K_nsP zC|aQTgOulvp2%|ZpzI^^qk$~R1*9=35&zhmsWI9fj*^Re7CW8$^?qt(*pgkjCZB#a zF&LQ(`ZU4s1+|LRf@&%@=rn*RmPgG9Fkn8fn$I~wNUcq-`RxmvYD-Z8$jN1X2}Tam zYwjOOOo`0W&M=w4J@c!Y#Uf!LmpLB&20))NeUPJ9uNv2r;^4s68q^mIXh@I@za|Y3 zn?j%N3i9`wXLcQt-c3R$k5xy@-z|f-abSwdIwFc01>U8B5Tk}EdYq0zy?H`*bt-O^ zuaSQw8c!hu^7G&y26mMd1EQdPO7=*tl^w9yN=pXG{8*Lq7LDxSd#~SkbF+GVcoD<8 zMWA)nZlHD1MkFV(mR{4smv5-1*W6dicHq$X`_fU@nP)L77KpU`tD03Z!sl}gc2 z>gMgSKUYHYzj{1!qZ$06^oilWu8oL>sEztnD>aD!4K?!bUXZMdX42Z`cg0kB4U;?#C8U08khC;F^g)H8l@_ARq(;4E1uR8F~x*S z6>e23Qjsrhqy~M82;S-BxQTL}hE1fJYnQXLFL;cw94a4wh==CCZ?VXB|H(>UFA8TS z=hxWyIcZUHyD;Q;SWpC;?9Mxba+MLPr@AZcSt?$Y zWfc;tWuA{+Ib4%Bb%P_ls{SVEtkILr!DLo#t}>gwy--m@| zJ6k564PE8!m4nhJwMH+j_0IIOrUkW3LB9NUj}NUBkt5Ov3deXL<6>*kO~vYmGe&xH zo}>FY8DmAE<@gQkmU%V;_aKrRj*s79|P_l>TzrFG;lFYks zC>z(Bb*`YX!@R~4n9PbysFUWJyWoCf!YD*VA#x-{xpcp)~ZkHW!9=;h9&r`%Z3QFwdX zK-3*6F;p~pKk-VgmRKpvB5D7at{8(>?$t?y~7OK zgSWR2vz9@3J4Uep_2BAZPgnX#uF(fjH;Dg?(drX2gLW)9VH3W$2&S!&OJ3&SM)`6}nN{uM>&rV;!FkQ{ACm|2mDMJ%jHd>8PW zXN~4*dyCy4v15)h+=4uc$m8IJ6B$w;iR^p~b4!%m+PZ?N`It+}7eU%sI&%!U&Mr$=jV#S8lgRb!~e z5K_*~Hn*3PHs5QH4SR&PhdJ;@Gko{h;sK=fNVE){J{OW+S*c41>VZl%dU@odIv>R@ zCx*|Lt|z?()Na?ZgP3+!K=42iFVk)I93&1UbGCDTsTI)X3_RU-$|5}FIU{WlC+x9L zJZd_(A&$95o++nC5L{kG5U4Gw1J9hU7#*QD6BHhfYucpG$Vr*JR7I$HOQutYjEU5>Yh zC0st`f(=RUnV@IK@8Mdb#q0Z?GKdR)k!&A22o;SbPFZ*+#aw8W9+s!S2&u*%z1JcP ze+TNLxgZLVA;NZz{Sm?eA}vBUCd!8uB)qlzOcD2ttHtp9?f_S7Z^)K0(uODv@gj8} zts&uaRy@n#TnV!;C+&tphBB5uiL65>^`<$Z3v!;ptcVG{(4c8{c*8ZoqgD|uff0v4 z7)1#>K!Y^Q4P#(YEH_)a+D`L=L(bYM%5XAJN;6)RlSx!msA;P3WP@^Xo#N%IN zN!zncaku{Tf}-3gRgUW3vTSBv;-n~0DBFewp2z5B0f2HCWC8slY5`{=$*N+cMXeX9 z13o2fo*d9*j$_p-lejz^&*C5Mi6yrd)8SBIwIB81VIR47APlui@Dq6!KAi)CQ>g#f ztRGq)Hz7*+o}!9KIGYp-ZEs;qB#FZP?tH>fk^6Z?d=DM_7;a%UjoUt~apyR1u(EdD zR8+6Bt!qlQ|7NE-DE0sYN`eVfQ1gT#mGUhug8#OwM8s`&A=6chH%R!ZVTKrdeXK}7 zrpXxa1oK@Au}Rw|O2^mkrjmae2Nl8ViXY5NzAyvg@llIIFLOs;w$RB?k&ttXtt#k+FiC5wiS@c_Wt3{Pjo>dWgS0tWIhgWcfSGz5Tc)Vg|iXHZwg3|B=h11NKVyjheJ9;%Q3En z2Xn#+Tk#+Bp#pqJ{@h>cuD<-_YBLDhxQIWXM58Qa*%QaYYbGwcrk0rI4BUzdv} z_TV_kAf4*2A^;0X6P;2RUYJ;+SgEkc3kqJl%1XY&9^t7Qk+K*kI@$7j8c^U|NwAZ) z^Pt*9pu2D@CP|&$p!(ogpnqf%6|3V9WM_wsbsOa5Ii@Fc8g)25%;|kT%-X;!~ z5Xw0iPbw@XDX$U{@5xyy3n=g-WFFRM2_Ep4Ezw{W6D8m=PP#L=C`n46?dPo5Fb>?! zGo7?fYR?Dz5aBRMQzPZf%&m^^Y+`c@Exc~a`NmZ zG_te^Y`Y0{m4VUc#e>yHQ-i1h&jhYWG|nV>+6VT-b&J&fqVBq8c)AhtTcnKCNGn_> zR%gWP0fk4-x<{ikFZ{*9=^-+$Id?_qCkw;CUzI%BHVTwAB#5>O1RtCgl3fV@g7?WZbW#s;ys&n_&*GNEa_FP0iJ@y5wMnlXpDd(xy!6xGKbTzAQE0VbmdS2WhI zHdek2GkN(|T$-Crg>*;^sZm!C`HinZrjaD5q zaMt%7xj7{qkWoPlPx|Fm8xJ+5|CK%u``DCb%L*NOZfTqdh`duBJu`{kWqipaEe2b& z@H}CIJ1V%}cAV26$J_yvY!jayb=!pSL%ZJl_DPc?9z>i8LGa5pbRH?J|FVgyE_aY) zZ%uZ42KwXb;FjVj*hS@xMs&~xqAsEB_Y+wZSze+Q5!1Pn2 zflyB5M+-s#%spZ*IxPvSi;%m8{=1yq{;mtv$J51l6tH7>~&$ z!Y;LXUl`|4@%S%z)gn(dchkbWdNs2P~0w~V^1{ZjN_dwuxm!nhUV zzu<;a;dd~E`KLDc`#t%`$M}Y6_@@&(LWi%BJsq&T-BTA+g^{cEQLFb5b@%&UxJ(_u z0b4zq9bx0{Fzl^gz;^p)9Y*9H^e9?}b6zX*e5oT^ZHIr6#y~s0!zZ;{PtJJoNL}Xl zHLZ8YguBhIIn*sX1!QSv)U3;0dU52n4{Cic{dd~U>#z@gRCGnN;nA8DCbhmumNE?v zsy2+!Wwo2wS@0Ed2;GXvZB9^CHmhn3oRa{);%h zNMQQOE^@^QYRnnHi%xL%w-xsmj_WP@EIsg@m+)%=h*LQvqZQ5(oA9cji+R+*krSs* zQ0GqhpfRYMO(v$;G>%`rY3Y*xKe&SJYFby3ZwyQEzsTkO_0swuos0hh?TY=!r6ptF z=^C4(nySq znJGT>Rh14xuovMvf8Z~MN=KCUiB_9#xBBA8=glp6j{hLdTuQ^A-UL4j7|98Y6jlat zhM2$P#qAG&@dOwAuZ2daPa6{K{av}QiD#2Cm(rrEcwC6f^jx=9b)6#qth#zP*9%J| zB~3w=TF$5h?xvlUdp2(>?3P-)XN)d`hKZq6vaRRQ>J+if3|bfvMu zWw13h0uwb@uo?tbp6#*&GXMlUr+T6LLxql9;LxCmOVW(R>Z@}x6o&o^JKc$XrWvzF z`t)IeSzu=19LUz1h;!r95vLF1CRZ=N+4YAY$MoIwskgp)aSyzwSmtLCcBw^@^m zHa43%W0;TZH}6-PQKs6bH&*^%SFKO&PduN;8&1=zx^LG($zdgO8#_6e_rU>8GwH4h zzGIU=;a{0wor*sFOaI~XS<1hPeUD*(PkcC`kIU~a!neN@hWLQ{pr!vns($9S^_iHI zcfY)9eSyIKAg+EThxlOrfbo4(FZzs1_dQ1V>UH8jEc_Z>Sl@U@XXoEPI^K9^XYa15 zDrCI*>Yt=Iy~aV`%FrI@^}VT{<6|(S1~f|%plR7t*o2#JwJ^Z^h@Z0y<|-{L2aS*NM;XV5Wr}rDG)wy_bTtB3B2rkmeC`h4f{1h2c>9sU|{M%_m%utNJo$& zn?*eXV)cm#M%u!|7Bx;Rs?LR$Q7?L(KZo>5X82fUa6@e#TtXO?TNwX_;PIIU)bf>* zyaqVfKe3EYn(DEOnaYz|wPp|V^7^;&#Ea)SQsrp&@*(N5cU-eY4_R)Dik zg(hz2$694yI5rX}<5ix|C3hzn2|W}_JOTP6FJk0x&4X(u^?WnTH3agxqaP^7)PkhaPsK$cydr4)=O7*gLjsE&9?M*w@g6^p{B(+3OERG2aa{LGB`;^8@v!T5ShN zUr56B-&ZqD*90sZpI%5qbw2#2EX-C;zg6iM6}IqX?%lxqxW1)tnyrM5~Ib5J3`=Snv(F!a2xdt7bBa7_KWf5Ra z7LyT(t`tUlfk5+Pe%SMovxG6un26$SgGymOwg|QYS#B0c6Zy+2uoCZc2;ztZ%WnC< zPwo8SuE4*lWLNMOVD;6}JmoYNQ02q(u`(k+dV2MB|;i~~4-iiqR(>MgIkKe9W4)El+63yh7D;+bHs z2PH@nmE6%t&58^Ljq5g12i;VR^O&%m{-o>Y$J@!r(yYd|KSFCiehrW$&QpNap2Bvb zMmFNoZS$qBcU8VXG4kp@(ycOS2RXoZq0k z?|~;c$qVF;rJK)B7pUVO1C(4`Vm=t9yjlFrx~VuSwM+3?vPCVXehO!1MN=$KE7zBr zKeaV#kw#{cC@vks%Sx||^eoUV#&6Oqo>fvUo^^Tv(NjKG&)JmP1otGj4wQC}cxA8u z`5t0%mLyB3e7l=8><0c@6UXxfng!Pz;{m3Md=v+b3bBhC@k z5Ih%%jJE*Ax$8F;zG6sPm;&;_M=10YJZbIO#vcnKXI6qER-3I&cBSG-DeNWnttD7ywb?;5P2GI^ibohd^>g{@B1pB3;WJDV@ti!dBp5!tLYq5Mi&v9dY?!d5 z@>L+oxkxFS?O;b^xaTcFBIL(X8~OSoF7BdbI|5HJb=fiXfu0>q1x5{9z6=GBJ{ zTcY?8HQKwdJzI8*K$KD$1_F0q(!*(8f#G5%^{aR_7*wa)0r$2NVtNNygESeJ8AYy9 zLVUcFM}Dr4=Iq&4*;|J^b6?g_aK_St^7`&>(cE&pxE?x_g6bytn~{v{ z+1sV8aZA-dJWqaUJG<2HT8~T}F<`$TYzz2Q$HsA70Ood&hz>oezO`4lbr@XWwn&9+ zCIA)z%5J+;F_cr%B;WgeE8)&xRY-&&YQ&@LFf#eFOx}PD__HYj2pZTovl}sH&uz@H ztLiSn$W=b+)TE;_QTITb2}|WE%(06nzo04#OYWYHrrMVJS}xa!7w=tK2 zJTb;%=tQkX&xN06B8_HxEG1YlEEYxXdZW22vAX`4GGSdt4Fae5`MOdSvxY0Y((*1a z9TJ3v+T_3DvWs*-lXM4?=GA@GdN%Rz#t&^L)d3+Zry;81dX7ZTJG~IAJ7q!6yZPt*_Z_>^h920zoF+S@{bOw@|BD^ z^B_WP!uG%{z(3`f(Z+CtJs$k*m2 z0CUSM%K}8!r=L$VCX(Sz5g#xEb%0QGQHzyrn1PP%lg0;v&Ih!^t_PUFZDRF83=i(_ zxr{?e`-xO>aUC5^JvQbj>F0@UGRMh8uxs+sTaOjL;5rqxVAT!yX~-vg+ge-?#>+WS z5nMUkHA(Cy=q7IEvq)VtM(ay}Tlj-hbc5>p!^`d#D!K;o$|^|@_>58q}^LbFEN1irIuhz&^-9r}eZgjYwl zPh6TV6;hC_TM#`lgr`k(vY@P#gW^CJdQYdQ58K9*1Ptk6!wl?4%(nNKtr#y$nohUB zo{gIMceFTL%ov;8prWc>prc>s96@cO4S$m6bpdaByQ|G{*g91nKcTGGyLkL^-(L$0mrqNfKY}tEsyT}M$ z6}$X|-lOBTVccNENAH6e_8RI_cER^RBzAzN0NtCDsj2DV575*`dd;>}O(t1j|EPdUXu zc4Zc)tHCu^tvTr!6RhFA4N94wfzl?-L%Hlr%}g%!PKii^R2=id9TI5`@z*JL(@VZT zXGxEJrPEqbDvy6%R0rlaGHdx!|K8{xZF6HwojUUqajcx03OyL3ET)RI9=wXoeUlvi zD@Y*A^RY_3F&*RrjZH zg9$q(1AtSXJghA{arzXS=}oJUv@GR5oObH29WKN`X5EH~-Jkx_%=zTx#(aBAB$tC7 z*0_-kwIbJKdn?P;S^ngtwb72>EExoIPbs!409qP2f@-3{3EotZr6SSUQ*C1lnlFWH zkSH1Mr(!ODF=^>k{-d(+iVJyg!nk-y2_7{QmqjyG?n*{Uaq#C)M}0_#Ad^%ykI4&3 zyp_vLFMABw`>w-gx^4yPPz9vesLNAd*FN-BIK8LBc zU)Rg_rLJ1iSw-B#5P1mhq3YT>?&gc-vDqbLf>u<^>8UEeEX5+_FX4Wz2vPi&_8Kb- zV839StD3?&+XEAeF9-iq8}?~S1z??o%0E=8A%9O?Hrai#T4=%r{N#wTWDxEX5Mq11 z&|3_2bupw!pqIe^wE^KM+P0ozb6w?O$a@Ln&wh)may1?N{O5Ekz(j$ zRN3JZeA3VJ@`tHFhp33t*MSN4pddR&E8>NqQZP$#8i+p#yLr*kt3VrX#-lr;!^;=T zB(i5x;{?vj#-g~z1Ir2PgQWtwgbSd658&7PVQYpJn<&A9oC2^t<134)6xQnc0~-Dg z82Y3X)2#+vCj;zi>Fw@398++-!YE(D^Qvh-NuK3ZzH&T#Y}DZop1BYu-d7cfd!asN>Uo-tK%C zID4$~;YmuF?Vq8Ri|*ZMm$ zFH|fTS2-PEvGgKX+6!*zXchCBN_s$RgqAW7~%lny% z9|UPe?|TG2LMHI~Eei1Js#j&W(wlJ}W?s$|sm93>U^Qiv(^y&HEl$|_?nNkNS{6H@ve8sGNm&-+PfRbs)zW5)bYM>(l`zOy zu%Knuf?d8q#;6p>sqB+!*FW%9)8ZGaVV;j@(9d7|!nB+w|NVHR0orkDSsl@$k-O~o zd03v9T%P%{@a|xT!|_uevY}sDR&HxkHx;6@o!{Nd?p#Gxv630LFczt#Yb&o%jf6%S8W0FMmRy}kHDFk|sASPO#$_pFS zmoSdA5PzX}RIzAP2>>H=T(Uf$lw7GrcWazwCHtsZhm@S6YzG(4Yp<~j<7%cMceFbc ziqpv2gYXIe&iE)TzJ0d%fW^t*%#HTWiB*&sG1C;d_Kci%2f<%#o6e%BUx(_^=r>F6 zDQ;}nXE3*oKP0BsmjHaNoD30r55x^)Q*2W?fw(q zYfLl9h(`tjvZwy9J(z#Rdj3~En15$({uAE&H^3)FRYzq}5bdi49-hvS64O5X2Xgaq zs=A_()p9xGflC?a1Smh5p0LZ`a1uQcAS!rO54TjsTeAvW@9)u3@Liiicg=rsR&*yOpkImW=6}%knXK5%)LiVY!L|8gwIf2=7CZ@apRRa|1P&f2 zi2v(4RkPo<2u+rFm=Tkj;&Dg&p`Y>VCRmY5yG+lgbUy z-qAEoM|g-W`Zm{LR%R_m3C}}>i78QnGfe;fb+AH1#>9+_C%Zrkn4$_mxk#)m-6|>S)JAz+go;vxfM3~6 zY^<1BnngcDJe%!D|1=q;@fg|vh-{iM3`4da#^C;8|Hj>V=AXqpH$W)5ZgVKs8FPdh z`Hra0Cv!(JR=ua{?FG%dj=Z%AkEOaL3#3nu4IMct&lAYNjutrAz0GQN#*b5Eh~eCm zJqk1q*mzQTO}HW};e_~ik~2TS+TFxAqmv)o9AYH|QF>kvFO`%i6BV9jyQ4HW zEoaEherjrGLk;s=RH(H)%kKKmpx>@}?={1kx!vw5UuhUCSe-!CXZES@&gO&9?&+VN z*Q?2AdL$*5&uI}qZgr^?m+WyC*&Ne*{FI(c04Cq5(5W}IZ|>%4MpxevSW=R#U*C}! zIRn!xAW4Pb4f!*@J&op^;xSUXR(-+xu|rzmX%6?11(B{K*ZYk1b0Fy4;QoTc^GV0f zOQ)EHprX*&&MR!wJtNz7k;|?WYn?U8fXOp%+>`vK@-cwOowlRc+}!3gFK?tq){V3v z?($BF1Z6fl#&n^5EIo%%Z?yX^*^$yoLTDCu-Gw-5hf;FAyVyRA2zjs--=H)vGdn@< ztQ?pmYcNxsBltVD1B>*(>WyHM?LOzKW|^Qha>A-L1%vRcQHLYw1kTQNk?@^T7jGg;!NmTqhx+wC1MaS z){<+V83E%F?Z8^8?(!#pzJ#)u7ioj>*-zwI`>NfTw#g%j7~0WC)5W^svK(BtMj)Jc zM;H>JLi5JT`J!mn%t)|s8tWq@kHE}Rw^+&`2du-Nnn`27g%R{KgG2MOM`i5+)@ZY| zL+jow?V|ilhL2|Pn)vr!GaxcQFB$P=6!M6HIw>GYOyCz)<)^mhO`50GH;tMp!PG3? zO)LIftaq&w{^Vj-H-KKbNw|)jVH?TzvhqRezn(FFdsr9s0xK2tGHB@JicCRozgs7$ zHwU{?^acahg|cxE9QlzW zGM?w-t4w?3K0co0*tOm6#okEZ%=*Aoa`_6AZNyLkc%uHl?9E9n(XPC#rfx}-m;Y7>8VIx1w`b2`X1))%`6?1MU2vrgkD zt@%G0SC5-%D!0O_yWMBYJyZ2nbQklsSpHn?hqAUyGRh>i*F_))eHB;K017ayg7s++Jsl{RBGY)L6?Z)g6g$P3h9DE2QQZZ1wNxJ zR`x~9CG2;qr7Z0CM9a0C8fc$Xp_`{8m2bO-M#5lQ8nP5|NB_ocW=HIoPFK81#(1)k zuPkZD!Wni{us7wZ(^rln56Q}yO##pm+8lDgVQ7<2c;;<~=$A|Injcy{voH&ek!BIG zabcewXiMD6a~GN*if+ronBVSeO;gWX0aLOfE@O>umM^eusAu2TC0`-WrVm~Jy@wv% zMmiur`J>ga3Zxq6KD2bqSE^nDfuio?r)u4rt{IJDu_hWER^=v23wURd=Zwnnk25{I zYdt5~KuX!{B$Xr2N%g%%nMUO{Gp%Jb{qf-?G^*>Mu}elbYM0oPVZkPK@TQ7o@C)1T z4#(C7^g|oQiKBh`sCA&9!b0s!^HKQj@pE9uC);>}x&e|1)-&lLRxPmWgU#gt5l-~# z*b@O)4cTFJR1nrcn?}uQ5#ChG+iS32u7AFN{jR{JW~(Cl87Nc)q$L5L=mT<+jG}UF zse}bOpY+osR`ws#EoZcA?@01hXtvN5FQ$$JFX7U zY>@WRGQ@1y1;SE42fMQujNf3V0VO0&u-Op4sH{LUu+@hy6m2+XJ+OZ-6GYzg+>y3~ z_n?ToRt9HB>x~dOXSN7}v(7i+=Vp-iU_wgEJCjhc?GAj$QY ziHyN^j1foH>#s!3D%RqrBsE4R!KN$4HgIgL*)&&B=F~A<<;t^JRt39nF3Kd#6yv7y z2r`8Dlp&r%tn+p>2%bKaxpECa*>VU{vpbn4Dg#-u0y5%A7b} z6Y@=IzEikwvD25Q+EC!GL~6F)N^G4PA9bRx@C&H?67m=6=@A2VZV7nt#Fv_?(m*P6 zKO#V8xRq(N*@y0UNvC} zdu-~yP9gQxpG4(v(8u3Ib!a7*lW7b%3ZN~L$%Z~$+a-`klt0XQGm0;4PSmA?gi6QI z8)#qg)SX(Mpm@(8QkE!?9`GMd5FkA;A0VNiJFxm{`V_;C8;+S~+m6B{rDeows!1A4 zb0AE)Mn)07_OycYMjDJu@|%3WD8C>{mq?3g%X0Uid;JtGNKG{Y zC$0~)!=Ndbt16&;`F$WB;fhQDi~TI_KwjmJwXB56^SPz~sMrx(Z4O6U4tt7Q@sE1m z7MoP7ipsIUjO)^hR%z+?a>qEBX@_r-gLA z$?HZEr7D_^j7{6l79GP`U3m;wAx~;e3wA?>+GhtBbrPhs6lq%q7}_|xWfIf7adI0i zeDxo%oS&uVZ+)-~dccsoXzs*V?kbX3jVa!i*!T_6sP!t(`Z}+;>KEiaMy}~9ZVH*_w(K+GPSEs; zXy1nED8?`Qocbn>!QkxSf9gyd->(WV68Om@Dhi5pBS^%KCoFScCD*587pCJ(-8v--qG11;e`2dLtBhl*PL=I!ldYi zc`D7{SMNO0gM^RxPL(EcU^X#F5wZ&tR~IK9T3)@3fKI!E5FTqqyBvnkZy>1WHjq_n zEF;Zf+u$ku#PtX@gFmTLH-U*x_0W?@p4Ar?+etXz_t3pY_x0DIGS9RsQRciuZ*hHD zmPmO}C4J34x9Oi>O^ZAj0d7nYrkM2PSazSeI-%aiAqUn;t#VIhcv11AuIOeF@o$g= z8wN!{Y(F%1`@CM^H5j94AP#fb zqZ#2&WmjJr{y{#`*AOl{_$Hqu{x|Z;zpkbKktF+%wIpq5Y;W|P-6&`HZ5C*3>inN1 zStghP!GDlsS#dy1>RaoU#lA_hl;I&1={BLHiC5C>UYxLqd-+4?JUr&O}E~;gFFFlDgToTTID<$8(zHWY{6?vXrBAvR_An??%ohIu?!~En%}lu#l5&orW=2 zLMUx7H*iX=?4nW{GRh1VZKQwzJJ=-C9Y&`^$cb?VYBo-;vat7&a$57lM#FMBi3siSf7 zelQ$Sv2@bla>{TiFwl&?WLgn3Ab^!mhNmpS)Jawvl1;IiV{N3~^7YCJy>^i`Vc$T z{Y4Zz_kEU^DqQzHXS?M62b7+@P*ek#d}R0g1NzhYG$OyQC$iHH%-p?RitVM2&Gzeg zotGQ+osLn@ST1C{t*Cd8)wEaoXXntc38r8}eY{l0gAq{9gArk$kZ0bps6v!jM=gTH zTQv@hLu(X*6WX2`$lm=Ck{5E!J)JI(WX!m``O!(GI0{nUaqpgK+}-^p_w5&g9)^80 z{!_@V_psv^WWTBM+}nfFu9pm4fl&sJI~nNS#9Qmo;;&#c3u)O-O{OLjBN67D$nsDe zON~dqifdfBN~)b%qIXniwOu5Y1xvPR#pR0fdPxc8xFR;TuF->n3%D5<&4_a3(Bo}e zDZUFeW$8ABr_iK359WkFBj|-UF7{~^LtuyovN4s=g$e!WO9jxwXRB%u-tLq`oha-0 zSTj@8v?XM!V$bZC9S!!TG8#^`ds{VF9qf|2nbJDzqQq6j$I2UuE&td7w{-x5f+8JyTZMhwkC=2 zq?ChI?15E<0y~u#fMO1DKIhFulUv)!nmf0WMY~7K^Dgm2tJddHI6ApVIf$wHD0e2> z9C@=1n*5;#Vqf|an0WR&_pIR4HQGR#ogkOF*1me zKeL3jXFaOw>%5S(xv5&4IovUk>z;O#gwX5GB`hWF)VX4_^mn{2ivm4Vcwq~$1A_{gUjP}W>zKbpk8(i;3M z%B~ivGi|feR_7H)EJ+p(&V8K0Ffay&wZH*3Eb}~(hxto9U}1PYikW;OCj-+t@lsu& zzf^0ob=Fh>oTpit!2?Zpo=F3N0<#(Ht*3-}cwuBZMKCU$JSm;3XI!W~pn~E@vTqsc zF;78y*gt$N3oZZ}#Y&U1RwVX5#AK)BYAYy;!o2q236>eG#{@0;ti#TwV3I-ZeEx_; z%Zq-|5{Z&wI?WShWd7c!+J91>@4-jISHF9W+^>EDE1m?+#aDBFkk6SE*tTG7ad9(d zLfZs22%BAgj1I=l1)aT_PFHoxzZCfOQo96oLHxi802BM*TE$kmhBZ&KTBDCPHcE zbJ>RXPiA|O0KPPNkRusJBXM)^?)VE|PQooD_Ur-I%tIVp&wz`S)P*CAG%&N4re5R4 zBeb%U+3e(6xE%9Nz%=v59Q~n}F3F*lF3CPPHp77ebIl>2&aJurhuDA&^H*e=X;)y{ zIFC$csT2P%(hs?j$`_v9OG4(ah*gsh*uV5};!Y3z{^}Z$@c62<~Cp>-$Lm0Oy8L?-qXNZVXKyvp*AyB6$Nik>j>%y^t=h|VP=4qMP zog~hKCbFs>~^;+L>BX@35QB;b}N(oj6pC#9)B2vTp!1$p84 zFyEA}*q08=w{RJaNZ;-HVj+j+@c?m@a{mrqQF2YRK1V;ptfQY$-YC3t=PbN+Om;=q zcq2tMa?@w|kwJ8Z=)H+CZC*%HHc9C8144Pg&adW8mJ9{E@a0iqu1R=4Ys&l{uTj-R zh@OrFMehyq@82%WsJ+eX@MwO(7%@eQy)Eo(5Wpah0?Xz_~N|9o0~;jKnU;=Tycf1)5&StEVD)i59ytyD5{) z4>N);k5i9X#PC@*suz4{oEno*zroYpmp`C%%<31it>9rUQkqvupQRJ#aj)YwZuwe| zkGpG+2I6rQDYHL@OF3HAB`@3S4g~5EokHBQ8w8UTn}AeKw!+<&#JJe2`5eA5oO=Z~ zpYDlg${M>M~V>o4Qz9!}OI=v-yxc+X2j!=Q^nRjqwWMtr2n1vFZ<0HqV8)xpWv~Vapqm zZu7%lO`SmsFIdLdVJKr%#kxqk%<^6Hv&fD&7P?5fKZC8ANce~}YSstdwzj;r(BB8WqL!R#BN=&a1zBiEXpsHnWe?#E zuophcTYxgy@Ik>v3k;ev^LBtC&bV_dIl{DCHsU<;mQQ|vl5;C=c6&S29b39ctd zW+e6YimgFTLo}+!!UmTj`I1AREh))uu}8k(C11@55l&c<;1xz}4-+_HVA%YhA&Py% zls^F9*~&1QP~fz|AmJ$Y;e!^kI=v4qfrq-Yr z-D6rjlEEO?&P8jCtJfy{)`tZ5$$!Kqwc;@w6zr|DSyC2=1inJw6K4wd1^G!yKf+^) z`CV(d`PH)h)m!Fs6(-86OMp&tc?9ia*DK+#aL%n4<_Wc9cv z@W)x(3X}&u%%x$z0%_VIm+x;7xs~MvuYy5nAsVIHn~#s#ziw(X;3=+SLk-c>&8u6L zqqCV7HB3vW%fTCfaDsW?p$e(~MR^qo64LEwWoS(S(-|48_e*3gHhW-4&@fvL2BwCG z0%}t=zRnG=2)F;cIjbBsIuhi1r07bbsV|;T+_T-%lKE20>4l4Nr_EZSK~ET<5ema2VW=a6Nv}y`))0fn!)^$^Y+g65Il57o(_9$i`UCP(6cP3Z z$7bNCDq-H2^}71jSc{IMFZ*!NbHv!TjC}={3p zHhIn2bQ0`_N5uU@VSm#t&04mW-AJ`uqz#9Qq?hC}dlK27;7h&14T+8Yf8$cc7rNo% z=3@Rr=-Pw)qw-inoRma{`>rcU{-?@A@c&hL*nJlwE|z9y3_>P`w$A_8@}pT}TLV`N ztyctPWm=-Lg(zG#(&*J{bzwyvWUWsacT$23xw?M^fSp*MwcXY!bauDR!B=Yk1LhVm9VAl+JJalPe=xe=O{PRC8D5IvKDiOxP{GWFcT^dhy!Qa!+u ze5b?5TSo@nVqL5GDsWKi>kh?S9H7&hM4D&jF<)f2YzB7Sja108ZsUYN=RWI@)aeYC zSSYcXGBJM4aE`DHXNA!mZSCBcE?esQfxAhBq%XJ&Hbd{6RINU#Gc~h72Wqab*K)tK zmdB3y{AIF6=NQ%}%Oh(7XSrx9mer9eDQ%)7i;Trh@8Dvw&;WM=1U~gM!%+)-5MbF9 z@ruGzn%tf}qNTSruXj^3D#Tt+H_BW=KdB8d_#HqX&^rTnasO-Nb?5Z_M$L*!^4Cvq z+Z*v%fPPXG{q>2~@NrvJUn!U!Ve4{^QR8RM?>cR#7u2^?cg?SOR<~mp``?1p=pKSU zzDNUBbt|_NNZ;NoBZTVV7tRjsLNdYYZLQyo8oK zQ3{;}`a0Q6;%zk`muR#%E@?|=y6IvsZP4128cBl&>w?)RBn?KsaT|<7A299~D3Zbl zlD0`4EODA+mtTr>jk9xfgf#AXxIu{kauO&LhFyj}tk|sF7sypbbe&c(W#`S^>W<|BQ?H9)75-lgz+UuhPbn z`2hPzv|O~)VA`a#RHt;0YKBdKS)(F!65oa;)?-_OMSXduk&ON=>}wDwh~{7zGmOPS zJz)0m7KvaO0K>%OOogzz=Y?k{LX9Bf5Z32%3J(>4i_g?=z9-42eyPM->o3crH93)7 zZV0vw8?gVD#b=9E72ch$R}~4z0X5ySCvsZ$-Im-(s5zE_f2$s96L!a}syIzW*UT6C zRHs3!_RKmVWWmfzf>8SubNTavtZZV3W7?e)Nw`^29Os$V`t}Q@Cp=ez+Kb2&4nqSW6g6eliLk%c~N54|g= zADJk`16UstUk=npngi4UVFpxk3AFo6IBzu%Q4eM*?j8^UffPdK1quNmo(C6=6tyS5 zzk&xu_KOX5_ry3e;(2($@^!^ek+9^~a zVuvyA>2?&IPYsuQ86qECqv=BzH6n|&CdupXeBryQR@jHjp$rGRBb;l!&B6K$E{vL# z_CENI^h%YtK}VHLHhh`$Ly!rWV~?*r=Vz9KOlaEAXG3jeSwR#f%~1VSJOoyAkm+?n zXZpEp5jln}L`8&Iet|7WP8dtI&`!kdzlcw`*cE9sY*1<;p0vUX@e*uM;#KED!wkd& zDl6{KbfEw@s&5xj!elRO(c=6YhYx*j{AW?nQl_>jEdWaK=f{u<5dd3K&yO=c7yif` z)D!=>dyjv}A8|X#l&j|BpU^4(@3@;k-){83k^bu*`>&*e|1l@yAL!11?6H!T<`#yw zl7==mY^?tZ@-(aJ*{F)4ec8D`U)!%Q*o-Utp~WmHUub{HikMQ_<`>hYY%A+U9{m2( z(Cy-G-|pQySCAJ-OdWXuOWqTY6o@li0IWo%kcdTUC0t;SlpBpWLU|WbwmWr=5g0ER zy?C9$a_aN&i^Y6qtM)IqGln4O&YvHhnD}dep>(7}yQ|0k5OW{RDD#jtvZ>AxkD0L3 zyFeuGA*Wg-2AI1Jg&pKDVwhpGc7Je z6651|55(FnqY)t+Fo>KuT2_7(phr((xrw;z;r8qj^=KbsdG%I`_|iS#QaX680&+9% z#jT~hb#HxYd2X`PU)|a+$!oB#WUmlg&}K)E*i223qtj5_F*0**No{^_a?#h=i+E;# zc5AY+Q&L>n_43`W>YMj3G+cH~*|JJXV7o$x*1>H%Oa>J5#S^ zk6#fZFjJO!woC=Ah!rjpFgwAhf9D%f7sObM1NahIS+LD8$1VQM9YB2>?I%>#o5~bz zOTt@bxY7O6?^8~T9H7btTrnCO<7gp6ur(H&$8&LbHldSQEZyz zHBYd(m}wimWAS{C_xXWJ0UdKOu499KqI30FfmG|^#=I$^m5TlmA?um@ZW>)%-;4L{FJAG| z20C`kjaaKrOmxmPwwZc=P;2q*rZ{(l_T>7uZo_yJaF3>WjEym*0gg_6$=uS+7W?D~ zuV3iuedm!d8}~do__l6}V-3c(ShqH7dbaVftL_ZFkym{{LmUmRkO$YSo?UgQfho$XF{L&>#yu6KO5rKxtyYtcpTiC zaO2f}Iu;Kv>L4d=yR3fMRoN#rUJi4{J~)UQV$eUn$fK!Y(*B9>u-LRmw6~@?h$RJO z3r1s50fDVp{m}S2Fg)l%ZRbt+zgEh)Q#~tqVfh1|p%7&IPA$ruX)Eqo;W)g0O@65P zWzG=vU)7~ar}XC6OfYnhi{I$?I$hn+z_xS4`}-Pl#|ReYnjD`hja%aQ_t*Jzdcvs< zNF$ZP$PcV(61atS5AHiPGGVC?_B+J0yViy^kr=8KHO=zIoD<67+abq+Y0}2Deeue0 zMQYnfpq{E>nLA$%*nKt2cWSKHRurahdW9luKF@=(PzF)*e@SqmRD5|`MP%atAO#ZN1 zQAb#+WugT^bw%foZi54Y_&=}Af^^+>3jI11-A@a+2|Ey>h=xo|Im)q(CE;n(VZNhB;eSuLB8!Q^zsmh83|i6yN0k|YBz?hP4c?q(SoU4r1v)R7E| zw7}(1M#$)3=NMGtK149#T|%B#$VdC7xqkQOrA;|JNpcv{xC2z z_x836fl?2rnK^-JMFi|2K*9~jSX&Vb)cT(5PcJ({328g5cX)=0#!8b>uc{% zth?H!hgLx~f9e72#vt=M!Q0os@8Pz^KHQva+dFNqI_vHpOvC$Ji6ie~IHHPpHd<NH|gZ|HPr^BkPoTUpr~Lbd!>gj~`TXIrS3A6;P<4%|1Nd8=FUk+CX>}1o`v?8=w!%eMQ5-ZTiRkf)-;THYw%V zQXT%$Bf)YM={))07Az{K1a^eX{Uc*7Ld!`luN6J*a=W4?Kus>Yq)hWdcs@Lro=KQL zs#}&7Pp~O&h*?~YBdd&z?LAiD@F$3IxtSK8z3IXv2;K5IHF=m-$Z{h00h+h0wPLe{ zIF`P+2-pY*9tZx{`Ghj9+KFVVew8q@ERE@|?QU7R-ug6-A`#ZOr9%5qxBu){wi{mhjFc z>w9%ki_mGO>ic&lW%8-O>+&x>W_G%Kg5AUEXR;3HnL}76E z7)!Qac3pdlFUs{m9NAXPC(3od0%`O?Da!Tn^lY8{z^vy3tldM}*&*$-)C>A`+O74@ z2gIqA$4?c+0|0dI@hw5>Ee|j8z7j9_z9TPSUy7G(-;#H*Zr>wvZs2ZWBH^$85FsgV z)F~-%942X3c$(;k(m<|*;J~Dhq5lXCivBUw-vQ*F&{eXo0AD!kSV-_eDitJ#RGtQ{ zYDI8keLjUXy^{3|HI|IKw=qWlgSPJ^WbI6t>XhqQt5B68myP#2GM44UcWO805hq?Ua(^rlz|9jZY>#dq7@7P|rnv@e_N(G;Qf9{Y zPxK?5v)tKAO$&Ciy<|^;Ry&O@oK!a!G8e_<%_t*i3kIzqp0ebmC8qDN%JoGt?u@Hg zGnn8n)WtB+t80zl5nvvcYhKh9d>S?Cx`P4@vF{Y_ET9uoX9hA(ViL_$QDe)k5@}-$ zq+Qqw4Mf+H60Tob%Fojaq^^Ud?Hc0c?E1oyH@w{+WX?xSxIU&zU{=rPP3eDwJZ^@N zSbTisiALP+akZchbrLGdTkp`n6Vt=ZFX+mse!4z$K3qa>wmg=2h6fD+d_p7x)RXtlTT4oII zHq?1q4tZBNv`>DRGc2F5<0F-$^!4i zwU}q2!Cl-A347#D>C}62<4B($*vxiVJz|oenmhz0ds6dp(JrhSD|}iedt!5n(e(vAp=!`=EMTe% zPJzh)@|io{(HeGJspAXN4-Yk`G>uFj-AeS*N=;dq$3;?~FwMwP6V=k+X*DgC&8`*g z2A{HqbD%CtrU~FZp*czcKNYuhpG1#r3h~TV)ExY<@bDs_U?0mCz)F2LF_0plh^h6Q z&A%vkk^=(39o_zr@|8r0*@vFUXW|9KQXCxsqJ$7dv?2~l{}#Ff2DXnHI#f`1PGYr> zUhBAVj&aMvn z%eE;?@FihYMFsfZI>4q}36Z(h_S7KxO0&{V@@qNr9Y#uxhic`lRk=q_Q=??j%@PQS z1;Z9m6ok*kb#?d7fcCb@-<{S66PulTtkjF!5Wi7PWS1%hm@CT6=6iY|xIPkV2VjPu zicQp|QFeaU<=xQ_XMiOc1tMJg1LhBOjXnFdkX~bsuK?UThOOvU2iz~Y+R48Qu($qg zg!YR`*F-sefG*K-@1IOwWw18fG=?k@HHO4lqaZd+l|L%aH-}28$Cx@ks3qo-{(9zf`4`bAe&{Dr>{!;A6 zfNfkuF{Ia_&K^sJmRXa|&-q21J)#a>T_waBSB=i<*72jxb%4kkMSRU`pBw|z&XjI| z#3tyLbd!>Ib_Pk`?Dqh!P2;VCTk0+03RTzi%!yiL^{B4)vTRcl;h+b;%v`{9{5TDA zw%Aie=7$qV3zFI(hVt<_X{35Ej!S}p>HWMhXI2^ZQSo~n`l;flS0KS0A+ayu{?(Q< zjkIFzmvI9?XppSNMv{^7r>$-jV>oR`LV*@|zvn-sEL@!LBxP8Jz&Aa%Baaie2n z9R%jwn#;Z6R-=r*E_4dDS-i%ua5I?|kD(!b%Ku^Q9fLay({Iu4*tTuk>DadYi*4Js zla6htV>=z&wyl$yTlbv*otis$KHRGPZCCA2yVkp&=Us5Bu&%QEK{>nI&$HuhMxqeG zwPSzZ>g*bPjWBDoVU2KE0AXI_(JhM+EUV0!5&W_2&sTn9-G@7ZunKjKG|M2~u&;Xh zZi_rUS(Pr67}${li%HO^U(M{?i)dKbC*}Kh_|^|H#U= zF_w2Qw=pu|U}gSSa@?c_t*$(b%GZB6#ixPRI+9F~PZ*X@w~fqrc{_`BgZPWsB4FGh z7rF^DbVqSPKXQeH* zbNSi(#M1ug{ixgY(-Ckuarvt7mgD^+PF4|Sz%WRNBnwuRP53x`5`+uMJfNQ>0(K?} zt<-2VeX^p2KCB>Guj}?$OUcFO7xwh!%V-y~)cgF+#pw(?eYZ(rG(!B$iz_L;IL19C2bhd%| zTVXaQ6CoUIy!;rEJ3jm-jc3Bhu#zbhh^|s(6ap&!S5qd8HhD1OeX*Fs@LqIh9F;U= zt%m#-zz(3XISRHhs;VUB4mg1Rv{kv`jOBB#-~Kc!Pdr+wo~Ou<2XsR1R@OYB_f-=v z_fNp5HP>5<?y$Oen z7rZ}YvrqW0^S9b3a>Wh|v&=E6jArU*?TN@W@}^%!?5?`G>%TIyY?~u!2cS5 zEQUi?8gFhlN-sB+JADd3PY+3kAoYmVqU zQ$_9lm*^w7QxR5$r{Ufd-qB|o%Z9s}TiL-nqH&k6Ev5u!g0mY8l{98J&yS-+*OP}0 zkBpRb&RsrEi<0N-V)PJsPm0MQK_-muB7GV7YMitmm%V@#K$&$KbRI2ITl#cSu01h5}8v zg`0&;GDodFGOXrIGJCB=<%!L}$6dm#LdVz=wfOjja&i%~oQJinv5s8x;YP_Arr zWnitNc}7#qbN0koxX`bWPDf!r^5k|89nj|btsSL=z+o}0V#iUvSNl!JW|r05xJ3df z(h5~`;tb9kOr6(r={bA4zY^A_;kZ-IF8Mi30!n+x*2+mUeTA=NL>B0Vn0GNP$?~f zd@i3E40iWAf$I6eguF#jm6>@29o37Mo;d`z2$GCJRww-Z%1x$ie{d}1PsM>z-t@Z|fN6ClAFj81D@#{_8Kwday;42y2v9-UE-8vBYwh=T-zdaD~SA&o- z`C!7UrS}3&73gYMJnY6woEagnU81-gw0jzf#t1RV3Xop?fLh)l(9-fXYI`BN1kv`p z?Hh#W&6~u&k!5PC)IspWCX~6fH^H`IWUJEWL%UpWzveEcMkHNxRs{@wD;w$Z16D`cau?-0oY@)R z1^6#8T(7}94jKX6Cy1EekGFO>A?#r+7<-(vy5H6*ABlfw5lscZkdti%zLLgT^1n=z zZH2xX$6^J)l#-`UpCiYv0zNU5>GOS64~BQPOsV+sKBiTCfL@Q3eTZIBV--LZNGq67COBk4)jXAAlC7e^L$TiNI6u>TFOYS&p1U}ub{ zE}*8P){YJHq-F<7-TG*&?B}W*(|-nslIsi0z7O@9XL5s;X`m#Ag;i(+qNM(8#2Jic z(?`q4dTt*T2})43C~YyxVg{CJDDCayXAdiZ){|5|8pc?p2B|N>3KFmN!?HY@YB|MX zj+%pNVG)tIa5W0*GQonGQeCC#-O+!;JcU3j1dcxDukIx zlqHPO5C$nkgsi@+Q=|~6FdU3TI)AkNmi0GcSYw)ep^6oDF0zaYY}}4#%bvQ!H5gFi zp20e>xxde)0FgoOR9G(PC#`1?j;1q35FZ>QE5j23azU`3^%r`Zf`$vUb zGOOLos#2JlSlX6g+11CYcVKdWfvKo5T%=+QO0Hl6ocalyx;aq9 zeh0VF$CPFT$T83=f#C*OMn$sR##H|P2t{+Ksave+@-Q>Y4b0mLF2eQ`O}s{10Jw7a zbyW+P$!?o8P^!c}6L_06QmOMn2`G4Pn{c|t+ubi(+ zWz7Lw1c8^hs!>;iLK}w&ajnfRoMw1sxh;KJQl2IhVn3)p%KaL8Z$TZa9)00*Y^0-~ zITuJ}Tb}3orx%LIw0Me&1WlAc>Oy+X#axMJiI(r@!yEn&G==G&z7H7HS_=aplP0g< zDewyi$j)VHZpMbu225~m_!ppgz` zR+7n{@=FAkqYCYEY;lz;84A^k==Z>3&?6sgpZQvJE?dq;aU{E&6f0CtSX(CbD-ntN z+uH93=c-$%`)Iq)5)Ljrw(VRqLlvvQMTu?3!*({iXVmVDW}w`0C{#kGd1XE$NEFZ6 z4QB{FRE@+HRLfC{$(zzERho7?KTo}cPpSSWY`YlMp|%DjxDNDmQEKCje<*kYI*-C+ zX(Tcr4Kq0NsJQP{ozqv*r!0?=xfeb+sR^YknbjTQXg1olarBBFbVJ`{RF*`g;XHMo zG@QMI12WyLc9oFjFaQh8N$bg5;pFuTKE)P_sCny4b!E!Q`HGeNj^v?^Cp)))tAhyn z)yr+bwrrp-ZS2O{#hgv8Ux)5_^~EnsL81dKeua#0$R;Lr(%qt4zQr zF7PS#+dWm1d?hU-3AL5V_F*O#+$BaB;wi!=_Sw#!Sbj%tBE}Y3zc?uKxMX&B#x zglnSZ?%dHZr75RKX-woL4a(2}?6F-jF0;z+Fl=HT){fijqDt#TbyVe?5XCx;pTtCI zSD^wzhIL$*O<>ew-zpB<^F=POn%i@(_u@0hO2QP9_fZg6;}9=6FA%@x%+|L%n|`ms zQ)lFJ?sj=)pahB$y5>Zti4KIF^?z~Xn;*6aYZt7&CKhQ{Mw>?{#dz;QeaxueUkMSb zW)ljU_c=Aj{fbfL7sRC|(96ip8O45a@*&D~|EZes2^+2#|DOJc#38nXli<`T=Z1heBZ?Y0r6Q;@Z|Vs)1pbY9a>ID-2O&r?a}0pVbL$_`;ZwY>S1aA0pC8`|2l}2E zdcuq$+9(C;5xb1Hh$JF!BtQ>XDGFh~F?uCY6uc;dazy1Lwy8txRN0-$hih|av|NN1 zG&Q|*E1WA<8Yh68$~fN~Pa~$HH>9r~Xsa<5i_Nad*t4ZAG6`F)E*wJ6Og8qiPQjBN>rF5j$$ zMra_uZf!K%A0xZlT+yjOzLLY3!uArawF=)N#%E-!)bOTFs=l$dxJh$;st`=J3d-d1 z%pWm+tKl4m^p6`;S?BBRdyPH4jczR(vYmJSzoRTSQSrOBFU z1`LM1=m^F!6$0ITX{v7B#N8QgwQu`yt(=B{DgITh;CiTO+SvCY=uCKL>g$EarVS8S z(;idsz?H-gsECY2hmS>H;M3R`e?K`R)2!3}Go|Ka?>ji%o(9M@55>wRZ!6yBQbkRw zL+fo1fVGMkUP82@Ed4ze*Ir8u6I+vE5HQIORU8LU?|5GruXP$UWAfVSwnMU4hMlx3 zMIBz89Qs`}&#;j~t!v`Q?=Ji4Y>{a!2e~u@>m1$gzP1=sx*f5oy|J839P-jtom2{N zJD3!`z^sXkG|1~Vlt6(tE#2hSi?;!G@aZqa=@hBX1=D}?w*CUw75oZV+GN`-fDdI1 z)5B0+-UAD{MvKlN4*StWtaM_}_JJhS{g=Sc-a}LZM7@u}J952nvyePY%S{U?njmBi zgv{fLKz0^cM-fu*G=|)R zM>}&+cqyv(IB%<@?de7UyHl7$5TKlo?DdQhpLkugv@Isr8|%``|GN#|`<8AeOnw9P zS|HYo6BnUii($e}8r1hSxs4Gs&pFK14k&ZhY693SQw8FYm}GQBcuBKQPijVUc<#4b za&y_c@E317DvjM8{65M+c^Du5K7fjS`$SX z{)(h$5)DEL!-kN_YBYysYxQUOIY9~+BG`tewEBxa-r683o>XkaDXr_i4!;=wLW=G} zI`qgV!Y4s?y4u(PVu+E1IU9|6QFrRVbt-3}`s@9zh5yI8Kb9a_6x~F~On4gu-(W|O zIyTyMdeGqZy&i(EbzJR$X(}m<{R}EyJ(U4%6r9(T*dnPhsTBhVIg3z335KenRI!RQ zl?iEg1=$^-%oxjaG{NvHhUADvg}(4~x~3w6&KTg_REXtL?wi=lZ-k~C5<@yEuSQjr zWnoRhnJvndI?<7DOO-P8cKLg2bKw!A_>7y-QX;Uuxw#=xdlAY+iP>t$xwm#9zi7EQ z*%0FVnlQwyz;5Iyrz!<=R|aGVfm7C3zFIV{4dZoSNYoCw4i8HqxazAcb9!R z$6KRdJxg6>(s+6DDZiXEz}$EKFr>tOxUox(W>w!RGQl&B@j@h|I^X6H#d}imiM64g zJPvbc3YVZN%E-Rh@Vkn6NxzmPzyO0&3=E@qYFufI%*Sr$n|2AT#+wv zlah?^)|b0$m0DDOyLz2<(dOr?fuWJt`@`Ixag%_-lH=Fu4)Rn6Ds|12`TMW43P(j) zUWLaK5ge+vIi~iT;3yd{${lLV*jiEpt)Zpoki4%Z;`kfduD#V*6N-`15yy{oc6s-# zns2+lD<&Deljz*Xen2?DZT&fC@Gf&6wIFR`H3fi@+36m9?3d|iBhX@Kngn>jL#d!v zsAJ`Alb&oep#*p0hd!dp&_&=4@q`u9_&q+Tz*5mhZjqBax-_j?fX*vYYatKog8W4Z zCRh|mx>3R(y$#lxJI(GP-Od6!6uPd98PS zxiKK~Dl$jv^9mxs8c1y>5ac1Z6B?US1$-l$;ue#lSGL#x=N^{~Q6Gn}&@Ne1K@5TS z7&S!G9@g79s%5j^Iibs5n(97a@?8 zJ^odvaNG`pBD)|x;^Pf~?K4u$UE(=2BnsS^mR6iNhBj51Y%I2P7-VZkdp`55gfrB_ zPt%@6n`*r16jeEB!383{HpCnFvxm8{dyFyE`a zOd--N+ECh?g`Vl}QOX$Jx0oB3SZ(lX1+5?Vs-Z zh!e=LNAchw9`IEc+~jScpe;13_2b@q%i_xFF6SjT@;s)W|4b8G^uxO<{07DJ|EOl< z|F1z&%-qWA-vgrBh9j~H%GU;0t1)+HZ>ASu+ zRDlO`7eW;Kt~y74kV{4DUQw`^oghX{3qPytByeEQglEjFZWI^V*a3iLo&YO`WyV&3 zlC+SCE{xKi8bK%K9Mt@Sl0L7@%iH?LM_0wkfH|*%lhqd1g`PotPgK){gRSadVMURy zECZ6XOldmYoVe&1I-=~xrAVoMv5}}BPhdogL{3I(+?a@+bt492T+3onnWi7d*v`}q zy}wPgOui$(2n{1ZhGcNNMyyMrG#{Ur<2+B;&@RnO&&;pQ;wYb8NK1SC5VgWs@mjwi zy&-f~NLos@X$aE;cw=1VU`i1t?=VDs9H>G%FQ`W-mQlEL!`LeN(B zsi@+NZMua9v!uw+)SXlR!~%^v-k4PB#OErGBu65|5GnAH9E0cIZslj!l6MBwLK@KY z6bbO)JIS$|h#z@p#gcs|Uw7ph^al;6%A@s38;gtmc>_(BZzaQkCIN*jw9nkocy^nl zi6pMFoBk@JP^F5eF2&+WwOuOwDS^8kKE4M(EY5vz2Kj6K4RBvVYRju%c}9^rI@{W#Q-8=swij{HVi+~@U8_86T}fV#EU(Jqge6KQVr0Ikxv zX=Z0|)9enL`Buaf_#?&iX(vT(g~;ga{Rm9BQE{2o-$su_QW?2OwEkcH%7#umr6$a& z9W}+z?&}$h$tZe4?}iAG7eDPo``;%v8Bdaa-yhv750p^6;O2XZcNbI704!m7zrdTveS5(={n$_L zjw(O0L0*-AyFgDVS>hsT-`ku)=IG~{n!V&;(RGN((Wn1dINx+i`)U@@eB{1pQD|KA5+{>ji zGNVJ59c|}V_+&pQI)bMFgLj~YEu8to9%@tOSz9{`&StmtI17=pk!RRai-YY9D{i&u zdVKg8szpkBj!vS&CE!L3>FsfPtG~L-BHy5F8kMU#e2;GJ?JSdnQn)%^kVsp_wY=Cd zG0?iy4V=BY!7jAfzv@nV&;Ezl31>9ig#47_KtHYaptbbO8{4kB0FcRg?~-~C`@O^` z@Z~N#4OGrscs3tZT}7)XsR)k>##IkA%&gU4*(h=hBxj_&nWeIFZ9_BMTcb#`{neS+BvCY&%o#PshES>hTU3bJ%i!q z?(IEYH_RDxXl}`LsB@%g0 zdt~NXLH9om4XfU62qhBYic3A#fn2-QX?;xbw~58F;+dyLFirPqqHCGcxbcc$Y{F>- z7VCTV&Jh1{n-_K5xUPQywaAThL0#(W$cei(e{7LmK68Jf|C35D{dybyRz+qZ{ZA_W zuL%bd|MjWy&+VU}fuk9~*1^f_-<}_n8jxNn2dH1&D;riWuJwfeMNt7jKxEj0K^BeJ zzX>2sSP@7mlecF^FG(=hC#oA7{LQ4`>sl68RYA*}=h0$UEh>7=q^!$$k7eLJ*DRXQ zS2eY$c?+*HSF&jk60H0_v3%YpGp{_KJh$F9+0Q)>;(33dDK_G?fYf2ML>Oox$SmXa z!FdhDt^vI}ctV)83jM-I?H?XEll|$f{mT{V7@5!u>Cb>&YT6$yn5VEET}CfSn5Xca zIm73uI6Gei`0WM(FF1Ix8w9YybsI(=8u<{A`!EbV*xfsz8c02afXA?%NP(>A;eqwk zfM=%1*BPy5E4Xuhfe%!HyH@qDa*QsrkebLHY{O;p5Zj0yEgvtf+SeGjmuieI^ns^3 zyiIl@^v=hLg7ov_Yqf(H7mSaf;D7Aui+d(K%#-gAtAKP0Ib6 zCB+U{c~*5c$BT-BGBTE{=jQUv7WrzH;)QRo7z z(wZyf*sB@ZdZ_@HQXNVeacT1Td9H=|K~JAq%ZF19!ST8k<`yua(jr$^b{e^I@0Gg+ zD_hsqMi1*z`~F!E=>^G5E5Dj=YZM@+h;9wgsHGWVqLj6LHFu%rV~J*a3OJ%oFiB2z zHJK~RDsnDV$|%Evq~-5cl`2cw)Z^iQu)_vt0_CRXKm?<^JT}uDE1$;gZwJz?HE|Ri zSLdRCy8$8mTm6Jlp3JO~_gY7E%3$A*g)0YUwe1V!F4>)e(Q7#y0x-Rxn0~oI7VK|T zp&BWhmu9wZu06wuoFsWK2lUsaS1!yaO_q`tJ(!0qIMv(5MrZ8m9FR?qW_imuu)2%MP9E z6j<-FoGvP*4EgKsZL6SnqhANwkX4draTlMZW)^eRmbzPe%|%~UC4V12Qtkb)Wy&jvwztv%*eX%r@<$QvaIi{;f%3+2F*na z5`x?()vDDnFo4o^cqC3W=UppjBf_6I%5 z_nv(FmM33)yYa;I?ZG#B zhXnt=FE_k!$Mi+(*BiKw0%rV#4p`H>$;bCiym9T=ALcjihzj(1R~qWRw#EGFrDlS= z*(4*9AcJ=|xm8HdeP>GEBTWZ7PNw|!#G?>t6hlG1l_?fWD3c2FQ7f^^q?kjA7-vY< zB$#7SGST%PFl7stjIm?`Mx3y+Wz|(JehZsY^4J1qDR(>{=_ixS(I!()U^4bf+L$H_ zm`%#_IGGlpFsWsK-HC_E@D#QF#Yt4BW=V&Y{ewU4QaE?vZ9#R=oSWs--xBRcRrFw| zX8pJ?9DqVdiy0aPplcLO$y@M9SwiX*x!;?yZ)$fJ;W`RiNYJbgd+)eOOXJ&8Mpm;x z(@TpG&m20BiS4o(+}QLO1u28JwsVgKR5{V{HCT$4sRdU|n->^e8}!3)vnFbNGd){% z7p)~xTEf*132!RBG?wvbFjqqh^xWlQ+9utg`Uf()Esv0#h+zn(4!K8d*@j#qk7>Zo12k&2yFA zwA2PFb`)T0kG2MrRHvAu+6;MD@@kVk(~F=5bLCSpsYJxp*AS#wtxHe!MGMx%nO2u9 z=8Q%Iuwc3=LSz}yQDLH=3(}kGvp9NMt0EJ(~IB=pZAMry6&TPS`!l;$?v7cMpFCsMw6jrEssJ@y@2l*og(xXa1xEC zW|h{})H|E$v~L1+IC+yBx1J+dA48exc!{$aT%s-{n|~J%oGMRZq-PbuVh>s9ut$&$ zqZT41XQq#ntW>Ia$k}G5&rcAM(x0j{tO^POP*ljVo*BD{qKX!X`eev2_I8D<4mx;P z@h##jYnbOUS3TSKI~+_t`@chn2Ra&a2#&pG?b$}nOfM7~v$KmNZZkC(U$)zRlQ=FS zMyH6A3L8Y_-|#~?A4yQ`4$HY2Pm>`rm68o~j*Lcn4s&?bTj+&cT$-zICO55}Al8h0 zRm6~$qAz&c2ywj>D>>a^jc97(=hl~p$rEK`)_!U2m(Jqi8&J{lDD}EmYFLL0Pq7Tz zo*BCb(wvN&4q0T_ z|J%%n(jx*RH@VlcZJ4^IdAK-LE8hfM(}JpJTJZsm|NkM2Nyw^_>Uv84ExK1OZ35k2nW2E>v2(qr=g!3nMm$hE@fBt_Du3>XX*!*Jnq{ zUYCAxE%j&nfeq|VY17z<0%_GBEI6JhPkaS|Y=wr1=8t3_LOE%u7>OAxSW5`p1y`dU z6gDWC4L_YICbH3QXCSNU}0E=ttIA#$AQTpx%SNzp>&f8{EkZV z?$e)mod`)h-zbKh?ekAai)$qeHzeD>8hc=$K<;Z4WS;0@%ulkM-su}|qW7HQUC4|W zU>7#4gO073;MM?Qd_%bDy=ZyPF|bQPbfJR@Yi=YM(6l4&c;gNN$M9c!Z3yKQK{h$m z$TKwiC_>+h8_vPFsW@XHY|Pu`zschEU_s`1uW6CfQ-wBD%3@tRW9-^5U_kC=AxY*Ry&Jl+gk-989&hwy^o?q^{3P(md` zUNdIdyDDBCEZzvrr-KfJMN!=mppACS<^i~L*U?FJ3Xxzp7CT@!*yE6Y;Aq1{@dsDV ztoaTEErj*6tCJ$d&xbhA=S3fVl_B{CoFtD4Cw3kjTa>bqt||CpFWT?iPFdIF6;Qy% z`k{vJ1AOZ2bSd*3eD+jC$C~Zq%PRSa+PTk3qq*av5sCtL{bk;r{E3(u5DIiU65tM-XMNII~ zZl0NJj{`d>KSx17_0j@;@7OqlR1<1bc#cbcR1;!ql>#j(VX!NbUKUF%3nkugq^5op zZl^jy>Fys1WXR%W2qd#44zDzZ9m+=?ey8FUSeE8A|J86J&lY-;C*F`dnz7N{kcu?N z?@aL#r#?oXmj*8lhMSQzha4>8(4o+gteSPPNWARXj!M&OG_CUYXGfTfVKSUO=2 zQ6mU9qhAH1M8qCIyWde|wx~5_JYh_CbIRm+vV#j#iv(3GP4CB&l;wpY`arZIc4}^m zU2nUVMWa+UO@wrwG}FCmhfES($mSFeDfa4^8{WvQV`~f{eX*q69`3|+=v~o|d*n9;QroH>%}kdnR&7hzCC$JpXDb$MY*^(Z zTB$!NMLOe~N1A}v6rFQTmrl!-H=S{qC8qu+n#mN-$Mx-1$3V+zSelj%8>5bO;Egc& z?P4#;FM=yus?pZlKsyK?O*j7V*mAo_CH<9|8_n*P_wjC zR>S?;@ZQKY@rNd*gpL=bs$C%k>Eo8S$^c0~(v|p~QaZVDF5_U|fNgVG90b)EEVu=K z7RXoi{3Dyo$g~kb6Vu6w>s8@{V(+>4BnltbdES10i}UGn5)6niue2bJ_w6h9&bNDN zCHHG@m-I))H7@K6ML7e;pujR!O41G;j7S>?vwTl&MCjlRVI4D(3mkNxm~vz3vlmK( zoiGDV_D|U1f!oq=SKzKa4mvpbz-`bnH|1|7AP>b~a*)U7bv(o=rorz=$~-l@prFhy zEUwMx79M7%{V@Pg$2B;Neo^bik%t8rj^^aEwL*P>5g+?L2B&FmJZ%~jicgAb)4@fT zrqSQy6Lw3_TVUYAGF*nN&xNLo;`j}V^c88xMH~i4IFTf0b#Kmo%4K6%XJ;1&>iU&2 zjVUzHaik@5(m^YW-R@KGeX9vm3VoN%WM)@1uy50zd0|5_1NWAZ@e^h2;SA3j0M-0= zku`Oa6Bel6!~B@) zi9vRP1X?A+?C;+x&nQLe?~S)c6s74zwyonT)lgMkm`@7o875msnIT3IjjMq#mEx88 zG?M4J2{G8{i6k2f^XohE3PN;q#;c396T{XfR($FNwD2w%fq})HWghLM^qMs+d_+l| z?r#SD0A}hp%!X~%ud$Ur5%%-T!GF%9MvNI0CJ%GW6@f@I zCYvYO29gJo+OJ(^Wc}~K7&FXDO*AHotzA*TPzs9&urN=y2ZsO2+N@oIQ`d%jd(X*Vjz=Sgq~E z2~0h2W_*M6sPwk6C`){-nHaC$OU4#WqAL}4xAaN`czMuvDMezl@9!VNGjck z9cVYs5IKDb7`=g1WiQTrsj!1Hj;dX3Mla;82m@rc;aW83fNd)nOAsf~Ur%9yjsc%pzq)Co*8H=fuxwri zUFYCrGZaA|68WyGKQL!By|Bru$2ILLtuEjKV4JO@u21k}&?~J(4WSlg${Ukw{xEj_ znFXJ~W3*}1T{}kXB;B;Bs#3ysjI^mttbx=8d6UWf?pDqBAbQ9wL9g7MQ_*J0DIW~S zUeNqy9*&|Ad!b{|dmIzCQ&9^QFy@O&k=59VJ=-gVGqr zny5caC99U14iZ6QVZy8{USS<4v#sp}5y#xORnkRZA9?J);#J5o%lO+MK7`dgQ1kis zufSUGuswSD50F~FYeR}wEkiGxNN)cvDbg+&lOW_$vMi7!&@jTW#DdXzZPK_j{0#i` znrtzG^w|Yy2wl-*a0v45SUU#Hzek;s;-S9;%M?nX=!6o@ILfZl16v|W;tN07tHMep zc&pV=8EG+RABghBD43~gUCjg#D61vRWrzULckQop{6n0BsCmkaV`s6R4|Nj;AX+GVKMq_IA&d!E?uUd(kpAhRxr0zF_WM6O~%1?dX^()s_51986 z@*eiW_@9RSva!U&ark&R4Z+?q9^j6OlfTL+c%SJPl=yJ<7!p#~;eH^->sy`W5k{5v zb%;!Wa7TNEa5vQb3p!pCS(`C0h%_%rvsle0gZvJ?QBErO(>KY<}@W$j@sc4Xb}`W6|0-X%E(eBMF7?5!V1+S4&Bdq;Tjx3 zyahJ6j0ERM!^5XWg&y1!^6F*kGkph=+_;1Mu;lvmwMsZnagE3!D~lSF9rd%dOrOtn{0{2epb;3!LM+sb zLNNRL*IJGAj;g4&hwawEJmbamOp7Es0_OY2Q!=vSaZTWSVfsNa3(S}ibm{l_sIu5a zTov6`lGAiHbOEtJ=!KPQUx3(}x(u@zrkj!fYGg$J!{ZHkn z-KpOkggm||_K>-Q8@F}>?#3#k?rp+439n3K3bYv*^w@)fOMYfNII%+odsR@mVSmfV zT3ZkAl?qCem_%+kB_m}O79?Qt)KoZ zzP;1NXmE+PtTjo~^$DyFA8AWk>@_(?I0s;a(f6!Le<$%;0~~bSHYz7LpW~J`RTXR_ zbSv2fJ&om{M~oM~bKRvVDDwDjLzcIG>c(&Ac0MR(R4m*!X?CfOFIj|FsGVwFomo6M z)875#(deQZulWn?f$Vwis2kk;*Jp;YuF$HQ!*)PK%~iF&P}OK@-eRJGe0y~I)(~Z@ z&G(;|wR6nPzxBWMbGF$3iPVYw*QD;BYj;^&2V+Nb6C+Dy2Ll_&?*+W||6TB2rRMJS zkBDI#fO|s+LIML}ECR@ipg0DSq@RI;@vmBm9*`LXWnCuvL@_dEd#3(;=L&OcbIU5{ zGUu}00F}l{NWusppsEErmpK~?>qw~8&($x>?l*vVSb%i?cTmYy+flaXrAC+IWwzR< z>o$QO)cbh9K?S(T^LN>Vr+&ZdzFla*Rr}6BHl7!}E9G++xXt>-AaCnZ*P&{O1!@O=lavpWKa+J??Ja^`8ZlX{; zRoh&k+$cO}y&ybCy>9QqaNM2C!5g~gy}F#|iF$tyYSrN0NNU6s-wys#hXO;r@?0BL z1RR0lNTJbdbSV>*cm#GSJdq;<2J{MCC(!MdGIvUI#D`#i8eK1emYE30hI~-xLlRpJ zd%TGQa2vP2&?FWB?0 zt{_FWDD@KMoJhL_-Gjhaa<#OFVY1%0`r7kU+m^vB4zev^dK8Mv4NOkX$1Q00<}r%v zKu?sWtCQ%{YcN{FmXNXtbB%p8jXshQcWK&2#3icXS}qb>-nUXNnHMv>bO-!Fssfbs z>`q_cEr^uS;jIZfKaw$bNdA8B(4}LJ7BAi6EGpnbTQM5|1xmkw!FpdrJYzuy&}6Jq z!%9F+Sn;%kq_l3*us_o?_K(l9v~Zf;BZ)38tXMRYL?Pgon&Gr#(J#!;=gK!~A@0n)`;G~U*Lm{TWY#2$ z5&z`;oZZq15Ht+iG-e7}_kZUi}{p|x))jk4cJPH(T&2K9_XmYAPyk8BVQu1`ZE7Wtd1nNOr)D8_30AOHdII2Ie|L$!UqFs1 zCrT@?P0GNh^2aptxLmb!PCqg%1%^JOUpC;+LnG@^OO2ww0i+`yPH}XH6b{d?;>AU6 z!nu+97-l0j;xWO7P#Uj4Xe?s0=m-_@o;(kA#vLo_fU!%q%PbRKp_KfHA2w<;Va`B$ zW2NHdH5f^NvTaaQ@EaoAbVAgah*UfAUISFIYbI#^0t^kZN=D=K@x)jvj^bSopYm-} zD&5{`)Q<99)_1`{dV6twmqUO40$}mU?gR_ps%>Y~?p|9JWrLWAwzQI6*XPa%$qB`4 za8%oE8Bky48}fIJ?fmH#vxBxfm3L5I)NA;H`RWGV?QjUT{)pAepg%I!a!V4f~Y zG$*8Jw?jA}d0L%2CB(!(*yUorA=zA&5cQ&$GQb3*uG+0Q6wG(`bSejz-QuBL^3f z;h=sTAmBXvcvKhu6!oEKDKQrUs@C{cum`-guKkF$vEDzY{Dd6OL+bJACO5%d0}pE- zdgh>Q(LC~?y7cRTr*3tl;*4c~%_Idr$|sK>d0_C#+_dd?^D1j>9lW}|4VSPCk|i%X zR)6zN>^-??OwsSFhbrJ)1>!!?pt{5r@ z6xO@F;?WE;t*Qo*+f$~@RYNucKn_k=#AJESN$a|SHH37&>4YU}etuY1Gzp=b9r^W!?jf(%1&@6#%>OjiDZGs1XdAxMh*jl6IF`p#NRjsB`XDvQn z+2nGaH>Gg;Mt|X8Z$m@H6_Hhm^_IU|9~f(3uEF>dy%wFk9EVRVc}}vW_%p#R(svt|}ipkzGIiUs_Vq3%32qwtSX98tAAWpa3DW7i> zm$98JqBj2Qb8K34d;C(AJk<*uWQgFFb~#~k#eO$Cpc zJ&FXFHqHK+-9VX~o#nfo0pfqH3B_+QyJ~Ti3gwt%0moc8V(uaT5@ylW-sHu zCFnbsq)+m?oz9XOo_oi5KVvui9`-9ko`54$Kl-D-VNZd3JLBl?D4&x7Jy`?1J8eh{ zy3#(pjD$4mv4F&{CKZ#nde$cFxn_gnDvKc7Anha@p}OMN`nKD#I`lc~V^NJIh@4kd zHMU_jR_7lIuC-wV%27xwJcb}+!f;fB;xs7kt;+iaqEUj`6ax!_{QyR=mT)2~R3rNq zilGlfoE#F{(6lgKLnOGcQ4Xr&ZEHqUa*^=bNb^2g$zZbL2qi?eVxl>Co zul!I>>2=s`@~KvCY=&sfRmj~A#-v(`JFuC7Tr#cXRc~kwSvjbb22UN8CzL9=r^}lR z-M6YLD3pue)=^E~;agZss=HjqHY}KwmAAbFl`#;UTVT42f_yLFY z{}1>7-$G5L?}m|o81EeHY_0xJy~u^SmJ_xZ=I2m?D*AY{l@#4tE2o6{;A%_(nYjdY z=0KShxp`LMz>q$7lg2o;XJDaw%weg{`2n?mIuHe!jxM z--m;5zF|C@y0A9m=oymV+j%4;GQUlKO~0qw0=h6?TQHxC7qgD?@`75ss4k zzk;6C;PI_CliEgi6iK7NCLGQErR2csF!F5UExV>NZLbdlX3;fWZcy;;m4d z`THMI-R>%H{Y%td*Xdhd+X(2yYO$y9rjiMC^~1D8jLP-Vs1GO`IQUigY`K-*Fxx|D zJlTp;@6WU1$25ZjRA@?|+L>JmoQMA21s2EWVvb;g798I*1cgqnKp5S4)+l_E2r|z+vIcvBNJ8md5 z{}*HD7~DzMwfkh^WMX?_+qP}ncJhyH+qP}nn%K6T3C}$Dd+=7BbDnytc6F`p-PIrZ z%U*l0YyB>E`yN4~aeGC&1xGWFXf}#O*qHi%fMszE&Qp}V;u)D2nY~JUwc+2P@G2s(u){2eaWN+}QntiV zT-1rDunQ##>gi@F*WlDC$_@Y7YVAL=u|{{3QzZJf^OUKW4a(hW@A}H6tz}ByuW~5Z zXMgihTP@y>cYZrYAJRFI!7E_H?wJUWH{gWSFq%88y~w^$Jl%GB>%tQu>j(faM5Nv_ z3XRH`;SEy(SR#Y~91$yk2N~_?eIMd>{~|bIOt>AwNwGT`FRqB2-OjG|i9q?Oo4vn$ z2q3dN7e^n63YRTt(?os+S_{;?R7hp8tDt(PCj8A3)M z(_J*(o*wrFe1|?DaXIKSktGFj`^#jiIP}*2ez-UgpsvgmE+!5QNg(6PsK*;9WE2z?9UFth#3UdhdYpvBa(AuA%WD@Frv3ej zt}<#wx-B-iN?C{POAD+hjKuTzn?@m|a`Hlk0{B0ac3t&aodgUCZY6nyddDpp1O zt;QhIkaJQAsx5z#p&?cY2&l+iq>L@yGA-DV`G%l2coh>R7yObzX4Nw^Y`K}RviKQ2 z0>byF0{rApa(C;ByHwlLu8<-8JNWxW(L>np3%kAA3ci@ml)R33L(3|z66Hi?p=O56 zr8KPbnBd@U54a&`6OlBu=62FX)p@-cYT7RHN!cQjdCU)7FC*S&6Tnn$3tTMN;_Gc% z!C!IW-nFyQ64vpuhi$Z@6^MpgQKnBoZ<#;)y4v!9z?Md^!Qd1{$7`4;WDWX^~?Y_h|$tx}ZbnlSJ z2dvzI5%(a9wxJCmg~#t?l|tLpoqLvA+W`IUhbJ~&1K%#mGeLJT?*P>$r*5^?sFjO_ z$LL(Wv1fgvS9hp^VIqdRSK=$RMAS3G@CT9v%^^>yLV_m62swiel0(Fzlvk>7!2T8K zGPW3z$df@p5oyG`)(XDJ%ZCD7WKJ)>i@Hp z{4c35jtT0wFVnbeL;7WjM2o9rJ}@+KW=b&)jdNm32ywB0Q9o%lGnhdGmqf`{KMmL{UY|d-r^#w4NY6F5wNFH8Snt9w+?@ik_4=ccW~lpR+SZ!A;HrGH zPAa?pV5K_2=>2io-kK`^o3yAxX>GD2?KmH>ZqA5Z?@qS@9&Dg?_PpFA+am4U*zmhT z*HY z+im4NSNexxUBEi0h2ULO8YjV6>}F|Aa@Cyne@tQd8)N9A{Pu-HC=F9u{ zFiXOKC@fuSVW{U@#oOyhA%9kCOv=w;z#~_-s>E7UD$d(ZpDK3}VeK&BDH2(!2%UUR z>HDvhBDaiuMv__hV}usJJc42kSTe7n$%#w>rq)|YOf9=ZB;Sxe2Jm=?f(T4rD3+O82=?G(2d81JCCu@p%j)U*;+{*6JD}+2 z8sHKSV;fzYOGK^r5NRrgr#dpY4_Su>WHRz!w2t$LjIhV(Je9csRu8L51LkEEwv1Cc zx#+1wpXxBRMPuO>fu>~cu)ZzCT1&(dMmof8cFC;#;rU{*X&L#!YHJr0VlRysTTobY zLM3RrVs|&roK-SmqnH|~Yy%QHFgC{Q2H$=}N&L!0bNU$Pa{(nwcfc^-nUdp{aS)xR z7@P9N1Y8I6H7T%NvV5Hm^{%#(&4m62KHD*Z?nz_Pvr1F z9@rT#5HxzoY=4%4L!=fd3t7Pi^cX|W5IJy6GbEh0uul1*Qdpm&tZ2o)jbn0UDx#fO zby6P)N98P0O*UFLwA6u#zt#jnkX-7w@!TBhM~-1Lvn0ZOSFL|OW%ut61+JP-8dTP= zO!{1-x`}a{1T~>@_SRO6w1>qUxqt*`Hyi7kMn{pn;@ROP+Z75Fd=b zh6m+NtOko2fBcM{c;)aRI7kIV<(m#W=7{e8AR@y>g}AQtBq&!G9#~ zHBsm-I%PpeZ5+5j*^L2^?ZyGv-wAhiT|@_buXH9o5+2a0Z?uE=Ua?uJ%s9pIVPcCv zJ6?>tVz(HNh)Ed)ObMytGzg3sogBhol~}=r?C)zNpsaeQG+R2LR#{A?8kq2I!Ybm! zlwRm@7!>zggb6k2P@P2WB0Lw$M5M^-#E?yH)Dy~Bc_f_jdlWv9`&UcgSVxqeTQt>S zVh#Bm2q{P8SQqC+r;8}PQLJ=k8mw=ydWR{_Q)Cmkw0y@Ul52+ZM|e9%&kV0J#8a}B zMTTMK!XryE>(rR8E?jk=*#7|VpX7hddIs3qtyjv(5HmY2iyU0B68_SPT($mioyrW) zC$Au7JU=#j&G?`crla$2K(yf4s>C-g?_P=dlgA~l(w?@_ZPM&_w zN|7eR;zB!T5B^ z2Fml3J3>`hC7laN(~Cc=WAA~J%AthLDs^|;7ETy@eXpAk2NMT9pfX3BQsdQE=xpy= zVgfFyN4dtYe-rm4qLGKnOSh!+&l>S`kD$LoHJ4ZEp3%3PSGA0d?$5A%QYhw#8A zYj8Ns1aoQNlXTrV{(4fGE4t>9W6Kj^YZ+cCCy7#Mg;paQpH5$i77k_EnoCTdmSQ!n_Y^AL+M zPF602`rXMkH<#T+x#;b~!mh5;s)etTDZjQcEYEuG;!JK~sZar`;v<+3FdTa$8rDtq znB)!7Y%`H`?_t;w%1<)5O=uwIP_)~(r|uI3`pHy}K{odwd=B-9a^?mV@K{wCFGDT@ z#Y6Scd}O^`72srPiZT;tieeXR&juS=R=O+`)#sXYAV5uGNkTjmV8TBB24Vn~Qs_VA zcy7$BSxGe)WV(N{2web8bBQ_tPLBneZ;^rbqDjT--)&B6C zJS|hype~OU7F|KHZtkX51v*JEgHo~(fR~FGqSYrvju|qw+x|={4yGmli`Mmz)u%<$ zZ$)@taFXA8l7mv&4F=MU0QRe1_@hUydf4QC!rruySg=S7!w$tZBW&JB1XIv0>akQ= z{Ez{5EfP~Wqm;4nysEKn102ej0DBNT707J^;t;-WNe8UPz~X(w*xAB1x6OdHh>cN! zWQtAVq>lt?GrWVa=B|ZvgpF+PR~lc z_yu;()4TU-8SXV)FIvT$H0FwSfmb_PC+jsHvnXhz>3u|WPjB5}Ba6d3cP1=%F^j`y zX2K~vsmQA`jnw$kB-`NJpVvDv>n>Z=;>;qIbd&vh-J5G+mZL=pEpgUbrtCy7PV&!88knQcP z-RO0Kd8@N+4CU#yf16Pb{n5!CfaC^)&H8#P4$ZGpEn<1_BAUFDC+r`uk*m4RLfWVv^djIgp0~1=;pHzlVQ_~shP+XDYmq@BJ zv_`zHESdeROu<{@rVZJTUP04_at&*jBB~@w4TV9_u1$G$miZBXg4?ZY>f*qHimmhK zree^S>qG?cwWv2IQXpUII1R`u(M4Pn)Q3_cnKTO3hckwft3<5LO2e(xD_4ithZ@%? za}Lxo;rbJcwlI@sxvRqOH#nX9gGmqTHKbs!TD|GENNhl(a)t3hwf1?o!v zZiQkijAb`&80(&+0nJ=9wf;5n7j40cjogfgm=hfyK{(P#rQooSN)Txk|EmIMVOTXw zswt_M8kw5V050Drz z@Ub5)+aNL9AZ1hLT&MqxLvya({~3E$6kfT zoj*FL`9$$P?xv<6pb|`!a)(N*PDIp=tBu(cD1#0NKH&e^GNg6r_53}oG$a0ZTZaE! zsPNA=LD0qduTiq2fTN>(qloryj0`R3K0|3=lmxa}Nfx7C zl;o{mYDbUTWF#0HXQ6mC(|Q5nOL{B_BIf6T3{Dxan_aKGydn3obO6tQI78}AT*u6H zc6p>@Wm0~Y9Dr4>q6AaysN`?$i}EzikYS#Td(VKS(h@hBYG_)jX^_4WiYc^3Mng)z z`ZnjWK8G{x86Z5p`^x<;8a7nKiT_G8D>EK~Xj&@HtVmupG#Zr?^a5b*} z0yLN=lURE;OSbX67E7on2he8DF7^M+fA<8>r^&xG{aZAG%v58t8UmX^=Nl$P5PXC`68LuS6;zQ zb)WFgw4Zp-;=Zo%c^`oyE`@V>8%E_a7R3;mOn;f1Z%v#nQ*3P8|r_ zlHO^Puo-05?Ds@uLb4^crw_=mu(9|kP?b0;jShO)mN+nNWylqtvyajh>}y*+Go62Z z*48dlruWMP>P?|EwxwU8I}K@Pw$R^m>t@+s>T;A9^?CA3w2*dP8`y@&i2pV_?JC9ndz{1KrbvBH3le{^ib{n184TR-d}ur`Ta ztJzU-mjHuCtw(J>)gWbrZPdI~za6ulB278J!5}3+Q($bziF`3#731aMU3{cc zIdK|;=i3GnLVrfKUy@V5SsP+*#Zo|&$T%xGnVm)fn~#9+EI2t)OFq}kx@^lxhuWwj z6rN|IXbBTA19mEj5^i&SkGhpvR}0J90toiv^AKb9f~7!pOR7wQxm~SJLWGMm_2rFh z(eLVPnsj6C;Z2t!!*pXyG%Kq4i}SRnV?kN0QrguxS=Se{{mO)`J7sAtxmmVRjjHI< z88d+dm)F4t6q~5l9N^^ASwD@q7&Fa~=pxuL4~>n*A`6b3>~F77{47Dans|_F{na<4 zHO;f3qdUaJTy(4HI^b98S?OyO*LO{^OZK13u>lLB0vNpTuT--2EYg^^j<93gb&Vdf zx!6`#Ml!U~Pc1GF!pt8l(aAASk1k}+;?erkh6AoA^x+o1AYivYWzp=SUQ9*R$3O6^ zhTPpco|TI_h8jV6zg-^T-~@(PskS) zT5XBX5BY!K5Mz`bfXiBYY+OoP_Q75Z(7Up+0*{J-QYw}%C7N3uM6cx}q5s>!vaSaf8)Y+7WT=LjyARFGSca7{CE3`>myNTP8seOD8D&2+Bk3Xz`DFTnPu1;e zhxZv8M-C@Ow!68}oo@rAl+gOs>}U2DS;jUOTuIpmobTICuy!O$q<~Y#WuaHO(j^;r za$23+MA|J!7)g1!^Va^A;V(9EJALhBm1|g){tlp<$oZO|oS*hnrS!4rLX~9j%pX!Orta4G$hAnVT2eV=)F`rD5K{snfkl*I|$1v49c zh^-wp+${H_N7>7Wa4pw%Su;|orOLI8dk_rL_#*nRRS#>K8K&-BcEsp9I2wuPn|)>T zTEP+;|3fSByHfSt0}>9GrhlCf9$IQ zoAgTa!G&$~;dTRu_Y-Ew31I!?!$rtNY=s!YHB{rjMDzS%NT>8wwTh1Lenu65_Vo#d z;q?)Ss4<6jaj;%KTxlyy!tm}bF%-&VbLFU=>qX&s9o;&-A?jF{$AJ&jjaWaQ3EspV zKcZ=MLh*`!2xzUak*t*@)rxEFkQ2zg6PQbcLEO=~`&sabvMB#br$;o%;xdl85@MGu zapP(3OFFOPiFciLgh8k^%=*g=b8m#wm?@ZgzztA{7j5D4AYjBD9N`~52xbB}jQUWT z!SBl+PqmDi3|%(HPp~*t23ND*)n=|d`>E8S3t42;J@{mo5qdYZKY!?Rz2gkbxb+4f z8;TO{bww(rEFdrJ1A)FgHe4qED5|QSEc;!(HLhFpHK^iCkxqMl`x<5@+69C0_SZ}` zrju=$Qtp-lWSgK`_9ve-WJ!~u*wOQVUyT8HtT z*O#!H`dBwqTg#Pn-9L^?6QdL6Pnq2c3v0|`YP9y}9dHNjb1PW~)8LH{)n=P3jUD~( z)Vn<&b(250FenVmLsr4MQ8fD}z6C7(av)c58KpQ~-+MpPUvH7QF7eJ{n;m29C1^hL z>}p@C370K!nH?p#E?@tg_1e38v!`JN{@9}W_WW}KL;V{dsT2|heMWs=8cl4DEQ-{9 z=&3c>mha*lymAn+{JEqX>#6lp_LstSx~FsUME=v+H*jU=^oh;=)3vsD?ZWQv4HvIF zJ3|%@(2>j={>&QnoS54%Hyaj(n5-heWR6dS$xuX1$RhlA2RpVy&_L*j(Nu2{<^^v) zkt^tlreS`Q540sU?2Io{@LmpAJl_5Y z_TUK;^DQbkKB4e1HtCvZgIikkOkpA>$v|IU-ZklmKw+4p>y?Xt7uT~A+z>gtWN;{f z<{S|H#1lKsXRO096?2G>;L#&xn@_aq{H!_f=LgCRdW?Nf952KL4D1%zyA&)gP!Y2; z!fy<9KITirfuS@WL#yIR4c8-bBN4IkSNcDM$)}ZFM-}r&^xX9k1{h)liJL z!YQbRueD-RAIEY?q8iA->?shC;T20R3u1g?PDcih)wvVJ8!@{p&p-~u4@pCZX)udU z6+;=~$sod%$uj>YtWQgcBv~Z<@~1_cY_>+U2k#Lz)(Ql|nQN$?SCoX^y28Ya1(Pdy zs2i~Q8ap&%K61u$)F3Jdmafle7{cr86Uu=Eb5@S*n?nF~W{8=0z>vHb8hhBv z*7sYTDM80GIX;= zn5Ed+w4mK;8a~}5|Fchvbx^COAgwKfbC|`M1*8cbF+C)f+JI(HB_@DMOl7B`F&V@S7YkAJks!K&&NBRMQE zy}L%6kC;m#MC;b5jrkdADtf=L_z+>Owp>Zneko)y;+5_RrB?z{!TY>P> zuPbIA1Mo`;^A!a5jC%vJLlM%PGNsoQ_|ulf&i2QGvZf5!JooBmW?IbD`Q+Dj7$@r< zR;Og85i$>$xaDc4ABsMA^t>R0C8v3cUt#7d3~nW91oIK-ZWxCMGgsQeQk)v*l!Xns z{JdakoJcOp1o$q>GE3+OEy5JkALYN4oK}SW9t0?~pbvsv1wLUXSW)L65U21ZN~>p} zykhMHz0fA*=g6ZLx^;bpx`!wXPnHNY6;}3bg90Kh{atah6jczQ=iJE784!`|gk3^e zf<`>KAYY%I7NJUzzwF~`oT!1;AWkDTLkLl6TqA^7Pvz#S&{l%2na4xw`wMngcUNnc zLkjv05xgl{^VLNHW##Q^p3AuUIiu04E`W3q0Qve3^e8`pYXS6-T{mEn4tA*XANq)1 z`7jdO%3@8lRe!6m^*#3WjbG;&HC86m9KdQWIyKim`Z$<($r~1g)DO7EyEg-BJz@lR z)VAFxWs)C$=fe-qc)KS1V46g_1+e=j=Sa1EcDf=_y`mdKzH@MQOq|5JrJnRY{2u{$ z$h`&VLz#~WfJj|*y9KWO70B7vAQB&{hM^nb_}A_-#G5cozmo{JVaYp)d1_rGEBQg& zI6>{mFK`R<-VdT+^B-O5Jhcc%CYYbtUGoCKTBRour?>z#vxs_fHAWbU+h<*PW*# z{9unl^alNsbn~%uJwKtgn3dqLvP@mE6c!lb4>DC22UyJezF;b(aFI27w(FULdSuDo zkpO8HO-s>JF}76~yJ-!(=&^7a<~K^xYKfIlm@yi#waj9F+jS6m2CZmmjlA8MKcx-( zO$bc#>1h*&n|^vTjaV5|G*37GSJ>ADR zLmM1snvUZTKH(8nGSeiu7$SO>-njCzO+9k;@gByuX`3@M&HVwP%se`NM+zs8xlbo% z)D-k%a84g?@sX(eL_w30Nle5kTbqZQUrLaJ_VRFl8DbbMr%a8YQ$*w;i`(uD2<)jV z(X0wSJ;NL??8})R{c1iAm61=*oj@s=I@qL$x7)(B#^BtE6Y~s8lhBN@zgT@d7HAy$ z2)~fDN4`gZdRLkji$T!^7EHw1rw-`sn4QLooS7N55f-W>ECm9llQU)^0(aEn$f1M& zoLhSO8&cDC41EIjh@)y5%}WipFwzt)G(zJ{s40VH4v<7UV}qe3Y=tFAsc9%I6>Xj# z5wl=LfE=P3nRu>Z>m-a@>_W-8O|c>4BseVes9?5V~t`<<_K|=9=8-( za~xk6+9dcx=&?Seo>CJHYJdFJVRSXR0CDowr;EjFl$X*qibt7|v-zTtJZq5qy6-Fg zPY4v^2rhCKLXT0cYo?$}+CBZ|5l?-Z3}!Wb0djVD=g|r{RnREm0T*h%S6X$!cKNE% zmwZkIUli>|`R?st65ZiJxL*#W32vd(^BiEr3=X;z2Sjf2sSF5f1Z)0|lJo9%+*@|| zE3uOhItheehasXK(|bLt9rlQlb3Ac_{+(wgiGCWd%hRYc*umldmW>C zcxSPfJ(8YtzoY1C3b!ma)fY3c$|d~aXNYwap2y;;>>Cn?{xWGDcB(Ur2VX=X>K2P zg?_1^TGOgZs|Um82vvy^qD$JZWGh{qLqVYA>%1D6Ya>`rG8Qvg zox#>?tS*_Os-Aj*2?st zQDfD!7MzKdr$WSNWeK%9Bh$p9IX&7B_kHg5i8$eMJ~=4q_pnJi&j?<}3_4z%&E=FY;Mr~O%M?ULSs&wO<1lS61x|*%=pGVspdJ%c*t2DpDn8RU0z6(% z6$X+$>iJI+5DTWBKwYiyII18{Ctxs*Nn={7YgSIq)+BNLwy5`jH6MMt#0YhBep^&J zvd^CWOmSWyPfQ2AwJ_N@Qr=xgrtDELC^QbLrP8sxB8NJaGx@L`olpJ_OTjtjr=5@g zyiQEi8GMp~(-3mT3}9zbEGs9sG)ypPFh(_*giIc@#GTEv;7G0$Q$#(msJ&qsilhL1uILF|~`gy)g( z_`7mWmtOE;cZD`@Udb555}~_tb-a*eHg}2PJynGmZw2clvSsH-MTZV=$#uM*QtYI! z0^J1JV&^@D(6}9@&!47vx?F~mNwaA8dv~M!4>zNFuYU6cI;`w_G11hI`uKQ02G;Rh zOto>gD1kpzMyXy4?Bu>Sn>4;gUJ75!0LdOBFR30YZmRE5fbQ2gKqH6Qr$8Q^%4EM5 zQ@$m=)aw`{*+y0wn5k+cEpbWRiSmb&KP6LYnZq&T-+Z8&G_Cp+*|MNrK_z3QEX=(- z!}?lPX)3T{y-RK>ZAbVUmu1OIVkx~>;ptd{W%|DIOclc$77z1bQQ4|K!=PFjR`sWM zXoiuEvQzbyWsXZ{h8>UJ7sg1e;g^Gog|`w-eNXjFYmU-nmD(cM@`YvbQ%lDjTp8Mi zLgi&##~7^&e&cB6lWTRvnv+UqxA3sSL(4{L8JuTe$KtiJj%(_9%e!)Hw*tu(l}c{6 zh>q!v0>yit{qQQpJT=n9 z$~oRn=Xnpc;)|Kaxj%KUM;tz_Bh7RPEa3c>i5TK$`tGebJ+yQJ%!5|#Xm9BSA26;m z!FH#6WHwD~#5uiUw?HvMyK5zGgQi!K3!G8Z66yWOnOE1Lvngr^6w!x&vM>vrJSqE! z{WGBDx3CjfcJY}?hMQ8d52=b)LWz0Vh*!vOkLGnv$)oLaI6J*+7ue~1y?b6NiONmy z<0nJ7PqI8pr`E8!+E?v|Joe1(p-mJg{;I`>;ObU~5iRxVhMYo@N7m1bfn!kzw$Bjv z`p#S0&+3pCehAt}91qxVdPk%(&)tIG)!zn1+b=&pV|^moUUTMqW&W7= z+-SXRWsCfk+LZF0w*n$>*tfs5`ff;ih#txKfjg$z_{qS&8<#wLvUU;qn~bj&8_=4)>3~6UK-LUVR&+6mI`v z-J~?38zla1i*Tg-chyFP|F{tLZv=|OLUxXhCPvP7jJi8!VN4!Ak{ous|z4Vtr)FU5mM4B_ol@WD``mkMbwk6 z${(=D6nwwr+@m>8WSOcG#Q8gU7Idr=4>9JIC_t}tVG0OopZ**H#N=jbi~a7 zzmY#TSbb0AWTr)g(qN7XIYL8}OmC4wgvwQgc#biBnfOa?BBKa8{ns7JGyH`__LMC_ zqf}MaN(%43hEzp-ftNDf8Nd4x<^;iwZI&(}nLKulWxg*g`RZG^ zP)o|2X1uw*a$Xw(3NT6%D6Yn?t(O(t&)m}CG zQMFa*L#&`{m^y||!Ra;+WsJBtjn~+ut?)HbFGUOczRUn&V9>`YB6&U>F8Qo5lT4Uw z)QOUc!Za+k_dlX1;R0kw{Eo%*`PX_`Y5!>Vwt?%Q7~h7OYAI<*aC9KrG}*W$UBl`1 z+RoiUg?gf$9=apR3dk}pU93`;HZgYjO$fT*Rd@>*{mMT#Ej?zwSQL@iVsy_>6}R@V zgiN4XGQOn;{{2X*?2(zPcj&@?Q=vYA+ggNOX09H|_Dp)l=-fm*IcL2TrDO&0$N*D) zkPCvF&XckL92ev@XMv*X;xmd$&}??;_Z&WhSvO9CRe`@f8f5R3_Z&KG^ozdTH3B=^ z^~DPIAVBsC_s(*Ym%0yUxgTZyDM^0__|c;Y32}-oz%p(L`6(>N$3sQ5gp3fMyBEGF z-G^PC?MJ70ndz51A_0m=$nKxTRdgmo6MeB7BmPS*O`U?e3Q33@ZB&84+ByZ#%NkX| z8id&J881AoRjuGE$SZ96_fGs0-Rya)+0rFAn$_5o6Sv1Bdidet{P2?Kss1qS^ zOooWq9^QSSO2}Fv3Sk2|;izXShkBB*D}=LQ%$$rMR`@BX3+amRFtN-(POo4E3e5Ot zL?;t+;O@rU^gVo2C! zm~E8Ngte7Y3riMN@e2;h9ayuew%OH6V*ydB*>saMp|~dZI+s#L)xs`c=Z3!Ze9`+B z9X9CPh9Bc2mZ^_N%*zs57D?h6e5R2|`6U5uf{(So*D+iptybx34$|8E-}lk*BJJ+T zsy|73Qim<`obd`@9y1$oUdoGKkni^xRP&<|@E`f+awsy#+#)so$k_QS1<~k5H8HVi zH2xWzX^tl`moq7sBKCE8@e`h7Jgm`=hoX04qzat4%6`H7VZ>Qymc3HMtWtt-W1F^J zM;RLz&+fWKMNKKcnZwbqsSTO!a^|^HpOl$g^OSfyPw6P|^*khg_YTwCet`T-r%^gE z`0E!q5KuYXzgwREbEo8gmZyIdG5^2Ty$vVi70hqkiylp52*Ly~M~8Dmi57W~;U7ku z>=r1E>%|mix3>W; zyUUezV}U>Ny2|wNMD6RH+M9EL)N?ZU@bUg5^-lr(j@fPMZ;$0EIqtqW2K72pBo75S zIjnGJf>f$QsqidYIa>)F`o~MWg)viCv*@h&RyTT3#baUJ*2$FqT`as~o)iXKbx~d! zo(=R=l`#w`0;@7#w~1w&Lb}{DHfkr$)@h5t!$;PM4I$IV1R%PX@iBVmnB}7c&&4|; zy*fsc1#x^+aavkGc_wG7c{7c-`RPvxXePmR-mR7?BI4pw2H7*A*mSll-I0iRPA_we zCl5bMgoOBz=+5-0&RpsRZLHN&^vIBAB9FLzeRNnRX7~gy_+%%e5SFS~lX9~seSgA> zJlpgxoipc+MAPuSul0%h#ir@IJ7GQ1+2o+}BpVcn`xXOK7>zAjbuIv_qTU3zs3C}{ zgp-0;p%%tM<2#MfI(3rNfL6oU*_KKR`Q4?YS!4YiMF#$|`Hmps=Ili1`epn%olD(56A3h4xB9F~pg#E=A?9UX04*dM(Ld zhxZDP`GI#dWf<1Z1hMbw&B!DAE{jP7m{)aU5*W1c0PK1)Dt9B%>mjT1`qp((oD>k4 zmwl~rJ{KFjnsR5lES$XUiInLWmY#}lWCw4ihW!v+DOM!6dTZ>|(Wt5Bl`vhpKp<^#7R3J-Ae=Ck{$TAXdKUfYYVLiMyg+^M1y zNF9w+kL-m;=kf8!=;Ys~<-+xdln(9t75yt|=OqH|83*oeCO!Q`MT|pY7oF>&MQxJh zF0iFp*uIwT-|R)ghs<7UZmT?nF}UBC5-x6ZTXdn_t$X?|uV*5BwtbFS>Z12hKUWW^ zO4CMU8Ay244!?Iv$TO{_2!i9NeJv@z<*Wgl4|e%9aCS zXT5WKw-2WE_CP|61M|laU*$#kT$wIAfFq|?-;z;k9B^NX8lA86vuTiU5AU+a&Oy)S zR+Hk7xsvP#>ax45iIA$BJ9U~Hhl!+exCf?pJwk@tsqxAcG%7ChzZBi2srj;FiB>w~ zm#FMUvRMD*mis7D9WrbxN!6waMa7GlCD|}#=1J$EjLVq)FsZUOWhxk+Q!!$5Hij1# ztJLr?vtfm3LmZ@}Z-R6+80~_+c3{dRsU%V{R`ZWo7AUWJ0XE8#C2|%m;4(JOqYV4f z=CH~frfxs^&4dXtHNjzu3?`*h`RdH$`?*Bak<&gO*oIBXd^DxD^CCpG$OZ2T91k(_9}j({>E!$y|Gk9Q#eZI?B91(EX@t z&PyLgA5xcIHi|=Q-G2fsV1uga5V5g9Ol})4CBF&Yn%5B*BqqOMo}(te5q=LOB|N4WcNrMxzZi|^n{BvA=*u58R zE~(Kx!ewdz^&%^n3ylwCRs>+S7nvRU9e2zd=yyS#qyb7N)FeyJG8X_9V3Dv+ipePg zhmRJAipzr3P!vQ>K_DeLmhj)gQ=$pFviERk$cVu*NQ}|53-c|C<`#+SD@7}5%V@Qx znZdLqdPkirMYYbwB`HoEb2mgfoA~72HxMwI6DuD0C;3a}eD{n#ZW;0%QG1?Pw&-7_ z?C;H>^HkEFl0eUXgVexQ!+46Lpv|p6)TyS|$))XvffQ^7c*K*$-^~%1eG0dOKGFaEDDJNbr(i0BGfDNT{;nuiib9zQ^F+pV@sI<_h~-!~!x$>s zYipQdp$;Nf@O%ztwmm}44xWrsC%9I2Si4ai)dg9=9?r5nr}H~=?gCS&7Um3r*HW9_ z10Bvuc;hpn?FF2;Y#vd?x9*l(+Zvz;KyO04^J{UMba7jyzRX$0J93bFR9r zBVaG@m}n0(0r_zDn4Kp>jl7*&IbR?c{uWd19QwW#EA}`Yg2shV+(VBmmJ80s9J;o` zO&2bTVN>=d(R}1$mA`aNwo3r!gH&WqOW9y2|Iiy9O?D3wS3h<^;u(x{uqOaM>^$$0e8(_-U?Nuw|xB zTd{UdUT-W$74r{k0)r7XjfL_HBO(mTk*hZ-!z>k`_Hr(yb8^nGb6z=r6fR(nVxG3& zY_(deUa}tm_BP);PjWo3Z?c?Twz^#J4lRJ3?sOSg_ei!s^MOhu35*2CwcqLOxRQ4X zF=WP_YnTM=bBf!qQS9g_`tk9Oufh`MRWW3szQk8St-jo6r;w$-i;Zn>c;&8KNZ85w zO+TRw4w|Ca(4gaFG4jINjFa^BL~#HwWQN{{5I?BvTDC3fwLa53!A+4ZD<-Bb{m;>_lOQ!0`vga=SwFwvXtqxRIkuf$9e2zZL83{`nYK* z3}9-Sm$ryfHg=IZ$hjIBah9> z;WO;WG-`~=+pWuUz9g&b2FxTz$<)XQkAbTGq_np(Of%&DpPgW9)v~~>vq+sSWL1RQ z6zaVexEVs<)(kUyvtWSay^5s2T*&!kOUB}1BdQKgjMW!R$@PQ!B)o_-Dxvu%%M)yk zgWoPqZAn29LL+7-~ zZQk-y4AtjwT=uXMp*%@^zu8|%MeS(wKb$2h8-Ew zLxlu9IUjg~f;(&ved%0HIIzP@_;#^mqL{X~OCP=`<#YCg6~ly2YQI!vj>DU3bX6-q zyE&g=j6QLbZsX%>qRWzgbk-IIHrBOEINMFqxo-I1^>P^WTtEX)?v=KnC9q*RlaMMAs zo#=B`)v@59rk1v`<;aFCWwQKLN2%2)Zp{i35kTM#ux@vc%)QB2&Ujxs?+Qfy560dx zx{`3)8cwHU+h)hM-LY-kcE`4D+xCua+qTomn{(dre)o>^-E+s;KWfx?s`lQ0s^)su znrqF;af6=ey5qdn<=4Y`L$<8FGv8v@4P?u81Gi-i;nTIBTx5voEUvLE^eV=<@!))Y zs>;Q1Wg$*f7HxLxG}bB!Ge`MGnr!i!BBd2W`mnDxNV7s9WLli%>6~vBfAWku&%Z~p3zDN@?99k@Ci}J@ZZb;&_KH{Z0 z8}|f#RXrZc1(9%L9kyq^k2frOK%b>$wq0SQM($9-8f^sLp&7Hb1ZU_eI0ucin5Gb_8^Op zKKT*AT<0<{W|~;$<+XDujI+*%Cx?xF)~NEBlXBD^Wz-R6%JH8^XTU34LSyWPUb)2I z>4HbFHadK&yE}VLAKvE) z`%b}q*~4JQ>5X11IBT%XfxOK>i#U{E5B6$${CpunV3mhAl=Jz~o-AH1a|@D&W+N<{ zES_fNmQ!*o%2(yZ-Tj9JTbFl=x~Jtu-DAqbWi-U^-Hb8g*_(1kR;dP7zZh7hm{=3< zV8>bAR{A7qz*om*0x7tYNCflaV7$wUWnes|ciS|iv`1`6aIM`~0K9ilTDX+KKOJVP7e5~~a zD}c|4Nd?5K6qB7FqX9GuG|dwCx4DfFh6?a_@ixP(W%%nw_7}0Vv76hql5bp3zjb#I zPl=w!lvl`G^m@3%?O#dolIV8+eDLBW@D1+Y`P#{K2a;P2vKvti=&w`b)Gh9bXM~qn zuiN!DBTwH?(_;t3Oz{SLKU7YTfyLT?W)qTgPUZNn=lv1zM9rb9^g=eZN<{9OuyKTfy9o@f4|g*OZ-So8~U-5~pJ zwLe&tlFIu|UVF=-HE@kL?k;0l%4fbYtoZfMI!dK=#Jw&!5YX5ET1WZMhl+&1rB3y2 zjN}~5Z48ZBnE!RyrAgV_N>LewuLl3Q%h}cv7dH{|r{JIHAI4TvxT-&F1r;xnZ8b8?OEs~<^BErXd~ z)(taiM`^;Q(nX#D9qRi@KNH}u{aA7&^pJq014Zu5pv?9}>DAw+Acxwv>hV z7ztm`$xk%Qtfu|#oke&a)yL#FJJC&uj&- z0W?Q^q3>fU6lAZ1R5`Fw7g_up1;>D(V*n%G(>;B!fK38htyfZswXt?WN`U{6v_j26 z`0qNn6y4=SwP7TPgrriqn8j6DxGC_J4Sck(ihr+V3I^H3s4wHG5<_akl_IJq*cqljk0OezdNjP^ zaEnrX&IYV_9?sA-E4-m`1;MH776lo@o}W;g_x6vcGU5q5S)_+sRW~#xy*?%CiG)>} ze+r`r ztRZWR?Uc&1G#*~Qh}>mJt4ul9uXhgrI2ZHx!5hHcmU?((z-v#7aFBc zLJbtBQgrf`pJ9~~_*uCOBW~x$B z#1`)H_ilgmg~s8)B}hh)(0CT2q{BYnNI84pVC2-{piEf>++Gb=<=}TuZ&v5l5drgX z)){8%-O-D=X#?I$NYh%(U;00|?m*WU1o;E>p?o~UaeSb3brw!SwAD2~P%Se8R9HqT zMQngPE5POPu4?}TkAyFBz}a`|`z@J$1j`5kb7dQrqT3Gi&J2V`!dMS=kpTu~LPB@0 z#PlTF_vTaS{+zSk;o&o{>6g=))ekW1&RB(Db`#VMNa@D5y!rbtvcZ61yW^XHMioca z@tHA}+*mcwhDCB*TF@FEF{nbvl6!^gj=YFO*60yZ+9#naR6N%&zOPuYXjb)sT*yVR z3X+W%nI%q3aZeawGO0(aukHHe_+mt|e#%e>u*Sy>GtM6O)>Vv~ic|!0)Pm6Zp|6Uq zHrf1z{zp;XTNcD_?c2f94eEc(4LSeg-0&ZAdjA?hvJ^CJkpxgagSB1ah%kPk-r6)3 zDR(^Olg&L46*eJ8{jd^rGiz=QVi~8U4R|Z@Lcp`=?0PlW^Sw#In4VD36qgFUw>!$T zoqC-zo_f~B?*Uc=Y(kjG5QeD}ItWgjrp6FOX2=)XNosyUx;qs%Me&QEwAAHR`FhgE zG{$ct%u7A~c+?{p;uSdUmE@dwA!IJ(4RUvluyIxBUa}k`Av#Q_G-j8_BPjG1 zXe=%jvrYOg0X>AlvuByjU5@?<1A_b`K|{T|*N41o3p{*-KPlQJcso)BD zCU6_5+$?Q0dEbFqa^cLoa}X>Aw zw|H5sAOHd)A^>_0eipfZvlju+$!XyX_FhTH`v%Vbru*l3Ytu+m>Q^4){x8yw=dF9L zX53OrdJ}|el33r)>DmHu`b2bx$P{i&f49ltrT@~#4vV4xB zWH|DkKjwW7Yv*fmq~6U0Hh-z{Dq(PBIEu=w=<&%Y8$!$6+vz;+N8+1e9;gr-s#(K$ zVi~A2Va_^e7)ZsC)So)BGGU5aF0BlWzzNAlH72H9&o?FZI+Z*$X4h$8fnyX-U4%~A zxlW9nc;21rZ(b}1D>By;B}F)`1Zxo+U`92()^QEkiSSUyJHK5gng=HuK9hNuJppC zx_Q0Ls0}503c@#$-TUKnRmTsV8j9-foUuwc({eDg0kf5_`6dc^bpjHX zPO3|5lXkLf9BS++*`oT0UxOkHh)^$v_>52NoxtVBr^j4iwFPLjKDYAKQ z+2tEm1!E-Lg{580P_9}XB=5d@hbVKkM_*d%?{{g1-CVZn8f|BsOKUyO=T#-cQ)fiu z?V0aA_=1bKR$EdhTrfVBo2qx68hq8#vuM=of}qxJ(tYRb$HUlATLAaqAx)E-9pEj6 z8`i1!+i3rY*1{d_OjY`TXOzxqWBi+85wFr6MqYyxwL8v(NIn%i3>4vUq$%s*l9W`Z z;DLzk4!34v3YvsS0L}ae2~}4Z=t=In{&obOMe8Ud%|_%^4~KuVFC%+thI+6@{qfv6 zHr_JwNA05pF-S*CUPYl&dL}(haB#iNU2HnhN}J)I#V9gOv`mp?v#t z;tdt@Wj9RKS#N0>soUk9$M*^r=%OLt{R#qtGQka+71nQ5K-fe9 z;6WL}Oz$v1?IP{n$FuB{SmKh2cSi`?^#97+gZ{_DxaeSb>8C+`c2V6AZd3B{cQ8`P z{M{N`8ujdJdA5+GuC3;#-3nDXe4X*(Wr>hW>Y-`3)#K$a7|#sb2{PD`zCR-c3sP;) zYrI(SVEz?Z(I|JQ>%6p9#f@y9i+YRHD(+Smk2d+L9bw5Cq%0VA@|NSdUKTg1=#Tv0 zZ}1rHNnbnx-)wo?l-9}s?M2)x{oZ3nghwUJSjm!BhNC{TQN6}MbZh+(BiRQC*Kz+s zd@ay)@os*)mXZ;#1ZCwLP|1)=8y5DM8N&E^7Oj;bW~wf1wu^kmST3-|4LJIvk$9q} z6lP`d@qOdTvmp;y9i~uY2F%ElM(kRL;ojcMHJ)Eu_OCR!kTyYUH5L<#1hjX zis{Gf27tbqk2{o-EFvmZzRs`Y;~!XDYAfS6&`IRm93jH5ua}e&Wjd6(8oWH^%sn>y z<#Z@8U>SkJI=^m1{IM-=q7Xopd>yr5$0!$5JodAlP{tXelH9`HhHHNehmDL2KZ0Bm z)yUPB2){V9(vY7VHrnFmXN88zX{*c1FUi*Te-htv6(R4SJ28)F9gA75PGi=tE#aa02p}v)ZvyG{-q_dNg{{PGl zR4Gf^Vk@J3+E~RH4u>HduHPwlK$l{hljTR!JBIWJmKDuI?B5 z0sE_5P&)rWLORQjlVei?hLnet8w9T7-(%|yMn&qlqTJ~)Je~~~18F++?0L^}{I*fq za2)3Q_*~=xDqzPK1tveVqYSme;5|r$T;L zJ+M=OOBfTj3dw;o(8%qwP?D-@HB%}tHq6PHfDEPZTdFiv)t+=gZ!(yK7{Q49EYs%a zFj*`1)aqU4tNpbz%}Eu^?=;jHwW?vhT1ss;F2X1~!Om&S67IN3@YklV5=v^CJ;_Ug z%F?6n_o+-7K&veN2yI9~Nph93sjWSI46Vsxv2a3bateE%WqI*PyMWugL$v4ug=M)6 z2Q~H5H`2jD7SR!X0Jnx+y`+=SuF!WUhe^3fq0MaVbwO8YRqWYelEuZ$(0J?6ZBA$O z7GjBcS&Qk#4)||dW+hQ=oa2UkHkhn%96Qev0el?uYX%BL4QJDsV4qzRGo&b0yJ2ND zBlXD-OvMrmlr@*)Sk0VuoOO27wWjjnoWnjo;R}b~Y@xB_sx>s7LB`qEKNW+H(9PANFrs%@!gPkUK<<%f^i=c=Y)?OV zBYID}o_2d0buHTrD$``D&YD8_=i@sQK>gtEXSd9mL2Bx3#XX!apWI3-h&-wk7_63| z2LyD!0z2nUj-JJ*c(hpb`91*LAkngMnETZ1;9%E+URP}+Y*MLA^y0@9+(Ia2T)XPr z$6eYlo!G#`rxe~veR&;b9!mPz4A9yA-R;ZG{{AG0x)>+Jy)F#Abh0OwFSPXpU#9C0 z;ij#v6{&JUV=)3Si=bX5GZR??R-y^7QUq8+1m=fK0xY>;RZ=6Gd&ejxh32W%8S2P97l6`R-K6DG_jOxkcly z?1-}TjrUt*;hBcrPTUOXr^z#Pc_2R^AEaUc;ilI~ggSb$l1+-2%}y-UPj(jyo;2Rk z$!^?v!De!r+}(@&HKc$`KAVl96rJ6)lU|iU3n!jnZ;!cn7MC%WmTXxKhllWDA!c2+ zudnjOFNH^$f=+T-7%XgKOzRoMVW{5V%aD#+eja>FPO{RTk2vcRZ{& zt+4;jAez6mTmO9)A^snuosyY@v9XA`so6IR>iBPPPU%`!QyIetu81bcK)=x;0%moC zn!X6waE$>xf$_DCg8pde!%mg}-rc3rqtu(F6p8VfXyY*wDG3ZAQc8j5>f4y;9klJv(tg(ZOwvZKhK{ z=fO}Sw_5K&+FO5U1YK&KlO-Mnp#Zokpjp|@X*_KfJv>--DD*1l9K=gZYTPLr%581U z6oeA|l0%4q*+ye1Y;Vt;o3_Ec(%K6t`uXcQxeVt6D0g;(a zz0_d}uhDTFIAne8dP;r<-4VJtDSA7v8~ikzigPGw1>w#w)?I)Th{ssn%ns_Jph{j95tloiXe3y3zdv`s7^?QGrCU9bP4dqu7)v7ei#wOPTzR&qpx@&0gkh{5QqeFr z{3H{~I0M*&(g4=I zhT_f9q0c@+DNPQA#vv9mG&2Ue&KP*>)K3>%SNCJ-GO$Ss?8mfU7mkk7;2Lq1ldqZ zI#Hoa?Y)OAFGbsXrthq?>aTDgxEZe32bo)yqufn7=f_~Fv*OHv7*V#S#wMyhZS|X3 zeqliq-R!vD9mZJhz*yEJw@`*Mfi@3>)fdK?TtXnYQ(4rI= z>tu4!7ePRZKWj& zXS+|dC5DHe_b0=yHkhb;0O=FpNE8@B~*V!J{Hk754!e?*Gwv{qN>0-dKAEuD9TKugAhz`WtIjr$d+s3e1iW2Akocf-^#xM66d=|3w+6b2svtZb?tS*(c^fP zw%POf`Iqnya5j_&rRxsnu$B)taOrtpno_>MTb*mPSBP)kE^ETopYD84pE} zNE*h3`ZB7++-^7B2ulN8-8Y4Ou5C2%Fp@6q85S06>6c0yG)NsQkv?Y zl3QTX60H?jI5W-SxPlZTodLwK>n#-4iF0T2fki%ZYmbg4GKZMjHmTXfX}AjL-qr$} z%w>MZau|p$JWvgg&=iYO@z6Tj8U|}B`dzX%&fo6mcF1Bgmih44sqB$9$g)(k0avM< zDL2(&i3(dxx4gWe`l|q_V1t(#fLN>1o}pZLeRz}I5TG1MunbkpAobI?+CNXoev)gW z>S#KJE+J0eX?g?B8Y$&9erJjszR>&8AEi4McD;(WEUY4sSscp^;J}?i=Jbn;`FR_v zfJ^z@@A81W@L>5QI4b;-{cJ2b;%#i`X`WEI)P7wXL14BTa=C@4{n3wy$%1Hp1HQC^ z#lkNIHP1@^Qn+=fMuBfNe+iBykVXEZwahl1J9L=r;)MIQ!oKRX5NRLAL|_H%dztPa?r zeF`XBh%YzJ0DbQFEwrUmWUPP`82!rLege6uDbX`f+>`Y;XD(Gfyy^^CEolcxG1;{U z1FOTxV+A<`3S!}sqb!|(5DFC}1QKDvB8Sg0xo27+#uifP7B9bCcsl*U@}>&PvoJ@t z<_cH#0F)~p8s!j=*~}o=5KVTwSplVKyI{Uyu&f&22u5gwmDmTbFm#5dq(7>|*`J}b zZu27J$yS8JU++>m7pp=!17IdueBJWSU_8QpdMK{hV7LQsldy zA}UF3s6jN?&W-YpD7at^UUf}1aJ9?&`$zMF)+XVa_FaD3EYpN1D8enRSZ{}uW|1l| zzg2_@gAj%M9Jh0=z3;tBJ@^J$bW}1&E7JTg3(n%Zz&6!d_%Y(!KU3Yy$j4cOZ*2Se zCd~gmwn_fS*!C}E`M=rzsaV<}FQa}|7izEGtugBPK@>5=hDC)}B% z3`yJRTDr%ft80j8q;V3~pa}}*ikmAkHd2_I{F+ab2`LQYA%$!uRa}!nev`=P4*vN4 z^xbNf!!?ggfHRlCy*&B`DeorQn;ulOh#* z841KHd1hQ~xB*VotmcgEC#@?|1!e4mW(q{71`_S5`4K^iDr3%2gMFEobAH}2EK^ln zpbwf>w3}l$RTZKjUVo?98=!6K9G9$%E>e{-Scl2l>g^&D4D=FqN2wxsUHfUFtXB3= z<`|f4i^(e0#zsxlEvPNqk+T>)A`XoXpQ^R%3Kd7v+itBvxl-zpwAZz%_);CK1h>+d z(>5l7Gc@=JRO`_Os@3(2_GNk!a?o1KoEHxZP$sQ>=BA1azlenj^i~&{P}tviA#1Ry z+CiBPCFoB5?-0RCTU!?=j%lviI33l!d#i&{LUo;!FW~T!ShJiq zCat37R~0|CW%Ogz^^Td3pk0=zrBe1GE8E&Xl!!|*H{2FMJASz&i9ju&rMbtqC6R{qe`DN4GY zpS5(!P%QSNS+UUL0fVuMH7Gy{P_XJZd3}KFA<-Q|JiGJtd&D0}ir;F%ej&MHj_q&t zs~P#7(_aGXrJPS5M}NZ-7Cn~ht%~MUnkcE6Az5vygB9bhdrI$SOMXUXRwmv};D@&5 z=^kDup5XfaRJVx}c99SIROFriww_*}rBK&D7}y)H(c$_S7e|Q-r81>F^a4@hOHO_V ztQ9~@LNFtJ)JJsJ#KJB7S%=jf*jW-xN7_>s{Ow%U7EDLpQxsf7@Z|>Ell-xS<%8>P z3)_?3SraTavb>9|yfv-slHQL^>0u}Wufp6R~dep2w@n{Vp10+8&xm1;YavbWlW`#-z7?i zXTjC(f%dsb*XxK!wZ(KM{vcK~33GNNM;A5H$prE1C~1N%0Bq1J-kgaZWu9byJIRer zm$?=kt2k|^%WK!O4&(V&WOJI#4XEm4yePxBm834moNpq4qZbKZ5tN3OT$^TOh#pbw zr;A>pf(ChK`Ndnxj2k+9!>JNWV>KSPyd&!)s;c1DOn3k?x4L_C+{qdCx?p$Fnu0f4 zAC(X3u-f)=9m2MrC2th`ZiZFae(R6v(pv2C>Izh0J9L+CWqAx^PdAi3FFjNw@8GIE z#ghhZNNGZ3!*Z0V1c@h;sROdy?uzb*#`$STxkHCT2a(moCgYUlByAl!?PdZbo8n{dboSSr=F%83 zoXA4YR!3!$`F;4{zo*%65bDq>VvMI!vO+8Pk%4~;Po*g5=STRh`G)ke% zh5E*36AM);X;31?O4pev7xlO+%Z$b=x?RzjfjO1Gj6m(1)K`~PFPO^ggp8r}4V~v_ zx(T4!?T|bzne56jon|bQ2h|Vi>*muQzEIz9ye#nmViY~YT=wDCZ#W^(_iAC+#KGw7 z0NI8bU4ww`iS-*O(_Tyz`(#Cf=y#vr75KZ#nFBeuswBlhZ zhbE!+TIjP@42W|Ro?1JPa9wMUz0g}kYNj_?4Jo7o>M%}+1DG_*4F*f_xco>BxACM@6s??9mhZd&;ggHs1otdR)^ra}>5GWo*2M z0P19)0sgfNf~B%CBGk-n6hkyrkDK1)Eml%1X}MDDIDoX^Jl_1#AnZnxu!y(r;zFr} zqKs8XE^L{C(V6ALkhk>ax?{rh%*G6!>6rryzMNDU?@L&*8xDyC)w1xKk1p(p91WM? zH||W>z2fe&_9OvsM^jR%8z5vTtDw6^3|@v)`BC7S->~<*VdP7v2r$2O(s`Qru709|i9^ z>-baK__V#a-`D6C9lDByC-;?ENqzY?ON>?C!}Dvk9B_@4u&l`NOb$4H^Zu|Lp8)a` zhn;oPG$ueZGe@V?%*Vx@{cUP2#&1=P~Iq zbA|b0xqcz<&4QVn91(3*#`Z5TVSO7CHFAKE_78>yQm;|8DczLbwi7j+(80i$%DW^G ztNR&gf(k+u#AFiA^q`k;en$*32kd+rznd|BZh)2Z3|VssC*%Y+4z+(VhJ|&N)$h_DBT;5P(@C_soDKSh03UEe`efV8ECuFi&LrOXnNiitg%5t z=GpQ1y=2!~qK=E^Omb^)c#75gS@5Tz&B?vPEGKb43v^-!YgE~q_Sn$hG3E4_Gr@*+ zh8V85Egd`@+Y8_6D20%B8JFGCdSbz=_cN|HzK`ha9#3Cj+89z{foI6R&r=s9hdu&u zPCfmcl!{&GbWV`609J^?1nqSBye8-LVyWdsO6jyb3MQ5!4Mo}^7a}9>AHWGA%P%N} z!M}O9txg1SF{Yyr2@Kd|4yQ#x7z+^f?SI9eXyw7R9ys09rzYpi%Fb3OJYZ71O`vpf ziVSD1CPwS;LqPp5Q$YE!1(X!Bz_0gs6#eDvnoA}pvhGKPl!t+N(0ISPKxJV$_8}PK zfS=9Irs{N&EM^f!zD3g)2zA~h4bZAkTn1|gwpoGWbBzUN!<6m>8Jp&CWo!F`(k_m8 z+dhh+a1q?07lD0cvWG`@Wt^W8_MY0B69%5@78_P2Wo5WW`2A4tA+8AOT^;*q);bNf zi$h`#GfUZXBcs>WL63^qC`gdCjtVOrksV4Y#WDh;$JDOH@-U9V()C7w9Oa}alE`tt zsN(s$H$xgEAjB99E2?bu!qqY2gf=SETI*0X)^;pnLF_el)^jS>R5@yE0c0wO5z&O| zZai2Uww#Uv>pu&Mk+V|c(l=h}1-hlzY)!FXoP$NrV4u9f-hBf8{^|3X(X(Y)S%-NN z0(;jF`1>1wJvhgWBLDLjTqZDj;g8rX)P(S2H*1}a6c1dT;{<-P$3H>*NR@cCk3da~ zP2f0pa#0oi=VLx?;F)N~!IBxbAcX}~A(4yTHk&DlRRKYe2_~+Cf&UB{8SnM4PG;UaTEg*cIhT~HIWm512a?$^$zm{-=vIINtv11M} zS+j8qUPQ6*lxrAY(^)93ycC)wv=m=~mnkJ->u*R+fX*J+skl|_yn#z>fEo5#j7WfGY>4pkN)ec5&O# z#jKC-Ki#!Pf*IeF+YO4lNw0REGvUznPU2?y%erLiC?g-1pZPf~R@1K}ysvy{DhbUp zB>izwTwp)wW#F+ZBAj6k&|Vy_wy%H0OI`hmu9*axf`PVxak1+CvsLX+cvkF{9|zCQ zJP&*FsbAaK3b$lA@$gUQVz?M^v?jB7X~+9n2ZQ-H(ZEVhTu zwhjYyY7QfDsZ+nA70$k-mQ7>x=QWG^PIaiV@kco-m^>A%iwddejGxBXQ`}-d&E|fn zU;|e(tf-!|#$;3snlJ5xz@BTsx^#$V%1huBK`f=C2)N}Eg~BL-Fa!h`y0fcfL#ll8 ztAYO1kHQ0?k{!C^*D4WXo|!ck6!Q^jHiTFEt77X?uzfUX{;=NF7Ugq>yLjU2#uMdJ z!d5ezBi;2H)v>dd4#S&Oe+tLCIa=JY^1#f>qn&*S?*NFI=_(ld{(vbf25QN9kF@i(Chb8CWp*X3`KH!ezn z7t|R8JYRP-o8hq?R5oE#ZHUu=jstKuX~`}S$4_vYls>|7gOesJ|AFL|9d}Ef&ObDZ z5lc*V02K%^>y!b>=E0kAYs^lI^I*f~EW3@XKgdsB4%;f(*I3G5^p{^xWP9$IrKjM)9uhbllaRoaV`$dnIbqO=z!ohk)jCb1V>JBn@}|NmD1c`M#dB;L{geChxF z%J*0IXcv=j0xmc&LcSs~>ujfxtZdXhGuEGIDo{Dwo|SI4AFJvGydH5?9qPQ!sqJ_or^rGAoVIAz~!T4xE6!Ck%UM+Or6ho zyYHhnEX*H963!r-b!Z})W=p@;_R8K&x^rQWh6XV8b(7C zPp?S9loeH|HqdPlFAWZ=_Sf(#+Og!0tt;1qg*WC_xWSOc(AZAP^LH-Y;H)O_g9XKE z$?4fRI*?;S^@`RBJ{{-0#uTMhLkoWFXXDWE56vr1h)cCTJvFLx?NHz(DajmPjM~AB z>h$e`$}W#Fznb~M<@!@1zI*SBXam>Qt+cJdFS};v0?HgkN^zY z{A@*|-`782PHC$4F;alw%paM&`~ek=ZQz=b+ne@OTEn&4vPUsMU7Vn1;FIbXgqAfaD_ z^t?o6qw>N$)lg!_t-)XpLq#$6S&i5+W-M(QlhsSGb8mqMNL~_-G%wWf`<`xDX4Z7O zw_U-F;I_;My9I1F3>N~`BB$6dJX(=Kg|Q`6Xm@xzF+n~KdEg_s^kAU-CZx^)n-h~fVv>`RS~bQPMQv@ zpF1_oizu{c&RpMt!aAnj2?!KX<_vU8JAlyLMhAK2XM>YeD`Wsy?3n5S!Bcz?6WyhT za&ssFYBd2S4>(i?D>Ov9Tw20m`0nnhbfx3&g}pVUUcGrbmhj7x531MRLFGTWd1w3D zLwPRLTHgu&(9Mu9{cM#Ur9@QVW62cz9Y7*3h()AX)4M{9#k_NcWV3pz5#5?hTz!~g zv`ddsl}-R=h!V$?O2&*6Ge?%YtmvrC5#1rSqY_woV9$n^W{#AN`?cSw|MGmW{SR!O z2xEjJ_#WJ7LHzI7yk=?t52LI9@AIF#UWr&67#kTG8~s-c-+xiJ|5xL$OAXR1Qv~&E z+Q-w0O*i9;OwyI25k+FvD)-dbOyV@H5l{?nUDhaau{@b#l<{37c`vdqEj263{qsl6 zd|W-+{})6&GccMkoB*6aVt%N9Xs#9!k;CcNqz&8}5KZa(yEl{VR;T+lpY7H}#_Ica zhcWt}TQ{yh=Ip~UhW6Dc+p&Ax6jLdCz}J^Gf?vQ^-im75cQU@WKVEr$RoZ%%Y`2K` zXcj%^Nwl^+=lE?ShC^4bH}C`4L9KYoX6 z7PcyT*h23NuaGWW8hpS}_z+EUdB2pwyHd1f+^I+iRPCh5*;Q4N>Qi7)u{3G)#zzmL^DI2QlgrDtGFsBDN`(5XB#Y74qb?!I)5PbEGMapBXd9-?^ClLI zI8UV%e*>_V)GVvY6O(MJHTDkTPmc^$Dl18+lA3aGRA_ur$4_Ebaq{HWVx`uh*Va|m z+lrRXP&o2}rTQgk8XUyU(bH^7NYhkTRNtK!mRHQ!o^}ynCfo82H_R)fHPE{qvwogc1oflr{2o?i zOCDn*QEC?3W#3=WwA8mlY{c-`A%EO9XU;~vlF5zC8|MZf>fBu{Ws{X;dC+}{A*K>y zMKNsAT(&eXpJ9JAtBWhSPGV75M!~ddySTDl->V}gEIq2VrJkM$1hY^jyP^&|9n#_5 zIvnEZ{etNVs%rB2?qXr?BO6V@=)Jx?(Nn{*VuEAu;G*4!NXmfgP1W|=I^{>2_N3LH zosd|B@u=TnTnSPi_S!lPaGIcJKyHwl5UmR1%sbMn4x8RHLLScB3Jh8#n~L3&qBz?3 zLC#5z&MBA${B)ZM36bKCR3`KB6Z6X7mH$v!j@ea(V&Xl$qQAA|wlQGKroYAhSOO&Y z@4Eu;QhaOy@QvWUJ%f>b0S#oIfn>;3gCAi;^*E2b+@^ceZd(BHexDz{47aMMT+q5q zvjhv=6gmJ&GM(f-R0^HJZ7;V;!1ir>nC}iO@)yd0?Vc{#RzDN>EZ^&B)AUu^s+qCz zeT3uPsN&@(WwB2#R0lam1=O*DVvY( z1XHA`>DqiWOv7n}&j9%~^xH&bW|CPGE?&pqU{P@PM9=uyn;-8U(dtaL3`{N)Hg(8V zul+I==Ugh$pK2lbCt0;$`)=KK>*z8ud4(pXYxNZC6rm$&+Jr5TvP4PZl0>1(4;jn- zif)69yb`)K^H9X4MN*8h zStEAYJRT>rx0!>V7L1O~THl;S_-%FVD=}J-`n-ND``>C%PQIEIzK(ZD#p8MIsMR1; z5^K{oCywG&1;6c|V&Ii@#W9xAkR;9;R9d3kugOLU1x&0Rf{p3MZ#7MhqfMOq^L_ya zU3FZIlY8DnE*{T?{i*PPjVlsGWk)mfZc+|Ft;#XjF&2{sk2`I3+`rD zf@S#L^5v^~r22DcwCMNH-zTtl*|95BE1nI-blV+|cb?WfvXwhGa#JQHDzVK9?eje0 z@P6iA%P)xWBodS)?n=v2MeWs8&1rJZlTKr6q^pX{_u2bCmj zggP1bB3_6|+`^gg2N4zmG&OXN6|U>={ZC*Zxjpz*Gfmi$4Ez_Yh@wzxiORA-d$W^oLVg@n~uG+41aAm3lPs( z0pL@4{ACEu)bSOT%s-Mz{Br$UmxM-}&qrI#N1Mk-Tf|3Oz}GyFuR4pb>L|)}5@Y!# z`?*6}Y!>j0mTE)V!q|+;8=?%_lN;^=C?@w|>Sue98L3EPv&=OS$c0cE4XS2$!^(qX zxBUo}34Gr`oY}EGOkHmb{^_*7&ZS%fr>~P9$4~rTI^N+Y7xHrm`F2bV9WGSWMPDsa z#OR*%rp>k2TB&0-Qs!2eN1Ocy4(7WD*2FNyQ@M%mBErLUGb%t!5lsBLZ|Kr`jzN-!+16-xS5=qQW!pBptSsBMZFbqVyKLLYvTfToZ_S*0Z_JtR#EFS7V#kii z*w354GT&!o?X?2iwb1RrMWiW0llt;Lj{a7gat3S`(_&-NAW~_uOG=7xGPsLH9#`V# zYRJLYVB@lJGLVkk^ZK1?D_~O4thbM&z``#>$z803>1Ny?6|->;rA!5?x(=acNJ)c@ zgR2c*_N(S`BEt#$w>9p@n9^etHpOkm%Gt0pcVdY)kfPeal;C`Nn}ZKLhDK3@4N&x% zQyJ)94SjN>D@NUKK40KJDhc?X2f%7rTiy z@Br$KWaJ_wuJ*H)p`-yT`$WVkQv1O!R@Y+5%5nP$(_ye}lA+g~dpIWSC9-%Cf6ZEw z6g9h<8k3xH$1Y1?!}Je<@+^ggiK*SX6VrfY|AZeSq*Tx{DyR{8(JIpium%@w4SI_7Av%5IGwjU1h`FX1=>zqc^9gf8bibzS2WI=EceM0z46= z2mQHmadXdzxLa`d0ng|Tqq}1yZ8eB8x=7h}Xjk8xQe~RLzjz$5CwDNp2X{~0)`pXp zJ3K>wMIh zq<*%T7hA+QL0IHCkzI5;v0bb%kFZECb^QG|%JE!Tv_)IiK+C3-5?C>SMPeQ&S6Ldl zZC)#vQ;6v>&ukEzW=*Za6ai~qSOXYmols~PkSd*6Dmg%JDsvn7ZSH#=qi)Jw7{%sX zMq)o!I*bmu#D>F?f}mh~FQItZab#u!0iCa4|3R}CsKi!C2%t+Yu^RhnaTjuH2d54I z(^9Z2PNH&|-!i2^vyaqwR?qXO0?OtOL1Q|kK0?nC8cvbEMC>O3;-RpxQfe5-41p21 zDJHdh!V&2yL^1@Ie45q~d{OQ49Cse_ASK+FDB=p|XHI&}HQ`MW7-L>}5!M?l#E(jt zi?cV>B2&b>lmjA24x5e!R5o}GW4HJ9O}-u8)Ql55R)(lZGk^gz_Q>U0P^?I#D=>4` znqk#3j}e$JRK9RrQo8pGqYV|7*=HGu@ldFTp;&`wH;mgrH-`NVE{1%CpQsvM48b7^ z(_Z0sU&$pTvD-g<6WHiO0l$6oA&GCl^X)m8tXV(T37)>S;(9#ze1WCFA<(rk{4T!w zKi6pgT4VhC{;kkgweg=R>;4lMDxl|JYHVZgX!`Hg#QG9yUFvc}xJ&jMc)I0$)da zQR8BD+hln`{YrB?>&mhkS03<4YMfbqJri>D!a8)-IN4|kGQ1U~Z`G0spq4AlcOJ

|U_^;{S~vb6G*%zs+BY_XmdXH(dN`c*8V5mSG81*{3e(b*;7Y!g zQO7)DBf`U%P}@jY=90_`TX&2wQ-dr^eVF2bLS^S_UyF4!#Ophf0G4VQV%8}8_n@a} zj&ljYS7^_QjJuVMO80>V-Ag}TuZ1M`!G)@o7cgnOZIEJ2oW_d z$C5n3Bjzu`iO`6qCRcOH%Q5w848jU4m2Ra-p64$Axh@23=LNUB;hXhw8OE`fIz99s zu(8NEzwuBTiTqltTY!*c4@!`D#kR>;k2IV~Fxz3Jwy5Vjzad~67-PpsB==Pno^-)P z)KD)dOi>@Vdl@k~NI+#j6*|kS&+qSxDRj%dhI8N>aS>n$PH5)PZMwyMwgil`$g?`B z4KzE87&H#^jgMlJkLtkV-t7~%DE|FOLCnxo8%PV43jbBMi8QKr@YlqZrJ&RkNd*hF z0&Q-&qmY6>mlVW`1c?E7Jr$AHMrd?L>Sm^5MGM>;U5O(TXzlXIYEkb8p?oNIjajHC zc_|O!;G*=>a>{R|=SO8IY^dYqap40Ja})OfF(33>!$g_6!!Autd!8}V=oJL(K+(25 zQ8wqVetYTw4W4|1yl&>;YXpGNSIuE$%x~zt(^m@I6t)+^_41T=2|?N0X0Vf6YOuV6 z-mqQWbS!V;euw$ulM+`JB?mUT!$jcB?SIf%-jw||2`aZA%a$-V{nZbCubte}^%U+LQ|4{~#Ir+>- zsNkW&dS2T3+`3#kXOiu2svecK`f*Dpr{J=E^6vNk)OWDdnJhDkA0`21!7BkH6a`k* zuSUhp9Z_hoN^!=i_Ris$HAhBsEWH?p%TtCh*W$;ZUG4T)4bJ+NL8$@KsP62lBjoV$ z=k+xH9yn`q)%b}xVnO}z;{*yosX-<-FI}op$zRm8#-tI9!2o$0ro_}@Pq`vHSy z%+aMC5jc{hk&N827gfFb?uy4+g$ujgl=YpybUREY&(78kM`6@b-^d}@XfzJyeB0&Q zf{s^5shRe`Vuj*JDoDFfCv{pzB9`Jcc>c^0UOr+Vs_ihbjd6&0jgF(e5!Wmep8t-z1Vq>pu^;_=92j61ACm* zja!Htoe_hJjbDeIfs=D^mogfU-5Bzfy8Ch!++^+ij4soLEoFHGc3`+fLYF$VZJS-$ zYgNM=c@ELo46Pz9hyBgJ0mTD8#q|BuvGXr%!}}BME57kVX&I`it&?5C-evC9|3iwM zB_Aw&@%Z8|Z!ymw0kk1Nn3hiaf{*QK51PP=E7Y0!RQ?YG63iJw0-f9*yqhl}L*8hQ zg;M>~9uk6R#jh4RTfK*abh?O(uR|HM43fuB0&a<5?m=1ZXcBDYHjXmwD3Io`C(ibe zQ;wpI9tJ0@Nt?mZsJz8o2*ij1&(=j5NH$$xq@mOheS)0m8P1xJ6p>V`xAZ7|@#~yS zX5P$BSUeJ`uPrt7%HWz5Jp?#sf*MKNWCRC}C3$KCSIs5={e+$E;qYq0cu-WS2oQ!rRmp9@+CD2a z<+;#4zC#x9nf)2{Z1~aRTqJ`O1s;b)TCGEZghO#k_gm8eSjl+9oyo0YE=tt5UsJ$)HC2QAm zwPP+9a-WO72*qoSOtM5QZr4T*M3sy35CU@!*eDY!&@3)TlSr`Wm)|F~i?uIn7Fs4G9ATZ#u|&%pk)Eb0i$;&6bT3541NNg& zn6uy}ck}&mqKrr^r{r%Bm{rRz%=1%L$@N#|OUX~a)A`0#9X$_N$PrbOXjQ!y2Q2rj zI5CV=)*n%xmbZHtqooB7qp)Mm}Z=SOx& zhM^_b+CNtV5T#+M47oRqVCz(onnIc~F_ncjQB0il&N0ga`sC-t*;CG$E5(hFUdWdt zOQS%4(arG1DNI3Fz}f$pO9z zMLOwNtjrcbWCLA8wv`w(hf`B@Q0-1r{`}eEn4)!Pfm&sJa`=}@yea_s$D!EbQZp47R@qNmJ2lv9mF8LB1nPD|{)L#qt z)o;?zobw7Pi0qvFLc_Cf-PfdL+7>-9lx6RDD@)j1S&aD}9e$g+V5-S;QW25{aHt-Ms&k$wXWUeRO%6-MOQvv)N_8O56qh`HNoE{t$qY+CVUS z!w$_9?VviA2O6JqKe=ILPh}k`Du;hDzROMd~Lr@eQH$!s&vEO69(KG<%s@i7R z>@4_Qy$S#_Ws!B|^Zs1If{98!>q$FBPpSG#s$e$msBBFl&ZN5-2MuDhPrLiC=HGVf zT1ZADa-`zRSf{AJ6}bF9R8+LT4otzbkcEQ-b_HX)%- z#a>f5Mu;MVawNv#nG}pGqI=lFnLc$mEL0PLYDwpY4IFesm>y8Vywbch@e{JDxuk>& z#l3X#-q1H%>3g?4&Q~$Hqc=2Ey#Fjo#chiTAipS~RzUu>B>nfXm*Rh1lKv0BzyDQI zM9Wq~6y-yiS0#yhwN{^`1CU7?h`JhjLMkn1jzQM%yu#e2YTo@IwWZz}XG6JOrme-{ zw3-haaHT-b#LX~v)r~X@j=n|EW2oz@t6Rv#ef863j2@=_rkBXp`Ep)e9+`{PI{274 zO2uR{>wSV_^CC;@)ZgdxX7O9p78k>rD1l!A`VVqPLEq^}LUBau+o<96vUaybHY01L z?YM%BC+I%j{XK)M?s-<5(zO$o4fc^?-}|04`WXD66HB%8o8>mUjte3CXp$(9rO#sVsN3^yw5>C_wuqtzS1fbB zDom$u-}WF>u0NIbUbel@g9&cDYu01Y4z$B9s2m)$&@Sd9m znQAKv8Lhqbm?}eXow;iXdv^9sS!fJ!%$6?RbP|d|1!bW+#V^b0AfjN%BIdU1!=@II zf|IxXb+r#@PadqWvShHqQy}`Z@xXZ}>hZog;(YUIg=6aivyt8#9K`eHZ+F_*OMR`r zz;a?v%8OT|mri}7$o5{Md>d2p5{}-5#MWi+ssrPRQff!+Nw;ecJcR+mOUYofT{&Z4 zZjsuEy)ae|UZbpq?Ups;3@%>Xvv>BS+w82fclM`awZB@mkH#z?!0iyXqluy-!7y>v zGTuQ^VpM)|y4#!jpD#RFIDHPFDk4E%{h;#(0Ub=Xt}oXpn1&8liTpuVuhsC9dwK+x zd@-N%3d=cJGB;YOMpHEtZh7P=iqy|2o_ldg`iZk?zZ^NUdiM~9K)ng37!@2;G`tzt zqJL9`DK9vS0|Ip-(Kqm6?tt*70lA)9OBG&7GQk0Sn^GRxyIP=a@RDE*gsTLHmYSS{ z+ihYizJBCb71z}mdHMy1|L1)tyb+)x&{ccPC z1p)n{2;Wsv+&AIog|s-C;XQ??h-^=&c<&pEjH`H=?fkC~bWg)YS8BY^$c1lv3MtkS zJS6dlxLLQqzYZKWV}z#1{+Bx)o}7wMaGjRmx#JmM5kBz`UPRDW6-?P?lN~@&0#p(F zLdb-0>a{q6;wx=s=d}oN?=V%5Wai8wSR9x+CAA1~>s}{vnR@4Xi=En4T$#GpN2+=p=-6 zVf^jlCgqapoqpWZGn~y)n4QpQyh1o#gHRtq7EkcnCjP2MYVAFw*Q6d8HZ>gX6l(*p z4+iby9|0~)UA9d0e>C3yFo1bL?s|P?eMcnum%B!BFA$Uc7;(P>+#yW>CuC=k8AKES zT(}+X`C|5G$Q?q!@4aIXhZE)QHNH?K)Sf=v?mK*B4zCp}Ya%Q)BH`T}VM(|=;@ ziNOLB$S8>ORm7l(5RZzQrDwlm!vtKp#SywDy(8)1mq5p#RizM7gmJ%u900<447<92 z0M-*e3FzGQa|Xk+lKn_&nTG>OTc(K7()I-6H8qp|VWx4=QuaB3{|d2_wy@Lw{|EkC z=$}vR)b9D^K8`LX_A$?2(8*)BJ7-^dI;{8TdTdXG_2N8U!rOQasxuFQb{_6aO!Xh` z_DU+t6Y!5e?$=9x z3_21z|D8_&Xbj0^UImm zjhWh++A+r0g^fc7U__zw>8n@QCE;1!f=^Y)qR)B5Baa8(W44bO);D6Pj`61k6q8*x z{eiecHY)&U z28TBjr;d|FIho31a4Skr^)-xn0^`N?#r<%vR*{7BGS%_z%l?Su#fAI*Ozd);ocnkG z6prENvpFIgSu(m#ug}_eC{Gc~0Kqa8QZ`=MziOZ4tRneVa$DLhWGqkRDY3V(hg8OE zTf6V^DGV+it@^*m2VYHUuGcR;Tk!q-WaORhNV2C;ZIRcGGje=^(_M?cc(8-PFR z7Q}B~OsH=j_D3WpGR$(c+l<8_QNER>cvGIi_P1tFX#6F}qQQ@>!w-P?*+ULlh|sKt zphlnuR;L?lo4zy!^#m_ip%0uQYDFbvHN36nvlLT^=(|%+`%75vk)E=l?QbL%G85oj zO27e=Xxp?zuYBrQZ9YRUQou(I>Q=xcK@+L!_BW=Ct|A|R;zv&7K?^|WY&#c>+DaV*Qi?&zos z7e9x*UUft9n|}7HP3UBUaeR!!y2UD~)SING=jxq+6UeE_=r#CH`=Z%NSf4-8N>~#W zyBS;uEGi-fd_8i3s`ZVA_oZG@Bk$O$YK^9JXxKt_&abEQ zr>{&5oyx$s@sfoF84V3aZhoypn2c*Nr*c(f%Fl#7YW|XY?fEDm#^&rgIA$U?#9le+ z^lux&<=t{al?Jw2pJ;X(4=@K#=Hu$%pbtNcufMvCXY~g#9`vBsftvos}07m zI`CpAO~l!o-)?CuMcjTD9dBB5Jsk6rXuN5N-<0i;B;6jDatl7&Kd!e+mgau6Msau< z+m5w4C)jSlBaP^q5PWZco_^KyWEPj4IOhg-dD2mW?Kj5`c+kZ~f7WT22hx@kwZ<>r$Km}ZZJL28=> zx&+jfuLSDalWc5oAoj#+98&;nl{v!2wIGEP_xBBxWH0WLoB`+;_DM!>cyCCp|IQn+oSeZ7*jzJn{2~kt0ksbuW^N*?_auzV}-bm-}TwFVeC} zti+-j9)MML-)eZt1ymCo>~>H}xM=tC<5+I?5+cL^Phx*xn_6XCFH3W4`_%rh3u;o! z(jO&Mj!_Zz-`0g?f2TE0vi?k6?sO>FK%!VGt{V)J8Y;PuWTNy7nl*=O4zIV`E^?q~ ztAq|7SKL*{Vvgbm97$XY$Be9_xM{1P{4i!1=TMtgm&VV+2t=YBE$yg$8(~Zy1Z*gJ zHkXYZJIUM)5~clQEf9yMeT)vJOf2NXyzcn;MPTN9ojj7LUra*%z$nj^_Q9axmRol8 zgNP_%LjHu7o->m+Ir0Fgx^wfOcdjq0GhNCcg?@QGgFQ%y=|^Q@jyT%! z9OG?-lau~oe>537bq%$eCPFnqa-dWc3&=#7*`c^;&d^3nN6so8VPvI2SnZE!CB*Cc zjni@*Q{L&OZJ!_~m$84-Om<`WQ3CrKRYj^%ioRD~YVYPg@Ie+HM5Fu3pbz9|oM9S1 z&Y}4(I*l(gTzUs5WGW}Gtae0=bz&#wsG=;hHHT>Zw(ct*lz{uH=)ujrU>>Z`0S}ck zdWjAhP`^1Ux(XFnwN|l$3|!hHeCEx&Dr)M)f8}+AGczzNoM-P-7^^i42`v!DJ;~KB zR#DN34o)KSM0OA^yPmA=_%XYQUIc9^8#lT;Tt+K1N8-$v5+{1e<1BrxoD_SaH!L;> z%Ghmp=bkc?iUMjtq13WuOJe?G89hu3<<32F`&Q~TZ&S4qT7S;xmX@u(HMftYdgatf z+tR0vj)j+G|0Y;8bv$`V)$!5m_)S^!j1ulIq9<$3fs(REnC7xIE82?A4&Q8OW(H!V z{5U72^YrjE!}?BMTi=RpplyYeDVe4T(Cw)j_ONb8PMKP_UqG2!zh7UOdmxOY+%*G5 zrg{gU%-tVWP_8-wXkE1 zRS7(_YED9N%KybydqR@Ge5K?Gn{$b0Pgnr*ipT7OAW!S|2GeP}Z)&1)s~TMwQbFac zN^}(VP&c=EsK!-P`^evDzif(ji6Fp#s5m+(W5x^5?jKReMk_vtNFz?-_qVX zc3Mf9-up0;0iA}vjDb#YkXu>WaZww^x}Uc250eEY1a z+|p>KV~Mj{-5Rqz(o^pl0#ZgMv^0``T@2|SY;sl`TP$DF&(@mR*Gsmz*DhDq+~EOT zZ`LtC3p><_pMPvkzc>l7`7$KZzBx+iRx!`u>2WT^@O*K}GV|#m{H24LLIXPr|3c&c zxFh-gvito7>HACk_ZNllFEih~)c$m~hguW3fmISeUw(VyUg{QSDcZpvpSBJ+GqNOU zWVHE7Kr8*zAEr<}hSfLK3>8D58Fi$d9^*{YVxk_Ev3_qwNz#Hu(4tb9p&}B-s>PXR zc4c@f%K|6G*&n7x(}A8wJ4jmdbgW(oqt&(oYqoVXW~>3Z@IE02ZPA^HMk`3N(ukp= z3g*2z30VJ~anIh0el}=`KElF{uJ*H{yQl>F+nK|ozizOaE$mp3t1E=OF5F#k3;mA+ zeg@&C=azL2c?sbTv>!{{TJCfAK5w=c|jhEO#$kZJn%lDH(AU*RlYe;zBy68 zIa0p)-K8LA!pj_*^TyW^gQA@5n8Z^}YMVBun{TqXS-rUg*A&az7*Z2V> z90|kwVb~(al?i&>iwj_e9%%IiYyCjnp`Z@gZ?9X@OEROkO0GY&{foBon8D#>rFDu{ z*vNr4y>hP5(m-B{Nbu>O!PPA7z&f0Yh>o=L#w%!RJucFFuU}0&tRvImQsoP$$}Fw( z&b9K4t9+?eeK_LARv_ec%%aqTv{ZEhIFhE{F7XA`)1RzH2^c$Jfvf1y2?>Ye^joDm zywPmL?;c1JKoYbWq*q}@m zh-n1@sXCo!z0QrFnvifFu(RhSv*$s)nOKJrOzL&UO|p@X0OE{bKP)dk#}{WUKeLES z(|60#56hV1(LBO!zbEt~9t~n24URSI?C*YrR4qP#bcn;fUQ1}C?w*-2Z#rY%HD6g* zvFQ9Q`K}4U07j5Y)c(wwofpU>8txS}ByAty!*a)XHfFay`1nFTMT%$*B4t7ms}~9* zLvF!EPV?}$eJQbzTM2$t(Pz}FQst#ZIqvSxXel)mXpWIJ&yFC9u`qPy2PXzv9`zeJvG0csw+CU*WJd$w8vs}R$%b;htU#)G~UQn&46#PoluaB z)1N>)#h^*YKP()iKr~KWf~^1;9jZTxgHG~6HY~sCX)R$WE%xo+ z9Wk6E_Bb#mEU;BIAsC@J`RsD!MC8DWA=8ZNPrmgBvSI)oyT$)#4IDrr^!^Z5Q18cAF5tOtY8p1q!kJN zSRR|Vrs|{U1;@VAOMbaEV8RB_VFM!5poH8Qi$mxYEjz=eWCk8My4Q{|3?ksFj7MzR zU!HS#Nex_;8^Gv1{~hc5x{;zNO#*ldp+RXO_)m09WL;C)KRNv0gK8c1(jt!4ySUpW zG3p%u1SZoM_~1Zb$IGJXBJ>Gh;~P|NLG3lJgY{#hB0Hc*yG2BReSO)107kgepMGxT0eKuyoK>Qh({3Fd~B_HcLj%hPizU@hqidw z{zY5Rt-hXs!+E59uSmTs*v5ieL)LZFkuQO4n4)X`CtN&#ylT{mEe%`L=x!NTC~s6y zcCx;1x?Wv&y0tL;HDB^KFfct@%z$xIWVk%Q6Q=MscN(moDT7end`tjAken%#wIY@B?58a!!^;4xREgmD7LHR+F*w&f|1?LI?&)6 zd5vRf@rIHoHGZY8z}(10vg1@JX=yV8gexR$?@^3oDD2WNH=`Ly-QW*Cc8Fkm55WT6u+Z{hJZ|{Hm7R5~0BX_{UzS53j!-ChnIu?BGe9NY)%kQYJ zuA8&(PF;J~tuMjrsAk<$gUXhqdeJ98DtOdL-EWr!>l$o?mZS!!*Rs!4zSk7S&iP2j zhkTL0n(4d#t^PI8DBHd3$kYu(r)T}+5!$*zyQy@#;^F8qyu-0;sb~`$FZUI!%_M6d z4Wi9nX2=PBM}2D#l|3-C16yh_C-0chky*<(s&I62`_tW)*^P}otsNa(Y6B{YvhKq#PD$KUH;}VRo>W?M%nZR_L%RYxHOz zUk_VK?tsVcUl~6qw>qjZih#K7(X{?dTMq5nNz0O1eEUCql%+JtGrGV2(n4LM?`kY+ z;_J@u_M6{C9SQAPJkTbjz8TJ5+!O?K={@U#P+R6EmkE>9+!P_$|H9h8V0SEWjZj{YXx)^&7d}?Hg^$ zlhXI*1sTO})^gVtAhu;;E)d;2Ll=fHIW z+_e=>l3e{x?Jy@rMR{A`E~RSZjSDY*kHkpViZbH?SvfcfDm_l^Hy=szxjOHTm6W6u z1hEH0G42^9?DfKFgjTVQh18OtTG9t#!$vGTup zLJ%5{AY<-13Oz$}#Pd)U@&OVu#MzEgoztclUZX5XXUvP)0k)n{E8C1m0i)aOJmFM! zAgntg{JrA>66Huc)!JeM$pQS$l0(1>KddIm`DU$@P_CyHHPG>5Ee3C~OHiiDe41mT zIO-*cx@&{DazD^z*OYvO91<&2QL$Rc;i+G|1Qf`XXq?+cZ_tDl6jng|P%EUN0-qWi zRZULuIA4j+!bTAYw2!FlSVKSOUeC7-VmVtNKDS8R4T=L?g;JnaP)B$9c4 zXY)s+lGyEPktP3Yg4BL-he1~#(%bX==RaqiQk~0O)yUtz`7-@$qx9crog)A7tn&+g zYwKv{Z1fKTBnLBhqkkW?7pVNd+P!DSIcSY#=_+;Y^i|uoi1xY!SWh|t}}qn;~K>?5v;Rt>r^{o z2P+HZ5btfh%G+(H`S3x|sC1hFGMSlNYkZow6(Ye0OJ*u|n>|1NQ ztL!BfU3f1kQ$OA)pPIG8{+?)qY`d7QwU?jIkjRh*{>lYgrgbSfEB<#npU85q0(sIQ z+`5e|5k+;~RQvUzB<&mTJnMsl*P-Cf3SEhG^G2e2%x?xsEH5+5gQOVgB;I3$zNR8Niw5Ty= zzkxohU>EZfQ@Mn{HugtzTc1$%GF1-zXh+;!KbE<2Q31|qk zw-PvLng{U_4T{qBLY8t3E#}j|II|~=)R--;Etco~Le2;jYlv)_03~YygX^dyNh}H4 zoa(EUKE=C{f>4$sTclKi73!l3`ReQ#m!g?Qz5P-S?8_rv*V#Mb?4n3}aWgt+!-z_! zz9Rd3BXU>4tu$O(XL{6g$6R5N=hUswV-jLB2&iinOF^EXSx!W$W2lXj4s&? zR);BZObdA!my7*y55&dFuzB{sxrkDfjRxQj6;PcOJ6undVM?lnxlzO7q)iN=3?=*( zVf)2Ou5Y*-3A-X|6}}Uc36)f_fitn<^&c^|-iYRgd$AxgsKhVw z01H1@04&VHF1sUb&$XoB=Zc)IB9rnoD~=ADbNv~peTyuqtW0n90i$H8R>y1R#8&3t zC3xI+|5oxDb#3G}nw^`@fd71&pd-CiVP)By?3*?keC*?z z8}m%Yh|UJSpI!!Ye9WI$kbX+a!_go0jbhy+kj>aUIpb;tP?%B1)h{0G8B&XMUPqqp zalE!T+a$~4g@n>G{vOWG)vWGD=MLcOo@$P1aSrF1js;A?}A zBm(T{jAzg;u-n71s^Rt8MY3C~B*r9;k@rZV-4N3tvtu-&?P!N9$R=Xj!r8&iEZ~l@ zi1VgY9XRrNetv0n8wDDWbHMTfX>KF*g7)b6-{GbW0$$j2czl=d5;UU~0-l%)&c=x6 zSls?U3ut8}b4iY<=fhfYDCVL7r)Kft-=pWA?1D(d*l+0o9q;MD6OILA*3Nj$o_S&t zxOWh^hYl@NG|w%TO3*I1m_HVhzLgOSaAE{`$+7haaVI>ZNV zH+ML0V>nMR=a9orL+b02?ZE@`VeQ?&n-@6%J$MvcnD{}%b&I0kp(j?P)OgN>B7(O4 zJ5x@=pEc({V!Cejc-GVpAfL-9kGn8#%}WpF+r5TU)C(om@As9xh`eh)c@LRcAR_B> zpHr6ocknCMqvP<6@-eBVL*dYH1oDcC_a&B zi~=3n!y}wieH*ULt=(Z5yYK%|d7?``bY)FR1qW6p#;!WA00`IywYU92#6R=ifQlcS zwiyA&jOW0di3V-ngI`HzNzjYh2b-3C(i!di0Gwp^Hy%D4ggBO}nZdVqc5ax-gBX0n zgiNrw$l#tV0V-ZGxQ&gY$y>U0+RpH^eD-*zW&afb;mK#cMyy1!9zzUFA>$5#0GrQ+ zC=+793`D~+JI7_f;Sz>)hUCpc=I5poVCUQAXF$3Pv#=8%>y_!V%s_Lv;<@%ga=7+w z=7+G$D@K48s(=XR5^h<-C)BS~C5Mrtco9-e(Pwx+XckVI<1i1HZ^pe z5aP|s3GdbXc4&5Rmc`$q32jdhiAG@e$bU#kTp8~SO`M!RditffGRqmtl(7KNY_iN8 zyGKwVZqeQeqrk-xiwzQ&Yr)b8z11V*;ls1@HYXR2C8fm&4LZ_N3;J99w=s#Jl3C}C z^x7I`N@G`Z7rK5Vxy**YJZ3f164%34W2ggb1^W=!HN#^IBMRkWFk`oP?T!_-=1NY; zE%WCiA~jC|$^mE82oZE}MuA@KQKDqIELDb>YrrNz4n8>~Ply>|i-jERRF*Dnia3p8 znr5os{VuE#pjAufGx)kU9k|CnMLVq4XGeD?tnByA@!bzmZ;d_JuQwR|K&#WKgs@)u%+``ft(7BYE^-fm%IS?h3+5ocX!=t zv)wPMe{!UMO)LL>{{Ek{`usONl>Zexx9)&7kMgPIbv9Ba6iz2UWU!LS(Y4AcOJyhSW8%tv!yaQl!Pfb%WYf&gc^#Zdhq8mfu$Igiq7ZtnS) zO|9Wv@6z}5t~sMICNZE$e>FUV@)-tGMT>Vu>3+Do&jxk!xOhcZ`Eq~Hhe42b8cteT zmiFpidu1Ya-E^Gx0@cIRO5s8I1!Gingt685LUzem)KL;c)$&052NM?ii+tu6p>Dl$ z#mR!~C8*#Qxf4_0Ktz~#p?21EMFy)vZc<-L>Y_MOn$eX@6@xBXBqp%V#aTH=WtANH z#X(qNQ8cn8S8L8f8bVE@Dyw{{Rf$C+%}QMmrsv0{?o!J}2GbDOY-_pN7hR9(R&R(| zw!WB^DGj~jc;XmFh2z4^A#9ztL%kt;v)Mj?D*4)Uy>=*2bV-c~`hk(mZezimG%<5n z7k#Y{hSAa@voO%ypmdArx+ z%lT^oW&pPt*k0K()|4;%CRBK8>M^(ql82?V8Dver?WfjcFTB3+aD8HN64=WJ5|Y&O zb4kVp(cl?|;cR`W;<(c|>|j`U=^!?PX5IqiEyy$>l>4Y&4s_xWGN@Q>S_Ui8o#v3G zo})(27sIj_M9NhMsSx>XB9m}So5tE&|94Ax67G)6Z2Uom&%>d|;ri#Sn@gv5>a5JX zm4?P?bsJB{sNsdTz?z%(A+AT$1(q;VM!|UcVl>8EQm4ne{%aqJm3Fu;nKMJiQYjQ} zk5T*Bl*gj{)puw_&7M(gt;j7*(Wq-+L`oJtqo(3bdV-3ZkM57!H&D48=Nxn$CDD9x6Z0{(JxD!q-j8_ofS3B^CBnF z?SdJ6*N?tC$kIKqFF@Yu(M2AT2a;h|LEa%jaULZH5QD=a#NpJ#`$OpQZr|P=yR+kS zb051M0Tuk%Xk2Ii%RS;>8$rC%3lW)uyD$6jw_Iz+;q|h$NPheD5coE1=T$@ToG-=` zDyV$}zn+K1{~2Lz3NhRJ#{X=ytIUm;@ryxlN>_wwv|* z)3qhMF<{zZldbK6Y)%)`nky@;Lr@Fc>=F%OeDyeP2nBdP79tyk>tAa^LT+(2gn}(d zd!W}i%M1qnvcTy}7`KpiSUFTk)>K*sh1Bv6f>-QFXWUHWZU>Vxn!NRzKBQ zlWSs!|Kd{DHRtP(#btO`;9?+F=l8X{$X%LFUN!91&`YF@zPb>EQ(n6;S#Y~gID>%P zy_|sA0R26aA0`m}!>jZIkWO)vTI>@2w31ox^=OkhnVvppH*%n#w$J2IUHGHVguv@qY{L|B>DQ`;Pf+Z*gvjqwIYFgt}obJ73TkTZA<;f-Jt)I@aca9&W)=>yK443 z@t9n$YneGUPz`HuNA|ET4a|(xR>LxCKl@rj61~M(K@t&*x5QQE2YQ99w>1i5igokh zA*U5eRpZ13HQEUZq{(VD#x0OYm7F51kdm0a;1fW)>50z}OQn4y_-t``G$*OTJr(60 zD_Txva+r8K%uZ!8vAzk^@j4(ztk~1yX^s6TOjtR}hwtAMKgTHXk~a4tYnYTczZ^YM zdjY4*{58y*6dNra{sc|vJyCZ(PdCzaDEuLeaoujRd+dL68B_l;?6Cf;_5*O5Z8YK& zyOM19mR#_p!tmfX)VY&aHPiKcWN~-N^8)`O6Z@WwOgGY8C2rEBj48Okebzrt7J*w0k$71)xso3JDyRFs0PiRqd+sT%Rt2 zFM7g6Da?CMPksIgcLK)&7nV(6G9F7Zj5Y}V~RpPkfcwW7gAzj+VU^x&Qurj2$ z3PYfDWJqAuEiJA?Azey8@eF4;JR7@sWuO{;|54IWc#AB)mbe57xgPQ;=#tFK|V;TqPXW*2@Q(H{!WgeC*a+T6USca7iH z!Lg1I2eMfJWh6$nV^zfYw1Y{avYF`PX&sjvDal2xJe_ZzS#EOyWl&8RP=bYrX>K0U z{pDNe=SIe0Zatk|V!Ll4l|G^`$(BS(Xw5Gy9cAhW+(-^+3%R0kOYiz!G05D<)+#Qw zYu6fR;Xc2WB|E}cGM^ERMaeU7W_;WklWr^ed@@-{-oe9|?c_5W^5B7|>JEZPpVPm; z)fU4oV)!Gj>X2NSp<(b zHO3x;HPBpBtRf%W7}aEu8avfiMQ>tGMrh>^OLp`)6{DW!qK>k4y6?BT(599qm$dX! z_L&`n;(YhdB(_TZQ%y7-ZfWb~;Gk%Q1$HRe)q_N*){G`Em&_EYAi^4#8ekpIvA&rc zN&iykH@YKvoAKPAO{Gs!=>6^z^i?HFP`q_WJw2tZ8t2tDuZACJyU{T7=rs+BV+%J+ z9bw9XIV;`%oUbo7^`ZAQ!3xSJGIGBc!z9!6S|efZW9n#mTp%&j&0Tl`JjJ;*ZZp@N z8#yikzjXgOX)R09H#n>;=KHkl5$eNc>P|_iO!T!W6+!q&UApKuycfTUFBjXKO_5>? z4~?%CFh+)35vhgi2$H|#0`Oc#4G%(`WXu-6iKYesnJ_G#o3LV(=5Q=3QiFMl7g6S{ zex_`zi|&yMm6)OnWPFL2XPLe{vK#^1e`GD(_TGou_5x|r%EdgaewHyoGOGnD&x8)f zWbhTwu4KgUe2j7?baZQq15fYri`QsP6O!Jm>*~odB26kIm*#B`6>rNLjHBsPO5<0( z*?VviV|*^nyz!KKNqI3j^CX-wpR`5OhSv9RX2DH=6wAMXp)_D5HgzK%<90p`P-@^j z%~h<3shz~`Urg2>r*hD9Cr7CN(D(av(AL;o?`0#|x9bM0{z z>E^}~$wII5ZS2|ocI@l?EEagjl#%5HZhi!FXXQu*O50;8=G;-jm>&#vabLWa@S$SQ z)FceEuK2TuN5V+jBbu&m)jhIq#eGVb^dWZ5GW(PZHvOq5eeK*23nkI8c%;(388E&4 zV%Z~lD5_g{-+Y&RQ;O}uPej`Q$!5_7AMehyO|E_k3Kt32rBHb2ELe!Y zS6~a|hPUd`u5l>Sr7`FPCPJ+@+jN2(*D_Z(JjrJ6{Uy z+s8-9uTWijv^i8wBvgd^aE2?Oe${o~&bS2S<^;d$IdhZMUlC3_zX$hIg| zM6%p%SbvF=;kbv-fF}An+M>x>yB!MYz4TNx{HQ3XzLtQ$rluGXYlFwwStrV?;x#TFz7e0vRVm6M%OVoXaT3b7`n=>o>rd>59&Uoj&AUIzYT4#b+bH@oQFzBmyo=gi@~bD)yn64l;8YF+NmH|gH}$W42h-(^z{q3$SznqB0+QuS+k64V zD{jRsQy1qF&3s4PPzRvJJr5cMhtWc!8Zi{S&~xo%WFN2oPQLfEp=G;wpNf*s>+6U1 zs_&9o4Xndq zMKN?p6^Q9e0!qhgX|g=VmZYRwSy1Icm~?<1zbyV*cw3}%ZiH#s!mYq(vB1~~Uh1Ss zX-*Wac1ADCtV;lbk5Z1WRR6ghd2UB-nS7#;I*RQ}gjY(jY4|Yvm9KWQFS>j zTAxvMo^toS&?;UNb%G?64%ZTFpj2!ngfQl~e9^Mo*>%5cEMVC4hG=n#ek=)p|F%*Stopl%_qb`fRqEpp7^`ldX z2H*R_#wzg%RV)DhkWWRPUWIH&vB_hJVBIw+&c{DV|B6)8@$W}a6&|6M#JpYt*G?#u zN;u7RjFS7_7CRP^$zc-?sF%rI8VH>;kmBa*><%X>_pUx-@?7F_Q5^c32{}t~o`aN@ zs@Nd?{9}F(P?~rTg{sJ~RoI13nIn?st^AV6Nh zv8zmbV$22w;y`oa_3EHc6goH+OZ)@n*C}*R0Jue$)@<1Kji%8x&1*Gz!tVwbu&ZXH z#~putgI8v&KGqJMB?wKL=LrB1-EwmZn^J6DTM(vd{bKBgP;bj$D$rXxRu;lkOCuBd zCUf7Q)sQN|l0hjb-~|>jQvu=1xMiR~deE;8O;7{!!@&%!VhH`IeA%aAS2U9+!Tp5# zvCg=6LPnKDbF_U9Fm-zN$wvloWie>|&<-`MsQ#akTbN5^1F*Pd{=>DvB?NyyS*Q9) z(izXa2J;oSSQ|1{qZO6ClpfS=D`_EK)3{O!vZtz8AjaZI0&+4-j1hj_ZRw40?@KM-z(f&@I7C231Slp zJBUTfQ>_jbQWdW5CUvYH}vMMGcljAM31xIgiUZm0pWoI=lYR^eBC zB?t?0XNv$PP6@uz>N}V>#?Qnak=jLsGq^X(?s1qiINi`JW3sK8sbF@!<gR)ho~VqynsHeQmMIsWo~d8InyFmKd1P)y zY+~Oa8MFC{p69inD34zJKsDrfK(_fpt1@}Z;C~BsW=!-8ko)jo1w=HDt!+^L;vE>< zgjWdJN@~Z!XdYD8X|ar33_F?;xgMNT5qElzU*C?lF2RPH64M`+$y&mQKki20GOv8Y z{iK}pD%ar&sj9_uyZez6Z%$nzl9V;R(Y(+Z2oYljoWRs3;sW@Ez5X>P@cfrXeTuf* zfZZ?%*22!d_rl6s!Rc>IjvQxO)so^O}kn=o8*Ll2A&Yb{Xs*S$ByErN#dIsR%`?T|@Vwgo zcHoV5%Cd^vpRMr;<+b|!daC`;ak$sT_9q>LpK& z@^+8NtkRrDy^e=vAqaxa%k0L(zIQk0-tL63Jcr!Y{fE^P9_9z=8$9_t8sEKvW$4_& zN7%10Xy0H0F0*cZzn7LlDbe}`x$IL~O*HTQ?RVaz9l7>bEH*x~WsK~`Rhx~5o)7T= z82XNTm=DGNT6_5bf?iXvu(sD282a`*t$+e!CkoAGDy%ryBEX2dvRts?bccT#>nZx> zygb#yx|^+W=??c8^5%o3k!?IF@rGc6dQfgfY}0wYF$q2~0uYcK3A%)c;CyKE4xPLz zhFmbU;C24VvZshsS2ZoZlxkCmV&!a&dR16KGZN2+BFgf(V1;7eHX_uhV0kQPMk^cZ zLU?72x42YI%bZE*QT8z138Z($(b`J!@k9qp{*1f`Gb)T4a}jcadRs%LuVfk|`^kvb zn3S&$NeTUxxmGbbwoqjOv!XgiDIzTtDbW@i1YY@aLQ!9r(L1pf8pA~iQFS$%3T?h? zEc&60DBUV)IzLTu7)rh}w?LPpriZxxKm=y|t$LZv0d}8=zOrAP&b39KOCIdPkCr@% z&tsDP#Z=99Dr`3-&;8G;9Cw9UN4B@??PI@FE{j6?f)ZX71kA{mJ5_S1FxiXL!W(~L zR9uU*lP5VTLs!6j51dLIc8mQc@#_XS18z_ktOPe~#9wDn^?_I{%RUuRDOWLxF!M6A zQ`1gY3Tw+5cQG4t!P&<}Mu;kTfx0o+V0BdiDLp#|q5_LDpj?ASqBK*{NuyD=U8(~3 z)KqA)PJd+7Dm1phv}@Q*Die6J@po>>VTHO>b8fivL@?&WK&A^G;rJg+OS@H+lwu8) z#cWV|^s$uL3wAKgs{A4ux8v|imfSYxyw08zIRc#BmPfJECzv;&xKqy~m#eszmvX31nV?5JP{Lgj zOKe!CIa4Pe&1dW*iWgl?{}n|S({<6*^+E{ko+A8rmLio8EFGYwx|#x?dnXa%Y`nnLp&zc zxXD9K`hz2($Gc(1^7bjjW(0Zzsv(3?t4y?%%{j7P$vnh`JnhWvq?zj*h~fpEXG4X) zkA_BArC1M@r2$>(j@Ik6&w|!FdI?-CRI>L&$^7zXQ^6h4qCz(ei1f7m3SU*h-9K5} z>i*@VqU@v;q>1(@e|d14ch}+lg=JUy0`pZt6v>LQqi|36Rbt3{HpBj&t`BfdsI9BX z=oe2s$yC#N%3JR_9oSX*0QpwF=lv=^*uA<2v4wYfBoKWC+Hu?$Li-;6)_xI3>!Yne z95_LCRbdx~Z!~7vR}P6HNs#gm(K>>h!UpC)M8^_m9XVt)qV=ZBFB>3MP8(ASQ9DA> zWe`LIE09McCnS=8jM!QRoxze#g^R&G{@!vIqZuv&pmz@wk^k|*RAb%AYHzBxjM1{c zzjrl#!{`2b!B(yx*H6m*i(*HzKKW9m*DPvx0_StWK5rxdA-~8XhHRt&4<9g=KP9gl)aa?8Kee3L}ULoW2 z^>yU)=(|yUTP-nWG>bUb`A)eSskta>4&M>`7G+Z8e7XsA6BRL%4I(dKCfPP}U{J?+ zP6$_P3(2{I}?2aBbgpimDnIpFkrDx7#soQfqX!${~#6T1z{ z5cg5&tsiY8_AJbE6zUXi^VGe1>iY$oUYY-GiT?nSU{4SP;*<}TninU2+&@@ugOvJ3 zNjq#d1|l^%C#mGCw=sRAKm;x<{0Mx(MU3{lBOx@n~uovP!|_}0vMpIBdC$^ zir<83%{jKE_&kw(pZ1vIP?>omlEXaI-95{;J$e^S;vOLHQ0S8}AVVDnMQ?*KqI73+ zKmc>XN!XQ*za@5mE<{6^n9C-P2(6wAo|irfN!Fb556;g5f?DMCO~D2K$<7|=D;gv_ ze-3AcpnZ)<`p0NSue9RmX}{nbZG4j12qB_~kLdr2>Q7GbOHT1uE?L>^+$JwSNv;U+ z>=P9K0`&h|iNNw!7tM)BS1A5PX#UIL>923U!2F$xdZt=oBJ59_e3rj?u#721sap{jP}_j$}V_EQe~4|yJzg&L1O#*+j~~GGMY}IORngApg+Vw9d=*MIWmhO zjJ)QA{@J;`$eRD!^5tpu2~{jgzU@SrWHw7+tj_-Obf}R2)hjl+%#BSt1d8LyFpoL4 ztSxp~o~fn8(%hTt6-3nH<6N6cjT9%$K&l>a(&DMbP(z=Xz|PY>-;$q>+qrn+xZoI9MCq4)&Uvcygt-mVC0+3eodP@#uBMv_zEh=4P09Vo)xgBidH3@Ro1A_7{09 zh!=jzIF~7uMGj%&)3R6mc-_oBstdQABUAIp#A(OkyjzjZgbDXmGdH#N_!&WL2b|u+ zQ*csh(ZKE`kekdZ_T;)BwO8#i)1l%oy9}Rb_S%55lf5P|z(Orl&(JR`0nY zrQg-lz3x<97H0J@mJF>Q!pswOCedI518-xT1K%m`w+C}b)A86my^xZtI?lP2^4)I= zlaL&WlLEmu1|^CzG<;@gw6t*UDimF9@`rkn=sqFl7O89!Zo}j;4Du)jz$J>&urq@! z^PE!#yGm1(p+hsf%+_yNjLl)J1BS$(vuub^fh;zByoFQ204A!@dNrcFW!f;)rjmWL zMQ18L>mOPL+vOjeoF)ODH6nT>m@?xB1rMxc8j)n9hGgaX9Mev7R=ujyO5ivT51bM< zZi%!*=$#1?9f?L(N}Z5OkI5tehj;EJp~U4q*v1fA3$+8>G$+Gi>JWIMc3JazTdMa_ z!F&tqYQhoOjoY4QBC25zK3jZl7`xg*6iN9|S9U>%e}PYMY&?#{!^Xv#q$3J(3hAjp zhcPB@5c=rfVRCUz@F+C0sLC_RM9~iunEPq;gP8xUzai}Agz%c-Z2wt7=m&p8((8*R zch$;%VISXC2Jc(FbSQicg)mQwX}e|YDy05A9cOB*%Wzu3N@H0j3JjBnrByjw3?6h} z(yoPzO+;$8f;2)42)SI1{vBo-%_YenE3_zQs-~|I2m~->x|VY=;`Bp=j4ch&o#d-e zl};n}ff)j=M2fV9itmu1AKK3Q=NL-lJ@#&L>U5Y$LQ*Ua ztAjG1aBW;|R84J405)4>d9B|B|MBiL&VMBC686_GU&8;YvHrW|N&0{N?o`;$(Z;~m zSl-dX*2v^1a^!zT3U{l+xGSl&=w6bnODra*vKCV|jV-3~Q=Sty0oxRTY2kxyLeu^c z&n&Sp&q`*dr9I>q07u(hRggcbKobz~ASRMzWQ^o2ASgI|Nx!FxF4zlyij9T8(DBO4 z1|(0iAG&?ozB>MUd;VeNSbcikHb3tl-{$cG|6<)T32s~~7$s!T7bfs~c`Zy)qd!#T zk82mT9{h{H857L)l6CwsKd$F?-+{LEMoPVNA6a=XJmE6MaQ8B|nx}q8Nd47wG;d*d z3jl$fQE;j8lR7WKiut4!iDa5pB=pTJWqyDPpZA#=*y$|ouxIgg08h(fF z)KG^a1K9YQOl9Y@o?t4=yP8j9u%dfDcmJf1q#Bo$*|uApDm`6loDB<2{Swd3H(%x(PnziX43FYhGcsc7#KWGZx2Y^)8AeBqmqtCDECFbCm8rJh zWj;_0VkJbV8PMpNZvSd$Q)s<{H~_sGi%Qv^2=`OD^A8Wwh_Zx_pD!SIfGp4?rWV{dKoVVh^im^;W%5TUNa4K z`zs$|iWQvcLP-G0+4BykreD0fE{xs>kT5x)bx%E5`$QM=H|-f{c{6<7&vxzQ zG=QV1h}57{i{>Nk8k^bbb-A1NmY&X|&oJ=?;_Vb3mh&lwiyVY*xnx~^cs-8;`V+qs zgV?ufDWyEBjPZd<9HC0SvN1CQFVBmn%+(%~*!(=4o^c<05*Q2~-_ZypvBPkCuj~;^ z?it+mCycGa!&;;LgM?0Au4f&z?v38o&i+qECvA_D7UXV*01ij`Xsbn3?U8{T6xQ5u z0-o#;p17+@cRyD`C+Ax2Tvprih!7^x@BNiJKM*HajnfaMk7>L5IS-5BT5b&N_9Ac# z$(ooDjs5vqzw~EL7_}nP=?r^oG$(B%-EKM-rYT%3jDs6^Y-Ei#`&nWH>z5+~bXOTU z>$k&1BbqJmuaCp$k*$7QJQ!%X8!rLF*w^OM-IqgSJ{UP4&v%x=C$4lOAgzZpmet)6 zT%{e!+p4Z(YV_QHoehx@dbP%}*pH9BZ|`-W=ydI7&zT^jVGZ`%{pBJS?*{;PazVi? zu00plStp2%F5g|2<6=m55Woqi^0z*^^QG=m9>4tp3fptRywfQ61l$!Y? z+J<)st6u)}f4RhHYDge|F=6c-uv2@vhVIqbZ>9cl4cV=^+eGvIS?pycg2X}%G~E|W zWGSg!BFN^LTt_F#;6g;^+N$}>H>Y~@2yRi*MZNU|Fa&zax+<<9x=7ZEN1ZbbwTUnUZ_3K^d5y%nlD1 z_LIG(Bw;`8ptr`=%77-REk_>IKBv8Cbt2Y`;XWP;wQ^`_W_9z*{UhCC1>4#wYk_ zmms}ID?y=#71-TFpm75?=NN7V@1mXIPvgcNc*#4-6(^?at>u*zkfMGk9}#!j7LDzw zv>34PF-?s$;m_K0yx82pcYc=1?(CrwpQZMBDo*a^3@`c75*Lh8BIHPUw2B+V$3x;8 zh?K8%XxC&Ep)w4PsKjav52(a?4B_bA!f4jc5IK+_AH2`jwYA;VnTL!UNd+5-+BdbS zT7Tvf%bK4CICO>OYqXEXMS8U7evMe<(79F4h4Xj&b*y4&6gxYCXiLI%R%mHjsA^SO zz^6fU2|PE+B1dEr7MadyUR>FmdVQ`tU8E|)XDs5AU=3?7xPJ~M;@Zgbl5?U?2ek|z zm#m6>dw*?7US6%w%pm_nW{kaeUT!~G;>Yynl-SJ`ZzFQeYV4lY9vl9QaYuG0u9p5& z{nU*67GRWfWf61Cub^!T|6o9+KXh@+xMNGN z9PN~GN3i8j|9UK9lg%+0xKFnkptethVl%9Px;>^lnm?PH)M<-bwF%Tk*_o}Le#s-t z_Gjhc)gOSkCk!6{PHPts?--iOs)Han*|A~RCvH=T+mwEx;58k%-kQ|gGvvAXvw!#! z4CUtNx3%WK_wp=UZvE`B#k3hDa60Vx8y2O9nTwJyjhSn6gX*LI{HSGP+v59X{b6<# z31r=d`3JJfakl5*=L3N7 zAd9dojhm>khFjR`?hd*~ObjIDh3#j9M#CsxSH-&CsdX;SIhmO#=QU-R+4sPFGW)GZH_O;ED zOLm8hi&0;1wjK{zOuI2{jB`1&0DfeXXuutl00kbkrR3-J0a223L>0dn&Ma*K%DBiX zB=M*t1|~S5T@YjA{txC%znTA?njo^b>A-Su2J|d(mD)b`063a1Kf7oM1`=z&awlI(&3ykJ_Y zEeUp&5H&>ns)5z{k9mVW8(;PaMjpilB#~mI_&gl|u0UDl+Z^bi{-ppvb*KR6uT1gs zW=nW~+qg5X#M~f%zeOKl%@MvnKu{;&6l+- zOit%4a|Nm0Ijc9Y8!#3x9_J!q=BVCDtE;red!kgQ$e3Yt9>OW(JWUTU=lt0$H4L!E zc|w=SO;DG|u%*yRX>r3e60jzUSF|_N2lcCpH6pk1TvG2b(kn9k(;?9wDg}*!75Nbu zluzqp@zPSNWR{B?g7h04i?83xmRyAz2#H!U(#AuLc_>>~_&IaVQP>uwaV$!%cdNcV z#|caQtJrbjOf?ZK(xHqfPPnOR`yAv28D@s>>*6KJH~s=SiBP~biP8rV3Q~fY{2neq zERghgnHCMc>c^cz(^zR)2owQ8RtO_%U2^hM-zebDi5~ z#)FFGU;enz^MJi(;AV)e&^ofG5X-ob6Eo|B7;7`@O|tc+^%m2*DeFzH^`*_0*gET4 zTVX>Ee++V=zh*|Ee79e+E4Yq=Duq>KPPRSr!gdopg9tFVMo(X+O%kU9{MK}Aqm`P-tzj#Kn z*TEEXmaF3>i$n_6jy2%I=`76*+zX(?IIeOBoL&4j5Rj1T@WQ5@)0_ls5oAb^423M)Wj&zg)u1heIJoa6B=1JD!QJfo!WNx3-q8+ z2oVz#FN9yw85el`BA;rtB>u#xrJw8KC06WkQK^z)zMsjrWsF-U_d9K@;T?GqX{=<3 z84aKg4PuX7wC9W&t0usj^2!ba?Es&n?6hy$g^g}N%4~=RT94gvkKG1#+Ao@opj8L% zYD9}W0(J*X7mU&d331Tu&Oz6|em108HE1_4u^P;QEL4jcMXLz>R)h+WvRI>v=`&Ge z1ur79PNHItw!f(>xrMop#hN)rev<=k4EYHffX93UGTAmgMs- zO>ydq_1>nf%0GIfqbW(A7<;5W`#s73Wj91U&ZvmmD!Ej^OvK=v%sfv|(5 z8fgmFMX1G{K~0%gr9pJ;WW}n1O({S%0^Q)O7^%#^@f@ftndC@Wp&OncDz3qd(2YoK zA~k5v>PaX|l?c9&4G`qEc*dKSriUc~lbinl2qK@mN1K*oBwFN}V`5ik!KY()bVq=Q zGNm!kFB+=bp{-I~<2zLF71sW3G?FCDp{L1+sK9rhgB3{t30|iVU?&oT1e%yoN>LIH zEuIh{8a$uSAR1&mW>46MJr+*br#Y5SFbGNP;GmgI{3Pr{kp|aWh)x9%2|CegGHKI3 z#8OM~`sW5yxj=GF%UAz!@Olv~-@@wt`awqhe6{&OO1*{2ukr#H;*6$1Z4dkVd$O}yDK+PQ)*S}~S<^a(Z!?jPmajDaWU^kNE zPLAJq{ep@=B%}z(OHDgmTBHgq!M1NVJZy!eV@d!9V?xvOtZ0Bk_cv#}j#~2>A21SA$b@m#8^9NVstD;D}yRSnqZ zs3biyy2p7^Y*$EX+O#$gH{n$xh;s1V(ltGz3tzcKJ|T3gqvwm4DjoWH{xse>bZg`W z$UQ*EFJx1reEwPXC_Nz6FS+q`;@UxQ$wz7O`rsG0L!2G68|QQBl)Q2jOJ~!rSRHk_ zA7g=vuSuj-3zo>^F>npyccjY>396L4s746=F_22aTNckrt(*S$wG2pa!)Tl?BEk*f zhC@y$f+oTYXbU0=dB&IYUtjDp0bgJT_r#c?1VM1KeaaunMI2HK*~AvSL97EhFJM(e z^da1;(1psR!xd$ym2*KcsP5bn>*Qd>=c(8(0G>Smgy=o)raBvdaEW?wC?Vo4Wf) zsxxsbYp7JJh!da}#X&CE1OgZYI)vhR36pLTC7#EM-i;SP7|#VV0Eh_}s0)LE01W|b z@nBJ51x6M=>OJr`rqTz zWGsyB?JR7a|L1N~v674(jtVLd{lB$lrY~~~%}0g5a7(Vx46=W#H{(mzM1o0lNNh+@ zL8V9N|3zJ6S#hJ3SHyWDI^o7c_GznHH7tv|_{qnDYhUqxqOU`9;&0!`gD@*m> z^*G)3y2NM zP6fQ43rJqpP0^KWpILs*^nX$Qt>TiCYsc|bu?%07?=rMRpb@YZ?U>9*jYx^A23DZb zN(aUmHIa}OG}8g7QNOfd3`5t+YCs=uCx}<*E%yX=imF+q(9oH*ok+ZP<(yKvQ1^A} z5N=K^RH}@LSxBsK(>Z>j?zx)b>H&1vZa(PTcJVjg6<~LGDqS1C*toP_xYj~tQ=@)s z^_aPI*c>xUek*QBbhv@&-OM%g94zWOU$C%xO+GBA8skI@R+m)%sae+Uo$6TycaK!R z=bKHmR2 zRbj$nc|Gd=S$AGt-*U8cOz}iYQ|LUR>6677$|-BwSh1F?EpwX9`s5L2PE^ta7U83g zr1iIx70we8j5sQj$GhK&IA2y_yy7zdhcZgD*J^E#Ke#~T9 zAyh=|xK9vx&+!c>s;xc>-`^0MCI=k6t+1f5qpv^=)_1a61vE2z;6rhxW4tbr zq?o1}6{spQT)ooq3)`kS5KTk*BDQ#CL9%(}qTEsT`Izsr9{>DyhfQP8f5nO01pe9g z*=zT+<=uwkZ9RYR*M&VZjFP<-8MH%|w(HojD;(32uNZn77iqtaW4qQt4|$r`(ZeUr zRuqBw87~}ME{C80TUyBby?-dg@peuw$Lyy1ESS<_U$#*YrVrv6Cg>Gj;wjxM*y~{F zwxfr5gEu=4h`TUd+{7V5<2^AqS=#9F{U~-W;+R}!MEHE;mNW^mYE@ye20snzm_>u( zcrua{Et}_?bn6lA#jYOF-c8|8b5)poN>y$ka7_#-!~wlN~CQy6r(gY%-!{NXaA+5|f;gPCBQwy`KH$!dm<0J@d#4z@p@& zU$-1OG&NK`O(RYNkMaew$w^r=CK2SWE=W6w5U))*YmES%`E-G<=nXID8b03%*R_4e0T_&xDQ_dUt$#u=9@B7sQYRL5PjDeR|)w!C(ou%c=p|Abx1bG#zDHw#Fp+lmKJA*dW8{%TnVs->F=O;{A00I`K zQ&Qvw9NUp?lFTz%#u~X zq#42|NAYIdd(U=x2e*n%X)NG&)hX+kp|`}zBM+byPOu;7%s}~~Nk#J$-QkmRP}k1i zwN63RikY2@>zFPlR#GBnOQz-+EauK8&v{RyLIs?9%gvPy3%PV6 zrS-c}8Rm2LeNjQ|Bz1e06C9LI2^iaFcL!LMFB2M}n{5z?&5sEMOSJ1!OXQNQ~Ju}1aZty0hR2J^FJz}t|T*- z93YY@JrQOqwe)D`{)d9x7K&BiqdtQMO*qWnsMGZFhhzKUjF>%2hM#39!D#6>m@}TbD?|(x~c-Zw7zn zg@kvbt*ym)Z37Tm6|Zbiow+{Rlp=I(8VQhff;^h^D8xOd@_(N*l?E2AYC|XbI#HYR z(glhMz|0jGujmufiH0(oC~PFliPPHI0#>iYO1>$L@p!*!=&C%R*Tv-1c}?H(-uLkO zaQW_aHP5njW-iym+zbP^CP%p|X;aiDE^~anaGZW|Xk{Dj9dTX2*CKeC&>dxa^EG?K z=X!*fhMi{siB1t?j<&la;~RBx&$zn>;%^9jJ{N$<5lOdUyuVmOB%gjXl|)!k9}2&j z9>ycE88Q%-KopoCszLZ&{c0f?q6S0(rXm`=@)0t`ADtFmdvs4OJmEd67gE&}$k|Sf zP1X%Ei~p@3Ct3LHA2}Y2X4Xc3j{cg+HhU!rBI}giOhIS)HK5J)~xVkal*}@sX$Aow9^M0s>=KwJtpz1 z?CAQQOU}VFIsl@JKdpPr+z$%O9jo|?5zQS=#hN*WUGn)edxlritT$ltPKxsbj`L%6 zDq~k4WoMxEPRn|bYb{`R-?nSg?49S|A&+bA^F8&A-Q%VgdjP_HY5p89!tgnSCIcv* zAjbxj#StTf6jb|IDe&YEJMtea){O$e7cbE?(_$59*tpDG~q?t=SllT!emp8&e#FdcvUJ6&xQ3- zV_DiZC4M#8-d+2}3k9+>r9ANw2}wj-2uOx!NlggIdWY65EQIn0`=t%p#}3^rUG9@K zSO;l(HGdqa(*{;aO?Px4AcXl{zX_6;M{5>JG$?>uq9&mWk`$CD(Jv<#Beo@NJ526r ziYQrf;g19iiN(mDa;XG#am7_z+(njcJa|;e0`J*BDOw6>KL@P5w^xQ28$N|#MsA^5 zSRqhe2a_OFT*n~{M!vVasZR29(+IMj#5!HDc~Y&h)sor)v`q{+fGB#|C3lN3;!!*s z_TE}AVufXDS*>90;va@v+O&$CQU!|5y5azCn_H9=tapnuJ5-I)F&OUv#Ya~EHx$T~ zl56EGrXl(K(40CMC}#+WRR|2!{z%F|kd5FVd_qL0F!~L8`x^a&y)^1x8)gWC2;mp8 zH?Ce(2$`gC3oTmT zj&&(~8WJ|`3d6OrV{*906{^*buPaFH9!@Ysy1F+%N*>5GoJ+qf*aDeNpO!G@?YU9N z_0Is82r!}GdJ`#hk~};M{RpR^2PXZ$GE}GWZ~|!>L4y=^M8UZ4NFh*I!(oI5&3CY z7i8f{+a`eBE;yCSQA!oO|6kluH|C_Pk-?MNBRNkLlyK~WkEc3 zV(a^cSW)Y)?6LK`(nVEIR1rAa9xD6(rIGoV@W#sLx#qv6PU*4lChVsoPaG-@g~1$6 zVpTK)ycc3k#HEU2u!?0xFfnQ(Prz)n6B_H+)UKRvhx8U-b+s`lBuY8^7o00lXrxLx z1v1D{yoWs{Qgkc401Xvoy0R&O59HJX93QE*X`)XGo>)db;`FWey0f<02{@QsAF#%% zl!R(!4qbNKd~8P!FgDG=C;%wWP+rywHSofJaJ%jjwQ3hA1)kv4!pEuiVccXq#s_5c(oBGQ@!wAl&Oax z^}yfA)c5sm%5B3`raRE485rnc^>fU{0yZmK|LI+yb-gp%KD%MdFg2ipQ)pR0d(T`c#LY!-3updgp`t{M} z`P!Otv3OKzD~&F$bvzbCWu{1Mw0c3)LmuYe&;XQ)zZi7+Zk+7bs^KAR+3{)k84=Ww z#|!jNZHe-{-AV#Joa+56kn}i?5Rnwen{Ao+xrNwWO4GqMj2&_OPO$dc&E(ygr403= zBSQkp9Qw1kJ33{G8r-Jj0BkQ;qc?ovW)v!i@2b#<*04PL0$jC_5McCl!+t1D>tH?W z0p@xvr*`^1kNP%43XRe^jny(#ys+^XSx;pv9LW_{>;7iue1GB|o(dhYs;KnpkKP!% zR=D?Yc8;cyBD^F`S+?4F6{mR5zw_76?Ix}N+Ep6=y>Pc=BrPo+Ib8=!@(`fN9;RRi z^p}qhKDG6}SxDozwB*kIst3b&pp62sYI^aIHEhYEvpp!-77Vi$=DbVhu7=}5Hc&`S zV$>3YX;iU)yv+_!Eg0Jq9(z%aSvF~2uC&dq`ORGKS z`a(p_M&$Er2ZbkdKkIh2jWIZN`H_K9F^}BWsno>tu{^$ZnjNAU$xnBm|5*=&8nPF ztQQ|WTu{&`JL^wSnQvt3Ft&$}2EU6p&X~hMJ*WNCt7=MoBw8n0=l9#sIbdJ{EZYf% zL1=*#?n)oNGoAFZzW>o(7(JRrjNlp@Ci#-!U5wM$%>4h;9hEnBf7SU%yCygtxpD2q@|=NJz+E|9xuaf1i!2 z=wfSTBIV-jZ1DdhwpFi{lvOalbGEy^JTy>-VUYi-nqJm4M2gTuNBBn)Q6N&Lduq_x zo4DP2KGRv|)n7@`=UI|vMp~wqTa;w__eV}OV3%5y*!kQD$uNDwt>0$r=rRsDWJhH1 zoOjX z9bk}1DO76E89p0fay(DCY8+;dMR7b&vCacHD2_UD%0g91cCM6N8#C$To@)U2^q2x& z8#W%|q2E1A)Qrh`ti)S+#!}b)Ka_oAaHY|Z= za?X9PZrxM2PMufv)!KXQAN$w(=A2`!G3TiNc1SZcU5!G}s%=S><}8z@w(#t4H=OhX zSe;L~S7SVBqDi~LfIcl#tXbuCUoYbN^CPo>sWz`rRPbb;H?P~)^9hWuvXa@7dP*;) zcsK;mV%EW%@l2iHRyIiY%W#Ez6VmK>JrUaBi#}TcAXlVh zN7_<4N^MBbkJ4Yx+`^iqt6noSZZ?xAG$&1Dri#zQ(q*+8TDe@(eMfLCbOOp+$mPii z?3{HH8+eafj%3{Y$U4h~&I?a;$5&wH*LAr46QTfaiXbqwVW#J_iKbGfAr}I%D_L$f zQ503OJ)*NI~6?F&6r3r?i(bx=hH4|F2 z162(X<$Dc+bJ*&z4WEnrRb?;iyqUUDCb1a)J0kTlOi|MZ#v3h-TPeRfZytG6iFkr* zfUtzrVme9ZIoDAgekDz5VWz4Qo5`x+I)PpFx3%0sY_v6=3OdyrcU?mxsF5b9# zf?dWjItn4kanYeVIKbnl$+1^lUkYw+qA8B+PqH8C{~GqIR?z918mB(F zcNuG};jdM+ajk1zVqB-bfJur|OHNRwporgiw+n4PJ3b_dqvp{6lEk} za_bGuMjga^RFwp!7uuq1;ZUQ5$B6_ZNK^9 za{AVq8zXG?Gs*}4!;4v@<*iu39uUlk+uF0PmH_{JR)NCi{}^OLo zR(qfMAkzcTTY{g^J!^Ge<@6`Ynh6-7DPoT~*c#O|=A1vKe1Vkc2}I(K2u{mXl&ZWO z$iW8FONmIrFQ~8vnJuTV_Hsv64$h#eq{!utBcsr`EW#h`{rmQ$aUX~#x+dV2S@4B& zN`Jvn^NAvr&dC?d>gE*br_|jEBzFj>a zbQt>&7lt#=%H3D+KcA#9T$6^KBHBY5DQ-1rSGzw*?NP1}*PaZV+(yi9b_8pe>P7I# zhJ2hIP>G9nen!$dqz2>Y_!*+eZA&cXMQz+BoknyK)jZ{ z2}{FA;UYj}ZjM~4Rs82jkdTEJ~JdTE~u* zGsKy0;|@J!IO?@r+hZ2w8*z|nI%>wgR)7ANih3K({LlwduK-z%A;|6-&@p8Dm16UN zvw8RlWP-ON<{g05@E)GQcejrQCP4<%6gU?Lvdj2OO7f_=Q9%Gn`D&P(cnL~?ND8+w z_7}DZ-rbA3KXP746tI}mHmHZ{)cCVqS=;cZ?>~ocC-eZOFTj5M0RFB={yV|^t7KT@ zKdwdoJHh;~4Vj(lUfw7RfX~ZGTT>=3te-me3KX@x2{MArA$jekaG=Du)Djc{jnb?_ zbv3ayTrdNg6*T!OR%Zo(2HuE9WqHJ4{u)K^d1zkEw;DPd8=I=C2vseswOpI2)_N{t zVgikT&swIVO|MIiEuN<=yUUGVUmJ~BJtyvRLM*gP^gw#l#lxxUn*Fl?>MD~HNxTS$ zVZ!8bWir@`kEqj^V#HirroF1U zUDG~kO+^3QVs)+AnmP-mp3aum^tK=Z`NkG{rkugnRvKecqjVf#02qe+{(b&vt?@Xg zn7+hHPyNC8NTtb;WC5ow@mhIir8D&kDn*ap3vd7j%YtMiE(28x^N}$!jcMD8dAQP4 zsYY2TqMm-C(fXuITh*hwXr7NgnQ;}TgbY=av&F-^b=^c(dLy;atBtg#sn%+ZqD9Pt z;w2I~-!jsu)vUO<@Gn#<`Zl)l$r$eWlm0>W^v7N7Tl-u5A9tQ+2u&JIhFc=?Y*#^U z7OP>JwaSWlZI!jP9eD$YNtXHXK2)H}IW))?%FH&HDWg`BZiTxYlmsz!TFUa8c$_ic z=c&JeG!lD(Obct=*}BMJP&EVZbijhD4t$uBY3=x!elA`}_)NZiLzrcii4&2a0~f5;x?4$E$_$jU5q@+Ert&E7yu-BZZCA?5+qO64SiI#nom=kfPp-$5uWQ$DfjL` zZMtbPNMvb5T6YOa`0x42kfepIJm@>qOz;Rp zrfv`55;Sa8plm(_1|r(%x#sFP{=}!E+CoIT7>1&@%DLki2?Q4l%Fe&ybB>Yb@iwFa z$k`~kx^L3?+p?{eGLsW8JZA0^wDM}lt9QtuNDUoF@7Ol0r==?d1=WV_5wrj<<#Uu} zWqVUJ?cGPv!9J`vB3stc`oZ=XmgB? zyLw55WOU5c4k8Y+LWvREQ}*butzlgMTLLk`VGYPLca+#NckN;1<$^s3cg10Zmm8GF z^5v2}3+{ql4VZN-b=($ePzUUc}qV&}mtj_3W;NX~oK_(QCSpKyHR$t(L8(@HS7eEO!)D zPDgWN`l7NwlnGcJ*;K_5mZ*onn^q2cu&kUY3=Uij1=SUhmF*ZK(_c>A*>qdIGg)e` zfo59YS}ZqnIL_p_UJ+ByK_9I$9CEAUB?kqoDCF=MQH;Pz(QKu)iDSpUR&(;L$9~SB zS=68q+g080Ux($K%Eqry-Y)(n$ecUzbZ?qHFDyw+!@WxsoQ44I@FqS3=lv8d^=+8( z9YpWXiM!a!{135P*W37PuMmgeX{O@AP<~A5ISErof}Kknsn3VF(I#RHQk-($q(RLUBSjc!y|2rsddeqdpxSG@Ymvpvt>`jDO4 zbmpUBC`Q9J0J`2)2WVN-<6w;A^9xr^krP7Jz(#ZTgo_`~Hq+ zjto_)i)FEnE-gAm7noa$Eixjc70Yzy#|5JS7xK?r@lj)g85Bojt?adLq}PsvBG&hE z;K{hiiwk|AXd3b9L|aQS<$D{}ARFD`W5h8a;W%)T-Shr=c&RueGNhzgBq|A~M1^wC zzfn%OE%jMmB5|W2&BFvP>5W$Kw!(jb{Xsjgn0W~=>xI-f#ciH-2`UkL|Xp_gNtk4QVh;kZW#f9S2-rV1Rm46{Gq_S}heJ*h0YOW=r*V}rJ9ZBfPI(Mf; z-U}QxRKfrcqu>v74TTA{(xebe;g?jL?_X2H3^xY_A{8aq>p>h_(p<&YKVvt3k}I;D zyiPeu*3QI0)f@ttpSqKTs{Di1HsGkqi?{YDa z#>394JwB0V_9P4Xq;IVbgHkmteacl0Gd#y!g+(TwsRDt~4KNZ?;plvqM;o#k*!?M& zxZ9!Y3jDF6;kL%_8Uw#F$4ly{Lr?^>=kd|>SX#rTUWsj<%G!G74WzjOZmo2B?Zekuggk9El0vra)VxT}vcaz43H7$&LgJs`X9q$G`q8_~FF_|_DLLW&qwkZ2#BlE` z2f@;Kbu2^Y*?oFTs>C8%mQpQ&MvuJPb$0h!Dzh^w5T!6NWAWL1NILkpR1Xx?@-X{6 zuDXj`HsAKqU^0YD-PP1t+&ors*N_~l9)22cz)8KqDMYVv$pzPZu#ojywA@y2} zbYxLhhe&phQTRSWaue1Q_JBU8S6wsqfY&hu5~N2D=@|v{3O|45RM)4fuu)wsc}|?) zicYrUq+FYdgy`*mde5jGG#1~3S?B<^Xh74nO?lqO;*PPjo7*B=+M;mWq5)bfo3x{< z5V$t5(xRj7$0dy77Ey8h3x_pqV!j*T7MUu31h7VWt6e$h?W{&@nNpFt3SZvMh?S`h zUOtuF7FeR>-q(zzU4mQQX+vn&Ub_ynqI0F9#8q+TE{+;b{QGSLTh^yr1pbyJ;jVc* z$;Ga!Ew0?@$6g#HKTdWF+fPTji5!z-As2g6 zoFY7>BFGh>9tuVm7{To`E1eR1zWlvB&rg=ryj`yj%vZ0Nb0y9=-FGgkh*Bl}mpDBk z$;AXXC1HQa{D8P29)M8XvMI*(Lf$96q!oq;3~U%?hgkMyE2#G9 z`o&(3(O!+SZE2)QfU$N#x`nYmLFV35^1cPYB=7xPzOwUvCQw~AS*dsZY;?{!zVJAo zTcn~;eiV8$ubnaXX=gXDTv-{MXQNb+f4u}Otes82zA%B(FoBw4U%d}`+EYm{MwYpl zm#37|*^mmphhmB;7c?BlDq!$~@$Z7M1d;S$!gT|0&{1P;^^AD4hQUCTQ|mw(&bT`- zTOvDMS(dsuN#DfD_W{k8tGk2=lHS8BxWfsG;n_sF$Hosr#g>|4Gk@DGM4t3{rSBFg ziFPv=+A2aG@=8j&QgV2YWWCxFM*Qm4x$lC&+lD&b5_`F2J?S9h2F@3cLM$f-=qkuv z-35_qmUinro5XKM7MPD+5I!U}dbr-qn03$5@=Bi2)QPh&u&Ncdp$iobc=8IyC3s?z zNp|gvGn#kBA*H5DNowmxB+;gjs8MSgD|paHK!?CoK^EVSb zx(5pax;9ye5KzgAlV7mIUnDVKVSC++H+T;3PAkj0WE{FyIDZgtEzyRLPRyiIkqGYI z>b^k!!G3Lj%1cvz1Cw~7e+N#4{$p_RKSsF!D`8rsIA%M?kHUk@_P>q-U#t|jOU@Ajd3+Bu5jh?UwMWPzpWYcZ7fUVw@3?q1U;dr(W{++BFjlCsQ=ZR!N0tw(OYl1 zMvGopn#2mFlspW?rtKNoAv|UWoo!GRKEumVrJTh%L01 zeV1yTlF9<^1ff;vkUj=ubVj9DHC_H$Mvz1>k08DVF`WXR*PRGZBR92xV3lxzQKO&| zx1Nq(I(Wxy@y{&G=%t~So!>%2qMGJCZDNd+o>Mi8w^=>$b_z;*gyPUrDA}Ucl8L>W zbEcJJr#ZW=qok{-L`3=JeOy^Mg-BCCnue&nlO{22W^87)f6trqTkt&Ly!aXGA1AT> zQN9HO_{Wcl|G~rlD@^A8k58hsi?jLv!r3cL*~&oE2CKtcx;ziX-} zJRit&Ez=0Qklz%Sp+**4xf$8DZ@Mg=$@?S+Y~yXK!b7$=fE>w#qL8o+z`=(Z(XF#P z33sGt+o&eTK~r6fKXrLrdD)q6zP~@Y@d1C|Cc6YdT!V*rhdtBJ)?|yp+Z{RpsV$rW z52Oxjxo7_AE>N`{PSSkY%X*$a{YWU|#Q=e`X}tB?ZOZi1`+7ZIL=%;(iXvIo5eLST z?O8ZuShgV^7lJ}3*#=g{Y(5F@XrY}Zd6%&P8c%Q@$RuFtG|Y6j5Jk@7Nj zyn3nxObomTCd|t?UluNl^Rtb9-taRnA@!=9D7~D5fAOkNbzgYQd2L2%z64Lrd0}oY zT;~9rB!9L6Z)j_2YE|3Jf48?NJ|+Z6Q^|A`^6NPNV&g2s=ThVAl2xK<*(Xo4Zt1!^ zE!}eMV`;xYWLkjaY-+X*rEMljkM_Kj?{$jCKgWFRxxB|NK)!$T=VN|#ozG+wpST{4 zTAz?9V2JRPZ8;Z{WoszFr%vpncLZ0SF&s_|Ha>L6@nAv^#yM&jo5OD7x;`0uY?2uq z_6A~I1#`A9`vGAC7Wq|#od~`CcL)Ev#T6(M^4VUd{|!ug7y`_CJ3qkebBh$vVQ=R@ z5x?a!8I?aG3t>0T@@xt>_1GSQ5nR1R(|qb2UG>V7^V)T}p+yr(<$JDYA{u{&QF39> zAV}I>QAHoYRTNWjKjL9#<`9I3@SErzb3mGnz*KA*S^k*0o%wOZ6ONOSd5V{}D2jnW z)HLe+X+(qVH*P!B1r}m&u4Im>J`NLm>{w87Fi#}a^+05rNbarTRgc)u3MyYgZtDXw z@DHthH~X5x&peIv(c)wia^@;*p<0VF*dhjaSB&C-;-W!SvZnjdLwHijQyO}z#OOd7 zs?5Exow%PF1f(TH;|9I!WQ7RGe=Hfke)Iq*Ox+bMCx+K5<4$>vG(9D34a0wvqR9^4 z(xEA_Cbx~-lMcqcL-%W>Un^60OBzSaU`U5Jy+ySKN=x8QdHhvG`HNZx5b>7!zO`3u z?T4@Hz(SdUQ<}Hn$AGX$QkhS}QvaRof1FbFUpyGzV-=9w_sd=OKh%x?deI{JAHU$= zBCWbGV{oh(d@tp3S`DLWe2I+=dA)SEcc8d)1SIc=zWxNEBbzBa~F(mgDiWOrC( zwA$iL32Zb4(?ghxPLPgG6PkkZu1W6_JT8n$Wl3qO0tf}xe}L7t)Ts9a7;3Z?{?0&! zR*u6#Q9uL}q0VeMdxHAB^kVv>l_6{RF-*6$?soa>D935)iu$R8`=&P#?H9J~{k9b^d#wgM+sn0!cYmOVk2mtx?T+dCZf_OuvqL7{)(|S6?J$nxw}8hR zLW{>dDay^mz8N9-xqAO4r|>eKdn>h{74LHJmk-L04+8GBemlaRePGtrwSEbA4{cff zRN#h>v|u+jZc;xk$2&hfUsAuHa*G=LTVX)xe$Dsi{%U{1DqX19{&ng4O&SCQs5ZG}Pp zMi*m`*`lFYZ4$vMdt+=b+`jpDa~0DdGg*WBxA1tTj4b4j>L+56>x-cNF4Q>T**vnw z=DKx+^OJLMBXKRy*)vwYsPqz2@*OgijgiVPBkw>8gY*<>^i;)xpZExkOuqsuo6>;~ zs?v%2cqUbC4|lAh(&8%tX^M`7!kEQ>4x7N76JQx}tvuw+#O0W+ev_*~rwpw%99z;D zjCfcopue-&t1%in!%%ZlR3DXzL@^@Yz$Kl)V&G7LQObsG$A@{fW$ey8cnadDtxS4m zU$yOSh|Y!$S9adw^8l}GAQteHg&t67h8_hmhy^s&Qo*gikda9!-YBqO+s|emMx&=T zfT~phjOOG}G#9~{y54a->->i-YFYdAjejPQQ59onYog&~7|RZ1BzU43ogI9wDU#c( z$vD}EP4k%+oaC=c^LQxsFX5ar+@<$(i>yZ7)XidQ&Mz0zF>n%6AsO%}{2_~a(41BO!?X?$?|;cqf+_nO zLsbP6^)B3>eKR=~aJaE8IsM2kWxlN5Y<(Cp!g+$rIaahVoak+8lav@;CLt~>xF{_A zyf$)6rOK`p_Yc-?mcl+`DF6;rk&IZSW#%=_B5V(LQXb#Fj3tpPrauR{poRJwyHkeL z(q*j9!3et<-#0lnJ*YJ1Y~L`E^m|H+p;z7Qn1QusvPL5THMOBQ;H0}R^>3ZkYJQpS zv;rX-YV2_c`+1Aiip@mxIW&yA#&mAy89t#)HF~@yinPFbfHrUjhZpe+ zY0KARd)FlAOnNLx9K*rUaDd(}0Ia*OzJpYBAA#aih2m`~;Wav-wN!x~%gpmSBVg%93#_{ztI|fy znH2aX^iZnd5^@RU9oG(eJ~t{;J?B6>d>e0h!UP);8h)1s%x(_{>}nSd>}qr;)?Kwa z-V@JP@!E`Id{__V9pI~U?e;Fz)v4IaN0Iee=Ot}~87mj}DLve=7c{yx37yfNJZU@%=W*JKUz>k!(B=S{EQ z2otrC8pX$q)rp5pK~N!zE%iW?eB>Y!QBUENfYeU*mT#@XKaA@0{C{y7G8n$xbdZQLc6bTg`H zAGqWx1R!f;1z84DXC^wK$iP13GDn{A_bB5rJk}Z9%NM$ypdC{i(rq^sa4TqFvt*}$ za{I(&DjFwN7;rURn3xx*QD|pIMmR|w&-P((t+8Q2)Og76F29(F@pD@*BMvrrB2@1( zZS(mx2TW3Z)E{I+f7gCe7iXF5e9OaGdvhQ-j*=~=rgpO2>UsVIh7#E^#lZZi#aX$& zmGQN}6Si29HI8-)v66~>+lJ(P>RHL>eA`|HbDLIC?ZC?UH3HwJ;-;v-Y!~D*K~V@{dp^Yk!HIemt`X0uKFoLK zHUdQcNncwEFCw*MQ{~>M1H_6_Qb`&)Kz707N6BSxP|9pRuQV(tm1GeNN$M%}mapEl zN|&C?MUg1mLzAKw6)kIS3dE#e?w(KAFBGF|bfJeIG#=PY%Nz^a6d@aP4ObYe57=&< z`uRG4oni?V{^q&HSpnbJZDZ0f%!Ek%N6a z^SrK`#TlW@pD1BKN#(GL9D}e8Rn;AThT)7%T%di~jB5FnhGMU?5jzSm0lqP5Dc4iL zIjURD34&{;?&8!@h^Itsn3%!tQbZ=;_D9V6GN`~lAIfyCu zk#5YpFXK(|vsfIEyLFyp6A*Fvt`5Q?W5(h^adt76`y}`3OjWdYPb+Cf?DU|Z%;Pkp;4xEK*zsRK^X-~5r z6@c?t9~o4v&?C2LQR%)(JdJN9gbDW83sWMu3Us;RNzR0@SMd@_;-|b5lZ+(_rT~;d zgSk*Vq*27Q0>x@=#FT2aRbLHO+MLFWkSU0gusoj`D}fSvO0F5C=kcqGsbAYT40E(t zSk*LleJ9jTq^e&+0y@XI>YkLTpJYRdd#Rf1 z5rwc_FvGN>L;L=;=ZoHB#<)>0 z?Uj<9aTk;yO+@Y@iw!N4p0~{pphu>hz(g@B3?KlR>tOvbmmDs&Vr@!|Vd8TqbEymN z-dK_w6cg~dxgYGMX@RF~xzGov?O*IhybFtn$$^^_A9j-;Oh9!BS^ClVToO35KC7mj9m+XxUUwUocZX^)#8^R$g8b5t!ePEQt=a6^4VA_AwQB{n-cWMxa=_f*IzitHGWA!}_dYwXb( z2v_FZJBIJJr7di+p+1SJ9oVV~KA|f&mO^fRa7h=^|=eBc*@K$-%gt3}XSK%5KgLPo# zt@Rk=`jXe1?Pm`Yf)(Pr$Tb+>@j=hs0TMc*dczw!N<$D5V-3?rhuJpR4=%qtGvDlZb-6h>1P&=VUy$gj*^>F*+wt2)r}JdP`q4)qgFveP;x% zP)8PE7raw%-6L!}k&oCiOlQE;?*-8O{EBkbj=D;dR>u!nOV?dT9U;6^9&mW>lU6Oq z9DjC%zBj4dM=aX9M;*mkXt3G1Lb*pBJ^$~oTl#+OyaP06Vhhi>y#y;j=Ny-mo_&TF zasba3T=>@yY%S9VZ(zUE4@>FpP-s4Y?3OzNR6_vg2G4K=8PHD<-Ti|ZwZ33pR!ncF zw4N~^OdEu=Q}){;S+OG}xg}=P6!99`C7WId*Z|8m!bcCuB@0SFAZ?N{0ZkV1gli{_ z10#(T#Kc(^*imn4kwe4WCstumYW|m>I&a>edHnJid%TmP<;3hw%1hTx>HfBnbcxK zg{8_J;~hR9k58`;i9T;{!?{3NeS!F^@z+Ec!XQW!*SjfriMt=ROq=~le#L{EQGT{> zw4Xq4VwIa{&s@7V{^~yDxaI1_@8S?MAyMk~e08v0Kr%~}0z;++4*la4mI^XcjwCiH z&>^~t(B&*^6;YPlxhJ_f=_^^r0TmvZ*2GgV+Rd+QWGsy9@$9_Z2{p=*db3RZ>+^>y zQkh3n7<(g~j5D)CX`0lI_1#Vhy-dPuu5|;IKBW9r22HY%;umFb)!ML_=WK;5maw9{%pJEz9&4k-T)U9G*x*B@xSCn8kTqbDX*DNxq8y{tuW)+A>{pf&7MK#5xKzH$K%kb9QE_MOeV zzmoNR+;{wL(rP|$M{Az@I&sY)KjZM}wAMH^eVQ`^8SUySkqb*aqA8v%QPHz-?F~|3 zo%2>k-g6e4_;fdv%~lgy4o$@fan0KbiR-5pI#Pnb2ZeL;S%)Kt6@=uB`WexJ77(8B zQ&bA(;OF7s9xpGnfxz^yD8~L)8`ZGur^KJ0H{id}*W*X#-WAA?XsXim@)(Fb8<}W# z%lB1yN}@^*-8CDki?N&6XNrh43w9~-FcFrD^H9Zrhg}$Yge$11la*4+ifP)u^0A=G zZyOTF%lnmlX%d?|INpg>3v=468=TU-sj5?GdAlkO;}pa#+J4bu6c;=+G)}(K#)Dv3 zXaN?YElG*$*tJ>sd9#ns{jeqfWWZE}z2u9YZR#uWJT3v!B(McQRxj)txbNl2vKJ8p zJ_Y@J{1>Y)18c*`cB7vOKgH*SYVaV}!anX%wrqh?Yay2G{qok}A>eo8XlenWH_&Nt zIK2v)Z2%ni4pCFdvolTjbNmoeP?jeG5yntCCe!r%@IJM7XM$1T9$7jJGjG) zLsu_h_0OH$fsV0j=4~|hH*cP?YX<86sR7PiEz!jKy(>+@ZMF3X8Y1yd@Cm(N(NwjN zwU>^N0Vq7J=9jmhpjXO9#A#`_!Wqa??qz?<0`6e4V(r`CfFs3)J8A(04a=QTDWb~q zW6S-lh%1^p`$P>g55gIQ{-Mk53H|lUB67*xvI?!n6sjDQCmMgtMW;Bpdvv@dm!?w5 z_2X^x#OSZnF7e{;?4|`9%&t*s6?%!w8a7Ew)1My=Ap23aAPP-_@_yVPv^qy7#28Ya z9fa!~j)#a^H1~$kBF~!(sX^W@Ppbq7hxn8jxrN_)VoSBi#^qXbou2-Z*5&YQUs}dU zbshRfi?fpq7G~P3-@8X~E;&iAz1hi@1}55zD5?MY>Lk5NanG6TUSN_Iv%@}$HheAm zK-v&={mQg#bwsq^1WZ=EVMWi=^mqD3b~enBWva@#R(GxF+g+V6N$uFxu1D&+_?lMUwIeJTOX1%Adiu0X|1DHc`OD z{^U+qtw%W*n|IkxxxQ~ZatOfc0cJGReZ`Pn0YDhlNjsDn)lK$r)quZ^?68018tFmh zLJVMt&{=Ai1>p-&k(R9urCo0sQG%3`eiNhqWz;4^r4&>#=}$G8=tH#zSZ0<+kJWVU z4EYLt)z=7F>&4E9dV{bav!%5t2$%q({Be=01@-xr0-@s_i}q9BZ|X{Fyk*K56CB2D zUFXM)rGf>^)F)81eeWx!Ek?#rTJN3u`_rW?2NCUDCZ0BYwy2%}zy2uF9_Vx{Yn1=2 zOb}aZ*qY9!I(#>QUMgI)c5QA+@6f^?y?;yAb}&BSM=(M^ez~Rf(qx-GgN~pYSlW-+ z9Bk~%Q(M`FKOD8tRr=fZ5^YODc4lEZjW?kJXp3EKWydWW&uTbEZ3q>b9I~2_ky705 zm_K?u*-&+j6hhMImJ8m|^wE*C`%tGG*2DAlIIPs9id!AuN)s$Swz*>?S7&@uS!z+q z#mYQhX|Fzfij{l}fI%H3`eZ;7hD@D6T(kC&HZw8S;|+wAAf+4gprO z`KzepYAb7qu65N^skT^~)-pOUL2AozBV()VA+@U#S9eRlRL`hZ_IgGsq+1j^dQGW2 zGu8UCnXW`j66UE1HaXUng_AR%ni#{_^{H5u@Su7KN zqEW_@Wpb#9UbAnHo^uF^=9;$HlU+C2)ndII;$iKI_L7P3MA(|Sb93nK1Ji3lvGztl zSa$!(Wy2k$!|J+cfE6na8T#QTL=lGolu#vZ#R#2JqTOGduv zH}7y97RmlepsCxQB4zTEUOqbVeTx9>zlTyHw6PM6ldaJ%ftj6^bZ~51l=TQM4o^;d zrESbPb5HIgcf^xRYK~ydj9rT~sXT_4JyiXSj`9rMzE zu(V7h+0H80I=+^byM4;LFteRosoPhiJ0w|kE$yi|YL&K#H>ZmeoBCkP;?6M za!%?5I;Ct+!1soF!$cQk>fs^IGPYN6bbp^A7nk$$Y7dV;5_&5AGf(^CfOFhKq3z;_ z@@sWEKx}vq{_r4BT2W@x=wQYCn zgg^ROgBvQErihb69IsN&h@AGc8_*=bF*6eMK{68T12Yo*gfbH1uu7e9IVq<60{38> z!wtBzY^7ufvTQR2i3fXEU(m<5eLz8Q1Zc6^1xKe*&eeWiSc-T5*wepWg`Z>4JLJSZ z4r50gUJvvbtwELuf&W}T&kZa6!28f~Hq2K#a@9~Kq56bI(up1&a%L2StKAyVyF-Cv zj<}-0Ch}KLw9ne6ZBQKBnHn#4<&6^NBsq(h7~hJ0Y`A7=br-cHewZ%EO{#00SDjt8 zW*jKM&4icECs|<+EP>Jdkyq zP&=t!L$pJT?S&v~5k3LU4kgJBMU!w5B}43v@Q0L$d7dA2@UVGcs4i7ncyuc@CuZfR zN+(Ckf}5cfF*2)36DTn*&Y&kWXbDIS20!yMqT4RgX+TQpIfugy&Qklzz|os znJw21H)Ze04Kt4qm!rG-jw@s0IBUr1iAeSwR%s5)*$mUdxlz&0*g-2U1I4q3^P%!K zpwWe>Y+0?@g>^%z98jJ+;5Wph1gLayrSb3!!TY`auqqwAOY@3M&RUuk`e3jVBm0Es znYs7av3(t9r*Wh{A@iW&Tl7J}&)TJs3F=4&Y7yK{a($d5DTQ6UNE6tC2xxB~dfVPk z^kG@+Be6AjpJ<&}kQSisfr)1v+umFT|0M^m&0ZaMyr=E%7CDjU9d-nSQZRSIPJN@Ta8+$->*~r9Qp2}cd~OeyZA5o97Vhxivq+cbh2%Y z0=OxR3-?X+2nr(-c=Q7I8S-rsBPv~1+a9VRo9AGMZ!^{PSUs%v8!VkyUwtO^5Tltv zWKm@ZnD$KN00x&m?-Xb0i6f2Fcr+DOqc2JdEu5ZFP1?zp$puG+2goated|}<0GN?_ z3;}F3Lk`1PaMM+oGQe^CqhNWeBX|s(ZJ*>{u-fV6m`HRHNE^}gXbT1=$0mjVUQO28 z`4&_?BP{4W%mS>6R;=C{2l&OfI(Y`o+7!4lM6@%$lECprPj8&mX*E99`L|MqLRY4| z)x=&3>Lhr>N$2bu5gJQm%&7Ubz%iEx(X#^?0kWaf2neo>EK)Mc1DsrdeFpgsvqikMnRmWKYO{zC zsRm6njRQpudaGPhk+X?Xr1xSYiB2AFQ1vIy!zUq7Wlr_^2$`0YIwe;z6&Ham--?QE z!Ps%~u2a)*?p)^F%&HW^GmvMht7n(-ek^u)yIY1AET&nA<3}*kzbp8}|KoyB+``PM%+By}eUB{Bm|OJw!63%r^^$Y^v1aEk9202KU3%NH_F=OVaSF?Dou((OtHw@}OH8@6<>n`>f30|U z^4_@N#-&eqpE+h6DzT4FP_1{I=C&S-I$hD<6@X^?q-rsB>m+X9dLZWF{i*^jK}SVv z=%_XgY4jFo9^dGM0&j}`-7&@p(`32YZ&_UW;?BN!+iwW|1->zV0S_)WcWVG{m&#Jj z0Q%;vbVg@7-0)88LM@a7@mfh7tU|$FRWxT+@&GK9KlQi7&{9^WxKVxfuc-u8ipqtv zRaE|sb`#UPoFaOX>c3T&X z)&khG%#8tP? z)TjfaxU1++&V%cON2(mnqv?dna2kW&if4;2721v^`PH0-vgJVMy}Gu#X3MuKiyJOP)>Q3O43<5c^%i^~5Vw>)X#dEZ zs@CFfa&$%^ZfaVDKz}SE2zD)A%qtURsWiqp%#|RCquzN;Gz>D#E1@CWOb!Sw2X8PV z%t`htT_Y8rCgKptQB6ddZbeAx=R*DEtutZ1lc8I!$(8RRFhGGA_zFCw0dfAB==4FQ zsvF>F6%_4UEF|ncZ7?BnEkq*xE0%%yDB%V&dv8;+UiCdUW{;xPtV5c|<#cQUJ`9LXcby?i4f?=E|Y+ zL>lkY{i2Yu>IBr`n7v7ebb1WYCVI7^s}}BGAgW?xL#2oaq5;|*l13hoR7G`&f5Pma zjF=6XGeoGn3wSH(vui=K{z5Iq=I5K4`z zieX0W<9PG%WpE9j!>=KgFea9a31BZQ_-SbZ=* zvSS?yYNtj)sLUC}E8Ehl-+`!`MfWtKkFOLRCC|2bYwCWv!`N7TdO5OP4!X2GkD)%*@dpHbP(Zj16`9U3_uowVh zjY7%g&vTA4v|?dy4UKG#N#P1-@d)EwgcO>jLZ9SnoMda9OlCm&rcXh!pTrGMg_ob_ zE%Bx%k)DxYBfxWlJq)T?O48Ubj$BSO0d*X7D&YYd3Q0rq0fZiedCjyb1g1_Ke~osN&pSPyVyK_`Q(Ugu;bFtxO6-O6RZE zDdj{pZKh#t|6!YTMliNcdGDVXT9sWcvD8zCnVF(;ah=ZshcC0BhDNE*t2j6@y@%|C;>$SAey}l9t2lT%S z_zM4V!2efAs(;5XYr=fDnzw#+ZLFlP7$;gMNa(W$;iJtG6L$!}UJ-W?_Xze8`6bEJ zNuVZdnABt864J$&00%(k%j2Qcpegb511BvtDtpqISE*_JX(m)JYl4h0yrF!|V&bY# z+z47K`gmBv;~P2m{o3N#dYSz4JseN(`9F-kW0WmHwk}%S<*HrgF55PC*|u%lwr$(C zZQHhOz3M(^ynF9?ef#wo5jk_sh>To6R%XmK@qN|RIGjKLnl_e5b}9&gh_-P)9q3cL z23|c(-H9N+I4jLJ^q{f(k70D#IFd z^|wvm|2k5>z}IneN)DR0m~mc4|0Q!{`izX;Fj;$!(^;snsh_M2i0NS*MJLn25bnFr z{c=Gy^gyFzbNyRT@kTJQAFRN5dca?{wTbDPN?l zhWTw+#|c#wFnqrFdUh(MPu;o3d%bz#OQ(FhoaeCKi75(md#l=LxmGfJa2NfV^tdhc z5>Dan)^w^g7!ul>))Ri;B{B%vSJr>Cyq#kvp;oZcEj;o}%44<0%47BR7!sx-L$u&v z($w{M^5CGLEZWxF1pw{S@0-=4oaSKiTv5sFPG>U3F>IQIq=lEV_-?qWk8H3#&e-O0 zjP>J>PfnBQ#=|uq+=Z)jKruhE_&P~V0rvQ6(e}K1)Yh+i^&PHq^3(^MtfxMi3VjLt zbN@7Vb!({ny)4CV&ivkt)rM9*UM*jkIP;9ce9;K@nEn3$Hf&FgL*$_G+ zds`}XC-E^qsUkNLF6+~VLBAt-n|u6MWYlwZS>D9_nFH3ow#npL#`IS<%_;i?rbFfD zArB4i#H`OLAZ(XDV2e1WiE|;Q&{l#jHvY)g4?&k zj5tweXE~|e>^NiA<_u+Ji61lhNr@jcvV)?pA|T_dLt07NwKua!ELV|G&sT!ud`qxa z#{)h8Uu`7(r8yceKwxl{s2B!Qx!hsp)zMwY1VuKEL{~F2&Z{*kCRlI9W-0xQsIy*b zW5?GVGvmnl%j-xTYCFZYKVLr6p*m@dr7bBo9yrPChu6U>iL)NmNyX0t>ljt9MOk*m zakdJ*Ir!cE*H|aiG&XM*ldtGMoG3 z$xs>T9Y<&XhF9_Qd8yM27q?zVso$^PYa0_zAh~_}>8CfbLk6LKrcS=YJXmeJK;9fioKtU0Qmfgrdbp2JxmRr!Z`yT{PoWP2330ai9 znv@m2CpHs0;aU&hVrSR31?(F&yE%~MC1=i`2Em;M$ynCm5`qv{x$nNq@3q^UKYWY=+Mb%$iphi%P4)c(dB6wtM??05QlNj6dME zF$GWUoYTZAf(F4`Rgrj-eM+|EjGJhGi0zGfNbpjbemAT6dXnoA^NO~bx1W$4Tf$pE zmZ8<81yaGU;sGWup*nex_t~kBvzRaQ*$MW*GY{-0(W7~ag?;n>XOb%o^@(h1veS_t zDcjm^rE76_@sq1;1o0-34Xph{U0{id3xi$Ceu0hBWQY{dSj`4yswoG;73xSw81Pu- zMmHlo#&!I@Zij$%+3((_3lw#S4~n|)6}8xy33pwl4nJMu>kDsLCI)= zaQyK377NC8(X>?=W@lmuHG1m7@5TEgY(wVD7-emgPs`~3z z>+TQ53Fh%;dM69?o9zOKw?r%{4g)&P@++2;E?5n|_9K7*d_bE}fU>yT(4>B$F$U#? ztQb9dpbW3TM{O0bm39VF%%dHYBYWmPs(&i{7To}#hkIJ!S}Hnw(AzQU*+q2X{<^?S z2tp1zn)r|g=>PshD6tEIBL%)2ATqB;7y?t+c$ZKw7L&6NGA4>Zc+R@iTnNJa$GAv? z0z&P)g>EvuvK4svdU96*LNR1+e1ys|9QfK2 zVgUg?1qOWl+A=cuSk}diA$a)_EO}r9biXSH+A}qiD-$X|z{#u|pCf6PzYL_DIc!MS zGpb1Nkgh*H^{2P~^wppK`qR-DD+1WZ@!Ntq!@&b3%(3-=XBI&p{h zk8!R>E(n362K3bt+%=VYMfo#~WC$8Q4X^Hb2E!z5T1EkiP}trg>%-T6>5m5pKrCIm8rM1W7(?h z2h2__!SDliZW`IbPzm2$#N=X)ov>3w-Hg8h4-s`LTC@QHp|u=e@h%FnH4`tp^pcrn@YY$aZmaZ2{E1sZB!2^kkWqMGWk<}A7nm_J z^_Qym6Bqk#WYzMwgMY6K0KX0;bRZ7SNgL|N zpLcLsV8lU5U+UE_x~v&+08dKW3OFpXujz9DRl39CoFeH(^!P#U!tq)B09Wbf*b(Ih zFn>L)iQ0yizHQg#`WAOd`{uIPq3II>)Q!jOt><%hkvf4$55%hxOab75FY3SV^Kju+ z0i%Ij-zD1pZGpTMkPUgPn|=dhfts%yobrn%d~;`e5U)m_(pP!lRECBdhzC`S z^8RROMjnU+2rxeaTP7yDSf9ZTni+3QXl@e7E%Yb|1oSE`sDOo_TofQ3D_wH6psoEAJm33NDGt6jt2gwE))~BHFT@nB)ZrBuP9BglETn%dAefxr-1VUWy zu7Sy2Oo3EZj?>rygjuyjR*r+=9muChDkm@ck7i7PSXw5D-qnwtF^dxuPZ2ZM(I(($ z2IbH4ERy5tMTe5}cR|G2l3sQ-`Zjk^qQq#=>JIJzcIz#s6rfZV!` zhj;YZ^8lzTy=2NGv#_$Qda%3S1v(72(hF*WhX*R%%Il&xWa(K;%xWn12C{xU_4k=# z!%S8Nv6F0UdZfdHLXoP*p7&^LoWpOHCH;j$FoZ9ALlAnZepu&?GC>r&=+uFRFYHLm za|4E#!PZh3Ubtf)$h>~$m@JrG39TC-Y`iE9N}+aoBJ83`4!MMEWJqF3@s7DDcHuH5 zg?k8|xnJG-H=0#gPn$*;KhP2QQ;+*T`COQd96A zadxy3JMoG8(jeP>t|P)XRQ}UdH-BR-#KmUE67ti?XxdWmC?^w8=OtWgf5fteYq-44 z`=fGQ#gg`4hfvw1NX>9DR@I}CV9_MW1OH^hED!KH${0A=B*8mfqKd>hr9O4j9x;3+ z6naFRBHS<^Qph}rkfI(wpFlq}AU)C$BHScDR-nB$l*{1rR;5a;bh#)=vf-ixefhCk zvcna>!<7X)3o|z6MyzzTC`qc}q9lF!@!HaVs>RrN4u-5*G?FFH*6B2#*5VdN+{?eW z&bl$nadxw<9&z|6N0Tb;KFm$Pxq8oYfm^=-D{k-#`cy{(qI1A9{5@FVU|-OZdT?}c zJb;vUft~`pcT8GB^mpwk{l!lL$64XJdJ=DlxPg^zFg*g_cg;B=ly6yXB6VRkSjKD? zQ-V5bu?4GWglvIn(j(gCiB5OA^BKDK=6MtBfHk2fGp7ija*~K=}Qw-7qD_>AZ zZ%bFAwnI<(tnC8uNMJO?ua@LlVcm74MS5$4cy>PzG;smPp|AIWL5T8}Z7}R1;%u^Z zNuP*GA(Szmba4FQZqfUdF2rS^HjGw$KEcgG-(kc@$qIQ!T;^!wGvwaf4Z{9^;o3uFLk%9`-Qcmp2F8iC7j z07dK(lS68AgKERdJ6jXL;~NN~s)N%FEBqS?SoxKXH7-ZxVqAEi)Nk)4^ClxNd z)3F>u1kJS;t?=~-jDYcdKJ3L9lzqHjf8P_hJWX``Oh;mgiS3h{%;QYOKEjOq;D0;PW{VdD)YR)XO1iW`1G5kMZnR9wRNK*qaAGrwi0mVhPq+`b zg>8FxU$G`bSv;=e=M4L-ZMNgqV^^=2`|@-E_T2Ycbg)9!gFzo0YG}7NnV0*AL=>Os zBRn!#aod6V^Jk`aS?TOLgsnXv>#!#naXS3Ll46<$BbqkS_tIg`&1Q?EwQYh$))#^3j>jdfP8|fGjSFH=?36i+8M^xOLwj|1vQa8zJ z$}hVwk`=)s@S)t(nBON~1%0oYp4#P)7g}E%Vnv0l!uqC`TH0UHbmQ6blLlGWn|yASsv8BLE;R`p_UStwZk< zk5HO&qel(^GY{nXoMg+IEqWGwmsD6aO;Pi#C445auB6EKc-vYTm7#w1)hXubuBU*CiurqMg zK4rGaE5H`HD5I z02y>CBIN3%utm~EX5GpK!ir=-Mf$XD;(o33T6pM2}KL!R0)q`C}Y10nF?X%wdFSpUQU$8EUjmrl-9QHCHKa( z#g%U?-_>w9(JTw$n{qb_BXv~XyVFY4P4P`xVjI#$)+7n9e^T;a-LeUw(QfvT$Yb_W zirMz;vBIG9XlEnmMR3FE4roEc>7$Qpe26l71v3T>DfbXL!wuD}_gp=qQE$MskPcZX z%5LIT0*GdP?)50NP&QozFM7-OaJ3NiT{Ie4zF)sKc~R+5?>r zW9Yk5KiJJp3Du4yPw>rjtNK@@8UoSxT@p%=uXnJVcIdQL=-zOOE5n$y1tUt*61@kk zFl771Xmm+rsoGmYu=Cu`h&Xu{dcra+D#k~L&VIz~C~;J!fxb5j{aiGP;qdyH~bMES}eZ6+X?`!14@E7anE+ef9^?}O=qwfY0C%34*3qXRoMPyw)q;&0uy!7ID|9w+qv6Y;PDoy`G0CXA zDVq+Q#NIz&)6W2OHf%rc^~;}_>i-?RRq{V}umA7y)PLt%S24FiT>i7 zQ^barMASosx`zZwr?aB_m8|R+5o(EBanRT)Ky#4j%Pl8ol2!osrj-`=u!&>>VTxFi z3t=@MC-LQ2^cnkgav)rMDM9kRmii?+Z-0HIrONk$%rZZUo3d#?opqn--c|4ZE5x;9)A=G-Kh0=5*(<8kL%ba1*nx&B1cC7T^ zqee7}bR2O5Rs2j`r`ptxx$r5IaD;5oRjGfWsVN3OKb3mKE<9DEpg8fhCY94~hDQtM zwFUcC2{{IaR_35EJTG6}TL&WJ8yG{o;6^O;dM`W9wN$!hdI4ic3fcuY5(Zl;S8pjC z2KrZ7UZVasHbiNK)ey}4R;)l9fO8=Rek0Ks+-2nSQZiYnAVqsp-2T2j@;{SpiEDJ) zL~7gf^Gi~(S7}AuRhol60HV;B_CyPyZPrf#Emewi`mB|yuNhM-U#D)NmkTsapI1*G zT~E~FOxL((_{I0?shTaTjoa~6T+x%w^p!YQb??>L;a1*&jQWgb{^BQ4KI?&#@zbTJ+#&a z+zr@a8s(#4#XQ*hx$4uj6J8*_R7T;-Uv!yxHpCHwWz`^qj#ejya8jV@TEk=};WrmZ zNilczb7JvtAam`jEp>m~Vvm^y7xq~v=G0!bXl$WyL`_F9J-${faGy#zvF)m*$8 zDgBZ9+nEkA-^Ut%j)jbmt-F@KvbD_H?@o0+&9@jEF*_HqHMi&2*zf&T9J7oxGEH5Y zIo|YBJ%0E(&^=JJ=`H0oon$cQfn0ujLZ=^>%7WcMb@a?I>f-~sz|+`NhXZQ#(RiZ4 z?a)`*OjZNAglfB^D+8zWR0F@jXhG~Wf820bdBarGR%Gs9_91#R0U){tN#4u-O4E^h zEig5R7dDkKy|7ptg0K=bJKasny!ChUW8sKq7RjHA8#=E}WU9tmk~CIo%eM_{U;H$8 zoLxY9IHm-AI&X!Jl!!DW2*PY1zcygRVX;^1D>#jy9g{M)l()29TSnN%=;jJ37%Gw) zBjP~M^ro1x!(=FJiA9;F<@esVP}7;e*b-}o9qUYlsD#DP|MeYY>#jFvqB?X_ONR04 zC~I8buUfbjJ}6To?18_(eSMNz?8qbPEsXpL%qM=`N`-MNM2>GZfLhuC^2BM%g=W*$ z252rDtaL$ST7Bv3S<}rBbn_e52SSuzLnSz-2lv%pbT}piqmNb;nGXX`6giGJPFe)) zmXB76&~52XEh?ZUjK^%b?UW(7%7Cg^C$Q$m-*cM?;-04c0|5f?Xqv4 zW2H*$Oc`@@e$Z^78u1c0AQB}&pqLLv*ivO;pOCnt@{H1AdZ*{&3!YOL`kVhBVit5P=rFxhbBKy=aA@p-5~B6Vb#1 zyURF~3x)WN66z8H@kvW1S<9yK-jdo-<&>?uwv9QB?K$Z_%AOU>i%D;JeT3rYT+SPU zhi8_EWW_XQY2>4#fL|>)lN{>#y&zw0*O-Xs1%8_v@SMzH5Vw`eC`@@vZZ@V;{O-{b z=yct3{w$DlL!_;REY_Y`{&f)o%n5asL`?y`W9*v9NZ)%RWMcjA-5}x%JUP>hE4OIs8D8qzr z(aW6uHly|l7ZJX+ZT$*x1zlmYiAtmN{`Be-29oYkdqfqug{?;n-+}-kZTgdls^w%D zDBrk76=xV7--1RJcMLv-qVXPDHfau&+&j>Ahrs7;c9QEY%wtQ3pusfAa|oq0YdtgZ zA$Y&j;d#bZk@LMFh+^Yq5{^<7(8MeFI&KNRK#G#Lbuzt>i*jQ@@(C5hFHfbNOD%z+7mRPthC;uP7_X1j;0c^)e{;g9sE=ctH#yK|D!R8 z+Zl=ee})ncE@J*`*1sPAxo&LIwbYAZMHF#Rz5$L~_JWj0T2sLKl=W7ZP6{NWbf^n1 zPB1N@r#asPvv~0J^c(0O|3_=&z%#7C0RV)s|DB=ppTl$gA9(~!jQ_NC{%6g=p^Bx9 z!ZNzol-EW(W%v~WUKJin z7a~(AbLi`g5~d(s>cWQ^i8p)ZPoc~xW9F%ZcLUE|K0~IdvBdWCMmtnExL(7&sV~>F z=QP{(^RQ>KG`02zcn`kENw2?Ff=)Ez3t|WOZZ4ME(_LM3a&V?ivVX3yi)%vir^GEm z*GCE}*iB2=WUC91bQ$Z&3m)<_Lc6zSp5e*wY|g^HVXcj@Y}&{9R`8wT4$l7ZdM(c2 zPMIe8SsfmMmMW;2=H_fQ+mBhafP*P4$K z{4#B**wUHA| zsmW5K3%^9P@cF)5brx-?ppO&Q7wV8I~fqb;o=~^XPL6sXG2}>%|DP{imYwi>OB^MvY7k z+j5bb$=a!@Fp;^FMTFVOg9unp)5L_06xv5>euns8s(V)lRK9zo3&=9=`k^TD*NDI2 zhZ?{rD{`_ID$K8?hvbX4(jv}-g!(Q%jku~(Ykg(06X=uhFRC}msVM)R9!093JhD?9PDA{6B{JSN(I4E zxtS1@(a|^E0y)n)SBa&w0SGG?gRMjm+V3dcdawJLw=b9Hyjp{rQ z?PtL9O+Z*?$3=wJ%V=#Pm0Ht@%4p(a%to&GMC?ftRct5bwL8@Co}bT0uEkl)P-rye zYYuE(NMN)x`D6I5NO5CF5KcYE5MJo58tsa>XR(SR({7!-qD_h3=g-p-|E?J6Vy|hWDk=Y};-#{YB5|N}p1L#lnkhCA#D=}1B01XR}s0{b` z-7BVL0t>(Ckf)wS20khw=6zBfu%1r(=53`tSt^j+#ci0jw#dGmPoZvZR<+5clqWSu zPrr9=iWM&Oc!I`Mg~i-KHJUJ+%QC>acTbEhgL0Q3Ho4fPXr)P^g;7R+n~O2*`GUT6 zlZyrA$yhL7my%4>p>SK5kZjg*+ON)4;c8Z`&~k*Ss%N}E}g#Y_Zz69w)de& zAf>AYIOCedVC_9moT)oI*kT3fR~u|p50imS?uuSb58ajEMd(aJ6D}N$gLhQ)Pk>^N z7w#*>kd2U88J$a*u=c-`1@=3M+d>%g`~}7HGwdzcE^cNP8EWCGuAXu8zy!@Fzsygv zG1LCqxn00%J_?OR3{o)vRxw6f!}X-NZ7SBgEg1kQBT=l66EaV%$aEgD{>&H@#ao_+2gf`3xCr<8Ac#iy?W#qR^PAtoIr6^z`b`r%>UmybAtci6#Ldi#Cb3=w2saC5HW zLoi^$xH&VfV?|&yk$z#hBHRY`!+MMOwHk+XBT|@TLcvvX>-cMJknX3| zo1hx+o*SA2vtr`Di?DI$WbOj)>U9WIq}lgSBxk%bSk#!%))%%-f#4`09f#@n6 zQCGIuG{(LjS6h~vgTkJu#CA7IPJ(Muj)fZI4bjZVc1=nCdBW;fDA=KWu%?^3Ubl@W zY8BS?W1!FDA#q?vd zm;qrK*TS%mF)hrroI_T>hg;Gv=otfzoPu`VNT&q<4u!)ttYqWvW$8tGxF$R55Qi)Y zM3@)qt3R0}_?aY2t4$JF79=H9@t@hNtKITPq3m&=1W}m#O_arvPO44)LK}z5b?6Z- z*4&MTJB)>Q=pdtbcpcJ~@07^TY;ras3Ea_W)Dh$nnW=p((P8ZEv`$8l{?kIJLE$8} z>pSra4=tKVUOwv0wR+8oiC~%!s1Dh~6Y!fzt9IPji*b+)RHeV4pKZrHQ2WXZ& zv1@M?^6Kj%OR(ckcu`vIk`KQ~7eQ z+ZyvnGIckMEGeFv(mE^G*4b9qvEA3xJ1?c}M<>^+Wyek2(FEoC?__U4H?;P1-|M|2 z_i%x?F@$R4rNOfpB3co+eO>Qtw0!GK7G5nv)s)TbNFf#)VtM7B*ON@FXZ}3=s(-Ao zy;dFw9nS{ayeIE(_Ow5~R0Sx^p@5xGN zfN+o?6K0~hfS{!BgG<4{5t>faNKf$JEl!x2tel&`TwQ1>DWZZ3T{ZEirD|+lM$0g9 z>m1*)&t;pBqb3=mIl$@mu3%JPCoXnT)U6qx@7KJ-&4u(%<9z)SviZJn%%lCsFGhv+ z?@UIS|JXP7uS~{&9n!c|G5=w#N8U2N%H)V2{YyMbXoCl$uC5F;@D~9RCIk?;O9mT} z)?Q}E=!h6SBRQUf)ADcllW*m8Q^O*Px?n?C7&r_#zMPLJei z%JD|)v60aoE|RJywMqrU_Nx1K=k(S)$8lD=@pq>&4}gRp99IpR6H*^R%{*u{xg-M% zz`HUy!i8L#l7Gr2wU7Nyve^6^F|}Np6|8;F0GHT2z4!(MUxzT8jj^jxhq3?fYsIuF zzX+FD%g+?Mna7;>6CXn-Wy(5#QeN$#ErL>Kv6ZEHjV5f6|S-PL2Ve;&FP_zrI>5 zpNgD%Hcpg_snU%O@Rd^mku(i6^gOvp-_os2&^$b^z`zQ>KoHfu6g=HHpl%lZ6ra|4 zN5?h;BlhWO?MQ&UXt4iYKGsDfd!q*xp7!A&(3W4C2vK%Yq#%ZB%Bcv~W=KbqWXDXp zK*^Mhkr)X_V?KkHnplQ`koh<1WeD+F!^uZN7k!+F^Q{@e%NfKncDbP&Crzf9Zb(G` zUX?(5EaJeh!K#s1M6>_jPl$)#&Pw=EQe*Y&jl`yn7QLbuiw+wb473NyV5SL%#~O73 zIA9D?4RuNRrTo+C$s($A_|PJX1h2~#c-*leC=*>Upk2iRR# zEnQ|&u3v6w4O7a*aB0KlY<>6d>~!M+`0oPu`J6G{Pl-kYt3#lqO!5Q<@28V*=vGV9 zJCZgiZ=yvon@gv=ACAuO^kzO&PvVd9b}AY8^SosoJD0t)+@UZRY8z8kgO@NDDv~Fc zmxxrfqd<-*CCxsxSr&jD;;1%0@6LKOoTaE$=Yi+$yFpqmb~F*(;RLOk#I(95EYn z`qhogNn%8b`Q9?X+lQ2Krb|7ZAT0}zK>w_1-hk13z-tYGMRP#VUkJ9{HoMa z=?fZPwE@LUs{4V=N~-78=f}k4vjFF(@C}#R!W@FC?laeN`Lm^S?luqQZFJ5)R#eUK zfP!`3w|;|K^mmoxrVe#0@VVoL8}n`vBQ9(nDuk~Y@$F%1!it@G^>DGckIt#X{oN4#{2Hz!yll8ekD|BZ% z2}Q?xwqiGO-$%)(sQ#~l+`=jGfi-+vub+BXMSeEJ^57>c%s(jQ7X%Fm%N#Cu`h1;L z-JWP#JU#6{5fT|C)`A7pesmjH$|G-HO5I_=-{5-_fJn#Uc1Ov_6V)TBG?S?`$ zspf3=O&PAF#@JJ7<1gXHxO=cj8W5m6fVfaYk<}%#hKr@-W#W$4zv#Qbus~pa7F1}Z zsBZi>fWrokylfu-0tQF>1)oD&ZqlkN4>)qGE9;$qXeb+<3$3sxo(rwEL8>c{I_g_) zqFQXGYCIFEJ113^@3on!vurIb+H9^iS>;uh@3*jA6Rn2K5~z^r6gu0-*##IV%jW%H4sL%`1gP>guAAmG0kw6Ef- z_}cG~Leg1~^4p5&5d5SbDWXN^B01C&6VU%=V-q8gV^s?s8Js0ofw3yVjn{=iC;(Wx zQ$#V)t3<4=ni>%6TNVhgg3nbKI6;AL6AXC72NIkn24&f)f7zpj2(c!D3x_at-_6j0 z1vBO(3@fP-)QJgc6d|pL^gB5>;{9#O2<3OeUXL46#qx84`J?firv%TlP6g$Cu+;jk z6co5KC7?oruaOyQld1aas#*Qz62+@MaNBA(Ik8v53z6Fv*kf42YlYt947w+IHUOJ7 z*=NNztZd=oZ@j;>2GbOFim4t;(hwCRC=*kcw<u}z(DbvTWQ$h?!J@Xa9X*b zg_1#V14{W@3ZFrop>3$CYy^t2Q7DFZMW2QlN>PF^#aNh90#5NrMErFZ`Fdw|`@M1N z{c-#K^KljNx+c1Fu~Do1{buQBYx%g7^3LgzA8ftqIXw3ce_H$b|K^v(3QZX^PI6Y zBP?`VaR(9xzRu;Va_}P{oz-Q_rH*0W}>*H<%PaE@{eGCVQMJgZ3}mQ zXDXw>K|I6Q>1&{lnA`$e$0mg7?q?@D{8FQJj}kXLDAT5`v7DkG0L2}ASJQUO=C?MB zo8L|=z1+&byR9Ar`M1v8@qTCIxGn0o=MHvBae>C$bf9>+)S~+*7nyY|N%TTZ;&+Ty z3_^`N-{#ptX(=@AC>{c4Tn1u>LN>>lwM13~O&*xGY|6r_W3g`>s=zsOXa%_c8Q$S8 zg=`Y1Tfw{Z(VQcx5vC66v_rgzN4#mt@B_AE;l#7{^S?84k=ud{&Y;I~dfP=e2G6p; z@J)Utwh~YPffE7SB^Kabp|}i4het+KREuzJF4nJ^u!NXs)jo1L-;bRml!$0ni zhL23r8vtx3DC;4=@aOm)*{fC&l#N?95Jnl8jgJxTSla)#1))_D1;WG6C~=jf#dIIT zqUt)5Udee-se~=HI@W*Md}k9>!I{BP!HJ}Im^;yYC!?g|O8Q>OnLwa~T_r~Wr(B*0 zro7H|>f3{U)Om@s8gD z77JCj$#9cif?Pczzk#@`^<`N%q6zejch{q~9DD;M5IEv{YV;Wc(LeE4JMK=yEz=7| z{_+?auoj+wT8Fiu~8cdZE0ywEPd^Xb^YKBT(Xvj0Y4S*;rz5PJ%K&9m*Mj zkHCP*51bR~ntS?st7My9{x`4aMvHEFD1;DV617IVZDF?nm%X?ep@~R~Xt({*!-Vsc zhw;&QwRAhc8$47Vpe`s^V+hDDueHxknfD#ZhIC~W*@=7(MGJO8B=8t!#o%xL5?l*^ zg?Fc3XfYRpw9-1(#slZ zn~J7cRds1ZVx?2$R$M8@3k`qJGWv$`WjxJ?y1+BZEhW`o5&BJ9j=wiRv&M~K>@|4` zs;R}MIph@j@jG!L^o`i1=uul4!~8&Q0{3kfK^abxa~dbWM@LB>F)8IYm?Vm8O7xu3 z{GgKbiw7+E$yU5hV&9luV$Ds2!u>FzXZ26=NvBNEhC+hUA+2)d`$_XKhG^x&ZD9~o z7H9+EF$QNLCpnJVQtS&3z{=?+upHCAiEV||vYQ2GYcl*O*!U+QOI_z!S)t_E_`{O- zk}~quJM!w*o{T@4N@L`drtO$+av*L97+uDG)lM$(F)Fap!)u?l7> zN%fiL$>U7gMC}L)SMLPZ^p}87rcFu!>`Isb%!PiZNg}OYJaljxWSK zYX(kTf8FY6Gx&0m(@@WtY679~{V@bmkA=JO?A3E-_^95(Jw<cqphF66-@D;!vo<@BV$wlt2l4YywciG&yG zBg~j-7`I24XQ1!G7hC+>CFs~d+i#y~?y59cWb7wK7chQMIrCK~TwEE_76|Lmc4n~) z=_)ow-K_Wg&mzqM(rxPRA9ADRpG=bfl|}MDxlhFZ?B| zP>++Fqlo?bZ{P1Ax2sJDJR+ikBy^p(m`(d@F70mnX*PH3ub1OyMF3&lUo)ZMUKc|S z0LeGGaGM^qh<`Eaxe0+8UqX1O!EWfdcNdC3=!RR5opXS*Z-Xq62ik8Z6vaGu=t_B8k9)Mlm->hVVQJrvNHc*;H4(5 z>jybz;c@eH*A7IKo$#4yD2JPk?%Cbn7x?yaR3tK*2h;}I5P%)0(bv+I$I4qq&g<`+ ziq|eEkg*h{t;Ok?il3PivwGF@bu`%Uk|qBnOxUINGKh^sU&^bAcB+sWDcCEGo-o$C zkByMO84fPIw6KpdzDdR8Xa@5LlKTj>Z+H8S*Pr z_7_w>AHv)x>B(8uu?0=}Ss5Vx@H+8{C<5^ z6JLg*p^>*PK=74ffsT$4?%mszKNn(=r$9hy_k ztTKF>uejvVcV_NxtQN5A4w+k-LmBg0<96CCqt;vr{WG76B zbklUHHzX_t)7te#RQV^58!LqP*;}7jNG@w>NPTI&g)exmpF*Xyz@((7R)g8gyDHFT zNp{MMbh>+f*J3{8tLvrzeMKW{Z}L1^(I8P*2s6~AKt50~nx#*yXq*k*pSrm?ouBSj zbrNM_z2V8eZ9Ic6hzv_rBw_SoU|Y#40IQ-94-3FHAiUsBhEs)LD?xb5TMsS>;Dkg# zK#QvZm<&Egu=<-!8wCL&Xp+%R*!x$tPci`=e;OvUoNI`-i>NYG*8z%eL}l8^mvf&c z=q5-HS$zHwN}xzWzE#qaEvD4OO)BDqd+mminGHSn9!*+ERoNuHh+%oL;zgLO9J8bO z3PSjd${A_lari#h#$V0rXd8-znQUxEtV%%>4V-1QW?i)DiJfkR)gbmK{eeo!L7d_o z>8XFW82wCWw(`I(i~B-|1OT0M`bg{vj6_ND9`a3gxBH5lbNr+XYn`xE;;uRAYrgxXsVbW8ZAF!}Q$ z*!%k{@S(-lCksr3;)Z)Ime5+x1JiEsm*2m$?ma3dbV-jvHU3ayCU10S- zUYr5jz6p>=YF%3hvl!Cm94UoaFx$E??hyHa1&Wv`aBF{9xhj4qhmjv5(^)(Y_NbVO z$g_svd=w+sI>^#mdpesQMKsh3K&*% zvf%@CO8K${CNfK%x;jweVXS!2u;0h9p`8cnr&1N%JyK)OZbRKJeJ&$(*luJ0II0hcWKoNP zNyf!7k6*jYiScxkV|l_Sq*qao(=yaYc(8EWedtBXo)S zS(U%RSEr)?ZnK0srX$)y{rV?equ-rB!1T`^(ue-P?<4<{B=0{*clkf)8vk{OUU^#{ z^9S99dX?}uN^Zl@oSfL~(qCNjT>L}jLJ&eCP%(Tp6N+>j(Ig1WHVYdxoX0`s;a+EL zk6T`ClX8YXS)almGz<3EK}0gRFf-`F45LRI?$goN9LF0Q={#R=mqb44JBuN|Y+&^P z8Fe^)exN9ZVdz2@^Dv%2QYr+oo(IPgaNz0KE{7!m99?i1j6OwPVhwI!Fp6~H7$gGs zTq*KT&E43?8y&nHnXIeK%iA(9XNO?2)G=7yJd@7ZN*R*&%QqUp){fBS;fm=eQS>bt6n8&ORSM@TG9-8rJO z8?ABbpE_+}=-g0;lLal=Wsu&qO)jJLA=l`GUlrH1Hi;8B{dxh5ANAFRwCjX^(d2^j zWLO}Kh$vkL4VMWRU!0>W45m~FTF-}$m3ikA6xA^eni`Wx01aIf&Mm;@i>5VUtfFn= z%|`Qd2&#g#?1YlC=?*#TYZ0H4TgWgCKW9c=tXaBalZ6|q3Ob?)v-Lm}Sv);a=_~q6 za3q(YJ``kyiTM$U5yeFnLrt}@yu8%HG~>0WBsmjBCK)qwXt(ty*K9Ig>pFI0#Aq!| zpD}%KN5;jXe+xsPt&-e=Zk3%vlsJ6Ls#ZfO<}jOUtw^tT!p4h%79<^J>%k6gz40dVV7&adebwZP=emB?FLgH_bbTp$%|IK5`2Ag*hf7Ln+~HYvSDPye zDAc1@?B13?!+tr6qX(bj?bj!@yITV{a^#D`AQt!izCAJ=U9}!yv;yZ4V$jp_(cUmB zIZ7@RDjBkA%y($L84sYHs34pb-3Hg^>!i(b0-3Q2r8g#`=#pJq>MTN&VM?mlweh0E zNhHT|LDLMKWShGz;d@kIhIotR1xHejW{g2honM;{P1Dy^wR}M>2Uit zx7E3MJ(5r;K1wI(0e)E5=q`Z)s{k#>4KJ07q_2+NL|b z>krT|khCJ+1wp?FOBZDaI9f>mEapHYkEF&>=chJQU(B1?HdeK%RTel#9*{T8ZnV2p zga1&u8#Y9ePhSn&bbpD0059)5o@jn1Z z^9^ff#2$nZxWyYH^vyxc6ZtEMwrrXyy5eq5b+z{1aO49MyATBnM%gYx2Qo?p(R9WJ z#8DFI9+cKk<1HZHqAI~c5e^$Zz@m6j-2F}X;BL{zr6=OBfbUhPzA8N;z6M78WO|Y6 z)*d|}2-5h_A^hz_Vv0o~6hB}N*_ko~VsxV8>hr_SYEF2=6=xNDUYeroFcx8fT(1~x zJu8SUUf-xVkyKyQy87l*kZxt#O_9Wmuk$7@wk~sNkl(MI(2)=ak1G?}C~L}n|Eow~r8uZ&s)%e0f@1q60Yifi>Mgv<@B3(HtQ^mG zO?=JJ(HJ~TlFmk<566LWl>{zV{W$iB`zR+M1eXWbY}gGlD;pcHN_y77T3;j>%UdhKkMlt_DXMhE5^N}$G zmG4e`{$?!@;@-N>FI&8Q{r}h2`X6f{8D}deb4Mp*yMGRq5&ydyq=b$6U#2tn_=gbW zq?(o^iVDIX57+onSyBW7XbIw92=uGp(m^9I@~?rz z9@E4mX6GUy!K{2s0;1zBB67E!jXNgFVp}cyUQ7M;q^Hc+&ZjW#wO_p7B z3~{vNG{i>BmHG{G$%aw7-#zSFeeroQfA-ATN{p!*nY0O`NImuPH_{_kCsl8p1dXb+ zT*bV#&{Vx(HgmFk-CW&1h0uUUzE@W+SwwPx%uHSp#raV{mL%j>qtynh$`)Mm2Q_0m zC(fpesz%T$J!2|pqZr#h zp1Z3kl+~mqTz}(A55`lh<9X}$ID|8tW&^>LiW3Gm`9c1;k5OUwU7i@xW(RqkT9QmN zXfX^qi8aye-$Ge{p}}v%=2UuN_VMijB2U=lQ>;XbdBsMOwnqE$O(&+RMGn-~Om$e8 zA)y7o^L|-VC$)~MsswWN12B!F``s@wD-z9(?rXCxf)kqz4N3_zX**?jC$`I;eq$Z& zAi}EDut*QXz``3A1!|sZNAw^q$5TW;k>qRbn5v<~fOXj7E3{QZ)}OD(MfKQqFR)wd>A$)(ANvNDjSU{w&O z#l2N*1ec=N3N}KYe~!o$uF0!-`wnXI`OtK6En7E_FzEz%w-f_?o^X+D8XE555%??8 z;1{*-3+$Wr(JS@2INa7;p41(2wVoJSJBj|1nG4hnY@ub)b2#%Qb z(6VuQYFM=gMEB|uY8e#2xh9YAFQB*KY8tG+>U+0ru5HoY3zuK641LQ!Vsl)alyLL? zk^`f>wysE1+hPzZ)PeMbRq?2;2`=?BPQd8i_<$7b78KVLd>^of# z@;zKXc7}@vW)K~FED4n<(RCEGc_reJvHaC)y~DYfgU8Y6e6j z?*)J%@VWcOVuh+%O(2TYlQFSwMb zSU%Pm-FdRJ;7vdbV;bJBA2(crTdmd@kowbX*O^E{ymAejNYs~6tz=5Y?z}P8jyz>Ibp61BIE`vld%u|LN*y+ zq0sYL-mp)h`!Jt@1BH4lPaY$bJBI_6xeKK`kwGbxP)>D}HH1_}GRo8M$%9kNhbS6A zWkvWg#Ey6gzg)s;*;~!bWC-+fBQ^v~ZTJJ2p~zeQ6YMW!5LB>R==h~~ z{2lH;=DL67{lxw!WFTtp;OO)>VDPsZ?Y}_>jf$I+z+YUuD4WcDU6#R95kZ@y2!s<6 zLO_B|N7~XpXB{6aSG(h15(TfG@(eqQHPR&>VQ03l@RIk!5 z)^cK4&t~>wJ;|t00H{Ydwgm*lf_!CLe>MbM&mU0ODK-wReu`n5hVFf)rfMzl%}%~g z(7!x_k%FRv`=yYT`NhWm6Mbx0+W%EF|N9@?*Ed@SQ#ybhz|hQ?&d}D{`U`;3Sp%HR znCNVcjOpY74ghOoCu4^%h+(AW0I;+B2hu1^04O1gVGMtIO0?MFl!(h)SZbA%K<Pq5Bq-td{}MP zQkoe0V|3xmegWEWO45eYJL(8JBxlS(eNI^18W_%IJDPu}V9=D7$&<8p(I#9IjsCvt z9_Efa;251@Ao0eOVVXGNlP#+ely?L>6V`a$bJj-~Tg!Y8xU>{!(1BrO>g864s(b8mEPuL{Fb}hw`;isH-Mt?C(@lzOmIm$N0IK6`ce=OjAB=d8!`wHCmSz^G*(}`Tt=)iv( zwtuu!J9&xKTnHm5nyy|s%`}B`L9YYo9_{5(8{sWh6ir1zW(Ly+&(PhW0Nq&JF)`Bn z_i02m&UgC=+lQF?+Fx`hOQ&E$@I0L!RFjz?l&*9dvP!lDJh>t=6kP5ERii|Q4@ z>uE2_a}sMbG5U;^Y5`?Z;fJP#OS-LlGu<`#ecn;$XEU^%pTGU@o_oMP#Mzt8q|l#6 zkC9%qwRDR!i&&+igUhW~Fbxa$_&9oA!x1f2qDTxXXo@_ElmR-mmL`WMmVbpUp(6XS z;+Lo$IQV}I+kbsXx&EiHHFo)`sT}G4_KJ%9^?>iP1uDz9vg9VlJ%exvcxT=Y;c~ci`z6ZqPBOsZ|0};?VG2 zj?Pm#wp+7b9`DB0zRjy+1O%>|w8js7tCKK_!4|{|B#_>z3Y3733Zw{f3ire;ZGgb) z8g9g=r%rg!IlBgPwd}M1@Yqz#RXT2C-G4^i4d~dqE-2$HS9D9PLyK(e9tel|Xd~^1 z0ZhAqA<^VIwZPXKd|@$7jGykM1-eFNCZ2-qu^+86K?6uSM&gMDNOb8BG>BH$G|}w+ zB-@8ur0@kVwoJ%FdSLV`mXe|Rqx%5z5T@nuhg9>ho)G{KSLAk^$FB_L81IA=Qi6_C zgn6}Jo^N$oCGk!S%Y!;#MVL@J5(8|kX1LVjWqWOyG43E528V=?Cg$nQE&KLki?2&f zcFw^Q4uhSU@T!-Knn(qrP?&!EOIsBpc&L}lRc>AbHeuo?YD=h@zhi5ZxH^jD#@+lBNtk1!+rL3<2+Q`B;~Xh zrOXI07AQWC4Khz?5F*j(n}w$x{m>R?K{~39|BbrQ^VuD$PQPK zc_R^LU_C~z_dS9sjLE%jj|ebxk4hX{ndlvUFE5dRRz*#47slfZe*YU0l#ei!=%dIQ z6pS-u@~PMT%<4*ZJ(ZIS%k3!^lC=fSa{dRH&0JOv*%R6na$-TdDsiaZUqSJwu~xI< zE05*=w?V=3zYGdx2Y`*EiLHb6KQdXSinZLlJc>`7vn7Sd5&u?fb0{{samO>OFeyxB z6f6xw`Hc{!afDUo*OdI{b@WIQ`+nYTJ>Qs{%{oHJKtSWD_vHo8wBuB3G0(@x@i5&t z`*R71AFBfWj*!1s5a?-skN`l_t=tH93PTtm^DGOX+(--rf1Ow9L5qi{Bp^5}YXLJ7 z77^dK{jT_Fjfe;da`_thvl*vHK$T{^VL4p1&_I>l>B3|oqAj0v{_Jf5EZD8h>KJuD zK9-9yQM*-{QVX@vNI4oU@z$?2g{(-WlANmvpz<{oKH7kc^L%k%HAGNTXoB$yxtiiN zED&-|GT%<&(RQ5+d$<#-P*F>toLB4e{LX1@ejLg8g1*&+QBfrIT<@-^uW51T@sFCMqOU{NWlxl9HKLFyrvCIqXQC z5@(msl?jznr*U*W`C=fFs@Hqka#GfzQqM^FahNLDy87=BWZW6|c4Pez{WA!jKo}sn zE#c%Wofws*kgFt%yKi8hn9tSvu=Yc>MxOabeBqv1AB{n)GpMVtWw-^fAHmLf3ybc3Tq(kPan3F zADU<*%SBD%DQH)P54#D%uuAC%4hVA(#*zIQ+y#0;6Xx02wH36;ssFA4?|LJ%VV2V# z7=zb^X-2rgF9+S}@vK@C+6DHig)!6bFNiDz3lq+VIP>A`WWlK?)?5UBb~1afkNc5E zyTDMvvctv0_eKDPuUtzz<_#fHrk?ccRlHsSYL+Kjh1<~%wmB08WDSbTLq`% z2KydxgVc8GC(E>dLPB(EY7&TAygwVh?& zyakW-*9gYRC*PP5{y7-2Y8r8<3u-JBx_#{tzG!H_4lIKl^-yZ8c802t1irsWpe5w;3L4!r(xTN0t@TF=1@0V0ViAecMLxG&;X7FNT zRppzVv$JdC*;!j#Tf2(ZO~%!hbdVSU{U-1u$1b zEfZPP!%A+NBTR>GXw!-NBHI_~P?JY|~#mVCwd=jUx_y-3P}%jPgagod)Yd?O}YE`nEmf3jD0* z)r_;<-;MeF^o@4V_u2Nfwfxs-3LBzGHyzqL|44b=d+vmf(atc~pLn~iBBwq{7j+`* zQ!mP8-ng0zpLV^W+>Cfx#0fV_W7D-bRaQ$=$R8M770SMIQwXY7lBQsUOEHNn05PP~ z-d-n4Y|I7+F51w7w~G)St73;$@pc$&ovg)xGJ!6u;LH_Nxx@2`nnYsx2>C4W;-HI( zpP7;?0T#R{$JsOrf~7;ndjUUr7zg4ix`^>L-CuvNLyNULs7`HV$=O6T)&pzWV8#QH z`uQ1a&1sMw!_+gkg+=1lDSgOV@Rv@Mq0zNxew_g&|7v%fdNr9%uVhV~H!*%t&q$Ck zHYFP4=@y*FYFi3Y(_bV1+RjAIn|IOjA0Hcgt3N%cdG0!#3{SI&+WDfEJ!Tc@f@(c+ZL^Te5Lba6a{}pPhN?g74e}HDcY@ zV`-~2ePPG`oFt>8@^D~fdiXPwYAG|Hw84xNz(qCwE9{r;BIdix*$MKzrFvmhyh9JV z=75HLZ+9aqnP8>o^MLlwdqlahD?vAE6SZCeRj(prc(_CVG@WO-8 zX+fe?`?SG|kOmorz!^Ha$us3V1*dR}RnZ;?0aQ&K%a`UQoiTNGvtv~}dzopKH(h%* zwIx%;y;dquK%uEy_V2r~+*LSBGx5$E8)HV;0P(8^%y^eDOqO5?^FF4K2VIAssC?yW1}RYY#uWp!T*dlD-dLqATZi>;a()mVq?t#@v={YtkE$%0iM8M~ zaP&a@kP0-*WIdw+I2tsjb96luyMkQLS1y9{C=IC{UP8PqKvtSlNW0RKasJwY5b4FK z7qG>2#$Ll2`?bc?GoW1^SC!Yh$_OtgMb#SCJKgO3q(8?hDNK^^yI2U?*0t5&bJcC7 zkrD>BaW*|zlkpVUdv4_8YB4iOWhH*9Poz$=Qfm#V&~m^AxB~7f9OSWMZ#nC{6vGem zL_QlDQxK)W+vZ-R`?hvQ>Q!YWwc6&fnxq>H{X@BfWV9o*Q(JJbVc(lWv-i$FB#HU7X?G2YN>8}B5O`g|WA_}u%1dG8Kg zzP1GEX1LK>_0k!^e$MnWByCoZh!0_o_bR|vHi*lHiI*&$DEO9`ZnOu4%tM`J!ho+5 z;$tgMlH6l{G~m#bPzGUbEASIr*?P{ZjG;8?Oge3U>L?8bG{3*Bbh~B{ucq#$f=UIY zg3T;T;&`SNY?AGin{zt{TDlFP`-f9U;Sc?}^%KH)tP_KHwCny^K>`9CdUHf}`y|;b z)+zv!T5Q4KX-%tbapp+o6k_q!Wy@9c(oY52hcQwr<#jaA&Mb92-CY)rcr>ov6MdKaLYAVllih|R0Z zvBdSF`0s&D(O{(4u_`uM?oVfrww2!Rp1h_^g2$`bo*SE$tmR|)$novGf1&_haDxkt zR7Kki4)Mdk+UGf_Fb&}g>dsor652BaY@9Y|19TjUnjR0jL_Ed~&^-w%gHfXBvZ9zT z*E5xurVdCS4U-lei57k@(%8!_3p*a&+JVv>mlu^kydyVe#hjJuA%(Sf=EQH(-{=&r zoq3Tekym^4xx}4WX=9!0__iR8c7@3DylTde-rF=O{F3SP(zkrSjoe&z86;tr%^yr9 zt|gLMkPFz%E%lnr%ySGKoZ9ml4X%^9z$UdaPi;j*#+SXY38$IeJH+AgyqHkx3>Jtc zNxV7s?z?n2@O(&3wRlNlKCP{PbW>;zE4(XvqOq^bR4s}u|0b*ZbW z;KHSp$t@WTZkFtt1TMui4_t-{(PQ~Ivb)`uzpuKS)PgwFT5n(DcyH5c=lBC$7W_zG zu=YW*)WyUw7mW5Zk4O(J0KZ3FN4 z4YAI!!%)3D?~tm;t;T9@#(%Lj#@$Q->A0cvJ@Dhq`fv}|4l2y-yU4wmoczJ15@p?8 z!o(ls)Tit?cXYmvhF@do5IYgY18mM9PoV;(+ncJNGr~3mV!`b*RKm9{MjdQpZLs)Cz#hCsMeNxGV z*(CX;%j%iP1o1w564nGuv03uVf{ikyLq1<$$pZ5e1$BEJJNCxA8}N9#f7P}A=EiH? ztA5SY{3(QLL|#?Rsl`D0EEcbxH)t}>fOl`2zP|n*1zyjEz=PK86rS2+MNZ3RHik$~ zCaf@sK|j0dD*{U*)1-l^AO%U9v<)6NtIO>XP{KteJ8RgIU5#iNXmYURhrEE0y^wQ_ ziD3Q*{B7)>fA5&t4|QA?F$G?RO)Y_Z+YU`_53gWOcD1xDrPDU~cGP6T0v*zPv_)!` zNAu_PC1 za9ffAZ{oxG%3=9Ndm?2$S|W%h|y@`S1vZqb6S%%n)@$Q>BwO>aO*DH6v(WB zmk6zkWv*2=h_pvm$%p!&u()ATwQ7DK64mrBT^P@l<)SUUM!TzurL(*94fr0mB*dm%f{qQ?eJFmPEvC05A_+bqJq_77NzSK)k-h(*5 zc0<--s$ahp!DWw*{)lHyf?g4MzN~9aak-mXx;bQbSNzOW>c6IgEZ@(BZt-WMJhlq; zscxt$>xr;Le`&h=@EX9|+AV*(r#s4(O;mLIjaau_RAFD#L4!s$vQIDk1adIOBm8Xj zCD7v$5$AfKtFK7>8*DJTWI9nyot=cj;a<6c!(w0FeXH=4>iFvF99%1R9g?vP?+HmS zyJ~Vx%$h=mr^6^`shVa_6zB#2*C=nHj=HqJx-5k-MdZ`WgSY~i`xu2K?GBk~Bs2tX zg#WpdV*MLN@Au}bVUVoA$*g@)5li^|Lx5a3G9}-p`ax;guVTCbF&>WSn(P53o+>qq z=%+FNU(c7Yw!SGBckeBt!}b?>o;%26joezEb&O>Tv%FC&TJ+I2Vj!En>h5H!b2{oW zPbeHY#XCQ;9t<>QV628#OS1+*Y*sZgA0(BLFtb+l`XSVsKrl~{ z+9d27^eOxUk!be%yxn)$?XsblkegmM-tn^Y*lSzkaxS~O`{NsZZ~_b+8VGUL*w=ak z5*Tqu4B~(k!5$Kl&;9r{Tc)mr`YjQ$kolCJlzLK4-#0K4>$D9`rUuQ(WsITQ^wWoj zg`-DNR;3Nuq9s-(s#Yf#Z!Q&a<2#O^Rp~{_^0i#mwPTA?%~IvbG|kzwH)spz__U7EA1NR=cqHU4pT*NPvQ$l{Ku;B$t?UgE# zoH3-f(&c0fK{n!;C=>{t?d8&2ep$M7%}xMfJQp=gE@SmEO{ew|+O|wONw_78;OY@g zP!<-OTPQbkeUn-v<%You^mbVRt2B43b31E;A;#90a%8`Y?Bt+GY88CF-~>ZW1I7f? z1edA7HJPMn`Et4SXyJq?$?li_N{HN)3btzKd>Ol@ZzMx+r9N;x)Mc0ySB^faB@Bb9 z07?X*`Q1#UlV0#2)?4=<@P*YTeG+OvT8QCy%vN9P^iX}PqWbAcoLGc?X}Hle&l_u{*m5csDr_n` z^#fP0&v*{_vcH%W3Q~#Cm%HYphzE~b7~==707~8pK0}cZ?d|e|h})Y6sC+snvwM zB312rd}p&`8mL704RdHJN%fSGyLFx&>e#E4JM48*F}Lqx`xHRHPERyiGpDABCsVIv z9zAF-DPC!d6q^N6{_X(=W|QXtMnAw)S;!+Uk|ibh_&OBT>P8k9dJsCwnD3Yc$+o&* zFn!p%Kzlr_dh%Xbo7$iyw+=IYiB3;=V`AFe-!o)%KqbV~74>iI14j-E%J0dnd3T8bLXq5c3{IV6{J`c(zyuy;hv@U5fT_aB(l#WdEfOZ zWUOAY5Z+nNgo>{t8u=%=M)g3icTsS2**&yERDB2eiD=``sqf!7Hw`7Z$l5Q?jqktZ z+*tqraBkuN8zZZKZ;Qy+%J$PEc&iD5MUjZ+*Eex{I2ERFheE7{->M>ut2F& zXu~$u8up+0>>usdOeGyNoWF!*{}{2Z%dCNE`6~Kah_y?sN&B4X zAxlXjU-XzDvca-wu8*EiUM{Sr9$pexLWl?;fZ~G^R4x%h2o~zYtb`?&?fBmdc-;!T z9{4{mfZx=HY-d{St5UY$vTtX2UcOv%e4VVX{`0Vi`mKK@Sp<%Y6R;OcjW;+YE2t}! z9pnQGg5`p_k|{z42CEJh1j;$o*%STdvXo~^2fAq zL{}ACO0-8APvSn6A_X?FHH(0k;hiCijFn->Ih+71J>qcrD~3C@IC#Uz9NeK>I9YQw zYW*oe_V-ZdFVozI5^76CbTAd>RTn?)L58yxDU~@#=7EJS9_93Fc*1&m*I@x~{`tdA zn@(ciAJYnvbq`dFGutGZT8CKEt(Z*GjnXZx?vh%iI?SNet*3z2@yqIlC5MS7k>lpy z;O|g*)Yz4gPB@ht!XG0#yY;7KWX@#T$zw>*bdXHQf@=Ke^n4{G(c4~bSrxGbD4UF4 z!J9&*5VDoz^pR`*@p|B_NRJG7{PC=I`2s6j+DEqsySJo>>E6RrZ2_c9sZTpwEJZCt zDrrsFT8gH27O0_q;o@*USjW#$2zPV#U^_;@(~6P_`7f7;j`XUrnxn4SyycDeW0agN znt%AKBNF|bc~E~B^DTH3iO4B+M@*s961+`T=I%BRuu|+N_$OeF)uz`n{jQDty7c9! zwcmIYYctD4Q@d>G0>>3f$8d%Svx~8P%#B|d4k<3(X9&g{264lU!lW^PBfDqZAv&$3 z-h<5^#ddmw=DIzEw6%NL?uL7{3!GFN#?%t>bi*>Wr{xuJb;D4#hx{IL_Z*7Hx6kx0 zSZ(dt%&a5NYbM{@@Y4-$;p1zV~%fC+gI%r(OQy8+T*8*@3?n!_-qVh`14qUzRPl zEvoj$&$hk#cD6E25LyY-#8g6GK*w_^q6U*_@hLFz{V6c*R=|jx#rn~LC`egLj##Mn zio%@@dT0)2aD}XBV>#+ttk2D*`-f8O??4!R^819iqKk0)gaPK)HR)D2lqjm!e1HD( z7;r)d?2Px;3@Ow=FS7ust47EI4l8EN+gW%9f;)@iC4jyXl%^vH4^vdf&G}%V-kj1K z5@l;Sj$ZJ6oEB!Qhax{zJIq5NG+;-{f^o(0D>|0fAVJpHuwJM~>1J)AyYj~jT?aAp&bOW{&)lJ}N z;6fguq*K;_XolX9iIus`EsF781#l&`OV={pUk+?&j!M-2dX%gF(@fjHcA5TPaL~UE z#$+n=%KpuPeNYe~VR+mYeHI2HNOTxNz-ci#=nzkJ%IbePu+J7#juh|x8{gP-+bV`( zhyGs<%yj=!Z2ilDn(X9+;hVsZP-gT8)n13g%P^5g*9sM&@BwLe3RYe$S1=opLRH14 zak-rLi5+@DO6EfbSO`k^7IL7-0IznrQSFXvA~5;{a7l@IXkioygEb-RBW-R-TY}c& ze);l{U_#vnju*$)ILfH!6$n%wGh|7}g){nuJzE3OqsgvyQ+>xT)kLCB=B$nf>%BGj z(^PNBM6dh~ezE&FE=;=niU^!XOifGlzMka;dYC_F$9x_;vTesBGs&y5xg!AowsbNl zftA~-(NhA?@17DiC}vahusaxVlZT*OE5t^NS|tUq;|pv`?tcoMkd28(lO+F;sZsQ#tTdx-ey z>v`2KBTnC&rBbfS(E1G=N)VWkpjDihI0dv!J$7<4j#~S2??UIBb-76RV$(A@s(`SC zmVs7T2v}&-(rcO7g;M3(T3KVI_sU-Wl4{`8`PKzVGC~~m;gjK|=L8$mw(n7T>ZB4l zz8gdjv%e4a`!l*iG&OmCxNa4bZ0X-8zZh1T96c}!{A^J9 zOYYD*~6%c1CX>Oz|U}Zn#sAC-N%_k z+*Z*@C`y{iV30fNsEOLB@B%aOu4ItiAH8ViiJ_}0(fV^$>Bu}Tlgn$UX1QLbreCeX z$PdSGgoBabYH4s3W(uyApJuz0!WUbIZ0wU$vDL|imJ+i8#iB_H3_>PuhZhMqjxW4e zw2NXIY$0wGQ)TKXNKzklYQ|Y413cBZ%ZT?)5ZV`Lb;2Fm>>bRA#j`6O43XG9r8&v1 z&k|Uvg3%2!tjl0Ado^&w7s?=^U}Wov_5Y~DjIi6;bb%Rxx(QkKTcEd#xbBMh&7{;! zgSAyCk{3RIM;KqxkwhKM3K@>qu3u|0K}5vz1YprIgxV<(1&71Eb}Q~=Aad^#=vwJe zCQ*g$>YjHOQvU=-U+w&$x~uG=m_eU9yCZo&C-_ z28}>^tH}0shAhd-aUoUIM&&LHYiv=-MuRU?+KL7{CK0isH{$0-d$ZhSlA};-xSc#u z9onn1Ih`p<3RcXhvfbC;rD7VA8nU>G8!b|PWoltdj~}yED7Gc)E9dIlT4)spwVJqT z?Uf3vSI)P9laDeuLgB~QvmTA9hi#9P40&O84~_#L5~8B4~%K*%iT9=5l=To5uYhupNTg>Te(@3 z@N!w4k-0B1&b|X@BR~Ba;S_!$2#VL$D43(TXs`z;q0#QTKt@w{xM`sA5{&2lw4s1X zjp&c8BNwdiNp(*Vz=vs_DlBkP7qBP-``(JV`}ngw4oiVZ)fp*;<=1}XjT6&QHsxx5 zf)_dRY69z-vQ$YpCgC+O(Iw9(5P{2WBFe&10-b8z4O_ z)g7;}=7-XRCgWI3J*S3%o(I(@U8r}+QQYLAv0wgLX*!L)Gj^tUtlzF(SX2d*TKZxM zz}#hVGc}B~v5Fj)ED1KMi~z)X4=^c1(r8vAJ6ozDs|asMSANL4A-a9JA+?;wL?U?D zna~szH<{_e+Or_eSrFtn_QPx#$s13mdi)*eXSb7uVyG}HNy~$>R@~2gWqtT^%>-K& zy=i=)sgR}08!=PL?pv0l>A<ze)=7r>h=jm*Ds zvze%PK$t8QV;X`6tB~5LfK5@_Hi^KV>kfB##CANAG4C2Y)wB2w^RWP@=_U1J-i?A+ zWFPvQJ++nHtgO_IkGNl$ZV0~yofS}bC%lVa@a{<NS_=E?kJNTZ$XVqwX_s zlkNyNjlSZDNf8xT@GZs)}Alp`iH50g>m18`GO4<_&Ix91_C;`SnOd|8sg#FK;s1BKsem zu82umj7NpW3kU&^%%4bmY`bj%E^7P?y@Wh{J1(G?{wvlx)8^DZOY};tm~$q&-1>ou zX$I?NG!YOAN)<+-jhmT7k7tOXsPd58y{ep!mG5)p6;{QKa1MzW#7m7-V&^hM4GyU8 z8z!JzIGV=MHkBv+Zhj(u5}x)j!DxnDrSK$3>_eCS&G3c5f$7Z#n3EgcDL?e7Q|k>Q z{fgo7yV~H%R@~~x0OHlx$m^j<)FdAb8&Jue;4WbndaOQV ziVMKavqGz~v0hxVJ#fl9v~71bPJ4J2!<{RFabN9Gr)p!AMTIa4?2DwiPfa4EX3g66 zL<3$~vzBX>uvaO_Gij%^cY<)=*1_zWXXib+xw1@EMRPUhc{kXlw3RiY04oBTD+q*^ zYy_iK31;?Gd6O7yvh<&s2H#YTr+J;>QYP9$hiTS#YAzVnrL{SP_usBZBj4=KG~l{B z7wl#5WtnE3c|$_c!6+|>PgQ7D6%I}G%ekBCI|{cHhjHV=ea~ZY?PM-{?I-qJlRPe{ zUgd|j$k||TQ+aQVy_HGk3M^UHoNL1p&{`1);UqWY-E*!0)??2m-FT`@;e-n36z->vbG zPf-`(?weS?(WhQsF z2yq+Ty)*K()`2SmGWF)|1k^e8-D>1e&rvT@ZraQsZ0yDiQ$sG*qhR3!eay}@v5}ka5rHcw&9WL2HU^4`CgRq74 zcGGmw)2@iQ6<@RiV$R8%KzS3(j2&E%f}p4G?F|WC>)7W^IwHKa!`! zWuT3AhW<`CUHnARu}rl78BG*Mt0;9=P_Z&aB;zzvNJ%7Z#u6iS0hT$Xd`73+`ls+3 zuR;ZU=0?7u4l^vL)b}EB-jyoBam0!BpVVP!?%}cH&>r-o(!5ISq2Nrt!qa|?4-0tg zQg))GTE_{r_6FTpOqTMIsVpTvf9B&fz1Kr6HXX_nFq&onyDNfXodvaB2V4tFdKln=T(x2SuR|z(usX? zE~9Kt(k5df{HTQ?Hjh!Aqm|x{4$s~?%K6u4gR@kN%zgQOa5-$F1v7oV3*yKnRk2&t za_*<-Z?t}5EzJou3zX+4Rf{|UbaWKSq3+MWQ4F1>OAbLW-@b_u{U1|@|Hd$6#_8B1 z37`aR`vrdAfLbb3@3v@bl25d*^vE3wXkcE2Xn>r-z@`f_4zNzbWo*}fXVCSmBpt$- z{~C{F%vxn7*wTp4eBzltm>6E===S+!2dW9I1g^@>5CdAiL!q(k0PGb7X=&P6w&oiT z4(NP|4l=dhZAEt~gv(i#2C-(_*%DjHMGZ4XoHIm=tvBI7XiW%Xh`FfU(0h!?tb?<8K%RWOFSd+uN8WM87#sNdvw}BFB^XYnxtke9QGHg@|rY_4~)v7lskXH z3NvCj^i2s_W5~8oGY`=HLBxmCB+MNLg8U?1p`k7|_$%-`w2GB_OEfslxJM}RwcSaB zvFTalqZc9!mZXI7Zm#T?lv;z8fj=Og(nXfaWs1@zE)2JORd005iadD^^3NLqPL>j z@tOyG&lE-2_ZaZeekC#t@JZcZf_aDawfO_h-_=r73-RbBVj86t_%dQ6yM$o}Bze)| zN}%^${+aL8ULt4Vf9AIJG2XKEJ0$6)Qd09JQZfyrW-<)3=#zI$jbet8oV~$}D-0sN zaHFpS-YL#jNNjh$;ohRq&a%{v8gCiIGK&yJj!QHIP#u6(#Z}Fb%j*g#Q9ObFMTQ_8 z8*PAp)zpFicl7^%S`zA1+5B1(Lin`SV)x8I3&+2~&K1`pUj`ENvOccfdyN`8gk)nTMV@C#%(pxC2>i2FQqHjG} zVwKT7RMkjH(kgA4W1`xii%zwXNWrUC#?`V(qv|T5eYbZ=%bllN*CiZ}v5q9b5`4|l zP&ODm?vgh(wK9LJhoOtVz~iOaUBD6|mh;3g2ya3ee;5lYsl0^^roItb-kZXzUbWa_ z7G3y`*`rS_PGR95?3wjr+$=oB8!2TuxOK;KUH|c*Ln**4P^KE7kFZ# z52XOvWVhYHF#y|ZsRpd|z~Et|3<`ln(--g7`f-nJPIS+hs9P}o>^(O3bFF^>bIv3r zv1reZloS=2aAG%Jn2)3ZC^QU5i|od6RdcU1WlOZ@I*g*gK~el80yL0=Ro#M7yqkUn%60eHwiTG5>36z@w}?iHWdN*FRlO4_whsrlo| zlK&tOc$}7=DBQ_ z=|YjRe8L}KMEU`j+v_dd_apKm*HB)2b_-_BBr^s11zIKJ1}TpqqvUUIpcfy`Tq}?ke<~oCkUWQL z;ZaVg5A?r6hQ`EfVEQX$nE%t>!oS`x`QPpl{cTG9@7|;c|F$CH3sp-XJ zlO6PhJFuJYBmj-~1pIVo=j3K&cX~gtbE;6|7ye$>UZ0v_X}qC8mDt?rgp7X8wUpYg zN}BcmvG$J9o$txJXm^s1ZQHidv2Av2+v(W0ZQHhO+qQ4^o|!vm_BsEVId|Q)erx4b z-h2z6r>dTMss_uu;iD`zNQFVkd?cc;=9m#iU?zd1o*^cD74Eez-Nr6jiw$Yg9{ebF zIF3TPvFzv$uij1Hao|98)}c(olKwQ$f<*Xpmx7+I#yyBR>`h|L)&l!6?C~lV!iX|3 zJDBc!rpJQASsho8H1&yFY;s=fuP*3v?z#DZMNaZ82Rlh^3om*-n7vs9jT&OPxw!`; zJtfmQ+nAfyqPewV!d+ucwgw*#L*7_#x)+&AXX(hhGaGf*FtAT21 zlGMIo z)e1oPNtN3Yi0XXpNRhW;iLvT(4f@z9i3Ym{jxddL{$5RXU6G z1_^V)wZ7gZ^Bp)wFaf1xXoN`J(BQ$VreNkXMmT{X0fru8b9>Yz#^|m%%ot+FT~WYU zVlBRrpDO~ust63u%YMFT!M;ayHlQ990u1hLZsa!SN-XlY3edX!?Lrnlr(uU-j! zT^KRL72Nc&SV0j2tuHReca+&9t-}g=qc&x#$eOzr(eR-D1Fx6zZ;((c8;uW`#eu{r(JM4d0sVD z40J#S!>8DwhY!PORzVlGK$*4UNF(s^sgTaH{iTWH2(Q72ME$Tw%qwy}CyganP9Z+O zNn5++Hhkk3Zjy!YbcPFH1{vpo`IS`K5hXwbpX5|H}hQC;ho~9 zlkt;DicS%^TOtdAt|6~nI{@w5dV==DHrR<@j3b?m7Eyhv2OqQB_o_q6b0q-XmT%7A zPZ`gq!JjI`BpU0STYV7PtikAtO{P}aA;C9(PZv3A30nlxY(bzZSBd*1imk6^ZT?JO zqv4?t%XIavVOFR@yn+h!4ddQ2o2$tENCj?RH>Tz0ja@OR1E$ds3STj;Lvl=GK|VzO zlpzjH$*L2!p8a7E_{BjST?+dRH&v;f>7xiR)D`lrohXhdeMR}(Fl{JmxDSt&8y>L9 zwmjnx2;TaHs1tD!2fD_mR0Sj!l>7XY4pD&bvt=ge_iffJc%x$bD$`QSV!=+MU+->~_tE0e7K^OE7vNOlK zc`Jppv%go2g3ir*+D+p%)O7Lk9{?c8&Xp<4kV&kwhWI+j`Ww)UFqEw;D5_+Tuh`L% zt2zKS6K3)$*f*(j-86$Q9K<6?&uM1bq1)TY@(4QA1%(0M5=h30TCAq3*7Q9mx@aW& z(`z6*eS1&r5!X-Jexj(~7yEj9{Rz;CkCaxjz9g)Sz9gal=h;5(e>sid z)%!!R>hHrp`9HQuQMsH>7c40t8@~Glg^;c~7Y~J|!1eersMgT(kH+-F6wI-UwJexp zWxmPM!_%QdWxmS}9BwcHT~=;xdIG5Qjsg)P#;Wwxgpr|9h=%FJ z`xa<(icS=A>Pqq^tQvvau2oPZZ8`D}5c}p~+_ONAGIh?*j71hWn42YRTE1#2o27PN zw;XgfGQG|{_*5u001Q5gK^FUlXwhvP3oRGXhQTbAj_}sYGM9vhOk|zSKZc)t;5G02 z3pG0qu_$jqFA{s2ws5tMX6-}p7l^sljYd_lWwdXa;VfhIa@v{*BQu@ipgP{xBizo- zY0R3LxK7!$DHYRdBub1oN;K*?Vrp@o;kp>E9&~t>%nGbV90GAb#MgL^AH(_){>OYG;ba&v| z1|J#eLOOx%_OJ+E*EXRHSmEP4%Bza>R|aYF?SMs_f!X<;;6grL|9m>m0yXNhid#+>=$rhArQU^GjQ9a}iwd3r3mxa4Bl<+&!Eb7~cl0C9ju1#x%qI^>R?jC4lpY<0 zkm?f``FwWWOw1$i⁡Jt{v@?pghwz{hiBKv=8)<)<^K91kO^&mr;mMGIR(+{pnA6 z%%F%aLE|qVQwH?!yqN31^x{8(%-^X$g#W8c=PUeeF`D`hm!{b@U=?uZU;jx4il7r) zr5zp`i>8)9=}DVECp%MLaQd_t8512eZTxihRcWqL84Bp)+Yh_ktl3R?WVqR0dVajT z0CvG=^y6*m07O>d;uGl7dBag&U#aks^9~zmRpaaU=xOn#>>_~0Vk!%A8o)BPzXaeZ z(F3m9q3zY2s(mEr)u}0k>Xh$1L-jvtCxImBx{endHpCUcVNz0TbmXfDCt%be#`lW% zt~*hBHMGim<2C1+mV8LfinokJozxtjNHr_Xj4~fcsF|%lm9aPjrRtXY8_9Cs;H>{3xjV^|B1uFH)WW8i;J2coDW1@xVH9-kNxUX6u z+A2q3mOB@0&p~b;h;gxXGo>I;z7q)=QLR*9nSV|1t>q@>i#S-TOptBHEt`a<9!v^F z5=ioLj_*=_-QSm3wyL(>!7&fX^WCm=n6y_lKP!0610+VjkAm9LCgMn^#;e&A0Q9LJp1Xe5U9OJx+4FGy8{D z^t%xFj}y86Cb$d9O+~xF#7#TWX$g$Q6fSrgDw6w&Dc=MgV4~{;`kZ+5+hd>$4L>u8 zZY>KH!p@~6vwK|20~>JL)E2U54MkuQ_bR~K4yuuKWc>?cgJl#h%cVhoTI1gV_BB5r z%lAcmPE+q-KSsRjj01`c$(^x3i;!$*en9bgD1@c)vGZ~gg5ePkM-5F!K?dlPBFE@l zb5x52TH0$K;TF&5VnLeTtAO;bfGu5TqUFKmtMuV2q^QNunW^AKMrRaa9`L0NqGsYd zfXUFdBtJv_0plBMoycRqykF}pkN?j(T>k&Y`~Oz?N?7UXm`mz7^IJJs+6y}C85rmr z=>PH8`k!gOJa+OA?To?BO7mhW2tmZYkl(?9atOqJxqd%QMQH^Qx;FyP#aj)X8kW=X zyYH596>Z%3joEu5%iiOWesFFw; zXN7W@+h&A7xb^%*^43BqNDUq?V{XXJ#Y5R=G_GC3kK-|X-&`L$_HUTss)c> zO+X-DXy`0{V%+jZ%3z-=9M?BC7w25tw>(weBhs;@V9Z`8K3lj9P&r)J`1P1b{ zh@O35S|pO1;Yxz0Gp5%a-12I4`l$q8O5c!H)e*wT9a`;EV6%9_kzQb{)VV606P@X*ng}r#mWIW+)0?;gA7hKy-u)>DgU~F!qgi zPZ!4hiyj4~WBnq3F1(JS&&A~yR|qcP>-Vpo#;Uuv3>L*Nh*sL6tj20HH+mZmYAO?v z0|w`fw%-TnNVH94Np`VHzz!0mYa%25bVqbamKh(rIM0Q~2Z*;7b>uVpSjd#xnw=@# zs20fOGMVpsul|IqF4InGfRkXrjpw4J^{y=YDn_gb!CT%_+&En0G6kAS7{U+)Hdz2I zb+wpcm-kY}G(YX4@gXaeU4n3EeFvNd={@jCdD$@oyOCM*8b#x?Bw7GC#5IXDeb@6h z2s8uV^SQHygE{`&NACXv4U_&K<@%%*f->yKfT|JJE+H(O zF<5@SIR=Thx#v_}Up5d?w(5K}`57)c;Yf{VHH+q@niWgHgUo$rmLi1L&wjk|?|D8e z*seP=_cPeAB+x})KVb!jjTNW@(|mMs1}npj*N0RVhSrY9L#Iu^q&|0aG|XdfZNJ zI{z$6(07+b6#wxR13d8ugGd6v=dS8@y9WFCO>k4$c_=VkeacM~+wR(48EbuVoS_ht zMT6e=jQ@rP#*Ach6)tAZW0F_iG9}MkRY*{as@v`gHflvDt@W3 zsdy|^f-^9G5=?HL*KJo^Gd}o*+RxA;s91FkjAK-Ok@Rt z4V1NmEMh3WlE?Mq>F|Cf1hPN!*V!Od0 z4QNXhq>9<{rF4U=-*|2jm9bO5~A zRLw3Yj};G}Gwz!7l*zX32uV5gS73xOrx@q@GwarM8|MZyXJEAV{Rq`|WCiE^?oHXM zapqj|47T#M^oP$uq2xW)s#XQAG|ZmfxR8LXcz5T*7xTEou#D1txc3I+c>T!t-lF0< zJ$Pxxqb@(SBVuZQhPw{zG3p4=s_JwLwxxWglOBAI2uwRv8sM?C*@LsMcurK8`uTIi zil5jqie`JCI0m~aac^ms_gvh)A-r#i%0Ao+;qZwLc6aUrE&+4YjZ!cnvc_Z4^5?OoRWZuM zkAnrLCV8rh1H0Adm0OYeWi^aPsc}o~B$L;uJkJji80~-u-2`Ad>DOuzew6}#(kY!Z zB0wVa0rc=4e5_uglrDBjJzvAEX)uu#eqX6=a;hymcHdNeoz#s%s*zo4q$`5-e(Aap zH+yWJ*&lCwDAyRvP0|LOS>V_+z}T`-o$^?bWPJ#xTQDz-7yG16VXyNi`8Ckmq!sh> zn0*xP2nJX^rPmVe$eZW1T9L06hE_DA-#3=?yKc!o5X>q9R@T#BApQvMv&45dm#<8` z`u{r@^Y76e|5q+1X^M)s0L(wBd~*ilmS!ywUjO7`E{4+$KuBtB+OH&cJb1Wwv;!Jz zcm8Hz>b>ykO4Ad*}}(IE{sfvU4Ff3U^KJ2Ikd%7 zM7)WHBX^%7jykAXHY63|>5ChSbi2m}v?C)$32?Qq^{P}J8 z`1=>7FIaldcwz=D%b#;RAN8DY1mXDjvkC6!72D>;{c;jn*Vu;stV3kv@y3?`7wU`HrvV)rFJ_@zat{}(yvd^t_CFWkk|DB422zCv^AR3Fc+&<*{yv?u_U3ROT{ zJjICU4jMZiC9#}t;bbKEru>2r`U3cd_d?UxTH1jaiu~(htl8~?t#|o#|8;Qk8}_yq zlCsTs_dPm!)Am+^@2X$F0+Ct(V0<1sbKp6#_XFsymbn~7IMxuYJQDJ^a|JcOWs()+ z*EpG#79QNVcIPrs2rLT)nouF~<5Ah6^nEGJsxp0>fzA{Ij(IYj{L)#G744FN4-;Z4 z47)`Oj9hq{IFk}o*L2ooP#64UVjtF!BtmD?7J?Vp1~>lC zBZJ&UefOG5sJLhv(rseH?JJkyX~+_H zf)8)%MVE`SoIaK=k1K427r$f}(sqiZ#O8%3Adh}bk6ylsm*IYVCGd&(oC@9MtsC;% zRrnH~Klz}ypRC0FU!J4&FF5S4p2PZ|JV(&k`fFK5N7vloPwZ~!U@k2n__v3>U0Ks! zK^f^|LV|u)!V;Iz8xd4S3^Z1v$8S>%>^q?hJ|M5}9Ado&G0Qd|eeA^AlpnI1S$Tq* zMZHp~VBJSvy|D>|H)2XogX#S+$l^`CS+j;Xjt2LG=-WfHlVyOYSdf8e(yi0vGSBA6 z1NY;{HIG#|po;$^fpMPm5EN})jS;{Nh%{u6Kq**HVZzN$$F(RicyHD(7v zYG&fGlfms{k29VRhYh~Z#qAD^@p}i6@~XBoFj%KCNet%(My7Y_TN+ zLmSmPPn47@nQ*tUbbi@b12;ozeGT}wci8$Q7I=BEeF2LlbkcCI66Y67L%Oi$+H;nz zjX2|?VTa>PV&QnmUOkz)wQz7mCduN#!b^L~-uz;%Nai4T#R3{q1r!2k4egwyb?5-H8Ru%(x zU$l@Ta_2Sra0h-s;%tsNBNGQMUk@ycRWlO6mg;y{J}So%M>V7dAs+0Y``6$e=8L>W zFb;!rv@;%kgNI-=NF)4o#xH<{rhf1>Cbe5CxHbC(u`+HFyIz#Sb)zz}iU3v5xyMNa zw@L7|aJAl?VkW8&a}yey?!p`crU)Q*-#8f9v@SVfeq!`Ug`vLa*wC#jgwpmyl) zkg(6lojZ*v-d>Y5#8l4D%??68F3!K~vPzjMB$wL5@DZ7tEC-NNPWI~OpsN(~q=A(e z>B>b2dBZyH_z3b@(4DB9<+%QsPU3?JviGd<=~A}98qPaxBx_h z0Q;hGYse1uEMI(E*A|@ zy}2$ySr;%p;Ef&wK;^3jZyOEhU99D=|Et^=f$-GZYIIiCnH65q->>1mSgc%kOqh%b zeD{GJa0B)X+zk8?#iJe8{<_)4wNzZ?dVtL^hd#^AFpqJ`YTqXogG(efc=V7jt={th@%rR0V)OJ#V@ zCax4pbd8olLbvYZuOUHxrm!%A=x4q@c4;_%fqUtybH29(T7OGlZ^wG7^4``gN#;9z z_w9L;w!iv;ETOJoM;`~SPp+etZXw@E5A2sfhHJYGicS0pc;sz`<8_EWD6`FkKgHUq$a{-6sByBI&kns{g!GSfeDT>k6Py26&xDlOCi!H zkp)WU(L2pdO99Mcd+EQiGV*O6LOg7GU4SN^!TDWnI+2Z=FgU%%Ov{{{lS%;2Sgx+h z=*Eq}%Bp^g5{icei_aQbYqY1f~wEEQsc<$Fr zqFEr;ulpIS;}m!hXsi)i2SN7p1^t(gR=nXfDso_Uw)ksVs4uffem;j zF@mq_9a=<4(=Py&E^f~fa`%L7yWTsL5m@`k1Ah}8>`5T<#9V?P4}qlz#%Y~^@$(TF z%NVXi*<~bx$0yI#IC}+L5~R2TU$5I7-Kn57#FQ`Q z@67Sqd4xgx>T^4Gg{S>rk7NME+dRNQuAa$^G0F3;lgUipez;F_xW^m?)fjGiH_FC= zT9yQdclxEMgi|i=T{qrd|3+_qXk7BkaA6lCAnhGZ3RQ+R=!CC)d1g%&+N=yOK%VrW zrzF^vw0OcJ^ze1vxVze2O)Sw}AUV#7rVZAD{C1);VYO0Tk(QTY2tWUznPk-V! zbu$ZVqF3iK0UofNJ5oV?0M2?)lk}ZuRH&`*le}bJJ|+&?4!J>6+h>6;IzKJh6+)(eMoY_51(mqejL)7HRtoMJZkuwpj@#3zmFit&~+kVQg1Z}ek5@wA_ShG$8ATCJy-@EED6y|HxooDe*B=VeWrK=y+; zy{!SmwA)uh&={>JEWDnb%qR!TeV(vI^D9A`K%5X%doHMX+iH+#(x|={)Gb+j7T4>r zQ^uG@_jyn(ku)(MP~#rypKb>rXAszM{UNH%~93ULjT zfHgsNIq`fmK{24)?~bms(8>A9&E?m_IC(V0KBKOAKvL(>2;1at=+Fnw&Mkx#z(15fSCbOTRAxG=iJ1Xi*vqM zcd9oYa1||_AwVVxy8g7x;w~B%B(CZ_grR|K<+M=rmA6qp+w4LJQhE}j^LZEI+K8GF zn^mOHPRs&>ii#ns-|8PJnHVFSJl!}N`Cz$B2b#=__BQ*(KE9E46q5HkyXqyfH1FGX znpz|{`BT}EFpbpMrs(jqSJaoh7QLiI;zW^)+fo?&HK;hv>4&E=bA%*8_oi62@(LW@ z=SS6N>25^_6LB)zz`YYo+$D?XEDJ!p07^@gZ54YP5eLX>CxyZl+G1sE!d}8o$FOPf z2XuQOMeA@w|A>!VZ77nj%9*(ONUIKMQg$kKJ+~fF<_);-ntwgCk6QF;1wpd)7iJnU zm>`~ONbP6R9QFA{HdA9^d(3#BELO^8q~t$$zv0N4^1JvBEsEp_jsDX@Vl=QQPDvhR zHANm0-L>8!KeS&0EcdQbWQP7+5I)kG$1G1w>hF#AhLQnMJ`Q-v&*OhD`56 z#GmgCNIbie^2~5hA_A|SDm+MR&&^~V8$buFfAQdGYnaUrZJ~>nym7HJzWsR^LfbaP z{qUUWVtG@=+f1I~})pq|3qrbOr<%gvR=wPY%anGWvAV<42dNHeD;rYOK_Pn)eC_M?@yGXXj@!ye%%xTRSt+1i z0ma%?b4wRmdJ!7gQqFtjbE2``m=CVeDDON)Zel9Hui+KdV1wKP%07d{lHrb=f?oB5 zlG4_JCclP%Ua!orb?DPd=Zet{YTp~^ALQ>03X#FNnJ|W@hw0}`8zsc0d&)bq`b81! zRP>8wdC(Zt!4b~XoNE|=ww!l+H6RJr@9q~Emd=w6y;+xUvSbT6oaXIL6s0NLLQvV& z!M6wT5iYg;WKLu=X}+)q_9Uvhs>FVKrPYfbz&2WttFmUkG4`mc7ktzhnXV7H%1Ud? zZ7pZpmcA}X&mF0n5>SX2x~fcYmxB8hxS_97jhGQ4VW?+=k0iS=seT^ufM0zSzD|a0 zboH8<+Hr~tvH9V9+qt+m&k6`kAmd((B=;TZTMr#7jEX2x!9k-A_0?@>SvZ=CPSI#gS(-gC`x>|We|4y+3sXt9gGa_YdpE&BQXQ(pb& zeUN{18YKK5x)ow_V%{NE+Qul9ec%Wt`Ou0Wgvi9Z8VJgwn3#npjdWMv-4S^`ze> z&(t%sQMgni3dOVUHIC$$eO%#6aG)q2k;|thVx?ZC5`4a?l;3Z6*DD^;TaTDz`dfd( zxOA4)Tlg`!R7QgOeQ)`Cyy8&-W+LIhup!XFIC_F5b}yi%{-#?21c5$w|MdwY|K;)e zYiH#@K3-5&BW$%SqS9?l6JLS z^_3w=?WyD0Dr(o2J?P4eDX++bhq5(`L=}&4E_Qxg_wq~ zf%;2Ha*s}xB^>cNIV@A%7WBQ;ej!8E^*v+?!xBF3et(u5*@K@0}!^*4RZeO8sQmy`LDL^XwjdS!Pfa zmbE_g2Z-ae9G$z_k=wfm>!)9wKeKd)O?CJjZVN|C42yuL#X7$}ELX$Rv`X}(qQ&*}t;4rc_pCxB z3=9lY!kj(*c+8#QT;kw-cOR(>Edojb5|bVgOU~jr8fUo6XlQN>BcSXqU)Qi)2AY=t`Bw5B*2(I_l>*4)&G)^{%XSi z7%O%<7S`q_mPUWOv?2d>rSD(I!7`&?v4YrMT(5Up3jX1135nly6vtOx4j%6#uhG;x zp;17VtS>S2_g@Nxy z^1#p6V0||-HCK0SmcZ7xi7*fpg7b#tCbC|`4wY|{f zE&cU?t^2gEXvXQy@Z4vy8`XGd%Jdxr;k08G^Jwhyw@P%A0bH;^Th z>?XCX??>k-n0*hFg@Mn*)$UZ0I|ujcGbm0^bNyl*!kK^}$+wjAN3ts^VIPJSZsXuhuRUQjTr<+>5(uD{ZYY>$Zj_8bE=%xIrAfqcjq)$M+S#UK{Uoemd zv`rV!)8+P<>y7ElNny)-r7tG)FJy~K=2Ud}2(2)D`4iPvSCr)s5G*qMgHg|#)|CK65V<~m!31Y^iV z_pIRVoS4lP(P)dhZP}oo0Rr!+i_zyqS(xvz8F?H+@3=7)4i)!cBTCxe|IB{`j3yk^ zU&g8bx5oMTUmNF-xcNG1Y4Nv1mV96A8~wi@0nJwwm;XA=@nIRu{I$iOy^n`Ws;ll7 z5(J|*GD=T7`#o@O;WZznmyv;SFY*aYqCgCiN> zV1Oo_IHcY55>@dY(T%S0s9Hp`64^zP*2Gfvu>c&~!Xv7daBbi~b#xUJ?=GA=y<=-x zc9}ZuS=+WMrz%zM8LD9H>c_AURw3mec_ErBI$~{0J<_PW`*T-LGUM?=hh7{7w#{>H zVgYh>xMHEUvg5cWFd2GoyRkcs7tFjucZC5ShhX`9{s?RQPC2z$N(<{7H6z%*LA;?vx%|FV>+*RYn zXNLku+-07)BI9YQEfUpBL1zfF2ZM}YpeMMaZGBZx(kbjpQ3-F#6RRYFpjF3;0`@GA z&u;AIAGvQv?N|BrS7_1y+u8Vk|2F**UjKXAOOFx%5-WloEWAG zXlM=bo`@^K5pL34%j8M)tflib@fUV*pl-j{lrn_RZKRXB!IYtIWSqSz-nlQ)Av++* zJfuKQN}?O8sWeTCFi|j}`c-II-!r*$vkry_N# zr~&a@ru_;QV&W# z3cvYBOdwyFIdv2jsgNfT>F3x~(Uj|thRr`SCYNxwq{&yt?EaUG`Pa=O!T&mAeq~F2 zI}-yvv;VVg^Oel3H4M-^JI*rJ&xVKdO&SQ>ZKq?*jTht4MZ9%~8=_(wQsREnkQcTV zj+-#MCDaYMFCt1d>A;mx*0P&^S=<+wy{&=j(;#PBdG-R1BvtKGnILe#ZA-$R7| zF*zBpLBdfm#c}k!I^#G!5y5_3#=2nl0_fj$9jdhf&6#PV&%Rj?7rbd}CiT>kws?u;L_v9a<{J7S z4WGKt0RYc%sx_)?#KB^~{NZIrQAu_hmawqYpR@a`>i9f(R2(rk!s`AlyggP9{%*|GUt=CfKG8EZnoMIZdDwiUjiJRP;73aTJ<$$l*|j+sSh~*n zSynApPbYc3a9Y`f{+d%ADwMq;BR91d;G2a}3IrNQRWqG?a6&CNZZV4}FPflL;WuWh zR0N5_g<&WhWsm6zYB(09&Ih7$0&Tt;?A;;}8jzCyS# zc6iZPW$T3|e_NCGv-~=z>Y}GHoAHvh5UTt#b#mDno5D-ri4jeErK($StaRVib1cV| z`I9M#I-kp5`{mI-MsC7g#?ot+x$mvWI z11R1HcUsiKZPxhr0@`ab9h9153ZDzh=K6IvdtRpqdJ`%0rYyEG(U7x4%h!6e&T6Yr zP5kpO{Y;QA`aN{tJR#Co@_PC&YdV9PZz(l?Lr`)42BG5gn@8>lyGMS=<%p6NacI zh)k)9@Z`wM%B|!NA#Ku?tn1_&-d?&%fda7I8f#~(xIr>>qHi*qT9Fs>n*{+bTFhrK# zUbPOxVCEYpNI5P#)=YFw>}B9C=k$_+SaK6$k8-!nkJpyzzEK|C@RTc^N zD=+8&e#0^-J5y=NgcKQ5YB;-v`6&}@8sMgz$6!C()JHwf7|{^x@WUUND&>0Q1;Nrk zBqPzud>w$vCtIRuFks3>7ha%5@MR>`Bcr5I-;`9*u3I4_yjUB(uDe(zsVW@FTjqz+ zRpesw8wYByd7A&@&+YcLc^$kQxdYd6t(-$U^4pvdwp1{qSoSjx%tUJ^YNP&T5v%}L ziO}>?{}Wc|sUuU${Sk2gE6+PyWWYm3NX`lQ==G!%?ywexM}#0uK7oTHJOMVeN!wRRA8;B?Tv$PV~e zKj>uTjxRH=uVfQuYV%7_gsT#&Dv_yb`XrKk7&m1p0PM7tIH!LB6j1i_bV+Mc$I!yJ zs3L$aY!$jFBUa$U1%<~oK`eI>@sii$%XYRaV)pN1b1<}k1{O9ZMT$@rNGNpDVwDNI zx>&9h+`p038j%vSGQC3&CHikA+k)-1qS#Yq3R{34p?$vIF`-C{NflLBZYR(n?*~?fB2W7{e3@v`~C0>bo8l7q(k_9 zKYN(|dyGM_NM$l32Rvuyaj`kQ#3@=PH84Uj5?fIL%%bP72bZRmwg56L)Z-+hXxk~SJ-UMdZ z{wYG-$$aDe%>ucWU^x6Mtw!0bGgUz)%npCuOm7_YwZs*A!6AEk&n?Bi5xp`)B_Z|# z<9iP}r^Gq|6CxwUM#Yx&5pB=4*bPtLr&Cx_Jjg>dT2*ek`=oT;h}20 zYHucP+jQENJB?6GfsKQe@6UGq$V!G;G1{b0A@fL5Gk@*>`jC6%*c61l{_%d^-xvm;p9K+=5P z86lz!m}dQ}P&9;H1hc9*IyB!pq%XL7%RYZ=ZU>r2Ojh5&2i1S*>3(wB-69z77oGvo z(C+f+HE8ugt!+vquU=DpY`-vJcUu)btG`9RCSJLPzXG{QMj*4$x>1d7%Z&#ZuC&E9 z03X{SjVd_nOnNJ+a5xh$>PKllVdV=I^BW*r~6tGm8+Cpo`V~6FHBbnJ-E1*iTW(AfyED^ zWhm|GpY{o{I$v7my{N+BMPT%6xAfDS>WO6apmPcKGyL@WSGa8m&BzvGc-&nwmtx*S zS3y8dpDXh&?@QW_X9N$3I={l4P=+W6Cuz|bj)((JKfsT7x{|V-!QL5+{rO|?nf!+v zli?ypOM)2;@qw7>_ctN1bKUHZDS@!AHvAT`4&7{GqDS3=CRYAvcQEFS5P|k3bC^p0 zUZs-Q_a2Ns)ZI-sAWy&iGwgE*60_&wSxXzqqbkk%pCKJ1~>4UbY^H?Xmi#FB`H5M*IHZOm|bjk62;ffygcW~cNP#6 zH|XqSF5S|)J2AoT=*>-fS+_5#n|MRs$2k%i&=kR2@&bbA?JU-X1A7Mo3I;~#nFS!X z&EYh7I-VPUDpoa<;daUPm~or#hHd9{H}jYQSOp^8f91G_)yrW`8F6aE8L{3(65+I? zNk_d&wa3LriKjOW^2_gKn4E-=rVp8(T3?rdc-y=WY>grhHxE@9tRjM1RifVpMQRFIsvjb z-I=Rk>DHQ+n^Vzj9|E;)V!-M`zCjTENzjFzSVU*03VibYhQtkN^&J`IxUbYOb_L>~ zxz!vxMO3ZJ)VQjDZo=UZyLQ04XyAuaB?OzSbS2K&3yt_%+A|IYv@TV_WT8~k zLrA9tRcSAovZ5vFG6Qe(pg{_iBHiGtk?lj=rA&SVOwjR-b-MGpphNOCAx3{en|kZK zyP_Uzc3OCR^C8n_YKVw?U%4}zTUT_Cc{6K_CP|rz_#go=caXZh`%qV)O|7@(8ucCl zJGbeU-cyq|G$ACR4*F84I%FHKW4@nLZj_Wgng~QQn45hX{gq*x;9xE=cJJ;Nn@k%0 z36Z;eG-7hA7ML4_lAC5{R(C6GDU*RVk^~a7M+eZV7Y>jBmFemSr^!|*-^(=-)-UEO zBzMK$jr%=n8cp}FE2SaO;ptU&VILXwX6#ir>C2BbMrZMHqA;oq9%V?sVumJGpVjE; zOcvE^#=_66H={qYKelB(F&2JxqT>TD6A&oCi-}~cUDcG3cgTytR7nLi?Kzs2Q3j`o z-l#9NcO=vw_$D4O^6(-wcrDcyVl~QDC{bP`h>9;iC_Ak@mq=*OG*cm{OTu{v0{uK*3TD3y;&Jbu=NLL5MdKH%ylg(v(=mV9ciR+StNcHy8Oxx>!g?daRwov7u@_`TzqSsZ6;2^Z>TI14br>TmSf z?jgghhg$Wb=yLvcG&J`$v6bF=JOQ|aC1XeX3|~iRC~;7(+=$L-#tAs*Z@}0+7HQ`K zBFwocuXBKPvfeXu659T8H!MF!E(>lzg?&d>dzBYFz%j0iW-Q2Yg(MqgXDxtQ42Y%t z;^W_ytN2h>dX=keQ&0%PCeV3(# z#@2kE@S}^er{|ET3Go5b#BW$UT}lrFdv5Ul)B?kpbDXcURlYUKA5V%l>UAhGk6`?~cz zeux3SY^X-vJv#eX?UNj24lwc7tR$R_C2#LegSq6MBHN`;;)&h1PZu#_GwfDAo>kQihM%WfyCn$QGh-Um^hxc0nZb(Y}WC z^?qh81m)3eXN>&fOF9KH;!O|m*F9cZTiKrUdXu_`m}-LZNJq!b-}Ig4%)=)@AjnO_ zC$jq`6rE)AhsQRm(W7nZVn6&?9_5LrCabV`jB1~LAZ#VJt^V4^enV$_1OD-rfb+7+ z5U-_u_A#XL4mPe(To?^qcysf1-l^BZ1g5 zbz3|Y5qY#)Fr5)dR6MGkW7G_=i^7)F0IPsFH1Ke!c91&JL2ulx0~}!&ODs}=2gq#dus@T``J)`qS-(Uyc3y^97rF*N z2pb3}FLzPo^B=E%c~}%-Z1FyRmwk1^|AhEZWPad z{h9tGNBtjxi?W%Fh7p=4x8pL@sHh2TUjC8@4cKUpW4(z9I8bVpcs4-r&)l8+D!1RU zXZ{!dQ*Pzc8*{E^az*nED^sTGg~@q9qDo3EaSg`dw4kKfuLD(ANdo{XWmfoB5^C7!IIa=81n=dbMK z0?5z`45|!R@q1;_cIriNRYMUC^_xZm8R_ebgcm~7+KkL>AnoW|)de;PS}yLlxz}h~ zu%otlm!G2|UwEi%0}UR)qTSX)rCqPdXs~5vX5D+hH%u7NLe)+DJ$#Gr6o%61a%YuD zQ^W}6h9yXK3=1Fqcskp~vkm7m#8Q?uR^(V^ zg3B(dt1Ga<%QEU_lgoO_F(78?p#unVRT<3Ar3ZSHRx+4sAIb#Lxb`ooe5?m0ySLIM z@*|UvQPY_#wvt8mW2(dW9tBs(7N81ez!)qy_3~kk*6}%csr@Hv@*r)(={eUOXC@v< z&mIFQLbOkH08ZwAp8%idF{O!1s2tPT;Y*3VYm=J}z@(a}cR&a@Ij$5Sv@qv7)ecVH8imYQQT#HebM}b;e>i)`=t{S3Yq%=5Q?YH^wr$&XDz&t*y0wte^9lb3UW@F?#Q(OI`sus<7COvZlw3U2rom3M z*J+)<@qA+FC(@0!#{J!qqO#wrtWEv$4kX`-hktsjI>shb+d*aB-E{5xTlENJDXLNV zK-xA5o;@_^?vTVel@p$o`~c!9=3J+dfm;+u!tlmkuy`Pnaf)_S&pt zt_S=4i}=*`TxJ&i9S6ZN%5j(F($~zTUk9afg50g#_sep+R$n zAnEurax$C1Q0-xWs6@Gd1JoI+*Y+IjQMt+RJ-YGptp<;(hMYiw&gjeY?RU-gh1Ff} zk#Jq~prWtBwl zc`~AS;GIdp1ttm_6Fnk=yumVqGeUlT>UiL{s>{IyE8@r=Y%u7+@EX}qqMA57_JsI! zGyFusjToLqUqi;MJ@|ue%$@tgS+g)I+?BG=auwFc#GjS=G`&owhyB;R;pC5yB zURV9SUKQ%80%)*?*46pW zoAj;hnHel+rnBo~Saw{S=mikHV&|9z^Ie#)dtyM=1stKDPrrhHHb1t*1B=j6DF5qM z27WYD3KxD!2P$rjG436ha0_pv--WgY$R+0hvuwH#5iBc^<<~KHIF+w3f;qq`r6>J7 zh$y3S&ZRK)@KMQ=TbbMUwPoRIU6f9A8v1-`xdVKM10t&-snz`)1L0qE1ji}xl&p%z z`m#=;e0;+>+vNT*vLH4f!2Vf;T7*oMy_l?kHX5(=O>H#*KZAqr$%mJYA8c}AitUi6 z683fC0h__$Gw&!`*X3xs9OU!=;$mUp~ zC6j^a%6s~yCa~v%*&6uLba4$6vYONcvN=FRekr6isUgRg5Bq-0b%#s=IHB1ns17+3 z83r%r;GUN{EX$!JuFULC?R2bDNaMj#-m-bDAK4yoHUUd0L4*2PNtmA7va}q{VB1pd zl<{ITGb_P6UA$C;f4(oQ9nlRnrm^&_RLK)HJeddXE{(dmZiL&mvzGxvFF*#ulAD!e z74x|nV`Xub_7TD?c#@i;mi7iu z@=Sp49c%IR-|xE}t~3gOPr1J2yY*NZ|4c~Jqym~z84@CC>Yn$u3{5;{sy(d2;AZX9 zfU-erqZ}cvpme3op{(j3STK(;STKd~80cCe-|gVHKyUEgKdwLj6#aFl@8nK@l~};2 z|Fd@ZJKyo2w>1A=V*PU@RPj%DRIYl;3Tu_#u!nMUCB>XE{xrr$#Yi$HBD^%!et}m; zO2lPjo{`JhkZ$p8M(!uTH@P8>{?)ieP<}9vtBLimut1aFQ&&7ZKfjyi=<$mT3Mz9; zDneIaxLR)q`l17(Ryf0jm@e(vQR)LS`>*Wi5WnUwp}-4R4@0l-GYJ%Fp3on+>*>($ zb6DeUM!#o;aNlH!aExdE+R;uHsnRS?cc*tW2&$Aug|_70oswOaK7Q4MTjQ1q!eFjl zq5Cb8g#mTGxcr+0G!*sXF6Sz=WVD76PK+Z25u0_OS*watx^P?=HNyU^WFfB8R4miC zaU?Y+A1ij4v20;YgCSe~k}6Pwx1JFd{9OKJZ}5a*}2MnBE=MdVPm3aTrD{ zQS|yl1U`5Zyi}f0De4)#nM-;Zw$osTFu;|`=H#f6oGDE_Yr0_UaTl{-pN};P^JXe> zt1t2nk4dc_7*d6DUe0h?lM-2A$MZK-WCO-vB8 zM1N{N+7w?r{>&+PCG*JaI=;p`%moG;`t3dAD1ee*Wj=2f6LcRFWqfDE8EFwv`6GygVn z<}XCuUq-|tWhVa^r~Hs#57hoYur!*t?Vut1RfhCd- zb4SEP4SG(wGU4Xl+WanQTV_{aS0UTFUFV0r6yC=DQyH}p34OYLqO;HO4Q_5$R;J0w zz+h>xh8gSNadseRGOca1y@v7NjoVP#>psDtE$ynox+&@PJfOf1|CQ1@?m**6ZKuNa z(%JY#U#Pl(_PKk7Ma~dn!4=`{#Ar}CEA@k{pT}*2z^ZzWct0)%!`eF@1{n#2l&J*i zQT99iZ#pDRNcB<97;Z`w)PKxM-gt&fuYX|zh5r*Zi2cW?;V;sP|GoQtp}L`fp@j6g zVHnT5%%A(cK+(zq@;R^8uL(Fph+EtYtU+-8g^y(vxGCOn&sgA$HHyaTBpiq41DX36 zYJ1y%FMkhbH~y#pUTgd4BBhx)zpx2=rrs2n$79CUd#1xQHuc-hZ<=m^mWT!%u9lTh zYf5lCiI4!eael%;)th+Lhdt&?$6QDY?t+1rEZXYV>n>QFr)#|a(#nh^W&3jWExAT} zvq@Q~DO;-C6Aik;62m4p%KU>n^<1QJilIkW$?@A|zcGiE#8$UCkD{2&y|%V|)Ki#j z{bNmqW{5DkMR1Z$@+n7hCS;Nt?(j`ZwI#RSlA1Frv-BYU8!^3dr#mb27eJwD`kHpA z%?^1=`%Jwzu#7_<3Pfo4T1yc4*z!pcC5LP2a^Qs!24>8THG8e>YF-mBfitLC%1+~B zu@c}c%A+|=8L|^hwHE|+;n7NpHu5YA;n8Jf38=eB77DUweQ7GoLE~8>0Tue7*4MP& za280ArEqm=I!3#WOmnl`RVuEIB&>d3D*x$lr5_R(%U!c1mU$14HMm)4$89*t#~5ly zikeIYA#L=SK%cKsu#KgVGDsG|X&I$xrrpgM>Ks!gRAQ?Pbomakh-6`y=2?&7jI~&iSO)1BWB3Bi%G=}SxtiiiP}q0S{^{oZ zv={{k%MVVV0**JBxxe&Rwu8fz5Eb;#@8yQt9mE-9KRz$rGxi>*c_yy&Qd?ma7euI# z#@SI29;a)gpKct@?Qf5XYWj9VU&o>l#>p7@m1lpu70Dr6fJpcA?di;oxd+jd>>9gw z?O3)Ef{nPM;f%V13(&jIkmT!xe8&R`WR28AONP7KF+j`SRzSmO8HQuGZ=y$9kEio@ zISDuK7c3mzr^J++F;I-sdnujiShcA&I@qaDrbf*JbW1Y1kY?<*ZS&POs|`JtQAE!p zbBKy$LO*gMRud`BV5SfPBzA4d<`0%)e6Kr=N;{ZkbIb=-lyaRRiORZH_@)UKvw7u; zZOaMEo>lr&GIMpXDcctZp>c_#pj$kt+w@_E9pM9wlCuL;g|!XT#nlp4-c@wfpM-ON z#h-<9f5ZQZGD8kb-uGg$#T^17zDZoK$Z~fo_ZRtlA{<85VjlgHXBEi$#Y`a~YM!}5lMTY=9l}=C zJ{LqG8UaIuVxCivc%9O#Mjdi^tO7FlLj)~sC!Dk=BS`{*Q=*YVmR7w{@m6`%75f42 zWn#-LXMOG&HPLASUggvkOW?09V#^dQ>b~#saDx7X1bHp5$DBS}fm^>CDa-h$W6SW+ zDpfx&T)(Y&vXO-z-UtO194~WAbMBZh-7U=*ZNY`x*kNs@YLZlFU3`e`q7#Rz(QFPO znNhnV4l!j1teJw~h(lIa|0{xj-7|Mh$ z^@rgl10-DxGk3zueg>BV^_I)j#M{T+JBkm2IGyNn)E+$cxN71JAq+4Z-mM(v@TeLb zJcnFCfH(Obnm|RB%GMG(Q|I8d_}yF8*z5XnYS|83)DetgFsuiS;#GbrOv_v|RdYFW zu(8f>&)~I1lR2B1YRN$KVD<73>2fBt{fkG83)#0s9!hzKlYlh>hn{QpWSx>2MWV@= zS<0n(5$WN3jShpkC`?>TPyJsGt8_d&Wt0B++zaGKD7}&vS-ls`zp1`64aRF;ru4ah zhqqO#Rxzy`jA-%|X4xn_)|kvN>PwZM-R_JOi|=IE3Q`1dNi7=NTU?HmYIX;6;Un9) z6Kv6Lsr!93&~x&56>9LQ*US9y6@!wOgcM_X9e|r-GQ*4rkqcrBMWlJ{V104y>JZDRi{`|7DY}$_E;G57Aw2R&k2$jwZQF{A+LP`}p4bLS&NxLhr zONh@i3K4zMg(YS{m}a6|{MjY}La3M~A4v*fkC^bvh?tA>@h6426)?3z{Z&n+{GXOy zeE)GV@F#^RZ02fY_&?~@e_(;a7^y#|x&w!a7#rTI*uGnS&2+aZ0u=fR6^aw;_gaUD zgi;KL%CqcRYT15+39L~F1qKKRBl39rah2|N_t@nP>?6SnvqKv|0OCtOMn5ubtQ7B1 zK}Qi{qNJv5JSx#Jh+Iv0qZ*rZXPTzk;Amhd7->FJmNYOu1j@gGR-7hIubja{k4i|+ zVyXg77t(aeF0DWZe|a;a=PPV3PPqV8)hu(nuh;yUQR=@QIX82B6~4ksQV-lT!jzUV zosE*9wo^y6P&P`cyn1ogz%Y0kSODv>HE2!U5$XHnbWW7is2uf1<<~p9wCM!`<-RRL zqgw;$JJ+tww{-&d$oF=+$#s`aG}`GdP<%D#(*_^QCn{?GZte{0wCuQK-U_=`|d z&)rSb#`0e(p+fmlaX>yeuSBaMyLr^#(8%^7*clUtg5%lPrW}~-2iLC2DuIC^l*d4pcO!7Qx<9S^^$UMmQIg6 z8ppot<)a6vB$-0C6H#&epR`&`&P+iN-Cl&m93@??O|cAwc-zJt&~?K>gS&H_$5Gw>e5 zJ8ls@M=sF4NGTYqH%_P&(43&9lKkq&86b0rc0!IIm^SgPq}&U7N@5F~KKs*AZ(|PF zE%s{{xco)*^8X)&|L-SHE2<scA->GQj#kL#`#Oe96&|rGUh> z`k?5YXJrXGARs?bl4+8!8N~c)_y|MJbJia`f1HbArk#(Huj^*!>-+!R(-8cRFQorM zC;vMzsZ;@XRa`*+*czuC-6z81mE`{+$J<8;7aA7k!wY~)$OoM7C!rH3LhnqEXhKX$ zy`bK(SgA}w-B_s+z6dP~vg_BPh*aLV*tx50wP3EYwkq|S{kqvPAqkSW`rO5KwC-@l zb(D3G<*+p+bGZScOU@0WOKg3g`A#=q{f)sk-X|USO|&N(xB|sC+(!fWO|Zubz#7Fi z*oOlU$OX9OJI4Dlm~Q-bE4_oux8J(?vgv@LtMf_UnpWp^zx`gF_X4p zDkN<2ZLXHfCpdrs5Ejx^uqPkDn|zy2txlk181e?l8NyY*XBvo;Xxog(`*N7!`|4Zx zx3udDADth&Y@9UPz~5;gTt}mmfxCBytKVD~qP5T)v_CW$QMCYTQ;@|d#Ztf}{JSzb z;B!U$!X8BW4V`G9A7XXVrtBA!itp4bR80$0!73Ye(aC2`qQU}SCYI4n6s)33BRUP} z8P&9AM1TLf>^QLRs%1+y6h&J>jB-xf$=6>TlXb+sMAc(Rw+gq~3~_Z7!go*$t)c&c zTmdFDVSDUYo-VCX)Z2}Zu3$_G0C+I`QF6QKUDPXIfD_bI#K4UO7}{ zs-we*U~|rZ*a^xg++I24Rt$aJvcGZ$8{c0LQLDySVE3E_aWe@f#2>2WsJu}C1D$0| zoi7*84`1$;Q#}_(#l+FSAEAkKLEn#MOi5@Ed?I!qRO0k#LJ^tn^}ZupP;4h{!U@mN zp2DU46?BnMf|*}#?KWP=#qo-rM!slf!N|DewK7L8hWDZ2hR1KlASuFtS(J^SY@t3i z89F$@M8RccPWy=$WiDuv}j4{#ZP(v z+DUiwl)7B!Iq2ppikTvI)78dQh`+%u(a5B(xJn33;<2P9QI($ZS%iH(;*I9476H;; zlhhcsde78_*+2n&C3QS}bX1i-EMifwQ5c3f<4mkT@fP4x8A1U*SRy9C*kRRM)(|in9LcnMvPhm3A*no7k zrR7esoTAnhmv5;w!=x^4LqLL}F1bngJkh&j=(H4Qn(50%(#uP_^e&}#*)^{Q8E;kq z$St>|Ac~^SsW!b(QcXrDdGJK7UB;cFv8{Gea|07AgwU{i!OE$4d^8+}Hu?9M6#+$= zYKq(8hT01LQB*-Tt5=$~HUd_NliHntJc)&~ibTi5M{4C;Ba0)FAHV&_R>v|&W|SDs=hl+&aGZZOiv(nXiC9yoydhn zmYbwLlrc4YFbr0}VzejpDQ4TKYwyTrXw87Vch}(_8(p-gN=jFhD>PS}Ziegcrl%1! zh^`GoswjdXr@l6?l z2kTbL#RH+NV$b`m8Rx3kcvRO2E*H7L4^_YmRlxCse&W+GPmK?x759X4ZCC_@c`sIM zl5IYqtue$}g7MTvV#&V>B+O=;&1Q`lPdFG)?9&{9rCz9|+Tw*f8@;Gl&NUXZ?q)PK(|3MgyAC+(SEI_DBc6r6>vP+6Ez4-~ zg2Dki>qcOWPW-AIW>-TN)t`5cNOFrBi(8h695YnR5)4F7950~{r88F~%P%7=TPP71 zW?I9BYZE?JPp_IxSHnt3#h_EOZKN!>7T342*5H?}v^5W8P-eAovU)F`4)Ng+MXANZ zBcP5efkzpC4wX3ng$$lL!0mh;)YpW-6wo|lb&=;M;TCLI%Z#EG&C>&@r&=e7@=YZ!|fmH2O%|{J`2p3fg>J+CqrVJF*=^2v6(` zAJCT`@z(B;UaslDJ6IXRphHHUI_o`0gT%8M&n=>C59ujs_T(TNYm6bt`?a|F!&J!C z?1g!Ip9;irsM+o8lEsld!`FK_1s`IspM#9AEJJi;eosJ=Pe`D*c{pXYLZ<9#jhvK= zoUF=sg-Ss%OGz-z^o}`8rBGO4Y>Bym#bskTJLO;w(v(~&1Zp~PlKKFjuU59OD6%Ui zJ^6_RN{av@YT0E~=tb_Fx5x4Kh6mD4;e*o6vd{a-upmk^H*5xsF57*|_+3}`{;Jb_B~ovq}jBMQH(#`wSHEOwXURhKJRCws~oML zk8iHWJKUvZq`$AEzdBfRa~&P}olgR?v1ISC|McB^_fVymg?BdrNE`ssW51;ozwuv zYrN<~{iD*~wuRYsIj|32ZOis16x@7sUw4-70U3Xm(e^=(K3~!npx1+{vPr zMDi4H0=c~ynUZ$&cgG(fH1kzyvWD>beSG&gEA1$$aonDbh2JdD4YGr5McZpgwRQ>y|ixbPACT zk_`?+EG}>Uz1gKgPr<8+{U0iSLNRMIN3%b)<$8a_I0)E$SvD9s8W~FI*;^Rd|1I93 zQJzZ%Su9(t zsFLlngZLMB?q(D5-Plu?xP4Yf&Cej7{^_-V(&Sas&oJ5<_jMA*HRqlHVHFJT_+pcD z_ftxE!!8R0v~t6i`Ols*oRf%}g;;p}G9EITJgf95#79n6*-NbUjcB@P$PC#t)c&f> z5=w&;jtg~`h#W@0U^g25^a;LVXQs3O(HA zC(BJ*^VdrEYA{Hl5Co$jIh+0SVEtNj{t6IPf{gWezP{6+8~y99nYWGO#^oOVm6^M~ zS(^*+%(QqoKyXr$`r`VyO2Bh*e9W1#s$Ua&y1=*F;P2nOgbpOc%99Ji?z0Wjy!Dh% zS9S2wQ)t*A51zqbC92+tC=FnCkpDpCx{!9Db@p^)dOc_3)XazNInJkV zI7E-+q@<69?P26)FBk7$W-7oikdhFXa8Z@}BGQ@?N%Na$*5JkU&l^eE%Z@8<4v3w} znq6diW7GTKocCI{QzBi`4nnh(SK((>~7)EMvA^oQ>_eNcfR^c{_JaVOa(=rvVcW{XnT_h@cym~RRUzh~#_roq+{g03 zCFqz;yB(@55fpIS-TRtCBF0U?AV;Y$CfZq28)hgAsc+nI^kU5^lS1)WSxnc;|EsJ+ z997%V>$%~ga_l-))#`TQSbsa@FbqtKX)}F(SBhn~(W}XPyAeR=g>umHsSB!H3SKDA z0UJwp*I9xVu%5bHe{pTHP`&e-g=WdRqFoP(<&CLTDhK4VkypZ43i}!}h zhI!@6Ma)XY+agt29UCX@$3y8)xoO3ZWfNuS&5z==c5FifHq+oJP1}WB)U!4vH;E1e z;yPNX2wW3=)l>pjbA6;Gr-{@S-}Hb|Z}zI1X2*5ndDuc%e(BMM^uDc{WaZ|9eua~~ zHdN#CFxx7vZrr$}}hF1@U$s)ds72L}qWDc@27}5E1ikz(DGGuKj7}u+) zp`8&l{C?GdDG?(lnQv!Aqs}TtN(l$NpAB~==6nbSqGNn@^O0?*RS4%^6*~@ zdYV3DjQEqv^cfKeclf#<-2UQ`@b|sW_V4!kzpe-Y8*5`T6Q{2i#=ipHGUFz#=Xj9< zr&*f>@*BW&1F`|2yQMS(e8YeNlz1tCloauS@oO_udQ-`pD2DZXT`>rod;|jr{6LQd z@S;e}Wbr6|WVJe&Or>5ebH6?8k@#?^QuOi}d}pRU>QBV4`e9cYat5#vE8d9tsK`Dm z_ICQ*+y(PN=|%oAc!(8zgh*`op~1`q zkPD$@NqY8I@+&T^9RAV=g*j~ zIXQ3Zw46GcT zLq{1`Y?~~qI>v`pW}8ew2cy2Fxjk&eYzP_*b~|@EyRQy|6fLyKHgOCjPMwVgt+yzE zoOy?}b|vYJ9OHYt_zL^;$q~j6EPuRt#I||pufMKO!@n@(e{Y@s+c~xW_Nn``L-lv- z!b+vJubl;lmE2?vaSxNA(JBDY0D_077!0vm09V?80CV7G5UrWqh*h~Hw}aw(Nb&@P z?Ya{g%^$H;MOPWuBt}4#o|?(vaA^GbakoeEjWdvhopW}l7NjlQKK{9+SF^RQcAR}; zo6;6q0)oa?3Ys`&PZeR!Ms3>`2|eW?Qnm%eg24k6n&bYRHUuhrG}A=*I0v4tdlKBD z!eb;{w!W^CZ}fKEXH->oK;_-Nj5+-<%$`N;9ug%Mtb0A9^NAFHr8OtfCvf)HEfb)eXifkX!scLr+| zV2DRV+fWeiN)|pssrOulbjB?@g2Ds`pt?U`m{5I8*y(01hb)u4@aG(p(410)h}OoX zO^~}uOvJAU^jyFhD^v0bP`vy zOR$n6b;LGuBT0ZO`X7m0U-}g_@}R2wo2%%wY~dI%JZg}l%P~MvW!q)BT)Nt#-!#&~ z7y<}@W&*qo+T{hW#7Ax_vNeKOG3>p_RxOIB%l>{&ukE&6}AT-a(Jd3J=*T5 zOZOSo{?O&SA(R zta;VP)smfy{fp&YB`A#jpZ#05Tch?rOrIvcOo#uw!uWfU{%<3h{+A;CAH_tYs)i$m z2-?R`Qe#qG>u!J$EuREN|ZuQVFGjE zucCD^Ux32G!h`~{2O_8Rh6YV_^(q<8Ubc=NU(l?bo}KJi{L!fM<(--)ldpK4=cCu^ zyXvj?>GI@nmP1$X%YJ&m#hxuFIKTH0p9*l8T4Z|PyIKWg|o3WCl;~+~v7R_U?I84x`bz z^7o<)^wGT3BIw9p8}TUbQ0z{sAbU#bzP9<*dsp8vCaqW-Ie@sh5f`oaufxC=yGc(ll)%sJJGbYu z!MLEJvr}>G9dmN2>i1XyPb+nat)!jYt2rmFLFrzzn@w(`1*K)d`A>J$MddP?ue|e7 z6&HfK(pnkSC!GM*r*YIUnI01_o$IDsSrj(~AS{joEk&dpuD)DTgACd+ts%cPOHcQW zUF!y0b6BrW*>dQ&b!;taju*XaGo0LFj`rh2HF~m&D2n1PytH_P6-=EP`sO`LBbhXx$0{S4@xlOATEjEKX`d_JeM zE^aUYnWPL=FNh*Ys|>fZo85ys4lo{{=o`2VD(3+5jHAR>7#HtS$<-^V4>&HMi4zf} zB(-Yc-N2ogb)Kk==onW>>K(N-)6S5w^~W?QvES6Wh2U?~N8j-{775v+9hg&c4L>2T zz<6m*r&MjAMDHIud|;p;#DRTM7y<DXbW0MbQXGSZK4`aD53d`Q65;t)Wu2;i+Z(9DCTTu(`aKzO|?a*N$z1GsM ziwn!%!R*hoPYT1~n3}6%-9Ca6`IMKQcLlvevMj+ylu%$* z<|F24r+|Yd{6NCJ!=l*OQG?w6gZY9|YsWQH^2ww_*IKEnIELe1U~tO`cAlkVpyq@hcNVhnNWbI-YvVr)gP$ zAA3m_zwWTN*W{Olgbag2z2uj%yVF*u`sNCVAqsD_^Jf1@wR+dIU(--iMi_vCQ`m_F z+k$~Z;fkvv35V?NBK)m2#0Uy_w+MjF_h92YzUQXLX+)BQfoWR^GSlrsx~kg`3E&41 zWe{OIhkO&HX3k*bK(F#PKm*mzs=}E$`xB-Ed~Vff4w9N6&zHs3rCMjGGwQ4R*`|lU zI{>KsWm)!DfL=>q0iH>r9cKBGZ$AmSK0-Agr|%zWmZQ4ka()VceC8#73TM%A4s^I? zEJy%*hA74k3on)?Dypl~5hfHB zW+HmsaQ3cyUzSq(3XP;CdR-U;?DTaaXt4@=UnZZgU6@;@A>?B)EC(=4g(zqxhpT6g zNh;;_12UXrDJ|g9x}wV!dJk0&u^VSfCgB02k+rm6&3xL8O^^}QvWuM^k4Y( zzr31N?DcGI|I4bmP+3g@Nd@V{y(y~@G?sOYFl~VpmsJkPh&O~Dj@B~F4~%+Jl3~uc zsQuyuPydk|M`6^$^8v4GAFnhFQfzF@;+Ex>qt5d;Oa!hj9$DC>!?g4C^A!F25l=TK zuq~91P%TP7JfW>LC$}OUf>6#FTBJVI9-ZWNM-H{1T=Xa^^={m@)F5r-xL+E42L-ut zU|+_zCUTvHoaQhza$A@ivKp{2Foy~0F;?w{r?|_#Wv{5wh5TsKSZUlP@~T2YF^E+2 zd1O0V|6~dzWRQhwRw)XowUXm>ficTF>#WS_pf|Cj3JqG;PMS-^x~s8IP_CaL`7)Ee zg3i1G@-$_Uuv2i}NI`0|WA*N=-LSiv%!BHDrKkC;*wli$SU#<0;raFw2s}%hZp2VR(DzxJe($;euY+M%8 z>1|9Gr%?tij;bVx#Gz{sT0l7S^qYv%ps-q?KkoU2bp!!OBC{}M@CFA(%g)RC74|J|Zzl~+ zI%x)$=R(N{0EeS<4_N^}Ov4rh5$Sn=W}7}CWtTo__M<$-MYiP+sk-z(y-6h{NWI!u z5o>zPOn~bYH#0IS+esTu#OWo9MWz{z)di}9Bi&o}dnUjFN;e1p)3R z>b8yJ(b_(E9SE9&gHYfX3fe=Ss^QM*Bi!waiBFcDmRBjIck86S9ODJ?h2OkPex#x(VL-m<_c#O}(l~^eC&CA8tM`3- zhggCf*53GEVf4_S^o+nfi+M0&V%-s<<>r-7)qShd*eZJvC0_d>8v1>6@S#(%)2--n zRgcOG=D95TCD!Mx2CEc|!cxNn&^f}FXV!yksE@G?P&HwG2n8%#yTw+ zCg7jyjmbl>IYa^<0qVbjJhB#;sQ@!|(T_r(fR!&0%ISnSi|D4xru0A{Tl%(q(5&Ct zJR{4Wk`g~)+5-A>51g2f$kYeTwDb?=D%>foYZ%;@!M#w88a+xxc+G1z1ZdpC3SLZi zlILFw0OHsMWc}mVCA32pw`!6q&+{TELtp_>3*JHL<8%KZY)ttnTd4D;4U2;OpNRPH zJmkO4xA>DL`U<)D(|7-$SXgQ64;9l#l4V^@XrLlESmRLA;+r3sltp34;BEf$x5m&C zsm6LjNK29xS}|M0p_@^(cMQ+_z+~#s&yK)Bm423avSS=`?r+;QG4VF>#xm;Hi|Rgc*$J~gg2PmWlXp2|g|ava*DVHNZx z8*f6NgSZ@GzrG?=_Dn3ZQItShNpG}taBHtKUc4PrPbDd?U&xcwW-?FudQ^?IW(#Vm zD4=*6>L6;Vneo87#Ied{nU%yFuArO>lw*ve_oys+{QU3HpDJeT?k4^ zFkx0+bfB8ka-r6MjSi7D2%+Bz1(kXtNTLB$n z5pJ_w#yClA1T~hkJ#9U8t~8y}u)o&;v61W%VD%5zSA*VR)ILIC5176Y0)vM#eWDL& zCk=oT;0$1)E7;Kn)7i0*(ro()fl$qT4)GEdo?w$;a6pq(&ivh`MkOm=^ewS`hjF-r z;m48oqT6I|NGDwFM$Om>k+q3AlR>anZnc%hL0kipCf5yOO$+H^8x>YZ|5hjMPYN$e z_HmdZsdC8o235Cd?1ITQk4IYf79RiR7M}5Vc18Pdy@K?GoPoDMTG2!oYno1eKI5L+ zdNEtTNuHuL)+I&9mHJn0!RLyHk zJL%)#9VWfd)&t+�Md+Qd?fM_4n+N13=4JY{SfhEC8&Fz{l56BZsuBpU>^ z$d$7B(-{++V+p;eMxoJ&`2L*khxK^s#~gO!@RhKRVrT$b&3-~Y%{}(v?4TJ8#Pp#! z@f;5YJN;$s>YQp-D7qT0wffDh(LZ?Dbt(E9WYrary4vrz-9qA5Oe!$&7Pq!RVRU#U zCLVNCEQrQ{cTc^T%z2yyHgW3*RGJOShW=VnyB(om3zgvVoENkL^#j*SICD7E=ea4* zvXH1PYkQ;i8ziSJ)_$UOZnR9P(l5E6;!iT3^cl4_j)pO+iMf81m-b2l>lS4wMS z%vX*GAJkCyd}Ds2In4{yk9j^I8trB-a4MwE;<=iQ)l9Ov8(8kNKT<>x>XVhiLxQ7Y zVsyF)uW+huzES^TI7UCmz=UfHET9vqA`~OU%v`5@ioJ;Q(jy^D>T0<>3Ygkn86{8b zt%im{*7)p+`q_K?k!c@)4VMWuUU+;RM5<%RJO+BiB*+R`ThpP>f^x>MR2o{zI!R-d z61oup)=5)6;y-5`f6~wR7UYZ&T zoB+%($=qT=IUZN=3`<^Jg0~d6QWj~ZNr1jb*IJqw>3qi~O zCbd@F;_VIq1>VtAVRZ%*;I@~q+%d&*vrsXvw2`8@6-n;2#fnj`8B6)-M^xiYblUi~ z6@%ka!*x`gB`GcgH1)DqPriC6>MJ-fD0D=$N%EAoo*5O92xw?0M+9ckJ5A>Pm5!d( zE;1|i@E?=}$QKN^KaO5eO7&?Rq=Nn3@zcfVe+z9EbeAlzIv~P9D-6b zlN+fcGtdVuko`h*hXw|Rg?wsj(afou9yuO{JfYjboE?&%XS_E;R5w>;fM%m6_gXCA zi*lhM@lVYV1~6lWyD~mLL)o1?6i<1j0H%nwJ7==p))m7CKx|vksW|(8q`hO1Wo^1G zT9vlVO54Ut+qP}nwr$&XW~FW0wpE!`H^1()d-wkCJ*VTujhKJdnm^~9@s9C413hwX z!pYXU;o210q%`e9E08!I<{6SLmZEK`;zyG2M|WKyQG6p*R_OlI$-%nRFpjrlDd=s_ zKv~EgDGp`QXXYwxhD`y@sMN{cNKO=6Bz28QqCj|&tTf5#Vr>5QM1{p6QOvE8JEO!; znBVy=Dk4vqQeQ>H)BIL`>mct7Qohm|+Qfky_01o2m`f$@m;-)B1cgu$6)yw2!D*%p zLY|;e@2D&34nw6cGn+##814#$wcloS5H54XPdPdhQEqoAiAXNxoQYW%w|hRsB1e8Y zCKokL3OVUnNyv`E1O%=Hq|bW7xMx|rJ@;B9vQoAb<{2PwBdNVS@^D&ZtXFjBdjZb{0L38Q`ftZcrFrZFW9Y! zuzZyt!ZAV7Qnd$WQ^x6&N9Em1NwR?!qT*g~x1}Rh`SGlU(5E<7lV?BLqex2TB?;qVRlUpxEqo4faAfp&ED#Sz8-jtTvNgX;k$I`e}m{<6h5y4tt zeL%d#I#CZum!IZ{E}dkTkUUnDlnxs@%S`%sMrnZvQTd+_d@TJX7x0!_(+!c|;|~S= zI?xDinMClc4+EXOxVA^3r5#*8@IK=k^??py85}VHuj?>wzp$pwK(c#;?RfCpt-xG^ zr7*MfP{P}9OD_m*mYpyUo&Z??*gZjXps+&3t)MIZ!JI~dxqxgx8V-UM+B8eY6V}c> zVT!ALSyi&O0USu4&v;&h*DYslW2#?PsuhiSrxnirBAj-5JEb=8&uIE|=#DW6%QKe& zcv($~$u{gY6vk91C;3nx$L}>q$n3#bQE?}84NgQh9f+3$zd_GLHl2<(zq4%xCb_k9 z+J{R=N#^^kcJ7b~n%`e_#j;#6ddf;R{&dD`=FxfzC-r>hIrkB^TBxkHKN8 zWfL;+`YoGvX5clh5l{0yjFavUm^%9!hI7|+C;LTf`YCZpAe!skx>l17I?Z)~Gx9`V z81jIARp`ZQM=$2sD#5T88$XZ+o-lZCbnI$<}GFCI~H>H^l*0{SVy?|=KiI% zg>U^C&w!GQ{5grS7o8!IuR!_wb`i<`iCvZ02aY}QT{N`{FA3e}VZ@-VAkv8SzH8#> z_fD?{5VEjix3EsU{hCnL6~WdEf@_bkg}^{;S9@au-e$HU@La?#in$-WG0cN12{U{D zq$Qr8PT#PWmD}eXh32{l_q(7Kly`-0Er;yKQE-*3#KHf8ax$8 zg}~pnX%!p>RD*Ud6ULcT#mQW-PWKl$IHadHBmDvf%l`u${GBz*{wHAdUqe4>eJ2NV zLt{tc|N6u6UuvztRk~KI+FEIBeZNp5?-}{aU zzaM5cEc75ehm%ZC`wlthCC;pyf;gz!&mJPqut)+E%n%%vHWo1)M^9r2)~Mgqk1}PC zNfwt#Pu7mqLTD8AE-I$o|QQjk+*a0k{mt^)%Qsx5DyCqH)Phwv7m7VNZ@Df z1q5BlJr{{zN!6k-K%iZGwkNSz^-tcXaptYPr|n=m&j$%)6KP73r2yG<>gvM>QP2Wu zbq7QWaL3i=jwME&`FcHmHXFD>hl3(djv+(uJc*g#I=#ZC99~;T2Zoe%dPzbgX;FYg zIX00AN$-CLN6FjC3JLJ{i$mgIAuv9f=w+ABU6fSW=8H0S2W@vet-a29jZI?+mW-M{ zdBk(YTs(9H$nGXW*$kWbuZoKDLq0&^Ax#0Hp;GVZ^R&M^=ua*~gASmZtf49wN=vsWcUCB-t~pGrKUtIT;2V%bQl$ZSJ;Kv zy85dW7|%;n^p`o_V+@Yr`i-ZTIs}^p5L54vE6MnC(w2*JxCdY)Egkj>R@`q4wpyJ= z#|iO(v~}MpAJ>Ralk;uc!sK6`e@sgW7HB!atz*Q;vvOFi1{|aSt@o(a3p3H_6g477 z&K9@PbB!NQid>d_MWo%`9HVqVxS|QE)GMF;Rvn)1j}Iv{o8^C_c0JC9JH5^ zKLvxx&Z;fF^$*w(7-|Y8)it?#ar3JmG=9swEM@5bu2aXML4|VPV5o^LB_j%ue=?ss z@vm#&U(o1|NSsR!+%VmECrqvGZAw2NQ>t?$OqOXxusKp~7{>pU&NEZ;qJ9I#^^^7D za(_m{vp$KB^=z;FWqRwZ?f-|2`@WuZ7UIqTW1tj+3P^C+x(#<9^A6MM4&&N?M?2E> z6Q!pTqUs!r)Ks@K#&#d8$1S=RSyMgY?ZY=TC{s4UL(T_;vla_%*awr)v_v`w8N$o! zGh&Hw64iG2BC#Y|EcjWLJ1eJhtyDKGfie%isK+{Oz$|6Jtcp#s1DEFu_%onrnDoFp zbbC!ZISHBWh$)A5gBcO9r#Y4&bEthoTw&tJ zW}|&Xgj+mLRv{AYEVoX6=&hheuVz!&3&x)eykUIxW8joORDcNI`Gb!z9$^MfX@F9R z52xV3BM5F`qtRUABL+ZtW?{i8CnsO>k-A%AW-iwK7}vw!r|&iO5$Q9<*hlo_^rh+- znMe9>DfClar?C~jQg8kDlu_69LD!p&Hel^j5vJ)qpJzkt{x&~P_ZDnvH_$*a`iNZ^ z(zyY#VG5&H-ff9oObyTK&|@4T;)&HTu>$a~yjX11Ff+ zTfmM#ImsPXLO;;?h^-x&3!wnOEw>qbc98WqaA!R@<5s{=23NLzC+yz=ofs52#q`%E z&p(E4ZC8%t+KRVf(M}z^=-SQjC*HK3;0ygC!7y3c$cM_}Wv`qsM-XogwlWAQ`$3a8WfANjw3r|Jg(=`{WqSo)jh@Bh+&&?kZO-B+ z52wxD=ej|<%MgZi&2v7P^bK9}BubhsBS9jf*gl!1;Fr&f{DfkShX3>*{QUACoJQ3x zru^kUprR|F$%I3G-rP{W4%@m&ObZ2-DQk_^Uy)EssekmoR9lH%lp6y6m;azEY*4r< z^DqBFC|5?J&W77H*HN|R2Uk0d!0Yyx2LV?*&D&+Ct69*w3PSNO55oK0cJG?(P=s?( z8vJe2?Vhg&$>bk2-&E{c#U4kF&ds;L*6RIk*56}jIfguJ|YzDx*u$vuJ7avU_~2PEZ$pS*H~j@$_yK9WMfQwdDUISXmj?e{-#L69MQf&O|c z%%r-xLcZ`>$CuvizqM|Ee=GiD^4ot)LI17-O-`8jYIsEnkwq-ug{8yZ;nQA4U?V*j z;le<+M{9Fb<_t~W|Ej!+*;~{4hhAO}Wz~%SO#HXw+ce49uaOJvZ%%r-1Eirea2qfg z!(dX~P@}uYx6^M*W%cuzP*)NCYYHfoMy35EDQ1kaEj<{^TQW`XkVk6Pt=W%pV< z5+0%n{8SlcIKILhO&phYt4DRB;XRdI!!={(+kIVoS1)MOxlxOe2D9o8i5#PO0Ab-8 zE6V*o2xmRJ57SIFk;spu+M!p+n79%?&4lyx1P9Jc?eSd$$lpDbU`@_%yIMcx+<(h< zm6ER1H0Vd@2aEyvv`jj=9wqzq>sfIMV#8o8j;frx)^P@MRwbP%9OK zW###Yr2$(iclpQHLlFD_`w+gGcK-#1rT=Y3{xwH)MPB(T$;g;nHGpCLp}5y3eI`Mu zi)v@t>k@@)6cAv|GRhYvs80=h??=sXpJw1-E+8gmmiU;VBOoDhx?ikKC5<6qk;wEWIJ3C7tW5>*7-2w;W*&pSu?S z)3$)mIK#uVJ`uHOAj1vkD!ND2&Nh^+w_xtqV?jxX1fMXQ{4U$Mr@P)Q8)l6`U(Vgn@_V zHZh^TO~4`@e-X~(c)axoubmFBaWV8;lzP@(jK+nTyZH7Y75R{`{&mL0eBte2C?g4F zlRWynUsuTcOi8tPttn1e0^9lL3eKljxK+b6r!dpiBwKOYSsIi`VR(as9G*pTQre_C zke&79_&N-a-VqZNjAcCf#c6QZT(Ci5_DNUg#9ZmPV^dY$Y76WN@EK?-fsJIYOdGOj z^!T(-m1kR{_ z0oNQysT28G_o3*RQd3eK%OJY+lLm8H;^?Ft(wPO4mW1^%l4#ls=lsffkt@*05mz)G zu|D;a{MK5{^zbazVle^MFN{RSWn3KvgH47fMo7OvI4|Au>&>}RdC%?2tcmP&L-d6@8QRl-%hXfrEX9hsBr0!;&G{{~S3O>+2be z3-FvwqMM^UcP2m#?=mzNcATFHo9R0gU&f_!)e9F&b!#SHDZ^2iIPAWo?-{#U@gRQ% zqpU-Hah#g&wVi|Vg2o<-BGexGBN&#jB6bc9l7F9LmJvMv!FK9@F`H?dS5R8c&vj>h zN(3@mZS#)c&-cR}H!}m2Bo+2NJW~!-Tw;6unk)VTIT>_z@Pbw8ex3h`OMU{g4Yl)3 zhfLblaVhX~HPA$Yxg9PKw0gfYT?v~)Sb>3CN_6P@st9P6-v*bX#;cQVN9N6Tg72qb z1ai76qD~f0e!0RcTdB$KT~G9+51%vty>U0ZOSM5nRuqOlKs4kv`V28~&T>oV5~<{( z3Z1;>Rppj6`zH4$DFjdmtwF7K)Q^)X*i$z7H;xK0U@5S-{1j|8SAsm|Tlpd7#e_9G z;E-LNpAR=FFWzJ=^RT-RtOw!+Ed2uP5}_jI*J_aa+C2N(AI=NeQ`AwSY3Wec9(f>l zzuaAqHoV^eJzjK2+LymZJyASUA;E(VI;NUuzA|KziA-Uv!RHNIxBKRj6j?n`paF61EQknI3 zHhCw*-U9F{ErlLlkj_49$apFQk!XY!M2RcF8sCem9ynX75yLH_kO@fTuMA%}DCM=; zK?Qki1Vn4OM+GGGk`e&bK#2I6@)`#xk)cz#@R>%Cthg2MF=)&E79~WhoaoEkQ6Lob zgerYhJXZW;P)#9Ac5%1VQt_njyF7X6ybI;<>LvL05u3aEImV~>OoOs+v%JL@t&-m) z-oKG}`z0{mLW$$X8>?RN7b{dkCyQ)tkSG=Z;|@}aJ8nVNHEs6I-OLPWEqKp366$>R zldYk5Hx9bSF_wlc0ptDm7BJgFA7VLQmCB=%?vdH`hJ}uqPW*ndsk$(G~3UGUFh&z1Zhs5Rz{MG*OUYs?O zo<**ztt+HQfj>v-M8XZC{+iTgZQ%*SFkm^XrLVQGx#y&>ecnA>xPEg~8!te2WgImq zKzEmtm`E~^i0D+1GGzdk{GGkTP->_%0wfsn)0#6L9Sk-k*?^ofMbUMWvUPLzWz6zT zMoGJ_pRrY96E^TZgxpczv$Ip{_Q!qJ`a>azWK#9z8@JhPj6bT`6%%obHJJ4d98t(( zPqmZB8g$nw#X#c+CIcB8#T#WX<0ERfUoG1wF6}lu7t8%&ME=DhEAHNy_vKhqbD{t~;l3^K^*tN@nAlO`Ns!8X%foaqZSW;@ISu=iQpT_6WAup$g0nGtVb z_}kfDB5sqk&z%O0cak(^$AF0D`oZ!@+%APXN|+X4d^w1ARG*5+vvUx<$xMH!-+auR+ly=eP2IoMVT ziI5S?3_^TZczqBJ6^q$Qlbv}pZNFx&`|N)7zuqDzg@okoG$;%`8}n)A%iTBq8++@DrW<% zgpeGd?3o|s7sf|J$R-{}+_G0JE69~Za0NpF{AGjnzJvbwuFDdSyYe~WY~Ke z2AEh60|_}XC*AwGs{48U*X7yA>*trlU%m?>UsHf;n7Bz_tDi_JXcm!l<^WAaN z;=z(IVoT^qcgf}^jzX{Xc1)T4l`x8{YTwSR2m%kC#lGqAx=m+P<1;OXq&~9gQX2l& zf<`w_pHKLcL-SQ`fA?_f>!6b>(w7`-fw^uwD@)>pC`LDyqR7yS>hh?pO(jNvbH} zkLW-iQ{HASuE0Vywl>tHx_gk(NsrD?AC_{%2noBI7xUlyBSYeN;!B~$jd}zb z&HvujJhxH@$%qd}@5ITK9vjkm`j^r@9mTf zG4`|J3S&UJL4g(TvkesDg7q4KtQE|R1v1j|mcRv$_jEs0tLt*#xPJrd1}fNIbWb({ zejXqL_3K0QwwMw2H5QRwh(1}uS2!%6ZkF$Xpue=jIG!ca>!hey~z%{`AWH(!6bL%K^=KFJek z9~g1PO`@ih9JdAvsE}2fBHv|J=tTWk;-MtLRh%snJUZ&dA3kszq$at5*wZ5EwjEtO z%O4K>!z}R(79$-rk@^^z9zGddF0?NYG#d)Ha+{+6+$iD@Ms{$1xne87S}Xte;}GTl z^pXB=hh+cwdjGXs{8wbhe;r=csvC~T#wdTXNv~SY6e#5on*AVFOOp87HOZ4wB$|u) zESgc0t?%P$tyuLNDNyLNP(j-%U4;k1O&cG|s8-o1Za@bUsc>R?(U=+SN8=;5=G)+z9{c`o}mc)9{zQK?gswvgsfK#1pQ z@be9V2#A|TLLof7X6sdXp2t87F_;jP^~PPLDk9PE41Weui%W`)rZg1=d7$Fl=Hp~T zy`$hL+~Vc`s2DovC#1FwSC98YTM+;dB18xmGB6>AS-8yH^HEa+Nq5lqXTFfJXr2VC zh?b?up)3-Wn2^!%t0i`aIA2{gJ6DnNqDW@2`e#7)1T9nb^J_My)wuw1ZeX!7wbGnV z*%j73>afmIshMlnG@NN8+UnV_oNBm0Oxbla3Mr+rM!I#XrI7rBSkhh#KXz?z*zOs| zz^1M9d>jlY4q7tooXcRg0_aD!71pdZ2@lR+rb)^4ac(VMaR#Wz7slXN6tp)4dYkP! z_b;Mtp=c(~+2}W0ZhUu5LtCoGk- zW|q`p!O+AbOm+a+e9@vT{0muzE?pvQG^NE5%^i9%kV{21tN!Gx1!o4ila8mQDZS>_FXyEqcjUrBi-pnbn#mx)Oab5 zw9-8age6BqcE(Hu#3P+;GNPuPCf-@`VZz&x@j-8pGe}XvR4cKe*Cc{Qg%p_Y`Nj<} z!~!d>mqQA}!LRVP7NcAM<95m_jzb4h$-`M}*I@qm4yx8Pp3OQmdS*BcE!W+IMzKsp zIdHdVr4pfxXi+59ac1+zmdUZp+>%A=s4QwV2B1804ES{AYC)-}US<3AG34wO`xr5m zW&H+_*>d$D-;?2Y`~qT?yrL2*Ddoy{kx_H^lL8hfc?K|1P3>id+}pjrqeCVm!_`F0 z+yzHSwpHy%GdwV6kb|iKny3of=V?>{x+tgfobWFT@u=M

(ixS8aob6hqy(&9b2KMpxBX%OYB82{fI`1M&{wiV;PwM6(b)W7^0CG zG8w-}So0^&$c5MX@OvEJWZe*J=-`u8WKPN{--N9;2vfv+K zdXnyp2kzz-+yQ#41AkD}#+sC2o(3j(^ZIm`;O}A3mbPkW|4Jje-f$qoAh zV1uXa1ZErrX7us0M;JSLA-jXnI--7P_t|trd^*97oPtd+NPh_I?7DVD|2);C%->)R zyq=YKk71pEX$tnSgUXLtQ0Yfq>s`9)`|1gf&hn|1GU{N*SdSu=X$jI9LX+`E@GV@6 zk2Bsk^-&GgO-UwdCm?#mlI-|!cycE7OrKAnEKmt)EudL~CtM<6KJ@Z8e7&x#D3)46 zYT=Nk$iG_clQ_paSdZJgH*E_@f44T}LH7t0q~5Xp8viU{WJGGa1@C+{sX*-b{sm&2 zA&2;~zZ5sr$p3ym{++%3M-cnP*__O6oNb*QWu2YuoSpu0EdCX_Z}q=OoGPRj$`R@x z-$qjxGPX!+Ap}HeR!GFzJbnKV9E2&-G!WFPAaR$3C@Yr(6ZF19m3qA9^<`+e@51Yg zXsFc)ggOAB%4Vg?>Q#xQ^#K)OYk&pdeS7lS$kBoL?TXEI`=!U#_omzZc|sHqoE|y1 zJuWg6w`~X%lC4x9&gSTdRcHC3!9O+HW;2G%t$o2?+NQ03EtsZlLfF%lsVO=lSnn7YH(kk)7;#`Kq?bW=H8)6xB#7EF3(SmR&Sx7 z-x;=#1;lk^vBt)~Y8^UhNkW{vBv`_t*~Vmz8R7_EJzq?Y=1hgNQ$VAwTWF;!eswv> z(4vV7Nx>k#EY~SR_79K?Zzf0X;v^lrX0HZ+C@7<4bDakIjg@?%w1i|BJx6oA3W-w- z($XuyziF70dH(rvPPsfR$WVhFFWhxy#8CS#tw!F@MS$4%gRjT3GokAQpGI+jwL$9a zTw&nQ$oIGW#Rx58hTkIKARL}B0u zy)CsoaZk*$8?yul+3saTMI{SkK!3lw5TdoJS#tAtAd)K(e|w5{CBaTelNK4)_qZDT zwb`Nz^cVmesFt#&#!^k1h$*g{O5R7=fSKK)8lIr2rmFHh4U8+(K?U@Igji%X$;N}F zMVbKA^kHy;@lhnftPezeVbCXp1XyGWGN|Z@kh^FI4+ERW{AVIUdY^31Z z9Rf#d7Up{MwZ^!y|2YE#Q_>=bNmHd0ivpC5y-y!vvX-WgzmA!)fzp<)<;a;=BH@x= zf4gF+y_fxxnW6|?x-DTYK-{C4C*VA?;f>~!HX^= zN_f_>jfPVlH@)~qT>+nq9N=8(S3b(a_;&$Oyn6zewR?Viefr?CBIvpAOggD|VB1M| z=v^cSwW~M1J4PS4f8y>~f1maKH2Q+O#$6*p;CDREmjm?UR`lPiGoLlMq!QI^@8`hF zQtk+tc*1}gdjheI1`$k|wvB?}ZX0BWf7C<3UYxOp2DvdpvbW z3@ICkILe3++l0u&QVJ|tQrZTGtJO+qid6PKui6tACP^auS)zApU9h`woiJ#ZNWSAJ zY6%xwHCEVZdsqmxRumD#Mnp{?Z#P_~wX} zj{`4x%)0MfED0j)^N*Rylu4B0 zd?5FD&imS3FmM!?Cs9jYU#c>koD;&($=uYniv&$sg92J+694$s&Rkz!V-)z{K6J~; zWmu4*nyM*fp~688DP`K2U$$R@vN`g?vN8i*g(X{2S(vs6rp(&PrUFulg)M1?rosY8 zE|`+Y{*!8mUz)sTxfK@C5TTA#!=U%eqg7NB2!4~5uV%27@3c~GY0%;Gm~94&O(#J= zIv;X}81#Kky}Zn`)9u?p7@a#k@9?rAW#sZMQ=xcdhy3J;7W{yd0H=o7#0p9weot5r1; z4^FXsJO=+(8gDysH>7KxQ6T?*f-+9sIocxhg<5n>7*nJy@w(#0^ZNT=DsJAwco(!r zs25aM+Qz5=-EQFzTQ71HSuuc zl;4G%eKt5NqZycRSrR?u=L2^@*bL!*=2E9MhRu<`>;i%uJ$gJAOy5_qica6bu#=g? z9P)VY^`#1)kRpzX#YT=$o@^Cdbo>duA{(wPn0K+NdYhA=SM*tWq|+|iwhVx6gy4H* zRkngk?U;0WX_#R*B|cwS?Wva|9juV3>eS6v2?g3TwF0UQ04-b+xCkRGl95n2yKfveM^f38l5{`x)IQ0=t z6MmoUT@1$F)5TZAWXs0QKD5Br1TCVL{B@ZqR_r95vlYKfm-{GMFlDnCfl8@=PiRii zxg;jQme_A;nT-wM)_ALNi6iC=uM&6HjOzhkNIjB19}1U!6eSbf`5F7zmV12!x8?cO zt(=g8Sd@St4A+cET)a6|6(my?o=m@Rwj$#I`-Xis)>ZNj_0&}N76G;hPLwNybgF7b zhzTO6pifpjL3@~oK4RC9@bI3TX+g=B3?&{|Gp;0&-w@>Rsq{V3B3OKgWX5iVvOkzy z`LRHNzy9>(T=9HVNLT;f=6t9K{tc*#Hy#CxjmVa$)e3WC6eL_h)%;PllmUkA+bWz(WvRaQHmE1Gj0O3@Uwj2C{lzz1Xo(kRDbE zGQ*x2BN;Y@`G$Ul$x8e$MW}jfF@hEnAxx{npbNZ|YH#`twwO2?>2)y84MC$Zc7v8p z#@OtPRB9IIp|LU)GTfa|pfU1Lo^Bk6?xqrHYlVlnf}0{D8BT?aWARSp(tDlq z=nDq{=#w&yN4R_}~#=Hxgu4li*S%s3Uk&4OkyFjG*fp%ti`pV!N zVQCz^w>O140Y@T?%rhN~R5Z1L`*BB5SHtDSXLy+`X{pJ__0AY&^Ybupb!6UDTx8m= zGBGh@t0By}WPuF2R&z}9q8r!zJ+*drHS#IeC0^PhA{Nv9jgpz9G`D_}6_Wt1{@X`ucr3`a?YW1CsqQ zs=B3GgM$M`e?Zwd)&IQs???a3CSaD_flW3_7Ku^#?g77tNwNVTrqM!XS-luztSLTYr87#J19JiL(uh@~`URY( zr1KNwc}wOm&rd(9BUJ+u>$^1eXGyfrg2+$v!kwl$+x1g6YpW8>fx6PQrV&}^wON4P z`8C-VY;>k{^k-3hzG-7QnJk?M?#~<_?vXQREhAFWcxP@RTOoIS`G$R%ERAyF)uOAe z3rv$#6OBygPUBxtMFTzDs8FF8}qbKNw88k;B((C8$TVke1i>{U5z8QAh^` zz+Y*>C%FI4w*D@l|BpF+|F8HAIR{%8^M92XMaxS|esyzZmp9M7D+AmSW}plZ`XZkW z&-tm*B6K{)O+vR8Z5oUkn_s`uV!wK1_b>aD<0K#<-I*TnZW!=$ZEwEWfq4S4f?7eY zima~C(pB&Y9x2QCe`L?ovW^qt;0PP?ydbkEI#gIuiuPe=>ckWtkOf^&X(=K`H5U8f zeg}N-)WU5ax9nh16kz`-5vFMDgQv??=ClDm)m?Rzi! z%W5mqT8eED4oD#K2Fey`1HxL(cu~J;n5FNA^MLjM&C2T^3rf!*YI^7|G1mS6a4r0u z;q%l?(lk=9SAD@|7*LsPaNoazgSTLkQ*2+KUF2)k7`o=Vu&S(`V(SPmhm_&q`-6 z+fpG20SXCBH(RbZofDleJ)S$h_Xj6B-{^5~jtU@Jv0g=Jt=g8tG23WY36)+5KF<^YhnsC+`ciSgmg1O^OV? z%f4JE!PeOR*zNU29U*F84eYk~)x+(D{%h&B%;2l&KDK<%zL~o$gsj2RH?=`R+*2VR z&UnW2{KyyJ_4v7wd|A3^rv@vEa%aQBT^(Y&Xt&tg2=)$xgN*WpJ16jU5F>`F&5YV> z`F})$ygki{aqq?zM4ZNM5B!-_`XQ~23Tugl zwTNjIZjRGZp&va?jpWGn8L!8_Si>^&iE@+mN2oIS)rx9ciVRZ3Dd@C~MEVun4Aeql2}8ZO{b}R2TF&BR-9_mYx``xHTtm8q*7)bB?Ctz<*Kaynoyilq^V* zXlX}IILPVDwcw!E4%qDHW2SUkc3TsEgyBrFLLWw-?~g=?ZmzO_~u7!-VE zSWgb)AUiJEp&qA~4S502q_fA|q_?51K-O^94(0oM)mrE+5>^!MN$j zd4B&IZ#)MNW(xQR&D-@4zT5%xKMlFB z48kKa-x0BZATWQ4msM{o!toDCfXSr0LUPkyDZZp;A>p}uC#2hhbW&OUnxsDAy6LYh z8B$%<5ZK9aUk$^^xTnl_F-Q;CAIpQC7HxPd>93SF^!7wH2$QdWD)aT;gYg~mYiO%< zN!Be@nkux}*ex|Hs%Ea5CRNfqlMKn44xq}0r&ZDh}FG&U5ThD&c^WtF3;==j7X zLM*sZ5Ue7G+x%BdHxr7jCC_VWG>VmJ&sa5g%X!RO4+6{)BK!oB#>?%KJK8{?wq z+JKgJ8-r~nv1<-vmlOsZ7nm$da@1L$CKJX#pRm4Cw$+qAkK9-oGWEznl-z#(*gmMM zJ`emP$Js_Q!VQkkaOjFDwDSm`0aO)JAF{)NjnMV`W8}`+ClP*!Pe=>WNit;eD$1Z( zQwti(0-Z7=V0#+RjSu9WHdf5>FZ>F$`L)M>31}pLN-!WtX6GvR;dOD#4SwrKVc`Z@ zu|KSxuN!{WAB;S7shDEB6uPrVsp1R}`1L@3E?7^<@j7ueB8IIaAUP`1<_bB!33gJ0+qowmj(w2VrtBik6H>1Z8?q!d3-5$H!4IXb-b(|K;C#cy6etSgcBRlOYgvPi~)0^KA;Q6 zlyebELtM-b7JaP%aNVp*Q^AV-)sye}o@9XUnBGAH>T5%<#5%~{OVSV@#a zrALaueGV70VM+^1BS8Vr;cIazm)l}JMz~^je@LsVg z*EOt*{l-S@4k)5B5k#hb17|dJj*s~t{3z~#D7o~)E__rM98#XpS8%yYXUvGWMA9}G zS$fl2D=d$$HFu*iBFW}6MpylU0%dFoQ=P9%(KL42*1`b(K#w^;GTE9>gUU zvgFojJ;5m1`Vw3!C6CdBEC{ZseviIZSNMEIy2Q!+@ z2u5a1t&0ZF>j(0!ZF<68g4bt)#}A523D>PX2{#1u;n zvL+J*>11R@Dl%hU?yBd9vJHH{NuTaz%@g2<$neJqH`vv!3W+tdspncx0LQ%!%kq)R zRbtBxShj@B3P4sh+Cf?d_3fdM(Fx=?rfm6);teUH5Yh48qrypXp`{uTc+08WIa4Dd zJou!a_wX$bZ=y09QlY2#j zjjL1Ibp1eGm{G3(1*E*XxT4=taziBZG^g>DvmSnTlzP!IkdR=^Rfbl@f@83Xq0nLy`cY}eErFeMy+XGD8trG!}1(6An zjDpKfMvOoE>og*rxpo2DmtlFBuATJ~0kmw{%|C3y^=k1k(=p~Yltr3Y*y^{5Z)nPk z+=uGqakjdhMt7|iXasvmlijv%@F2Z=V+rS_mi9?w;o4K4xs^CmsDUv)w2OnbW84xT z=Br|Hyn6&5KU?VYFQJl0)fl2sB|A~lKRmsO1oDq4*zOm>+Eie$nW>FU%tDxFFc@Kx zvKr}0vs>|BoE0y{CY+8F;wH#Gk`^>8D=>$`m97B#oc0q#1+nOA_YB`>MByfQfU4Tc zUe$)0VmI0Zk1#*|VL-7N!rCmrp9+!Zh*LCG_biP*amNn~^Me@^M3>mS$AQ%u ztD+^@K zM;FdZ8$y9>`hPELrr{A<&Dz{J9Kq`WN5SrP{Q}?rrHjz+2=NXg7zQ?M{_Txmuz$Xa zsrMBWneON{@GzG`2{VQTUqIa)tdYVC&()sJ+Ys;nVeBnn8w;~7-3l`^Gc$84%uE$# zt}rum9A;)_tS~b(GczaU3REWD_w~%Zt-6EX&&3{?FcPee1Whlaycl0sj#G zHRACROR0*S^~(}o??3MzaqEc)MZZ*jhX2p(=l|%Z`d7m0|D{gVS{>-XBz5a=MH)O z5S@;?#dF~lhbwBz@4gm%rs5uNvZFCP%W}M>9z_KDgUUcUW_bDnt34b}4t_2NFdg_7 z515Mbtfi3#zCZ~RebTTLf2$$G5mTzjHZzz!6?DPDOW9ZYBa>Z{3_rFC=3z`=E}Hzb z<7L}2ZA&>-l(iqAAU*+Hz?+`5{(1Gbxl5Xz=bTi$r9r`6By~hmk~B@V1FTsU<&0N) zL0crY=VaU~a)?KzHajR~RUv`eU*dsG7>0h44U8i~K$mP&i4&sE5aa7Gj?9)RT1=Md z^9Kzzg{`=!%oM1tm@hp zb0?9XQx1+2*#p~SmxKi6FK-^m1xU($u8l4a`Vpvo|3o+_ifwdTf0eV%{}8SId*9{# zPs5OZmGl3eME&=yq8xR-A72Q-ZLSPvy%a)uJihUPGG=8t^KKnWC`7z8VhmfDpv zS?s~3ak*@{=I4y>%0#~POuln1YM5>{7ft?y$Gi16e18H&`dWO(x=(YR&GUR;+S&d* z=I!c#YYXXg1Q_X$E_0Kn6Ae&fhTUWCXiRdn&?B0_Oj@_s79mUG-wtIw*T$xBOWftg zsuSE^wvjMz#P?L|1RiruZe@XHvvGRF?c=BBkg&yH57ftrB>lQq383> z%QrCwPt#FaWzbzt_oXfGDg2;$(-{u-VEM(c?orxnUfJ?gMZj<8(wTn!sbqkFp;Tyo zt#XEVsb+ps?|6&^L%>>W)Tw2~ftyRDi3eICmnSTMjBVxSJh2a-=q-ajE(@8fSkJC* z!@b}ZZIIl(*XyvZ`#w@sxvccGrq*@P@?Pn>sKJ`UBledk)Py)DEBl2p5@Rb5rsjp{xf4xRH(Yj;R{J|r*kywmPX5O@SosF97C9Xh^694vF5nZhFP>lIP{x(jt zSAoT=LBNo3T|f^_mf58;vWids&f#7BRnV20DC5cxhI9578o%}tVu$SB5M0{dHr`?Je)oA}+$RR!O@iqvbTU0&A8zwRrW|X_M3bH8n5Q>Rt@HxMKWJG2AP^(7{e9pw@%@hG@&_D(Swrah zqgsvJ2XnILjsy~Po<{F zGoncfT<{8iSO$eA%VAmKZEfbNDYkK0nK3UG7(Ns`iOBn1RWKv-o(_WA#%q=d;gQP{ z86?HN=sZz7c|tUT=@~Ng1`7vLam$-X?I8_KHnkhDyo0k`uP>(gi|0LCmqa4y7R5%Z znMZ=xq4grK%%Hj_`WrQ=@lAZtr{uul&HTol32#!eO;0Y~)@U!XA)PE7ac9moIr6i^ z8}-}Gd15&UAc_!1=NZ-U9+G>iM5`MW?U9^#A$W`~MDS311XF7UYrM3RjcM-dtbMXG5hpSkf!lP#GjR zeg5Gqmrjb#3KlxStbbzkMhjc8#9?6GDZiLI8C^XBz2CS;gp5>;WR0@ssxrsSm=j=% zJ`#{hIGs((s%z?g?(&~)44qfJKwM_m*he{1a~Ch04g_Xt;-qc=qSQ$AO5K^z#)skx z@q01#>}gY8Q(j9^y4f`RQ|a`uwG*{_*91!xYko41tngQR{8u6~aL(EyQzh=!+=gub z?nj2fCoLOi?BXa|Y^yBB7*o6pyS@wY3Tv%o(#|9!NBhfwj{j~wg@Ulqxn^l3p8I9Hno=|jDiCKo zikJ&Kv=};Iqea|$U`H1iSa@BIHT|0Upg&%ND=;X&YOFrKu|>pZBE0+paS~Pg%VZ*~ zxpJa;%PWW4Tn}=YB58eU8A%?eKHDHMChQ>#@v+%$n)07$bY^ zku@GP(uKlc{O6LshV_z~P^?s_D)Ul%-_b>G39gae!Y1PAN&;>BKBs_e&3Z@5JmN&V z-XCRL>@X|CZ^4jZ%+zgIBw$UaSzU3RfP#C$eWmW#HVy{d$0O7}W_gI3!WP-qP#0k4JRxB*fPW_3FQ`hAH z%koKjTc0D-l=~;qKS~|Y8uS+Zb=;W#AE)PkFZKV3;`|pN>R-gD|7s#NTHX%2>NuY{ zzT2kGS;f+6?Cdm3vfDNbcA4y(iOqqD&Ft~bDRah|)=k@6IVd=;Bcr$3opt71@+wzTxz0E3r`{huw?4b> zi)o*aSL^{TKv5E(Hd(~Hgh7jAhhO+N34`5E!0fQuPUV0iJ3*iR80{^pU%k}fOc?u< zZ3cs2wRoQ(&$BV8KH`HcToX0U1}V)3&WFPM#rth|vW|ISb)AlaJtSO2se@$V9_YKt z#c}QT+_~{pR2=-rBd|WQQN9~7j&fr~Np{(NY`D3ugV8hyvsNDZgU#Q-pJJtkm^Z_M z@7qwYsBd9MC4(a8;^%vhJLU~Z@nam^t$r}$pDTc)jimG|x%hKqx39pD7>Ci+)3>1A za*E7L`OooZi=VMW7Jh{Fb?T9ce%-ldBO3a(8~}kPLqqy6xet%Z@A=~oQKe%KG%7!;4}MC$c)nW@c@3Z zF+pudYlMU-)X{i@64XXdWpVQpLbv={t>R>0`~AwQ{h}k$NK4!aT->day=Sh7{9}(hxVTwjeElTg(b|nO@}sv zBl81le(CkKu;9Z`X+yYq&oX-bTmw+Kr6(^F5@IvUktISyg)jEcFKq7oTxZ1xz`u6V zP_wS7G-df&tNPKN!%G6Li^$#(9&vGS!F$)|K&uXkahmxp}+tISXq`NcYTwz&)wb zy7(&_Dq~`CCG$r_UHWyw3rzYm>xBBL-U5t76(RluCuUTOAc zV4AZzNx2`c6AwzPVZD(wsGa$@4P7cXM@nep~T9m>tS8FpB@=h4OlP zW>78Nr(FCvKfw}@<9Pe4^F_j=32zO7L``ImlU1e%gd(yk<0NpCBq+I?!t6GDeoJb^ z;DuLD$*+J=h9eY2%RQ2IQe$f3?g%D12?b7sy}q^wlT+m^)r+hnE?cazuUH6F^Ks>R zv*Krxhu;P9WP3Nr!5~WY`+i#Vds^Gb?0C`GJM=%yw1Ack*~J@kF>Os{Yv(w61`8dE z;M^n#{vyzp72KXzW;3-xm`uLR@N|ett};Q>c5OB+ibZG>ll*q+svFBmkTqXigd-2C zgH_x&v5qT1pyQ~5xb5U2ED46|S}mFsrpntBb33=@d>3FkGE&G7c4+R&K#|J3(I7tR zelLK)bm0NBTNaFIDc7UlYGTAcv#=v`?4N&V_O3J}fI0>C!mf2sRn*PvgZDgz`<_K_6=DvEK4&kT%Z&T7`fsm83UD&KbAPPG1yQ zXDc-${V7h$51D?lw_HTJkf>R?eE=wI8SD=K2Sk$dxuM3Ug)5J27snsm`h^T{bZezL zqd$6bF|7@3P97h;{;v;b>17NTXYpN_NGCyiPi{+N zes!dxCb(b^V5<{@=#rHRWUT4fnGlJH!=b1SC_d%t{?qm27kw%6n9v+etQ8q%GSk!J zzAKCzP4U8eDlI*L-s$n*^yb#)G<&+SS?LY6dykxg&jT<}r>MK=uwK@el*(;hs5ev? z!jdW|d*7lQk$*THH^m;(x>SDeOwNbfq|vB#Qwor;aXS#GKeVnT@Htf{?QAcUYCy<5 zxc_pFi3_qIZd>4uk{Vod<3G&bRQW;GpfoJkyg}m9Yjr5D6D>q(8K?{CGt!pPn?lnobaY>FvTAjeZ=*z6>P`$Qosuj zuRa=NQFC}GZz-}bKe8S^Rm3588yvicy!b1OejqA#BoXung?@NiGmuO(G;ZGY*PPX_ z1(H1CtzY}vGq;1+(EEt+`wByjT!OLQ4p=wCAK64h%Aps$9R(Ozd$=7_3YnEhQPd>~ zeo_ztN_3HRF_(Hv6HZ5D4i%4`<-LdKu(7B-wfaK+Fxl?9IM-*DIYQ#w!PJ=pDxfN! zD#o?4a!)kbyN75=nw)`OJD0l8u@na_?arvWc#fApti>Zc)<1~$dkLU@ zPKCS%$T%=3Wmbj#>(;D(P0g^4+Z!fV2dmZAJV>L@X*?F#hR`KMwdAdF0Qaxd zuvpp^dvAhbSr%_TOgJo0sfwAYiNTlS$DKR!p!DEhIYgCc--}$O-jtProxT!Z)$5n# zMUZfTy(eygugDXRmeKXOt4f!3v-Gj5@|?b5>zhrNA!#;)G{+~>33CK0B1fpd18+}1 z==*mg{_3#r-O5?nv)Oiwm;4>Ceqic&+_n04;b9#Da!QK)3{EU!ujcpzbZ?KKQu!Nq z369mb7m^9*_k$8O&n6qKc4^|UOZsnOEa$}*qsiN@sNd*}EJbVnWOp;HuJ7=A^Tr{^ zY9TAty=kj6%bh?D;&z}Lqri&OObiQm~IYQIt#S+cPuY zwD7C<%8PR}9O$WnG#qrr*j4&jQb)|;%~`oe((_CqnW&)XK8qPIU_(`d0*&>mpvL4$ z@uk)|0@d|iG`#!v9W}>YJoQ{_M&}I`2jUx7g}ryP6BLGM&ju!w4T2v-k@S^iy?+9? zTPSnzu-Mjhi{523tfs-F>n;FA$|asG&-kjDaJq_h+8aIch@siP&8<2GuGa!YJy*2O zvk}{_K&Fd4bw}rv&Yvt1rXf-wTx@C{Y|gFYiWtr2l2QwNK}JzxIJ*-YtWuIGRu)TT zl}Iw@skI#{)*`BgC|#mt8=}3t51h<4^>b~>I~FV;%FPkt1)ZHvQIFZM7)w(YEHZg> z8hz|HEWDEh7q!sHA>Gs*n(G_K<8qIddtzr%yRBE$re}hb+(B>cYV_T{W6Jk$s&?C; za!|2JB##ds(9)ykP^0OUqw+OQ_`7N+SYr-RmPm03_6=ALk|sBDbDE`nE`a)^4=*@{ z8BnO!)1&oBE`sV=I|ri{>Og7g(1Z+e9aFeX#{tcK*pV8X{e~np7o8&s6sMwrn5nP2 z#&7Qt_GVb|vNl;n_qIS&LSvTi2b=d5S- zKYSTeeF1LF;%~_TCD|YF@1Qf!@t-88CP+qa|2%xxCxqwYf9+WC{zo?bzoWqZf6w~< z>FN3R8~JHI1P`_4lv6qL6M1ue&`9!WXjp1%R+z|$_t1b4azkcvDG_Gj(6n(fPv(rs zN6J7;47wlXiD)miR4RJN-Voh7yUpCh(cGnu4dYvn+n|7;qzw2&lH*24=-*&qG zjFV?bJM^kMpZ2`X2>Abg-)1|+Bl5pi|CSysYPS~9YGXM{Pk4pOyJg6wkZCENz)X_@jALTB8rcpg|$_YVv3UMC#8p z(QRo0C;($rMiqE64O78Q4Y~ucNXaHVz3qu0r_A}YF+cWo32V)(A3Zn?1|U!wT?R#T zkHR1{$L%q_>tU(x>qDUWr&atM5$v@_L^-}QT1Z%XXiOem039K|*P1%5b~F(FXus#R z*;}_ZuM2#h8xuuC`nlyHQ0vO*ZHaUD{e5XlG&oVX^B&U1S(L6-woP~dkD?0( z1o`OIPzhlb99{2+E4aPwcGQI{0t4Ra3WwUSrC%$y)wLB`zgjy=5kP*TI9ZDb3lxHr z)yU*4il-BX8Z^{4l$P{VIGX%)9qa(=H4-X&*Qp2PfN;ox!{W74f5?a%h{35Xg@A%A z6U~eC4@0j{YyVJ+d_`?;M<{Uk5xP(X>|BQRFE0z%tTUhLIxczF-jTFzPy6sB36Uwwo++SV-RWiLA$TT zyVDIx2hG?Y;YK&E&C6QbQi+P(b^&S~hYOe+p%)3*TX}*MkE;i`&|kaI8>#;wllSvC z;I4Kf<>q|k48b8I!-{}eH8Tki(@I_TGZw~To#&|~m_@;%hVOFa$67N!O)7)CdKP9V zqybSuiZn!`6(}zC3Dy@X0JDn?InRdKDSAo5p_S80b0A|_g8DEjs8Yf7MLXUB#I$ADLka#HNL=ep@VzLOjqAS0>xc52Z@zcmWJbQi8J>QbO^MB13?6ffM~cLf;augKGt(eu!+8?1)88hSHIkCZ|3MJUIO*`GStK2qksYg}n!( z=J$cBNQ(e|eG-8i-iQna~p=<3P}+X%$rRxES7r^koMYissVzMtSroDT{V z<=~Jm@^y2fAPd1?S^(ow4UR%LZ7nCg_(pp1f`|=z!;ozr1douB$7sBQKV75%!hSL| zfgr^Ix|KuIhg}b^BQC^*8XEZ+s`I3BPFqazd2UHAdTnwHZ=uEUQmWBz+kA`}xI-qE zHE7g(`7r}*qe~#^@>;~Bc)rX65W)qTL-zneoSuVjeYl9Cj^*dN+2Jn1vb8e4j@nQa z>C;7FM~(pQ3;J_SQJa`ro2S}Ltw!tW@C9FEq%n$tlXv3EV@KGaid>mPIvs%1&J*>A z#=LfLDze}Au-+2tYgS}SQOJ6n0EMHjrX?LI8=WH=Tu4jm$q>m2R#S)AK)RozD6uti z0S;?i5u%-JCVIG-Vqj$XpOiLHta%>Qc6nK;j#NKx;MjICN(|yH9Z5OxT85~p7ux_w zi?KUB5x7a|#hV;aJyfPq6gV40-}Iy}Ti=%TA1Pa!G}D6>+T3erJ3zahic9*?Rl_ZS96g0C`!Ot)Wlf2jMF@rsgpaMk8n{*)eY2A?j20%QX>- zVJt*j?nFbGuz4{@hU=zSf~=N5$&$7fbC{A-@drO4PtV$ITh3UGyH{jBj-PNX`(jDM73(HU~naQmSn7ec23V$8&a}6Eo zF0vwX37^QQgy%Eth3|HVhX1IKS&*4ptsFEm3y}53d7q;Z#d4XfhiIM1e>5QiH@gbC zoh&~v$7vn3MRglri^&YpG2My+!SOcyE&{nq-CyXLM!NbF-~z{z7R^m#NKRf!Lavuq zTw`t?b+j31goD_psx}EAbG!4?8-eZ`;KfVa*SkupHyE+KD*$XZ{3zY>tqS=y4zvpD z-^96Fbm#=Q@0r86k9kn}NrZ9jLmk;3HjAF@Gs3vD)^?(t#MOn84Q}4W0y+(QLpsg6 zp!8Gk^$7)|e~){7_mTP?kdDzDqMmYat+^z@+^FT8ehTHWMs^qsj1S36x__*0>^AiP zGQ&>*A$-I}BpverZ~JkqPxVFwhVj83Qenv72}edveeip!_t97dBNe5A6ga(8S-nAu zlOEu46F~U9{vY>RFkc_#$v;BJ-W4!P;{q7#!ewZs1^l(^-a&=s_)Q%cpdKa-ECev^ zPon0=-;*OYvX>#(62^&?bIQKFG^p_vcFKC-8qK%;G@>n8oRg`MnB$$+_{rP-=&oZe ztytxfgI>aCugbSP({_zD%09n_1zimj`AUaqXvABF88sZ;R-=Hbx}=`;%PPUnSfq%I zW7Avq{DrT8ZYWvJ7gi=zhU$1R=wSaoTh&y!QvRJo-=Lmqslpah;M2q9c(@{~gY3nN zpm1K;i=g|{&ShtF*@3$K(avd-b*WT$_AK*hJRoXhc-)aof~~;iuTHsJQHpB%+(p#o z@-dPD#;(p;%*6||e;}10B?SjE4K%=Yny^GPH*0N_ZH|f;-XF?Tp=mv5>Y|KvFiQZY zPrgX;t~JMKz5OlefUF1+goV{!H#~ff<8KuAB3>|NOaL^;>HdzGf{;WDEAoXB=ucFp z5r~!O%n&>$ea+?S*b%1|S-9BK%jS^Dc9M)9QuLkD5I)JzQkUjBJ8`84%8|=leF__t zgz36f^}}3d<!T)BR`WydHBZ>0BM9aNThlmt z>y&d-2}ReiqG+OdArNt{IQ)t+1oz(A*7F)@-CP2wq>)=At5abfCfhut+?MlG&JhO1 za%1akJj{Q)!^XaKcjFtMl&tp0a7M-0ZgEa{pdDurmaI09PHhn3xM}&G7jZ^W47$P= zUQtkE?Js{~S($JBpm`YN zr)@5`bkS8wuFn`~E=QHQRQeU^?i)-xxMv-3fgtl?{bJ{^wb9qxo~v)@X(+Kf-mtzG z<;|_Lt+B&?rkiDnXHsZuUk-a6LUJZYytH0CF`{S!5z4Z|9p+X^IF}7wQ!e{d>1djxYF(jrw@&xwVT7Ez--$8El*(_4dQ+3qo^wTQD_DYk4zm8$m zGk*T}j*e(gDW4N(gK;mS((eL@1|ff6<=Xt#C|ADv#FHo1Z+ZGQzCF_VLBzJCle~hI zA0*L#Av90;AkOFnU^ordrN~^j0jwXZSol%_( z$nmwr;QFBKaJf)Z0Rya&9Kcc*TmFEM!Br53XP>IfRL1Q+$NxaxXR3<3v=O_yzy7RAtE3FfVeSanX)28BTl+f&6KfqV+k&_^2FVSYQ3wbr zmjMbPdRIZ8JHmvuu3DoISa{ZWiLT2Ht(uh4g`_R*J9V_|Vk5Sq^2ba2JNcR}Quy%w z{S`~*`tX$_kd%hSjrg(#Y(Ga)6Y8ND`Ibht3#}L(%QqD*Yu&<7TgS@Lngupn{~TR6 zc|+-C&_)H@xjWf|*ama;_@@@pa+e$% z!`xLoa`o(@4lDyS={tt}Q$m`0oZxI)uNCa=ArRRsn!Mh~j08bi=WeRdBMZQDZX;2Wwgf79?^t0C`uaQt_)4Jo9UyY zYyo1Y@Ij{uq>+ziG#jH2tV#}ec(RVz7l+O(tUqvw&P!Rv&kz_Aolen(Xg5L@q&F*T zb8h}53PCl%!D+2qaDbPYouJK0rBaj8AAbtP;b+S(SU7e~_!8#nJH4%IIUH?u zO0dgsIVQ9eWxHeVVZi^*jcaRLxC9V<_|VFK>ruSwkuLo!Dl_aaTKiz)6q+Z5_Kt2B z)LU}+fdljWJNa^_=;=wYB-#Kr^eM5ET^VSG<(%-SN1`i7su?Hsosm}4JmY6E>}C3I z6pLSQ%h$p7r~vsX{cwAj(M_n`QVu@Hc_e?~pNI$I!M930hGMgL(hZQyCSv{hEkB0F zd^N<3Vcj*+K`}#{Fhc{x_p8N)$za1gKPkFD7`qY%e%4C8WFoQNW!|D}^pct(F=0C; z&Hwezgc!`a1Kaq5hD@n2%rYPFOxaki6YFA#GQ1;I#7pSt+NM|#$mJ>tM6DYnUD!JA z3(l(8Seq>@u0?7^ybT?x|42p%e#C?hoW~MCrG3 zJR)a7ISKV(=c3F}6S zdBZJE?AGbnOc9_mH-h)>Ro3+^CWK2ot`nShqamWOqs}p-oC1T+mk|455i!0W{sD3D z+8%9K7=-wkz{Uc%DYV?r7#EM_3U6;qrSXBntOr39>0V`nuA+7JefP}aN(R@psf%$0Q1nkZYH~h*gY+e%><5e`lL6`63u|^+9^K z2R}BN!HmTeDDFX{wohL^Vr-lb&U;6@7U{eXk_{Di0LmQ@y~nIEu-FE!-&f)QSr@qK z$kP?+dWY79DR^Koe@II|aOptHX^g=+KY?r0*Rlp+c=um0!rKYpT5JQ`yw~3f@IE_7 zwi_yHgUOSG=#BJy=d>GXS_`$`$MnGh1O9~Hw`Z|&F0z{(jHm&BvoTwVW=0^l}f(Aoa?hl7k|e*U?X+NufvoNmyN|He@9_ zGP&>Me2qNKje2~bEFSZ22Pi9%Or{d zG9qw?#NH&DR72<|zZ?z5YxB6zbr)A0JP4!$GF)>^oNyUNRpgnl<7)4to1YzEkK0-r zGEKv`&uTm6wHygbFo!jNno4_5C2BMkfAl4$?qssw9A}D2xy4be-_nnRrkZ9_WJo09 zJiIqi%-%}nS`K}p48QMYp?n%ZzZmTAPPse@_B(IbXMz5tA=S6&P?23K(^eSdeW);XefN{+w8$O&9&O*8aOIAq^a67kn6%fD{XL`7Ns)|Kbugv2u+tQ3sYj{tPo zVyKyxp|%bAI3-PJjx@C>dTNbmWJs%5H*NkDW|P$2_}R2Tc>CVBfy2C*n<}K*T z_DOH#j--_y=AD#88U)`v(mP8Ewn`)RY!ddU1oEI|LXTRNM6LwXQ^w-02+>7 z$<>|XMN}!L7J!X>gpMp?p3PW%F=@fYI!XTYxjB7?bzLxgV720^6Q}LNqNvZ}oh^WC zuqOV);vd_5gn8xm^Dj^k-1q;k3;OqMzTAHj5B~c$pIqL^%I=>L!vA{bf5gGpsL9&@ zBT+ck;PA&Hc??OZ5E}E6TcScXrf3#B#8o;Z4|+*CH8#vP!2T-o3WtrYVS(Wy$UiWI zw!sKQWw99o;;S(XsYXD2LU6lZb*NW{~8V1)N&_Xypm}9Qvgu}(;(4D(uC9zzkFlw;oL(p>xnNRL8`nB15d||uK zp?K+2_d{;;aqBxP5kHi2g82GyHhT*W$nEh9U3WIshL-Fh|0@+(8@$R zU5L^+lt;6*_Crj~ONYx2>Lr69PR&M`r5;Lb#mmQF{3^TN05FQVW-|Bg=yITbRoO{Bp_+dZ#f_m+d_4*5Y*TC>oH=&fg)RWIoU-u-a zvU%P4l;;-toqOnII@c9SP1OTrKJhNMa1%B|BL`_ab2qotyZzpBR}V_3xGmXD0F~eR zjuX5VOG5Mx~ z?X_}gQudca%t{X!>vU+Om+#tc&Ka%5h!E0c? zA&Gm0eT9@f)A_EFt9*9}vOtn;_;jR`1YkeYnXSioV3Az=)FN_)oPBmu2~$k+IYm&y zBC8ln+u&i)1e6w5jE$C07Z-*$vE=SD+*L8(0+t2Ero*x6DOF&e*^>~3!myshKK9-u$>OUQub;2Y5UW? zX4|$iZllKb*Y6$E$K8kOZhmxA|j9E)(X404O9R z)_qB)Tg=z_a6cT3?^8nGjfP2yAnVuSC^TtJGLR}8bVp!`mJH*=We6$n`;lh{1hWCE z9xo6QKCrW;uXk$vG2vEn2QIleB!@0Ivrqk`+55qe+2efbe%TQI`5*_nrZ{_NR0IN-C5pzdfIPq@YD0|n;8Pk~-e=Cq+HQvTVdqZta37eQUX z>0^CJxC9Op^-u}+^FFKYO|Wa5$Vdt+=eP$6C^5BsWQaL^OjT(`#*=kv^G=F&AzLlZ zllHn#%SPSGOUaYR^@1sX?XZd$>wJLHTB$q5l3HE?iEi@mxx$m;dG)H7$_Bd{&eW@O zY09Y$LXPFHZ?ImmoN29SudC>?+-e5RNpC(iC9EUEp+a6o9rUB?autOn&yKUoJc`89 zoV2R4NHlWU#>#d5e=mMLW&B*=qI0 zDl(l@04_cLt(l>loW<27dyI+uuWKrg`m?&lrLzP) zR%xr6syVeMHzsr54u$@w!pIU(dwK59w!TYQhif8GYt*9Du_%LeNmE95R;gyQtuj4( ztE5CbgrBa`{5Z){==y4^5hJ9d5=JwfcsWOc#UB(~ihRggCpIf&fj-VHS$%XZv)ns* z-(m)%uh7B0dW2m z#sSAAW=_fut_%@Q`(gkn3Jvl}EY}pV)T;~YC%tn6Ic3)n!K!?smh_4pTMfGdVCH_b zrrRnH5X;RM+m~kRIE~h{XHr0i2FWjCc}zZ9fdQPOlouiUI2okdm4s3*3Wxj=|$sypXSp!GfTkfb?DNns(< zx;qS$Y$^G5;3stSPEpOWd=51yCF;0Z=Ho>5Sx%r4eDxUnpGSp&_j@P90=vs_(Oj{{!HL#Z;1P0yfDOg6*#cWdz)iP}tlVXbY@j-8 zD}W&Hkxmuc5GUv6TGmQ=I^Q9A;jMk)zR|Z9>+Pmy-c)8p!--b4NkrCeS*0a5E+xIl z&Bq$>r+K0(g(_2Tkte5L?CDm1M0`q{Ntbd0BS)e=UzJ0O(|M%LT|2pIX-6N$XuHx# zNv&G%yIo&fDzQ+V-Kf&TVmgMn*i`{OF{v8gpWbvAdW!ZDj@B|zf%ytsk`c7bmG&@M zInb4+o3Q#L(~?1o#YS-H?s)!U1I3q&p~$Z|v{ISGX@HW$R8f2~x;SGu+>P{ce|7#= zD*M>*2D<{36+Qv<>LtY?zMYP54Y3Pfw48-&-sHtPetMNC+M-LY7i5Iir&S&$us3!xW~17?-F4L1y< z3wxE?P>ASooz^5P=-ML^@Drm8ok_JGtaUL(v5T=SK(k9iHo;C?Wt)^&mpCzHjS{y_ zA#iigj`i<73}C%er~mm5el}NSPqa&Sgbuw6m5bT~qY~C`C>@XkYwZHbbw4-kei=Ru z>oy32;|ft1c3RF%<@mB3P9h?-l_<|`+r%{#FyLBmEamsztQzwu=i z1c@&Z?l;>31`~3r>KHAe{F@h|7dnovEr#Jx4_FFVrSkx* zvpLQnZlQD&oy(p-5knVG-D`yk6vHzA5?(o4dNR2XbSpOuWd*1>VcQ^ zPTS68-%nM3@aGYiP4sM?TmEjflZ`LJX05Uuxjcf z*FSm>gOjIrN3&J6w-Zk*{zebo-5b-g^y?}g2TyEzvFrD0L;<>L2phs zeS%4^xy^(t$dhh$xb)?R_ccMMi|65Sagd1VvmL}8j2rV`714?5!D>`5T}*{>{)mZX zOtpDoo-Iv%=)4}>FH0xTHX?dN$Sap8+pMT=4}~a1)o0}otJUVJk*Foqah5HldJUjV zcb8;`X4>i$Tlaf>ZQT! zrsZ{Q65lj#0lfr9M|+Hah!`47UQ9Y~?m?JfO#kUz7qZ(mHJVY+;?kQ`K{P4ZAdpSS z&}o?^U~=ss<067?QfT9(ik}XXQEqwTrr1mmWA8EFTbpqMHDgr=As3*Mu8(1d!L#BY z=hgSwB0*@rd?y&!qqx{N*4DI*zW~(OYFOwinW;}yFK-dJFVovyG=gexYOs|&$0w>Y zG8&KTR~nIdW>?b8s;ItprVb;y(zim7Un*}AfRC@gAo38TuE&4i)MQSuNT|y`@M*H8kf*#=&o-z2#gf59eu5s998>NXvx-aM#J@LGn466wzGq|GBxlEH#@wR7)S}U?S1ce(CB!p z*@yCgZL(B(MPMPW*4{ra!&=p2rl;{TwKvjgG#A%)mNrOFey(tGk}VPG7@82(#^{3Q>AlHHt zwY8HKw?lqIwJCJBMzp#)`K!cV@rpUy<{`7i%6p3Tl!kt3w&fDVVNG=IN%l+oDO=8> zBCYtI*Q*mt*9CO%eT>+!_?1{HL3Hl|8~nF0b%a{LDX~Y5q>=d`mLmbUzbSNbV<8AM ze#k)@cmdM_HyEsy4cW_vl^cv&pLRNE+Q7L3&XN$+RIqD3_R1h9uew!2*yTRt{b%1J z#H4B17W*bVV?LXdq9Qm{0lDZXm0?{Fs1gL@Ft6F62oTk0eMCuCafdFV3w9wI5j0M7 zsWAW!e-FWgqm5e^ zz!7>v!YO&`VC<(!ql-6O&GrTKi7sAT+&#P~&wx~qN^w9By^Y|h->?23w)CrWxpK3H z#T~Rqh+c@o;*w+61R;Ch)MCZjVw&6ah;@YqNQqAig*(o!gQSq%5;A0r-JqtojNPcV zC~DpDwrtUQVjaBJ@gseANz#{$=8-0Yktdi=vPk4sEiR&Au<)ERUrodRb!G9+-jD>R zogewe^5#-O?WxAtY)?%xhoC?jIW;}ALKrPy8392D?9xS&RFQXrq#2euz?faJ6(|IM z6MT5K)JUco{!)Rqz)D7ibB+LtkoHC}&QwcAtl>ANz3qeW3P6P%rJn9dT}AZqyxs$842F8#=r_4*J0wp$B;NrelY7|jQg{&4-y2Bi zi#vtzL(Odr)VYFI!y!34pot6kRc%SsRtA8lU(w5@H1VRGT%{!-D-Y==w@4jcbODw8 zqkaD^`(*%nrzdxG75Rk#&Tm5s2ErMRfiVBE_ z2MLSZ6-AFS2~Wb$uo{q8Y{8(1$T05g ze8Xh(AGCFnT@u<2A`2GH6VmJ`ZbYTYXhz>_xWShRX5NUW{MhK@){>hzrTYn%gPF^A z@Ln_!glyOF+>rXVq}K3gu>+b0c0kfkVJDxwJ)ln>FM|NP+HMatjzB(ch}b@Qpuo~# z-k649Fx>vE1Iv2~>L2C&M&&Kjk}+Z!$?q@=vzG^MFh($m=?xTZ!vKZ?p{bpGj*L5r zF<7o7%U$#hcTo-u82kQByVME35Ss3uSU1ZYjU5WUmSPMtT|mv&!+g{FH}jP{*GpDP z3`4S^3}O?E~s5bp@)9#7aD1jvTnx>{57%^TMHK8?<7XJ`8MxE<2tE^DS-u9DVhtSsX+h>-{-_q zo9+vAZSNU^wWoveS8X%>#^|z~qAiQHoEAEXxSG;=K^uh8|3J0h?4VU|tnbT=UyYc0 zLq7~+iHXcd7k`-L3?yjnFt&yq zSA!admr$9W8?4_D7k)0|-$kIqW zOHngt!G?2c%nyTO!N#Zlfrp9oaqtw(@b@cQYZ5CnjaEP@q?3teL`KA~rE^QPXT$c7RTC{dLw-g}RTlfE3qq(11FJ7aA+#o;6T`#xZKijZ4-{I z55jjZvljZJKe#Oc(1`Y8jCD0?hb=*{Gr-*yE^r4zxkuK8=@$g)1EBPY@^t`zYe45Z zWcQjGvTZ}H8;!n)Tyo?axtG`q<#XV=8IruC^ntbS|L~yeiTHI$*UT33RVQD95WL&| z+rw_4Nf(lT*zZH8dysdIoBrK{L5~pP?}MY{LsaD7Z&E4Z9xIV(x zBOeRLPg@a8GJJOw=Wae)8_{)AZ+GhF1o+8<{UqnA_^GjbB#0#GL2MOwFA+Xh;S~;* zW8H!i!^g%o5u_J34W))O$x4tP0hJ}aa~r?+?P;z+rb2p)a4YcjNbPqaFv$0ruOtXpQk8IIdBsG~R%&r|M5Oen`|1BsxmZ;j9e3*&K!D`rZ`-$3X2gN%UQ1G-Ul zN`t?V&<`ex&9l-}DrQb7h&k4}&}E}-^<|0)IGKi3;-+PVUWZOfG++BpDEdHH2_&pu z$bc+RwwaD|sY6#f8o<(ZMX}}m1i?`M;tVMCbFMo@_QwJ1b1R@l;bm~T3(`9rg=a5& z#)}}Org&w+x7pv+sOsEM_OhT~xo6dnpEA5-3UKylIeDtBjg1ScZpW*dAZhVUjMzc4 zRcH3ljCet@KQTKzYbv8PFug=_>Fb&QMYZo%j~jk+qP}nw$)|Z zwr$(CZQJOoSNooQU*0{rZ|5ZI?@Cry=KRK(8Y9AF8CU*Y|5?xYY9f%g zIXG`q^@?1I6_oq3*P_XHi$%XL&4~=02&r#!wpNot=TZl@Op`iSU$*H7rq6U^7{6dr zdNMFTK*fjK^++VC(H=XU_iKOe2(>5=~pX z8%A91-P`7AHSQCARABNvtItV+3uWNDkmOf2WgRR7tCNhQsEU%Ijq2`jUS3kL98I%E zJy4g?wknP$AIjIB8-}~um$b^$re))C&yMIu%}Hh=WfW2V>H6(PDT`tY5?+4*?MGDG zr(&oLi~D{H#(Pim8(>PGY>|0t^2ZjzFoTOXco&hW~-2~7W5 za^({SwrL~H0;9s{YxsQJH7a)s%lQE*&D_KpWvOy)DGh4+Br)*Gum5tO=13~k#`(Va zZ2j)#{{OGX|C2yevNkievA6oSc>FsM#mWk#xs!{$kBC~{wy-4lZ)-|rnt)Mk3 zYxW+yffsZ6MR+iKXy|!_iKr1L@b0oRe&CivKujqnv~6a6)8| zKidRD#fQ!ylmYrQAl&0i_*B*dd=SZTt@rjdRFuw5Yzb(aL9tibpW|D-JEENE_YA)@oYrIQpGA zcJbOCPD#p~03l60C#G;>4=NldslwSIC&|MJCe;SO4H?oFS_~as%wGMK>W3$uk317P z3bMt~JqPnx^QxnYQ%0OaJ3XAd2Q*+UoOgd(f%C}(_j8iJ#*Ii!CS=>+H}WO_7)W&g zG;aL+MN`(ZbTU#fvj6s#{5yJ7!N1QIkUnjU-Qq_jzyJl2dkc|+!Sw`z6k$UofA_}B zNb&+Uy@+b}?NFXlhNzzhIhATvuC*x&X;d~E!NDUXSIw+>*=U)&Tvly1R=#CFYZFJ0 z{`U3U=5U$vdd|AvuHQ;7*73Oz`%#}r5^~#8i5_m(9>Wo^L3R+&e+6&f9OU5#wo={% zYDaU0@T9<3myK-S9RnKRDLmqj&aDv{e8UEv4Wke03{pe*TlL2{fGS+i*bjAoFuml8 zO{xPuXb-`?E!?R7-!Xi6(F;3roWzFNLBswjQ6zpLJ7Ul>W-oq0G-C_N05A5ikuPB# zZ)KvZG#)SuI~Ff(Ij-s}HX&&?V{ta4)i&ed*Fd*gp3~hxPuZ4#x?*s^UUP$R$QB0n z#x>wGF_asJ)e#jnbDhnY<7rS+`_u`P7`f_V$Jy1Do0(nI#tp^EPAt~;#@9HM6OYOe z&orhqHn*1Mme6dhsU|&09o+8I1o5{vl+zx<@}8OmO&l~#%;t)Bq)a>{yVmi??#JWE z9Hd0b`L)iC4Z`6jQvyj}fgzMm@pp$1JzouV)?`z3i{9f~4Vz=bi0%V5?G0*UCX5k} znvEU2a>rWYFP^2&dr5y6u2l?K8^{ zWVcl4Ro`S8AfMpY2ZvD4Rx@R2My710UGt;TXrJ_ktO&xHzln%N^r!9MCO%V)i)s)^ z#%t5=W5CSD%jYpNeuGFSCDABouv^&Hp-j1onZH4R<|&l4&aLPfGBh?zDyoyKsN3@; zP03UD4yis)Zv-tC_i`0>t6Ml0sYru$R%7RbO64Bc&C;hP;$z+`49X^pfX1Ozca|g! z2qP=71U_uU&1wUmLgtFpDZ*ZGRZTt@L@KfFM>|9 zj$mlrAU(Pl^H&BVt{c>BHWR3FG1{T5EsSzft(}@736RqU18}#6d2%MwzegzgfmWE@-1j(CILfVow<@Cd^s(BgVT+TSBC_*czM#!Lt06(A5TxvXgkh3(SC?YpY zSH7DjCm?b&e43G~0Ju>CdY_IQFoVxcT!c5T#A$JP*~+G}-;S;VKTOs*0P ze6BIButa_)zc$vEtBE3Pq28=^9JDX8*w$HEF>9c*8Ner!F7If1P82NA8*YKOW^mN* zAcpN4j+Q7zi7PJ(Kj^qNqSdiuyJ(I0p6P5UZiYj%}_7k;VO)d3m6S| z==rmu(ZxEXdGPQITW7hCBK*pczI>x55neG`Q^f7!J9TzgCk3~9B)m)~jHMcPL$hU;Ra)|e@n!0Q$iR%sM52;kvx^^a8)~Ka-L}pyQ6&Cd2 zlX6nGX-&piAd=#uTVIgx#x+0e?AG67+cL;)$uK|~ z9+Jy3#pIO&1}p976}`V_G~hF>S!9JhSaw?xCEY|`?jM$!a@=`j7j8?dGtzNP5H`mQ z(Ehn66ztoQ=-j#jOsDRLDulxf7ZPUywGE!5lB?F_$yx`h1hbaCI-W6Yg_BL2P0U?< zmpW~Nmu>7dV38|U@UweTDVR7OgekooTncXyun&4~rC3~;4esZh1uepL zzvY(V(QQ=Sk7WicYhCw_>|LLH3QKHfD0{r@AN@ukfb4@TX6{SOW5A5no>MHYQ|wK* zqn9N%oXqsUOR?6=7XH|Da9%{fF8_3q8{0(fw*zR>aF1&Cv&F2FEGHj_6QDNb<=K+b zB5*p!++-U=ER8Sbtg5`DOk)o`Gm&mw^eFjEOy!Vx!=OaDJb2S8>9u|hh6dD&4#ewI z<1qp99~NK2gNl!Bp4%S(1Dsci?pric&@?--Ps$7_IOML4-qWyK4_X<2Y4U<;yUI-4 z*Q9}3fp1q%aBHrglo^h;J?tc<=L!UB`++MR)3R;AmGv_NHFg`&bv>U|j4v*Kpj*pz zyNaHGQ^0{I+{`s<_KOqwmYFBxXSjrj&cuYNbLtm9WKJJZ%YxWUNg_^!SLk}MxcJA? zL3maCoA}@{7iW5>8=OiwzmFjVL;Hp@jl(nrwdyB4Ww+9Ap<5$Y8(`e5Oe0?Haw6rL8C;FjMFmy%K;gVEVC8pM#3A@1-RTGfx zbMYKyb~J`95T+sMvWoArXn{F;?MPuAjT(BN!n7re$YaD-kU^uje7}R5jQEV50BKm~RTuoCg>#I4D@RGM3t8 zRE2pd@i6pGg1wy@kYcxlrjwW^6L&H2YkXiT%E-9g$NpG3p8GP z_vCF℞4zb{4beCwp&RmF|P)pnl_|QE(A`cTmfIQQR6whOKt4I+5wG8wlFptYXvk;j5+x|CC?U1_?`^lN3VC;ZKPf3;LN=)dBB&Sy z!zgUXLNksx2%X@__CRcvTN{S8<{lvCtf|B};&(~P&w>lY8h+`@wFwnT_>-E3{@t zN?G^O!Uk^tAYv56Kd)-jjSMU+1I^*nmvia`C;pc2yMw8N4mOwte2`U&Tyb7xNn>%J zJMq}&S*H1+p$HrXK$Oe*<`83E9f{A$^i<%VWVz)e$=7^b(77Jrsn=I#H}_Ja^_4rf z(+(ifmk!gpgD}nqep>lR4KZ%!3g@eJT=^2;vIWmu@@uNJh5<7_EZ}X40IFTvvnf9= z^yZDm^H0Vu!Uof%e}=K^h)a;$({P8;XRbyWO7~y?5=S#BLi=~|f&4#Yy#9S(iS|Dz zPySWl3hFuP{i`~OjMK20r$r6YiEc9cc5#b<9(t9O$HNa8kRq88WENG5GzX^M8Jmo0in=$j~Sg~b@St5llpA) z5S?|$k0R-qY{e$2{#jf<^0zMVk(m-$RZiZsQYXW88Zq)2@Z3y6=pwwDMvXe;(wpDn zknm_*m<3T?=s8gxQ+VmQHO9(NWW-j-@2j09w#rj9j8q>Cmxs0;>}OOVRot`dR-TV{HFHjPaW}Iw&~W8|hj7-^SkGrLeM= zB<3>GXHe#*UNZ1f%3#1IQ&0gjWh6_Lfxe&rExLa$kfy(xWk!&mOGm`&W^a4_0AW-p z27*xH8mYWCzJ%OfksVG3bL<)_6a14yb~$<30_St-nLuHYl=|By$G)BvJQF$m^YKLM z_rfj5cIVCe*M~J=&reMlJr-lY@@#=mpxB;Q*kBVt5pGAxvwckd7q~2hr`Dbw0W2L! z7_K$+mhUgJVBPDFgy2zt2=oWS+N*+nx8u5R)(&LAP-;o@4ww-6O$BC~+ge`>K_vR) zf+WzzA@Ggz4bNWD@)emY_flu^fX7n&-u9JiEzgBKgr`-Y(B#=xyj1yGzO4;J9>iNM z&xGFQcx(qK)1H0<=%_qL06exNG9fZXr3)G4$)~W0&%b$QB^B9G^h>he+g+n8dGu0J zurgXF+LL*SO;e(lMktZedX?p@LxL(0b*3~zls1?p7hlBXq6kOi$<0}nFI4kVU_2%0 z8KRX~C>lPyOpd8tqQ}SoKKH~_k|l9A8y~{};MmPlfQ4_uE61Om8Sq;GW@zq_+H%iA zy3>?>fjXwzOrq{@&_23`m_L0j1kSXON3)HAPq4+IVxQuynnK`U8F$ahn!seYV>6&! zCG4p1)iEFRwJT4FCmF(g$oN3Rr)qtjr)ZK(0xmMjy`SnbW}b{-jADPRw;+mTv!Rvi zbg^BTU})W@G=}E4iMekvqKZrhj=#bi-mxyK5GOOZ0V6Z}gTD8yvyl8q`|W5yqfn;o;qMZif`>r@t=LXg6gaDW7p2XTZDUc#4gY8h{@rNfoWh1s0oPu=&q48r^bB zYRk^_Q80fZ!D!E#swA$u!M+8`V>DGnJ-Em}?8BhDbzECS`Cv#qN38WW+pw6=L~&uR z&-hA{x~ABuL1XXI6plasS}QS(61xJ~*@pllx#ksP&Od6F<%uJ4XJx*jIH{cLj{4k2 z%8KH_9`xqkzTm-jI0n4>;F>CHA=pD2#CvFK{l!qmx*ns*6ZA!8dPY^!wXWUt`y;Jt zY;MPJH!XQ0l3s?9{MeO#Ziv<*wkeU%gl#5Ewf!mH7zo*?v(gVPk0+EkVr<2ufa+?f zih#f?u9Wz*)(!qoTr7d>*rdydkXCZUg?^k$x;f3KImSUK`G^ztK_~XX^iDArYvKp= zf)mg-zt5dPz|g?Vv5m0Svwrqc#GCRLJ37iT+$m%eh(@E+g(_#Nqq0=E1oMXX|F z^Ml)TYZp*`n|)qNW1YxO|DqLj`Z;QME8#UA&&#HIH*#zZ^bnFdIwlSmgZt{x^=#ea z)fM)%Yh3r`@wHI(C>7LuqL5*RAQjX0siTV82bI#rWx_l{E_S$H@F$&(1lpiN_yK4; z*|0@0D~Qni9=7N^7pQF)$YnExFV=yKzGZxm0P4d!G^+B`rzi^?%lJc?)y8Z+6z%Fb zqltKxqBpxcB>)O?a@S0!WaRGYKjr{F#!;oGJ#Xzn+Y z80pzfFFde{jn(;&Kg*oQU2Pbyq_jh`@6p_%r-x`(W}jEHble#)bGW5NIiq3sX;tzr z_@ayW<`!Bbi;6ozi3zjmhUkWnx_S+xt4;QQVXt8y zP)BdZ^QmKsz-Y$Y{qaq>0FrLs-7*>FcQClc02}gP-V!<|G3CH0PV)S?T#d;K+mzbi z)ygv=$nt`*>ciV*8>p|6s3Xa8{UL*40O*5T#S=FpWA=_fGnp+mW`dnNaj}cxa2vXq zu#l%JB|)_m(*6F+_z-p)+^BlUW3eR7G)yP+{841FBMR-v&3N*{RrhMYlq3aHijwCDsW)Q64@;qbr9y3Z`z)$3IR~>O z%pD1&c#7N!rRajcKgonRH1AL<(0${wEYq#mLf;PL0Ho_Q4{qkv4dM=UIpwKumx zOhbN-^`My0N?tTpbscgQem(J0kQf3)O|u25_owxSyDy-8EYYt{d^=u00(em*aujlD z%ol{+$rZDFQDFSn*G?PbZ{Zy0rPs4-8fyU5-ZF%j2MiwU9y0J^qKw#^3K%*`F;1)DY2B;7^lzH_V)7tK-(se&$fNfuXk$JuaGWi7-KG1ZQg2ir1cHeT5_d!&9)RS z3S47geuYE%M&l%Nild>T!pN^T?ftoEmni!f3qj=`I-WkwlO#$hVrwyGa*Jl*4U)?^ zt#m|NVi08@O@%{0BG}Y=iKRYcIuj-8lvZeEeTPF%78W$$HU-DUrOUFO+E)9+#ss&; ziE52f&sJ5#JjL0H%IG3;<5F4bBIU}+$lBW4{ry%1&BT$i%CaOS*co^WarUJ;dsAiT z#0vLHE;(ce=g4-~OZnb18YGdcS;k~5XomNtkC48GKDngkV4?`onEEEQd&}Z!l?!|a zkLLMt?p$4saUxc;-lgJ+)?$+gYC0ofAi|%eLK!x8?(d{)yba9qqFx4 zcXeCr2lm0m;>6|Lr;n&)LqPH}N30K&SQ_@&0|9vWtE3E>bdFak_Uy3*9asVcr>=sj+_ zu#E~v4)$(MvmrD0wH0H}r;=6(7GQ@r1$q}0*W8bOGoo8!z;eq=qPk>Pn&p^2Bkhpn z)dQ6qa>))~%q=18W!awL8e9KGn%XEEy?qYNUKv*`p8SYyTP4$y5|Mko_EV4OAj-n3 zSRGb6$)g?X?t2~njOY%WZd|FOy$l>$@glpgYC7Q~SG+x2Y+Q8J_#@fu?$nbxiixwtW{3QS#w7rTfzODp|NK^8Axrvkl1?j-N zmzhWj0nf80yXZ22+RP<=vofT6R6>%m$omHLB|pNXC|$fw1DZ~1yZ(4$)nqDl{PW}S z59n{U0|eBeeAcNwJ9q-sxH`(i&;%s1a`~l#3W?R2IV*KgS`6rQ`$&*ybI73n%Cb#bZL)ZjB-<7f4hks$^6!JVbExoAh3?EP zlMw4wrCwT1MylJqMN&wU=;U)mG^#Zu?d{_zGA|y~NAsfbny2Yf=jclD$y%!W%o33B zDAuK)Oji&#DkDSrrG90DO4#2X4+Y}n1&I*$t|Hv^SV1jBTkfj{GA-mJ6#IaOQPqic zK#AbM(yV)ELqxyi zR^c{(Wo8ZAW<3D7v6(&q!l&BkrlwZUaK{(xWjs*g7nljg@@1rTif*}*U?kh3$;zmN zjF}RvlV`UcGQ_9S%n+}In7#l?mE^M3-IM$trKSzFXt@F;>Hp1OCFtKnR5$MBtH5pB z1{qPZg=kwB=_~r9h0nR3<|YVW&hA8ESGT4QbJY`P$7(~4mtCFPHkMN1oxg`!AL_cj zgOBM>v-UwcX*w>TL1yJ-H4u;L_sY3~^w9QC_U%pkhWNt)H13BQ@!Z3iLogdsILi`D z@tkxdX;FI53%rzEpthu4trMthcd$v>K7O9QRNP(C0A3uQ#K#+!zkqfz_1U%VyUxx1 z#{~ILftHSqje*7BZ=n6QSNXmk<)YcYUD*f6PUk*j1h;y1+|(bovjewM5MOJM-UoVv zM-o``F6zd!%dSpwg)^Y9%>${IIrdwpx-PA1@*aox^hdWhc1{uCHvv zlQp2=Xi{DLu1yrMxHXWoY>Fb#J}G@WTr`1wigl7sCsD4y`ZUwMihaeuZsieWIn6V} zJm1XKVPL_#Zq?o$K4ZNOT&LxkL)D!I8?}>~Rr!*-KwG&v?g^Y(W&1>!o4dlOCs?ar zB9kv}9PX}@?uB)AuBw9}7EWNWT6sVle|w=^j2erFRwuHCRVuNGy?NmnCWqFPpFS5O z98yS@KX-v>K+jKTF0!5(#aL)2K}?5MPjp@PSt>Dvtb}Y<`u>8kTF}^-g7%)4L}|7v z%<&5QO{YSd<8QNSU?P-RY_1xtqKJ`O_%Ai`N<9*dub2*Q*gKz$%n#B__NY8Vn(eTz zcR(;V1c9}}ykSsWZm7Knls^2>KYv%RecDy$a#(c-SD?cqbjRC-)m`;gr{EUJRb`*h za0}7k1>?|)NfvkL4O-x`YT~bbZ ziA(*tKLd~cg8u6PSYppO%>PD6v44C3{!u9Y@0RnwP?672&-Qz3?e7*>{HQeo-}kN% zHVIu530{iVb}wOonCMC${K(#pu01XxKwsg0!w9Yi$dCaL3*i+fK*x`EUfpjOhfqM6 z-hAA$HL87Az5od)6_@2@A0?Hqm&aR%-#;aXXCv$B1Z}CqVp$`P5mfylErnMjYSBy> zdWk2E<0gfe(U=u1sfA)A_v(0Es@^{ih(rfwDbd5m-2SwniQ zXpJRasY+gcJ^?HqG-eA#{0SJ}Np&q&jM(N@FJcd$)rJ%G=B+Izqp}yoD_PA2hD5ZI zm4xyUotjXnKWpTeuoF0m$>w`~=f)`e!7{p)rbqFEfLB?FKVTu+{5cIc-C* zp6l{UpF^$P9)hDLUbr_Eoj*-lLy7;Io*(7(XW<42DBXj_T+o=Az#iIpUJ>r22b4q1 z-b>dCiC`5%^QBT|$u7DaU3|*Un94jnabQHePjm9KhE?wq>3;*L>ffu@4k0?%Z;I?+vDlx;IvZgpaiYJO0# z6!=2xB+~!}IKhFZJQf*Z)dK00g~P>hE-H|HoTwq5puee(&%(D%hGD z*&F>UF_n$}+9v(C9(19?rTjcEB3F7*D0HBHqiQ87fc_f5t^g{UoG@9SIUiL>|4Fv2 zGP)^(sQklESNN|N6%)f73(p@qy&^kU3+-m0SXjmEpCenHF3%Yr)1B$lI@>+~v|(b< z=x_KTIXaZdN>HXTv&FFvh0yGC==39HsETw2`YC+QQXc+#4JR$>L9GT!6dR-*jcEoR z!jlga`#~)`3lZ|VN3D}u^DZ0bP_fYELsrxFmLSTyvPD$ucQ*8rCxJdi64mll^-~}w zAxKo|G>aDJ8(MVB<%ppunRRMfOj;5zlQ|bEl+nA&q9kIf@29Y$BF za*ll=d4S(7Z&MRm^-|S?s$r}2YR-Dj>~_DMg0NUpDKE)ES40)MUfTQYN!=5~Lo}uN zEyk-#n_05S`|F@r3?)$%EvwRtXI8 z)p_{q;T)T0UU0QyD6kjbdXUcexrha9^O6iAuA!D5#E(Dk*6{j*WxWY! z{rW9{G9X6U(UYS`*V7N6#4@bpvH5(-5e>I^-%5}58@Oc3np zHRs}Y4PDzcSCUu9ZFKbCG%{?94rU7CWYJ?>nR7YOq{h|@y#lK+jdZY*S%d?BvXE|C zo%K>CCKCK{K;_M9qnEI$`E9n*3vjjfb5%qY;@fvRFIb!>7_o04cb{`KhE9NfKpGrm z2DUUWz*-a64sK&uh+lMIRq6#14>eLzasD0aFUT5C-WjX?=By9@V>a{eMV-`tkR$*5 zl=NTIn!l!k{{?3My}DSbY^Cr`XuYNDYGNv2b9BRLgd&;16AufK))7fz)$?mrJx`3a3v$ved4n z`1&n6^fdHE5Ex6brA`Y|wH^&q+L%gINwOmBn|UV^`Sc>JNCeW2<1#s*CO?W(&tut85LMuAg=in?=gpIT}^ z-n%4w&Z<>{kqqAe`&2xC+o?l8`|?~cHbMGgU`L?#`qX031&)g}C`=tDfkvuJ^YU5P zPp-)R+C&7~7{d6OvV6_Oz;-eGSweGDv??wG)BvP$I}>+sy$EKB)@WFcMhP z+%OGf?tzeBw4&qmJuSztsWHtv?172AnhGY3+GBJ-K zzxUs@tf)9k*O9bIuK;CCcl0%P-1n)>X{GNzx)tmQus^e=@qSUZacbCnBwj04eZ!19z z>EE&pB;vmOQTOt^vP4+is;ImIXWw)BNVx>_Y(Kf<3ko>4ag z-m5qg-JotJM=}Us{gmhVcwerPXyXk=MT*fEP8W^wZ(ln{I9T^@g=+ z0i$=h)4C372#po9SWmHgy-$>}Z-X|2Lb*#V(GvXg4c_FG!tm5Wa*m}%aJw$x8vl)8 z79nk&fU91l%{9Q$Z}5yO-!=AK@9E;urVwQ%Zuhe+mq_N;?BosRueal;a3V?XH@-%I z|5HQgA05{Irn};T68{3$e}mM-xaq(4Rh|GN8PW9?>GRel^ZWQ>c2z{Xu%-Kk{}6{Tr>_UAoucN zXR=>x=BZ1{9d2lt#qizT)B-8ab@$V2LJ+%kN5ui}oQ?)bNWCtJsma)Bn2L)!6#?&8 z7CGJj-Mz1;1C$$Pz)lg;db$iaX(Thq=kdIl&gf27Ftb7WC!y?*vb!O^V04=$T}vpf z$7$IPPEmTRfVhW;d5OSm#6@c2eZ^$+M?f-NWGX$mYK`&YpgP)l%ka&~-sCJQ6+LR2 zDQv_Os^6F06dz`{)pdp@RIx#9BvePxu%vejuMEj=Dv6NN;C*{MXvTW(tul7pzO)Cq4qbR*ApbK{p zkJw)E#z-66PhSs7KzDjyiby-6zD-fPa5JgL|LU1^JGPZ>eea$ae#g=O|IUK?Kfs^A zh7(M5^#8qmqNpK*A%e8GbtwirZs?q*xgpC4+Xx6P*S1=*}K)&PH;FP>Kwqizx>_WZN8l4L*0p> z8y8m@Xz#w!oWQocw@72_v7!6Ur^B`8{tb!6<}Muu5DzTC+GqqenUW%vY&F0zjn{Fl z`mHyDm(@;B0heBf!VRFa+_90m=r|FmVIV0kx3XhHT~0%( z8m$5FP`?)@rT?a!sQOijsDFhk`|#=&El`b`vyG6?noHiEzpvo;qmxy$_5-q)n&n4M z$O6n&7DoRMW1qV+s+u6o}w!OAC>Gp z=U=Du3pki_IPyM@qS?9mJB}cs0-CAvY1d?KaYuIRj8Ax3Wi!#C$UeRll!xR~af55U zsK&ms!r6`y$Z$%vByGZg?_gL?ZBzC2W2cTBZTp0)Zc0TDm~2Z9mN>ilSrQML+)EA( z`>$rp3L-C5)AjEmn2#M&(~SmPhfabwXz*4tw=reG9x`#$Iky%dK6Ew(;2Qe!?pQ^z9vF zY}-e?TaAwh0B=6H?%V*L+f4LP>Gstt(X1W6Hg?Ev0x@Ep!)jCl$oXfHh1hFYR|d`e)iYL*z~p#l!e7z`q`H1Z0F8vhM`+`A0up zj{hJD|5p5&>XXBr#>0SzUcasB>4Pz?~R1V-9YVJ=g+)hgHpuPVIwm^_44eT*z=gA{_isF(ye z+i_QM@vN(%;cI!9%~ktzm&f#7w!<{r^XVZErxO$}^k#fG?59SWjMv78cG}nMZ8x{; zO)Au1km(@Yi5J990x>hkJ&SBhiaA*Pv zLlC3MNy7KRqi4}PDo&BCFN}&@t}WS|S%vhzXUbIEjB8qq0D_mIBoTY!nc`8t7~^WN zc-o!-u+-wIBu?20B@Xf|V`kCu+^S=g^zj>Q`k0YWpmZYl1VML23f|-dXIY-woZ>lS zy2zc6N^}`Fw2gg8I!C;j9drzZxm=)}rzkLsEmA_RKm?~rERqVkUcw;_~R48xk8W@If|kb>^^NjwCYS(hPGk0;@4n%d#ag}3vHvFbz@^i+oYOT?C2Ya z!YvTP=xM~jnnG^^sWtd)dYE8&I>9Jn_oP*{1=HWHBl|2&6;{u&W{06eOH^%+OS- z&dp3?eWe-(^RU)EJZ8z5$$kTmxy&_GJ$}fp1z3r85ByLt1XKN0gji`|Mr;G%4WysD z?A7?R{2IU3(?FhS16v7{>_SQ!iwkyT9XIyuF2a${(+o>eFY@-O zZt-u=c+cl5@#=@0x{0;R16PeOM2-baiU$dL$MLcjPU(NiA|damq?T!KE>#>jJQC*x zeB{!Axtki$#xlN+B&=1ds(Vzm&AQ*!>5Ie%Z9!v91fW?ny#5Bi|7rYTtww0Bu4@@G z!Z(WZCX6Wai|^Y2DZLJ#x|`8ep`jOCe!OcVKqo2^Y+p^8lby9uQbk} z$)tY3+<42VNPVJG`9xXIH(!ujrm0w@3X+0chR7Kjs8V;~mjOIPsS)Dqj zODA~!Wy$Xqhi$FVz<6MUP{DEsXEQmYEYKKPHKB?hf8<{0rI^lnH2rf2u$5V zD!N7DKK!P&lgr$CF4T!c^29>wTIh~LLQroYY%laXSB}g4W5^(WV|q8|$&1yzeNu!D z2+Fmk)wu;I_)G#pzQ`%6-87^h}`UzGq1-gv+9&NSjUcQ@)9dE)c+(?9dQ$DXFn$ zJHn0_-%`Q>wf@#cRU&&984)7MVGJ~?eOCT_T6yo=J3T*|bAjPi(gFz3s>5g6q2EBf=6k-ioq9lDWQ(~#wBd|xc66XR$R^L{ zI)b0UC4`gEL9VV-$@+R^P^rG#$bi+mMtvV}C9`Yk=9@ht-4uUjE)xY@(o;^I0eKMe zc#@BFgyx#n+~1N?4u7S3L|!F0x!4^t(4T7Tg?gfA^j2t15eTd2(7B(ti)g?x93~-?1Lanp_nVGguy=}Z**-yTWdqa z=9H#FR8=ScBZ{dynOR`DVH(72$Bm$16k;O8O{9Hm%c9!)GKfIcYuz+n5r)9i ztCV$dWl^A$+Nv7zoI*#DU>}3kl9Xwio~aP~ICv8w=v(Wbe(~No(G=O%fN?ZeMQvdJ zD$CLsF5)a+F{Z#BEL26;KTfz30yj)YdXAx?p}YvHzP8-lP-Ro5qa;&;p?yGuH@c!_ z4f zp^0{^e2JxbiG?bWCUvQJ5pR(9y~%LQ@OlDT{0~yta}EC|r3rDk{Le=t`Y@{ zN{PC&kn;u{STT<#-t-JkdxjrOa32`vz9x4(!wKC>S~LnUY!{JruB(Ad$#wS^X-}6M z`Baf|<-@e524ov@!4!d~pTkZm9Z>3B8`ASvrDpeS9n++{p>|RFagV=eNgym7&)l>5 zy{$~S+@7^Bel))xAHI56R$Mo_8HHsfkDgttKBxr4X`#v@gQRT`TUkb}j#WI=Qw!r@ zB>wXK*pKl61O6c845;XzoO{sHeE}=}hXE#cVmn&w z0wx}Y4K@ z%t;!?vVQlpM|IVjjphN+EhxbS3L97CCH1_f+r%$ThfGVn)}M7 zUOZah6H6nAEX5d-Gg1iHd$7LS*ySx`+pEvUC%p6p_3#DDcu#>SBRf^J^ZY0^II+ja7+iAFbIsAa-em|bL&5P1E}{BFL`Z~(oWmG1 zC_DP61XuiF<=KtOqn>hR`v4UL77&)O)0NgcZ7xndM;347JKDsl?WE~-|Hl5R=nEEl zgzsGY8ST`1G`Q2%AJU3@RRWpJ<^hKfyClZZ9qoQm$=xi$WGqZ6=UdlyEGx=_wUrcH znvH^f5w;Y5w-Q3Y`V*)HIc{ZHJU_(%)JUN?VqM6@9rU!2^Af~$GfwB54Jyv&@MGtD z2be@M!)XHno#u30HGMlF1dp6SI9Ru zmMAQR9Q*LHzxX-A)NAAQ9?x5d*?rxN@2Q4`uHd zTv@xVe|Ma8Y$qMtw(YFgw(X8>+jcs(ZFFp>V>|ihIeQ)AxE) zw+oEuHKa2YAV@W{XVZGinO8|uao5Ua+eQjmlL=>>V2)MA6R)=Jns|77OvWFoGu1Vu;d1zzS`Q6fg1DJ!w6eSC zlQ>42#35=KAT_M$yyx7JONT`yyJ4)zbUA)UN`w#glAl2J3BqsOIwJ<5*O zPP=z!mWNBlYpvu>Pj#xTivV`hLRb6vS1FIZMTGIJ?)2H9#HuOygM+kBWRE-XGIOlM z5XPxLP*{*fR>33ZS@V@5awXfx%BWK_hyVdJ01C=0!=a5q)FC(8cO7N2<3=EkvM3g+ zSZedpXWvj$2@gJQLvUha0hNWeB&9~3G|RGaicxp8s>i&R4&o#75c(?}+qzf&y7pyk z&K|MXxi+mL{wmuWURtlT7oYv)ec3~P4a>y++I(x;#C;U(@_FU6h^52v!`(NTJb^6b zvxRE0>Ias6^ELHLY(Sw{wN7#LMSls04(G`Tk8(RE=hVVr4lJi_xa^(58%$dT z${a_u4SpaF_!&zijgMxLNy$z`x0G$Nog+}<0)ySS*P^nwoX-=%v+CF)^$PT0KE21a z3jI|55YH$H|JBtPW{|}HP{1@MXpW&OsN9q6b6A(HRH^l>jXU*b2%2)9F);SU!TY_P zlc?}e`@AVH+8QDA(#AN(D?P;LSkogxbpG}VbwqjEGi6`hN?BGj$^BAe(z*NL)bf7H z_}HE0{5hTZ{`OyyYZ*(Nt6E?69d? zYA2tJ2B(oazf5VLpH`h-&@$2Q?5_V?dWWNaB7LN^RV(SLzQ#IEa)Pn#M0*eGp_K$EF+YiWY=PRcbw<$Hxwo$yTkJy$!VeT9$zpd{ten9@! zGyKN>6gd91jRr5>|JAtvJMr58WZnN;2k5I$Wvir&^D%YDYZ9C{FIZxpridqq4>;qe zs1m}TfheLW0t+W!fM}kV@=P11alKHo+XFA4T0rfRpOayuoF!*Y|3O+Uz20V*NBn`9 zUb=9(j#=CoO3HfDdh~|3_1v}foHg(BxINzfwS_gRFbeW2Rd??zlpeG!C`YE!frGK} zfom&g5iac$fog)r*7V&vh*Kuqu6ZU@KF+im$RjkvYThe+K+d50xemoWPVxR#X7rJB zNA8}8-=qW)hv`)0n(UA`d^&XUPCBrGJpXCaujDl<`NahNQ^D!oM4sS{!47X z<-XZ6#Fc2Lr0IY{Gb`#1$Bg`PicT9ZIk_HBW#HmE1&iwex8+(ZZm2ZnQZ1xUY>EP2 zh~<~p06*_gl}vZTA~5H)*mvX@AJ1e!7dO|>!C6gZFh9yF`LBN{D6J+xcWDnQ(6N=%XzIB+(bfw|K#&6z`SgMP+c^QM^GHqS-ci+zg3_l~l zNRQLRbD9X!+Y1a^K|0n7wm>d6-u`3_OY_b{AGIy5;6LbkPT?$x@gIfN<+R5)M9yM1g1eh5g~G^J30*`J;kUOmc7C=t7hROgS$Ur_ z7uejeS5qoI%+HNIR{UBONAFPOEflAmJRGV0rOp~9Q=UTJOVEgOVk)lZr>J{V*p$Ez zcH*iS*;h&GVW3lAnUvHcP;<>WD^e5V$crk12$4pXk(>V==w>VS`?Lx{V%vj4SjOSA zuI@ZNYEkfs2@$H@VHnY)b?7Gl6IEhP6fKb#1gfso%&}#eC6Dv0$g#83O#aveA<8nhV+Dy)^nifW^hdrN74jQ0~AB_+Vtt3!6s^t069TYyMrHKA+~ zXj$K3vn{`Ba&BT3-Egy|FQpW}7`+nc>M5d81E|Msg7XSr<>=z~l{0$Y4ZJbPZm>k% zlce|TFmE_x%s5wx$oie#L7NU`UM*fM*-{pZrx(xVPD&p)XU?w`kcEvb3G$!0u^1MM z=X+Oq<)A-U&X_D^Sif~dtp%f4mP#qYMy9KfR&;bQx8Zg2_&7X!qO}B~5S9tON|BA1 zNl};~QC|atZSrpEXhYRVzyc`4pL^DT z<_;s5`X7{6z%=m)3U`Xf5g1BOyww5KEnIcgh~8z8;iVzG{P>id^%gwhp$rpg9L-yq zOiVetm-yetmZJ$GrBMhf2jT|HgIQotu~;$kad#k7Jm-wbmx|UHo@m(G`{;|TrA+mf z*H7`VXkAz5SgYTPSS2|0Lo+p^53(4PZX8X~(_!))SI}U>+73d8W^AAygPUKBB$kRs zUu7;dB=NC@be6E_ai+P;he87U2D485nW9@BvE~}xw>%Kep*ikGd%br230!DGswv8o z84o^uaqgaQmk3ROxqn$N}P~fl#saj4v zMGfot3N#U2E?vQ8E?+Sd4W~=-dpBMAyy@dqEYvVQC(QIY zZ~L@qj<=81$NS~)t#2l^n*4}TtW!J5QEM%Rd!${91;#XEXew5f29v=-;fs})*HLK7 zG^`CzDiP^H?P#ntRt#zoeL0W;r2WsU0Q(=Avir|dAc$vWi-i5#@#t=|*1>UeqX(n7 z!Rz6x2{8REbg>y(Dnh|)`8!fkfa)t(;o}qc{0Wg)oeUtD4lGbct!t5X8VSex;=W>{ zY$#V<&T5NBr5P6u!qpr{K}R)*!!}|n#IjmKt@sdRrv1X-$qL$IJi967LuE~Ab(H=5 z=1ZlF?aG}UdBau#c?cs%3eWU&A@kY47U7w9-A$UM=N-`PQ)IFHx9d$=9r4E}9F*3rTqVI8 zysiiJBLKhpvV0E|51W1b%>n@7C4Y6NPQw-MFcJ4+3HR*8G<$XL&J!>bPJQZLOEfml zZA)+MRg=3hdAk3t$c$4HmRymPpVMaS5dEji5ump{4<(KpNK48xkgaM{1n`Zk=5o2; zfPJrgn?HEADO_qoi5_*Obfo0NIE6g96ET=nJWba?y#5zw z&@HJ5V{fh6KCB_1!oIl?8Dg8T{(8DNV%)s=jr042&N1m z9eIQ|NgN1$;t|M@b{P@t?`X_+2T|5jMhx>HRF8MR2fi+Bm)5tnup5E1c?bIWtRwB% zWcgF+&uy2AA+J}afw)I;^=(gkU+Z3k{p`a2`Db|GLm#Q8?mCD54ZU)Bk1p<~UmqVS zzF2LHpQ#K6<%oXP_kz{EUA3h_21(USq(2YU5otQ;AwDOL_DsJ;Jjmy2MqX>w-;=lVpXQBVkeW@J&0oIixLGJRihGfM^USL32RN3x;eQvavxpr+-f_$lJF`}PmCt3jJwt*oQ6g5 zY|J_|Ka#&ks;5etSP_{wV_w_LZ!kGO#gg4RrVbsvVX^cy`bjfk+UNMTyMOGiasn;= z5seR|$tAIp`e9q0)NlqK{yU`^>KGc3Rot^oN@Y%aDeIJaqEbL48`VvLYKR05$jemz zVDEGK%-~rUZ5eM8bI!iMc!TuN zcj1&?93`oCfx$(c5q3BoHCVq!VbwOmO;a6k7PhPzJR4eLfs)T{t3(HEO_s$-Eer zYfu>|&2m6eL<2>-QbyL&OA?nY-jaw0`-G1`9>-9BqHx24WWt0BFQv+GDU2lNw?wD0 zt(JjN8xCk>h0V*nP=jF>X8qB~OPitnyx#KoREAZv^&nA1WaNglLf^!39ITCzryW$D z4wN6|eqQ7p=uOHEP78h9jd5yXLIs7cPcTmYL>r}#q>Ir32bvummxzYg2`3&)Zyom? zrEuwTUc$-t|00Btgq##UMc9eMW+2&KV=%9tLrk*`gyFTFZ}$L-KLH{z9{5 zZt%Kq_F_CF*0pJEO?=)dBhQMenPh6NQgd`to+}Z^L0&!WY|?m)>L$nevI73jI}(GeOx7qWf% zS4d0iMr1d1L>jNJk=1YQtcljpESoBK=)rLAdWSdyrFgT_x3M%+~l{g!4SY#){e`=@(8{^5j=XcnARnWT(k8{><(e%!rBJ_ zyK%~pKlIK^%OK$~P(g+wfmzxM`O%C`8@5PZSP+fQI<3;EONa-nmDtOdR2N__gETFV zm&Cxukd!#f?mu(NlGM2TK@N56IpriNld2?7@$qpt+I6zM!{BiP$cN^If7fHg94+@B zAr3@vZ@n&Oy>o}sAv)64_t$Le{hB?1H&merp`sM`|D@+D0oF062cFQVCo&z$%2W4RU89+%iz3?G=XZCYtrGeMir5Yr&4|(K6_n6d#wDo9cH1%<@G|?MaVKaYeWPx(&_XvlE@-a4{5{J~u)WRa)8_Y|=9dp1Vka{O_FL(8@>_F{NMrsU zwk>q4H4(jW1$VhPt%{$Ev*LpsxXN}-2^uy~S>*!jTpj}Ajy8xXZTKo>(1cp}FfZXv zUov!lkM2@=eHriP%+A}~eg);_`i)j~F54dAoSfRSTv-2fXy^&}o^b zpRL}mrqd4B=5C35uTP9v*;)jC=p4TNcfK9mH-C5rf4OIkOf=x`?j}j!U z6)Wy+ow5Tg-(i6)a2A{nDm5J!A2J&;hHJ(1Oz^iPhR0kE?NkQVWH(Lm87+s?V@O(6 zYc)1{eC7P4h-%+ZXHyiKba_mFfxG_+vm~=ta#nxg`b(bj9`K^@e3yLpe+-9SFwPbt!((3fq2$kU7t3(374Qwc7c{I-)f&5MyXvmF z9vd@AaEC4?J{~_m9WOrLJ{+e9Ri|~o(L;pvrAEsrrv^{PTg4e!VyxL^5PwPjO@h&f zZ_S2*-Slm_zKm4q5i%q^f$%XD`xx9CbaDYv!p*%pq1#RjiHmX8(IIP`4H(%yd}9mv_jya zl}eK|RWEP$YC{G21%WD+5y+uZt~IwK!8sbsSpGq~88h}PSH`to`F;Tn7;y#^v=pMKAZ3@jhCi{X#W3IJ}7cH+y zuG!tOs%;) z7EFo5`*TCxT;i#Q#KL6zUHcs*nxO=!ZEq%|O{@{nA*jB{OiVjr3$`bbnxAoe0~iBB zFYj5*_BS}uTG=i(^m?KeWd}A1n>b=NNk-lHLM=7&R`>YIB!d!Sipt1sJZeO<7rrrS z`bUfQlsXFvD%)f4ipa{ir7D~}MKWY-21gnS?CnF|lKJ$ispFL_nle9sl3CS+i|M1N z%Erwzrp45>NMT?BVQF&{`1@j(nQC+oT>e2Uu5h&YjrPcfMztoJMN9A%+qAUgB#&MV zAqB$C3CT+0vuIVs#TS0gW>fwjyul{}7?jumKc}IYTQ`tlcTNafaAxVeJJB24-8*GH z(gXF>^YN&}8k)Gh#0<&(Q*vEhLNq;mG8N0+9?|d*iA>eJ8Jj*@Rh4)S~r(k z#d%XV)Vf$kHQy*rvnLTx^K&*;rnc(!x)XSw!!*}8_v2jsb9(mCa<-~o(P?W`V{$v8 z{e9gPS`jbDn9#D$xB-p>2^vw?ASBI{3yp`eR!FS&;OMn)1G{#H{gs+S1ZO9la!7QP z@n#=!Hmk^Og7~avU{H}vxECcXU|N5jLl~qtQT`t!4rz>#x?6TA!|d?{yP}F(m)buYLdI5 z-lbf6P|mG+Ef1qEecJ+zre@H>;k)amKU_0pr_B;pny(A+68%`Z8?0z>-e}^kX6a`6 zgS^$E$-*O!+rab>3s3GTB;KCtu8bQ`Daoy4vAIwd7gMVJlM4^;9Iljedt(fR7cTBd zjgt!5_|(-#XNY|6qTNq3j!`v<=3YxiixvbSud z0__&^@)Gsl1!38#q=y7Yn0cP}APus1;4*pCDuslQ^C-ah2hXs8d*bkzJ6wN?l;GNa zNYfN_72)s>q3@u5Sc63Tf&>yEd11cELqGJk*VNld@+Nd!t9v478=+i%$V2n`J1VzL zh@IdCz$PJ1Wr2+eIlP>zT)UcZn-Vzt3vaFD5uRHC=@A}V0qOpI(o^hKcdnzE`G^G^ zy@oF$n26BHftW`$aO@Z|>E?eNRD?>^k@A>aeRGD#FvV!tFF!V=Ur=|CD!A{ugRk8( zb!%$sdt+`3-TjXa+1vu${I}|Cf9;^JEZgQ`Z;1kJ?MS?6ci_t*{@x5@B#A9+XM z+ubz1V%8amxmJA>E`2Hs-7z&l%SMF0a-5Ae9b|nIG`h|l*-P2A;iiGxb+@O}K^VTu zcSHBF4zR#0DDM@1Wj>sYsN+~S$Yz6ktei&F<9*`vz8cJIMR-KVE-0T|ZRrdkNm5Nx zs8ak23T*f2N$8s8HpE#Nx0VKJ-R8|cXxa8UDBzJ7Y2VYdeFz@pqq*R=@I1=2!8MLi z?dP5fVp`ALmV(tNJ(-sptMJr}q5e`iXoE^jQw~p}610V|MeMP4FaCo4>~7uezA$1x zLEu^b+y^_CYeD{bIQ&ZYhN9Ca22}`f3;OYnE%4yVJ-s$W@|H03l2SU@Jt+MqMm=CG zc-n2iq=VYdK=^R$aU)9*ew5I%6(T;?ZNf8(EaRgG{cy$ZPP`H3Y#`gV_veoBWU73= zw2-S*7CrtVk&{H$1Nn~%-APo5X1dXes!AXNqH-!>pBc&?y{_;KY56QgwLmjQOvjAm z1qj$Dul#n@YU_!0?YZ?E{$KJ%anmGC5Axf$IfVZyU;Y)d#rQY6YyWA8{gr6>hki*? z(zZo0M)4`;nqSdITdCf#FwX<HEG1r1rZuc*mDK|ZkqUq; zt|V=ukYIhlPGF&Q848<8H=nWJKy=(_crUr;^GI2SWDdP1(;m5xIF2@SKVRH2`QgXR z_wDJUNMQ=iaFKRp2;iU@$OjM!Bn4r@_6xB129Q7IFoqZiq9dNfv21q&?c~N_#6BmG zt`%?%Ib}~URAZ~uyR13)l6C8O9+ggFfsMs`Ux22oz>2XWGp0I<-k79m0pb+$&@-_R(J%(E93;;b=DdK-oM{XA^qf1Q^LKXO!kNEZ?eSA zsgc$ENaZ-EkH>x(12sfKdM7UhXL6Adc&t6jp-Xo(aUY^g?zBjPj8JAuJ)wFj*1Rqs z1etH_VH@uaJYe^PyaYys)N)2rPEw0U5)92VQAY)%z)VXdFixI^@On#{AV6HSRH3I# z_$`}O;w<_Mhp!oEoc%{5#h*Sbvrw$lz1s@6Ndy|UBF}j`9eompbB1g{7~GnkaXD}j zvjN&N0zorqnRLK~z(v0~x|xYRiV0JCw=(o>{#q9N(tt9+aocY`RlfH2Gqy1IvU?7G zRlu70il&~^tTovd9Bbe?kLz2y+V z&~AZSkNcJI7+tTg)Ye~zLyJyrOtYi9$?BJr!$`|+9P7msFdOa`%!0Qnaa*ng8$Q0- zFFy|_NZQ9yEWXTuHnz195YUe*`0B^?QKaCG-~D#cNhKwBgOjitxHT*8j7uqlqmdt6 zFk=fxl-$5Op^4kXIA);p6oYs8YsQVCZG zM0T|NwV!UcytT!GwmLnc;xNCw?@v+D=!>_$_h3=VZhKLm(1LN)$4hdhy=;{cY>6)2 z{{8UDt2heMW1eU<+R2M}4KWE(mgF7T?P!M&^j?tX%+1`6pS!nBpx+C5ZWX8#q8Sgm z`>wIWe0WOyXt`4jNfLg}IxVv$e5}vdggv(u#~>ahPJzfJ4{e`&^gVF9ii(~ zl^v)fd)T7_=@F1ci=aEm?Nj>oWt}fq3-t<*6mRq{jA?tCX?$AhQPKZ6NN%iRkBGba zsUm+PFQFfo6iHp^Mwxs*N07x$0lIEL7cjLGQRXmJp^O2v^~ zM9aQqNr%7gIKTS`_YqYd-A?2`f5X0TAz|MV&bL%AJrEn=6%^WE@2jpp@UDvM1RO6` zA4op#3YfDJE^TIScs-YIw3!8?XjkmnyrJ2gfH3odZAhv0q*y&u>11bgeA|ls&@9~1 zJUg%h=Xj!6MYAzPnX12uUeF{LXf7jUP~5&!`eY-@dPSH8)`#4 zqTVD@U_4%f*g# zK3yL|0UEb_bo1P^L% z_QnMRU9Xjy=6PIqoZ{KC{rU2`cKPj0l*9KNBbFY+7XoDWn*}};#5;SS(KjIsxNZ7q z&>sfE9q(f2nfQ43dti|cvAcTGI9Il>mYgd^p!CtqWHO-Fl%&rtl4qZ-q@%9$I5>NH z!2wI`Zra@RcZ*`(XD_v?XP@=OVrQQ$^%Ylp@Rt(ov^%g+WEgM3ItxU(8;_ zrNhScOuXrpAb)M@Vd!+GW-^_*@Ol>l-V@r8%dk6!r-rw;%%Prm7(o?RNL1Rkh?Xtt z^eLd=i(|m445=Yg;c+Za1ydlvL;=4B<(G%K#`s~_F9zeIhPOx+#%G@-a&||PH2tmg z6d4Y!Z3R_eA#{hA4#W6wLWQNec0=ci0^=Fz_bY|k_H@^xhWq60Ju};!ybPv{pp(0O zdfsH$Nc^odoYZQoCryX z0h9&E<)A`CIMSG0PluH-&>M_5nTp%FBYu;;+*70Eetor%KM%t4;)Y4H$s+bn&eVC1 z=!q8;S!sNP#c%RJ-HUu@n@sa(RpL1 z8gKWsPgY~^Tg1!&dYFf@HqhxCUa#gAj;`OM3v+`TZm$_=-|thiPO$4I8Sz<4tPbTT z?>kL_?IuED1g$p|AQ4DpP0c9l078VE5Vt^O-bP1E0+zPO+H%NoGpFA^!7d_@G&=nz zNvG!F8p4egW=+Y6>Vg4S`S(;yyV{_hh=j{xco$+IIs!!CwWtBhQgo=D%IrY}BL*no ziVNe0EyA|r!>K)lq$jN)&$M=Y*GLa7m$S-jvJ-=Dh1|4@CpVqaE#fHf0$AUUNyTSx zm}jY){PGt|e4=L9mIvfT#-E9dys{8_nSz}YoAhr?u92B%=k%59I8;O`oCDyngoIr< z`T|FUZDpU5uQbI{=OZx~n$>A-LZT>}>>`mhX$-6@a1mAx1=%<#2wKNNA6Foo6jz5V z2%&yTUt@>m?vm*fim=a_9H5M<_y@KY{!q=V=R_%UDY=gQ7=>JI9c7?Oxe~kT*gZPb z$P^~SMU$ZL*|n*Iq1vfevq}>5{vHgL<6=Ui}PFzed6AKpni3NqV z3Sll7(>K5jdjxL=s_XZ)^65oFyCRv|gQMMb?TBh`8PK?b^Mt$ng{S3`zzzQ~-5=qd zD2l&XV<>ej2Cwfk7n@rn>E-&T#Pvi@rpD6)OjkavYyl;4|Fvo$LjxAz4~{m?ms$h|CWhk9U%Y*B!D7(%4Aae z%LSO#M|hoIO;X&dvg?7#ka2^?I<#J$-B&0KugOB8OzF30C%)V_z#XFzW?Nv_yk{o> z@X9YPy7x}#qWKe6G^Iomsz0iwpt*ZoG7CIRUvW$Z(h=Vwxjt2J#m%y_y*8;W)&5EG z4V@GQE0fBeqXyns3jmxKB$|k@DxMxFdxtjnA6}R>cYs#hmkw|KI{*89vuD%cWni+FD!N+Bni#>pPh-(f!j46S8%1Ft*Zn`cI7Izr6;XDpCNP zzq~Q-HvQwkKu9PP`2vL_KbX|m)GHVmghVmMFbw}>Rv8E^kG8U60zLKQWGk)qrb>f= zh|)UBz`jEH<`3ZUBUXXJ&;2N-xnK|*Dl3!cY2o-K~8_o?%XoR2pfTz(Ky1NPvh zF*_i1W#&NyQAZdWGi3$k@b3*}W-)o7Df=@7JXsDSW5y{BZR0ZmrT>gkJ@s%Wz+XVOfL;K(y5sJlSkU7qzOy!VN95Eu0!iyCO!8z zZPuN((Fed{)1r0>{1Yo)BPiLYFTjnSM61b$e{@Jq|G0EtcrJ1iB$|xZy{Y(l84$k` z=fx~{*dB}$B(I%BrvV>$3*)6u#-wjLdoL81p`h zHC@;e<1)gUybb4JUSxv0!t9Egs^!!CD3w~cACk5p^Z{D`v-Q)t`Px zgdHFC(zlQ*q0MO3rJUm#e z>>&x*VS7O#Tt=*Ng`!;9+b_ z=+MZO3{>LTlht~6Q|uTd&UTzFO>)JtT@*g>VSZ|1vpT~k_p(?d2uEjonGFuAb#yV< zVbhiuFa;kOU#c?Y&{dW|&?$^&CGrWQIFI| zXuiU6)d{9NB`7)a>xuUg*6ZX4&+FlgLVs>eOg6$KaX_QnG5%$_pA8x>9LEh1$?kTD z8JLvFJ^`LKD`%vPQ0_lUlq_Ow3oIz}l&4DSZx#8PrMnL?N|zNcmMqs;(ZhmDrTjF} z2w{w_H{u-jumME5AL{67-#ZF+_I@+;bjVgV z|02{#w~i#|2+-uD<+%>lYH1WD)#*p{BgvE;-m-~3b(_SB4koCxz$%VhH%KMtqYGyL zNZl;|mAlP2Oy{ndtbUH0eW6nHc;5T%v0RMT)~(yIH%>GMA%_qXb9=GZUE4g39nmcW0-KK=hfmHroaW7_s>_~(lW z-nn^StPU|mLrgJ~Y=Bd{mx`tM;|&s)eZW4Cdd-6>1V?OX_P!lY*4w*DpScO z<$X_4{)jSsmAtLEa!lqklZW|J*EOqJTyA57?bfTw;bgO|sL$PWO*hcU&aW_mj!C=B z9ngLW5IX(v9h5IrDHDt-W-;beknQ}_b*?_x6H{*7-%s;AQvgD?}7H-5dZ0q=*bSPca%}El?79;(}=$85tfdpR6PJ zNDe9x0D%rlI6qlVMbCc3vi_X(62IoLrCzRJY*wwF2Z!?~z)3#xXQZT&Wy)!*sgr+lRW#tTqA0TuD#)F33&(VX;i@vD+(o#@tEP3X zyoCwxk?*OpX5wh7+;B%Z)3l{W-YB)v4v_-dQCx$ZA;XlMsbky@io);i6W(|CrDoJL zdDUmU?5RVXUk>$TxNZOiupsYLSF;X11$Z{2%*igSL9e*G#xvcqN7KQ3Jlk&O0NToYb zL~NsiYz%iU!T2VZmUeeD>XdpoSc@P5jUE|qA@)7uucuTv*SOubV9M$}Dlh*UdyuWZ zULK{HqCb~**N{28bkr5{mv_6X-|rdV%Bb{q<#1HuE(g9+I?(fY-7|O+;p`Fk46@P% z?-z5r?(wt|m|J@Osj}@2ab#!(a5meJ3;{1Kfz6?53zO8}2X+_cF`|+7xV)vkSM~va zt*GZ@C^G%NrhRa~?9~5OI4l36aQ@D;&p))?zpSOTqqk)H=utv`4)*E^i46X^HzJWLq4Id zkj!fIM8uCq@UwXsdd&9e=brS-^3f=JF*{GW($1=Elcy7h{1VtY5i4MNfcA^kG;~l* z->~%5&BS&tHT3IAODj|5s7r@}$x5$iD{rcXNiL=Zgg4t5yj9+-y}(AKKL8330b9mSWc&^DT2 zV~ADh-wXJwhU0EJ)q_(3+2J}w6R3&?S{0~EkZJDS6i^_r2crke+9|!B2AzZH$gnx4 zm0|oRAJL2jVaPWU^el*B7JvpKOoYm|qfxysl0NxggGo+>Lk}R1g~2y&u;{!FMw%Ic zq-y32q;%z4QNjZk9^X096t(`49QGz5JyACSpi8cEK7FFT9a z2@%mt90ZHBEiWC;3|@3Ad-KjO)WJ37{GjD`IXHG5 zRcC4YW1v81L(|Rqi=?XME-o;n{%S%jqbgNB=gAZfds>yo15(6gJ;I;Njl`*tai2m% zA{bOG33{3x>t(9br6Ob!-y_AkodJ|+qJBH8a&C#IgX@~XPj=kF{_H9nNG~>B*!|`QjN=Cl=G6mBN{JPu3-eF|%3_>8=5|Q7+?ohaxub9U%d9SAJ+>@c4 zafZ%h*Hk5&`MZfc?`fm0`rmR*Z30=+Jhyfl@K!`?E~1q#wvUH}+3-JFb0$=!cP(M& z*~slRi*4JDqU+m_uDIKOcZ1_WMcGcJb>6p#9q0PNs~NJoP0&?RMii0A=6MVtx-!d6T|y(R z8LlUwL=Ks+R@}oMXGsBGX3%KRM}w6OH;)Kj!eqora-0DF;fJrc8&Q)E=|=F|^s`r2 z;gO@rO#(8kaCGza%-f`jE%hgFFOm!1rJjVpJHWz(v?KyVj!?n6k{hYD=$(Q|#bkt{{Iy^hV%E)?k*DHTRO- zNiG{d%|oUyxEZ$N?+^ftpMS44_?AWRj@4`dhwCk-;o5%o$xN=xSc8mh`i_YgOMN;A znCj*Cx=Bv=fII@z)giC4T9XzjugQE_=A+|vjh$+W#gIwgW_>hF6FFk-Cg)*i*a%PM zRa7CeDL&mhQEpGk>%0zi`m_9oAY;tFrn)`lP;tu+Rkac6UzPr%*l1bt71+%(*Ni-5 z;W*3tYux@OTBhP(+f6RdM$y=_Y7|o*b*UGob=g;NBK;t8$|1xUR0B0dOo|{y#F{D9 z=Hk;=UIdVgc^{~nJ;7`dDO~h_ipZQ1T%oeGmny$L za1X+fqliJ7!8l`-Y!cHFiTp$Xh!aLZGb>Xuw}h(js|cbcBq1Co zB*khWF1wJ=6gB2JlpvHg;gSo6NekTb_`~8OsJwnC&WCG+I}W&pEEqw((%xU}AUP;X zn1Wr3OOP3urATs;bjSRGTh-qA8J)YHL)^4_;}?HhVi5c9mw+yXG0;!MqJJlElY&PK?+j+Hn&K21mjYb&`X5^p zsc=BVZGWW^s=oSA|NRR6*B%t}-*~A0p;P{PTS{2l{nIrqQZskLRz>ZSOQzPu;`01q zEt%d_M$)ciK1V%B&|9~wG!!kf-!f3tBkq$-nkAAo*f>wRv8Da zq75^Z;1yq@Z4VoFne~NhUSc= z1;&$ZXtyCk#U!rUlJ&UJNS2_T*RSZV!{m;s5Ia&_5N$(+m7_!r#>1F<8cef>!F4w_ z6o-6MnF%oNjJG`gA(%3CbcX$`HOq?H*{3H|91C0N9AdAXG3G4o3%ttBta`}eml3GT zAdVy`(2PmU7$k_MO02Z!Vzawc_PZr5FomAOY&KK?4JmDBhnjSb6N~cZm*I`?d-YIh z&za4g_B}IfBzCwlrZ{=_D6)#y9^-63PLkP2?U`D#pir1JZ_eOO>Y?7SB4v6cridln zSh@IDy3lgxi?)0dtbcO`R-?kj6|(&z$tlRMw=4O3+f28%)PcqGUOwX|iV$-V3Zy zs2;@y43%u0tEE1zJI?DVQ*0iNkUkjBGqFnq2sJ>9IRc1d3bf}l*^eXMWtRl7I0*HX z53q2_doTG3m6`Gog|ahbK7V8mA>hdWK~ zVqc0EBB?}npru_Al#MCyPAC&uvaN9w>8CB`VaK>QP};EJPvnBFwWiqUy2t zm81n9FLrzHN)PGdM=$=48D?K)6<5}0D`?6Y2rf=%cCS!GyTg9>Wzj9LlRj}doG3tRfwEUFhu`J-kP%Iwlc z##1kCH+vB!fJr3q}MC5cPH zGF_>XLK%q3U|vW;QK!}wrGBkCVhRqv6Z19j)Xnvf<>YoS>K3BSsDf{mn*XC7O|~EP zm{czM%eNeeH(bO3wtfxHKg(Uf!&hDWt;n7bd9a$_Dm>AB@4LR$?Lp5x;0)v-YAh9; z4WarTvBQy80z;oyD zg1be~&%wXi@dzB%$`OTani708z%S8)^I>c!UFmI7=012@!a)|hjpl92GGHT%azS0p zaW;ey;6u@$-laL`kAvIue#IVq;CJwK((#U?Mv`1oka9ClW4#CiJw$VLE~;-70Hqw{ zhXDB=m5E{eA-;|n?>Eqo+pA`)Dxu*Ogpa+rCvRRK{3-BjF`}$FOqa3Ni6F5?$@_!@Aa)( zRr|-ctL9pBjycvCeLs!nWhFwh@Ajdy0uXYpQB!;ECFSsn7~U(9WI3US1|6xm&jEaJZ5hGie@ z42ss`!9fXIk~Ldzt|w9mT_&Qg5>h`E32{Ecs21-*8*db>b{qU1=d^~eO1l%?Y%OOs zu)-#KA@TP~8F>XW`4^w1cAb+GpHgUZewLYG(-dX&la?gdzDAf|!k|91hkk^7=;io6 z^DtT)-4%3|gE#{Y+<0T%O?HIQ^o2OBENlBU1u22mqBXMxj2#+vxPMzwCKA{~s(CT% zvpM;tjzm%pgGFI!vxaWDiEI63419S#``5s`oz0w4>7WYv+5;%FB3vhn4O)eHF-yH$ zxBhgRAQAXFxI^(HI!~l4w1nl?*bvLbC%e+@-_cvaMw}C2Zr;Mi+g9 zAzjx4d6Wp%W8cP*IF&Jo>m@1n?Se1vETpu7D*S-?`O*24>>ch%#DMhK`bkGAbW(`2 z9@KecgM|1Nh-Q3C+zV1G8uWv~3v~2WOjp^Vj#b%lXhlT*xs2dE_GQ@rH|R+mfL^@T zHcPVsp~)Uh!yHC^4c!2Max;evll$-?;*@(gGg>e$2eXsgKOYKcOmneS-xO);c=ha5 zTLw%x*{k3L!An`I5mxE+ywE-4dhywV5?E-?^1R#^sh+6w-Cesw_)`UN*N;q6U+YwYyX$8RL*VGs4N$Y zG?a|wpxC#CBi?3z61j{P@&cC&3Y0lCD5cSFLZx^A3kg&W9h30@-itUy9C~mg zV5*=s8f~_Kkbq5?j{My%_>S(n#U3pUC3zg^!pdw{`n%2fmfbCwscHVI+#J64FA5C1 z`*PABAkZXk(8l7B)Xnx_q^X0hnAMb|4UL=7BbKE|lv(8=m-s?No_h%Bg67cnU$+-Mpbb5fUkgxI8#b?BlrhM||D_BXbbeOn)3e>;6k^Xkj$ zhwOcS2_V0U0O4sV+wYuTxSaQUQu4;a{T}DNdHR4QzisKO=*#Hi#;P(R56r}z-Ak#9 z=nLtynWCKfymmmN`%t@z)}%jseH7nOsB1v`G)A$WW|6VzaH8Q^E0MnrDQ6FX=$Um8 zO6N;D9YoeW#GANDlliXDN8B-Hw zZnw`jPPYiTU6KDb*edbpaV|T3LWU>iu%CLIE6=8{-7n{t1`qY}(Bt=WoVH8MRx9!T z;ehQ5x#&}REI+KnpZf`RN z-om@cynP!eM1M-QT@MnXm~&YSKN(}@k&<~7ak*YIj7I;bcuPS-;%hPR*xEvgzMGZ( zF^%g|R*nt-lPBv1ngaOB@$c_0c>?<{{vl$%0c<`|v|NU}pFKm~&bL@Szu!>|^l_RC9|12^hr4S0A{i63I?JSn1-is^&(|jmgh>1Y&5$Em;r8X;!vI zfYYZZD&Ik4Nrqo1DHAv^46(@?SSo4GICq}^i3d;_r{}YO;{pG*botkq{C953iyK%w z+u16aIJlVD8kzhH)S9iVrKF^W`Uy|U2|(0`h!zFe2O|Szc%&=HgET~i1RD~yJ}1Hj zh$jTL=XsZ1Dr;?iUon@WU);bd$#yMy43KrHL%`!+?43WgJJGsqbt7irYLQLk+|~Sj z*}bZ}+q%lx`}J{8?1xuJRfjD`>WmXq2o8J_Kd1{bI#+to=8q|hIp?4#)(Zpz;^;Xi zfGflm;CNHvZvZP{Crpl&Y%e*Q7PH8uySRsi9Rv3eV@`<^YcVJHH1Zk~>!{9XQCclM z6Tz>IW@K6s14n5x9BP>^t(4PJ0hde)Nvz%JllC={II}+nZKJlgOxc^mdkTX z`cL*$m`lCBNrGx_a(#p8&bX^NgC{*j^*RrX39%gq+e|Ob5G{;}IK67dV*K8IlnW=n zDOtOU>K4z=U~uB!q;I=dZe|M|^38iM%vHLZ`j;sQ2h5wJ1P$iuvz0-{&y4a&wqJ0L z%zrP+22q#vyTnGZ;Cg;i^N$T04j26~XkYuykWMu|{3DV@G)s`p0`CN3b)*nZB@O ze?r#qz;hW5#68-6_@Ky?ZafhB*g&V6F;s-`2wBk&4)wckH59$ca_x!#T01ZBb zDOyf@&&G1?UT-`k`KRtjgz}qSz@GFL)2Rh*Mg_(|__uVG~(fup1APEMohg|#PO zMsP<~1mYy8VDRYCLBcUa!x#=581QLU?l#7DM=xfS-o_rCmu}=iyMnteRZ(DGkH|eX$)s7t7lFnZ;s~_FdD#B_$tlIDH zPy@SV-fbS;i9Olz3y8hY52YPKt>~R@tNIB5)!rj0Qs#1tQ|0@E7pViGHWEQjuc$pV zLd+(%zQm^90ppVO#;|sS2 zp?+f+N?9LlMO+Cemaqd7MBJa%9>2u2K}dVXb!?pj9KgR3f{l_i_rtESG0C(pB90ka~y zy`SLck*2Od&A%U0IvTkHYW#e>$vL$%#9hF3CO40B-#x3PGkqPI6Z8#NIW6bz4iX?C zc1-htPG&A@TK5)*RsS9k%{~9)8B;+>$rMJ)WVvGA{(> zazoJP?sgRI_<2a3R1tsAjd?GB=!D8!1WJ{3xcKv&?xKW}?j@NjA`nLVpad=<~!a|cj5$|ESc3TSeWu{S6#^${m%R^ey` zIp$&DhQ(`=58v0=k(BkK7evtWzaAomhBO_L+9V&4)FLq%3HOIs4TIWLNyB~_ zAg@A2w&_YE2^of{Q!EU5I>fjA>JqZPIiQ*r<>xC{KOBY2nD+4!Y#ff2v%vm%&N8he zV7F*_VU$}u97VX@oQr7EDUvy}ReW+MwW>ANDOZ0(J+~azRI9Q=v&uEpDOP_&JJ%fU z(5Q0 z5lr_(+~g0943Fc)96UR0oqxCks~aQ{N-&_NVfVaryJTdX&3IUDRvGy3c*R3U$+fsd zw5pVu@}G&5w|b6-;CY;><{SFNmQ7m@4L6u;fwUHkQsN{@v|6Cr3! zPauGT5`%`fy#;cRK5)k}Jpc2LxR0AG$@+fHvG4DHV1@sB;QqUmg@4+Z|L-hV%K9Jf zst3KJxluBqXB%>S)qRt2EdtxrTp47Q z`TBE(+fSUK3UaAKcC=(Ztax3!n|Z_|Z(C^)hFVai%*I%p-)nQf_g-gjMm!NgpLU=GCrB zEXL=un3`&gNhi<=c94NIhzY5q4{&=BO9#S8(15w}$Y0`tE`A^ikidf!ueK3H zjqMsjdyLB-&qasyYVuo0#Oi*ZgtW6x@@_eJn=5+@1P1@rGs`^5I_x~P#>#wQMbd3m zW2raq<(Y-AT&K{rK$7TwXMXDw7*6zcOC$bvK6jINWi_`;sjGA8_Kc@X>eYgB%GQQ_ zWwwe-ZB0ufpU!d@?ZBQaH}2Z>s|zdc)(0ZrHUYl5FL3GAEVwfQ`|oCwhj|d2?bR9Z zFAI&Q>an-Symx$W#+evbHA50TN7^zx9J(tnSHvygV>ERmzw@m2W6alk@jbAfzi^^2 z$hyOm?kKf;I+*SR9$rDff8~c-wO{brZ%8DcvCw^nt(cw>I^yv`eKF+5h!k#N_Kn$g z?ojN)Zh~U~5Yh>pWxW77-=IZasVCI*$X4Gdmh?>a?oinD&}{1i)b!MkE#VYt6E(0b z^85N$l^CBOpA1Dv^i$vTGc(WoxwB>PPU$ zR(FA9_dSqj%AqP8qPSOMUDp}h*{pW=r{mgd{vWV6q(QNr=U!Vd^&z%?5J33I8Ll-G zJ9L0$QufhsN@1>4i3~H1nn_X=*H0cs!Pz^S^+{+GWh!(d70tpDsY=I>6tbP4)fc}9 zGA}c*lQ9@mQRHp{GG!cd1WE2vvQ&iAY= zM4=bZkon>+pO-wPlFO|gO&MDJfhb0(uB+NybNvYUU0P0~Er^vjI;`fPBJU>#ia61M zQ@;M1r&;XQaUKH%aIwL|zhThJQ1(%_-POVv;pIls6AnUOAz?w{Sc1AqV|c%wMlqzw zp$X!Xg)gCCY7Ux?Q1ocJWvyHxEL`#9CXs!b z(DxYD*&+DKW5^>Idi&6)Tu`e`<QqEO#L3t@Zrtdx-xiizFjIojo&I|lvf(i;VCx!}; zAotg&lYn$IcTevk1#t@EjLQS7)~8*;5gDpnl0>+@BE<~8YSD7Da%A-&1>^{_1|>?|FM4wflPcv-qP9SB|<4&&G8v(iI;S>;B@T z&kM|KPa14WJ#WrAKS~68Z9XM*Sbe}s7GE1$H>lD2($xi$gY zG`?2T_qf)dn9ZbH=to~32iLVVEYuo+Qy&^C!=s%Un&|*TZ~eyr$5(gMulCre8`@SZ zIg}6VZ=PJg&yu@~z{oE!*MqnyAKm)#HldMhCU8XP0?naXaL*?3B?5RG>s#VI&!G1a zdrE92p?Z8)#8sN>W;i~N@sm(^P$yxyM-m!4I5F_bC4*)5B9)hcenOjC=!*J$G?gwQ z+^P*ie5>X-bOj@TI9>qmvKP*f#W|Jl7=c!_{$0`&;?#(JZwN!w3z7}xg1DYX2`B3@0+BYa3{>~!v<%5%lbn0O!bi{FOlO}skwVf-v%dk;-X ztyl7Hl`252Eb7TwO-FU z{Lp{d%W*CtK0&;Kt#y&k!;vsX7ZKao2*_vreQp9^o+g?alV_C))VXVFPC!MHA@=y^ zYwiyYzBk>*tS~s4+*ax7$)1fuCiXLzX1f#EU!-ex4A$Skyfs z4L`<*aS7gge`3a4Zd50T7>bV&LdBP#EqL9Ar4YM@o192QkW55=u8FJsZlk`!sX%}Y zId!5mx0hRBL@1vp@_aU$DrdFu50ZdGtn#Xs}F!m$Jm7oA5QqTw{7+7&3JoZ$bxt z^?yb|F>K=&K#GsslWvv%eE}(=4Ft>H6HT`EvmVD@dJT>Wp1}@%*Xi816ke3DGp#u2 zFN*dIUwZe6o)0GP0h7ZK`t-La9SeByY^{Sfh0L{pdI7#I^JV`vNL!TJ4`o$)-B!~l zON$&e8Z?#|LAg7zzbOIwEc9XBgDeM`(HXRdlyZiS7yAOD5)BX#xQBWxZv2_EJKq|3 zG)||p?v~geGK`Ka;jj|85{4cPVF*h^TbJZr&K=CSQC62QCJ~6f<#6W$T8x;NW@GL!2es6d#t16+9^uxJpWI+IJjah# z;;Qj*y-Y|W)Lp}=LV9$}Q&_PNMkWE0k@2?4U-Mj4MpM7o+A14zd_n-V8SuRW-v;*E0Q*WwhiUy4|5oPGToYLY#wBjt8&IDapxC|a2XMW^ z_D)=LgDYB{^E2wyN%vNe>;B(J=yLQH^1%#n$eSmboY6r`0!pOFF$_mqroML+|(|J_N3PSUe&2e;x!%4&$ZkV(X|N6{jBv!-o=~4(2T~ zMLcaMg6=T~&=!;8#l_Q)2`DIXc3!TQ3Kv(Ra<&&{RpqW}jt5}4#@ZP_^eG_G+K4Tl|ygw^BH zBi1Z?_WCHWd~Cgo`fGE6UnAY8{N)Um{3+Ic^&a-oAE@Czt9WhrQ`}-<<+|)S;cDd` z^U~kk5ceGVx$Wsd_`vbSF#`G&BD6U|N;&wtX%5;z^!nBC%tJO2srcwmjapEt(lN+ouDl3XM-yhB|!1@7gSPHWe^zm`Eq&6TzYE|bJm26>F{ z=fDX5iNx+kD!DkAbjZ#N=Q?DB2O@l?f7Tz_Xc8#fZ79C}O?o0n3L_R*R#p~#Vpl>| zZU=8{VQa3v)D_#w>>PW>BviIRl|3aZ2VS4n@qkFKta)H_ZrIfJjftV1H(S149autOwk zNcNX|KO4JQM+Q^)CA&AUUHmogqOY)XaA?o5QF?rN>IE$i<(BOp(wp0;FSih~6B-?H zwX^#z=4K~^GW}qCagmi)Om2ki)KE!NqS(&roeAS)d0Qy{1}*?f)Fz)!l!SEU*}fN>tU>s*EIOeqm>8VP|2R#bCjgQEPfZ30mt$Y;)PQ zJDaUZh;O;2UaPFO^>kyTgxpSzo|?&}r_w|UC4hp$C4ijnei$#gP5fX-trrDJrW+S8 z0s)p`#Bz2e1*Su_>2+X`1b56NATCHVp}PLaM?-s$=Ay#x+}Z~D5T}dPwW)=TwWLmE zt*5@)A6QDv$LA(^daSDHMk!!koReh;e~nvz?Mb*|3PbVaP_(Hh1)rLweyl1%w3 zCRfINFR~w49Y#waDEokne!%+8&ov0hHz4yX(^rK~`W=L@V?j-B$kzF1tXIndkD}wL z2!%dqDtIz{>Dfq-)VkHO_BwsOx$VqgS32^rZZK;#haPxry^Jv8U)vI$q$2^7Cq>aK@Y5cs5hMLwFJN_3 zSRm(=V`fyy`c^m)Z$}F98^`LvN0+s0meW$(M@n%N{^c9{O>NVqv4fhe>lPZnLM^Lp zt$=ZZ?eG6Gj@2e_I|7@g<^E`eFETd;hIVft1PX3;EOy^^?hBxpiBVlhvXBLi$YFM` zB(wbygA%Mqm?PUq^9(%|nkWxH+vn(xui6hY2V0tlqw9aZrxG@Rr3kn$s_I34wjJ!gGQTR!gD!OsNUrSpzj zM^9y#=Gso4K)rOu?)iQxoN#J)?AaPI5ri=D_oBk^QPQTDohkc$E z)TfH-ux0zLC+OHxtCME_bXvoh&!079^EmuHrjvr2;(UihO}#Ts{qt9eK`tQhOyc7= zEMI;OOIuqKEc%{H!2$On(U&;iz0OVFlL1y25bF*3OFx1>-aBGV2tj}3w{&3s?gM>luKSzRbb0Da{5}u7kV?qEN;%#>+NUB8?s%8Qo zSWg)1+O-X8s$iE5tEuE>w$@AM=56I_4z$t_j-(D7SrZYLoJnnc9ET%38vlil)}=HA zN@HKU&MC4wec$MH6S{2`BbRg?)oSH=(u>X2| z{OgCTd+hUXf|?>T5-)*-XT%!+*gT9+P;YxxaU-1eGbYE^(y_ApvAvYO)Uh^e(&XVA zlZD=F8e<}?H-mjP1h#%Pi)G=s%{_~Rkn}yY1e^0_!{}4St?1~x&`+!oAfBuB?cIUiX=&*wSK(#&Wjl;H!DIzyb_FWf{x^fK%zPN$+)EM2Mpk+0n zr_8#K-2l-37};aJ*>fK7fTfaL(A@J{QXLJ<Y2H7g`**<|QIBekanBO= zCc)lSpxT&FK9zn(6`^zNE@1uiUoBy{YrS#fDxn1po@7h_Sn}%3;smoowNWkdi-P4u z9NL1&A$e&%#S%NN4F*gSPlScKL|H@m%9*VRe)=~Y1}Tx(Cn&8@)O(8N69Gl1i#wq~ zjlz|_(=nzxOH%Vr-|%L9m0Ek=m7J9S1e#8FeAk8N_4bX(`Q*&ZSt&WQ&;izD0`$57 zd3us$4z1uIcX9z$rz5|az=wBRh+ja243W>h!!QP=!!{Q)E#>&dNQdmq_Rk@}h4_$S z3O=hDf-tY2u&lL_1K}{O#Z7UpJ=gb-^g^*Ae)8hn>XZ+;QRo|i-!4qy4)rGI!v(dD zr!g$1c`8O(C;`_@gYv&+jRf5!T9Y?%CZEtktz|$hCkCE;F@$~2{v>};0#RcAWgy)W z(cq{A++reFE9Gy?oVQ7dM4JCSWXU>MVQ3@p`2);64VvQ!*DW5!HD2P!N!3LS(uEqu z10Ec<6=q;p7ZvI0({+O{3-fY*%4z+S)5zEHMhFyC@)jeq!}U_ee~e6t>a0={(0P?y zxA4H!ZZw{OV2&O~G26{1OTEtGl)|UkOizHWDAxxnN2yw1WzgDygek&rlkPx2E1I68 zvkA0WaG9gG3B^l5C{X0TNM&gg!e(+LuQ!K02_woQ>F|5LJigH*y}*-)>dnitC=Rhk zdS|bmP#SuI@2aFeaoFZunaaLD40-@RQY;@EE>ACJUln%^bb1U(UJ2Qt*1$B{t1Vi` zOVl}_XseF1{Sny&v9%Db%)bRHRh((i?hI3v1YZRDzzWW7Rpu<)v4;IjfHaq?bo5U4 zUR&c4(?DmS(OclSOZsqCpg~6vl9CmW4Ow|S!+e6kkbPgWK#-M}8*{S@GL3eBL{6w} zl`bV&+niBhQp)qh(YB>pdcoF7E9uI@QB+9=fiN>^AwB-qh^^Tx$`HIv36*to>jdu+~ zoWC5;<@;?TeT7rLW0J0(2PRqm{Dvp7_r%~3+RyNrM-dI>(M{2G$2a{MubFQwU_qK@ zP3KY7v!KLa9WZ_l8ypz=z(Tn&o}`~(hL|C?y~Kwk&Bt`5dnP;tJa(+<1nX)7#wnSA zE!FNY&TgyCHz9}xG$Fgr9@b#z18d^TLRm?nz}T=~^lck~894Tfm3nVAU;I@T+Itw> z+c$t8=afN0&u2KH*a#6XP<;bU33+aF=tNF2K(ptU0iR3m6IpsGpeG5q05;tAvscEs z0|%7g2N)W?{{!|IX)H&tELS=ub+KMN)MrLV&u$5#Zr(xSvs_+?zDfO26=vvmCfu*6 z0XPdc4GC~QKjhOvR6kjeykWvRIgAU%f{6!g8q&7klzcIyA_Ix13rFb^`@=d}jw6p$yQA5T|GY|Jwtq{l1M<->lqET(4~Z;VT)iS7E$ zq2@yu_(`JrgF^}a(zT)b8Qq11Br^0zvqN|;_-3$KyGI1$Ih%W&bgs!cUE?Xo>1q9U z?#J_AK8jke=cS)NDsR3o&DHIOCv)WOTVmAoH`A%#f=Tqu_@C==gb|^IYTK8r*~-_; z#^@#0;^=s79}XCJNeri|Y*p=}V>sTTLD;$gDxWhVHkG%o27tE!172P_Jw5sRnebbu zf=D5M&b1s@?WAPf#!W0=V_-Pjw1#;dV}I*#1R%A0<$Cif`qFt}JXK<<-1F@yo(8jF8ME9Y5N$b}MWU*D5)S%Y9;2vpZjLk`ftUl1RaJs8yZ20Vc<6u=?$FHp) zTJ=^n=37{4c~fIKX}UhUz3>|N7R??=4GG5gumWo~wia7h4U#=(_mt29nK7{F3-9Nf z2jPGgjEfHx4MzzK6lwhSWOJP41xDwruZ0s44Clhu+Na%~$|u5R0d3F}L@K1^tlJKA zd1(!WYjrE1Vo57egPU zJNSF}=Q6%g#Ps6CHM}p4?NpL7@<)DKADEdc;=NeFJWwos2QT(tEH$!d@xHdTFib{Y zV(dcj$fR5Ybz_Ef{XW>Q9~e5P-D635``O7dBgD)Xu@u;)gPdX^6`bgJ;?J#KJ!terA%|U(esz-JSiNFnjAt} z&~Q5Q*`lOPvvEZB!HZa=h=TEX{YlgblzHH$yAxq+DuAV4K`!EZ( zw&H*PVl$GgS=7XhO142APK>e0`dc%HQVuU6*S3xdC$EiDh!+x%tfTeOgk; ziZ?ls*iBeig-eGS*%0zTxgeV-PGZQ60E;?_1Gn3|QYK6FvQ~}a!&%7_$$P`6*~*b` z{N_&Yv5>EH7avsMp;6&20KB;?=dB#XGS4{7mge&qUeIkKu}-*>7n&^psidN!QsyZE zIPeh3yTq^_MUzIU4-wc#3>PrMHJ8oRp`WuX0f^x)PvmclLX7m=9L;{3`QLxl8ltzI z;2v%iG&l^&x=XnU0c5d8TAYS4)`4 zjjy(aB)WS>xU@hM*UThlm9j|hS-|lRF=Mv`BJy4@TB=9zQrF!mO{foADwn&<4&J-} z5~6=q?kWS2b$PL+WjEhL8Ozyi^ms$STw14RE-hQYmse!vR~&6IxoM7o9?9YmIjm9? zmS+TS?@V^p7ih^I=u@}X9X8Fh9%)lHq~X!LfVWt=Zfzx`pUDs>n|TKa^F=sgJ2XNq zjh1S9T8y8XS)XFTCv0hq-Oa&?9o%VW4dYpy1u(m4gO{^oTiqkbx4lo9PVH1uoAF1? z&=AXvXQO9WpP15^Y}zp*M0gNHn!HZbd!e73)~9x4H2^Y2M7jeV&1$>iP8!>flh-)1 zZSe`$7e&+vjB3q3lXm1erkwJM%nn4y8!n>US%)(`QYOKN|MFvQ(;}pZ+F6jG--4@w zgJ-di1G~%jzfkGU(v%&tQzzX6XYmK>PG4hd$9<~4cmtyBvRj4!syX$H;5r#svWmHC z#lYXyi1Dtn{~(6NxhTSSjs4YDJ*xjx`6{^5zUHy}Esh`F$_)TT2~D8*j2~z-;Enqi z_mKm)np#hAgd=O)$X=!mCYESWC(Zj4W{zew?v#!v-2v8Vi+VK9j*bK3&Zo4GZVUi9hbs;zp$dUWhn?L(A?%v;Vd3;r%uU zSasAf`pCXym0#}d<_sp-i4%Rs&qgTjG7G;BR|gY%w~gs!Z|!hy*T*LmajRT0FWU#|bKL>D ze`53VrWLD`@WcRrS}ZdaZ7`ZE-p^`O^oBqVD9>ipoFYbV(ly0;4mi+r`aG5+YSykq zN^9&BqmbMeVP+ntin)_*D0G^!B%4dDI-Ec~Ua&gYns@k$Bm%cOyvOLA)qF-U(TkV1 zLpeJXFN>feU5@7!XsTRdNJ2$VS{P}vpPyIbqBT26uPK{0q&dfDv*wZurCku@)>rF? zaCZmHG#2OqAS2hT@5{LSeZJF-$?aNWP+5k~6mg^Vkh6x2IYv(IISKTQV|oS#UuktJrxM(=!VFZ2FapJI&dd!);g-N+x1 zhXek$^aGos?Qn$YEoY__S$vwzDRo%cMiFw8KPjp+F9jncp1EgH0c~)&_B5O z`u=tK0vrmY+Umqid+68`BIFgqY%7uNH{rOtxs6E3_lOvt9igj;Wtq|xrwhjF$~hn( zu&Mg>E{&6ubu~IN&4xOBIWi*&FcQFhGcAE zjx6CSZAruSWT!w1!3-~k1>l{-V5ZhBh{9IthDgGkok=DvW8aQD)U4!rxRif#)Z$IW z7y-!4`N>j!#TkM?lUy?@9>n(x%MLvC44st5SLO|*(+{ePe!?4t%8uycs1|Hq({xY(}2=u>1)0; zDAP(5H?tZLak-RzSJE`uY}tIoeo=v9E4%jCS3MEZjTs*02Vf)4Hd}0;{|#I);~S$z z0T}{nSSk5bRO_4?c>|Wvvjr84YZQh)R^f+Loa;1UKuZ{-^zf%O%VyLzq{i%cTXc*% zk*sx}+kkoR^x+<9{qK&`dqnoVkVgD3(~wccVohesNlrDSOG^|?wS01ETxJFXLu4~) zuP|MI9C}*6t)G*gCo5i^ecm(o#>2O^V9BN`uYe2YQvaVQYW6C5#{?`e=UNT8*lnhU z*jO$$D?>jYGTLH*`~j=f9erz+z)~us_c-!rE0|T1n_SCr;X+AF}UBq}=&im~%4t*_nwLdYg zU>;mNKWcZNw_b8Ryl;ywH<&A5zFNo&chZcA^q{Vd+%|1)FzId{B?Ug5hn9*2_Bh;7 zk^-1~ZjpxMlnqagG73N!VDUu|SR3(zP&g#gl`r|EZ$MZ!{H;{qf%Y}ei40%rDOQ`) zKb;U5I9B-iimg^Gx_d%xBX}`i`JAhpE5koZd$l0uG_$2<2lu#!oz==@1_i+b#|*Px zNo|D%$WNQyUo0Mwv@rnP;mk-$23;arQ3^s)CnPih0~(glH=GXyz@LfVk+S=W57H~3 z=Mm=q&WKEnJ&#$8rlYivwDY_iaXr7>@L41FC{>!V z7QA!2=q0@Rl>0evph4=nhf>fxSc4k&J11Coh|Fuk&LkeMU8-mDusb628Mg5`D_)Ob zUn)s{gx7k`lfbIXe*3TyO{JuE`Yi5NM)i`1)yM3H4g5rDOKnVt)lr!BJoxYc?+!xz zV-3ighw503<`Z7)ZaO|4le6na5S3eelRKX6f&CwR8y>z5Gxu+z*4KZz{r#^I{ofjX z{I7^s`X;to|L3qyPV;bASzaDl<-5ncf&rB#i~vbMB%}hiB#a=$h6GP1q1u5Bg25sL z32SlrF_bUsvO+~nOce-Ayk}kAY+2o`THU;&X;uCG`F{SkFj&r6P~&VUo|i~mQB=r zt@I?P+b|7w&o0UmTr$BR6LQM8{OnvoWH&H0aZ4f1WISEQf_lx9sln>FU@R0;>ptj2 z+a3cgMO8V`?3R>z^E$=jBhylSi72Wh1T#2stN#q;tJ+di z*c^=!_wqL}#M8^EJMzf8`KV{N!|i$IzQkI}NW(-*Ovp$`%L7afQFem0#h9CG^Eo}? zy2|ESZakoKwZ*k%iG9hJy6b&^qI(2`&1@FC(7|555%%%x%KObnZR2)2)tS16=A{O; zre;k3){TE#?PfdENk#_F2BopN9bIPgFyt@%%#T^Z9LwC@bTpkQ_0R0VUJWGe(uAf| zyj-hyOE#Y}SHW|^9y6q`BMvLt11H+-%g}o)vl;OE&f z!L+PH+Iv<6xCAw_rNqBdWjHQR7NUZs^QU~-@pIB#%=unt{gxNuF2-6~uJNEW2)BuE zi$HwK_?3W&NezPNMR3M-{WHdx> zl?xqFr00`#-4X6C55tP!b+#-B9Xt9N9lXtoV4OjfIpn0x$|)22&-N1y8895jPMzyCLC(s=eU##{|EB*GDf%t^9VV`fR|6SBy2%(DE>7`Uvfqqk^;RFS)KA^XTFLcGCi6hS;bAPINx} z&J&kLdT@orSGLtQ-nldOn3!lRsb!>D?pR|O*YEw@np>^TefooE1S2@N5nr%f3+6Xo zab1~`S=GBrXsK2O`76{NQQOmy0h3M2E-zsNyBg_u2tPf5k;bRBnnNnDtJ|C?q z+0M9H`h!)SqRGofr!$?&=rvhxrAB^w0A!EprS9R(>|as~hFu3zxb;)5d(6=6(bZK9 zuE)XOHihoOwL4~N975TG&)lkU$9D>=K?ppY;xBy!XQ;H>q8_7d!O*k#XUA_ZGnXvi zyTCQVLglYt@_Xp+PfDpq0|7Ta6R^=)@8+D*Q?Z`3rH*FiSp-k6XKIQL^zB~qK21r! zj)MvK5`cvljMMF^gl<=fsqaR)T>^9NY>mUp6Z*hGs*)sogDHExF8lp) zYn^OsL%iL=npz#Bn&X38oyB$0d{YMboDNIiRf%Rt=yZL^(V`|->Pr2<`Ke?_s@awR z`y6?W1@o*U0e^dNZdc;fL&);=YTx+h~%u9OswG_qZ~IXylFcq_rDI``td}) zM&ClYawKedX?3AT?jJSpoLvFX&06A>C+gFB6V!aNmnneO*d;?;>EpRup4`b^JeCNt z*j=XAO1h;#$gGSm7XBg#BCIW1ItT8{thVwx2PW@l*!(DJtDxyk9pncleTBKFBSvwj z<3?#e_ZcT}`;4+qCyf$*0vM;0?$T0!9@I;jLdK>`bHjTIv`CF+s)+Uagl9tR8PsAJNm(VeCPhdoUst$#Bjtv zPYMgdzs3X?wj;*@@&sK}Z%%R~KW{n8C-2*+aL!Z|${ePU|3pFb=ZV9}kGaGs|GZMn zKmmHD2?09>c#!U44%`Q}1IW3~sQx?zEU^GSLs%g18BAy+%t3winJEQ^fVM%BVfmovhutvBLPAo>GQR41AQye3dX-b%d2Br+Mew^8i;G#|3 zNTSBvP$kI

bW3Fi!ABxKZM2V2w$P_(x15;|ywy72kf4(tb$wvi=&wX^>9zM#xj5 zBgSdfQ9l_Fm`Vo1)ED)0Or=9TViZ8`c@C5@=dHn`%w4gkxT6*gcFeMX?ir29r%I!k z4SMvA4T7UI)vY_F@n{&;d8-1k;OfAcO#6{_unocq8x6u69qUAyj{1;wjs}o*GW2DP zSO$@$>Ico3G!4SbkNPJVj|P#on)@}!%tKxH3PDoTD^OOLMu63cX9d;Om}dgWW;8*q zzz(dx7dY!y7 zb0O)29@FiytVy~c6*Dg!*S3RF`{A=U&`b8SPt!2vAS>|m|~KH_g| z*D7Xt>-aHh{6B*2X>s-1;AJVb5lSO(bUDBV;Osr2*ayC4_CZT??U}Ru2j2E@skea5 zl5TuBC?H!0%290tm1wu%#aw>>m^mGQ04zZf1SF#H!5(V^NbF}Y_@KpHJYi>+2Sx!~ z#P3j9$paL7WwQLijSA1CS)sxFf%k1UKRGHEX8}AEUf40Or&t{HP`SbPB{vxMI~aTr zVvo;cS$G4-fQEKO7ieIE(=dz!8iuNNed0SzE>8q`gY6+FnJk4@|4{Gu4(- zP;Vf&%rmz3GT_M`C#ZH%#rGYkX5X^FidijI`Y&gYmnH1qpJVhe27jfdi;Ji32?D`xuL0JCOshU24I86fPzm1BsqY+k4(r7w~e=#D_N=zN_agPC z{BIfu0{5hR86gH!dko?IYq=hR=^qW@gMHKM2)v?uF?*helKOUuFA($&XoJ6k?0vtYaCPe0L_|&b>b}GtP-P z85tRS@3o(ewa&Q?k%2M487QtG$p~V7hNVUEeHNqz@ZX}-!sT63gXK>Lq{YbJqRIqH zZ*s!rUrW>cN!uOjDrb3 zi83iz%E?Ta=xb<7H19b=(4o!_mUoZBgqC+Y_e=gPA0zKxX)Zwi!9s-mV{Tli^fM<$ z{!wQxSpIG+T7K_}zx2k9P#KS!ztp7`KJN94TKM!!By=9kjEGa)9X7upXiJFrqsJRB zZs_fMlJLn1p=@hPi1_Un2cAN~HK1@+-(VeP~nYU^k4S@;}*w~Lg&fU2;zMP-@)S+hZjPXQ>@_s z@LE-i5P!^Shlro;dJ3l#l6zvRt_lEq2+%87>&W z7)JTg7(VoJ4rm3PAz0~kpw%t*gAQoIVIf$pXM8_uEn4|tk7rmFLKC_G_C&Pk+kz7I z>W786!ZzVbjQIp4KK}(rsIbNNOZelO9{74>|1hm4Wy)a5&C<>kR_&!b=Wc z!S4$>Z1F8YoOv>bpjGl28F7VfVk*uY&l@xBJme6AIDN@1&OEc5KmX&JgZT7Gk5D0p zFGl$8mFoKfE!LdZFG|?wlMpfLj!pc)tJnjg?C{B?aP>=9p#1ZTM)BdRLVV$?Td3US z3sZ68>ME}MOHZua;}b}+>W(eeGV2SW?6H|G&NAlc`}_I$%Rj!Z#2c^tLY2GVQvL83c%Kmz7xr?* z7mo0VRP?@}$`;?qzJF4}3)`*p*Bi3OtxwN8n8)fDuTb{Tm)^d`*B7=&`qvkM+}kGF zNW#_Hq166~ZwrveTsd1pql6!>!zq{zsoLj;S=ZxLm#@y`e)k`ktlY06^gF-5&ewui zNT~pDKYn;%{HKc9f83b-uZo$SwY7nxv7))%e^t#k?2y03R3==De{;1LRnb>u*(AYf zNkLKLwShEOd8;;ApUhT+lmpIfSh(rCmW)nKwUeI!*B$t#7?#IUR*`cfW%6pkmL-N64b+U;-Y`Pe+*z zG${4cp2Hf!JzA>!`w*OZGIK|K7)nCu)X;O}5?1BQ3A&W%)KhIBmTNA-NyI+2ct{D_ ztkP%9r;u2Sw{NPiW3xGdP-Qzsh%_rlqfJN} zXnC*yj!@;ucEB0FzXbweqafI&@*3A3d^ql`XKCd1nayP0Lqb^#E4gqC5>*T%A`!sp zG*WZxj!SPQyQn{t2;GFSvwVjgIP~h^M0Fx7M6nvbjoBUZtV%*9Ishc)0I)Cbn!E-@qz=x0al)vS!zCWl7p zN8paJLFm9|)(W~OT$C_>`?BeAq(xfgbDSMTaC`H6fkTxU{`1VpRZs1zp}M|8wc6vl z!dRiH^wbolZ>uuniamx!FLoY(mD4yHL4uVm@26+8qM1<4WbhDE-?(ig1 znU`i3_po^1Sw=EQvop?LZnw34b6?$C`70Uh@D%KvVJwN)7NfyDMfez@xH9FPY=tlV zL3*uD%BVm2D7h}ZrVVvh?r`|$0m#aZEtXnX#jGpNtQj((`X3E%hMz3Vx)CaggixZ> z2nU#b{qDa|345ALcj1=5SOCRp3Mg$Fwti+NMp4PH^0Ccs%F;4J%J9Pd!uSL^l!fTC*$ zE{CCCkgQ^u?}Bg73|ga3;ubWlPI7@Orft%vLC}x@)#jTFRwrOYa7tK}bZ(YwJc#uRiIm z7};=u66=?;^=zb_W942`Knh>%a6*_N-So_FznuEj_FX7#5V5+4|FA4*>{2R~gwyE_ zH=oepj9(a8j~p7~n-+?A`$c-TYNC9$x*oZT&+o_VCpnV@STNy6jq=7l2dcRKP(J{s zzR65+YSevy$1SuA`>jY@$Sc(L+Z|Jg_?@07+TJY@&I|o}3zQM>joFQE58c!ryJi=7 zvUlKYWJhQJhJe~TQo&oWn@)d^RCbpuv+s#~S1i#Uiq?0qMQ?;-cB>E69eaXWI`P25 z;6+)KZ~v^XgGS=J9%gV3$|}rs^Jp;MJQr$*T9p_e`~s;psISVFrjp^;7XQ?wRBlR} zvaCzU7}2@R3h+MU%Crm#>3gF^#($+1s#IafhBt~W?0|;#d2N4}$JEn5lx~-zL#~*1=85rf zr+mtmt#dE(xiBVM-NNKqFGQD@GR}hsPdOx~wb#1&EsgE2xqnKV&<;@P7Vod1{kH74 zqV`=7wf+~L*?(U`WcyET4m*2i3mZBmi*F)K6IBCi7ZV|K6C*1V$A4-et6V8ziJ<$k zcGF^mfdFHQS+&(XPLTigTT9p zFie8u^DNwNf`fVJ>>cj0Kz*F~oMu^V-ctTL#e&RC4QV{8C507Kb-Q|6wcA*<`=C{H zYidweuZ#$9;@_3OWDTauwA{2F9r-np)1%+NN(DCC3^;6s+9}HfFHXZQL)JnVJDx1r zYU3|Fvla(vMk%XQ?TV>#VyB^!lARZBrghnLz-5Wefh4eD0X445-EFE#Ggd7%_lOB2 z%7&#XpTp9ry3IT;Q!?XdB3`VX@~Cq%l@LRx<9IS!)ke4GGPObA0g2vFZZmZOO!ul( zsHXbfApVO#=7Obtwnn0>+H|ZYzxI+tfpd{&IEU}xetil0m|HHJzwKbGde4P?lbZyY zWf^BHh4LeRa2R#kEptOhBBv^T)fKmPOmPmU!YZwLp)$>Cfom4_P|j1(G()z^0t6># zY+Y@JLV3;KZbg7W63z=cVCIv?Y)=cj5PDEt6hkOzfy*IXJA!R7m ztI4|TKD|P>7UMY@r{!s>v#G$+_~bYA~zBRW(h{w zzQ2cZ5xUZ7uqQ=e0+~Rt6O~}u%}z!yhy_C3UE{hRr_qnM4)=D%{qR} zj>8J3krd2LvP#B@J1g5l2XchJxg#gPBGu2m?xQI7z=)AzN*?1pL2d9(S_kgyvPOv+ z%T@tA4`5+;vdeC{`Wo^f6oEz*bj#ikMY2oe0e3k@^32zriG8~zlJ z-SE_J?LD3H&OPHR|MqX#buK()-GpJ2*0?f=7awior<#0-7^#w|uS`}~Kd z-hpYR+U|F6Y3PUSaLixNHzyDk|Gi{Bt{r=78>-!10jljx1Z@<=$v+ly6*N?0^;W{Ed5sHiArgkvpEvID!AC+^}#S1{RAY?%0uMCv7yQPJ^O zrnimmb!TM7d)A2VgRHQ$;b)T~p%n@D6o^B%i?b{C4M5BrVYo}WVwJ-82C8WxSder9 zj*^ka3v9~D=@vyZdNEUPjBbQB8IhtMbb1yN@2*1Mf`hZbt?L7Q#GsP}rS>z=Mexp> z`T%BUT}+7j4TG6H4ixm+mvX+u@5$?Xzqfpk&lQjd)%3z>*D-~$r#-M{ASPlm*@pZK zt76yb^LzokB2Y^l)?@~loNMT)tv-^|NK9gFHlAcw`5mc&7U^Re5#?iT$f@4GM!DLq zUS1&*=*eww>Jzn5eIZE;wbY^JPo5U4x`17*^u;e825sOHg5|1)RL{S3lK#tyx|5KA|;Yv}2(wfS#z z`=1;0|FMnt-w{jD&c)W)>2Iq_Qq;0T6hQt2MQyTX1EEl*QMs7}yl85A5H&KCiX?A@ zTObWC0Z>gfr88bxIF9g>Kq?ZAx>?cNqm!SaR>l%CY+K1(%Y2#S*h;(N7wC}TdsbRY2ggu3m3Jd31QM?5A&0h&wVyBg%d+Z9TV%fJzj1ZrCswrSJ zpQgxcY{z)(Jg-aXtaTf{V4zOB7-ggy=Ju<<=M;Li8tv8QtSgo$hdsTiVM@;)hpbK( z`>e%3gR?$0DpR|#;43+Lt)*X{R}>7V?-&Btjt@YOR=O&eNj3g`bWPDE|jTdi-Hw zNPLo0yehdYOaiw^wg`s9?8_{GdKtIyIo2*-ZX%@+F(K1SbhHsWjsQ6^Ogu^9N!VmT z024ArB>u>hm>pvb2<0H*8MOvO{nXBT%RZ-t2dj=JoC$bRdB=wmAqGyBNbM`R4fI&) zIC1Dcyb=;VD=B|rXljHJcuH}s4%%UNX_O;uSxhRaQ+s@%?4j8>H}Ld52=E^; z=Nj2ixG;Y)JU%K(5fMBSoIr z`YiRCy)K>)2KBCMoP24QV@s-aR5$!y;!1vC0NI*~WY)Crx3v63f0Ha6A@9C}o^Ty5 zw75C*wnsO@i2*IxOfcdDa~`2Ig1p^0p1V^+%4W#bkH0D9l>y z{7khDz>6g#REg!`(NLJ`{={-vSE-A99?Y$P9t>8|cC> zKoxCbso1OOH^~p+$}ZQ)J~s9o`N|r+{zlW2f==f@g2*S{GDlc|zEa9p_GyGk5WuJo z3)Vy$!SNbnv8czb!3Puvq}mx7Uw~I0AE7PL@{Y3fcRPut#!#DD*ZPXwAavVpJXF9i zYffpO=_JqH-%$|^+)p7r806dhO#j9F{#}xX{eK5!xxcb|3r_=Q3p-nRN4symTbq9- z_Axq=Kn%!1a;vL#4>h>~Qu4xq;dHVzBf0eQ=5@CCFez#C5{ibVxZ3G(v^^pcObcjL zj1K-N@BSX*#&1Sj+t^DsZorAH}6%(e!#U<_&<5_*(vbAM-6}?zeH#n10 zGWDfIqgQ|RAM-`p&Az$As}Fy8c3@5lleiN|4~flTNZ`S#(ga@)B+JfbQ3^ivmJU@M z9hePI%0kVSxPGz&@7Mpwqknhw|Hzp3x1;};4!e+@t*eQn*RnwQ zBabrEZeGutr}TcD8?-|LJyA|O=%qz5vW_iN?g0o9ApoR&3QBhf7wTeTGu9I9tbfmG z)A|jnwfXLk;RYJOhE!1m@`l2J2>G0g?H+J9h%oNB@{2oRb8)BM4yYXg&KDh(Kxa8* zwxH%X3?n5Yg&1HLsg4vq4TPJ`!c}!;jsD_tgcpN~Yaw(T=s}vS6X%3pl4I)5_|V7G z&TQiH*ucAR^AzsBglz5RMwqaMxzqRaphhXtC*EQf+av1QR_!5L@-)GN5OYnATf~y& zy50yK^AH@YNh|0GUN661t9HzxJ9?Z%c$PZzvu^c-pF$GrxL!bJ^W`hjA<+^-fwLkv zY7B-{#mLriKb?PA5k-IeY)?4flYXFSTLL|f&i_?h9z*M^lqB9R>yDB#vUuza9kmI3 zdLgHOk%g4FT7_he2R>`hAvO1hm+&nW+|>aDl}0~dH&Jv7GuA^g*d!Zqb{fB172jnS z;6<%Y7yPM=8HH&TPr>s`$(95t#}v_{UO}8$mVo11F88G2xATTy-rR{>AB>PTm8qS+h3ODGp+UG;;&5SUkHN!ePD_AfA?W)3tJNdM>=^6S374V6YFm*`F3VS z7i*J$Cez9`a&z*?zO*#XR4(HHgh(O?&RCLJzXsHarTK;Gp^Y3MUQenQ9VGO`mo5Us zz9d8mMGJO*^NqUOYCr=MBCPIbW_oRAAKkBizJ6Sg{bW3xlV>Q{!@aZ`u^>ODmru-3 z6ci;ps*H4x6;wS9!8~M6gouk+e#glu@l#ZntO+dbVM53gg_eb zQobYy({d%bRi-=OssK!=YuMrnn)qOtRljE=Fekp2k8$0Cqd-!Gk5eWxd`9BOncR-r z@G%(Sq+UNcwh^o7z0YWpG@Pk^?7AF{{S*}IJS?l0m2eHMophGQbPaA2OokR@t`8jp zBfV`ZXH0L5A3+d2{)d4+_3Ka2;>u0mPxVOT@ZsRLnPq|>1I|0oW|}wd6((7Yf@BWr zVJ}`zdNS% zj$Zw=i#DB-2@5Mk<0JA#pqw`CMre>(=zuJ`7&RbAM9h)?E{W_3P{qvU@YBE3uh6Q6 zq|S&jtThVxGL~CVk%;s*?G4t2s)Pbe{DLS8y)7L*@Pltev8`cV%MvZ{k#~7h&ovEr zfOx_(*z>ULQz3<7UFQD&AJwFm8e0v~Z`67H7mNM(SonWHoqt-a;$LdF-?r*xZejmV z)KSrLnp1`UjJAuni35(C9)MUXuQEy}2k0YlSmz(9VkxXz8#i|6WFSNxi5E-W5xW5d z00aW+XW|Ptcv1%mc?B8U)2VvA_3=_YI^HW`y8;;Bo1#{1iSJj@p0gM2f4~;48!-&y zIiMb@%`9k#%;>IDH*gRdZi&t~*H}=Pc90q_jAns3!(;`<*SCJ@LaO$x-*8<83~THL zrd12H-%6&@uw!@SF=qwpwqY}wZ!rd|8nIc;KI39+_;TgOXx+DNsUq<=PD)6?qQ1Kz zcmDXmIdQ=T`2EVy8{b6s;nQA>ja;q4#a8}Ry#S1Q2@9I)F>ny}u&{golSHwimxqvD zo8&4>)@cgjE6xj-XGZzr;teok@auODF7!ktsLRR4$h1i;I>o^lX_@rO!$v8g{CQyW zLP#HMktj^c>eS-8kDh2&>}ceJkyM^1vNMhU%&v2{Ma;6SNlHUc((ccR(}Om& z=0s}7pa%mBx!DYqBDq5qn z?DUt#QSL160_R^vYNYO+KW2l}^7v2Smm+LKAjG>J8*+aJ5DPi{ofOuf`11y`hD&)f-ga{*o;7ed`Gk6Z_ z{UgUj{D*`!j(8SXp^g3lGHrHT%6zJ89-WYmoKxt=BT>03VSg{2WC4E5K}tefUZWdv z7TVM(fYm}&Hbs~JEjfKdhz2JG>E4-EwhPaV&Fx30bLjawQjpk(kb?e}vbW#kkJb{f zk-4qsaHI0YYK0*}76nqrB;4^DUMWh6-cGfO``K*Y$ zk;!-NXlMIRkWrkH!umd24+*QyEel6AX=+h>iUZ>eM4(eFGy6AKIjSc}!5P$J#K)~< z)pEscckk&<>jDd$v_5@u71_<93QsrP-}>Hss~^2=dVl!(KoFKuikC%-k3AsNSt(RZ5~Xtl3R9)zl#i%3Yc zLU{D}?M3R7F^JS*%>H>*gdUB%AKNYP{_D1Fv7WBMEGWrs749=XOVpAVK}}~wcS0B# zUj{15v_zHX@zid^a@eY^YR>a_ul;lFyk9PH5FheaBNvC$OM#c(j$>KWlK5OV5c(oL zP{=#AiBf7o=nP1`@lly$D6$B@>l>5$DX5Z~xKBEMPW(hH7%N0~kaoapmRi78dsWU8~hPJ{9nmlN2PRQe}ol=hLrmp z3|}MtWIBtop%x>U3_Kdo=GaN|;;rao8 z2gi-dmGwKF-rB__^GkIAmrYIb__v0O<%;|vlThe$SRwDp2AP@>_=zYRMsgCf2-#o~ z&xIPbp!VJhR0~nc=-w)s%k*0gWy;Mai4|=w-KfG*Z*uK$GAmX)D9CAM?z+aEN>?#4 z00r-p^y|?JTk8EG+4UHu{Tsdsb}3mni{T5QXxaH+zmQaa_Ks}uj4G+q((1L3@aVGF z16sj$S|n(7sqYn6)=PRqn2g|kxj>f{)j-e0h8Kr33KjQm6d$t~w{VIx#ye>Nczb@Y zZeO<9#n=9l37}yTmR?N+qqLefk62^r6v0Y+ZQE-PCeMh!pnJS_lLTbW90bD@y@?N= zV=piOrYmhJGQhyIbjP|fPaSB7z9Y-0>3`@2Z>HsjvHNMM`0NMUR;@oA5e(%Xg~>h5 zVy4asC?-Vli`8N%R{e$sl7A9Y&iRF-BY5{`-fQq)rTtrPJ=uD0^8~90hN+`iU4Y^y zg00MQFu4uX9u%fxd|sL_6MwYBRyCK_VW&Q+t1No4;|JL&L7-@>xL%IItG5V39Cf~q zFd~F-n|@9nox zeO4Y=Rv~vp)K~C`oDJ9wKgSwKbYm~tjVGS{eG2ZipdP(LTqQ9(UH}rXs;^ijnqLJ} z4){%#Wk=A}!35;Tczh%5ru4#Afs_XdZa$Q^up&<+gZDqwZeq({SWs_ZD4$Vt zcDU9_xT5g_&cl&yP}vwnV8RfDF1Ha)&YzWay+ebnH|0!4Wj&fa&P=e!tGF-If$LjsqSzc zna3U%huB6|5XP9dRLM~56a1bHL8khviOiY$==Ozft2+%(596?cQrR_wptEkpXyiQ2 z-#Nc&wD_HJy@V>6w^HJo7roa435Im%$RtOl(BmwOITcDY!W*+%FuTZBuKN z9+tAOP%ne6fgOHWPSN4y#R|MP$4p|BVC&(5I65p!1Ye$v*GqA4R9ICf_h>ZdEnr8Q zJ_5U^m_j=z^#Q5itS_CgJWeISPm-IMUm2QXdDA#ll^ru(E-|i{WiRs@E`(q(NC^JW zG#*tOO-tnqRymwDOJ}TWG{LvlDOd2sZg8xhja(i(qj_Fyo1><1RwL6XKn8i%I(Z1yr2Il zguJKOkY#*h$o0Qq$iJHd=l}V*`gcd!UD@C}sW5Q)JB!%RgmPD2Xw+H(>SV89q;;^^hMRi_!T@`iV-I@cj1 z-XlEm#G~1(89lZNaO~oyy}ns`5ya3TuD~*Ou8U#2CBgLT7o*{(NT53a0emU0{78|W zS~$k>&?~+04^{_9pSuvQIj#jt{C}=^7FXPQBNRd*H-#xi;14(#6%< zuTx>&!jHi^aH!+9oqaa#?G_1LCydqd?uhE9iqXaMi|M9|(G@sBNz@hSy;t45+~e(< z80Onv>vWEi_AR}^!QA?zJk5U8kVf+mahTa|ei-0n#x|j~Jneqjk@ov=+-NkdnX!da z9R*gDvpgNCPQK6xQ)%(soH!d?6fq)T2RG2deLXZNU`Irh8aG@Nb#aN|=H&8;?}PdM zHT)*VaCXx9w!^%#fN~kf`hvM!vp`1&Uts}7+F7tJ4;9$8|*q4hwmTp=#zbDUIQ=CoSM2An{ABQIaI9Y3 z;`AxAZ!&CCYE*5uI$Htf2|yxrTkwEU&DfEMd*=m=DguRV^SG8MN+f8^1zfn0VnoZ3?G`${jZpm?Kh0{uhlHvqLZgfDv+{DcL4Hi# z%M&M-nzR+)OJTB!So|*7sWlMj{%KB(S$9076=={Q8v)u+bJiARA$2;6%Ft>mwx(ZX z;Am+iw**PFNSGh0B&LMhjpgO|Ly zbMh!-NGzYGktn@E1N1--MUm8KG&A&TyoUctAyE?6`e445y&A%&ppJglpH9;Gh*}oRgdYgahAhlT(l9fK z`vrBhQYjRFY8sr)-Ke?PDL4i9_(?%@bLb5P?zY#>spk>Gf%^kP-_DuVQf;wc3+Z;{>x;A`PNSb_4AD zYlE*Y0}Sqy8BJ9-oQlxH`#OdcW`tR?Ce!z$uv^24tj4dm^qO1aG&K$8Z`^SOIuxw3 zvhA)&hM8HKb&zO+A(yeo({5Uq9@i^d z(x|*lV8k?z0+1{FBZjku?F1Se1eGe@<)6To3p-)Pu`0bx#Pat@FBIvy;~a_!sb28$ zp(`RlL)IF8QwdbHARtsI>Jq06&D+>QQkNNaQenywpPg1_w-{jkXc{|XHN0p!PGxbC zx@V+IZEw(BnO|B!lKs`zPXL54w}zvMgQ5fry#R1%A4fj0g~Oy8lFxI)j5cZxRR!CK zQT#{hEJ-yaqgEU%H`zP==dMC#Vp=^p?fh>*w~htwDWFBJuVaR3Wq)QmsmK>e+%yolG>b1X@u+xpq6QWKl*jy8=eg;B^?$}XDq*OW3QE_IMGFQ@&($}#QVPdk))QY5P;y}5yso;=> z(mIqe4!Uykr%-+tqfrcY$ILfAW|c~rBQwjUW8IxDw?FsYS1RUM+mvv*YO^C*D3irW7f&eL1WU$_9kX!rLtIvg z=j`U(oL42;j-82Y7TrT8-R^iWztoSsPAIafk+x;C-cB^KvWv}}H%SW4EPhY6n>2{P zKOTGIeejof9S?Kr2rZpvl4bY_)toq^T}+=yctX}W*A02Obmd4nPonjd-XD6X%8{>= zn(jAp^7Xv!-{elh-SmqyT2Z;s$~*6J#;5{4hdK4Gn`Ys~o$M2pF^Cv^&2ofva`KJx z&Ac#d*4*uRC(42y`()*8lexTNd}tq)JX_qyh^a~*ze68i%e`o1eaOS`4fD;t9KCl; zc5kCG`zkEE%N*(5N?~?a-qjonW%*6i9N)9^*Dgac&5+oxNjzNS0_BCz3SO zpHM{kRotDu2g};&NBNO$8*ppyZJl{DcZca`Ifo{v8sGz1yeCiE-EnbtQfqzokN~Nd zaY)?XR8L;r%=PsEMCHZ9J;!jOImS&A9c1#|gajT>4VqXb>nnPwdx#!sfBwe4Ma#lD zpVtVKI7abQIf~g&?H(;ijp0npf}81!z?EeF#A+DEJL8shehicTtiIuM{v^AYe(rYp zMDr`Z`Tl^`J;Mhhk|+d27H;#eSgquZ3|h>fAa(npy=4prTpYjuxw50ry@@W989rJ` z17b3ia*7Zaq>PZR>5Ai5O3kO7fcQLBH&Lj7cFIWT;PO7uUnA#WcQnC)G&Q$>5<4s* zwwgxR#Wv1e(Us@>2fO&ZcLPioyeSX#7P!4#g+W=v^BS$aK9FA(J3u!abgBGgY*Tn1 zxR*i_P82wps=6&@yjtHaP-D0h#Dtk*FfwGbnX;lk?x6)@;p$zjCVK;9ed#`p%OW<{tc%p=8`y~oVur8#y9 zG^@s%fyJ44Wrd}#j7p}=1yCM?hKV@dA}(Y|5x=e_>eXiK2UFkk6py?@D&B8N$rT+n zHM&Nf#oS~G7BQWT-qaaHmblYGDq%N73H(3haAZ;;hqp5(Qpv;3NXjlKw> zJ}dh*Sr8Fw0c0{~-j>R0=na9uam+s6Es(N$XQvpAe1Lu=E&==8jQlP+u8>9btU_^J zA%Miv6i~pec6GL}MzGM5UXZJHg+;?YD*DhR(it<{HpVE zxznXH;0Cl?cvYt7fa6|WK&>gaHC&p^9U#*@>-s=t*R-3xV2<=aacno&(?VwG_!KLI6O3p7HU4B*&*EpiuluWZL!X;Tpuu->oGWgPCG8-}v zAm1KFz?aLceW+)EKhTL!37c{nzDuaHnLhiDG+PiefKSu4I?UKL2<`xhM7iq%xgGqu zx45@B8CP^=$Z)Q=U_j~tKro!Qkayc4SWWtw2wRyfy<&+PxYNQN~bZdy=mXtjuC^#k^9 z&{apU$p-iq6mSStINlWP2Yia>Dlvyc;WDqo#50M`nuGFpbf&{0o9+<#7@KGdm#TGX<8w-@RALLZq$b3IcK8#DeeHz&WT*QU*u!~Ady)X4{1Q6lur-r% zQy;F5MNBUD_pI%SlguEeFBsCX{Pmqa9hM)**v*I*t)=dzCNB`u6>d5IBRv0wZaH^* zi#Zw&-+~DSVMWh@^Pz$Yp9<7Kc zU0F6iz-9uZ_6PIIRd!2+EIg!0HLLX~W1QtHIo4a{A4(1-jcK~n-J|Lzz$sf!1gJ^O z35`9MMdN2CYYfj5AB;Dq$7u;z&(LD&2Z*W9$OD!%e?UDxnZ~K9#5LJUD93UWgktHuLT;^wf_t=vF=hu9z(D8}kv3nO;;TWDF(zjr^HAPn494 zywYr*D*^0K`{_%gh`Jxnj(l153_zR3Xf3YGysiK^QAfI%5^(s=mjw{_^jX3&Jx{m= zOgjRg+(tk={uQ6Z4|8)pp267#IdgZ$-n7Uhgu!5Q;Zq>=*-0mAv&fhh&Eo zTq*e7ZN_u4a~|Ruzbm|z*|G2!~2sNRY7xz0lUWK3<>PSl$*0p zM5oUkleO%czm_5vw*XRaR+n;CHsY;XsjWIV@O|Qj)XhHxX?8-kqiPswK0dI`wsbNd zSW6eDKS33od^ls02Gm-jO>8jy#Fqj@PQ9R9=_4?c2Yn;&S&>9c$kEI=(TGiL^RybKirT`*D~zEVbzGCz9ko#gnraO7gI#ZJJ}=&p-x|wPqYQ2UbLEAlkO`y z6+i-3zwH!G@c=Mkc#BC@lVUnGXp=dw-dZzsP$^J&*X~JCGkaB?y^E1^b&}dX1G5Pm z**$hB;{in*9Y`impcdE-;f(#wNF6U&$rp2e?0<(FRdEaWJPLd-a=jg3a@%`mT9m8! zN|L!zIjGwQ+dy-RFurTguuT|;C&}G;{fr?33v6;pRAtVV702928R5>EY)XzQIWE(L z`F?Me#Kw%hQ8T|CU!$=|Fh`HpJZ(SH(YH4z<6{|qWX>ufgMc{k8Layod$TZ(VnJ(zO&&_-(J-iUfU?C!%O; zAfsUvyxgY&3?N5`MB&|TaWj#qqibA1snxNsyiA@jRIW2-1vL2KytvmxjT`y$y`Azs z)G5l(n^AVbpt);q4^#Sk(PD$8_qeFuv0Dp4{ghwhq=wwJQRcp#wT)f=+%2#Ib-^c?Cm`3Co(rmyLl_} ztgMQGkh}8SA4yLh9FU;FKVuNW6D-UDONt17C~-$t_H}m#xlqT<<5L? zU$AbwZDujMBCEH@ESL&t52?(#{30$7s4Vz~rha^K>qXpq;`oeYq`h!1x>Ft9!emad zIY4Y#lPy9pOJZzD49f={R3FJ#Gd3bkYFhT%3JQBE4aQb6D^#_`YM5%-I{plwA0dI& z=NJdam9@+Jp>JGb73;bMkko9>`Qg7g8128hG2kiJx&Yw0)dnxaE|y7Gv93X2Nww9S z5%9;$Vkk#zXJJigS1$RYOyeFvFgK0rGc<0!hi@hX^+rotP6Q+r(0q`4+AfPAWF8gm zLD9j(p>e$xprj*ieUd8?t0OHwaY!6nOk-yUPl0qx#CKDmV1_OF$VUd-^9u7oM}nl$o!5R&u0hC2+dnTU&xdLjW$>o6FSO)jdwtvKDt@2p08NHD(Ob( z8AlQwaX%%Otsr#2Nc0o{v~DE~86+Zg(K!VV-+aRzbN0I}73#_Wgs(i>S&34qPl#c+ zISO)kUx=1rS2w2%p32taZiUY@+!wU*B6@XH^7vFg&)m|=997s~RKhii&P>hn3O{7x z_JQTP$h_`QXBp^5LtItM%pVMY+%RkJC66DvaiuH6(tWf4m)25vcv;$0g>DHx`exKW z>rie#9h>v=7rpZ`zW^}5&@!%xk*9rzPv5aw?!;J7_!+WY71{60snjv7kJ{T7b^EV1 zLmyPGu+R!AP{CHs2uh2vIhiB>Ufqe;YomUltFzr#cQ{2+QUdxeIh&1@OBI+3^Tr|z zEeOMsS-_$laIP!=dO{B|-QvPSyvaayGO{@wsvk47rEc$yr&k-mMTfAE^L6{J-i8B; zkRVO3;TU17rrtcVPu<;fv6QS5p{ABnRlojNMeJ9e?Y!^L$7jMNI%_^mPTAi+s-R!t z2+a8NKs$5*h+CE)#paeBps_)NUs|3rq#=|pZF@0l))M+`wDoqsSw7+_OqJy#XhrNn zNlnw`fLwy2uyZlYlGCt`wmolvthPlGBoz6c_RuF(ozIXQ)NsGWr|k`3(`!iULTVa zFVZ`G5<5Fb8S{Vx&hICB6DMrFoVq$+fUTU0A8d+p>SrY?r3vCJ63EeS-!tzg>IkOr zc=iuF?kCPd*0o1O77sNmeqX0ea<$s;Ml(aAl`x}$ap`5hkMQ1$9LttCzrdsUAB4DC zeN|iwI^2u_97M?8d_|Ls*rafX;sR#xv|e_>I|#w zyJ|;WJLB}tnf{tSJIRRFeRDh{^uh%y6IM!DNpFiB&ZP-9-Txx2C60YF|Fvzwg@cSudx+xezu{|#61?q_NLZ!yvva8 z{MHV;^?gl;r`VD?A`=RHCEaO>(T?sc1F+(;b1o@CEc&(_NS}J^l~+ zj~~$A>vjLX>HhBxlmEly=s){se>dH~$48x<9Sy$MXp~I;YgIPKQCjAHVu0>OK#yexKm8iuGo(B3l1V9! zRV3kd+G*u&T=T5br>*m5W5E8CzPWrK=-fKqhgP`7^pgH`kQVEx{ra@Sa6TeW4h z2|~Q3LrqsMXM46m8Gyg0?H)xUIGZN3bw3pYa#G30u5mMZp-V|Q)J|f@Qf-sV6TucM zMLabZCR=lhRj3cs2y<|f?MY~4`z3R~DxZSJ$1KSrWNu5Eu~<)CL^>XX2IYx z!P7DHx(OeF$Qbz}T&rRhx|0`y2VDgB?sz*>v8I=Ya8f%a6eLmIBBVL-hf9R5aI0Z3gHP3Eh6<3yKsu{ zjKmYd6*9>ZnF(SsjqPEt)%FteOa)4hPCBNoXHMWJ(pV=1x5feTiRHkd-umKsw*{4! z2^FYc0z?5riSnTlbnw$5G@;r9M)uVY8cx`=bd?0x;;cSb@>@w#`MfZ2Iu zqJJDA4${6=Q2nj3nqgWT)A`+2Yykc5p7QT=g+l-5*5cou^7lfSg{z6Ei|s!~V*fd* zq_XzS(TV-Z+8k61FDcn5PyUcDMKUPaDX%G|XuZlGD@B>RC{!OiXw0^;A%7Z4*JZBP z8L9O3!^c20t8RJ*Lrm9s2<(e^c#A_L*@hT@&)D(u=&kE6YwPMf$M5T%>L-FaBWZu^ zwJN&7I`|%O{l$FSp9n2)!eO%FzEn}&A?TVdSR+)Yj?^O^N>q99J=RSKBLpcM^zAGY zjH^+1xuG}4OY!3-WhJAe087pEJUU}0#KH_j&beUQ73pTEN=3E6_K$Wy4L|EoS^)~o z)6;U*dF72J;>;=jP@Mlq+B*hG8gALb-Ni23wr$(CZQJZZ zmd!4^x@_CFZQHK;>YO+eckY?Eb0_W>kv}pbBmZPR?|#-^d+oK3_yui^Wg6z>QW>!$ z@TQW%f|fA+sAVk!u-1J_M=)oqFw$(L#BroZwlEa07BzzF9|j%ItOE-vrS+s(tkEOr z5OOt&R&oqdR1&y8szeZ1N5?7IE&=-{B+lzhELt|>QtW5=R)9JZy(TLcuSr%FRh&K9 z7nnfyN$f^x!RJ>~g^C-lT;yl}S7zPSJ#_2C;nN9ZZuD0;4U#~F;|vA1h|_{WqGRcZ zRP;l9<3|NmJti4fzb!k^qw3xWcDis#F#5mS)ByLU0)2EMMrF`4^f>y@t~}MAv1W23 z83By60JWR6NEcANJo5a!97r8NZqA^}I_QR#+g*cX^St8EIgNwPLXDCV&tP?r)fL(Y zgHGmxBaafF{^wKZx{;9tuO>#aP3$xz4D1c8$-|Ad6#9BP79E3R7MtY+Q5`yurg1a~vJ9ee&)e#z0^GlryZ%c9 zOoFj#or~p%-{ddxjvg1Ervs#%!bV83LmIEU&%MrlE?)LsP@XH?6h-OF&^2~e?ybh@ z1U^4s4%H1*!N5MOcMZ<7AF@|AQkjo(=Wp4_9S=(w1mKE6D0c+-il6J+We+0O^kRk}#z{k7@TN_D zhUmf5zK%s7hu|-)>Hb*&$Dr%T_O?EedzH>ghu!R;NJ_7Q0F9J6qXgdkj3OKiS*&pnaK9ohsd6QXD1VMKLKg75Je&xPN|Jrih_ET>l4saN)v zl91ag^77;Q6fxw8)LRrEj=RyN71G04k2Ju+68vwc;GNn{k&t~L{Ih59FIi$w&tH72 zkzb$}Z-_Y0qk&b;&yc}SL4kOAEzAt!$cNZ_uYCW27SXv-o88|c?Cx&|)#qIDdhEDINwE>Z! zKb6e*j%ARQx>Mf+Je%M;v_k|zeO^@|IR>t?4DYrfaeVH6n1oUS3O9RFbsX`VQ$rYble zE@jZZzAqVDXN#nf$Dl=@xD3VDzp;wgwkZu(FL+SDMu+s<@jq2?Q25rh`2gVmM z0VE*@n#RDLTYPb0CfjD!lxwFA_BqA9kbnz~*O6&ukqw~oxjiU;xhUVM1u?j}VwNN+ zBWW&KrhJdeJB)K48gA-obmb5$b~z(%RDA>~`z=P*(`_9^FWHTjH-ycrAKY%(2t&u#E#L6H7$fL%IS}KL!bA( zv|FmLu~{v{!==CMF*k~HaVejJEib=hdvF__9rn z6z6mcsp&=SMO`R&dJ-8YsfC2(EG2U+Ybr%)bqKv7`+xz&bD{nS>$xVX>L#8zm6`yV z-G{ zttS21_9w%dbc@&S&gww?Cc}QS({7VC`)MDl50bZ>@|fhLGMry{nckHBF3B!(pzJ$k zGS6;vWwRB%->{gA|L^bJpHKa}yP;Uckeav5?192U82m(x=yh_~rAP2UKSv4|4#>sm(lF^siB*A}67b40P;|R>VRI2Ahizy@-v^BJ`f|~;7 z`&{i}Y|f4j8|C{vQ}ZN3O|^xf@-T6SFk!4}WFtFD2+ItBIBYLwPj&lT=|QCWq|B8V zN_LQ~Q9NK^2UU=nGX^nG%vdszASd^Ls*XlGl&87Vvwc0B(vKoi6z9(E-RvyTkjpdg z?50j%-VMf1>LFX=YDsuE;TS&{W?o;I$s_yov;A=C7Fh$4Z^6nauPMi@ogPqF=t6K* z1xTfm>|!?+6qImovPMCTH6OMEClRq2L>~kfIaGCpMnXg!#oes$&J~7`8`cxu+@{E< z_IgfrA>c|@hJmRhdK}q;I%^?eV$h*VSKGQflvoADnb=fIOnqI9aQew215mCFQE>Yt zR}p-V=dVv{|FW(|p`$*&B)m_Je z4l4@O#5Xi5j*l%32uvsBWi|4-0!=#m`XEU_fN(d3hZiK$&2=v1V`Y^)2a^P;LZP!u zf~U17qm91?3hoTHamQ-Af#tlZMBWPdaZ28VG9_MBsfez#d`wymMG;;Vm;7s(s=|!p zEMbv!GF;x(fN2PbahS$77SCSB-={uxGt>^VN2CDl?j3@nl72|-Pm|oAiK&A54PpX$ z3H?N%2#@Gw5K$?hd}Q<_a|Jd0F8-T#Dyjip_gBQN-Y1u^O*-(dSZ7U#-%>+QKXlc* zSM*Na4+19Ft_??8iuTKWRd%>La+vgpEALDIhXz~8;<|xTTuJQ_(Z&_}J zFAGrPwi^{+*P6H5Oh}&toE|O`#IV(A`lW@C1a0$dF&|P86@~f=OTuIQD4;wVpmYOy zmd8~2UF*>LT}CXZk?=>-)p_0YPfd6)8R)tY_t_vC^N!^eHA7sTWA*WD=-y-}-3+>< zss6S=YCT6ElECOis0Jcd}MHmg9R_eceCIB6H*wL?q@fC zI|c2*{O9}O-`NU*|8Wl{YiBEKV)nh>Kmy;mqWe};O~5-KDF#T~ z*^pWR3mWCOFa+pEwY2`PHX&DVNWX-ru)+RbyzLmqO`XtO`kLxgE~m?kw*%s*yR#4A zZjw<}>hr_ceqFFP3~Xcj;qAZIx&Tu7$~YmgMKf_dD!o5iU}dvakH?nBxyHjyiF9jD zcKCsn=+Y%h))s2gUWD>-x-2wIssw#9Qs6|iroA{)mzGm=zQa5QgKFASk+;u@=7ife z7flD^=nb(jwW<8%Tk{y_`ZOvQJjQBO6ZFJXDx=nX#~$0GMd5^re!;rZ{etYndHeWL z&_W-05EzgM(Q?6jyO}-0t@FEnKe!ZBVuEHrGwBIoxB3_=`hkSPWf{Un&m^b0BCu7` zl@pu;Y}+2eRJlAwb~zrce3D@^gk2l&n8Kk^n0E)h&^0{Ljtq zA)?Sd^Xmydu8J?hXOL*IYk1tsezKcTX0if|6ec9bwDNulZ^<+zFkYImY=qkw$c`c7 z*JkPL*qMadue#n_r&({^v|?y(oE}K*B$zM!2{hvu3=AIybMKLEKGAAX*7@x*uuj74 z?4-l8+4ltIFY31JgqbDddl!qWm~Fjl7>zc)G(VPW8Q?8NdM;MC#*5?2E(fUlz@^M!K=#+$OR3vY^`P6;tS=TIG&0PTU&AqlZyH3Oz9RPqWui)8pyt~c-zM9 zNa8u!!A8fCPK=|*sGK>ox$b{)n#pmVJ`!L>G1ZfS99$t^4rxvum!-deNdsK%%ChQIzQ>vxbFkDe!(@zQ7 za$w3b7wHA9yk$OKHnKattr9&qjV|iqEvT3h&qtBZ34BU^aw!ete z`;9>h;>k9)>O(Ma?Q~?=XW`%{%_qicJ%>NlWC391?Fo58s3`e8VYRJ{fseky9<`+P zB@ANeq(no^k{hy}+a+#V2)(_3aDDN$Zf~W`aN16xqH*sD$1*fXR#Gda)6dlkUYYk z8w8Q%w!SjaiZ!<7wA$}>~3Y!BOELC}$(54wCcazdaE7c48R0ZD|M_WOl zao3q`10(pT1G%0mT%CfLmfY85Wf_Vg^hvpGIPBqh9hVpr1)XRuv>^@pF5oPqr`O)0 zxg~WL=s`yZ1{!sc*WpulFgp0bEaEJ^bT!O^GIRYw&36@oH)19!+;^c*^6A|%NI?bPKGiK;!1F|Zc6+=a)5yLh6 zPLMYDfgtpq`YvTgh|PEdM&5RBK>7(=osE}H&Fx%FMuvz8f|m7Q68)Cvj;BuC+d^eh zGAI8|Y06QS0~4-4_t-Dj!Z~78x7#)AS{Fr7uj;J}2PU4!SdwGpOO7SZ9c#x-jewTE z4Gr%oYV`4z6~h{ZLk;DzN5_(BZ`~w8hU8-whDLx6jyvd9f!6aZGy#BC8yIyjLnSBu zuHu+t%11qN)53`}%GfjdNUC<}gO#T$*1GE3%lC0%eXQ620w$wED3&OPQUP2At0d44 z=y%BdW9IF)2^@59P?Qe#pMeQ?99v_$Al)kjOELlvLN(Il?5OcyZ;_;R@>5hijEtvq zwZD4OxdS$ck5lTx4y2}}uTX<(^yb>c>!K4+M7TW}5pABC57K!?-#FlE_2N_c>1*CW zBKv2Nevue{BK;!672OA+EOw_^^s*yM<{G}Dncota->GQ+VK>)~gn1Cpctv8eDaF0X z7~giC02x6$i-KHnE)uSv=Kyqg!`QX!gPmDatpCRqoof#lftE#10R`_mo zjdNdCGpCoT*niMYx-9^54Kdv1o4jM74Ui)Y6RSqtLpBdkr4N(!JsYH;=>`MR1bDJ9 z_c@WW?!qAF0I{gY)T>TA&!M}B$(k`6ZVGp$@^D}q* zcKThTYhwA#bhD$D!wd#I;5DPA^atq7bQ7OyeuRn1ztHF5iP+>ZV5WBW68(xM@TTW~ z$qIdonTo%5%J9iD&(3?z9t?H|DEcD6JR??it4;qlJJ?bZe%99Lg`zM>M#J8Jky)0q z01Bw1mcerzwzBY)->wSS(hF2L&lg5fJo7~COh?`aN*8X1ky@eU1Vmt_&?2 ziL4(HqRa<=rz9PfYznQ~9omI%7RWxDw{a%CNZK zQFn*@I7~%=YD-XWZDdr%xRW!~kW#5XB|l^n3v91RXs!lYiZalsKh^CwO0xQxAag(n zJgct)4@~@oU((Axruym9{tfE=B^+3>GGveaEDAP097Q& zFe8&j>Q&%lcD4{~gHaCiVtqjDh!OMf_U4E%V)AIk_}a3O`Ei3tY|(hoabJ5z#dz`+ zn(L^2duZVy-yuGXx6g6RF-tM|B_xPZ!cj(lBSkeM-J4n1U0+w+uifjeh|{Qyt5Wmj z^p4-$MY^jj?z?shKa&;q-P*^uj8Lx3h_cC+$oU$}epDXS8H;0xm%-P1OP%jg?ZRIA zg_QPel%ifK++7o>p2Jn^`zg}&rl>$qm9gt8N4(58`%k5dP!=TL%+zSBlzFNYW6nz^ z$)Bm@pUTTvMp&wDP?mTupjf7BmPDOk40c;pgEh^jQvNZBcSkx>>38G#%&-DeW#9`d z39j)kqAf!0zccSo=YX7}PC2PUXw_`{#OzIg#%Y?NfCl@Mj*e_ACSOt9v)NOHaH~_^ z1z13wO|BwPk#X~eS_&wQj&_fIgJzhD=WyEp!z3o+1Y3d=xnY+NC{xDUtkl`T(KV#< zeS`A78#5Y@m~%Vjm>wVN(k8Tuzi9|d;rLDEnU*bjKvABGu;(X44Y)I zS)_JyU^p+f;}`mInlC+cUWLu|5h02PPE&8~AY_DC#Ys851pl%+WSZac6R;}bvL1^0 z;7P3rY_3d^mdQgyQ9+xpbCKKNva&ljyl6iOZh(;9nu6iTnoxuH$z+pQ;H|uQEh(3jqrt28TEYIzOsdjW=$O77*DE7m8)J_7c#JU zg4T7Nt-C&U5h zi-ksqAs$`TX2Vi>^r6F*V8ONe)^RFi_g7l5nB9{C+A{wiDDyAHu;8O28*dMlaPJ8J z;78?_waLe!fBbO3{LlUGzw@L2^YzC6>}^8K@E?S_j@3LrGGI$$cEUE2wPK-iAVzbj zwu3<#6qL_)R5g4p*|qRjN7@8zIz_@bLwIMj-x*@Y#v7$ zTYkP-KbQMGgVNPc@%t-aO`33MLykF{kqk-tc>rwQ&k_q7om55Z%MfTvaR>2cMdZ>N zH-hsoOtwW0l+CJz$jNw;G?pR}EoqGILtM}oOBghzuQY*MYwU)<8pqWc$Kj5LH_Oo_ z-UK3*N{;Gc}RyDcMO z^U&dHQ1=kn`@+|D;S6)$tR+|=FE#RjlgGR;KxoY&;Q-Q3zs)p{rJ<)87fwKKh3 zLm6xSCXBbE1a|N1pZO8q+4FXa`^6QY|HTyW z1k?EI2=g5%#yPnYe|#qvrp=chvu31NJZTg#T*1R-t;PI42MPDQjn8)j}Q)=`J8Ig+jCo zY5^)#fmo4(0GQF6v|v}tYoWIo{VTVH~iPKDz!sYl!-d=5Vgn4&Zsv>7w7n4GoB2{)TH1P?=9MTjS8KXOP z21m?YBx1=jZ*ck{v1`eP(SEGdeov=QQFCW8`QTXTVj+DtK-E`ie)IsN;yEZ++qI)~ zG^M46Sh=skW~rov^(kdg#chSnMx|`tI|l31$-~Tdzw?BXj=RYa!pj{^h__(+NQ&-@ zXyDNXL8N#?zXII1-ld4ic^Rf_i#518(yiABoiDWGn3Jlv3~~s5KomZ%;BdUO@1vCr z{q`$bKGiSxgzio$D3Lrh`b3UF+Sug-z9o{HzCZkukYrYc73ZehRxOBas)Q4IXtc7Y z0`&6FEid!nJ4u41ym|h4qT7}1G2B?!4qpB5whG!OIF)Epf9kQD((5MD+~Y+YJy&mL zu3A3(4K^ATH)y%#-W#2jGu!}+Nm--=5RIo>rgh8UO~brP98z1Yj(E^MNHU7Fq_!&5 z{koA`tm69K}PndPUzPI zMt>$~BEO9|XxSXK0PgW^Vp#_6Pd`0!h_}Bs{h3=UBYlAk&R4c5eNlc_C>`fE=jPHq z)O{4I>h$l0PXPD`LkFvnx)oHr)5}Mgs}Q92TFu7HK7H!$R13b8W&F&VOy_Xdncr(< z;L($Zyd1W~F(WH5#(v}$0V7Y;CkPq&q3BUF_$O$?w_(PS`#0-g>Xm*t-{MZryp|c4 z{%>Q@Z~{#)3dm-mEF|aBEs{%#d;A!K+C$8n=1?jA90^}kbH+gNoDuB2W^8>C!7uA$ zK7I|6zIRb_#t^Fd(eo_$M&Z*{;dhryD#9{xYyOvYX=()SELg-5X6-&<+N)}DNse3@ES(HGT*df!m8S^C?DY{+Omhd6X z2EPN)PZ}-GQU};i!H1Gage~O~{?bNEXXy~wQQR!h_|Y>kEpr!mN$lYwk9Ux*3I0GJ z^A?q#DE|F%FfqtEX*U0^iZ zCIh~M)~_z|)(ZlS5sM2&XY5IKrn9$k30Lc$i`KSte*#hc5dXdzE7Qt}|ATk=={d?Bt7`YR3t`%i+YFr=tb|x^8wWOtDrzj8L zz!7yc0XP$=7voPQ4X;XTYas0q>fMFTsz732CMAiyX2H)n&K1^DvmJc~?B`m`CyI~6 zLa>UcEHAqy?RX|IFs8EMaRx}o2K)vEj=)r(BwfIpJiKI8Q2;E4{t^^m2F;nZGxyat zXkINxiWc)QH6NjDzeE0Gh#WAADyO)VKCz&^BLqt^mDO$e8SQ3P=8yZtcD~X8PMimP zp=!a~n|o?MgrG3b$Id={ZI<9Ob8UFAd3!F-Lu}_~2g2Dy9D?ga?dAD_Phi3NpX!E=zRrQG2*y zSOM@-v`J_44ww~G$bLL$Y{u$Mw?vWa5lSJ>%hXfS*&@kU+#ld2Z0OW~zzE@JeTux{ zGE#7dye$1DD;jJMgiWjmS5;xV!LQI{>7j`)h;Kk%?#AU*RNpM=(;&_uiJDVN;tB2V zCDA4=sK=y-*rmT1O)G(a(r1|8+YkbKvU+DkYEMi{kys2NM+;B!05DM@U#;|QuQKb_?f=bbChv)`~|H1U~`^elc+=hNcg0Kbarsl8Y72{k z?GTGLU*0= z;3NJUq5hwz_X_{773;sNQx$6e80n*bWin61UnKJvit{7Gvve%W+Y(Y7%tEPRYOZ0@ zs@yw!S<9}R12$v|I=@x?yMOaLhZC6Cjr81OF(?8j@jGAfUh;g++|qT6>X~2TogTTq zXZe>~94~iQdU(LcfGVP>_Scrwe%eT81LUi}Qw%VB;fymuZVK{kQk=AV;Q*e~=Td+K z&V;*M-y5f5bI}ek&e~0`Y=-uTv<1COy`iQ;5FmzmoSxYGa`IO;0qe??zBl#0^vsmg zRuUTqX9$iP>Dbshb$IznqGa@iiPSnB?uh0r>iR@9gl+IT2VgLsiG~`mSsdYzuH}?< zU;7e%Fh=P{@+2aV+PMd-YCV?{EyEv%Ya!K@vg3YuA}_m=QfQrRqz3AtpPpAmK7Q6a z(SU-!>thTlWSKhNu1+BX;T9mLA#8!+Ds79BX!sf(>d-~b19%r5wH}IouLL8l+8GEn zOw5kOfKJ2E?6)s~WkYwZtaqtwH@`YR-0@^Z#BeFN2;oI;Rzb+uZf()6CFGzrv%XZ* zR@5#f!h5h(wXi1nbR0kKTUDX}Ub97bEulMRII@-HfRq3fqqE5(gJs2|QZJGM+Ypn0 zdzw|j4L&o>pGJakO3(?UvIzrrRk>~DIvMcY4HppnNu4Krn&fH=17mIJSyB||$-ko& z*TH9?$q7Y0t%_V@W!zQ{UZhxy2qzsi2;&@=VFw#JXJ@Zi5_oQul@wrwmODOYkJ@4Vx|+STcQm$dE@Al@ue7rglvMJeLeLHPgs`x zQ%@0A2bA|fs8|RqB>GjHW}kk(VivN9TIF@@5iEc3-t&$eCTU$_Fa-9f8> zdM;UvyQf9H0vBUvW!s|p)yOP7aCGh~>N8^M3s&(67eApeIdKVa`=)-L#kcAra&}1T zlortjQ*-oPmr$M!-zy=QEB@Jh1_>i+7S^9RFp(d@R7MPO2%3xm^Jc)#ccW0kL0|Dq zR3)iM$Xq3|Hc*cm174rD;^{T91QPx=L>NRWC{D}o7f`eSUpI!IW(iLg7l98e0uKRt z^SnuEVfW|WP|~)90$t)uWF11YFg$W5?#g?8&7OM`bIS`2DYN3Hj|^)r$}i^yR&#X@ zx%m*(+Q%Q@;Y{Ud8JD5i-3Tr|Y1Bk$r$=n3$3F&aerMi{Vs`hno}b9;)@8aaVGR>$ z(Qo#he4~`PQN;Nifc+Xzc#i_pQdNT4+4HM&fVi`dWjB5BI~_=NTbT|cYw$-!F+|{} z{5G@+m8e5!cpbag!b+snalVc=hx%A)WG$wW5i?|;%B}*zD2M>`Tua~%c!8hLSyEDe z$nwiuJermSoPEk?-@CZV$6T$wnPAk~WNCVNa=9iP&GySe32(J%?XE&f#*kJIXHXL` z9j&lpUw79(iZ_pqh!5}gXg&GA9j*Tlq*wn1ZmOABn3?};3m`K=>pL?8dFX2n%4%#> zh9*F*eFn<82A=q*4D>*O#P5Ps#NN4T=~aRY=?z<`SCeUnnQth0GwurNO^<^2 zXnZuz(e*OLVdne({tDBrL`}jF`G#s5AG$37B*Be6NW{&07#6%jOkFTRXhdK|U}g~A z!;4z0`oz|9HG%|aseQDBwR32q#a3fW*KEineL9Pf6{76nDJFE!$LkoSuP05q*Q4*B zdmE5WB516H1MM^a6VSvt0ld?32o7^Ao!BsjrE)1z2b;;zMY{$~<;SPo<{VkVv>6EL@3dYExkzKTA;ErD53Ozt65wv{Hm zm>N}vUK882qu*21qMic@w`*N4}8osU&Zv{zUC@3rm&M_I?YdlWz0;%Esxc`kc9JN>Yux@3@u~|QFJd>bAP67Ff z2jsX?TA)?EF4-qp6_)1A>L>JL)% zPj;?g_7xLCo_r@Y`Un=x;3G6<82-rSVcP(Cl)X)$PjgONGAvrMA`{y+%*`ppVak_s_$F)Tu9%>-W5Bg~-{Pf{0X^>dkLeEq+NsOz8-_($7=5Q%8*y+Am;V+zgd{ib5HIf)(mi*@%G5uoe^bzG#j_iv~y{z<2DTqv)A`9GB&?j8-c} z`NAm^GWC|62)LwB2f#=DYQm|=vMXusZll#EyoL?K5o|m!0Q^WvwHgxl7J=wU-PKfn zN~5Dlcli8-hO;rt=@H9w=7dvq_B&QwK7#>|h!E6r60|tS7Xg*xZzt~K@ip^(&+P!q zl-qu+32KI|g+Wsm9Y%=roUJ86csOlcR}L3RdUyybLfU{ODuT|yM<2RK|cfn6{Y{~B1iHy#ZZadS_fHIWDvA0hfGebpnRBzT4r`K4l4Q389Y(#v*;GxHy6!9PIP#?(sjTc3m{(NU2^P`1nf_v>>ULS>;jY1P%Ur#J<^ zPW`bzns<-eIiM{frD-tP!p&k)_kP8pe>?4@$9l*H3bxv8^~i0KUn9}42uIX~zD>(8 z_O5wok&XoV9Kv6j#?eWsMn+}?;M|2TTQPoU52=PLlK=Hl;KrO6yO-9byElU!bq^zV z(;(q8t4}AyuxmeIs#d{13S%`|W_9FrN)2!~E9o}LU!zVNKk|YE9gD+^AUv8nPUn~_ zAPBUyhcogV=_6UAh)uJh|u|`Q}%C=Iu)rf!jCu9}c5OwcVl*ey zfkj?A+eAy3@RaGQ1lcNA_fQVGl#hb@^)e%-r#i2;&TWI~!W;qA+m3>Q%d%&#cmP(O zF%=n5CsJEGq{$MHWPw|y!YP_Vdb&&UTUsyEkZ_gI; z9~FDPrHEMjy@<5uH0+Omo756HMEodwDJ&jylj?A+sLY;%wWZEcCZbs2#Dop7%v_WxA{}|qsJr4+ITV8s0 zF}pOaQaH8DL*+%ohN8Jhq?}YE(G$S`gDG^)D2Vh6{P{X`W9`6$z~qYBMy0cnvVI%4 zGUVF!{KlA9`j3F`k~E=X(Ds5gCkKG!1VR~v9&l_z&2t3hHo*}DxlV>M-z??>YITiU zk`qv>IWxEcnOpBwdYNbVvoao%`7@cvMu%)8`15b#IcNTCLV2j$d_rws0%9Q&<-pZ( z6e5_JMCdExV{Ttc&NCtql6qzPgwKFmEPQW=dp23_fRiS1%L^hU-THR+5XL3h;jbqA znCVIIwS)(5x3c%e2>(iR=mCrwE%nvr-!{;4d8gvs8R$c!4DDqMh%wUmMb)u?vtZi7 zul>!)kC9b(G^~4_5c#206zkz~HjVs`aqts=$Q3xmcEL|on3&H6)j^D*Z_A!U(qcdQ z>+WZfyt5V*xdIGxsVt4y|42p}s2CA9D@B#mOk?!#?WAJH^v_=~G(`7YaF;tV|1^fk(DMfUs1BolI;;IlHbw@$qL zAR_q;TYqD+9nd=oWUImOBg$e6`@%!qgT4IQV|jvu@Mwx>!}MC<)+h^#GmsOI6ifToQnf zWP{zJrQ<}DFv*U_IjDOQB06b)ps^$RkiL|viBDbaIK2fq)njaCwAo@KhHEr|0}+>% znMr|#E0{ujo2b3EB+t$TF6ie!4ZJNG_mJ+tGdyuo{xkpc@90bO{}1|-HgPriPHb~D zlQD4o2lg^{{&(!<3FWQ4F!Mal@pMU*K5++VgYbX{q9(9T%b|h_4vTB&hl$B-GUE>i8@KQKo7m4BSf%K1%cKv7jGJ}PuD6LQKl^1EyY6&c z^`BpT6L{R!h?|Z`_pEGJ_II>wR}Ob#q%TNpeusy2xX)DWQ%HV$hrqVH`-eofpDF2k z(oYO5zt(e*g25%_Z~2LU<}n=Y_x1+|qPU=VQU~gEaZQ=_i8NCCWN6tuxZ|$a>)4&o zCu*XUJe0ei1&0E!ma(|+erLWPi4Iw#_q-c|xX*x@szvGR*8MOwHa0+rHpneP`mm)Q zL?nxT(5FcD&}U6%Dhfz*SaZvmz@q9h4j-sI ziUl^3zjTuKWV2!Bc4C~o^kf|KTP$ptQe+mrp(NmQaqe_C%g9&KkAoII)Y0Yzf7dqH7B<|Kk4fn4g z8kP=Lj0-wgIH7}!Lsmv3ot?&C`ZjvZ9ln}2j`*3!WfyXfPl$cyrLIaDPdaTqi+PPK zofMmLimhvTB~d~%%4)5dYQ&Qf#ioQoKwptgMzwxO710R{m`g)OJoS-HJCPc|K^9~^ zzbDTU+BP`pYxiKjc-!W_R^mZNg#A2g7{_pn9y z1sFPNvrXBC*=($dk^^sZ;aLt**l2ql*gqd=T>1CeC2(+_6%`{mA$d@zJCmsi*ou}A z9uAF5izhG7E_^jf*&9UWO8S$dqbTAP?_wI7h$M({FB(*1XImPhi6dEs8SX$ViNRnU zm8<2ETWp3ofwo$OE$KJnql?ewqsJ(K+y)?K#CkQ?$dkq1+{NpEqsYimop+t9I8wa@ zh!*QjWkSAX#Tlix`GeIEkA!PvY%qj>o>cCe%A#X6-6E`#BA*QlFhjl}S3KCRl{0_a zuu>+$unJVXuI$SUBoQXpeYo6CZLY~8?MkE9dh3;h>ICs>UCsL;Ia*<^2 z2hhmCkP?Y7U*8f`CFqAe_Jg*OtV}s?l<5H5+H?i_sp%2TE2qIQk!L$aDe1hnuPq#4 zfx6r<#a;}NbD8XY5llDEbmagR-Oyf5y8h;qT~gSy_E`L1Q{5W6+(>3#H9yUiD7nM@ z`8{{A=~xXD&=wO2mm{4z+)=HZSR37Uy0$6EChvARh(Y72Ki#hL(7^Qb(X?tNBJNr& zhCp?-LlNk({R7K6VYsU2!Xnz6(No+FP%@+lUhq!Q@HlQ}{t)hg$!ebtn0T8xeSM~8 zHupwQIiT1DChA3vbuOHw>bP{Em=i-UN0gIgLs2n3VUMSmj}%4 zpM{fDVLxh=tNiz*5sjz}RrA5*u6?D2Pc-!uzbWK}FHV*f{1WaAJkUVOK&zh(ZWuaa z25I4tjbaJC9N>GdhbDOg$xz0PjDI%?o%3A28f}z)8)A`Dfqy5<4SmQNkt%Jce$uU* zANZW=@PBTxq#$ZA%d|$HS=;Gt%q&i?wzk%E zTbNs2T1Pv3AIgep(;AG^Ks(N z)~2VBV{-4X{QM_5q=}SmNa^&!E(#3>+ITQ)@bLvFGY*jal3Cz>7Z9Di`1nE(tJ*F3 zV>sAQHVy6vj`F7s9RV26iPM)Nc z4RaqGC}26qoCf@DF@~&)280?=|9JuYfzN)aQU;hu!xOl0%lUEXF9YIH!BUOUC_nYy zhzNS8CF3M*Mc+k{ZG3DDa76Cw>)#DER5zxn#b9*C&5(_3?aK0^Xy-W5L&4CS$|rUMe%>J6y`D^VXwfQkyR2BVshQTR<=;qWeFEje37(iW!Zn zB@6#3%U8{Y5G;^z6u`l8iDSXsgR<(Z4&26|wOuEfcW)lq9UN=6w)I}$j|FiOwRM^J zc|A2;_IQNjzl-q_l54CH#dn1tnW-RuF~#?zaHrRD%a?pkP^3P`dl21{>K&A6+)|h0 z5`SeO`)tbZ#~{=)oC@PU+dD~H&$Snf-@}Kz$@3XupYQtJP5OfGl|X9FFLOdawwLP< zdE@86TtgsI%umn2-$41xx;Nzt^+=1;(er7u8}NB2f`;g{tPwtIb|7M~LM%Zi5HTz` zhw4t&a@6P7ZO~mB);I3!&e#DG1|cWgpty$Hn?^20`5_YrY*0RHZoQrulnj#89jcTa zk^#9jlAFt|_9Ysl!e-CC2aL><=w^xQU?!$5ieB103e&bj3vuVSI}XJ6By)Djcme(z zmZ*=!a6S9ge$7GGTg)Cun>bC?LnyfZmVQ0DBq@)olA0;ka+!#lieh7gmJ4H@_F)=| zzm#0psqIp774zp6>x4@*FrkxPHbga|6huv_NM4Oh4N@gaO%v7LMz~7f516<=+c6G4 z%P~Aa%w_~q)3y$#9^c+Mzzs_2vJVyv zS)^k;1eJ|L){T}E5-CHg#bdsWLpFMY;t`JQDbSaHKwYZ-YSEn??M$3ZY&#R(>~G`L-uK?` zp1XIQuI_)jt5TJ&^{!rPz3cfs1y6a5viiL9X_kP8OtmIs<7{h7R<%LY$P;v)iG`dS zQDq~Na^WH~b1}rPLZiManh-1VfU?R+BBTwx8s^HiKUqEeJ1n%*XGN|dr3>?noV318 zl?B3F(^aR;Hf^;Rk>t+-!F`U7rpFr&6pgnL5qe9Z!RB*IFvPOTXW>*=B6$=`?1t3j6>o)o{{pM$TD=vM8wX_!DER$4Y;$->T1ILyat+GlB}n- zd!z=14yTvV@8Uh-{(ks;&E8~w20fLrh!4rWsbZgO3n| ztxY}&1wVnNHOjJ#ip;G7kTM9^*h!i_)wcyLH)!&?%TlPc40hVH3kd-=pByWe;wg54B?{dU?-X5fOW&0S7RU3`qJBg zGwUIBtQdlP+hTIQK+{Hq@CNQ3QT4+zZ*ew*cpYi|f|)vReY#*7`@+k=nDrxii8KD} zlE3gE>~DBb_k?TggnJZ^_0xs~YD5EG*qPCL8H7EmxsrCwyY!oO;0y3uqs7`p=mxWm z(YL7zJdz^z8JI)iS_=|P#(yDg&-v?@A+vAd z#QLe}hwM*MTkJSV7CtlDU7AH> z@Qu4Uvk{H!Q9C$Ijq>qLrCNH167iQz`x_sUdyX*=ZqY|-IB=+H{Z`&H5zL6J3RgQ| z+7<-B3ZQ9Av`#j@YvFrg5i%)9fZ1qlRRJHg8Qrz#g6|P-JoJE{3a*6W#Bl!ssw>x~ zyeVG%!X84~FDMcU9*OjuUsi*n;v~JVO&Nd=FyHh5gjfsc>yXcchg!EN#}%U+m}S{E zA3_|!afwx@5#bua_{5r1P5?DkpsU^SQEAMH$_Rh=jc+E#tR4 zSFZdRTPCN{J}_^KYsS2EBGpykrNY!XSW^|rfkj`SM;LGmqB%652jNXtZ;gV1399M` z-VMZshWTmX1ILN1D))J-(UzWvV>H3LixDKfBfk}*cLUD^P}BixMVXmR$<>qadLX@# zTL32xpV-|h3Jm!6vWp_Mp(Om9{Nu3bRA(F^LTQ@;-4g`Nnr_hsJ{`-$lFc<9I}#Qk%Dch}nyksqby z%&sog(bKVh8}1n;8BycZXjNhzv+vOhzgv8!*nOJ*uW4IuR4+-JTq^;r2}?W>Y-21_ zkYJ(qW6izDLJQuH%pohSWkUFN(=od?D;EqiL-|7*&$eI{IL=~tP7A{vQ)BAg3c8!6@{R?SR5*)q#g+uSHuu30xcG~m2_9A%HK?^m(cg>s z*fU3e7qxB86GGyjeSE?hFMj3IkxouHJX+hSGaWqIgsoHrcO?rnest`zHo*sJONIfp&Ifk=C-{-LIylVA~9u4;T2l<%{b z+1n5oa=4OyWvXDx6~8KQ3~Lczpr4ul6bfrPmM7?`YMBXc?Jmw={dgV~rs7Md%Vdj` zbe!&*tu}F1N*x9e-eGS1 zaY>5JKm-kLE+jsn&zd=%Y;gqc(GXBsrt5_RF{ZEjh*YBupl5Y1`#}MRJzL>pe?USM zPbZS5i+Jvc`srd?5kLdnjWk0c)ik9)7!+k1;bwVRpnEw07xv!d-K!-^voJ}*VwY6X}RraIC6Aus-TEh43c0X!Tlk7U>SutB6XFN#adNeHHH(yh4-CeO2tx zB5q-2ibd`Y!Ma^@=_)1P_>pI#6|Z%S3L#8davCL3c|cxCc}2uK9u6}p#zI_)@h=$r zYkcsw#yAw>*?>u`v7KDm6jdXkX^TTL_+?OgRZiK7k{D(|3}eXNC%)?wHt^w7!JZ*L zdixp$ddC@C`a>wPKQ%|A&xX5DPPz%UpA(k_B34Mz^lKI9;W03N4GB}U$ucuMF5xw| z0RKJHsP97_1OTRO*o8?Hi$YOQY%1h*&&9Ij6OS48R}?ETjk$<4TOYVF!bP56s$~#A zn>#1?Rktw#9`bQtVF7v$irr0C8e%QVm0Ug0HY)6{FR~Cd&m1|=JiU6JM%56rYFG^B zv2m7wt^xy5$jr*FL$RK1wTuy_LF45}ZXhYAxjBGNcBje-GrdN10z2Ma@H z=+HQ}O_^*cbyyvMKCLU~UyHmktTEgQ^|$7wW0kQ6HGJrC4;c{r!adE$=oXPWEPo3* z@S(IxCV<2ly}yT19_cU<&?YC3;eAlP$LsW~O@x8WBeG3pWJs?;W0Sr$>UunSi2n|! zUSnJ6gP*O{V3QIt^6ik+xc5Djizt`;MGPR>!+9)n0QB2^~LcsgW4QS&euv5Uu!9Bw4c|5A;{1>1CKidB~3GWoRiC zJ|N+z+_*)@UZPm2OHIb~s4*0kE?O#fC2pbt0P8j6! zIrItasvS%D&d9qK!h5X*%-sTHtRk{eYwjBnmhf0xrwlcIBsXGiW0=rQ|fU1x| zu=G1un#nk-cG??@8_;dY()9#HH8A{Q)i{_vV_~WY87Mg+U7Qn`y@kGfA_n-Zo#hEt z;=Q15RVw~60h4Y0)g3BPn`VYx%QkR?xq&a;u z{ow;bgB0Sex$1xh(NI)=EGH};G0M_iz65AWoEfjde4s6ut{Eb9DEXNXn!7WaQ0_Al zG?Yi`F!>}NIlnhBe_7L)6(ploE1uW2i_D3I5`stkAZIAHY-E`Gu$=K{D%MxOiUhS$ znQc`s)88uV$01@$Sr%o5dFp0Iw*hx*@^L9URA-cfYgt!bTraWvR;<_8&`wi$6k{`W zB>?^S^ywx3`iOLqH%=Qw-4x~QTY?2 z6puq8O57MUiNqY!5fjVd?E&1M{ie)!P{r-}0OMpnpK(nspA zn>>*^{Z?G^c)XQYdB!tBC|`?n?)^?YKNP@8C>;|#}6VLRawAjccAX5Nu;;J~#E}UoQ;NH#e}V>R~WaPU2^Jkg>HBP#M^xa6Ok`5Ss}G!K%ZjrBZvoR#AdOM zlTsuS%TdCw;7SbVqCb|Sshu*?7!;80mfXjFMl9;aXGtk!FAk$G8HfO)3OHu+HPwZY zQwo!k3M3n&{Io~+DEew zWqH9KrPc+r*iiaa*s2|E@8zduLl}0v3mu2&fm0QnON;H^-$^6ku`6D1F!d8$q-|*V z%tsgMD_@}DPXO_Y0(!P_S`*vwF%>BD0g~&J$O0*dOH0=>bx9u_`j%e7s-G8+XzvG| zi=z)tWDeNcd{Ul6qOG|Z(QEV< zGd=tGW<$?|aLdVx{dVQc>I8zsTpp2aFNjZ0G)q#PN(EBdkOg zjPJT9OFEWS>@44QtGp$I>nA~~E+IB9?K;;}l(oBeEA~@SQ-A6|vOBT*YpCUtH#*5e zLQkHZ%2$+GVKI35l+*1Lr0RqL3*L5+7Hg*p36YPEt$}Cy?&_}l^&}{4f3g}Kr5@xE zY5eHX6{F7TBqc3b^fpvdatVzr` zIDQAir=}lSeK*;r>IYtUhXccJP(0^MuTN1sNPF<;QQZantm3bE)kipy{SwlJ{HNek zLG&ItC634)I`uv5Fa4U$!(FaK{;t)d%)sf>Z)fF54ai>QUR+#6`ZF3EN8b653`cz$ zX9}%id|j!-wb~`Mp0paGTGw4QB-O^(7fpx`5U(BVg2~}%Bid?h5n@wVeUM(IR7YI< zLPb{wE~eb??e0A%8g$~S6kMHM@0%i3+lh+h^b9hsv(eGjJ9b`-77NVb3(-Y;Nt>i7kU-ozOwURBGjQn+foq)Sy+ zBaNTny|kvWLawmo1jSyT%fv2Rqx6RZE-Bw_AzsF2p8`buAbsvSnZ&oHdfYH$Qr!nt zU->QbKIz&qc@Dbkq_2WwmmDZM?3{XeW>cCnrIIn0r1}!!RE2I*ldDHXN_n6mQ+m5e zIYMArdnvn-^p$~^giI#G1hDGts9t*E)_Ys^@~WU8R0V;u1xq3TKp6ZGui-|_V%g-0 z1v5gLe|I9YU%7xLNt-GQ6=?`@9w*;eWZdjgbzvAcHf_p}xwBUpHZqO&6vrOQhC8a; zVD-n#IP~qHi7JswzNxIcLBkjeM{2`Q&o_UfUf8{_Tm!xk|78(RFqES_ z7#|2Ifc2kU1*`l|u7V|uT%Dce&D>oa?ElLhaJ7bw2ik9Jzghc+qzeR7Db3BuZ_@_5 z2HoWdaVJZ9^T9djOM87m1SD`vg+UJbk#6akys%u>Q(C- zi(i+y0`b0o3%~wuJn^&21c4`}adSBgW37-H$d9E= z2H}mM#e^dd;5*eTAh?S=V)jtye>k=2AUu!l>T~Qmxzo;c=DV1aI*5q=E~(swG-Az1%PgpVQxKF2CJpOZ*sby70u5@*Si7WCD6hU| z%PlO)OMW&6YdnUZ$6Dw0pzJEHN^YHd1y8PJbvbPp4p)7|5}TRD8{Wd#H}{8BG`}g7 zYE$N~c`Yn_wk!f)CK*|?&g}U{-wu-rS7fcdxHQken)YO^mXzWjTT*e@*eh;{-VZVS zmS^ftjrwE9ys?0lmJYIVPfB=XMV1~p5F5;$h`t5|olZvg?LGcny-j-OdfP_1$;*4Z z^TkGRlT3S_bI!S_JA3EVg{>fw;X>GmF=6(}AKR*}&Vkg1^da~D%B|&rVpD=uqDqPG})u$B9M~gvQk|xJNe;w2DVqp3Y@?GQR-kx`s_s zhQAMEsmz_$=Nj=l&ePl#-KiWbMol}mxhM@PgLVbtGQjDb#m?xN`vfp3y|lgH1uXq7xSYJrs}O>Nj<0!G@EvqSuyqF$@D)uRcEzG z+a*`6Z{S!vXyI2Dz@swZH>}_iYVUZxinkR*T@=syqs-`| zhmIf)bruXnPs)>-H1fv6!(`jaj?%+K+v?1ri!|H)*ntPS>1$cdtlk!9!cly@h%Has z3co{4--@FQc319qwsJnvuKBn!@Ff0F#(u*yt-Uq+9aOu*onf{$ZgudCaJ3E5XGXYD zk755Fvy}!Rs`^C4Yr=nJ_b-h6f!<_79A~pAnl_fw^l~fQm;CZ$Ts%NrC|~x3IcdHN z)tzxmo7dwWymk5va(O2eP@a#91;PJX@ixeF=)cQ=xUVU+*mM(_?c8d`ba6|D1sh!r zVCZRDr8w@fV|eYMD(xbut-ci~uYA@fz~qh6n8;Wg(m(r@oXX9x%gNx-u4#;q@9k)5 z@uD#hRporUcy;p(wKBsKX-VK{#p=W8Byu-y(1xjD-rDI#=)CkXZ?%H8y09Uodawy?H;NLf@U%vT}XeHH$0Y8~}E9w$9K4$uP2XKaEGt zvtoR#X9Z(dNG+{TA-fG*>tMST;Na@?D|~bKQyL*1du#Z)ziKv9%K(by2XArPr2F&a z{UY;qC`p~O-_hGN;N#s`hb+ee=WU74c;(6K_Pu5#$i_TryD|rzziHe}vJXvbeq(KE zvj^a=uyS=(^VAdD*}1{P`P{-;?Cv1r4k#2Ma`hxULQ;rtnQ_uhJ^J+r`y7%X!N%7w zsC8pMY;npM?{1~Lee;25bK&>eR+7E-`9;6l`&egAZr%Gsq5`yVamZ`K4Ma+(<%IS%@73D9>E>H#^`?MH4 z_KeU>!cc`27>Y)YsH6CAV~5J%U#`k_sipRz3If#(ds>Wqk~9dqd0czc2x#c7NTW8P zr0A)-!7P4^BJbSHk%>cK(i<8*@ndMhA4!TcC`!xqXHyU}hvkXui_#Trt5{K?)&?OZ zDI>z#QZbb(P>=}%NGKAYAMVQH%Ea_8B}&NU4TdJ3Rqu6U$d%S+<&MIza)wGYiE|{V znpw)-u42~nXayhIlF_opQWbP1inDuZC@R|`W<+YpwlO0GOD}aTR2clB6+p@|Wqj*( zHOeZ7O>Fwu1|9BO-+z}6Bc6JpWw`#OChUd9PKs{3jx$LBsnm{8;kvXbO7s11GDhtK z^s*Wxu8lFfKqW>cu?@SsHQzGM_!+dv^^fHJGz@`o8;ynHVr@-Y-cU{GqRen4IWjg^ zkVy*1P<1z3m|MSUV-#(g3=heW#9f1f7qIvU7CxH2tkiuW0Q?mSG#_=MhxBGtsTgezayA!L%RYBK z>}<66Z4g%k<}j>>RM*5Sd`}a_%Z@)RWAyWF)C-b?nO=ms`iS(BA!;?^F5bsqnEW=R zkaeiviryePb?7*Dnt^U!nz8X(^x27VE%EgOEymFNb@j2GDGw$gzImWBr?E4OCx-Qc z@uPhBN`Q!Wl!}6E-nr@f*oF0GzIp+={ORT)dognQ>OQ*@3A8Y*gHy!1UlPOe7kl<# z;0Z^s_GZIZm^xTV1med404ix?%A>z#)yPVDCQ8U4Vi+!#;IeJ~-^pRfVRIEZdTb{! zMOt|;WVk)+TOLx1LVe1(J={%tv2YKd!4P4|#bx9L>J#)g>~r9!;QQ>sR9YSNAAUx! z_`w#+d#)*mRX|TsOr>harcSly1U0w!OrB3|D>mjGE6_6zcXSk8SBKBVhdm$j6iuxT>UGmz;~i4(?c2L?5gzPvYt|5Dr;tJs9;eyh@R(EeF* zC-dJZ?&KUy&20bO2|@bbBp3gRC8ZDf%7ZPEChB;=rlU+E@s~ys=~}FBDJ7b< zQ-ut}lHf-DZB~o9PF`DKtXn6DcWi5Z27ll{Pq!jSa~#JR7s6i}zS5rAgx9#ov1{_k z3yc0B+%w6Yo5K#b3m2kTb^%c8WYj}$+zAGa+b?v1iJ2e^WYWOlK&RO&SRV(rKVI4? zthnJh*5^fEhZg5Pxbq>Jo_QnrcUVrubuKu#Iiim)MV=4*CRK%Gk)yTliD0Km*kh$x zmoyWa)ddlWeev$xM1k$4(v%;_GT;ZaCrLwRlTB-&PJEg@^A|?32ByFuD(};ja(6b< zw;eH7E$C0{7soFKR$IbN9QHpu<=I(nEx2(tErf#~>uvTR`8Bk^mNt_Nxaz~dRhvd|9HesEfJXmy%>%D|Iwr1|Z?fCv31 zMe!ND2Ck*AGMU(Tj`Hia>=>G$>`l<`7s=`>7)i*h9*P{~mSme8Qs#N#UiFGowk)_R z;3d?av7APi&<9mztUP~(*kS8My8TFyo_ry>SrEO0?9aNaNZZ}H?kKTP8*82iMvjVj z)|2wfu>Q&q423(4YwF#D3vd2gw@9s@L3U@R!j0Vf!s#GtfV3z2L~^Qf$3D0xR#0wo zTCSNeL|Pq-PMv0|u44s)7;<%Uot2FuUau@n03Ozz4Ngr0msjSflZRs; zSWzOW{Tn#~wl$Dl5|OfvU?z*m)qWqCFha`mY~bRFx#`4Ktk4%gAv0ZEhCRiz&<@-I zAm=gP%NBYr4!$gC+}C?H#&Cm+Jtf0!4W|P`c(7`aO+|zY>wR z25Y0B?czb!ziWk`pY?6!Pj4@XBkH6S88c@PvQN$c{lRpTp@6~a3ri%}QBo1@D%HBC zA=dV8&32+LbMkVNfwMNqq(mkC zVVH6yiHNZf4fZdryR|`)Q*$cZnFe*c-IWlhVJE#d#888*3Kq>tFCC_s8Y%J~EB2O< zuK)+nCYGKOy(=|%rs>XTbS{iiG2c@9O~tpFZu^zi~cjco0+xJ|yythmct1FT~gM@m1p^!7@wC-@GA%L64* z@E0Mu$bILZLNyweHc6 z4U#6%?${jL{nGGoaP9x|cOg<MPGWo`|Hwt2Z04=Hca(OI2om`Nwa|$xyXi%(gg}$siv2$ zV&>Dvz~Gff8JBP|;iy57=U}Q&`Ee$+^Se^0Nj# zGjNl6^^#SuEQU(_2NmH2#mr3-3IPV2kV$8QMK{C@KR@fO9vBW^Ka#710X>2tSKoAq zkI@9YLCUru%A-ve=ub%-XdGAybDs{D`wF(?R*EXvSw~m%fsE{Ui#>mmTeSUl*>^-T z{ee&L`eQ6lT2&q21!K5FfB;&GPbzfx#CQZe+%6U_{_xZcAak-NdeV`3iNAE!gu1CL`9#0H}N z^7!XkJOAKSv3RQLCw*rH*?)?-(fe;?hW{vmM=T%g=F&CaFfaHtU8lhemw8-p(w=R2p60JS*^E9y(>k$WtCO7 zxWOVTJ!BmpyI*r3|LyVqcoy^*fMAN1#-sMh+oQ9mYAfHv5m3EFHdhm6rp)!Fb2vV{ zKuuxDtaoH7c01O_<|JJ1bQ~J@!SR;vj>soo{DEO0jlYgA*hJHg6j&vH@qlPi@zDP&U z9ds70l|G%xOQF_NnI(^`>oBclqbbW;>4m+uz)))tMxDJYkds|^NCR%9GVV0!_?9p? z8vt*ksZp1|%OJflS`xP6s6V)}x^Tn8U^(_fqpsQrju)p#NUFaTr)RJx$Qy^tjXl|j zW$FPL>C`1FYA65!@^IzeA!&CLP@A-S^@EEkE5CuZm|(c$=L}w^YBK(OQxy*lr`&uI z2#*-~!*Ss6*3b7G&4las_^T6DfX5h6Q! zs#ZWauN3h^NBm<1GR=k2%S0~iUrtZdDD9<+1-(QV8-;6%rV6tJKYlyAc!nf&i-g<{ zA=QmH$Xg+VJd>JC-!WY6V>=mG_4+SGYN)IQl+XlEm@x|FfW#uUzTWW-iP*I%V$T27aQFNl& z|71L+&$q}WN-vxrNw?4r7r8o0prYtNV#eC7q5cb!@}wrJWw!ysdBZ^(Sx>^lZiUwg1 zQdkrzSRoo5_imx|dm2-6F%vRQhWJSXUcD3iauJVmEw2vS1I046#r?d$>HPfp^7@Dy zAi))bv}YcovkH&Qt~h!Lh=TzKS6Bu$v(p z6fbD<=^Ptf_;yJoRiI@q9}^#_07;$cllz^u>uG!u5}httnpjFP8=G^l+jeSVZ!UkR zi<^y{U*|)uVnIjfh5Wr=5_7!35UQd&I7f6{hlb_S5ju1-L}yF$r>wxp8QsT&;a89_ zD0d?Zx_l1vMVF4{8M%aYjpQb6b?lqmhI|xA4mAI6D*FeP+-5N$`aZ$cs3j3e-_6BW ziP37;g%h7ZDHiA#P5;5gxqSC7O3xar!*ljazBv`}F!KupI~3AbLl&FsEIw z@HK^TgG~s^0Qz71r=EbvI0nVnxHAhdLf<2vHCNT~C!`%HT#p}^mbKO=w!ojiN$kas zXz4pfU)U>74huL#~kGLxM7EWyg`vLz;(}D&tWvTrx zReS#_K+)p=&kvHbiIJ_5)4wv;{*7St?+vb;k)xxPy@imek)w;56Pdh&u!F0;sq??Q z{U7`_6`g;Hp-=P1wQ3vNMUUF*7H!LQ$Wam~W#pz}q9SxQh`(HG_=(h=tdsiEZDNw2Pp@yI3P3IO1bKmnKn%ZpHy;7Bqcp+KvQ}z* z-*^sANVuz-NU}j;1uIWY3X$~3VWtw6Bab=+3}D8A#BXEp$v4V z-X){_n3g^1czsb4defHA#$yCE&9nUJu`)reL}azqt&L3+LyILUH->K^xS=-JBOn(T zPGXCPW^22i@;pnx7;C9;7O9Kf3}eFAtk!J*x+r{fPqb;L|M@mRXvt3q&dz4sBwynF z@kTQYJlh?@w)YG2?IKSDnU5WpR&Mf=^$dg024n8SCIb*JjSX zj^XNDahqJgx&`+3K|#SX4VzA3zw0KZQ*q<&7`lg&vd{-($KB@|WjTxN1a6~$^AFz( znT7@0If zOE*~Ya`&IRYXz4FYCY4*vayp=rFpE>aph{gcL3wz0o+kBz|AWxvC4pClPQ z_6JGP8&tLEQg&Q%Q+8F(B1ycf&~sz+T}J9$^%lQ`6jkLx#g<{cOf))l?$D{@B$uU; zBq`2=Hv+%(C^LkK#~KjyEWKpGM+1*%uHJz*Co4iXWui5b?^iKJ*B#~)@z=wKnq%+K zhZi*NRs2$N3Y%H9o~hg1If1+M+(JLij#)sD%;`983Y9|!80bJ9poc{etmW`A!&PT) z6D-9*iIplJWt60rNx>^;dc6_yjKA{bEL^j|14PyGc&67jb-lag)Fj2uEIdLel=qK^ z7yJ$zWY%<_#KMg345+|JPF>id3B0_8m;4w5LI?K<7C@Ip3-R%bx+NE=d>%j#G<^{1 zo}hc49}Yz*r>9LpyN1X!&=r0Gur-Kqc=YNs!uh?9$+R)|!lB3!h}ka(u4{jy-Kg!U zvEla_h#3k1=;XnS3HzVsbweM3>96xdJ3-!{u1HqVBN7$4OB@HCtCb?;q=hNhYb6c( zZdo=zB$dNTR8M1#Z;iwR0!F=BssWGJ`k$r#0aBAY=E??L`V zWvj5PelJGI*JcvD@=)(?JFkA8JGLT?D449otL%})lOmQ z2a?|}+J`Hu>xh7tpn~l{W#m_vkbqPI{j#j~L74~&Q|jX6CY=SF$XyL+GGjIzfw#h# z#$slq$lK@@3fA;&&yHEvt!zTUULQ!N@K8K7zKMNi7@9Cu+2ed8@eE3>hXd+YRrM)z zW}@zzJ!}z!VK$D5+L*uUTTB_^!9vww`GnqCLX|K^;b!rz+HTQCD{#UR$B>)rjjpse zA3vI0awWX)y&RF+dl*1=+Xs&Fw;S3dW}si=Y@#I%5JS>UCjwXF@d?%{ttu!It`hL& zi#L8@d2KIEr8HN2J(~S4!yU4$XgBUj+01gk+?#V9>(;DrgB@Tmga~oCn@ed@wvXEBp?CJbDPUme z7>NCaC0>)SN6!I`f7!lts5|Hi7QgqiCz*Oo)NTGw`6gUOQ)KAV*!zJYA;5<;LS(Y0 zP1$OfaIP`2B235=IGn8`Wmav9^`a@bK1``=&JovLc`?`z9`wZGqM$9}_pveM5% zCi?(+JhA8TNlJf^CuscRF`uG{U5d3DGL7QDN-@QcuqTr0o#A=1{^G~nXwWBZAXt=@ zdda&O6p4JUnHQ2QVXO}zXAe_D-#E-K5DkEa(`a{*If~XEZ#s(>CHYQ))w{UTQAo{9iBr(k2=(f%gKIZ*B>UNd&3e7`{4fI|Q_4&DNs@2AHMrOV zL;Sx2Xth9+pgq0|A@ToYc>G__gWUh*JSaMunK;;+TDe#`*#CRUqZY%A5cC60^q3R| z2NsnvKUQ#r7Kxs{zUVIlt|myQsTO}$DCCWz_=!tYx`yob+r1C)s!0x!)K8RO*((!k z17Q1f#9IeiId=Ckb!{D;8hW#6=a9|+F}I*UN*>Jp z{=dh*U;po!0`NciX8w0Fg|O4N3#ysRcL}NDV&?d72}4=V22BXbx0`ou+) zYEzzViK+SILWcCO1B>_~Jr6x;6S;oy@$snWx^aBDW)^({ousg_xr|p9%Gw;x{3ITg zUX`ou+TVy;>gcMrhZA2lRa=5PHQuFer!1~T=M;bamG=9ywo#5_mj=pXkW~V=Qe_5> z*q2j|toYbRyzVl*QCFqT!L)vkABxQw1*u(-pAf|XG48L$nzBCUqi|?aw1UhaQt0TWKa%QnC0jWa}&U<|&)u3ik%#j@jgi#En1awS1 zJi1p48CY~8N8PkJCV{*9|6^#5;4{cP^j##T{?nnk@&Dlv``4J7*7WwkQ$zpSqUcP@ zmQ5tzuya$L(Pu7f?MV|awq#UA1x>Y?nm zXx8_dh)zI!xZxJ<9-NOt-?NyiqvW#@Wol#Q^%t;%-&p1wINwfx{EZ1PVpQ3Hh|j{n zU0r|#*ah+pDg=`xvz$uIQBjusck&Rc4=G5m;NCQ%0_e$8HMWExj! z`=^!{fnAs(EuW7VQc$y^nJGiBsb(F^XuA{&l9V321fWEo2M2fjii4Xt>Z^#zVfo!3 zQDP&dreaE(7&j?(_7|QzKk-2_v!+>-cDkd5eNjP|b5-W@dlf;KS-2%jJSZgtEQOfE zeLSg|;^@_fbnq-o%L%;Wgj?W;?q;Q$9D62~o0=b=db%7;J(hBepI9{QG$;&y#k}Tk zk#&x9=!KS$NvlaXd!-nAPnkq>X&o2gMN(WE{}#&oY2Xyyqk;Vj6fK1a3u2b4j9~qP z#iV}3(h)StgBg2uiIX|C>5GIU>|zo1*b$1v>r>@7_O&T2vb%QAbD(yc5&ok?&&pXi zvIYvu@I`B$#N{N>lsMakCE_cBk_EGA%?i(?8T6T%87v6%<8dN!bb?Atn*KD4ZEXg3 zg_p7t1UGZ4Q#cxaYwhC9cJW0Ql_Tafi=toEcR%r@Cba!cH~mbfJCCY?aSP|EG|s_9 zq!MvNq+4@T;nF#n>ZqnCb;j_po%h~Ja)?#AxpPc-rA)LvjJ7M%J9AAh2YyZKqzEKZ z5;isjZ6YH;W;@ap~&=QK7 zsn}OdC;?X(TID3M_|UimR5`0U>1v9qe5edVa!|cG3x({=t~}DDd$H7RbkGngi1Nwg z+STL~t1BGVDuz5~3aq4CL@ILf$?(RtMEx@Kkw-OKDI;CWOKeM@#mS3{rpprJ7I&HG zP6~Zaqyg3irz?kKA|f;4-GL__db4VaClbZlQeG8hiA`#gVrs#(Ws3r-;Bmc%rf`Gn z`wHXY+UZ_kaHX@ua$}3qRT`-XYd;~;llE{$^vQD#1Swl_8AH~qRY+Vh)#Z8V-A=Jd zYpOI}ZR8Kb+h%FGP{SSovDl0LIzJsT1ZFb@wjW@yQf{!Gq&%`XEsT0Yyx1fyhpg{n z+k3;E^#xOItk|Sp=opf3zz`%oP$0?Q;RI7}VBeMdR8SE5k#3qoEN*ClJ3=e~#UTdH z5xxD+aFfm*(7GoM8pHmVDYCh8EmOHmJaR~GaaxbFFQ8Aa>T=bivA@S2Iu}#BwTdu0wlWO`|GI~ce zc(#^4n=A$@`jf=DC0-5GB(8s_<|0}fWHyV|zXC?v#IAmM^~e%*$lf8MO?@%DA%SWj_}NQ$R!PWs+B!O{et; zr1qg|gl2d{l?ccA&tV?ZdIWArya@tF%ZmUJ?$A7^}hvZ4WRi;IJiLuBp8|#5=PONbGkChBCYHGBgetrCj z@7h*6h#z>27`CQwCP4<$Fhs5qVvUubNFz zVO{F9>PD^m;ku^Y{;O&)e_JB20;DFu(IuKsG;GTT*oH)1bPwpByUz!KiLj%7ydevb zpUp|D@ZOS47U(?FwDz9fvb&|bhPXY;nz?mF07^CLN~B*CHw$5pI9X+Wf;i_FxhoNa z+drNycB2xT&UchRI()I{oPq8NqgTx?}mWj|-Fb{r5`X#7Y!J{RiF-o0o?vfK<%c_NN#8dAb3f4gV@!(Qayv{C? zEiVq5y~fq(*TAJK9#QTeRa*^CiV(-^Z$L-X#JH}X0dMg)A1wug0nzW?ZpE#PKL7A^ zHT!JHI|n*GrOYvF7UE z?Alx>o?Pz)SnFr!enOo^ngR*lKCD3a_*kwDC}jQF{P>iMv*``uvHp@{cqMeY{8E4Goq0}z@VSO|rPLY@C=}3S|+$gLo{o$q_GntO5(V(n5>C=`Y{763) z52=YwV0!2gMBl$?ORZn?N z?Y_orPX)tM3pyKBQsYWOfiJA$fd02wPqHJvJBCeaQi9tXnWDPmMD|KNOx&I)U58ne zG;rqF+?H|%+=V4|k7a;_r=OgbSiBJbeTxql#F7G6Rg^$g9y)$+Ng}IHc?uNsoOt4X z*Qgs6B<2JRYaW3K_NB6Cx^WPOy-)dWML_`GZ

-$k&(>zOF)8B9`jI!WblQ+|0p zl>91H4NRTD(i~ne$=zp}<|Mib~@c3?WqYf+(P$lU<>n1(_ z510C6Ql{S%Dk~Sy|EHdOSXnL_^}DOgj?XrYsky2-Z@mf%7abDkqtQok)53BCH)GWL zIa4IXGvyMVGZXYl(@o`pH2ZA`HhqCd=7A(slyBgw)?J|?=KpnjNE=YP8b3c0i^U0` z9dHZbMZOYmqpZ6f(ER2wvAqSW1TN3XHTRhtR|)7JqF(+flMrg4~XzqAc) zrv`J2FIk5`-R{2Qadoo}0;qcjZYPi4v_tp8o1T zSm4R5ufJug>w13KkvbY z6%W>N{P;t4g$h5YVt>W{P{r490{P8NoW zW~j+FZm~+%F3RP$7ziL~jD1&IPJoCbGJ7<4?j`Ifoc(hns@FY1rsElMDd4PN=jB#&?sP(l< zN^d{j9N*-1cDjE5yuU~Lf!_>LvoB77VSfa@#nNPKwD^-Awv~Rt3@< z`t@qZE3&;DpGMQ`DHnwK;=H46tI+ zH+G+4YY|!p@*NclvdHOIamQf!jY*h0rYCIJe5inv8u~I!b@q*;(Ke2%jl|{T*k=e# z;o1`dZf*BAVD=tDKX-S~thgna06Z~Vic-<0s`s?T;DYd3n^8x9mex+?>!>VOtK67o ziD*y5FiDT{3ByYG$0OwGY3%@KQBOv~XPj)w8+Q6fNDcD;McX??R~9ha!X0Vnv*2=zvM-`Kn&%2 zX%^j*xKzmd(n9+IWC+r;lKBZa=4A1cy8cU?OydXj(3FQ{Q{YZn)}LVi2ut$aAOP6+ z6w%?oWxHhl2Vp6rZ}x3jW$I+~?|kaN&(i;OYVjX};ouk;e7>9n??0k^aAILKWjOpL zO67Qhco4Fe@sW-6YmNC@qzGKdiR$>aCm{E^vc}1Q8Uy%PPUqH-ch+1@U)dA2(x6?--(DPTz=OC=)u2ghYbE1y3ko;P4}YdA8Y*S< zShYqtWKcHwNP&;z&(?D1W0{r$pbJzBzY1v;n*OYe?_L>KaJvfMut6z{x z%I4EnRM$F&^~6QD7db(P8RU#G6D;2OHeX?sMx*}F3Z5(nDGv6fXZ_y)`1Y+fQ5W9d zDGB$#q@;glI{$wO#s5F(^#7nv{_VRfZ(GkRBYj%w4@&{ymtv!w4Bj`AiooWbs4K{Q z;~K!$>ckx~o5bU-Hrp3=G)0;aXFH|#vUeP5JvU;&P2Bm;jlQqi08cr7pV<>nFbPX= zzr5i-ew(T`|9ZQvHvTbW%jr+pQt{cvLYKdk=ex?p(}N6B2o0^Nlx_|f)#Rz*Jg08@TYbK?pX>CVj^KG275hxz@3=Y=E zZ=zx_QHpMdW(;<}2IMN#7m#X+KwWD1PHL&6j9OV1(~O9iEyYT!>ZeRO+bKL6Dm*LU zTgq*rJaX@%iY$c+t*#?LuNwKaY?fF;c}H5e6`-p={Szp!VKf-!@i;A&s?7s0}&R&YdOJ2I%CkP$8bWYwYa^ZthMaE z^%gSIhZKBa692TdqA&&1U;?ameyg~}j8$%N*w&$xRja0QB??sU*4e=k2iyQBM18W@ z$i@vu7c~kNvuFR6gFAmL(+zx7DqCPR+LSYx!QL+qF%_%oM7kS%aI~YgM(bqDt6LUZ z5LPKe+l2vYDs)wrT0dLl1=FCHuS2VItmE8812SwgibwES^}7ya8t0?*gsqZTzsDE` zto+9>nU(u0w{0v3w{2|af{XC9m|e_?y5$&r0fy=#mp0aACXuo18R>b>*Por+i1+zx zf(S|(OGr$Mjt$eZR?HmyYkemQH6ldB^rBy>q8dI?avqX%x@SmH20udz^gMurWW-oZ zEls6k?$rVu5xPrYL*%Lk$V>y{T%r!HW^;Q-B++#?A>yq33v9uSPhZ&MnALfQK^7m0 z$ct&e`H&^zLq$w2ba!QOX><0Af$9|WaZ^Ob*O*V%``{6jp!?$)T*Ah1y+TGDeY`nz znVBcFQ!OG~6N{%s-srUks05%yY;1GEBaJY_Oo#1VuC8GuuO2KG*<9o1YXiYfLB$|4 z71xNENMD9b9*Hi77U4DeF$zza*atMQKMCvjG=umInm))7e}&xnXy1JodL=D|Y$_AZ zYB7Vt@9~!zv?CNUskwxLunI)J1igW~8#fy$&Jd$@b>`|Vh1Dc=5zbFC+LH8(QMVmN z5mO+@GdDy`s|65jaV7OQ)M-1x|B+Fc=BL(Hzq5(We^GAzGbd&BKd2`ESwsHs1?8Uv zI+E7TMs`a75a;}hQ0G7EbUGFPO;XXEXbE3JfLbfW?=GhXx*sk~$V5aUgqTajCEaYm zIq6iiDv_vTBuOMF_5N*`yPvv+(-2^?5IpH&JjK54{C!aR<4Ur*?N&p6~^O4Hn9?F34Z`}4~l(_yddnu)PgoH^9N zq=SPiErTg9GeH?_%)}pCXkE#KU8B+KVqX)f9|S4Td5lC+C==)41@u)|LHi|@C~g=4 z3xVDvXE+yz7<5yr0nL5Yj_rNh^ayVod_fbx3In>&Zt#91E%9_a zY{D1~%c;8-jC+#eQL8@^(!RGM3rKTwSzlX`y+4G`Em+Ml!h$Q~W5EE>v3*Uj0GU8J zIAMthgEfe^(VdNQcXp$5~9lX->%k~p>a(WNQ; z@uyLJ#m>-fG5Df>G;AI8JBI*MbyoSuf7zTbnWYsG{>DoZ-(F1rdv4M6|4oGdZ-V<< zg!b(S{rQ(RbW&JjxpAw}?854)7mtS`%u?;Q6LJIfGg~@#okCn{jO5yDxu7f+&o`qe zMzNQAE<{GvRT7hG|J7w57hlcG>kV}MBOM1zQ|k}*GMDBsjQgfT?a^LSI4AT2ft1it zj}uzPu)Nq^KIP|TrHG$iD{Z2S9Faim#jT!X)?b}quC3$LhQ|dpMuSwwigUFd zYORu4ADNnuWARW6&LdYEGJ$(X6fmyCT~*LrX@tsKyxqU=bTg%~VmS?Ap>f9i(o96) zLKX+Pg^YPBB{QOxR4t0L_3$#0BTF*%Jb5&~m>Xc}*A_JpjTkT@$F}4>a5mG4<#$qg z-7CYXkho2U&Aw9KKY@4;c(^Lw*!+o6pFAvb4)Y_E!eIrTalwmNt=E6*SLN*-Uh@S6 z?N0LIWzDiP7OvHf*VV?9(J{cfaj}9hkZWNTI}CH^yF5I-^wpYo^(cjX3MDZcny=qBnnd8J;GKpq zX{?@j@fCVH_?g{X!J4htPFvRuVO98sE7UB4>CQr$i4^w&e)Z5K>LP2>+*R*zjgpu; zZuCJpUdDBtxpe;v;kZFHBe?sG)$slcPXFi3s``H^?qrRu^eh})|4sV%Z@^9QOa@B{ z>1)#y2D(3ggd%+1%rn8W*THh|wyepbb_bYxh9pEMNYBT2wRJrcy`#8lGh@+H%Ln*AwbyVc$M<^_OJwswH zBEk?tgs3qWG)sm)mjVRmos25-R zHn^#u`(pw9s14P$#C)0Z!acgcqHAuCr3kgj(*nSpuvMgDbmZ|#GS~EP zz;1j(1B>xCpop}CQ09z5y^l8T(LEJqxA>-*;KAH271Dfy?jSs3;ea_lO6IrdY zywDBNXH^CxIP#e`7kw$RRz6Wn$}&~7^e@s9VL(URG$yfekbUm}mB7pmRD;Grkraw+ zfIIQ#3A2#zK>1A!dct~wpG zVB`p0MSeyE=>D%SIy3;NMp@zNJYZ&^A{TMjvf25}#0t`OKkW(nNpoHv;%62i-?9Wg zs^|AAqJNeVy&&RCdiW_4WPfNE5599^+J2U|4)GTWj8y23CWCi9$Y$ffWx?U8!!FtzG}rCtWipA9pp;WKfo7OU@|jmz*@h&I@{n5mPh z0Tzx%n0k89O=5E7^{&XNNhJxBGtRD%Qp@l-h_B!TsdYaq1=?!yY7cq6BnnmJV#g|S zZ&63eOT-&1_;2(a%jg@z(iEw_eTBB=pE`B!_|@M^A$HgUuDKT9fsr~wJY7OxJ<;KI zkPWXXI{T}0A*v02TI+_@1UB0MSt~4XwgfoekZkn_yWl>_70t(-l=4Kpk*gzM?eJp( zdl0o4@*r4%dk{TCzlzdf+{W%O{mHt=UDLm(I`x}P)OF^1AOwV@Ql7db=_+xxKf?pY z#2vZZUktc3=5eimiS%nk#h;q2JQ3BlfbxFQhOcB~nMYIQJC0YUff}tot{YLm37M@C zjtZw8@pO9QOD@pPIZ4TPH~q#FA}u8NKm>raGzr*2n3;S)D?MkNJo{m249R(j6?g>} zUo#(F!=PMK$G%|8wMW2RgCvc7QLuQ(2baFk=aGvc37PP%pCGJ`lL@iQ3%aJ*xr@eA ziyC_aqWOP!)-eVlW0*#m7@6FhnSUVu0}O6cUJ_A%r>i80|6D5nxxM81AEYc1Yds4^ zR~w^$O-zM~mezB!NM1BZV-jG7>Gt;a9L2y26f_bMJ9S2R_H*>f`ePDU3=&xp65Ucbx8TK^Xjo@|dg5`xvR4TQ5%fsvuUYz#61 zDnEhnloGrxtzW{-lhJ`u33O~`WpZNXSUE%ge%XGL($=B6hzj#?9aej>`o>vBsq``< z)uNNde2wE}8FyrQK^Eu6hUfBPc%F12O9f#yQ*#;Z7);RKnV5JGT+8aRJG2bLYABT0 z`V?j+zFMJ=`nK8WC5?5e1Hl_Mz#82w6~M#0Q#N|hw05o8Z-rVPe=n(m&0%i0{JS#f zgD732?fPRed?g8b{h9@>Dg&r6&QiWyx}5q=~&; zKQJm-Az(2uaw2qu{R8xcFT4Zraw^H`YkFbI9e4|37?k?C2HSsKo#16mOlf+q8f$Luan<^i_4Hk8 z+i^dSt*?HpL~jq*{(>`o7RJKo!Wu@sjyXpImNFd~%Ec%B#TXx| zZ)*`qEx`Y+e5s-eXYi;;#}Nm9VMsW15Ps$@+N}t(x7`REHoDVb@X+XY)_{#w4ULeJiABjZ$!v9zl+?h0MayP~g5gnu4>y!KriOl#Cl z^G(Zm=>E1Sp82hK@;tw2d7h_=?}F4G3^SO_wna0Ap)-CcVKQ@4fTl1SGmH2PPy~?C zU^@C_PM1~k6s)NjE(PI^uPn*m>A|p&oq6pJ%c7(qPdCrljCCW*uR46*57J^0ff+wL zEqq@|NpyzpK9@7}g3&Y4EE=GW!$ON;KTmA}Hu8y~ADj`~EHg(ojE{d%RoT~lPCA1| z>zbY4%3*-UeF{|MH{Rbv8nC|Lp9Xc!*n$D1mF-wuHea`;-Ubh%?(841Hm&O>x zt?E<<1-qS6x{LPM8mA;~G}dH2Df;+QBpYhEhfGp4 zrPzPxWLGB@tT3`yLtlcK&s42D=f**kfkf_aF8Z_;{S6;VzOC(n>s^EV3blEYx{n!~i$9Z@=aVA$PpyUQ+e{S{IC9R>SF z9eMjoy>2jw98vqAj4qiNM6}m1?5W1}f93YFF=*DEvXg01C5L(28Yq`!Gq*$Vy9e!| zz^(igg3c7AOEsz5vaFAU!xlN!_RDr1u~BWsdW+5wB|tx=hgD{Zce))M(! zwE9UEnrk;b#*-!1GFU$hs`MnVHg$%)LfecR$(D1CRwoOB=Tq-b^P$?laFK(S zXL*YU`KcXdQmkFPWRuli;x6JXZevU9jE)OFWWX#Cva)6jeJlDmUT-JpI(E zylX`vN-%4Xx6SmG+)9;{C|EdaNSeUme8_UkdNW5I_M?5>ke!J&;zsXp8M-}+GiCf& z;@pU5t2=LaDwSTDs5=Mk>axh0i;tqcnyG@qqk}evC9kxr>=PeK^=q5DQqxcd7+g^2 zD_i-O34tA>o}!_nGr4Ayad=wIx|a0>1#nb}SCxyBSY4+NpuDh$Gv6K7z+OzC#J=#5 zh$m3S9<-~3*@M|w9nZCWZc%dSE|1XQoN$Ff!Q}(gDOFd7;e*F2L4Tm8`X86EhhyRq?SnTq-23}|eo+zIyngyneae`>XbCUYLDGs^mn*eiy zk2It(H&VXQUfqaq*E-Zlp2Ox0^5K4ClvO^5LgA4hu|Pjn9~cG3MExgy2MZgJB64my zuX7j|jDTT$_9Yo(K@yl5V zQLZ<2*qC;YFFh^9$!Qp2jjE}cnV7(mo?Sxlxc0DGv?Qf+3@|q(lGrL!{WFh-Oiy34 z>e}=|IXPhK4}W(0+x?6BwY2W9VN#Qgd56>bl_8aWEtgoJw8A&-qSNY`6BXMCDVG%P zXEtr)5?X?2374R2unu3;Ym#gj?*XjOfbsWGMBH5W+ZA8;*=RIr22c>Tu>g)JXdSF! zG((PRz#hsw&=bDYvQ@uCOLj3nzy=6TH$?rBfeL+0xpWv>c!c;*gno>o6u*4q(zQsa z4m;;S{oQR;Dfp+<9+NE(nXmPF=IWiab&G^l$vTbxa8|(DDz<5OM{s3*gp9@k?#e4_ z!vwyQcA*S!YnsP8NauDw_*Fg(?)8}FuFy*i!d5ZM7c|vXVFrtvV}!CuNH;`r3J?Bk zKKA|skEFZvZh3&>Y;n?Gh;mbuI8tM!GcH>q`X}-CsvKANW@)OOCTH|POO@Zp4IdyD z+5;De*85S{+qTERJYSbejvD^y_p}r@))oUI4p+m9$MJlVV^SL$@ZF`+Kpa}gZC3#7 z)ZwVJs}cWYS(U4iBA~5^Q3}Vf`V2AsE6qqY`9`jQYOwv~*n^H#Sw;$Pb)#3>f1t>3 z0(%kt8$o&@{AU#T&yBCq|3OjyBlAa1j{iSuGLfvFgNc~Ekc*9lwVjcnkc)wl%|8V2 z{|Yu66}A51kj*V1!MjAPTbL(gv{*(Btg#=jFZrXq%G9E8rAL9$BG_s4Qj)PrTGoU9mEmb?)&4kx5%=w3J$U-ZWlr3X5eT#jLrQqQ(GEq`;Ho2t z8q$1A?2uGYsjNx#8+ERL%xLlyA^2m2p1#y5-5!IPtvB9KGDTh)mOQ9`dn0g~I~u^!pa5p!{8 z%dKN8nUyLi;5loE1&?Lr1^5+tvFw!ACIS6?Jh7<9$MeNkz*2ak8}zOAFRgcweFpzo zMUacIVQng#SHW%h4oITs1MLb}uIv!W1DmMbu6l#PDXJR-t?;mt;zi0<-3!>hkvRfc z_r6;KbCGhNF354>(xgy?G1H0kmPjzfaMiHo2K2SBRd#{h5kPf(P^HzvndaJ3%+&xc~;bLD#53s@qTL zyad8n3$LirJ=X`nZ07O2L@=(zpWJ~vX$K)_K4sl_;`Xvl-|4Sn_Yh6JC}xc1-zCzr z$KSmr?tZbK^3J`>r|Cf6>!5m5Kd{PsgujGsgeCq_K%Zj*vlHD-=p*(dmoE_CO(K}A z6DLz0}wlIi;)XO$3%g0?dxOIV!m0GFaXd5`0 z!a+e5%y0%svxQyM6|dVR)<**-p3+NrVIUc?APW zFgi{@V*>4}p@}$d3G{d%VTziBgOrO={mVY8+hDo7+WPI9;5c9!C*GSN(JT%rJ`=I) zWJ5O$NogungvcqitZ4LRzR)`;L!EjubuNQ=#=_SOG>vdj({w6+&*WI`>s|Q^QPC_D zkw>TKYZT`$6EW*t@DA-bpc&i=>*Lea-!RyqP!+E}3h~5+9Oe6;+wb;>!M@hWD}|;) z1uhm%sGUlQt=e=l@diWXGl;@voTR-jyMiIK{~XBkvvOA?wJC`%LLxbNtp_GzFaIqoh>p5En6R>JVBaq-%zr;O6`%5S3? z+OdFQCNBZ)m{o)}NcI6y_A8i?5Er}GX*=Cs_u2fY;j#k5f$gYbS>p3s)ldIp2CwV@z28>gsIfVrT?*nRrT>qsN;o zvB`IHMPY{f!r)75)J~~(Mqx2`Pyb%=`wQ$h4qWH@MwqHq)#nG^SEvMX$ zzoMw4FSZ}MUpuhg>Is7uyW#oHGwyCHQ&(GUzi+zPGT&@pLa}ltAk$8Ka{aFRJglBpQp`d z@5F>;q53;QsKC-W%~q3oKEfY+3CXhVWzJ7ZmU%Zp)zApC!4>e{$^cP^k9z)n{F5&7 z697YwzsMtv|sUupb zGddEp)JVD_pjsG#8;oUxN69ein$M3PVXE7Y=WiQl1avc%p@26)H35qW=5ZDdX>pm_0ie zEmj6JQ9tl>nMs8NW8>k1YRA}ZeALlQf{8$}NJfOCs%~>syyFh-O08sGz`i$GU;Cg5 z0{cR|$wOLBPSuraC-m3q0wNc|Ua}OwPtSRzzb!dpX!V{I-bW;J54H z;Wt_QSRNAdv?8krvrD2#;YT3QUgX-VT04I1s3BOFF2}U$d@C1z$!vXE<#ASHgUs0`gckb1Y$V4H~#lK}8r-9jwun z551U%<|Ojsd~)MYz@qC?u0kH=U~u2M;sr8eGzFVaF+fiw<{|(?>K8%I#CaFB# z6{|feZV%*BgvnQtji*5YIf_;2LL)dPN3CQ(Urny7t1M=~y>0~yw9ZD{h;BxWQA#dM zNWgeYeuC(x8Rofx^HlWE-Y!RI;+gXL*@Lzl-RkauiQ~MuWW9(3A@Vw*cs1l6lL#G( zwMCMsRCefJdqsi|)dup2AKSzV^r&pA=SeBweLk?sQ1U1@njXD+Fm3|30^v{AvOcta z$k+fv6DvzKST6kerK}pfJg5>r^KcRbkI(?3mw2^6eF-f`4(XUsM+ADDH-Gd8n%09@ z_2lz>8Mc1%DF9aXwdRmjZyWJY-gJ_bJeS(oK*p zhd%h^1L;#2H-Qr$+y3z09eCl*>O3Lt+X=6ysbe5O7tT(y5nw|K=CrU(&@~pTuF=%o z9Iv00RUB9ltZ!^4X=pZX)$KOVFBc?G9~e%JBNoUPm_1@f=_JVN?8|XJp@~5ak`F(T z_Z_EFrBDq;q2FKZEFAk;4WH}xC#2POsBbc5eck=+qxAJRa(R4kB!{a$WcC`yl5%T9 z4irgAGA)T{laN@1P5e?yONUzu^-}x1I3*kTY37{rD(u$n0VJdL56HzJ+N7Fu*wObi zLk8ipbLSWm&FFIWH4E-Y$v16sabpG+=TmZ7@|aYu8G~j{G(SrVbhqacImvohzQ0#> zPLP-jW)`PexR#NDee(oyHc#vBOQOBQ0@ibsI8*XF0^L&qvcUpz$oe6uE^LXLIG2P% zK}e}&Czfub0$(}KT=xu3IjjXQ6i`mKVZmE*mch4rILJzqG>&B=gNorIgUH|XSu~>1 zFLX+7vqbfa+-0y>p^laQBEAc=NRiAUuRXcqd|il($7?kYmiZ9vLb1NcdTs!8O~5D3 z8&6O7&2{BFX3@SE(ehDl^@#x-qUX81vD<ItzOYE+2=kn$ z&J9p^%nUxh)-1xMc%GqU!g-*CuU|G{{ZoutSFUYlh`czJs$A} z>#UmSqEj8(pi9-zF^>GVG(BakyPw2fW8Xgcl!>c#t&ruHy>*gS6P?sEZ2Ls$&~ZOm z@E(l$(P@aIkqfP%S7gbPZjsh{ULD2rl{6u(d9EvOu*-}H!4KzKEt5Z13)FcC&1LIc z4I%^k3h14hN1im3-V!&sfiO#ecF`Ixk9x9yQ~QD^j$^mqt_vUci5wh1_@Xqq*R*l_LO;#}gq|!u z#157>8d6Hpqf>s`5_m|Qq5q9dvga5afbZ#UC`%bPN+uc{^T09fw8WqH{K8*OpV{Me z<*FT}R#EC91CRy~Qb?uvLPg5>IqHCLLcPKYh}qeJfM)LL;#tzLrmE^JBx>f!;^6nI z!M!V;fz1*YyLQMad4dq7K{QSrQv)H8%2h=ZX32U-GWEWI_IP4TBnPpmuZtFx5#zVc zzey053;gT)Q@nYkOw1_(>7E6R)z9%~pF+ILDQ(>?KWkq1%1Mb^ELV<`v<-@)hP5f! z8@HH90-Hf=(?MLB=oYgxI+c~5yUn8se6|Bh@Sp*vwm+p3%JsU4@09Vh9h zZrsdAqH>mWS%nPd8wP?a5_d_%({o@&!*cimX6D#vL|tW^9?+B2NE&1e zoN8KoGH0Vu&}byhv{aHx6}Et-Rk$clm@+rlhV+CHXG~d9l31%+&yL&EOU%UJ>jDTS8}zTMx)NDWoq{7s@1AQElej%br%ViYV%^D<__Ky zj>OG@jG|#Klc&=;X%Wu+b(bUUeIcLv7TO&zL9P^NJA;D*AKu1H#U2YnSPN1EJx(A8 z2fr!lnMKGVP`h<9X4x6xOCQvW2A}0w;Vhr!RbfwHFBQx}hz@eg1Y6Q6IyOur;=+87 zC0FP-E#l?(@Mh;slCkJ8zsE zZwaTmq+d%hqCs;pBPpf$u_VDkf?FAGl{RyQZ-Pzo4%yKk31jR&+)Gv`qe9Vx&0IFr z*%0cQ`3Ms+>`^`32Q30JzvnXA?zS6@yT%-Ic*opUCnK$#ddI#!tL+!74l6h zIIv~@DI(H4>CdWi8acuvxO?H#r8L?U@@$sp{dwXvrj2GodS!9{SPhAEWs(o%yXSNZ z7Qu3hifmn&!A{6QhU)E_3x%k7_%;EH(UJ*Hoj`oD6Pd8b*c>x&TxC|=nYh&Jk$!Bx z^VH;#US>-W^~bfQ#9&F#u5}CV;MuA$SXh%>F2Ox$lU%H?a&6uikA_JLx2>R^K1Ad> z&*YjHA~NdB8`^q_;H)x6V{C>7nMji9#(Jp(W+Hk6OJ=hNW+0A&jl2E#*cTk3nrSH-&CVL6*tf6zb8vXm~Fwr#AadBHux2k8{n^Ri!li$ zDC@wki?8U;W=^gcJy$WS^3`>m0#BWl+XUId-cwOwQ^iTz!~lE82mmyWA~dt@KoqA3z@5)JVh4 z?g_N3i#sVeX8G+Y?5K3DgtBJ#S|HQnj?bd)J=nV}YGlzkWDF)7o6HWbT0&p-l%pcB zEh7`dOPpjYl_sPA&eJd1zMza3{d7j0xbUq9dHQ?WLqk=F`T;_z#iKw&n~oCVRXJX? zpP!o@O|@x*d}sM)#0k2tm$-(Ff(N3Dx_f9^}(IXTH58J2k0iFTzpR zQX4&}_7UFw#W&O*INM>V%{fm_T~auNH`~%(>DhbkF09QrA{~j{J5HZToQfpdVBYt%2CftP&L4UT>|GJ)i533E)VgB=;W=qqpmoaROzI?+Qf%(jx zpSjI?c^DlL{G2^x^*Qhy$IIAtG%a=XmD2iN=*srBoH4we0xzgSUpT=$Mn|hy)GEh5 zv7RvhPMB@|sZs7U4oAS$ zBTcT~0Di#bnT0T!60H|u+sNfbv|?l@Gsr(0IAOGXah(fR7R9?jd*{aI^%iyK1T=v0 zV}Z#LR%U=^)vPP*j)?E0_tcqx)#}!FoA!GF$;+lbwwx{vBx~tLkQ9W}RFxa53Odu$)v4h(JVh&)19NDg zSm+&b(LF4V<%*6L_BrvBUL-)1Yl$Z3!hJH{DI&e4_aTa@kOHS}RG#sRk3IxriL|Rn zFsw?r{?iwC$V^6HuL}Winw2kgLb`ZHe%O>QrfSf*XxIaq3?X1!hMYTPmJr#2lO(SU ze&MpY_LSBs zqjeN2>1$;HE8(GpQ2P5kQL^>>4U}$HbJt#Y{lp{3k!xrg^{Jf(BW}!*p+=oFlk!|! zvV+fw9rwd63LV;SZgzVokpM@TgN7c~dO^hct0=8u(&Gk*^sEj6!`0(gT{3K>Pw$nX<@yZCR3^84tC} zFrQX*J~P0jjgPuOW0BxBQ(e-zjQG}DXEq-o=%$`2NSpi71~pe~M($bOrw zE&=c2XTGhc82eJ3q|nMNqfpY6Qm!mhu2du~QKHCG&Tka{?q&06l#0vE7tzhqITSkc zrsT6r>lax8SpAh#%yn|dC5>wqRQ_sc5qO27>0=_hVM#sM1$|Oc3!dcQ@!Ng_Ohgl; zIp}L8(26>DkRAjPV?+-G*`SDKK2^dzYMhCji{x0K0Tr@cT^d2)(#w@n3y7~%Lh>X_ zq)czGd4d$ovj|tA59*gHd_Oqji#!j&N(F)%V+UM653%ntO%`5Drbz2flLG!21?1rm zw9y-jTIRq2#N9Nt3ejI zJQUq8h3yKh@oDK+@meZH_t@%XP1f)*JdHd}ieeZ$>3Vm}PJ$ww_GtPCm8%om)Yt)u zTBY-5l%r8(jCJgHBpBwT2wCYfMkDsKUE;qoyGNJCPcb$&O8J3YYvnb_R6a0*KZDY~ zPYz&r=RW|X+Y~p2mdo37iJxYa8ykQ1uf;=~FHh*fM9xEx3(a&u&yhfvA0MLhN37#b zzOb3nVFg+O)4~;6w@4QvzhU2&`J6upd(LWEBzY12MlZQ!!mC@ski6)78-G0V3|v3H zY$$%ng%ZP>XSsz$Z_AYG){1o?guS6qahSP)+(rmfW~)Dqf`Zf36>7r`x~LkPfaf^8 zjMF#YcVfN#Q@nER@I)4u(209{;l)6zQPxh;Y2seExxKv|tyx?tA8lQU<>L#)urprd z)LnhHh?%q>q5Qnd@DZY|$>SY3pMCh`Slf^ocL?`ntmf)fr2`x!u32sMX3xp4oO*2U zkCbg6cnws~^0txY|EWl=;3G0oISxGWs`=z&#oF2Y zF^PP0j8$#(iGJ6NW!oYOzsJwXd^AaUf zpWNZoulY4RV5`3GpF$H=<0{as@fXzK5|*NkUfoe(6HV`R;}s^}7vq!`oMfEb?gUr? z*Eu52$f>h}VN`bd^Ti>gVjw6S|0uqT#nJHEVwCEm(s^9W)A^ct2xM zZ*vf-tf5N3jQp$V3bSmQ%2(ollF=-V92{VS1e}ANuh+c5R;&+u#3N zMw0oK%>?=Y+~9XL1NfcMP>i9UGf!jMkyPe;>iT zn8y(r@(a)_q>(h2*p439dMl4l#{}dNxPx@ZxIT~e!*y;T0~bqDqmRK^450)wBn1=z z(2(dDvpAFT?ckuV!)91|4PkbE_uWs2Djt){v%qo#_oZE|9+ zCBbMSvvdYnG%j4&dXhPzCB^9RaT}7kSeRF_GcSUDY=oz3#@DVKP4;t!JlV_q?%`zF zUvM0hS&mdXx(W{zOQR~qt*iINW}u_Uf8`42uQuc^=ja=j8$-w5rLD!)jLLW${q26? zwV^0hN@PPG+M3t&EdV|4gYndVJ`&mX9}vdUBj&DAY4%zCRu&i>!U|dA!Z5~?QaVXD z#ma{)2U8O;`KdF)SUV=L-hWE}euut%m{G~fm{Utq;UYcOkM!qeX|7TtRxr8)_dvW3!XGAAf@DqO= zrU!ui<0Xz}gcLrQ&ks6tO#`%}4AP|o0yro{H3fvv2M+X^pAR;Y#oiQahy0|R1%f17 zO&Fw8pBm5K#3U}`mWcf>{yAS;kSK@=PhfX|RY65%UfqQW}Qy z_%n$d?4x;RQnA27nBLG~dE1eBcCt+1NRePd$T=odWEdb}QLou#ZDG|-yS1gPSgkPL?o z;YG*HQgBzvMFuvM!+XjoJIYb{rX|MtTIMtWJIcXPjntR|Q?a-r;#YocDkZAlGxSKQ3#%p0km8!GOP2jz6B7!z1cC`qVAKa4veGOo9z) zguE~bveiV`|E54q7`0^6T^h4rl7hBLi_OKub-R>)8vTKV**|l*hb z>(tJeM6pY^9b?uoZD~aiZ1y`@l&zlcxy_zIxN`{0iApoR9P}ZOvYb1B zC5FexR(Xm$@!5JW4RG#!q$2kN8_*6`;2aty*)QfRY3ZghuI8u-ucUGml6i_Lf~KMf zg&Of>k;5Fj85&a)qn5?P?H_*zI*P|>1vf^uHXp03UcQjdJ0DL(6Ua<9-&`d0$0s-5 z4_&qGTVpg&>Bcg(N!@;nVI0y_O9->f>UQ^^QQfrxYa4sjFCQ|eTi!VN;?h<-=6Oic z-E+FhUt#NxgCywjh`JsL#N21v+;<0qtU{7|hoGdi$K4qI5cdp?!iJbdo1~)W<^Rm2 zR^*q$Ge1F9-_x?8YBn$WD@(ndJ4hE@WTwo)_nGOTGH05WXV28CtJ*mo@i)MWroil@ z(gCJilzwbeyLmZOcH-)`Z5&!hypnd%IEX@isSQ#5-1z}%fJ@BuNFl+JC(`2ronzpg z5^Tb_6zLl6&Q)q1dMDK&od$A;^ltN2#0q%R;Op6pq51STDNKU(VuJC!s8nz`xGa3L z0TUQfU8v&0X{ z1N0;F1k=kR-=njTiLD&Dqx6=B&7arW0wFKb@=w1mMkav17$zQ>q=|k&vS%A&;v@3d zcV=R1FCYSGbTI&m%T1``V6JxCySSWmX8p9puy7gmK~(vd(+GJ_ZG z_-g6+*ilax?$~8tPIvwPM+>zZK)O_JnUE?rO^hz9|SI(vEsOvjEtZ1pj$cK5~E8$Y&8pc9=i@| zrJ8VYHy&2b^E&u+MYJ>3Sm!w2{5_{=23CPGv_RuP@LUCx>mi7yaWc3#QH_-W$$@XK z!Jdy4>4*MySN5U7KK9or#}Jpf_m=lW9<>jqO)YP;B0l?v2}fuGAhO4t6meF)sqbh3 zQt@iHc$OeU5>tn753Gj7U(TkegYe^Q_^dML$qx=dl28t8Nf4MUedbB7*jh7jCg-^7 zrk^B97J_g$1qKYQSPEqGa)Iut;(;X+Gdz9tgfDTkaQZf(QQaGKV##aT-hU7-AX(Oc zxlJ%nYS%*0Q{!F8cnuNh%I;L6HBL(}yZ5--#;r*&bh!WiFV@bfSrBeX)3sIGwr$(C zZQHhM+qP}nwr$(Cr%w0R6VZKfE~Y0Ue?rDetbCtW#UB5rQPuVP)`61SJ9p?AmX=ZR z_2u)HC*lUb`|3}`Pi~n)r(}w6;mKnXyIyKeo~hrDerXOUDUQe&>!SW5ZSOB?;V*)s zZ{B~Mzfp<`5S!h|SGrASB^QiHy zvkDg<{n&tG<>n=l1pJYdz@HlFCF_$6Rhtp=8UC`qY_GnZfPn?%-_uxn&_v-qbkS66UO98K(Q|fN-EQn0kaMA0am3y~ z=thPEMNbiWtv5}&+1apJT*7>ldTrzJ3L^to+VQb~Y{#bxu1f|B*`#Nz@sYB1)80Yh zR2a+rLNvYl^U~^vq=IhqrI`L2WxLdQ>xVij_dG~m7JTu0S&uvwQ^_KLqfWoKH?X){ zI+*e6FMOGJ-Jx}({(K5ZKLl#o7cCe~>#XWFmM_2f{0>ZM=;9f(?5TAD`H2+D(S%s{ z>w{l>NHjlSjEuat^~#L~zi?`<(N9QXgFS;{){NAA5`EZws+3{jQgl>SKmHOaO9wBQ zY^|!FUhPq)*zFzza%j@y{D|@|VfzsN4HuqUWzd_K~XgfQ;jGaxIR@ly*?D)vGvzuS43gt9>N=ay~Liek(nxl zZM?D32;@y3wti&mPBsGRBJ##5B3gi{;3`=4t8h36)Rc$qA!P@nkZnr35AN z+MujWf?BN82K!bnCl0up`-$vILRymZ9Asb_^uV}(d$Y5JBS z{ZMq1biIvIpudZ$g7nGhpm*9l6gC&dFQkkwwjHnUy-zYduiHGnqfEO&auIW2@WTYV zJLErJ-*w8t8N6)4ChW+>&IISx<|D-ulGg0gnuIy16l4m)%`@Rp_Cs++2Sy9b<>v ztE{t{oFX(}u;-dk+0a*AT0Y!J2-v&rhXIrhkyjw%KE40P=s=0BD>giG3G`Z6%I z>O!{O=Uc00xek%8tQCXkJ31#YCLE3Wk(Z@ zG%1kGT#EISN!uBU#>y2(ktBz>0ID2{1>jtS>l3riCRsRT^((BSV%UPlI=L4lXCgl5 ztBMzQ|D+<7vmHFgYELSYBKcz_#z+BM)Q3u!&1vYCttT{&qG8826+|_4FPd2kS6bmV zPq@%qc0@)_mR7=yg}*!WC^k)~B+*<;X>YMtm>tC^XG)k{D0QDpNm`XZ50@DKDLpxs@y2AJ@)7_+O3DaLDD#R zPA_999uq|7)TD^sDM%{*kTgE?X7scaz_VO9ju(vhiYJ$$C;f(A0Kn1Qu4Z3&KUU&m zQI{Q&c8ssdG8I~xTi*>$pww6@W005a?m(yWb$ld7BbQEUcoq@;wDO*4QYV%o;i%O} zw?S+%XbVeZqAV1bT=3H|Ulv;+ozg&jF&rMG_gWnkwbR;bc3(Rl0Y}6g0`h;N=jE~4 zC*slHN5VmxJRso-3z71IsN@g0(Foe5*QHhYQ4`(?{T-jyPyr;Gi8JouI!vXJ zCuS4RHQnmRf@J!PVAdR7#Um%pfNOsU^QfFf74^W?XAl7OmLH8j*s2Ap6)?%(pXA4Q zr3V7Eh~1+f_t)w`Y(6MV=1T`RBSE0%p&;Zl?@VSU{uaqw;{J@w4RO0{mKOIJf>@h} zEMdAW6t)Ptc4{Y-y$PoXbKcsND;}H88NA4RXi&8CfOH?mFFdV)?k@hF>-h*GfF}!a zf%AoUVCGz6a7(ca_YzB!I4%5V`QOY-$JP%`Aje<=IPge~$QMi|jrziWL&*_SL!wPZ zh}qRzR6`Sg(^BhtipGO#i~a*_l5)*-c2dLT&Bze?8SPpi#3a8n}89P)AO(E5hW@kxZuGhi(Xe}7Tvo(_}K6+XZ`?s|Q@b$UXPe(dcB zMNPyL#}l&J-gttg;n8_k=&BW1?4-b<+wTek>G3&c`o#?(>q>_s<%8Z*a=17M4eO$GH*uP?({q`?+uYBx>nNdm`S7tgc|UGbhfR&+;3d zDAt|DZH=BO2hNhAHTP8ZwHjA3c*X&J{BR&0l|;#MBP~7tA<5JjXA)eyqgp<-JHr-# zc2WF0PS*R65e3i;!&A>x{R`IqE6l<-fz9ws>ghwkVpx0+38v=v8g!d1gJ z%DmsX&AZCXk-QaKuMrpnmJ}g9W#XUO+>_rCuOS|QKMJyY&dvaT`4GFl=NWE-+JnST zfV7`Ct3BmVJPgtzLT^#R6ncZogJ!DoghlC5G{}t0n_ z%3fmcvAx_>EBYR7NEhlO0+oc?UI*>3%g1WJEgE3&^COJ*omIoB<8=9keHS0aPeTJ4tOr{>QU_t0XfN;^~?0{uvqK3wyZ8opt-#S z6o+le@@53?-}TUc8|+`U4yLsFcKU{9#IER<}+dP0C4 zSreF|sAwLt*1An;=**=Zdo@ej#8fgOrF;(-?J0vK*erAyRNLm=MPEc7+88N{Bk0i6TK8@95mIZ{E$t5WGeHZ z9e!v8{~?l)XUy|cBy@B(ua6a<-+YDMR-C_jJ@W$2ii2_1i*n3&c3vJ1$aVx{Frcr> z#0fKqA5gIQDk$;~Jxg zc;8r`f0DGhFg0UA2}6)qHhSTGI(GxBGTFKak1@(5763D)G65JZNrBq1l|^Z0LzK?I zJY%ywU6a=OD5~ST7He7RXIwll{VXLyL}Dblw;XH3GgQN0zXE6oL5=T0p(Bm@Cj!TN zsmJgma8vf!)Y3}Z+DG%P`Kie3!F&S5epVtbETw^E>M4@Ggs`PD^GVlkqeKcKlOTrX zZB-WHr0YJ&^~z+54G|jW!dP01K}xl)B`61?O4&B_%j{QL5LqOsl6+F8fqWi(@9NSt z#rH&irKyaIC-rS}f;o$Ri07IliiiYzatbqzG!8`?HIcuRXiQTD+BJy&Y9xb=9So~( zHS79sZfjcH@s{AHyFTUzoV?H$ zk>R4Rarbb%nqI4cA$7ob{1OhD+vyx)$nFrc}`+4Gb z<{b|AQU|64EJ@zllQ;$|P2YcKLahVzte*e2whLfk za|&$I{*9arh8w&0!nWt>PTRR?B&pmz+C@|X7v!TVti+lf?sDl&F~5g*o~Rb8l47MU zz?2s2iG_0d;T4v-N}=>+oRINITuos~T1^ z-Ehz?z3`LGk8pF(IP;)#jvvA1a9v)*=TZEq;`{57m!t@LH^#O%oNOHIr94yD?5UYH zKfAJP-XiyRRMuaQ88Vc7^p0RBODZDm{<__izUt5xMvRDIeio=bbqgb zaNh}&_h{v=sgr9@9z|ZceB8L>Cn_I-XiF5IVJ@FI1{88{(3n1co&x#n(>}Nj&Pner zv|?ob%ny-Pig&%fB$vOz4{;v14DJ%Esv%&*`=T{0o)4Uw&==oS&o@CpD;D<^J!(E3 zC1H8_AG%$w^PN5Bzt&WMu>Y=Z{lC~#{a4+R`^)>Yvicv|$0}7wH^n9FpR7(BjB0bq zgm}%3Y0^f3F^#(UMEt*t?B>Eo5D+7bc}a|nx4084KPUFV+h;8^zP!mrr3ISs8E~d=ec`meX%JKkO$zKA9aay$2ltOuMK! zl|vk`0%|vXBlhm#d6YLjei) z6`SqW2;D&&l6Igh9=Fz;c=kJS16dF(NxL1bl6@~+r6XGiZR*=SqJ1yOo0M{EOLedN z+0WB&-q;iCwAT?%%`cO>o9i@q>%imE+~`vz!B5=)iZf7XV?O)&6^tSbDcDhtM2O_t zdNL*Y!-8{8Of0z}2E((lapQr(`D=cRf+8FlXb?q_iCpN+f@x|@V`T{yI@N|i)PU9O zVM+v?s(LQknj30`8c~b2Hp5R!QnuK$h5_ws3O$kWjTm2vg-QrInV1??8QybC;szwH z7)EVW79@x5f1Hd!5zzgj?I*GbP#Nj5&RLev$BcwmI+awdAsDit{M+MLm%*v_q%G65@1N&ls(yv)jrlo~D z)3FlK6>GF98K?!zslZZG`-|Gy(Wg0%Q3<*h3G<>)8F4BYk=8TFKISp8*R;icSkhP( zMt^xQU>-Fsg|#|QVoMi;=4*!`$(q*xmW@CjESC0W(?2{7m~Bl`F<@UX*dqUfDF6=T%E40>J!P}KQv!qr(E_vTLjI-+B zwU^x*Z%%S5F~-5KiaSpRQY})+b`_mEjm=(?o^M$ZZ}~VqlPnmRlVeB^4wPS6BP)~_8CeEO#oEav9 z+)!w@7sd)Gej$%+nkO#Mpse**XXA+99O@_A64lSjh4bqd}v~pdbvhS-^U+& zviG1?2X#eKF-?oZI#s=kH-34lbQA3;E~k7oL=|Kl1{R%sbVkW3Uvg-s2)PR5*&vL-Hn2OBV`bjFYxE&njO`gSq(LqI4DY)o> zz!LbAXxsf2;8GrD=*n)Q z5QWLPAk{ARnm}U<20OXhR$YOx$hg-+WVI>2^HAiY$C*+}A~f~$e$ANO=B{^+nV~=Bch(Di>dbn+9Qo z=ZD9!E7dipNe6BKT$jf;{ruBu%h5->@sT`~=**hq7!z-sz$X|mR%yI<>a5Y)OQpMt zzRAtL79c(*nw8n{_^xS2grmEi##bXY+|#G|H2f+K{(N-pleXzWD}?bYkp>vZSRg7L zXijbS$2ffoR3J!};HVA%16|HeE+kk*P?x(IadA{F^i?t(B&0wmKMu}xT&@ZO;7231 z-KGO4g=>FXCPQ26;VGJ5eaW`x1UA_g_=^L?IR^h&_HLu~E$~H){$Kpv;!)op#@xi{ z-9YPG90h%frr%N)=|QOM8kW?>`qN`5yln@R^dM=KLq{ z3RGg{S_~3Lp+yej{6{d7N5WV|;}N66+pY`O2EauzYNjx0A0qReWAP_M5d|G&G5-p@ zm_kn=d+fTa z?1YyP7S&g`tdtJrUI>c)#G4Sni6${E>Q5}5SJKAY#}1x~K|TIPDzQ?+2QX&(xG|-D zqI*kP>9(BZ{XSDY*rf4rCFjTYxr3nNqH>7UixgK;`l@`;WOsjFj-zfh^cq%l=aicB z{P#Dn1g(1oH}S|l0JE{#$aC#N$DRt&3S{i9ekYZ!h9#s}5(CVD$$)=U22tjY2JPtD zV=_&>QF)~&P-K?BG5r{_O#zU5kt^`Og4z0_(c7VftngA;3! zhmb!P|Ka7!nwh2e0+>32Wilhi+UH(J^8Ev-S=t9^BlySSGC?FWoi(3DI9<6&g`vIc3I4r-H|U}iY0FkBD3{-+96 z|BW!PFP!&lfm%?@Alx>JDq=T^F9PfS%)Uw|;q_pL0p&Jg$F1re);22bp6$N#C2G&W z&JgEo$ZCvlIP5L0Ciu5C9&Y(h0>NNaYg(MC^#wg%&gWqQ;5EXaV3vtES{weWL>5%vFC;Ypfjd z`ydY$>0uwpKJt1^oO_o*XJ}GjryB9|KEXEi0P&(Jvi;Gb2aV*zUU(&FP`ZKvC;Hc{I(28WMde;K^brfR{e7)qLz3Yi22Q(X zx1L#s{(Wr^2k?snz&n(pWaJXX&M^Lc80D2u_cb}Id&zRSuk8bB^)G@2*NO50tiMK2 z2DT0#TRtZwBt`qKGq)X>=b)acJlAKy#O3(Q4SiFL8^;+!TLK2R@zPO=o9Oyc4>f5aHegfmK*3H zQv3C>Qw21fkPz+Y-k`#qQyxsWz!S1(Fq2rD5FtoHk@@r~hST|+pSb_}vRb7hDF*m! zS#yl??|N_T|HaPezhg&;RP_HMH~)dg%ITXs{KLvo(6s!^%K0W~7$dn@FGRi2evmVZ z50R0;r4|sU0-Hmji1VjSa5gKxoDN=-Hv53|dcNlj*CT)I!`+QRn6Zk;f87l*UUQtz ze8{@tbbNdM+Nb>E%w&0MHNWJ`!wGYSPt7LPg^o3wx;TUq-dfaE5d*yQL*(-adu>wMb8u*?fDY#q-rq%$HOYJ zrbE>r1#jRRyAFg;%78%$UnCx%E=9zEYa8kme<75*I7mcZH7XXIna5t49kv}&W$MWZ zQy`nD{ib*ZE{InkX1pfRvSIAD(9TlClBIQ4`XOnz1^(OfY*EBQv*SVSGt2NwZrUi6 z;u8+p)WYrXfPUb@GCi)kUp!nb9jK0xLrH$RSM%DS9+{{%0|{V$T}pGD*Uo#2T6F{i0g9J4{BNBhn!!XNl$ zF1eZ_03@LRj_B7~tEEA~2VSL=C@DKVD52$kITvXPoEhha6*x#>zYE|-Hh5#+swAN0 zaC>jN)ARHGmsax!;F?8#VCk2$7Ni~e3TEqE@6>M=G?h&)qAoojdMC!OLL@TV|_ac)C2=M>Nl zOvc4#@o_sFF_M}GH-ZILgZ!`tmPR8Ul(PFrfAxnk`ak$y=8;k@O`{CrnS1m3=TKx@ z9{5f&-{)HcS=%sOVamhwN-$wyFjm!epV*kJ;40yENu*2R-nL|dCOn61eB zEG&Xdb`(O0S#YkkGS(V8yHM0OnU?w{UbYTIgb;6YymvwH@7l!-JmXD@K{bsD9c^Km z^}%~X^?(K8(pS3S`mPT>xMi2-g%#|${ju`>xCJIGB_p05bEW60WNtmgmr++ z7H{|S;Yz1W@Nh3oUpNR??EJnLlxjbm6giSvu{QPjA3)Qy*vUV?OzR+cjV#r4@wl|{ zm_BrSo4fPg&wzVJ5O(|f@96*hWQk@RD#yEhMYIapMyWhQXcSSVpD7^zr*&>GC#K)} z-@MxVw|VuySq%ISpx1vsMqA#lddkAjw`pk`I%A&ZtZn$<00IIC0wW=;d>;6Tz=Ed~ zfkc6~czr~0R+bUDs}mZvRKii=Adu3v9Td$&+aDS#EA^JT+F#RYo;#9cnm#=@9~X*_ zCzEMue;+7z$K%P(wwV&2t{Z?~Xam-?R(dNILxTL@1;{FyZhN2wGqiY*&N^%{+Bf{C zu#c-kF;hylK{%Rc_CVY=kF^Tq<9bVJokfNB4&9@ zY<}+t(LATQtgpy3z~nZ}gw5+ZKL?@880*d-P-b~w1uf7Id=G!i%(DLeNM_iPKlTjx z;ya639LRBchRyn_Y|up`nz1_7P}x$ib6E<1jy^69Z;G0#XxG@-Kzps&SWo91S7CB; zVR2;;OOw}Dwa`tU@Xr--qik8^27yZx6p0PFhNOdO&xRJ6&r)(RU=`C^GUO z9uG?sZgQkJM^Rp$t~P`VJ*F(LC|)$|DF7S8!%wGHSK=*ld9IAdNaSv^ei|p9!fukR z*l17ZRB5U)!z-GyvbDYt&{nUquF|f8rab3VadlZ@Zqbw17F4{jP%t!A{U}$ivZfX# zduVoD*f62C z)DGX0($JW97OEn_C2_i%FUp!)C2A@HQVuPRuYMQ2$c0g9bY*pYT;aESDpv+I{9R>b zYoSA5(N>4uw6rO*{EOSF`XAVX`rvAYHXufG*NxryUAc z+7K=*!2(*@>O6iy!t(l5ZGPRqcRt$qDvLB1Pi?Uq(6V_q*0A1191+2=RG}LRcbvf~ zakQ)KA+SE0nNo8jl%pO#t3uU)oJZCH!D>Q9q8&Oao@QS~|J+io&O%*Kec*i9n3RJV zGZT2|ctSNU^Pu**zIZtpWjs=NU3zM;*qnDmPkR8B|S0 zro4Zc60@}R2zV{ONSQ>^-b?I+w9=+`noL?D;=CMjU6oB;ATg8 zql=JhSbC(LT%wY>U0cBzRNTU#h`C*3ewjeFEVPIWFS-arXMR?ka64Erq_}ncJTeR+ zIbC%lc|02o3$0{k5j)8!s!(#X5#G5g@o|o-f=Nz$t*{DvNQHAWL9Y9+TqPJ7TE{|Z zATA|*v2;*_>{nKKK&3Y4yZX$X{k+sq{@aMj%j|;u&7DV zV5KrQZc!y~4-Qrq^7w>pxf)LyLr-0|C`@d!Bc-`I$)Kr`>dMTeB5&Ls65S|*sD#Rr zi1Mh=oPb)n$SMD)&+8(dWCV<(LxuggIU5RJ6z(UJ)5Y%MDs z)j7y)J7vO(6^4_iXdH&MeHV3c-)0937)`P1VI~EtTRtWhR7qb68_Y_dkRu0R~`2O?h!5c~jzc z`~`==XTV8K(MwfHHey2z=HJq4VkFCF#cWla7)QG<%?j?45mv?VzBYD>Oo-4GlDb9A zZHz&5(QnO<17at+O)ktF!r0Pg{V=o3oy`;U9%aN)moXY=M1F!EPvs=0{wIkk6GKU? z(z&8w9sJQyL+oRB0{ImHOQ&aCc?A`lPlRYTl_a)e6O7aVRg`mU<96()!{iK3amiDt z25MNBW<2`Nl;e?(qv~akN$_A_N8!jwd8w`Avbx)~#rlg7i@T-jr_dW3at~1Msb3K1 zDb9_q3m7rRA`jsvMlw2%yZr$etW3cd_Cw~?b`)^fmp1Rdr3czUQXMAj(=()ujOiW8 zO$p#fvFQko?-Od2q)bhgW>!|$mslJgk7k$m8eVRuO*PkMR@GL-vdL~@RP^y;uWN6Y zfV^D5vbzCa3$UzxLq4ZL6JK_WJgYUAth}IJwGHZRIgHcJG@n{~<+wI}n&^@5xH8zh zE3p_{gU-BG0UMvUR9qu^gFj?0ca8&jdv^^x4V0go6W%_p*w?oMHbi4zf3>baT&E%2 zb{W%#U$>Ak4-NLOe^PeY&#wo3S`j_R$7@w<6AoKJuk(}dd{+6H5MqfsGS9E_=Rwcx zad}p;SXO2b+s;C|0ym5(dB>D>yGUHcYDq-REVawG5I)CxZ{F4|{TzJK8H;%&~>{ z@%UpLS!!Hm#Qe~{Ab_LcyT92-rn4z z?=oHGWCU063|L2J1Pg2Lu(}Wis&S%{cEwj`a?gL{xn^?reI?9?&yia_7FY@@+HkXk z{|;vu@3gY`0_;ELA@a-H!T92kR|n(C%&fuoJp$Jh#YJtF9z9jT@q{U|0yEbwXSe#@ z<=8Ffq}2kp%xAo|W-u2Dh0O2$1wSp;b6FDyN#`KQP!Qj?Lb>02omZz0tmzifi1Y67 zy4$l$aw}4humr@*va8+9P}tlw>c0sn=?Hk|)_mrlD;UG&$uWkL*M1a+m$a)WMU+{b zT;fRcejhnNhCmZn{gN-q%HG_VxCL2JH6X6gZ@i+L?N~o*96*LUtI>#ZaTS9i?+~$f zABdm!E&1T##S>28G+}Blme_>&YjTtR-oDmwj=H3*q`b0Bm9DHy?OE0Pq&&l8iKU(sObqI!^w6elnZOzL}4i%cK z>9!mh28bazG=YaI^PPRJ98zNPs?2Cg?BqSU}Xiq265t4uN1v zdS7%coGHi2pKe_pKL9)7p3kJzo_1Xy!sD8&l$wE0XV5v!Un?&YGXtNv??LQOW@~|ab5hd5xZo4DbJ-QRD0WKZ)-ZPiTK4Dz<1^cDMcuTrk0wTO$>E1cwZg6O z{!D)-+^^EiJ}9{UiA!k!;&M-}2kP{0OyCy}#{EWjA9!%(m%{1y>%ezIJe8m&GXNbtz6xr6 z3yt0Z0q4Y%UuG=14k~(PvqNiF6l0m)k=hwIUHuBwKWGKpA9q^EMGR#bIVkw0Aq^T&?{!OSNemS5~Hk`erA z(<<@y@#Uv#;-rw^Lnynh5LPM;7=S&wI&0>p0of7&_$^u{hi~G6wES_w!hR`u9SLI% z3IkEAkEcfSx~e8-bbyx?6>@h;mO3n8hn4Y5--W5tm?d)zV%LBLyt#I)HVb*LIuA`p zkNB2>GAKqJ-D_eT-4K~7Sh*g+3Sz=kagB%tx+P{|jfy3J+Qe{8L4|heNbPnPD?EfZ zkN;H6u@o|ip970;G(aJ-?*Xg~PVZqCBoh`QP24CN?+^`*KicnY6~PVuBF?W1iN039 z$;{u;?mcs5rk9RcK%%{#tuQ^jj3ubiNm0AF8tjZoeBPDc#E(C=4DR#{s4I+a@p+Cg z7>D0u@M!OGJUJX2r4~_Wlxgabnhq!JFqMSIJhegEk@S$=FkaBEJ)MsLoJpST!|I3ku)?kbIK zDK+z%_GXg_ButHwNfZk|I@IYgP-r2fQ-QA`dXgAEv>3mcg?Q*TaFGuhorDR4%G(#_ z{{6{>pN`22v5>`49Tbl{R6#$Ulyk1e5Z0dbO)VR z;OQGx_gh_X_G6Sn5S*-G9$~MPj=7?CA5c{XR$L`5NDqy_WsO&tUrD1wn^<7UgxSKd zMA=wY7(|M$B5O`8p*IP$FULUac6UEg%sx_c(^|HvSVLJ=8*<7)uHtORIARHT(WxD5 zDV3SY&Rt=Qd68(Qx~X^~t_=TaMWaa{tKp2Bx%4Kbs;n^hY%yY(%vja!_EE_&tIYn> zgNVg9s}mO-*W z2pqFHoOo+KG_Qb`LK}+$G0&l4lWGgXI9@1C9Y?$lUfv~9N66jkR89mgVq9Bci2I1_ zpgUW^t2#az^T0`KqdyvEH3&deML{SHsT`Qm=wg*O1n+sq7>OK0(KMpq664B1+*h}7 z}uDY0#oiXhEY4&>djoqe4u{IMm}&K-V-^x^AP z-h!G)0G^>|BTu~*IXdORtp362cL&)%IV7P=ETKKk30R5%Q$_wzJiK2}M41APed;7p z!W4JVD;CPxwz^uKk_v6qW3T?+dTLbO%J%3H&&Nk@_(F1f5`CG}57xmXNe1 z;k2zAfa#;G3znDE8QSE+xgkvLy$ip(UzS0^L!@}!oclWgr927(WeVg>;AsCrCDEW5 z#|>*7R(#*mM5B3aHP|W$fTu#P?fFa-#9{7gT$wIT+B?W{VSr@5jDGyl>B}ukbVn=k zkmb4xfONEfEpr(?mOXg$BR<<&?V|dHhp*+3^H!YfKojy2VxIUh5rRuCQWY>G%Nt+~ z`xtViDMGX7$aoz@tPdo!tLC9NO+qHA`|>w%W{`D!qqBjReJ{-K_f4YneSkG&2DT13 zZVP;wTaogG6Q19iLu4Tr6cB{f1p8Rq{5f)1MSfbZREXkr z_Hym|Ox;WISHI3*j39rYHR)Ag;-_2gsc~s|oRedg=gl2_3|L9TA_y6f9bh;HG->D& z-%Tv!2NBG-uV7bsMw)wawjguVfvWuUJ?jw%^>nSZJ;0q7eg=V-zQRLYdYi;mE6C1g`^)O{lgffDbP$G?PNXWo=q015}EX(ThtB!kLFCU^NZpLGBP5N79A!094wtc1B#vnQITM0^m5_!J>ZFqx?)OE`uc1_Bm_D59@zNQBl4#eV_Cs+FL~ za~Dbs<1621QOsX=JY;48xb%#Zc!q9)1t)D;n`WTw0P|CBupGPsV3pan$R}QFNE#Ij zahXEMJ+(VLcafEN08D%2-f z61GDVz=MNHQb8FGk0FaHG)ov+T0C|pMX}gQTlJZ94dPfp*N3PDb?Aq4k78IC?a_H; zdIy_p&&V{9%(J-n>Xc^tvPvmmhnPPEG263BaGfexw200}Vu%3}Dg}J3;id1I zg=^ZcqzjLxd5`i3Mi$X5s}~e;=e8+YX~e)|oHjP#_p>$mFoOn4RCzI(vEx&`ONUZ4 zguj0o^=1scHUl?oS>kR_7vM{$BvtY4+)DjP11!b~=rC`g@40Rq}1DD4rYUdsTEHN!}r zSGL=&R*#&?-ADye6tebVNWNprZoQ-xtyV*A}9NB(MNV9@j6=Lq-A|28Ve1ji9r&=wZSK%Qn4XduGq zhMx*I8*B_H2CJT5`x?YXhF7s@Rq`0!H%sKgLm-}bo)KM1rUZgVmusg=DO-SNrKvi_ z<>`j6r7VmabuJR9rz+C7%hXI_#H1{I-znCXYqgz7kmf{neKAmOlddS}Dxe<5RA@Jj zqcNT!*E#1ZQ_jOQ=b$dV#*7wkpn}qH;cMo?PQ^0!4MHS%Q5@|xn~faK+4Xn`Jnf~) zC#r9`KET8_J5!*5S=Ur$n;Ecp3Oh^hCn3MNFFocYOqY!jx@xO#{;;=S`fjGe^_FYI z-BNfFw}VUK$#55T;K9X)<>emtNo+Wm6mcu(*PrsI<9U zet!OsvT&-oO4|kRgr~l_F9y13A^j;GMgUAPJ&{J6uXN?!AnH*)Yq)ybYB_LGbi23$@dhnegVY?}6N7gcpR-D9^VX6bVyuR-E zkpo=#0VZAjUZY%_XT(|DDtG(jDpDY)2!l8cV*>qn-YWybK#%_$9QITy3k^6(>#N)! zhZy!W2n`Y|~K+uTj-4gI!boc2rz4%+fQ1xvgnLprOXxJ-AHZ_MU^I>=hZ zoF4MBx6FlvnVcpO1+@#O*9XuzBI+#$K0Eu3T9T~lLVeuMP@O|8IegEszS2J^-|l3A zIrlCav@&pmRD4pM%m|!(r*wPXM7GfWL~W5^az><3_HM{+^>xOHm;vyqj_+vpAjx4u zKex65W0^lZiIZq&d+XK`WN?6V2zSiQ2N?ErGAO#r?L)k@aSPu9nyL5P`?Uc; zTc33cu>n%kuyu>F0d!OUu?y6U%46`ctLVb(HI3s}vuaqG$vs`ZhG<3N89!z4u~v6U z-kiuirBZLYYJADw9P$-*CAdkb_DtmI$33HCWLuxI%6V!04DK1k_{^}fX1Qrp^Wb+0 ztrKVt;u$Avm~)qQ>Dc|}D~Yv^)(!I`zQ$Phj&W`0_2?3_JI;H8wGQ_c`ckwz>TB@E z_-7ZkF6XV_GUwC$nbOzqYk23lmv>+1oA~7pw^i2;hY-PCuJDd6ZtOsqM;5NYJ-_s@ zxb$c&KTR_~3l?sROWA7IeBXgb&gvN50JPupO|LEo7JlYI>W-t?JLM!))-C%rG6q%m zu3&J6s}PKbf6mPhVS5K|?2h@}Nk9kXBLU*5SytQ(GD*`d z$pJPe-^=feRqYwE`6p_n42MVZ>A{0})U<-!D>{ARq#W5Rn*;LU;SJCkT(>lPFh<$) z)&Be`b-Nd}tmR?ooMt<>JLn8l?L@I#=?l|V-uG~VX;_mPSGW4ekRzFPDf-x11OH}T z;?=^MLbrhV)`og=#RByXv56CYyH9o*=di?V=WgMN%_lf}RCXEkcIh2&yWr%$;R&K! z#&-AON%4*Sed$xnn{wZF@8qoI4)U?%HRv73r|z4sN5V4!B zCg5QMI^c!@(5prNj$4GHX9jKb1tZ{%hcITxHt_*8^589CSYz@hn%7FJAD6!RC3j4A)7J1E-*^4hpV#oSH|I(16Mcs7yVaD8cNcv)=jHGY zm5cB-A{)+kO|f71PU@h>!{XI4+x^pdhC*uPmX-VBO*0$vZ6llVjWfH0Zfj`gfvbP# zrE`?`)+^fjXPEbX_^!vz@oi;0?(;?`!}p--aL2>+;ihxs;ijwN6?XdpzB}>f@QeE= z6VYOhAP^Tjl7 zmr*ExhEz&7U+ftgHTi}tkTjf0w@mD13J%EoK`7WZ4(-qqDZrbWU}6Qo-rE#xt3@aB zNgHqYtr`x0r^&$ohQ_|}hDZMc2LYrT$RPj5kbdkXitN!-D2`V=@}VS*!MD2fHU=f> zyI>IMM@asP7D4e#*`T;b2kRh*^86EWkjl59^d*PN&JwC#y3K3w?~%h zaVO?gv~JqRzVk=8ZuKYG?ADho`PFyuvnHQ>7;cK*r;dq4rE!ob!k8XCpP59map*AY zIhEc(c@k+3UXhf;5GAxaRiuujSlel&5}9=PF;vlj2EHevO(qkiLH#dLg0WIERlS^5Y&We-@K5ngR5#U2=uhEGNROefKD0X4RJ>f`7TI8AEwtTNDcO|=B`+RmOZalBG zZuqY(#kk=q{DSf0_ZM9&C!=9emW>X+F2535`IHFYtev<5E`w1zzhx+7`(w)V-d zmYaNc;+t}J)|+B?+M8&1-dcXI_|-TI|A)4BYR@bR7InMRF+0u|+qP|6Uu@g%*tTuk zwr!go8-23Y#`Elbu`bS8XWq>D14h*xHAdC@g6)^I8t>!TlZECS&<;INRyua&4_d1% zwr-%({52Pe@kHEPL6zGK31|CjIE4P(v>)?K+5MtU@|%wzYFMtDm6b+JhdWH+Du-QtdY_Xi8HAV$};g5%9LD;B(o$C$)^T8 zt5!uqs#SzSx>bfka{3M%8CP{2Nk?%Ud0U*kXKf5W`s0pq`P) z-cK=^T|6xzwP;diQtg;bRvC>rnNkX=gi1l8Z@|lv1c)QGrc)P%f^lv}sGgS#GZ~h1Ew{J{yKPQn1X-8>V`lG@@b$?~N zeb6@1QAVCM759jnNtI(qT9uZ0At_>#`Ur_hw`~!-M9T(^s)wy2(Q*nf?tH9uB>dSk9fwEb2~PChtyMrsK|BCa{*Yn9rTPSj3&S zSj8<@Ze4!SdDRyY!mbN5#u zsXj^_EU&N`<1mur?u;D-iUF|#g{MZ~t#DkYgM9v>K};#$(73fc2?@EH&7ZQ-R|9gT zg;M5z)cT&GaER^{p7hFLL!iIpl9GOEAm!o}{c@13zj3{Fng?|z zoqM7Mv_(L!gmkE=|9wO zYqya8pF%~e!hY}<5FiT1FMS@buvub5`Um!P`hC5E#9mfhKWZo$#%>oekN7%t>r=zE zC)(3Q#*J*lO^>2%DXpy(cgbB5JCQP#HSE{WL8woYT)br{_+_DCN>p;9C_T5eZ?toKU4M7-^v zYg)792h!KS0ft%Kuekmk@wRo>293YYL#}op)1p~keIZa~cRoh?piMzPZ3WV;fQSEn zORqH#{)@C!3u3@);L-F4wB>|_VWy9F?VjRiZ(Sjp(k}+P^2^r; ze$+&XG)oX?yT(LglUyvM!UyL+Oua5LQq3vn|!n@vS;gKM}Lzt8Xh6z&;B*!4eOW% zz zF5rJC-}eNhFshMq2d~@Zn(Cu{2x>;`Ov(oM#&3=6_~G8G)qDDOA^z%#Lw!HN)B!gd z`T`67>lTb5lrw{|W}}zmK{P+CAd?9_7H?~AfHRE{U&MVYxq?JSmVKzXRXAw#tyb{a zm&A5FBSLx>f!L)<1p+7q%k?wQ8|#n5wl~ zEnL{5(zll&V-V3Hl#7V#voj!QSH^{s}LX zJQf*+QA&_ZMIgBmu%0JA79$5gPav(u2=u4tGpB~ZM}eS`5YqUa2fAv~Jz{{!xCei4 zjTXWkzejryhZYkH_MBc*4;rYbm-31vC2aO%)0THcI#6*>;a(y+(0XAP>YgDva+cq1 z+$&WB63*Xr3PK%Pu+=2PbL~f9aDT+HO>($AYp20qJ#)yT-izZcYMeZ7w~5XKIAL{!N%UeIt)$&m`nf7b0~b90ap5xP(9xXFrK(wW)r&0?ZW z3*8N*i3#l>_^ErsnV{XyEO4<~$}t^O1>}*}>K}{?;UP;`aXZ+)qSFGEoJ&{ba|<0* zO}b>lJj$Iu*bZ7Q(O$grf)t(S2O$dmuSIIC46xG}_@IwFP&WJvcCyx=?*39J*K%`8 zXL`d@C92zYfr0g4;Du(SSypJpNJ*XI4KexL>%Uy&1NSG{PwY6zW9~srv<}(nraA86 zo(AXk>QSABpq?$0qPX`@V+JqfdJ&mq!vS{N0}!Vc`jwDF5%Pk)vM71POi)9+GiefW zDSckLy|VDD6oiQu#Yo=3cxgr@BF3U|qG4t#KpGPDwHyhMLNz^5(L*tA?SMmd+y-OA zrbM%B%cULCICM5QH%T%iI6#DaVN!UVdZH)`ke5Yaj?ff5|7Y(^wVj2TT5g7sNX)jr zUu9*SXjf=%dDew%Yx1)H&s42qRxu!CQJ}s>GayFZFY1h%ZfQ~(Ed=~g5MkWUOEzlM z4pi`;KkS$vb3P%qz?;5eAkpY`IKMW=V#1h*ulImti{VtHJZaRXJQIa8a;7Z_1n|-d zg&Od$et zY6lZgOnWk3pheY@Wdr?GfFkC+5w~jQNgl07H`y>BpxQowyM`ZYZHza}xuI`eMCd47 zJT@;(&M#XRT7Rp652Yz2(VVAhH5+aX1*8y$ry;oH{#fPss8M*DA-osw)d8CK1i~s4Hejlc z*a${8zweMcxDexbm;X@O&F*m3t(G~GfLwZa{Nm8^%uHWYcMl)4g*ac2WG*Qg)-sd@ zv?FDX3B$N&d>nGNt-f6@hmP8I%Zo(5g@=qR($Ey489aejw;mh_xOyPOSCu@OlxxM4 zh&R`iSp8ZqEz+zbXZfkmp;l1rwd716t%=>&e1?-GB&BJ?3Rjf14bx!kXo{xoF4Op$ zw{Wh@BIf`mU=FH1C~8$)je9Xul<29*=K|6<00fdoW;~2)`Oujq5PdKr9Ar zb;cSqo@>g6W|DG|Mj8#<9IkP!hzqVVqY3e^q#qt9g#(7j#~PcUq#+7url|@`UP_zD zp}CkS_D&<^=^xW;GEyG#RC6=Uw2>td$#|xwooF3QI<6l*9FBP^YP9OXCfo%d$rMy( z>xb?bYL1iAS613^O^nwwb|`cwko=Yoa(Q!*jai@jHIGjt_BHN z-#Bx4_-*<(q42Hgs%HK819~z2da)W!3YT)EdJo?~VrlzapOjlq?a;h7k+ z3MgmG%WE~4c9~T|EE%@^TQgMXtkk?~fpGmq7Sx@gXBVwe|Kw%-VwQwoG+ENrWQ^)8 z7^ReGlBN%asGb&8#z${p~WO0VkDmbj#(kD2VxSK_%Ov%cLRw>TK zn`Lo^s+GhVHWnGI$c~@O4p#A&ZZ9bw$)74Q4ImbwE?Jxj-}$o!eH6(Yl zLtgos<0s`uol;eYCFM$PF`83sWlFC$&X~UZS$#Y5mahos3?FLF`SOde{qpFLJ?-*? zWh3E6kL+>PxO8`mA_o5L>dK{X`I_2V4=a{##>omAZE8%2I$U{u$WBcBZD7SSUgN5vwAE@_RBo7Z#Hagy_- zahmg`ah!9}BL?S&dflyj?gAT?Y&BbX9YtG39Tm?cw#AGjzKRxd-O?7yowAKZh4ZWP zx$`WGGLHsMk#EVm%C$m_ifft7xeZI@Uj?;_=Q7KsuJg2W-bcbmpGVQhpN~3^0*@Sz z`j0A)h>zZn3XfQi3^bzNT2hKRv*2ZN7HQ{7n%!@W!M7Ex65bM2in`0?OKOdrk1E!2 zZ|Ti~-r8Jp-bx$!-9=kP-Bmo*-32@q-4))s-8J47KBX{^##;qG)$dC^=Mv}W9^r3A z*=0UOa)XV+pBcO`xA#l74WTGT4BnR>>-y1yx`a+icidD zVPP%b-O=cg!{IxM?YIA{sKN9Vi52_Rr1qB=;)IylZ_lV1W1?E8+M5PxRz*qF5%78i z;ClZ7W=%$3UXmkf007nWVeW zq#;2d<09!7b_PG@eE2HcrCA`OGoQ`-X({Ujd9c$OYgV&Q+*QjQEnBU$VB_B5E*s|2 z6Y!7Q0ejo$uuO}>h}EXFWvroc9Y~-PhN-jz+g8vphU-F?wy(TRZC5RDXNWXDtDci5 zOGc2q_xM}g8Yxc=%+0v_L79zHGSVOzh_q_JGa6pYtguFBV=x3sLNOCsRT;>-HGaSE z(H17Bpo6qht5}b|xtLt%V5(%<8L$cQtJFHgn?dw_Aj{4xv|FsO=89V%2&1XlVLjVo zr1PgkS@#VsmE;=#Vm{#`^iLlxV!!nhd-fcy-8BUU+PrbYj?X)y!NH!`?I1N_~OO*%A zcbLirn3CXk=(xdD?EI(^x2golVY!v>pEb(>Vg@^+l<2GD%9Dr>wkjk|m`|29P|6aH zmjOl@v?Fd4iP$Mbm)4THh?1iC9NrqpF5%2so$ApGaKBC8gwO;7n;}DZnxy%7m9!L- zrM-)fycqTjlr|Zp?Q1~*#0RxGq!8Tht!dn%nEZFL&lNHFf7~&$;KxVmPm>bF|6B?? z{KF!NAJ$J|gfC0HRz8;)X5cRP2WRrEq%$D-7i>!MZ?jT99wIzjfGV_gfFf%9N~S-N ztS;SC{|~C7ohj5v3LbZp-%^vx*bc_Gs!t$-8GGtXs50JEizjng73@?);pTNn>sc`= ziVNtrdxrk0EoY4KdA-o)ThZIlMHGc1jNyQm)yRSvvqpM2w0DSRRdibuU$KKw6|{n? z1NuUa2bs-MU~$r{fvI?hTtS5TG~9(-8`mJ5!r`!?7m9UStMzvm1&wT3k{{%{7mdA# zB z#a!|CVh+Wb#O&;c?}}e5-^6J)6)a%$jEovxh60 z8NR%1Z$;dm*s?!nqrvk~{p2zr?bnGha#017RY3=u3^1xx{Hj#?nX8~pER}M9E}&Uc zX6DKSC^7KBOw24<>|$1-*$g^mxWHcavOEe{qhZgU@6kx}@o$!_*WI*zw)q zx@Ef1;uUKTidmxH8#Yb2rMPhL33d4ER%wsf3Vv9xvv|e0(D+JrMB~j?pV(Styu7cQ ze8n{f`Q}+4^;ob$igaj$HgXB4H)}`E{zW3VvSEF@GP-TL0YFxcYfp_LTb~;wgS>hCp?@PBi}Gih)G!y#Q%GTfW#*j&h>$ zbNqFEVI1uWU|jN)c^B-$?+)}7d5w4~zw3HRFE?ui&TlJ+nAw(ztZ!H(JY}~ldgd6& zxlkPP!xfH_45ZsEu0FKl!;VoHAHrbshA`9!8vKNPt&ERebjQu4C?k%Lz?f4}Fru6`x<9;#WVYw6 zh(lCrZ;ezLBWD)E0V$F#(*)I!rT8ceTtgWI+hZ$AQz1f`P&P))pd>QLVa$<9m=ohq z8z^3g5F!k1JNJF^J0r>{$RRghu`5Eb_eS_JU@T8dj;x7U+@|G`bcKzq{tG zn!WV<&Q8`c)yaN-a#MreY|UN&*op0n4%z?t+SS3QS8^|33<(Ffsv-8a?d5+zrS8Y8 zLkYb~^0R}Qf5%!G?9u`;9W8f;#scJN(odUA@R1NjP?3;%BhwlaxEqc#l!?P5lYzq_ zlW~Qu$RX?fBzuyAMXInRY!*w#Sn$R+8v8?4;>?mCPgOnuA4i0oHm*Y80x*7eiqvt) z*`JAHEf8^L_4Z}6O8;7SLvLjKZipnt7dhWGc$7-+< zYJn!T8caT%p$mj({f9JO@5>#?NrmT(;42FcC7VmGv;v3YBu8O_D2i(|l?}cK%L#iA zD8qF8oE)LP=qU6SQjR1fRaUms^a09P06T=?Ow)N~+w!Jef%Xbh2yH#kS$Gs30wK`k z`HOWi56g6EO~quC87)I7L-0`*bqhxnhk2gkH^oBP*M;kYK54P;V02MNFKd)9z8;y_ zP)$sDj{>f6l2~CXevw%nnfgz)Ml*_WwAy%Wt8lbF5-Il<4P=lz+$WIz4opub0xPge z{?@o@f&0oIRTp(=AT+Al9Xze*2C?WSSQ}@ni`nKR5Qh}cdY8%$TwsYzMIs#_H7>95 z-C5UW2=P^OxPU4<1 z!Zvbpp&DbvF4<{gY<>7tF|!oOy13(OJ}^Z0;ERRPpdYHJQw`;%hcIHo(tYWGrF6sV zI7E6e;YHmeOo60@2D5*)W$P=-ssQQQww%w;dQ2|Hx~yWjBhAB=ub-JEGO6i8GD7C-*i}Fp@43}4O5mIvoAYN? z!=#E_8VhSUE+WHVU5I5|B3czWSw0=3S`j=QlTe=dwASnE-f9y$4xDq63R?59rlA6| z5oX9tO^&bJuNV`Yq}JA)!8M2KXDE#3aV-Fl8k!U#VPAl%W&;jF?Mgb5!9wOmint1?NHM(unBgbpS7MzIivV8-2v1M)Dd_AHN zJw)!jH5C$dW~a%zzS>6sYdO4O0aS%QNhf$5w44@Ap0S$hiP~7H2+Bivt^83}LY9bD z**Owh_SeUS+FG0Eul*YXk@K2v`{gSK7+hc~>*V_%^_g6}JG_9gOBjWw7+reM?HGbX zLH1Zd|K=usd=D4r;bsr|7Dyl3hgnj1KtyAIp*wGoR}s~F1I)=5^zi%ME*jzUGVI<6pRblMeAtzu-*Do>$l9 zP|1)jS^E>O6llK2jol5rg+e6m>{gN}qdzI9XR@u2U5RB6M$auUGP1>NyHD30i<&0h zw~t)4HVmf97MUe=-|Y$%0pjLQ1sV5Z*HCF3kDFJrR&~~H*L~<5Kb$wRcAR^wLua)d zX&*@=+tV+w^{1Fl(i~g*sU@5FNl|BaWS=8MIb@U_b)2wS9C1H!6nR^|<%q|5kS&js zLnlX##xe@7AUMQP+fY={$DG(az{44vsN_I$N_NS>Uav99LVO>#dtN9A3HWz1Jr*uMS_r#+!y$ z{q{h_V}pBIcl6Bc%KhtGTc^ZM@5aNuTZ|8H5A^NI1^O-4W5lcVTaj0e55QNsClhbB zX4m#q?bh|7;#KU8<-_*P36de~$|FTuWHdo3%k( zw@BsuHDcCV*FLd#2)oJ-g~x;TK9YCKYUwp1@bO)^#;0esm=FK&EFMb7W5{66L Z zTfx52C&O*fSL^-~p0dH?=eXV{1&NxkCZGyWK6*Y!EqYm3KKv0q>FiBv9Q#wHNWfPH z>Y|1U=M8II;tehrlXNw=_Fv7gC#m6{=$9 zwut(w(6oJ7au6*sK-8LvJpTRggmrC^= zz$omtgjM3BcUX*x)Ow^MlKWi4sD`7zW7)vSL&YL$Vl+%-9l)qs!ZK_O8dkq@Gt6vW z#HguaCN;B!19A3m|}%LS|j|W%kkb z1@_f-Gpl;s7MZ5pQK=`96OkuT6H#nYJ6JscH8-!}r0l(6m23mU0@HB&sFLZ{=>-$5 zzh{hJyBuq)hZ?q4PgeBJZnR9z9;}!xZZ?cIkDE4|du=1F3k?gaf89r0NAA1p2JQ>$ z7AgQ8oym3IlGN52EXF7Ii%5vh5deY*F!E|UX?S2eA&RWa6yv>%XIN<)CaR=M4P(ZQ z4KU;38FkVrhXK)vMw`Im@pI@I(X65VK8tL9ojYK*keY5AV>63s3?VlHWfjhoc|;894 z0OmAK$f8B3+-&FGmIwRGS7p= zRzKn_a+E#ds1BTyXnx|wLCoVoG5K7c^{H(>2 zU|z~*yF$M@@YsDtsDt}4{bC|e0f}wrBmi)CX_akDQ`r9Kp&rkDk$%9mtH>J3LI`%V zg~$=iR?&r4C^!@rZ)=hOp zqCr>qN}H5o^clO?A+Dn!6GG5^uYuh4D~NihtrC!z7kdC4NuJ*jHSwr1p?R1_3VxrC zPpP@rE4+4Umew)GIp9ia8n384@FuG}x}&@R)n$X3sHg<%rfn9~G1fk#(x-}ZfFymF z)w2%G_%YPY>aMUA%&42%w18?<`aok?ar(xn{GPrB1&P|{w1c$#M;>bN4XsW#a6EU~ zmHI-k6vX8HxM2xWCC}%imIYE}KyZh8Icl@G@3uS5ie|r9D8Lq+3o#GV>`um*jDQ(g z(@W*jDDYgbttKx1Wxt-aoVfSLI+o|!)_lz$q4F-cyJg!RY<)W zy@v6Hwe>oTD+YdecN&oqQ5ih2eF(>;G)y(s+ie%u~dcS_;Re-}O@vjwRgIa;KVsR*9T<+?P_z)fS zC)OY8@VgYuFH9tUz9lBoHuCB-FR=cT#a=2AAv8uVUhhR$IQ|~jh;DBrnGB5lktBuG zcGb*M$raxO;+<4#<_B4nW^Qt)no3nxG-jE^NMcW;!8Nr;0>@8iZu6iO$?`CD_oH%F zx>#DN$A#DhGu*oYrMvw)B_=1p{-LJ;bPsX&nf&*)0>P4DuH3y~_Xq?*3|=_T&(x?h z!AUl^{oEx(!4fhk*=OPb_iU8b`2=V-xA|QiIZp0#03@9UvIuD%>rsJ`oSV zs*@}N)l*va3@~ltakmC7&BaZ$HkPemm1WAjaSE7Wb&oda%Kp7^mez}VhduQbd1jg| z_*7LA`guul%#e+geL!(!oXyBPpfoM_qIORH6?36yz36msWKE=)woL@CN-(Wb(bngVOT40Yese!SQi(*c5ykJ2J1mS zTbSX$#=mYx-nSIx=H~;ENg@0ucHGMtvpJQ%lwA5xLo9i3zk~vW3&N4;7cPre=v!5ioV1Ii|^NT1P8~z%}5=+A-SzU-InXQgf1dDkrTAIdBAe8*eV+ z%jqHZP*UL9O1A;)!UYWZ%}MS8177t|Ulr@z;JDhx4p^>JunO>6bHNR^J{e1~)_L<4 zY~vg7iT=>{^}F@lTYT-$$$6Lc)I?O!thx2rYJE3SwQ0Z(tqQz!0t_Yj7H4+7R)3)T zJ^%ahAC$8@gvfzuu^&GQJpL=nnb!XYK-K?6ITJN^vN3ja6m_=wPg4H>gq*1Ym4GTJ zU$ReQ65?_Mege5FrQn!I__GF9W+H9OXyY;#bMs|S#F_nPfeF&I^4@=aXQxXMcv0{; ziIyDdC=oc%R{?m=jpwJQk#su4y172@#BfB>woZ(m*G=Dz)>YR)%PXF?`;{x}A6==p z`h2(*`zZH$m@!gksR;HD69^+kPW=I7UN;8(Hra^_O1!WJqXGH|q9~`TKEsoksy2j7 zwv_V6C}u$-RCt#Pb{5}=$gCJzK+sUZoOH7ujmTAGR-PBsR&yNP6Woerzx$k~0MF)-*SSc#D5QKO;iAI{6%YCuV!kv)a^aW+f5 zxyAV~6LU6;L-J-yQaSPP0#t=w#;aGpSqZf2unCf=^~NMzNtD<2;h&RdNCP`H{NuhZ ztHOxD{hXwWMsuvQeyIiN9)Fm;dmkfLlx{Y?%R?ePG)LG;oum!=11NA7+(i2>KP3>kWap!c;XDaAlRB-6)twRJ zUCHa%5K%$RvS`pI<2^0cGHD*$7et7-re?`9^bvOcZ~zR9gdNs;^w5Txs7!3gl^WMh zEk?~@%Xl-UR2Q%QVYRE*&d&wL(Mj7)zyiiP9|S+ljuJGdOjm+9*J%89=-xvxqY7{l z{3vpnN0Di(S@uRbwf1B}Yun);iw)O%+b}_XuPBhHD$s2A2P~d37eis%`&IY{xV2vX z6>ERC>r%&28)(VZ5wc{jhbq!Nm|iNh?&ZOZW;V~5-9M*vDvM&5ga+Pd9aL!<`>VR3 zY>VP9VlE}MzVUXR2u7WgmM>Gj^xq)vUkLW|c&#T%^a z1nVQHXj-3>|P@G=|_GY}0Oai8zl)DM4K-u*^K9<;y%KU|5 z@{UP$yTr`^sdI_u)~Z;rZv38_(F+UaAe$Mg>l{V*5W_8w=-_iI8s9GVBVBk7C90)h zzdmI{RwccRYU;E~>U3fn>rGoci)z^sjK;B7mM7hc`lEW#PM_xoT66A5Q?w`z%Q5~x z_Yw-O)kGXBTQxW4iODeCJ)|B1^qvMq-`pUFjF$%gwluSjH73lJW#~6`Fz?Dp9Z4E^ z5A+Jk4(XS!(E4Y|)b|NBWk;KNSy~ozDjnB-mPFYbUDdIc;O}gL9?g039tz(1Mav6g zZ?Z5%J$U=u>wlzC7s2|;u5Y(lHq?KWM%DlO(x|Ylvw@YdgpHB0+y6|V$}&pG0>8Zz z)~4cX1%>%P_~ixSb7@0&@co6$YYEi_^~*{KD#r}!BRa4O8y6MnzQ8_zdh8h_l^*rY zSNM)}tTSmKitzNQl5A}(eCj-Bqe{J;2 zTI>;%i+7O4U^m}I3FsysSIPKuH0rwP?wR%h75ox=z_~{cw$K(fNgcp?Jf);#xNUzm zW??-2WICvoMkwQ6gFoKT?|SHove+MwOuu;2N!ca0Xg3A5()3wZ4+)ZiW_p*c+c=m{ zo@iCEt3sKLrH+c23{Gv!;6#~x(PnIb{O#@g1xV4n$s)15ygMB_qewg0Z1}8pCJumw z^4CP^<~d-{lClL83x3cK#BI4&7D*#DmpDNmjISNZ~<-SImc- zfORH8Oti?qYYbdG&W!C{E%N=LD5;17?eg0R?%|PPF!_v*;R;0?QPtbuy|vCv+emth zu*KAjN*GWa7r&shM7Men%?-lkBgae0#Squ;f-J*so&Pfmd^(jqLg1GWtQuPn1@Z~K zl>x#NW8v3gaNeu!e(6@~CrwZAsGcyHly-RLX3Xu>S=#C`>PTeD^X5L7Gkl{Hts_*H zlZFhvl~AM+(bOp;n*{3Ea8gfzYQ|UxJbaXu;S-L*TDHoK)jQ>?CG^m2zM^^B#_S6X zu^S>>XP|1ht0F;?KAB5}tw=$>{&<3LrdK?DK7b$*LxbrZyfek;I!o!THo0(E~?fG03KNkvzp()L!r2wKKgW#OMGIF+30j!R=nBfBzIM2&cl%F*fh!0HgMMdxw*%%G zQYdjnUe}8@I^K^3s7J8dmh1p9Na4Ss|{C zXKCuMq;7Q;$i|Dp*`aoJO9L!gEp{vjBCYV}urXf~H1w0eGw$DWey;B!^K7smbjnJ# zD2Ltjgk1z4Uv~(lsz!(W!?4rBpoVMS!}57J=Kq!jX6%}ulwRGeS!p((deSf|8vEff zOiqEd&k`Nkd2VR9uS|(NBFTh$MfRYo-a+$XM%l_cM4o}0C!&uyceeAs$D^vT5Hx%a zmp@Hbg{bRrs2kuV&osjQ-Kjy$8-=Zy35GcClAHV;jcBOIW=2o2Y~y^r1?6i+no~eL zM&OisVW&%6(uVn=wR%w#6+XcKV=3MXfV6^qFU7w9-{_nI298b+`i4&bhi0lu&01b- z3E%_o=}JePF&Ik?4mm7riH5csNG=Mg4m((hB)$qt(nykW1a70{veMydUc0P5WKr3y z*~CycCuv!*tl305==J-(U;$wIR+4qr$Yfoj+q_`@kD0IXDrWs8^V9G5-5=!Cu9IxX z?Ry{I>-X&UZ+5=)PxS~T9Z2it^^d%QTh z@m$ZIx5nJLhB;bZvk^7B1a#H?1DwNM>fvHeUP}>*n{)`gPuWnkr z-Ngq`bgH`&uP+`9-G53B?-q2tkY`X1G`LF+fI6Fgzc{m3?B)68G>FDh+tl=AbjA8{ zp#c&^oL0g4VR3Q7+^CognS0K8!t-^af@fD5|j;0xF+~Q>~HK}Tx8RtwmgF? z{w8VCZE>YQ!$2eg$H1mp0+zRh&}CkTsLTe#^L#Lfd1`HImcu0R<1Of0z0Bd+@rheogJ>_C5vTQntRq;tc(o&g!Il{M zX|mz`kkUg?2%T>E1^JE z!dy_@zJq8y2u#AsEKH;}B2*4MjfgaIQ(s{Pg7Q>Py!o84L*$Q%+iy#U%6&*ODqdnP zwe-(*sDJPm`Q^X^D|gFU4UtKux*{VW{4q! z<0$)%FRwBYxjYx0wD?-h+YP49^B#oT0rqnf$$TY0@5gW3w;Q6)q62HZ?Y@|!G*@Tr z$2|;EXYA)ap3L87t+1aR^Rg>{Z5Y{R>b{64Hc>71DnC+o7fEuKy~}%B0MU6K7Bfdb z)l^7S%GSIf*hs99=*`F1TdvHmPOr_cw{f>uanBH3pTzos%`S~QG_!7d#9g4eXwh7B zirgo>G#R2wx+9mw@@;%X&2bFdDx!x?gUwNO(n%HYnZDn6y!iIgBonyHYb#sZi|cc% z>z#GfznjyvOy2m|u9E}{$*v?}E!A7xq!TCZD2)%%a;9gnI%yXM$H~7($;TqpGulH@ zPoUje+JM_EDnSV<+9V(sz}#~$A$KeJBL3u1`Z!m9swHzLNm6SSF1p~ih;5irQ|1Ac zEs8O>#f<1S<5H%Zge1~npp0v>iS`}&L(r#zASa%0 z4yxrIjY%J@8bAI}w#wsMqVUN<8%-Un6T+~Mh|H>kFUOZ>Hvl=Pc1zXNsM7=8fH>+U z-4=&;rh5WZHitm-U|6<10q@7t*0jq&gJ#}|$^a&r?5b)=Y_UFKt%ldFFhWHMpA|)s zw)BIOsk;Q*mTzojyrWWZgE~LY=H`YP4;0M{6G~2ChbvMxQ(u{oL%yS;TQMiQGm6O4 z()C^6j@%v%d$@txy#q%EKUT>8(PLIM_*4zeii=Dx>FLTcEw>#cN&FDkO`EJ?A2C`s zRJ(IiJ!FuM#i#gQ^!$g~6_daTcYJxuTEvGr0DOyjk5;drRZAV>&J1@!mnN07@I?0}(kU zU187H?h1mzkwl{8O8eQmjv9$`_=AN{3pSbkW12l1lx~?9qBA3B(z>2^!N$_=ttaDT zN>bY=F7!=h)t+ss=cdpd!ict4a7lr_Ax93v0^PyG5YflB4=mL!=;s@;_cMz38#B=p zb>1`fo1I^s2d<}G>@CM&%qRK{`889_0eu<59$;HLdt}0@6~Yc$?1ooo2;y?Rr~l%+ zkl`D>)^$@7p$jwkswTSrtxy~C!N$modk4pqd=)u~{z7MXF+5`*m46?*A!$XJm2tm< z@rics%_LjuHc`l)5%a8JW%3t#S}ws5rpoxy1j%?_rZ_?xqs3_n%iYv%ai5_mmrf|w zn7mZ)?@jup{@IDKQiI$-qhWKo<3`e2ux|vuVk7XinIq%<>Y9*ZTYV{&;3^iReO5ICXR2<$tq ziAP4(xT9RCpHwdHW{QdeR~6n}862{;WAO>Oxb?(*5c7DKi|o%apVzHTh{HL?7}>e` z{fs-Xll04ox`m;{Rta%)P~1jwZ7pp|3D9Ew%Dt5nv*F`Z!HpUk+sx1L(IOn`q`;;m z`|1T!_5B~)W>98rKeC&8SGR{Wyc*bK9ya^o_(^O0ub|)=`V=4nFsLUpyua)D5(z`spX2C< z84$-5Ef#My2a5!KZ&@4E4wIpi*bn{wQOymQQ+KGCi!! z_i5f-Qpf)uod7i*t(w@-9WhBf+a9Q`cNig8^PphHYh#H!lctKB(xu-S^nkVz&N54% zI~Q`_%d50|T^^txRqYAkVJZ;yeG;uFWG^~2?oeRMMNX%|SPn6TsuhIo>RlR+!t(*5GOG+Z@6Ku*NyXFQS zFxscYtH|(j7Pwbf95D8?RZJv%CA0v}&J>qAwY}uXv&a7Zr}n^)V}>pm`p1v9|I(fD z->N-e{2v8al`>H7KXe(z=*hG&G?4z`&y-te?I`k<_`~v1u?`aS#CNQX87`wPC2KZV z2Xr?>5RYTJyD)U5{=*Oh4SeHnCS@2yQt1!+|AC{Y-D#Wj`h0qY@x%T*l1o%2E-Hpc z>il3JDWocfl1#XO>A$E!N8VTqzpH)!0^V<(Y469j3Wemt##%bG!M3HhMuQ za+89wthD9WVQ9l7oP3r}phKMTXkxwclzpQeLM$XA@wBmte7=b$s_X)*N3W{2@|29T zZMI5G;R2`X5PY{ZDw5@i68Dd7PliIvH-k&YGXcgnPsrIZh=AA;Ry8De+$vZ+!b(Gc z!6{uF_1P@~2=7X@Jp4CX`wm@JN_lcMxwLiDwj4X>YpV1NW<(QSvd{aB#s$(ojQ<>1 zf0lG9CfH%m~GR2mL~5_^%3 zq3sZFGLngdg9Y{J2n7U*Ema(9ln%2Bc`8*a$fNz-f-rfUyv#4N68QOlXvHj{1noRR zTDW=qNOGp|z4HeUkVSliAKAhLu*g>gBD*A_p_o7MMl>=5JYE;;nlsQt`3rb5ID`)& z=Y$?AWwUEv&E9?q+Ulno&dJSg6R@JOgst&~G5+>*6Uo&zM6vZZb9`8cA8}zGiaIdx z!;g>}3=)6mq*bcduLlgN?B|C;1fFYREpcy=_k5mBB6^US;}ACgi&=cz=p#H-Hz%z4N7-$xby`}u$4CjL(+v67R% zgVTS0x#&BX>pL0$Z&S$sx_a?c!csx`w?$lQwARclDH35@=`PMjW1;XHGq8`XlOZd0MQ zICt^~c-1L;af_AX4x4vyVF#8v+=bYJp*l^Qj`m5%<|>2pfHkw$$O;zsYT8^;^552I zYYx(9r=49^Yga+8T3pAO{XZJKpy`Gf$#0qZl@FnO#~v8!%{uiTenw;EDz0w7JxGP} zWVm-|{KG9d1fsqnetXGmE%;tjz-Uxz`j13h`H!J#c3juytzaKD8h{k;!yt& zZSNRedB0_iR>ih$+fK!{ZQHh!9Xl1fDkmKTc#p&b#-s=d%0dg}Xz>5WS zNVSl}n&G62o6WkMT!@D@ZdwUXu=aw@)kC>7!nyd+9Zzbs^_Rfn%rmYWd!F^>;-A}P z;xE+NRy*k~IJmtRcHsWK%$slK+9}8EgH?>2xt0>aOAs-1b0?+M&NZSer@mZ;{T}A7 znDla0867-TB#RZW9~c_dI&nSh;0B#Nk`uX0BJ2TcXCPRx>a8N6G62?Xly*tU18v%~xEU&WyzVTQ_P1F;H<@h8m1f~&s`*q`t=KZmumth@okS9~_MbrH2 zY!V)uG&x6xCQQ`l@FHw^fEi}Md*j{2+JhsKFFC0K*h>NYuv!yEBpLhzuvZgTI||Z>GTBG#?~!b%Pqv+1u8|mMcXbFbt*q zOi%QUcifEP70BqfLL(Nu$T0B}(uynwKd@KVO{Fv;9_bBgcgicyRuZb=JzA=t-(PVD zOrR#?&lf=T>r3P6f5uA%zar4Ts);WBrI4=lrIBuA{-0t*%ImVo3Me`yS+4px<{}k= z;Vncqbug$PdBNyVkj2_WYv|dsVUWBWSr$i%A!hH0MtcQ}b(Vk|;5W!m;Y~A&!9fh9 z^MQ-?i>{fBu9ZwXem*}?dBHY(pR_n4auMCgz))XlONnsELHQ(MY{dH8?UWD~32AI*4>}wik1UeJ4pwR1v1sExnm34OasGqPC44bA4F5U%W zLBoLEW}rD1oRzu|BZrx58QaA2gchOhRSKmX(%o?V^t^=gqPZ7ala_=UMhfc7?4h`X zE4BgC&0D;?cA5CRaw!$oOUP5VpvX5UFou)!7$XmAwnv{Rq6uFAv6S&II=~@hn`HLz z2uMilrloy-(Pt*%Bw3W;+^4i!AY20fz(h^nN1y`Tl3p;gzflVa`xe*vs zmqG{K5zZ4XFosfM(jkP)^R$7^NN_H+TJiJKLvDN5QRb`wFpD<4h?!xR#a%S=yBi?_qX{DPQJOA8V$q+C~@37e7A_7p7 zLa09Ea`)qC@DE`7OHYmD@^~!Jv2JFktBrJKCsQ}SkMnhzZx)%b1+ZZm*9353H!Mt0 zcxc0jbui&3@_lm*f*4Rn80ic#gbM&f;{lGX*=&p91`O1-v_J*jCfT~HTC?5K%1N`2tqSt-BQ7|c zQ*WuVoocciWV?+KavW5Ko^Flh&{BZb0x3bOgz_}BShEaMhW1cpeLfYFg`*O?otMa< z(ah{=I(q1s1VnTSG|+sEaj8txL$_hN{0>M}Ynr5+(;>OJ1G5(0MKEWBt3jjgkK;H4 zEP4k;0#QksikE9yv8JZWBFkBZi4|G}=C%W3G}9#R$SNE(QGvFa6l=5aB_R+J_34{j zyonUW#&wlEWNFHhjKVw&RL-_XpII_)J8}h=g$4? ztaJXF zKk*_!$T8QS4~a(ilM+u^vX$(~0&ORS8KN-fpL!;Pf>jmN$_ufE7Ehn=3dIFYy*g#x zV{3Xw^2+3yU>_Xh`iV&(J{H3~JRpDy5 zDaXz)x8GdKJakB!Evj-?V$lHs-5z8Du3MNmC(N#QfPH5VIm0}CTi~TN%6Um7!zF%8 zShyec!gY@8$Pal2Vol02ciXoMM72`_$sfH-y+MR~> zGwXD3QlzKx;W4M9*aF;+@N{NWL4(7Ew7}7m0R#PY(XcP|nOa&e>Gb0j3$3+gLr^sQ zK&J7W{U3^2?{VtZ3B;oNGQ|~c@W5Cp(g=L?Y z?a(KsCz6DZAgIE6C+zLTFId7G!2AR-9!5y-yWcE{>F$oeMuOx^8} z;Tw^Jvx9=O^Y-M?fXW-*khhQtUPpfC8ooH#*4 zdYyj!n0(x_`y5XZySIK)k~3KDyT<_$8S5mTZHOY^uvYf5!~eIT)u$^|nAaDD0r#I$ z7%cvcnD<}1kALvKWDM->Eo{vMj1BC+0w9U>mkhn5pq-1Y@!$UVM?~yO{A-#T`Z+dK zJUq)5>=-5}mE{@`q8>;!ry3uJ6qj2y=(q>SEW5y*z)QVVhJX|v3IyMw^#{ey{_Zd= z(M}Qh>l^e;+m!bw=fl(8Ol;1#jgfY6aJA#vL00$`hXFcv9h#2T-+ORE%yTuu)4i@3 znPQ3(4P&z>7nN6utII-t4BLs4JhTe|qi)XxdD0an#Mu{j+H39!)@kuH7-*hotwmC- z7k4xb)}IlIMBB3N3J`0Ao?Nj)**E4S{o*BMsv>EQ%$^8mlcOxknxrISceMnVOz%vL zx3lAzbF?bPg{o+DDsS$i%*3}#3+3=-6N<3bf-r7>mVaT!iWbzbDD#(H%CIZ$hWB~p zP4FP;Sd2h@(D+{Y<2&NxsrqF0Wkz-IEzdq6=KjtfKzI)eIGtK&>kqEr@Mhych&OP5 zh7T@roL($*yD-uCNvVRB9;~CA#uw74gJaT2#%1dM@%TExwCMs4L&r<|%6r0Jy0E`X zW8!_=j-r+x4X=;g=e4+{s64=_Iir?LZ@xpF^(M+#E6n<(uk2pRBURK92yHHx_S4yL z(mPDk9^iR@6l~G)y?aJqC$l!i*9;U54Zpx4%23(+r*;=f#o${AXke6b8&P5$xf{-fnBO3;!55Gj>BcQ$j@%fcNp|Q+9UMA&P^z_yUC{ zKHrWe8Sr!LuD-$5r3(Qa((I|r6eJ95Vx7aJchuDb79)3CtGf8mi49<_Z7o)o#*eER zf{5vo>@R&z?^kHSG`e^S{e;VU>-^qfMDb|DtYpMd zwtVE5zR`r|m9m-8H<*n1(kCx1jE8A`5HFaq`?j5GKmjIy39%Gg4)X?YOd2SfxD+L52p;@H=<3)n;mU%Q`N?|ddL)5GK14?zBLGkq<(U1_3 zAR-7YLroOH);CQ%YzEnpKZ0wzuXmzIBIm&KYd%2y0G`F{@rC*o^iI?1yiVO$+NKZd zu`?szL=o-=;0xefFyP`i%O@F|HkKJL!{Cv9U)YL`6i0AF*IEZ!ifXk(e#QFn@UyN3RA?Zfaj-zzQHtZ-n_7TdMyh!X85=6? zqQCg)a+GCY+(SRbhLnQ94Zs3QSSLUFY|KVIuF_3H1k;{=JjkFbLIgwWSHCHRifN~Y zXZzAgT+!UP0h>JF=^{_OEe$qv1hd(BPI)|+r zgEL}D)@WLF2m3-iwRV!!GWCkuy<(1Kedil+1@Qvz4kzDIQx}x84KIb#p1bgpR{ju7 zb)7_zvy0ZuApHO$9HR-yT`N_5Z6u_K&mvNm)NjleG8`6+ zM2Ud^p%Y2Gm`x|*23PYd%Ns}3J85N>{%=k^y!)G1_zNybhxlhs{Nvwn;{O*e_&bEJ zs-^aYNPfuL0uOxqPKng0nc5gCk6D}IRTlCMbU*~CF230vY1sJ07>q1Y+@}_v?lYvq zPe4a%RMT`7f2ZJz@0EVghwOX46m~*J<*HZCM0a-ABWKUY^BwfJ0uIX|R+Q(@-As8HdeEM)$I8qy?ss*bUV?3tI$DT8!x)OuRHiE;CHkfzQNA za~7^N{p%?$FJligfci32Tau~WO_BifCS%kuu4MwZoqA&p26u-6&F;cM={Rb*RuUX%gAwkjjtD-u2NvfZ7_V z1wuvXxgnd75daZ_L5{AqDppboj!HF)K5qjS>fjJ%S2=3HN;iV$X96-t4Q4FeA*)s* zW${A+E)dM1Gtlcp#(*M=Hd; zb^eA7Vuc#0Jv}lbYp(QE`#Ba<5%?_KpAxM$BFqi-vxRW3oIc;YO+HKrSpwsR%nmuR$$LyPs=(l+U} zsSo8CgdCCuSFAOV@Td3*J7bDedajg4?oTXtT1iH>~m^Bih>`EoP}S2 zMo!-5mY%=&`G$`i2|Y2y$nprn<0Yn`*b+x;HQo}w2}19#UnV*OJ_d|~a)-zGVx?pd z4xK0socx!`8C9C@-6*PK2J+AwOh6LjD}>mkPBLyqe1W(H9+Pq){6^7l-4NzH0#_hh z#CvkdPiglh>pNP4SN0|JFnz`lIFTaB-wFMAFewW7Db?k!MM1kX1k|M5seJ=m{5ag| zS6ueu1kD#3o~?qf0fO(*=R4Lztxn+ZjM11YeL@?A<3ieGzuToaAYx+eW3^#-zkg}H z`_+Of&?xJuKtjvzB6i5*+mmm*EKw%Isyi=v)E@M|HbRXyqE&Xjeg0L{=*fpw=YLhK z^f3P{9%}v@@$mnmUHXT{dyIf2hyaX;->JD3w?2Mf2tx-Ym>j{Lf0U>^J%W{>8|+e9 zez_;yaX+v-1!EAny^-MU^X|aJ%Hs&RKWqwY23VEAE7tLa`#CUnU+zWOtt*L8-GWK!Y!olxia<{8i$h3 zj`m}bYz3y1^XAZB6yD_=ldQ=vi|Kq7i~n<>`0udj|96}IV;ZKVgd>9TVQL3F0MY8; z&?hJZsHYJk`yq@XDE%w9q9b=>PjC@tpcig>x{{lDP~F4>@~~k}QbSdvNFo_^yHlAc zg2JP5TrI~ZvPXz_)2l4lAKe+h`1StOsoUu%-zNX($2*!oU!}PDNO*7o2C9R!Ac9;J z2i-2nFiCK{r7#Y;2%zB^bJ$l^SThiCEX+fnhlz=(0a<089fvSvjEr>ygsqz-ZdMM7 zn})_nY^XYz8Lk9G@I!XJSplnoWrbDydmX@OnPLhpO7t{%e_cu=Ivz;VP2XXTTYU-{ zPOn2nv`{iU3SdVAi80PmgsMVq>A5BEQX+3}tww9E>-%HLdW!2fqdMac?Tq$0t*d%%2OeS6snE3aQ;0|bO98FsV1y}-qjgN#Tzfx?^vitV z;h_waQ!$)^qPszqitG=4LJ{a5?YvSuHA@yHIwERS5&;GKvV5a8JVtj&b8=1O>?W%w z*cyuzIfLMIEDMQ+7`^#uhs2@fKabtGnoG+pm^$tf!m`6WXdpP7tf0f#?Fz;Omg6)S z%@aG)sSo#WV`pf<+_d@!`2I;1iLPciX6?Bes<1+X6HK~&6)@)jfSA4fk80bV9DvwO z8Vqa{P$QRm+g*5ln)7#0To{`xjLAhsAL-4_h}%E)^-9X2fbU;rMIbCN2ayqk98}uN zr%!J6L`=A)#X}@lTdU=XGa2~fa(-#oBB6v2P$1;;Q@bnZBkzJ@gYYzxfQ~E~;(HV1 z$j@uqsOnr{Q!l^(3`3@P$*Q*&m}1P#dhzJ%^Z}EStczJQwETqB2An3}>42Nl5oWh> zyMyBlKh0R_5YVTKxGpSR`<9olp@B)5#$}`TF9ws8Ef( z>SoCfGHV08ifah84q2SAvCRpO0H<=`P4|y|DYoC2TJk!sz z9AH7sZp9z8wr^}m7=Q~=%6jL`@?p2vLr^*wfVxe&b)g++)74Pjg+|#7Grj@3p?9QD z45r>SxYUZ%D19!LzxOfj2{-_6vjb`>_WP}1?H0>Nej#-*XHst;@uYXrM{F678aphW zaaa=qU?=hF7Fvhh!0%OKEkMjZsn`(L(r5(RR1ARIp`_yn$Y#7s9DnB$G`Gn$LLLdy zr$69$$GZr@Atzs*;FKMa2J(`}4;T0QEAfCr63FFzC7y_XI=9pN|0nVMS9Go_Mn-nv z2TVwglsExOFb6PFtwAuycX<^<1;U#K{Zm=dQ)Og1mh{tIb^C8{A!+{ODX_XvUd=hy ze%{?(z^(lXA@5L1Unky+28_dV%ZQwrd#RUg$fH+!`B?*Jx^9xbIVEYVk=EM|120Kz0KN68`aN>b6BgBlHkJmMx8MLu+A>n;~Mk5hOGYl6JT;zUZauYl9 zea@oBFEf5rSLsxKtRuzG06U@x%mEf zbGg`B{GG5uFX;FM@%%U1N|maYeWnWP=Vr%GACm@&4C^~usYJFETi1o(iday38GHm1 zQY11!kVDFhw#|C%>lehEV)OYaCGy`vX$4<)2#Mz61gz`62Zwi?z-BYmvVXUi>-;449%* zM`$q`1jR-=n?VB=)d7(JRg^7^SNN3%q=h<46{kdCC)O9jiP2K^fjc=90%_e)MM;-y zY@-HHqrM(;^oG=PH2|+xn6O%!K1XrwvWYHe?Q1T6XwAe%X`PFy`Q?!4Z>D4CCT2Dx z?`QVhs(0K=v{<^kv@slfhg0M zOrc1aQ@SysAJNouia7ag1qhw>*N*hG@qYY?It!bjuwl9~RpPXW;@sP4y|^h&j=0Dg z^Qi+dHv2qdfzM!gG}bC=A1u)F!z7tdZasHAnS8M|-;WD^}? z)pNYCY_3c50MzMV>smTH5xQBlbGMoTvf7>WcjzkOLSCQ;bp_M_laf6Cn(F~cTl}A@ z&adR?D-V!>c0;h=6D0G`uye+JCsAbe)T#=UW`0E3F-OoEXLb9HJWip?3LmruK$fmH zy$`Zh|}(wV&sF^(`!00-;CTyhbCAGTx&l&B2p2lIQ*cqQ6=1sv@2cM%(&qVyWZ zOau1fq!_b~Bz-;W9K)Ps9O5XU2`w@K4xr+$0F&q&;o@G1j6bgY*@O@3gcU%^TyWT& zvh*xjkbP!?!^6x66`EW=QqDYB5~2$?;#b#b#3|&fb7)d2^WjBffTRy;LTu(`vPJIl z=j%J2e2~^U5cZBaK-`aYN)_hjAsE|?uYq*aAg;W;dMd4~99okF5^$mks;A?A_7e8&7bd z8}9Oybx;+XPt|L;aq|cL3o=ze)N&)?$Pe^6tVePR!sRg|Dq_X@WcshI?WtQ+KwHHz z$iOwDy}eeJTmhPZcvNyFHmc{XSbdfI+tzr!)Ce+_Ju{l=?4|j1mY~gWQ)13#SlNXR zwMpNbl8p)WLCLMAZY!hX5sK(fDNyX+2C6K2MA*Slbgy@F){MiFJq44&xRPuZ$%TR7mdlS*@kA8b;u_?CW4@LC+aiD-*Oe(Z$D@M5E{}0ziMK z2bM#?X|nndwpD2;(u5pfpw&KG8Mc@WeLXT{ZmC1zX(wekrsG=9bpmC&z`-_cTtQ6A z-txGb3kcyIf`bFTNgtq;zFr0OHj+j>fmJ1enFHQZZ=mKr0tqpFKPnV=lo)aeq9f2t}eM~S1LN-IvhFOmT2nD5VNzbU&qU!$VLP%sS*-1k~ zbbC2W=e^7M9_U%gai~2cn_^OG$Yj!-qjZx@+`J$1I05JWV-1TJ{-g#_u53GJ7th7c zBa^E!=?%C=4OLX|Xoo3XQ}0QJW$?J7&jPLZfty^Q6-CkKk#s<@wxpGdHo+=YF=SK2 z*p=qpZ~bZf*ev3S=f02 zR3~^6(pJ7Isdq&!}DT2R1C4+gx*Iha5RExWAo^ z7;&seZq`0yJy;=D#emTjJ)i9$2C5^)Kcn1^y#a-+JX z<)P2LC4OyzS)$V1xh^!Gz8hS|o_tV(j2;jxWvN;){U-D(QnjhSn;yfP^J)C(f&C>n zbY8M0C1duj4p?Z=sZ7P3ZAVvF~^;2clZ>M}CcW z27_Nyb)>JX_ID1!9oa}j23$pGdh4<5fEyy>p-Ei})xm%df^tx(?!<}jm5%N*I#-reM8_L2@_-PBIzM*R}xp?^(tqaPwl#+Q0-9N!aQx1c#d zBVSIG>$j_$ZJ|1*kGslCO@saZ9Fx9{Yo2JA!lFaFO<}P{r)Pu;nFn-!Fad}_pmHeV z87@Z>Wc56Vs-z`c++li#hC#S9l;<1JL>9zlYcRDTI2u6nfKWraBPNC4VFpxqv?^R0 z;9?!X{!VhM!-CB>DDFpbu`H5RbeSj`cO?I#x>R2DTtcDM>BngBwY3RtcW1ytb0nYM zl%DQ#^I-wSEE>V26moV7AI?yDA0v|qovIGiVlI%(fgcSR-dCwJDQ0TA)&-jyU+nk7 zWI0!l`dY;(hg&YKki-(@psr@(8-5;%ZA>3DRdTNLPe~T$zV_f-*fZU<{^su?-QT1x zA0>x7#CbD^-#2oh>wyv#E~z3j1i8c_NKZq22z_KQ_a8SD#D9^-%zTj#Fp>Wm`tz@q zj{iYJl(7Bc7`Pf({|CmCrEDX&AdljE*<4*2Gd3~%{2{wijv^f2vI8C&Z!AyT3WCh9 zZD}x6rPFSU^a(*m@&Rf@lpZhK{Yw2tI_%UD&^ak?J?}Kb`nOX(+$|lb8vQLEPjs3z>l-@y)Y| z%DW8hmcUqCwj&#RIxdl2Mv0n<#PppVZeTU=oHOdrcsVl7-4c_?3sm>iga}@%;T9ZO ze}a}#8qHH*dtb!{9cSooHL7kkW-1<s!xU0n$bXIQPgc3|$ zyn=bi$6_!68??e9D`rKDV4sU+E{s$1IrL zHA_8)N!kasgxP{?c*zxJ746JQice2(kc*kEpUCh43!Z_rKCdYTH)x6qd{qakKJO3t#-g3Yu~F&(euwhKM8v9aZ08#0+=>Ve3o)d5ohxK2 zQ6oPV$wpbr1YWTQvV=H`#(T1~avK}sj;LReFQ^XDTkgmaU73Zxzd{od8>?bRe+z1k zNi;U+2qAd2w*zaexXuv+cCUP*G$@!5)N@o?{q)VA*^YNsQ4|zGlCiU4O3^SUS4_1cU|}e9{fh` zn>3Oc-I)`w;5g3x*w?S|l|j3p60Kce$xvp#=f{Whw+uiaG@^cc@+_FKGh9|=M+|z; zg}Qfxk;9q$&3VjFOMc~g&-cIep3V|IkHud@bKL(A4RPbYtp>>bOU=|@Na$Zn0V@C5 zVf|-s^^ZohN<~WUi?91(d&D0fW5iT!6?z2jE6pq4O4gCm(hS1KWp2=}2>$$@Dtn-hRF`+Vb{!hWdfE0t7)o zCruPikRUKB4r&hxEKrJ(6c0DQ5%-sS&@nqNwjt7LZ0KXmXt_!ps_4>KSqfyb9Xtp*$aGEHWN~L`+QW+J zIkx`ZScRnvCwcESg`SnzT+Ffv1+PoV!|NP-f(r5*)?C2o_mE6?qpry4npA_0bUvc} z(mq%^>B78+R>0`ZJ&;yvFoV&pus~_sEO*VfNRS{4rfMnM8StAs<=)6I`Z*27u5A;4 z{wj6Pj&Xw%G$YAutQA038#=lO8D|nAWcOb8##Q6Av|}ovqpq_OIXzf|C_qwMm@0kQ zDoAuEhu;=sTgsfBuu*q0rh1)CcGO2Y(G;~NqjM47&8z1010ipd)d~%^qWEV~;89W) zE2bI>z)-r+AQ+Vbf-;<-KpzL0i40Ymki_V#JkmC4z4`0}otNMmr(G|EiO*3nJ9){v zfN`QNmz>aTuok-)BDb~NPON+Evx|aUSD1HIz6EMT9D#$9R1ewku8!;AehuQ#nD|o- zN0~A;>~vCe&L#dhLij|4Sa)kUh{S75GX5NecZGyUk~#lMp6D6NF*2LhndRYxYmw$iEGN|k zPr8v~9u|I5M|Ak*Vfx_zEawRQOCI)r@T-3ewzt0q+Xx@F z^0NnFTsni2F?eA0Y;4RtY*#unEl}Q(%}M`h+U!k=G|=~IlWK>NgX*;VcSRV2tws7JM4pr~G{32q zRlfxE1cDK!0S}UFxl{aX^y)+)A)8E@SyUV8F3oijjYdYXO<)~Gi_lfKf&;T@z^-SL z@emW@D@Pl#9}~WkA=nayfj&m*cMhRDzd1xHzW(UMFzjjzcBf{GwkRGg6sHYmMPd*t zCc9$VOEld68y#41N68-tb<3-Kt1#yguSFzx|qC_#TcRv*Ocl zeGXgIAN22+dQ2NV<(<{qTRG+a{8a5=)i)JZN^_W|ih@x-%wZRbhc!C+(Y-_h#*JiLs^&WCmc%nxuYbEKcV| z8{`+~b$b2k(4&FHk;2MwXy#fZew7LeFhM0zW1zCQFl~L1+=dCgOiY3v7>%D8x>TM+ zxAqFv!bTRhoumFG=&^?r_9*X9$(1YgVOClLS0|N;$KD*%Bhi?avKyXRyTLnX>~GAm z`UmF%(?Y;`mibJ>i_#W#`x5$bA(XvgAekC#E4NQYRXo<#io-jVbssFHwxf|XxN z*c7r;_*%_QA?%nei~Nx^A}LY$3;RED%W@7erhk9T%gJUcl~sHRP3RHe#IPTRRu@FO z1?G$I(sndGHqW72T_(+!Uy*){ir>jaQd{#AZRf7OhY!&d@+0bu5VkrY?HAfLwsHqQ zV>{y^t&c7(S+o;c7mU^3sEsHt)ZVNOT4_dH@7J)f-4LE+X15hu6}*nIRvqS! z6!qjINdn7SXIcfhX(gf`#}EWFVu;8VOA|?{Zs+9jm!ZC`y@q|qd_t>kSy^w)0m-^R zg+T(ZY7K+8PtGrId=ScK{9%?+5Kg(~0j$a>ok4_2vCwt7Fm>Qfm54);So!Yge=ve7 zZtA$BVqeXD^5!FQjE$OA0G^ejYOiXaI7-90oi76>F`O`S!vz|y^MWfQa1lbe^cZ_^ zztBA&mE0DNcx9s>&3<@1ShKg)rMudP4NiU8&nMpDlker}&qIEqaR!h8B0v1?_g4{e zb$|<8|21zwg#BkB^8aEN;=dre|0P8JpDCJE|Db3VoZI}3qsimq^~KSI$fxiuyAZj} zyY<-+#dUBS)CqY}1{IkV!q0_A&C)?f%m+F(n4bL9_C21w^#0qF;nzSpB=9pzzPfa7 zT(2U~1kBh`Zyiq&ZfH>XWlQS`WCd+ok&PBNT}#Ny)^R`Lrk7gV+p>btoLYZka_war zp>ICUVHOh(YKc(N8O(5ccOp!Bx#Pi7ukGkZw7K(GVuhuY^SLkN>8ypj%^{Qa$A;V^ zkI7wM>#Fd!W&v^8jr}cLCK|p7<`e!&hTT%o_4ng`WSBX_vKSXnPB09^M#qo1`*I>@*{_O~ zM1>GHZKg z)ct+IrAXb%9(e`z<5Kf>e1a&Laayx(iWr21Q}__^N80smQ25h##sEPGXWE*>q50}~ zRo_NPN(tooLJuS)h**&MK_BB#vZ1sjvZPaP8}i==VqyGQ)7N46?{m}lVr%K9p3{H+tPYz$8efEgkbl0QyD!$)GV(d4XKKs*`Ec+f58o`=C1VyHKD4JhTohM4Q_~}fV z6I9{-Upj~u{7%3o7=s8}zFp3nJ=JiTT&MiSJJ{}pjUR^<$0(mS5A!d~pr$^2Fu$G@ z$iUNhh7W#9!!dbecJcKcXh~-$-6R2oppNz}K;3ffu)3qojCrW{xq%!PQewKQZrHxh zQ80A%HP^@3a<2bTo<_K~wzMO3&|orxZ%ngTKuj~eU&y#jE2P}_KpLzP9u~(=F){;L zY&F454^7IR!qNzMLE}yYocVa>kA#z5IA>JmTWp?cpiOa_Qem~=5L*~?0p2+WBr%}L zp32eV6xrhOlyXUIToHfU)}?QWA<4N>M@g=vrJPohT2ORm6~elr?`F>#YKm&nZCV&N zpJq`eB(?m4qNoocXZ(a-e*y0cGPHIla0 z(9(U3&!XXYNl8rB9h{wERlHN>))3f9*pv*m#6|J+ltTXIz0on~ zmlV+BTX4T~v6RK~q!QX)fFr08z^mCfr8RTJ{=CUEa{brncTn8cCiWI~Fl14DD>2F} zFm5wW84|{JKy`5)DpmAJ@wUMCqJe1>B+-V`?BCdMhnuhWzB(c>=joMb>W`#`&8xCu ziHyjymgZ4ethf!^81U5lps4hFq^^(kfB_y4ks(82Wt_eWD%}AER5zotNFxraeHYY` zIuQ{d9VXdQjtC{Hl)48fvPTAuA!E+OWa+J5I#fF*&Z+Q~4awxvalL-;pEfOL%d^42 zOqV}~Fgr>2JE*pXDFc#~tl@yZZ$+3(wj|6wO#6uT$KSxY{G@an#O7gJ<7^2V%M6&4 zJvMYLW!zxW$jd%NE_^OlpP4c^a%W|%9#s%l{fYgyCAcbHc zOdv1D4B24ryAtg2?a=#NC%d|Xn~r)i6@AzXYCp2SwVt8cQ7qY8L5@gMt^tE*@cRN0 zDgyHmznH>pc17nfC^4c9l+?kn(Ej)+1y9tQn4ICTh`SqI zyZ^kxXsRXDT?X{^4Ntu}h)F!Oyydjf8pPr`;qic&GdibNc>kp+>4QAzgCQYT84%=n z*+d8vIw?-|w~)3W+vK!$|L8`lS^r@ko*4ptm@&|OLm zLb0>{f;7ZCkuw&0=5gz1jJFIqrI_sAKm%!`hbE;`s1fC<4ha&8VX7*e)a64q8a1J_%h>7jO6Oo~W0b5C-f@G$wi!|o&_Atw4;a!F{6n|M+;U5059cywT-QeP|5zIcs z5Ik8EK|t=)2%{AAR&Dk~O@-0ZTI8NpPfX2R6}wnBVc}89IC2VPbrAdaA;_c0@pH{+ zlbh#kad!|E#3}Ybec`*9ormyZKrUB)8F6WZ`3K^nqD{p~OK998BR=%CK)J(jph_3G zzRt?!KZ5mZH_WtDbHbfME97Ek9{$r$1X+iKTsg7%nBWK_M&?5T)u@m>#dU@xrur)i(IEX+skyJRyOYS<8Lk@M{$b})uMR0k4 z!gA2E?E+fy?IPGZX=O5u6=G;d>65RGvauzx5cS%>K6UCB^=&#*CP4FxvwMc89pd5pAr|NA<}_)DJwq1&rHi8dC9O?b9j?-v!vVV@j6pjH z3i)Z{K_6_|jZNG8u3zbguoB63i9gt+)RCxdOMRN$x&b`sftZB%1H4&a*xQ2nw@UDf zWLD$%^$4X|+GIoU2ZXxGLju+=zJlyY&8J*|NlUA5k1=MVRd4g1kscD9r{Od0RbL}K|> zl{)+;F?yjitwd+-_NlL{DRnSY*gqQ^4j>vv^4p=qz%NYPFLKcJZ8?H1@NPOLy8NYa z$QcV-(0Zq+a{^35)2Fc#0`qb8gYO3^_Iz^65DrCtD4i&6`H81fF9dHiRq;SBS|9yo z=MA|%o(|q41oDcICz8)kx>6tYz3!txCQmp$fz|&gTw{l@)2+VP>gnE%|d3ObwUDh!CXPIK?`zeW2CikN&3W} zVq`NqS0mNWVjvJ4`U$;%aosGe7|ec>Q8@ zI#LqV-N_5ini2kEz{_hayzn;wA;etPEwowWu*`gpN$kF}j9av^hDT=lOT$lo|5r@* zZ=AUXkxj-3ogagsK%inX+?BLOagLjH5?T{`Yq#yJ`p5a;hqJ5`g15l)a5}kn*R-o^ zMn6-W!Yi3QofAP*HeyfV#x~k3rB_r=vF_r&(U!#4_c&PfVxX#PG2DB5QrL2e`r5M2 z+G-Xzi1k8lnuhPQ<2GIse%A}*)rY8*NK0|ZP2;va@cL7rp;;#N%YxS{ylJ+j z()k0debmHt!LS@zStY$(5ph$lZ<@O@_WnW_tv$uY1XACVPm@4?Zr0>{b*s*xAh-`O z)xKt{6WPlJwUrq=Rxko+Y=|=Qq;Bc-CuqXS4h&31eTz#`bY;w8d-$1&`A8FS2dtuZSg7T(5VC9|#+LO2Y zou^cRndnrjPDUunOmEmV-~oGfL1z2LdU^Cj<94u2`L;N;d|x=1cP1sgPW{cQi%fvR(^4^K-}+-6q8gHy>y#t%|>+K(BKJ22G z7?X)rAZzUr%j4NTgsECYs19oqa8NA4oAL3zYyzJ@d69>T@F{y}Gf{1=D7ehn$yph6 zM*2NjCBVw@EBNAg5)b#o9k1=N&LkaPFP_{+VlUiYsWkNy;-pge8bnOcPInCkE4$C2 z$?tb14b3K_p)-92TFz2}&y)x|tgHTlyJ@duS>~uRil|egVtJ&9b3eVmDL}RW6v$1{ z5BJFsB8LoVN-_p#n$f5-CkD*RhMiwbw_K$7Q*3J{Qm9%wGrOKU`9yF2I3T09@;COv zk{-pl{c1Dtc^C_ay{{n@{B$puAK45w#j|C0w000X<8>^YCKfw`a@;t*Y#FbM{BUYC zK%aAc@x<1BGT%U3C8SS1A)Z*BY*v*XI{wI5Po_8yfxL*5yHp#nvm&I;UZ5dK7s2?^83g1FI+;ii*T{& zU#Rp|iY{)j(etAvZ}Hm&F9r2y{@QQFC{@XDt@)r_2u|rrg-MTW2o0{VF3jpnpIVg< zy8Rgzi`u(Ol#3sbE;&h{HDvF-5GXtnpBKYaDAx9z1%e%*@Qp z%*@PKVrFJ$W@ctqNh&cjGcz+wrK9eiIkVlnJ3aSayJne|X8A9_jCeibarf63m8SSK zEnJxfO)L#=85hPw<@Xot4VG`^B?XR6*nsDc^3w5jZQ{wm?i}Egg{2!@R?~;t8?v$LU;iXyBp0H+x>qfh8d^(S2>z#@FKiBo7#wv`w)7uROJ-z#~A3kD?l zB~P(}QSD?BvJ}}2TH!l$OBR&Q%QUnqU0-}#`1-uZnq^2u=?r@RKJGyRH2cI~#_a;F z6gdLC5M(O#4s-!;au>`nI9pjZx}DA^;N3F4St7lAff%ekQn7PRRv{skQzX?PAeG=W z6zv5+@wKRC+m`-ZF-DUe4ln#7b)dszr0pL4ExkISC|mZ+GWd#Y7Hpvq38rBD zr>1r1xZ`gI>#lwtel@4tDzV|ytmm{>W^A$yOG}fq?=wOcKWwn%KZ4NT@&QX54GR|J z@p-`I5C{smnQ7>XZ8kBFBtp^BvQwDc$*f@K?Xeh|R? zBx3s+`C9l{6JMD6^m`Y(TR$(O+b7J&f&Z^T|F16KlK+o_{vRgG|6*3kdKQj`0w#u^ zeB+HYH0`%QFY>5aFEc1cxZ_=rS7X*&&0ma>n8*ykfdtXlJKP&Ts}G$oH*~ySe~ElK zlw+X_*!co_9p-yWtlbZSAl7cQ^G%z@7H(EtlfG3~IFto)tjuDd}!fw+=P67 zQ@cZcyDF7Vhg@l8(!uHcr?qjBUd@?1m#MqmxK%LzGY1aTAp3)|R9IJ1)n(%QR6P2O zebu2jV3A#-xR;c__5({mP`=|Lf`p#27BG~1ht%lxkISWVCJvi=A9u%NYp>0NO z-Di5bd)4u2ucVLY^y|ELT0909)_wUntV(Y(B!L2JbA1~8Gww&L3@2IL@4tF^juuX7#4v4Tjqi$;%`5ctt zfJUj>D6LDqX(44QT&uGB!a>OBsrDw4$ir$x9hDJ~Q9s)$fmRW$HdjA$sVM2*Ps;$Q zP__rg^<*^53itEQ_W*7*)r6!4I?LADAW_aff8bOG&ZbP&*s!XI_l|jUb8P&0pDA&b zXG|PFqIlYug351I|LLU*GHFKmnBv+TK33+QW*WB6%0y`IT68*w&>A>niGp&L<&msF zeRyw-bVzQd61T{8p_-A2do}%OsAA{5-XU``fw6Phno+_I8;3=w4$pX6UV=5z1dAYX zBy(A(*IbLcwdRG93}c9u6?G|n)q?e`%;1~&v7gD-@8ZwsWbfU3%rgux33102SyC*{ zx?=`)?7|Ry-vl$Jfvj%@sS;K8PqioJ$*X8 z#q<`Z3>eD+Qw)(}yTdVFc{qrQy93a`i<#2MN!Yz(PSBEPlA_oqsi&#Nze&RzrokPS zruGsEtA`MD^v#ot2n5y+XWJTtZ8BGQMja2SQ19pqy~vIc`6d&vg_fFdK7RcTiaKJi zK~H@)ypH|b)ZlL>eShPR^*?fNS!+`(hu?)nR?qaGd{k~-9OKiwk~p0SojGzKTU~?6 zEg$RzSNkrnP*e+?Di=x>#f@zldRWwn#KOpa8{&x-pOl}*!-qQ}8kdU!qn-4jjKz53 z`M`r`?9J=V5oQZ^Rq4rvE0}&`sZP6F7$hBu5$#}*UO^vq*rLM0?SaieR|nOMgdGbb zHcb@L{&*3a`qAF|Ii?%OG!b1rPsm%J2F+-rTrm{}_$)||LZ3AIC_7-0gFI2^wt%Gm zGLMC@V0xM^6|Ann6+CI2HxjKUYT`vRLXb0tb3u$B%msgJE95j*4s23^saBHUd0An# z(N=S)N_LqeX!$4OI(~lhDmVl#xu3F(V^;r7d|lJ&2Rs`q3IbeCROJ@{GXU+Jfvf9} z*=chPQ*K1lZ12;|(G-4aHc?Zr6K;Mj#AyCy0*h(m=bW!W!Ay#@67QJrCSXd87R)CY z%-EUO>+^Inj=n`WjIRz0tIoRTnHmWzl^QOKQEN60^z&S0uY|6=_?Y1VjG>~8lzM13 znT>i?^}-8AAT-6y8FOcun?L!EPsBV1e62HeWho^=(3G=@+`Z$Yvxz$GG|as}N%_}r zu-epR)t}^i`Tr|9|0BjIf7(@8+x_?WlBuL6gCT;*_1(Rrw!?!kvXo3p^o7p?MIRnL z1c-=(dnKdh_G$7iJfc2fPr=0RB5K9-gVuUICdXxig$ypI;c^lSRSqFU;9M9l>19PKAQ#an^P$GQ(yZ2kig`l@ zIa`pn#_*X{*gB5tlb~el!<4g?!1R;P<29M!sPrh)7@NdKHp8G+L^ynV&}@jg3seW-Vsxaj z6`GNN5i7%`i{WG=Wc7p1w5j@y{P+b;*^oJ@uJTL9>=m3<38~o=Dht!62~;m9G9#rv zpKb+^8T!O_dzWCaXBYBG3!+70uQ-b3WQAz@53+Td3Wz(R@Y0!BtO`NS=Q!8uMG`~% ze)5BjwpxQ57t++YMT;X<530#B!-Kmb=WqpI+*jo+@&Xs~A#Te~s*KE{-NO8JY{?6n zgI}9BtdkYWVfgeswG zLd`#!^OhP#@d37c*!!Fid_lXX74&IU%>5`(43<>|{n=|AfNc?+w1R6&-f-i0?hA|N zcDlVH{K5hZ$dhNzOU}awW(jkN>p{hcUkHy0GuZo{d&rZ&gcBA_V>s_61RWcY7NY2s zYxEr~Q2?L6HXLEON|16oaf5HK`;jMy1TG)Fun4#rC%B)6CM&23#w493)a--h~q}ooX zsDp!x_66N< zgDk_}N2>oRC?zWV!#|~&YSeE?2!KXbaJi`q+(iJko0?FU018*w1%2d;#LB0AO8*wm zHOf^PjV>eIlfh0jeb%xToJQof-lL|`!Rv&_;n*Wi_RlY?YFeo{2eh>}(u86AH<_&Vj3>G@ zl9xeRDs8K`H&CyY?Jv=wNP#x>O~u)tl?_^2XC|BBON01I33k#G7E!I<7!6IcNHKIw zz>c!5`fbZ^)b)p}yGpc}dz1^NKC~+k8c07O1`nq+8^cw`Iv{YHuZR^utyUK?)eei$~xLA(1C~2qD+uQJ9jmC-$-}?guy2b;qnB zY2&dX&CcFnmeVqRj8uhS#qCC#yXp%minojUWV*3;PQtXv?L1V$nF#Mml`m9{cce*Z zfPYYT9H9jh1hGm0KEB=)NHov7=OZ zN^o{D+{q#4yx=P=AIi>NJo4RT?ihSOUEQ#xa&)GT=auvQj1CcmL9Q<9;?Svx;zh6H zT8wpQd-@Rp;_*Gg_r5`_Z?>ZWn zorTJzTti4?!WB(?Q^3o;v(k%spj#WrjQPQLnX1n(465zJWKTjWL}K1BT&ZTTiNiP0FI?HN9$5M@rtE=k z5eEn+_deAV01p8^awp+yOc8LKQ9E_sSZNR^9vE}kzilXEX%YIX&xr2-r@G7Kztml_ z{QZXd!{O1`(CYi2?~5Gw){ESrpr8Vv*iN9-PM}u8pc8v99@aB?m|z(I^U25FFc0+exa$Q;SQ-MxeyQ#>2wG zQ?1IwQcKvY%F~%c$e@CwKrm%_v`|Y&PfJfr=ktXCf&hpC2qI<@e2Md|zrQLE)89X+e^j9U-V`aQ=b-loO8?hma&iJyb^>J<2Cdq9 zo5|Z#Y#z(_d;)SGesN=KV`Y7DV{e?veQ|;vzdbc!(D%1Ihxb0ezP$*=_r15ZwYPTt z_qDz_$nWnSF`%9fmJyJExREbxp{~a-zr@r^hlzO0QPEORaeZQa(M0L#YJNippN4oG znqNPsqJD|_eE;uN5p;k5xcop8oN}5@W|DdTCJyvMtujv>e$Ty}aF* z4n*Lt8LxL_1M>WK`W2K%kxem78DM@XfwOn}yF5h0Z#oF{g^LcQbGmN6-4H%Md3XZV zL?S^D6H`g*tpqTIa2ipLnb8^RZ}b8B#w|NZ~UuV?=+H+4cOJr}XhHUj}Y3k&_v(w9H}=)!op&v68>gCDcz zZ8pkeq)=g`JJBY#dSfUu+*OQbW{0q08#)xe(TTV{d!E@UAh1b z_Wa|Rv`3O*>co}Dto(_$NuX(rDUzmF0PU+X4%)3Ljp&lQ4m5gc*eN~a>WsG(DN}7fXU%0`_>dlxfy5L5Zq~hp>Uo*M(GgPw_tSP2L8~Fi6 zIaGQv!Z3g@I-nBZH;wt>s-?B2gf(6N8ah+LZcn|J+UhJ2HN%O_YMfyNwH`*zp50nq zrYj^7)N?G#m*!U~G7&U&UbobyDLHg%@s>53x52zK%T` zswO;8{MEVdszTz$!~_dcI>pRF^KzLCcRf$}_rqlpDO?iuxeAGnS{Xw%)#}yXkS@G$ zVPGzXJ?>F%Z5-;ctEKFCavvu5yXd{CyX#r{y~p_`9x@ssDqJaDDdkkTgf6hG?MScH z$0BrWV;5(p0Fr4TIJ)dxIKjQ*x|endGLpkDV|j$OZ(Tv<21+2`g(2J8{9I+xGDdnr z9zqPQ62RZN67hSL zAU>C!&F5+Df0q=>zh8R)SZseRvPk*W&!K~`To@#_mXM|b8YaD!$Kww`5Ic0=uv7#7CA2KI@E_HnkX968?wXk4IW(>@f^zUM zE`$yr05VaHVNVl`hW_0-XOK=ZCz%XrL8q~>=BUBs^6J?1PgTyg!tOL^MZO+Y^n4Rz z-jAXY0sf;)1}<+h*9? z_;}OJ9j7bU8|Tc<8uITd+O59<9nOu`<^>#6St>DI=^KRw>Bz`D>mQG_U4 zw^Vmpws!E#s4+EnT6${7Y$J19;L4^f=vfVHsA(1~jz`oKi!+8m2wI)Fe zHc-S(t$a7$xa&!nTGd}-q&E#Ay%D-f%bimUI}ZP{^8>cOeDxk=9Td<~@1ZwQrg@um=oCxB)jM&I9uLfUT19qa z?gu)&ReEJVPUUmOcSlRJi%rt7_AH!Z9Q`Pxoy;5&m7!zYMS?NK8;}_eB{B*c83DHt zjr4-`p^FE*Vd&}kJpyj^ueol%l6r9WY#U=H!dZ>!$r#hZD1(Zrq1LY#alyTVVU z)x*5(RG+?VQS-v5@hWTV5uq+p9yM|2?_oC=>-XK*F3nM{(4l;?WYi4plgcS(9w304^o53AW-Pf9Ff`;Z(pBhkxJ!yY2Er{kbW zvZ3phbuUlgO0V|&w%5gS*vnVg&P_YIe%kSp@pQ{!1DXwLjix?+mQCiiGQ{We7SJtP z+oOTSD6Ves^-W3Q<4YryAt)ryWO!vQX-lw}S`^v@d`<2Tja%M-PmR0QI*sD5HY-OP zpSJiB#xur(uzM%-z}<^4OhPOb?kzd_?XHhCvl1eF^=I6JPQ`wr7lk!R<9BwL=>?)- z0~U8kJ&LBlsQ@iJH>5{!M(SNg>C5;k^ub$oY7~C>TG%Xs^&6)`A_%>R^AkA~zkxO6 z1L$3*)MLYfkP%2X6EWFyb@@>{tb8puVFvp?$5XZ$qFE7RC6DF?UJDT14GFYKC{<-| zVWtTDAV{tNik1=8fwEe7@(xfTN?)LTZWBPMa#PR~!IQBW`RP-J)i&(YCMwV5xKG2` zbPI5rmv-QuYgU%4A8cC5iOxF4u9{3Y>XU|UUwgC)2Q~ocp@Ss~w3Szo#e?wuXPjQ@ z7G|86VQ`!gY`HI>ldWt^C2@>T6jyj;+VJwY^SXluOha_EM$a3_s~E$+JZypNn6)do zz;S#@b_b&o&^_eTYAFeisp`I83Blk*1n~})_x`C9_RG%!o3$>WdL1$JkYX<@{eItd z$zOxhwg3-?pEy+V2JT_Y`phcL^zkyetdQ!_wysotWfi>y>J97|o0)MA6k8yTe+$45 zVQEMA*)C+Gj|Rq?u=6F z5i^h}00_0nwA}~c&i;UrTHj{^a=JpNpmo1ID@PV4ADzl2kXk96`HZ0b%ZF@Fxq~SV zQeLtwbX+yLLw+J_D2+S(& z%3c9y_oSqezK1`_ksiImBhUg*-^=ZW5jqC;GtB(rx(EYKr8W2P&C7wm@6bWl;%4p( z9&=XoTa;8fP=n}fiI>BuNaZce*K_XY>Hx)<$%lmPxZrwRbI-obaGzvzzTMlz!2v++DgHId%*<>M zaMcunP01MVAlAbHk8H@eT^I4Cigv#ZzG@`KHWg~)`^lr)Ex>9Sy=kbJDKVAAl!3#R z0P~QjYV0(WR!>=gIeguxi=G&IkP%UxS#AyzaKl9DVmve1oQ0E^l#V^4g1K2!!E*j| zP07j+)2XPV3R6RUGi|AAliG&V(OBjrh4aK%)#-)$+Je}oh76;nA|`6y1uzf$azTxm zMMjCPp$S~0jRpJK0MiOnWnqRH^`2!x-Eoxrh};z+2?Sbgo}Rw9XNF;jU0Z&$v?-|d zCgH}6*VDqBJ$~N^% zpLPyfg;M&-nB?&UXGlEH`muxyW<6x6bR7@@7aqG zD}3qShp3S?gTT3szAf737g0q7`K6;G(aJ_cD4LYfL}2^;fYu8cxsSqV7=H^NPd~^o zTO*~g)3%a7F2%}G1Q>mYK2uLGXH}3EeF~sYn20jQ1e#51+@JZ{FUhL*Dk8Wk&C2<# zo~d7TNP3fT2Ys_LF0?!YzLC>U@h!c+ki_2xe4bT5g@@AaxDl52`K+Q};I45&Alt{w zp{@_NG#-TI{+v?i7@;!S00;Uzjo?UjvKVyy0ePgy9E(WaFQ;t)k4^g+FEc}KI04u} zSiI6zwGdL!FVt*ZA`}Op9j(1t)2J-2V@%IXgy=xMv0tx5@*eSovGHqMw(!!BLw)bQ zbieimAG_i38~xzYEKX=~oGm7`iL)6PS^##l4g2Y}n_=9?_vixM#+k|}$b*wCd~`^& z%Y9~xQ?>OATx^g|oNCuA$t?&m;?3v4@vP&J&TQw!bb{A*p#?HZ+2qsmqWU6WNj}mg zSGW&h6`y?7rd^(3XE+nK*=B4mgf+;P1$3e%1b`p0v)peqxf`UZ3q+Ik(2e+tP0KUm zfniB$re+jUDDTw7QMzFqZyi}}@Mm116E3QCe%z`4;K#H{F7{Ip{fQFN;$)uaow+$A`F8hp&3c}*MX*|5#}eEZy$?4t`J)Kv-DYByhsv=PZXwG zeMM|PN|uNoyaM}plUX^DkHFsiqBxH9f8GOQ=YPk_JU#jmuFX7qK1OO$8NRXH4k&>-2Mc&j$_rT<36iF>A1Q3xsXnjF^yK6e9pWb2wsu zaP%JG#BCgW!LD~WA+in`O_aRG4(UGoxiifty(mrdR#j{LAcDLq?zd74fo*~ax%2xn@UK! zEO8l6WZY(2|72_H^zwcN)x|~w;Yv}d@lk|D0KdR1%s~mq_t5DEGJclrjuUku>=^|| ztN^Y>?^B13Mtfmy8F!|%nuB3Heg2iJ+nwA-LQ? z7>v1CX$a~q)rZFE-Z$q>=!D82H(G@|tHfwNXgazx=n$i|LT>6bL3S zj>%VP>25xKk%=PBk?|`IiRR%-C6`!u(7f6+Jf0o1Kn$XJxI`1j{rkA?^B^IzQxu#^ zy;CHm3N@{bxSZK$`E==)lAZxCv1SL;rimnwMcIi ze70qyB5Z=X?xx@(ZcD`-#Uwj>Th?VLel%vaRA?8If?C1sBo&~(c_IT*#+U;#4`+#N-w5d5w=2OygF`SEpMumlv)x9h;s6yC;Q;4D%0k@$(3 z-5zzW4{&rn>MQe15HM&MZa3N=QyWMa>jbefNcuKPKSnkl4isMLMZ%N3WWK(;;qOq z73!@fR2THG>s4XLV%2)P4)|=kx=_&30Fdb$1~L{FYT{Nk6E)nWB>wKY{~*m?ZPi$# z3crzNad%2pC=VfQ;c$WP4~1Tqx91Y&Vh>(xwu%y}{R9#kyDnoj?>vSEq^nDUq>d^L zD}y64pSY*(d+s~qHz9%7+OPy^DdCFrpVF2gW%=xfM}gNWjl(0OwC>nO0>$L!9L@J~ zmC2Au=spKH$a4vHZm(>|)8H@C~z?c{Of9 zYZ~l(vU!auWSv{|m4&$gRl3Mdeup-WdvA>XvHf3JX^=PZyn}j*AtI{L^648e=+2JO z54uNkWRZm%NE!}>b89+->H849^ub%AFj80bjl2;A2_prxo#_PBlublj!{|GsgZqy! zf5S1LuM2TdpE$<$PdMhUWw8GlX#Q=v{S!1xS$~3N&p$x(ER0F7%IwSvcMWb7pN$W` zkT^y`o@mD(pcyBzJ`^0q3+%%ONHhnRygL&|2$h3Okv~LzW!aOV%{t5YU~sZ}^UG(B zrk8)b&k=*gW>y%WnKHq4weQEZ6MgCu@Ch-qqy>FSEbB5_=qHgw8-Y=(xFZP4TfJj% z;1Yu-5-2RxZ)J)2LGOw81JAXrk`Pu;q=3Aa!C3Bb-lyA=$TT|qJKP-+OdP5B4nTCk z1<%%StuowZW|0LgYC>lBg;<9>ajy**ygt;ftdRJq0O;mD^@PbKNiSo}q$2T9>hmRb zXsnG5nlmc)N4$6zaNJT{$|aGTPBHn^_UYj;uPIX;hcO?526WT5kwcchgbivFH8G95 zU7#MfLazYaqf47RA<%f&hrrZCg&P4qfJ`8=YibD(gm+0=Z4y_iya?H>>?hZ&kVVk& zUeCd&YCBw;{mI-8y#er*t|ZNv38iL#o-`$Pyv=BCf8&8~@?t)URE@d3xm z2+nHj23+Y}>qKEd#08PBLs8 zw+-GN{-EFym?ppH&;6lY?uqN!TRU-Oq95i9#$R3arYbCthNUr(hE4h%WHjmwQ-Mb6 z=StcE0qQ}t&|+e&>8*_h$Ff_$Y#y`On_teQM#bA6_PD?bCd@A_D1rNGi9q^sn&P0W zTwAA@+H<}IvO3O{(#2Q}4*mlyEPB$ZG?`4PjG{(bz%9rFy<&X;<4^Ri@H=|9d*-SW z8S>=rzQ*4tjkNg=?am%7RD&-%GLv%7eV$s2_~1@PkhTVshB>jzkKUBAL*s`!yem7W zG&W5k(U8w7K+_qO{=97c+nSt%9E$x7z0dwzt^W_IRsN_!{r!ahr|yQ&lf8n*=Rh9j z)(m1yD{&K8iiU-_f+EF)YvP zKonz2Lx-Y=WgNqICwMC(w|GeN%8mzabI(%^^UKbU=UqAqiVIDE9dR0{b5#Dc;sW!n6$GG5hDDH>w?mAAFbxyIwqI^BjODeYm& zVvqphsiZmyBo&%g3AbD`x2zkPobnQD)2id6D#K)Xr^Y?-Cz8szeQB^K{9^|Pv99zw z6)E4S2qpT%vVNr5;bRIAH|^1-AZ^tdEQu-%>FPEsC17EOrugVn!*x}b-5@PWdiVB{ zw$psuwlnp9mj&`9hyy>%#I?B}rfUqDz}KuszN*Y)Yd^j#FP!&~ch~z+dlu@WlwHVq zPhOv`?t21pDqYKWSJhm!GM)tgBrRWi1~eM5CJ?RB^zt~bJ8sqamXqB>-Q zg`O0&25U&50{6#nF{`XhjZ&j03`IKSPR!xaJ%1G05?rQZp==ZPn*1pVima!IHDI72 zlp30}Pm4-fr%jV@TF&%0*gGy2-;({-)GO zHL*6}!k*oWhkZn8-(2`hl4fa3lvPWqFo&p;{fD1g+X?DH1d+(Lfqgm6&=@)Yk=%47 zweRTUnAvBMsv12`cKv$AscMkMl6DP6QpVKryA;TxqDc$&_ldHhtsp-(q+3 zovKbKFjwa{*V#;_W{@8Q(+A2B8SdP03~v1$-Gx5EDA|j6aZz@5T?gpX$?7;V*GGS8}!jTG@<4^$afzBm`rA5Fy!%Y>Y`3D_oOi!|``M|Fw@C-f#pIKHlb;T38~$@u@=gs(GGd>04j|l2eE z>u)P{-d^rlrrZ(4I2CFq2oX3 zyZFDE#NXWx|4mM@QsvxUQwi-O^K9MSnT174BWye}H67@(kf=CrcS02#^VA|?zO{=+YEcJ$ya-)&DY7*!!H*7rKrr?aAMezJH)7Qm@_fadVofd zdYDNWVq!&vwS;W=!*Z^rIk_d>3tN3P=!K}ygM?%f^09r11?auxlIE<~y`Y#@1CY{v zQ(=R98^(;B)VWzP;ge=A^1X+^dD6p;VGG}l)NnH$N8-uy4fcx16gS9_vD)Iu(J$s6 z5}e5!S4&d-=l#s3Fbqd+#toh#8z#}4Ha}B!+hOD9xg{PkB$kp%oc4Udp1n- zWtlX?zX9SCGFsMKv_La;?w$aS261g8Dtv9%n;W}*`?=DemG=G~Wd6+p zLr40OS4IZMHTa9$bV{ta(HWS%ux_NGMwKDrgVMM-(N<|k+%k!*RK;3vDpJ}K9eK`~ zEir1+LWN0V?{NkYG4m*N^(_^2?iQs$x$B+%$}y;c7`ws zH&ys><;z8UefvJLqp>8m%{kAEUEGLbnCA5nCTz4?9YcwPz`{4>()3!Y)F_A9k>1h< zUe!Pi>-ir?D>QbDN>qs~+}tXy?J&z1QP@s+cdBCiBOXq+?dmwiiXLB{~~U<%4|`WCY)W%#ym>9-6hQSQS*a zFFfkq4X93(Cfy$R5J8aHLIu_do#gJ`x`>N_>r71tYB*YSR{}cgDB;u}9L>e-9<0?R zIzx~=a3C?a982g;)0Xd=auWDGKuDs>QABv_*k@#$TJe2&Y{N{7lnyhVF5>`+@bLLG8dl zo#jz7^*KMT(;rJ0ZH}Uv&bckwa!x`so~ZF4u9LpWTw0un@z~t{iFPwpu&9;*gv9Mv zvD5qFWN^L~-;a5BCkR)y!xpuTbH#Ho?!dFLckWl+QbprY$Ew^x(gdkKEDAR+)$t~_ z-51TK*ghBU!IHXAo*CxrWAwc#{}YLdlzsQAfd(Wq1IMSI^BWa2*h2xvcZRhFt!P5C8~^5mFBB z49AM|B)^*Hi;_<@I{wDB-0G9Gc*3v0u|VmYbq)ON#{ zfUTn#0s{w!7ZvQrGK2cQhPFmF7`f^dsI)0u&VtgqCyZ9%v+2gBlZv!+_S#8IGIvLx zhEnTh0bo91U&&Y{#Eh1fFLtXsdikSGbO9>1p%7{2{@A8O!&1SO!VT0r@e1Asu6$sn zFrEb2##6eWk@;SzZ)dx~33-rzJ+{ROPFcf%8K3X~rp5^lV_w%+!rqYY+ZDo{@o|Ete$e#(8bnQ`-^s8723gN!2R}6q4vOV7Yy$K znk(mafA5_PlU|yB&~^gmZ5DkF>M-{!4LYAqxnAe~cNZDR?Z+Lxc5>pYueQM6h(vE< z3D+nzNHRAvx(M|x+51FSFiE4@6L|@ah(H-aCEXHB!S1Hs)7a~dTJEm{r zZRH~Yknrp@3wkkafP(>Hc-1z=fnBt6{0&!|OOvVm93Mj7YvHtwX59eHpz{>I=_$KE zE8s>RZPg&VOa0fbNA(ru_D)r+hv=%F>D}$KZ^=AXFmQhTUJ)zIFrW1Pi77SzlpXkM zy*tgnyXVUr>RAYz8d?|#ea^G_9M|#(FzQHDQ~0#n9+WYesSA-W%)_tpDTS!rQb$Gs z1P7cD-8}JcK5p!gjKhdW+#ZM7Exzi8*$TGf6l0p3btsy(%`m+jzx0-#NVoD0FIdKF5|Dm?VrW-s~le$W~u>jqIL`^|kM}tlc zp~0Vgs5w(H9O6vu)kGrHRY|8sHS1tBNh4ZgeE=NDqG(^& zM#61S&iDvUb*xGVXh}RWTZl_KhbfvX6i>v{3T!f2nUSCAX)jprCT(+qxR-0}V0g0S zh5&|1GZQ|J3PZFdNp@TnUSk9pkYXqRQYEoJZbVfmIG<#I3Qd6_Lylc-IZ-GmK`5$W^DkZ*U+#6FdKuam4^t zkdNQbcP4&rP)KsDUu6+$}PHc?a$-b!p(2m?+-5>P=Osbj$*IKvzBtCBY7j9TC*qa}ZZc)}pmp z)7rak1L9vLGE;QqpwfYzVN7Q*dR6cAXPT?oS?Q3f8NEPE4 zr8yEWjT;j-h(q{Eu|2@;+koP4IzHjH{mCKRk!XogoU;XaqqOl?NPFd66z#(JIwT(c zS5ok8mFXM3F{}mAZbu01yyRBsC^4-wJ!PMG{MoQ1YgwM{@!Nk(g!SuV(KfnJ+jm1Cn zZ79em_`tHU;XXM@c4`2z5@4|j@ZtOLWF^<#kgH;C1?xnsWbm7BJlrL6l7ufnZ&Cv; zMs0{Q3BaeLsSL)GkC~?v)jXTtfGIuvz>8PB0*roNgf(FKDnP!YF4E>w#*3qhbI#Eg z>Z$ia3b>24Ak&;iy}J6MoK5%ub? z*xG~g>=|jJ7Aa7|_mJA9X4Cc6l0g$)qZyhaMeHpz$#oB)r6p0W#*IRDA01%}kZv1* z2xzR-^&7Re(5yjj(!>-JoTnsU6=NP>UY(GeK-H$O`)$MpMq{p=xIbV!pJKuYe~;9V?PDf4cQBj%y9G~ zV}If4P|?K5Q`})YF+{P=99)g9GCUkAj`w)G6Kp!cT(%vlB3qzj3j8Ud&QW^g;IIwa z>yd9t{zia>bu{;RxS~5SQ8Itc`;Ohgexa{A_$|nk2t(&v&@cO!ADh{X>Z47km}+X< z^bR64ckJ=bnavw#^S?A(73NDT*r?g21{^9mWel^d2pLNI()UIM?Kt9BR^F07>XYQp zzfEREVhPB?K=@0`h`^}ZX5KNo*#epr15AgA!o)`sOWzQ$JHg>Yp@w(@g=gYlg(YmM z1nBF)zC_queNB_j@w^eWiao>q0!zRqT(H~X59SarR6VuD3g9F7Ybg&v?;{u@cz6WQFFJiXKmD%98vMv&d|nR6*o+T6He1KW znzOSz0bBf2VXJn7U|D*Px+`&a^a5hO#l|A)(4o6_g<7El4RUjUrd=Aw8MO4HxPs^7K?S z+NF8RA$?uf=hi`jT;6QP^d`;ndbT9g94Dr-XQehClIPO8K`IO7s>lr`od%EX7afB2 z@QjzCgw|ynnW{{b>%~AwrRKHL<(`@bSTxD2d*d9%lawsVf?}UL1dd;uEk-S9+e5N} zOZQKL@MouW!a1W#_ES#WGN7uCs~sZs9;#DNK{3{}PRyEEvS81PGTT$8Y&dP_B6@_% z4b45&P%_&bEI5jUOkii>NL#RSA%yh5lR<-tcv-o*I3etv<_P%vS_-=25 z_1qd5L;15P=11O%yuB+pB`hXWr9)3ap{tS|CezE574qk*kI@|1LBdFLWZkD74zK$N!2}Id`pcr?w9TubL8onfBfig4D|Z5D1`zaf3qwBH$u75-yK^ z2%?p=3!p^uy7@vdT+8z9+^0iG_iI+@a4nY$k9bHuVQ)j&q!DU8tB86XR={n`7f~u< zLP;~f2?8d*qeO>%tRI%Zp|BxDB*dONTkZ#$b)5G(P^{(KG^~soSjh$laPM}Nx1>Kg8keme!huVK!DEvp8`M*~M zDH|J8b3>cIBIA#EC{P)d|8=~9Vd~Q&3v?ZHn1FAmEwwEAism#nRiPGf&OCS|bK{mP zw+Z)@to=mOEwN6kL%C8O^90m6s3$g7zjG12WjbJYU^lGj=|3KdJTd{*yV99?3nOlm~3c=F; z#4E9C@Hw9P$}5dB-pDk zaxtpPgjm}&r0iY+yw_skLX^@;2J~A4x=zBBX1-e_%11XXc+R)NB9Hte9gX?r6A&y9 zhExT6Cu*^EW*xq1PxuLQzq1ASP=dH=jW1na;d>jtHs0=M4w^ur5a>57Gwf)Iqr{cn zpLC&GN2Pk~t{Y-vVAFSH1tCNjuXa)OyKE!S8B7SihXEYDeaDY^vwvv+@q~OzU{{1V zpMBwVC)nwxaq`r!0{9_I&9iRABtcm?^8YGywl|etnDYN152jI_Zo)-w#_`m51e-dy!|1Nj`YGD)&ot#bo0BJ`2it>~o z`oJ5U?K^f~B7YKf#jg#}D4;@GFapq zaa*4oRH=f(55;O)&Bq7M()n5ie0*L&4IoPm1DOfLDec^hz?2}WnKqN*w-5_^l7Xht zZWtp}O+^NY8@ZG^aoXBFH?jlXF&|A06mVK5qfQ={ZyTG`FuIYx2PJiOkS}5jOHFaS zm;ypAK1H87k8U>P9CTPOijzzcNoy}(p;pra1Q)4c0GVZ$;X3tgq|0(0#xePfN9fdS zlptDjL7+Z!*VvdfQPvi1J>jjwwA?!^7Z#?cXJb~I*;F+A6IMrcW6pDE);?k|fOWjN zYJ`IqctR10?-#Pgl9pyBRgD;73m$+p!*#az2Q#2gX$f%`rjuvWa=p9WGvo=MY3pOm zYIxu6Q4dE}ovNk zOf8~kVNIbsJH!+xG-=D7D~!4OzpL9?pBQ$a6;MXWz)sh^9H=rhRySuT@XgINs65`9 z5qI`iO|!_?%JdxYaSg!}aYHYoU3tVsXoR*U^%ipWM|36-TD0S)}HOt>Zk?R z#cr+eiq!v|552 zncxm!x2GgoVhA_|g2IEo~W%KfaOKI~Et2}fFO5B4&vZ70(x7a29FT`}GMb_^QhY(o193><=g zYDH{2FmE7uf@KLuN*d+9-Q+}=7h=HQN)W%MIHv&fdWN%^_v_;$eiu8s(T8X_ zM^Q)SFd3j}oKr*u?IzIwg(3_F5QBMVJ5}t|Y3gx$xl9Uq8^1AFw$}hQg-}vBwM*mC z$bR)Y9E~nAc!3?;4|o`w#-A!bf;%ybd~!P|G-MS$U8um9WnCV7#+!;Z&mGDh`C^@J zIA5i^>d2VF9t@{5PEtX^OwoFz>JL~kN@nBjtVl~MoLO(#VNaX(U1baCcg^UmzBdy* zIoSE6sHac%LGO8sbobDD&G`u4t}qMtr0bK5RG&93_VtYVnK+bI+H%dDZTQA+PIjnA z1{7qu2_5T%HTC8r%n7;P#bU>InTF)~&(X~2qE6^qU>~rm{b}xH*}W^-e1AM z8v@=ev6S-M_q^lWWf zncBUkD48@l|9m)8&!_Hu)<@b4s`lBwmfy#cIJg2cOc#ZBWP*>y5C)T~hMSBt!Y9LM z!6OfEAv@wyy#xtZq^z=G=nVKNk@7*@Je}+-<;O1O$vSzes4Z}!dPkZc`4ob}%4kf6 zFtLaJHYi*PCR)S0)ArDnfmaC_Uj@cR^-ouQ4Glau{_ndimp{u*8b ztmV+dS&Py6hur&-B!cP2jDs)}YZ_JiE?}Z=LC818oy4Bl)$*trwOy=zF2(wqydRYG zis%!3G18#!uLE*n#%*rCy4U7B=HmVQc!|)(hUv23RGEjDxANJS83C#F>nw9rgjR}T zZ$5w;;Ui#G5ggIYO$?d4qcP5BsEY%eq4GhGs+rQQc?mf*S|H=|ZTs_Bc3Lyml9{Fb z03B04?9(#>r_SkuxDsTPIU}n}#fMDNET+E6tycI8_D&M)3iS61HtbfWDDj^cFr<&Q zLDaU!ys#VTrB!Oq!4WQgmwYIg?*z65ygk3fvM653G#ZXc&I#iB;k#A1kQo zXL2K^OYn!{NXR{l2cHJyu0hjPpMJ|lcvcB5izSN@)<=aTuuPWUWH$S@LirJRzasv| z;RjPXlT8TIl1r*u;a!F=o+*tIRmAAbBr8I#)QF*G%-#&s2$M&QJabvP+HOnFuAPz- zwUdwf{&T}u7qNm5*=S|?1LHbd9C-zWS`3-B0=YG(P<4K(Q*moFJ0s;YJ$hqojdFm3 zD~?tKp6Hmk;OsBw(xxhb#El31ZTv3^=Wi99;`@#h2h|5%$PC0VUzl>g1#jx<*bcz- zS;)_Q?YF)*eV4)Z4w6;EAVtK*Q=IM<<07eAHTQGKm_kfRRzHC};xq zX=Pr?&M=R>(HTjod=|8UP>G+fs5ce^=*`38b$*4pVk))7%Veuiu9e!$yv>UIbt8S- zC@u0mnEM~XQI74Lwebo!FzqBhu`lP$Af`r(9(w$Bel3YKay<_`l%4K|%oB7ilk zUa16 z<^`lvb-Zyrw@|B&qFc7s;r7nG8x^K)`!+Bt97DDM(WxU?02=)g#(3~c)H$abmk0-V zBbOz)04#;cI3l)s^kg^pLnWZ1?#YNQ*u~-44WnK>u9@Q zWx~)KtJC*-27g~|GOx_0+wrBZ9Vc3C=wyxbU%*rmI6pdQYhBLvpGrFVD6EEVaE3JeEFb+{0hQKAvGpLlrhJ zT(#eAoRp{n-0mo(v?j0FsKukJe2stp$Sf$r=yjZw@A)CWPP)J~G!i#QE+FrbbBR!P z`L3GNq_2}i>A}BG*%j-@IPoib`NtB7k~#)74Fq@W4{|Y^A)w|}*{jSS-5)hAGQM*O zv!)LO?TZF{N{}f*LCeoAhC4!^&sQP(BK)n#I{4y_ za+5JgE$Oe5nU4K-9h^Xfg8mJmf6^@fsFnW@gu2?eSc(GiY3B?iALT5aZ4F(FE&k}+ z3siq6Yd#Te>7+|yOhrX>v6aLgSZESLF$>~~24oe{P^1<*Pzpv48`@Y=m=zs{lNnvy zBQU)eRh()2VeoQ9CO}_V3eW{<&HVj1K0pIezx`jw?Gy@HZ*|((FGVa5Vp@&H4kl!{bU)f}*=PmoDViOT}zb)1abQM=!Uw z9%hFX-ls=xb=n`&)9Biem|0hjDu*jKBYN>ou%S<=Rs&z8A(kDqE4$l)VDj zQPqz%S|SfdJruA?y0;$hdv>3T?(-DZ1`t#-QRF4}xS(h3=QQ)Ix70OAoo5P&8RLD2 zKNUw2X`OcoQF}JeOBP8rJiXRp9Z3fdye+Z3^fw#h4r1|Z4o2>OQ{wCBFyKKKY!^sV za=r?8ceP}Gqbu5Vt{pz`fJb}dMtTY%y9$_!wo`**E+Ag1qgUpj7>I`adHf!S4c8{` zR+9;QyD3cXi%aT3By2Vuy#<8nL(<78vmb2(>_8Um=%Qrm`I^qmqb^=R}5mU^nOmWcos3Xekao5(mfx zSM_v?nQ;nc!mVUI#hbuF5549Y)fuBEa|P>g)oHsNX0S+WV=@DTb!s8vjL?kXn{60Res}vM7lfT& z5QNjTdk6zaR_=bLiVZ*%!?LVMZ#kRY zR+Rj#F2Y9yF2HIbG?^PMiG}oH^9{?MPRYGVwS+IwQ(u|#m zj(BZtIgslZW#2}SHHhs;Z!R2ePi?O0kP?Rc!fcw2$A?>pklchN_6YQ5&`^<2(kEGS z(pB2B<1IIS@RCT-(xb8>G5Fb#N3XSDfIXB~vCtv`Gii8s$jQCjBtd3e9V@dkp?p%tBWCus%#;uni%A}-Iy}<~ibYZc zsuyAhXFnQJ=99k>o7&@TT%*)ISw_lp-?>}Wwt`EWe8g9^RS^<_ON1ZeG;gS0t<+d` zJW0%01{ru}%{#hUsUU zGF?Vokg4UdjIV(WluO4bWdh=mhZUAU|majczwFk0BNjJ z?BYtFa}XMUX22ZOnanX1?=1sx0gUKKezXHZjBp^+5(eOpVS4YSvHQZHO1j%c;ot6W zU$@3b6*{rSPlp9dg5jGdg#(B?QSIOWFxrs0srU3KGw#EAgZcQ}qQjx-&w5Oii!5eM zw!tyhmxykQJubp)MOua9YEMzrs~>XnzM(nGi00hP(X#T=<5SQoO|sTbUfOEaKKHC{ zR5l-6bg^5P<8OR(TD-GZMv3wy#|N}ZY?@M?56XF>P_;}2)Jucl!YdTsrw z3_Itr(1kHFg??*}hdluEPQ#I&F9F*Qkp`zXKqQ}+v~$zFXGhNscu@Baa$3x$5`Y3K z8NHcUuV<}peX~otRKeG{uSSnVb0xs7Jo!!aXg0NeRn}eVl)s+V549o$`ufs>F+aML zw!7ONvi91I?NJ4O3R}$YQ$`zc#6&JqfUyZBRZYbE3=m^SEV?@g5syKy!LMR9+$Y&N z(S`&ADymrFQnC}T4EP?=1LB#z21QuyCt?0*PDvW8CoCsXntVF<8lK@SEY8Xn@d zPD9o zd~x1QXLas41G-oqjVtJbEO(n=&pC>OrJ=ZNszZlD_ecVMNJ=r|_Gm(H!SlIpq%PCI zHrjE2B2F>{Dnl*1_^qdoOSDd<#9*ue2li(pgljmS>>Z=XQ=IoQ6(5%?tYjj!J~mCk zn-9zPR%{QMy?t03mFL_@Q`6~2 z_0pAiG_MBO3ymXU=bf5V<=&-D89=FjucB-2rGmW+H)W9gNJ{}&EjgdG9la%wty!t7 zrJ|h9k|bcy8w{IrK&Unt8q?)&z(-?Y3k;=VTaKCxBAEy#Zef5*ez*iM@g8*IiE)0( z-4}~6+|}>zIzI>B2shcIlTmG+5q%_meWm81p@EB%f!c?>p~JwOTG*Mi;@6+tOC&VK zAxQru_~bBs6!WP~nOk3TD85Ev_ePi^?E$C^rL6KN9hjhK?B@g@2%Hl~L67+oORGb* zAjbifAqsQx(yUwHR-%(HT@;ABuix~!b)Z|A)fw%2oZZnxPetyXZTN0 zb6LlHM@$^yLDVV#&5k)ypfa>Y0>E(7F`dX^O9@i2Y=;fa1QFNzXi+zG9M67_gy6gg)AB+TY{!dm+{vu_6V!&o?euSGM1Au?qa&&&9sWlO!%TVgg{>^*g|c zFsJ(xkl!^R_XQtBZ-s?B~3iS*`) z<&*Yu1Gs$GAc7N*@l6xHyS$Bb8*E`HUahvx5|TZofUJ&$#kJk#Y!>g~+Tb|!7OhRE5J>*%gYoLoW zeAcYDWa_1#GSKCRhu>hi+eVEmKK7$blKLVaSU^lt9XsV9$8R30cJnkQKsHp`gf^fn z`*Wh9_WMNm70u~)=FkX-!p#qnqVIKuUEn4Hz=hU9fd#316?FNpmTlJ^dt@&{Zt8jPd231uIO^vcRKpE7Oy zQaCFa`z4JkIn8RJfImWhT~#4uCrMTGI@HI?Xp;ywCSg~JPy}pJb)_@9G0;iWh_dfE zHq`*_HX6O~v{{oE`Hp@5B!UR!B`u~0oSaE5NjNF|S@dEIdXoA@EZP&&boo;uDeD}* zZlgJ&PiE^Yy97eIq8UnH&{VSjR zNl(`II@a+z)-8CNHsJ`qe*7Wui?fVj)9cv-hLr9Wk>pFFvYI?nm8DE z3r@6Kp!4^Iz4wEr@cf1c0S}s2j2>%5k7Z!r#584U5qx~g)>_+tj>-!bYM;$XM)n9o z)&Yn%!=J+#@bPLBCwD)WrvPN6$+HKft2g zQ#nkf&i$-Njb@R?)RfaZAM$fLC~NRFOFw<;vN8@scq0Ke!Ch`}baW2p0l|w1Mnnx` zNDGzCq>d7o-$T4)(YVau!xFyvYMrXAX2s#RgRq8kt;rh~WCsRLT3 z1J=U<^!U}jd!{p=_!DJ3$a}OZN1r4%5Ib5|pKnW7BDZ6VQVE^?2ssT=F~gn-4N8$X zeEK2@wr?Ok^vpOEb?za#Mb_qI+54ErA8DI6e42z{|}I+DrbJT`Ld`F68I>kHMy6GgWRJ7~Cy z&w1IDGC<#>T7pX7n<%YpyE#{n1rD@gu}S_=&(c7TbE|qf(74rfd9}cA=%PEY$WK0! zcr;MMC`Pr_U~!!*lAwCp2)%%CC67XJ#I63Wi5f{nyzq#^fcS@#rvPYeL!L@cT#MAA z@F&xsN+e85eTO8m4Ofca?)(n5D&*KAyiApCUG>%8d@+P8&ZJ$Q%@2uflE!qlfCQcPB!wZoy2>RxI`NB@J0l?t={JVu-*2vFA!CoS|s3 z)ywycyoLmMgSGfu+K^k%DA6^2d*GzwTnxPpRc)6r@h=f05`=C)3}44l_m+FfJT#zU zl6y?MJf@O??X25Q;2C*oR24l#Wf>y0#4EXuF)i;#579NFAxbTs@T&84#k4j5)8p@L zyW48K#33MPy8Z^5KMVH1eEtI`n&b@a+<*DT{kb)LlB) zY6{oO>kW99$h3`SlT}`XH5zb(9Mf*GDQF2Zk!~3!S&B-XWnVF!3cua90~whSf&!0Q zIwC?=0+KpG6V|BqSt+}%fW$NtmQHo$ojX~Epg5m7CqgUwoHf3mk;oGn(@9Cl*m}b; zWW-4G;+AOal%ppirkp-G*tib<-FtVcc7Co*M3J%6z{zV)eB9427V~LSvn}L#cXA@t zBfch2dqpjR#PI=i1NxcZ$6guz1Sj936fJ-$#0fpSmIq zvSO;!YKo|>|L}RhoX7QBiwywClg3R9QobRztdRC5u&^9dEJl-jN&5&38U`zb3kd7Dgp6A|MN4Z44v|{Ea z9b*4VM0gE~iuM9Z@rts*kmR+ zkn872SG-W;chr<)EH*&X>q26b1%-e@>5bk|%x7-Ehy#2NCrc6xK_Y!Is^h&o9*}sO zQvg)g5I$bQ1SB%DVY4KBBgZa$FMxidS46#uzY0GX=S-4h!4)&rayBy9kj2FNDR;j1 zb5g6VVY5<^NOKut(#cceyqlPYGC3wj6{V3vU`5p%w+wvcWq_~8BvM%&*ju}_?w6zE zOFlaY-s`gR-3kX&sf0?m=6DiB;1eS>k?dlgREo8T%z&vOPwzOaq_S^3t8hO`_@K#h z6Z5hTk5Wq3gt-(zjRt}4T9%?YK-b&L+VC}p7sM%Uww?%?0I7jI>8+O#VS#d@M4TBy zG0rKW{7bL*OHYNyvD-`$`#|AT1GCLmG>lpRAF)&c`crJ+4%|Cue7M6r84+ln&;pjv zrS;UYfgWJPF5mkPUYY3(z#tc#>u~*~2vzW;w%FV`vM1n~!n3;TDzUi&Z>b}B74n2I zHHnXDoM;ZIFj<=fZv(h7yfX1OCkD;Jg9p)(m|7aVeXD(B7p^OV;7^TW^&q}CxCHLk z7B7g66yVe}1wPbG2E}h&68>tDtZfKr(10zH{NG;Te^$PKIjI1wd_w>0AX76a)!(J;h-m}ruw!5d@OWZE7T@PmeiQ@x8GJQmQCNl%xV60@O^Vu#Qz-t3E z`JFY1jSR-IjXL(c2B3o-qmCWPCGsg|u+O0(Ifrlo14r^DD5prXggJk1I@4f~hXvVg zx+L5oZO*F%{rwIKJ*CsoS(xQYye+^~A_yUz(5aG|PN80lZP?0jMW?Q>ni7$HrOzpW z!3}%vZPo^`oERpoU^AF(cO9A;4fPy?m(0c-WciMj!t5e56DNrt7zL$T0?3&h7qHIo zGH-5ZfN@=rPNj~6r`+xriTfRf^O(ergkz=5kah$N<#*+bXNfDijV`r*!@^KABJwnE4*7c(tCgJyIFR?vFPce>q2}KdT{(>290+KPldO^fLKNiV zhVbnsI)J430t4kf$!6Y+7uAnqsU+Fw8}Dt9i{bJ;D!x7h9e;cmP*m& z6Y}TCZj&CxNiNUdv%5bbXK!kOsfpunsp(H}i2vLE*-p;h&fdk|&eB-L)Y0|VDTF_A zRDrs!3YrGGH^Z@+lqR@p{(Ry0#|H4j*~M8bJ#dkq-@g)p780K@rH$HZnlBWjA=G={ zV$CbOyxWlxP%Vte82h$%lXXv;p4l2ITs(i-qUe;S?v(MQn8sPKy+h&Zf<^J%!Ic@qIug5a@0ai^6cT-Ux zOD}MHcgprOT%CvOIGXI-)6%xp*VqCg;lA)y;d}Y@;jD4`lxBQcnff47hI!wBp(tz( zUvr{pWLj%Oyvk&> zVve^xOD_y{K4xm0QZ*(WLvgyu#TTo)pAXgb*T+O-E2gJoq_Q4Pi(5$R<}>34kU&J1 zq@jnGTjCcupj=6#x3$<`aB0`w4!hkRrTdm9_kImCw1BNBZ2}ef-bTa;@xy=f_9Xa6 zlD$elET-!ASF9>AjCVcVj-Dl(tYm7QQHna`zT+u)yF0j%?R<61c`G-=$7EFm$%*Y3i{|4liszc1+y}@6Jk7 zBo$iw6l8plc2U?OKz}7&=^$|DKr=-3C+)mGi(Ynkr?OY* zxab)!uon=~GVPEuyt8XXb>t$W$lbd0gZDopf8my56MCO4$VuTCmap22S>y-_T~NCn z7ZiKGiXu&-XO1mqE$$9r2zwW=EP@L0fF=R8Er7fxwucDmMtqXpS^U)vc}dKM?G{?P z+PO?IKK3oQR53nISqvHpg_6)iG9PlA&!s5VBmQxo;LB|sKLKFKI58|u0wr9t7gk!- z2R=O6Du0qDclxg%ov>tXhB8$sV910^IMM>W5DiO`>jnwcr%^d1Xvhg$-WHp!mpQ_S z4s7{l4)k1{?4C9~9HbPgTRX-8Uthx41F^6jAM`Z46I!UVn{q?zCw|T=qCCdRu zy%ysnG3lNGwS;pL++(&#$&|(+XyS%x#tzA*bkBbBV(EM8xwdnDp!oVu@-D@{fZ}=nGq(~k~=97j!>(*GGbctR_E z#!rxynYPBAv${pSCHqt0Rov)Q1)NiS&JGd&V3O*60TAp&<{%ceGytE z5E*B&l7xPVs+szC==|Hxl&ldn4w0V@lMC!j*+RKS-nlpWif#UAQTf1UriaV=)Mukq zk5_8ViKzITafjHfHSUg=*DRukXYRnUSMMAoylM(7COp2wJ1p?~0lrNKVXy_PG*ACn zY5pzw>1tym80+qVj^78;kDPc5gNy~b9TR7X_ikE|B?t;Aarl#}ac zVK6~SWUF+8)>2HZcnIDba5j;~ZyoA94cX`z5=Mz+xrpM42 z32cu7VN*S{vc)gqU)RDJ$P6b{a%{+iwEG8g%eh!j#Q2RNdbtS5t_n*Z18o_@c%t@U zI%)9*V8KpzzcrF7NJph!BxS_MHj+8Ja7KpE=x;;yaR5PJUi$BB_38z+1Q{1Rm z;UvPVw%C@ECOPf6J6F*92S1RtHDM$wq6ZK^7_o}9AWNU+lHKm)NYiU#f2l08Oo_C@ ziLM$F*r6zhU@?Q%ZoG-CVii6>8E`E(m4GLWn0)r}+5T>bUhC^s%qGu!);7V*zjo8M zd(izFVsAh-W*QCq90>XejpOuOZ<{I@)u&Hh?)*y<>r&M{csyr^e;MJRZues>HKn`U zj3C06rUbc~t~Ibv>@5n8S>Tuj(P>=e_Cy}B}7H|f5v#yWZNusW^GU<*Dc&=BVowRdVT#ZtLpOm2&B zjYI6&)hhVRadcZ<&!eNA)P<8^lm$HYlRT44KD-PsEmmVtT+9Ld3c-irgR*Un0MJH* zcK_=Fw;i9*V)n%#1)XfeltcHV8j_k0do1Ue%XoLL73J$c z$CQ!>PkmaL_?}9v{lU{ppMpFmY`E!rmBXqqxwn!S8`*==c4 zct{u(iHiUh4h&VvzYvm1TANb!mf;s+SkP`%_|dLbwLx{ z;2$*KO|5Hmv#L3SgA)=hhpch?*%xo*6>TixUMv*eCnvGr{`Oh19~AmA4}1e+{o~a@ z(SKLY|3hT`vMqD{zc5+D@=Jo~d?EypXqh_`lTg>7a)Lc2EybzO7{XsI@V|);7M6zc zNkc9Wm_#eBXSG;h5fRrDDi*JGXCi(3VrvnuTnu|?W_Eg!?i_vAeswbNpaH_D$YQu& z5z2dtV2F5!z{_-j91TB$r)hv4ElSlqhi*uwR@K@5qidBVLRAgfl3<_W&M2mI#Ln}L zijfif68Ii$?`P7jL%K(4wBPns8ds8uvvouFF18Sh2w5AV@tmNfU-E8o_ zEsgA97(Jl5X!9qEHp`EubEK4+K%FjVak$SBl#rR2=kVdG1p+0l88y__3Ao2)XE{bQCKcZRz zi&RGpZwernRb+Gi-b+R-si2Z9KVz=EdaUp(GiytMnXUsf^YlMvX6b*2s9%{`&Cc1? z!NK0i#neQ>;Xf4VAEmwgzqg=g)xL(4=qWK25Yf8Xgm$B+W(RTnG>Skno0nfC2ab+s zkX($uZ3W;4iRKD)t(ioa4=GCqfKDW_nwtTapwC9Qcm%w?UJwnyE;vM)a*0c}P{m!b zv8T=zC9t<_U5seXVp!0IWUZ1XnaT|TIe9d^X-OPG8uhxAjWvB;nan!!P4a3^5_Xr$ za)E2w&Wzp!eed8?ces_0r2(2lH?S0y4y9DG!}LiohKbE|@+n4hs2Eb7W^#+<&JPx8 zANu-nv@mT35*4uhV`Ah0ian!nfZO~2mvM&6)a@q zqy`DMTt!-?syYf`o-HK275r>$G0A%|&PmEi#+_>1o0ZB-p22D4r|2Wsvkg@yIy1Ry zP4PX>*k%l(GB=Kuf;X-ivA#l#&?z4dyM;}*^;@!=)WzzD;9N>q`driPMZPqsWG6F( zUF?Ks}FbA6-^MV#I^17o|q zdE#7_nZ~5G&($!8^CZ!=xO{{}!+x{<;Z}*b-rhsrgrGn>C*(ea5QtZk|EEiy{TSGF z8g4b`L8K|1o77|1#qY>uNKCm|UH)sx^AhLA_!BbfMHtxRv&_qiO2O5AUU9Q-Rt}z- zyuy9p*J5`lVFX0avFVA7KXbEkBBM@nZj$TcjQpr;rt<9o$>vALcZfKipLSOIGrsim zFBepTUOqXljay8XbOfmZkPt2t9}SNKm#Y*8r)3}4r3jZxx;!kb`x!I48ad7be0q*X z@3)KZbG}TU|CSA6_J(ltf!UV(A4SQ3-L-rcu?NnQ|B3}u6H}8vVxj;T6Vrm|uYh)R zE0`+(&+pD!v>7l!+5O2{;=xTf4E+Qnh(+9%=?@z6GuZLgo`oo^(EkVJJGEd+?hCU% ze4Wm^2i%8t?Ra|yu2W!B@HimMu`mCeh)Uz;cA!nPJ8BBBfs*1vCjo zNOvuP72a#1cdl6tV8TxY1E_$Q!$P=XS-Td6$NCWeu1HqW9yhLLQyiWZPDr!ip2Ll% z$I0I+0kyV7N4=k3$*r#;zpfmtaxWm2(Y7WemTJL+Gk$jX*b&)k@`f$}@IcmJ)H@$-4}ZfH`S#ZBSkoT=DmJ7 zyk~Pt@hwG!UPy5!X=i~!lWeHHtzH%fEMweL9PEKWKL!_8*|%}zC_Dz*t4zwFWm;*5 z?;YpCls2VQqY%VgiVCbjl-76;1qt7G5IpGZmufj|@AKluiXkLl>-4FA9NjNQi+5v6oLnzZ77|5aoI20SvYU!tw*Dfpc(4Gn=zzjK=G(2PMagm@ z{WYCP8_BY+DStt7lK!WqH#nZOr`Qq$Dxs<*V@6BM2uesOf9x20`oR(s6*Z*kXS_;7 zG#1fRK|dj9EGcKG;vDqu3Q9ou(T|u-#L3-ra|<6XmLU)SF{z%WXi#279kX`@-`PXp zRMAzGM-~h7Wtz&QafzC{?I$>IrBkx9+wFlDi!Q4DIdBo>EC94aM~A|*2oe-l@M3K<&EcP~z6ih`P+en;630hOu_IsjRrSWpp6 z8UxHqn2d&an}LFPQCFf>9{l;8!ZS!G2rtn^7u0ngvT;#%nD{p^f=~Sfh-n~tb1|I zYG?%%S64~s)Y2-qCBqc^`6h71d1#7tPf?xlc7sSp*j>x|H=>qdxN3f~fuczjZoTL+ znLlxpFI%SOQ*H}FdXa;niH$IjSUzzEe!>6dXKI^kYO_SaUA2)mKry2pt@^TO82Ocu zt2k=Um!Ze(h6!GzRAj^Suu)#$)+v1IKoH`w01=w=4K`8HCe0A_+tVUK&SlY91viXo zdhY{^w5DUBaMMfl6-gN(WcS^&Bu{@GDGuOiXgE^6=rz0J#5Anzywo~NaDj2q z^V(fPXCzB!J5?rmYv#g{V%HJbDd8238yt;O5rP+6lCc_I`NXK=XZS((4h^adK>qAlV(l9!L*& z$I^gS2@R`EN943 zjBda%tSN}JDl$~~j=umm&pH+6*)I*K<#WP37NiWEQAfWEdN1vh9Y`2NJcpW77XT&P zemV2giL!@Ps--s1t31M1l6KDfwHP&%jv(l(7Jf(@!V7n)zSrtv0%HMm{y}(AyY9}C z6-NM1{A|fQGQlfaqGGJ007A18f!!^V8uZR6RixL4bJ%)knW~VzLK><}LBs>}YDesRq>Be?W zGRA8epMP^q?35%=OF$?U{|!oisu}-y`NH(SjCUAaT`X-FW$ld(Z7jbS8rhis<-}tf zEr$pygdC*L9I=M%2x*u{ns}>@8qOtTosg24dGN!6B+6_91d%+In2wGnq3uzxy=3Xd z34%$4QP0n_=4E2B2|=5PHi&Ndj)kK_xPScI?RF=B6!}W8fjdw-IHMaNSW*P zI+RLk#@7~Y(|%<SOwEv2_?ISdSvJFo9u}C2yUm$Y9eTYe&%S!WO))Y`-)2jPpc&FEB5Y0Ke9M zOVWR?yZuWx?)R4xb+xs1|35xgMyxh)-whkEwqO!RK_MrLhcsiQUA+qurHov^DJRp7 zdMIXfN|{ESQWadoqg{7z49?i5rr4)<4Rw$AOuyL}XIqAwb8WVF?sZl>emr)UH9!eM zuqlu7kq+x?cR8=!UUlpMjR<>e4yv63AO`kXgRuc;o4Kv@hv7tM`q|$IK>;{-8m$_&dYx^GCxD z`q#PvaPKFP$wZD^SW6{nj6N^I^blh~_25XIf@ezDEu(#@>)x@JAh2NBt5#=Ni{d+r zBreVa7m`lMnbzInoiNa}VKZ-@`^FqO)NOh82vB=)Y0gEXDI z$tTrGoj2`!Z&ZeyhiER>8bv{R#{zd{M&ry(46PHz(cJ3!N7z{_AHSO)*BS?03T*2P@H>2@JtlUwxniDQa)80MDV@UYIX1%4| z%I1?RgDG##wNDwJD}KH+mJEs(rQzd6jn3uml~hRGZUyC9Ks{Lxl^P^M^E-phnv22# zw6u{8;}ZAb@=?1ty3+CZ(0qDbV=e6)=RLvHLcgbe%3AYPfDPJMFY;!L)A{eJD@_`F%sUQM6^D6fZenfCla& zf1g~);HQOY9PoK@1afS=d0NCA=evcSt#kxwfGlECE9{gsQW#tAdyAEyiBF_k+tFKn zn#4VGU6wCn?4e12FzF)3v2Fi#bt8({CrEUSaxftx=3s>8;G>#`t0@v7W@6?*y1~K( zDMo7Jhjzlr+iNpYxy7JFi0I(cCNVky$;F0SYDQX_>MK87E)p75cfLAZUIa!B_r06b^Y~&_7@P*0wz5c{vS$UF*Z&F#Kng`2Ump{@*tl za5%@s^z(lV5i>O0J%Lukd~OY#!*Eh@@&>|7;1)8eQj*ljLFk<(iHOojNEo2gJ=W4VWr_+qUzy!b zAL;ja?w(FP?#o+GK^^kXgC@dCh4=fg*gToxEBTtVIP@pacbM2bc4<*OG3Ej<*gg6D zt*hlY*1nE%iriy%;O{1$7~WREZSpudv;**ZlA}tuoAGO!m3rlHXRVvK`~w_huo0Tn zIDjt5jl;W9OrMN|Gc)5yGYn-n7!X>w*IR3vwe6ZDdhfQ^^_o4i*dCs6y@})&h|``( zKZ78NpCfxyr4d?w{@@RBUv1-^yHO#dM zyG4eGB^95)w~CH6Zb&(xoz|Q@_JkJoV>q6$SLjB(;SLMBlk~!655~cWLo2fxd_?le zyMqZO+(~{bO;U;av^1y@=5RCa)~R>mERKH4Ey>ERC49`R>3Hlam^Wk8SZz6j%Ly-d zqo6YQQ;?I?!^<`>s#qBxR7l$BfNs@HCb59Vi;WjRCOS=X++ z2eiRF_Iuuy5wl1`JMGmreUxI~hHEXn+EC)^6~bz=Xr&NGT?l%x?lQ|O_4V^zFPIdz z5swNkhUzujR$reu`m%=H8bghRW!RxzHSWBN5hv$#MA_j1L9Rvfp&70nXAFz~hq}88 zYU_y~1zw;)30^FCi#x%+NO5;B5ZoP#d!SIH5G1&}I|Yh_;_k(Z7AO>Lak%A2AMX4g z?%ap_a+xq^PIf=v@9v%hlbn<6(#sJR;q%E)D}?N&8TE@``B}a$@P3QFoA!<%4mH7c z(&NizP?rnA*8_3{9cKo+SYqNHc`MoBdqXNc(3nE_r=w`jlM}2MSDbn&S(0Xi9cKY39aTw~BDi!w)aG1+!?Tls{?jRMcij z;TCb&PE%)Yb`bk6^?hhbVJlzfh!qfp&2y9+%BYlSLg>ZYuvUlZFyo*co^VTHa+(hb z-xv@KUf-3Ga^HBascus2kI@T>I;n<7U$8em{La!G8gZwOvDeP}kZjqpV5^hD?aDi- z-SDkviDh%3@p|ej&zocwqjyPRhi;setgeGRov)LWx2*~jw03l-fFKJahPDq^LPn9{ ztL~z?=of`U%kVGi_HWA3OAo;$bLW{%YY36H|tt<`O#JclXKH?nJThv z&1H6LVl^i7*XIQTLf33BGh^wGeK7+kPGoN7`k`L({n;Ej>o(-$Ciz%+)PnaRR*~DZGU=UjVrtkB;dCdRkt-d{nf0{k3JQ?PH|1}a!T66D>~ zB2O_f?6&~UA7hgftv3n_7Sc-f7q;m3Z`WPX8_@@!(y(LY#*WL=J|wKNq_o)%g_dk$ zMox8l+@e0r9*dGYZ9E9BGVQV!!eX0G(qi4Ve3S(I5F_ksdU-jxXi(GDZOTj6>|Lve zUgiE+d6{;+3;+1~&$#K-(i&n0U%b&pg*y>)8X&xMX+FIvnL`7U(BXu4_|{o$&o_LU zWtzsGwl13y6ljdOoo<8q;Jw$FTTn4J^KIF%G(e}KNsG2?_?DGx+l8QF@utun*+;K_ z^$x3T35jLd|5Q@Rn`7fpZ`x{p5IXvrI;A0M-`s}r%!1e%**#9Op*XK-alPFaYgq(rZF=twN=&KANg6A6_~!O{5sB7X+&-?c@D@SMYqdmhfx5md zu4aHJgT>aCszm++yyL@jTQWs{i(swX=O=ltYHc?xg>k?IBM$>0dfm4a_0XU@)4FVf z{j_7jB;5)+#>Q6rp#X>9B>8k$>&+U>vW}Nmzh@zk1NM#n9Mq3jW{x`kbgpCB71s(^ z2HM{Wg!Ca;-O-1i&Mz1H6lTDMt1KDw5>^n@GlqI{eEhWSf! zSDUsZ#Q_P?KBY@WLxS5~9 zJS5vwZd&PPK7P|TVY9lMWN#wczD(gz{OK>o`C~%f7Ca|}TPuTXhOH_zPZi?vVf~A| zE7X6HrzZI4&%`E_U%KN^L@U$KdFPNQBt$&%sA2aEA5v)ek zCmu7kQ(7^v|LAfKV_(O5iOj34d-V12XM>!lcdrcsWe?GopCNgX8rBmgr-LyQIP1UPWTpC|FIExu~ z8WH18{1vz=<_PX?6l-1G+(Vzr5Ag}c>TIUQ!IZpP!l%ER?83)7|87J!Qz{qRx~XgB zOhhu*&ngPa| zK4*$*kLcTRkjg;$n_q}rkB?_~TaM@gh``(iCE@ja0wn%y5z%=*x8l*UHxc_DF5W-r zCuStFvExT`AxoOWn_YMKH_wiSL&-!n@%IJiKM5KJVNZO*t~=U%fEaduXlT%?^w6Ab z{<~iHw=XbOJTijO_|auohq#Gz8MV-UoZd~T#r<~Sa4r#sTCAqer ze{Sk6?9RK4MkD+6PS~xFmuCAwF$JZ=YlQv_J+Wo0;c@@%h5Pf3$spm`T&YHD6VgS~ z`;w;bZ@7(P_FMMPmOW>_8qAoyJmX(2izke;|6TW`?)!qNX1#v`I3Vgv@m@CkLpi2)tn~mQ~AY_8$SUMt@AxivdBuqNiUzqypM4|QW#n< zuht^t7!njW^`(;t^1g30^+u}0zJ3ZjPW<|F%CBAWOQ>=9x~*Qp{&=+9*R#ffU#Rxn z<27&P$!IG$vNMmjyRiai0{QfXka&aI1sZF`G@&;)`10%uBW4IUVG;*(h^Cn=1UM9z zS7BLnelSKv7;A_%-fJ>;DqX6}1sd4A6wln*gFQ!#u@FKA{k~y?&xiUL?R2-#eqT$p zz*|F3$|gT##j{vdx6Gc^kl-*Lanf<^ z4W$PN^J{Xdk*QF)=SjP-i`BkRGDX{o!uz02B-krg<)-9!Gr)P!V_4VkS)V-KwGoQF&UduA-%xv5&z@E^fpiG!v8pLz zQLTH_I`&B5nU84Jvt*#u2PzD-P1xNS$#^5Zz2#ZHN9`wwCK|fM*>YOjK%t6uh+Qva ze(uB6PsM|_%R3{!ijSd?=X61Rz3RO}Pjr{}pK7W{;!pl_dTK;z$+5uv( zo?A=3&W)(~GT|iL_5HuqBenL zwExfVk&UlvFDrSY<y#vUsujU>A6jDj-zf_V&l>=eF|xhxR+izHi(dWvE;uD}WInxA#jdb)&k$ z_c04Wfg~rg8o|VTI%xHJuyXW~u+M$G^Mo})3sfW8UwLn#ETE-Pkz;~)_nESvof&}u;nFz$) z5r+xu?sfvsa1<$+&ey`cfppkJ*GF(+M5qkl4jW7X8O(>=7lY!uw`wIG6kz?}Q!g+G zoE0>P2kC}*zob(k45u5>0C|^z+`(DlgVPZ3i!%(xEJh3sm=*Zc9;^!&Muq+W^bqcN z!-S225-=i@Qwi`n&W;qUT^EQ9Z+{L=0pu5h*n76N;V)jC0ThiGqmAJ00H_Xnelw`L zd#e$?OFi-v_FmzzeCa2oqbAlZQSo=HRU6?m2 z-4VWYAb1rr*aqPcgI$=M8i6tJcl=@P#=y|9t7mkS_C**wL=HBG)i#3G`nH7NK>CsQ99LPOKJ>FSn4d8a zFYF3|P87dS5*!dV7za^f7*PRTm4fKd&bSl<*rEsFw}?<kU`7hQN0$4D zW@Z3(QM84BQ`Qxv!vv4uCP&IC0No%KX6i4@vTA%x>coI&kXbw^0@$9t!U%T28ciNH ziwYG7A26_>LSKU=!?sQ9szFgzGVWIgz!9vzJ=6^>GpsG z41tAklHkD_5Fx;hhE4`8Us2Zp?AieGd^rbHj3wx!0z1SEy1*HT=DZY@aik$Nbf$Hx zz$AED*x(?%})`J8LfC`XCOuA-*K2ESh#Gn9N zm#yM6EQ3Cp0G<{%cnGOg*A+5xl>r~HRJ@@37*_kSCW=FkD*7FSpmz%qd_Y&BuE>Tj z{iS9I^cf2BB$}gAOh%`ss{kl!1M*p*|6n7%h%F% zQLK6?onDj1@mU`z2c`vmmIfZe^*;_0f)8F-Xe&0MQPWn?&@DmY3FjzaifH+7b!`+q zU*v1(X2J~VqdnmIaf6s}U3QikV>=bFJr3c1bz?J#7l8hIeo+VL``^|W=!^DuUr-h3 zi~hLP1>U@P+-d@E9?Jy{fj9q^s{?QTE7u32{#ULIM13qryc3btE$JlOJ?e%_+%<{? zV&neJf_&{;QllEkIy}%R{x`wPxR+M`Y$WW6U}-mB!&DphO0DB z17Z18nEpim-ue7*c(k9MZGJphh<9J!{p};~?h!d$`mRwt@CcuGzZ&z}H>E}`&|zY& z4H9#07ka-+Z9ij7dVXO9&c9#G>AXNA{XLIz_r>_ze-!D7Qa;g}Pfs-BiN2wFqH0ex z?uq&vK2f|Un*EO^KGEWT^j}uJC;IU6zoy+}JXQMfRH@_DQ+%nXO6>pQ>pjJ1eu{5Q z@I=#|==?wW`iUw%QKx^@;E4)7(Y1dx>xl-U|JQZ@e_cm?swDca{qawg;-2CM{Oh{L zQ~d0w_;>%hPV_`O|Iwr;TK$jy>$<@cUHeCko|=aJL<9d(=o8I;qWAx@>O9fTfArlG zrF^0f|LEgkKBR^WhW$Ovl&p$ue+T477i{}jDUPVXjHVG-kFsU}$ezg?mt z*2i5%FyJwd6?%QdV<-sADO@dN*P%;293`tRgmC$waLtd;_(Z+@&c3|Wx*+nzs3 za16lT@$Art#Xdf52O)ku#{OSG?;dMsfo}dQm4n?qw$JIMW#Hq}%>cKc$J$E}0oBJK znQ$_i$DEE}EW$@!4T^a27}OZ{_Hjf+8Aia5Ev6*gaem}+0JpG5-VY&utbSJjl6lM$ zpbyJ`%p%G>Qu*JOeq{2I8RP5#9~nEETg4;O3H#jmxSbCZP=3r#3MXTK%+3l{#(4}E z3!?uooC*x`$k&K=XdXEwz^(3)#X$t59$7IwgXxjEftB$dSs|$S@yxo{hjBe-4`d!m zedL`)J1md9hA;hbxJh}4QPn^^3-zV1CASKy6B#$&-N*s%o98NqnH>;qnwQ9E!=R`)H zauYz8DJ!RD-nSdlmj0PP{4swrA?-S9;PkpMe!osu&ATDIesY0|=Qj^}`Tmf?K9O`X z95azs7pF2-n^5Lwu?wMk?>>|5zFqmgj&ylBKPg3Nsh%2cWhEPPRa|nCH1kj9a@*XI zjb5$U#>tms%d!ss-rVX)qh--^L^?_HT4K-;Z+nkf&M_Z+DJF&Fq@)?PEqiOVh9WwB zqt2YFx|XJjvbqiib@ihQY^(fM3L_jw=D6gp1?Cj#a)py{0a86pZ9OeDLdI(LazheE zcIHxJveMYDO6hXD{qiz}yx9!Q!Nk(&WNF*soY7Q?3}u0l`1Y*|#VN8{vmX(M`Wl9(oINp(3(`Md6g zL^i3YyvF$J1ZxXSvdV~GsrsEcfGU7hMO-4g5pdo9RCETGTp1j}Pr6hnQ5Z<1%QkHa zj72Lmk<(LhDQKnnq5Dost%2l7P@h7}VM(4K9IDx+HJrmm#V_@Dthwa(Q=~uImFJvE zJATGrRrYolurg~hED{8)>}4}&7*~~9)AI+pIg5LQ(LJ*|(~Peh+OTb%d~j^P<<;6C z7;>qUv<|_m)k`mP>5$3w{cg$mPD@)a#DS!2XhzbmP3YjlUFjX}vH@#s)V`jF9l=Kz zkV~NpuP#AVWvu3$$!6^+t(HfPy#Q$#H9=`boMv+JW-DtsOC@uJRE(RQxr;!B0s~29 zFkTAy{WNXO4{(6S-D>Z)7LS^>0na(^P?tNEvz+!kTLn{P9#)i?LP{vfjJbh&NO^u< z1!stY%O}IhI`0xgex2{03hRL2WwQ)|0hecT<-MhPT6zZBdNOaRP;rM?8G0HKra@N3 z?=^7PGIcBklTWY--x5iRFYViz&FMpSruEK3uE0mi-&<>TgXBP4SRI)shtxKozj2?*#N_X?X*vW_QA0zu@u0~4 zGUi;p36inv8-0V1wz^0gx_bI;I7u|VIc2RC_~E2s7}uRxR&H|7Qv_yMdtIPsofS>d zmY`J&IX$UFeatjt6s2-jBVAGd9(S1D3VCU6Bx1tKsQ4H_jqH1o_}2$0N_Qi;W;kkp z>qB>Cl8%)8ag}t+3@aNubF2vxl@w2}1rHA{*%&8DRvy7n9Y$nwVqSMiMfB7Vq%^Jx zF`ON6MvnurgMTSireK&?a`AqL8BKjIahG=;#SqQUtwj-{M^tHK2)V%2DUBQ`icLlh zHhztXP^RJD9a6W!iH{QaIySMlYiGcBF#Wvj@2bxhCcrcF5<75pSGzbGTlt4XxM0Yj zMms1(1GjQ4$J%0Wql~j%@Q;3h`l=udB-~UG>#kO%XJ1U#u>B3$gWshM8XCedQ}t1{ zkZi$&(VgoDss{UJSg6q_k>t!5Z!H>G^^|0YH>s>A@)%fF)CDPBQVCe*HDlUyku7F< z8p~AdTE{l73HX=qEQpPnYNJm@w-EHXR_4eSM|pm_c(XCcRGZ26MSS|BQrXB^8jo}u zYiWgM<*)EjfwQCi?t#76661l$IPmojz*?Cu5STsfnJq zz$#dd*a*w913>5<7G}#_V^f0<7PzvE!5BZk?zQ+mTt@woNQ3AC>V_HKK0_(*d?waG z!+u05j0~*ANM)ZdnzD&dWc4g?dJvyYjTmw5+=m15hT|Lw~Y1KNCnY8)oW0d!3p1r?HB2GySE3 zhL%nYT|o}bYE~3qpWud)^Z0D019{}!<&>o0-Og%ZN6YPy_gPZHGrVwAR#~@NTE02)(oiNAggTaUB2cxzMK!upQ zjh@!Km{vq3qHVBLdASSL#c%&(s?zr+wL@E51Nk3`;6SZhRE3M8Sc@>4{?G`XZAxR+ zCNdIwOv_c`>l<25tWODDC#gvCdj1QlZrm4~sRoj$!TX^uY~?u?nV+9Imelo&A338) zGMDem6Aigkgd2s4puh9aF=kep?G84FuC%P+scyHiRdFm$aC%2wb;63Iw^@ec55)AzOP3SVFd*Va6PZ& zRlL2@F{M)@uOYiL)=O_G?xRgQ`4UZQlF&toODi?gbL75&Pz;PjqON$X-1=%w63 ztJ{u4_A%q#`Efg^-aKNHPR)7#{%r&1AI$PJ?iI4rV%$cNhlx4{<>z(#HLBhIVQrt< z1jnM~TUS&)=YNvg!9M6E++KkM@@c0;IMkcvdyV+N<17DHu|9HB}n>$&tP`t*B zH%MY_^0uz(M^w`I^6TPwqFrtE;Q06#wv~UUIJfQODe}Z`p?EUOxX%LAX%=r??`KSe zh{W;=$|O9b#yoi0IasQ{?v%G1-=9PmL@x+SY(?OF%oC`}P{S`pz*$IhTqQ2N+8H^; zQ(grx4|mJaV2leT=Cg0j=D5vb@`0)omc^OGZP3Dh%XcYhIAD3m?5rtd zX^n|CU|1q^zg@LdrO+?J_tqmoGkGJ$(NgzvfL$6>98bi$p7SI4g6$%^0HsBZt%}w7 z>6fHJWY;67{mZEsHNQq8)N9rb3z_jAEM+qRvU>rZM0 zYKv`Gq}XEQW^gX$hv(ZRM!`xk1FYT!WM6t;o}!r`Wy-|F3#kD%%T^E;605c|Hkf>X zAtGBB7An?`1bzJeN~2qvI3xuuKLIa96`x(i$Lw7q`woeexSsfSxt}%)!sM&~7iXbM z9elaTmMS*WTBTi_0ESDwwbx~pWeEsDeo-4j41jm?jG|=Ai>HFFb~5gj4SJDs>E3SM zxDlfTPUcOJRMzn20_IJC2ZBi<89k=$uf_6&~$ZVHvIi3ET&4+%-D7a_)>^w~1O8qwAB;a#a@WVNNmBA-c z09p2CyA>}B|5;t|Z|l<2>xk_NoG2>yNH5F;6qmCWre8op9Ua!##GxTti`mHyw%~4+atjQ|`5?mDpX*zz&Z5DnO`eGQx zsXC4lV|<_u3a*Pi1Hn9*JR^to{>~B~G&a0%>GIBDHUv2p*v9@Mw4TZyoi zj?2mu6J(OL=fB#b8AKq(>VC;V z#d_+fT+Pqfp&Am`CM|HS1p)!u{#mVSuqFXuqy^uiCCX&WE-&8J5CK{zb!W9I&?mxW zbU6b+39gS^I6W1Rupuw&h0A(KY0-)ZjJ-h*`8AsS$G19)ci_GuEra#hbQHxmwo>VA z{9jVNgeG}&NBE3YOicMo9!-dsiVAIQy{hkM8Cge8Dhvop%Ac=!r1~X3n_d{-5e_HT z*4gXN$ieu7FLIH4_Fev{{Q1kWnF+j$MS_oesSa3}h`Ks*jIF~N#W$gD-lDKAQ5N7Q zU(k{G{ddFo(KitZmAfgvs#OX$oX*IsVV3L6bUCCSX;;cI3i1<8o$;@B-|2+n!tH}Q zJZ8^j3whP0h)E}sR)TXSz>L$3qE*dZXwn_bnn6q?9xWWU4&7gBAbhuC44Cohu>RbU zPL`OBokiP?qTq?#Y0{Ok0w_;cxA}(W`KN7?^KdKvorZ|p(eFJHK}bld!NqW_menXP z%bVt~vt4OY6d*cfuY zLuTdK{YCD#fM00e2}k^O%O;z(siCKq`Dn9`ZS68%$qUNS!N zV&?>Rh3@|W1fOistfNavwC3T~>>@_`wnO^R3XG~GHmjq6m zoKTnUjLmr&$aqzk-h@Fj$@e5RgqIWTV`vxQLPtCf*~iPrM$;Dy1Wx(FIf2E2*n*@A zg{GuEHr7@x9O2{O9?TPGHztaoABy4Ryv*9Ea~`690F`KY!wiI` z$xpLP$=8#;FkAl;~f9zrZ+?)?`uUH!!#2+;r7d}!pURN?lhD3TUe2zcw` zs78iTL)%_fUpd)1Zw}~7xfWUa_$@=ZeN<~u)9WqFhbHIYe!N(hAarjz?8^+y-hfDj zr~gdl1U1W4{Lh~y_|iCbbs;BaWRtla)f^(vX1O*k2_8RrUn4>Id@MT#UypxfFH~`* z7>B8}{w~rgeQn!bx-Y39o zWQ%wd;cb5uSF5J|*%5JDZDoBSZ8Xp+{Jxtl>+Kgypsq)2*2C3YiWfYQ$%K^!Ri?drI6Is8kC^{rgC)-fxA1q-(9v+51ZWb4Ln69Db7p; z-&32^QJ0QUREO8o7=$Iwe>E24zwV5vr&r9q{5pS?GDZw6wctnR8;Hl)@_bq13k=i9 zsHcsUT!6=Ok_L*4jX~=}M$}T{f9Mv4I7wJp2Y-W1C(vG{3*F4G@|c{{ zGAHV&uoeY)6^JSG)Fi#4yNi#MzGl#?NHTk6w@!`-=oM=%X@TtyY;lF6T{_JHqvblW-h}$fxaxCnZn&j zhm@AAZnvCU2yds3eK^16G`fo)n6~)wug*O`d$pXP*aV$0S4L=J&+v8OVfksmJ0zjx zyg8xg%2Tv%Tl@EV@BlNdzQLvvnlnv~G>Oi6S&Vy1s z@danW&}K|R2DDXgmd1DzgpEXbIATob1&K18R_sf-X=cY)`r1*(zn?TW#fDC|)Dt8N zuonH%tb0B8$vRhW|Ayj~TV^RQP$>|r&-HG=bDJL6b7EeshuV5wq8dzGxkM;kNJL{6Y$XdxhL9eP=2X zDq!i>SCGXPF^T?~zm?EcX)iWkk8u7BMOe8A3E!m0i0eDA^rZT@PYHqDK(5N=m%(-q(kVOd!+ZoNe#>z3s2}^m3CroF0If%MQu^+9#{Ok z&j-f7iq;1ye1bSYGoNda&J)PWkcq4l)&MrG%ldLNCm6jo?1U+Z8AjF3(4)x}MSv}h zQ2ouCKE%G~rww3?ZckOKi49wormqE=@(NHw5M9Czo67SDKKVGV%%84B{yjRf^hp-o z{>jam#k*zSX;}E%6~tkUSA}#x3P}yUIe+miaBLn_0R=E`K-xlOt_hSOD&5Rr;fE<#FCWOF_3-y-VHhu^Dsy3uL9tRt?c zFo1jv?&EbUM=&#Rt=^dQspXrqi-fu0g}`{Ug-`yA1Gp~cElniP8Xry zJ0(=%Pw~{zavm?wNr#h{#_(qZPUDsVqWTxMzbFi8m9FO-}j=um3nQ}z&RrIU&@0+7LEX?(TvnSK+ zqe7#<+wDvdhjD!P6d>l7{!(BGOF$EtBpa?npQaOmB#lc*hD-_o3gXxw_$()?7MNUf z-9*e6n;src_#))P6j>IT8ClhFUY-;QxPDB;>Tz`#^OzzL()ecK`lhE{gNx*ooO-_ zbKeTw!xKWmDhZDaCe|2~*mlDzbtFF$A|2YpS9btw;nrk2tdH8@$stKn`@2FeBwuS) zyTx{oCW}oiFU9b~oq<=1e?ApVyKzR5fCxABng{Lcz=_*`FxrOWcm`I0Rg0G>%bYzS z$p}|LY9D9GOIB0SR=)p6k|uY6^9qTTvHTEl=s@p|jO{703Nf2T_eW(mVWD+{1!Ap1 z5|qy96^aBg4>+UBEk2eJe>Mz{D`@_d%EH}AIt4<_4J}w;91)_lc?XEL3xUfpGlbRa z_3V7&f>M7PI%PseiSwiF-Rf%VN$y|jsdV|4$m`)C>fKX%*(zCw$HI}QP>$6deyI4% zz!DW#r7)os?kqI-6?r;@t~j@z_!l86nTq^f3;N+Oo&(4_k}kSAcL_n+G4HM1ZI!M` zo#3-yb=(s_p{0!`bxUw5_Z%;tk%oe0zE5jS>1m(#8(!_&ZE_1Z!y7hYNi6j{YQJ&} zFHYIKQ=(TM@JZwUE~c2UbaPM?DyX|UbN#&Kw)`dOh7vUKVGZ_K2$s|aHNP=ScF8i^ zlBXZIk)}sop|TBRsiy6qvZ&}-WOrI+S;!e(qBfWcvda7>A!iefuFu7!6A-0ej;k|`Z#adwW-u5~-i%|X z4Y+M<=1w5&t<-4q!I%mx zvvs&SM}6V^R~}no@z&Fuy=it@X9I z*#{Q>+fC+61ta98%8PN)0q+|%gYRsTEzrBBzJ3~5%RGCwX!ApHpxs$vEQ@@ILN?&W zvRFq3n~HqsE0bmp5+%b#&ud@{=KAcVBzj_dix)A_Z|We(1?2s$oDVMH`ZZ?2{BL{^Rv|w<>$&p|W38YkkYedKCH(h_uogM0(!dY_ zrpr$2rd!Vm|6Bz09K1$veY%k{Ttl8y}{_7FvdR)O?%8Kz@l~Dg!CvAsVK~T0Wxs*<9u0opL z_LYIq6^qKMfxZ!*?S`AKF5(QajMZ5DB;?_mtpB^f&Ub;iewW$zD<=16#IZ@}6exn2 zo^-TCJt+F)r(pFi{@4mnTCA8fmj3Aq=3m$5IFzIf4o&^S!68j61axXbxY$lVBQoTe zED8i}`a&pUBY8@5kQ|n*|2&U|T343Nrjinz+wt_0<`NB1OBd4%V`oxWe;xEDurjY& z@$a?KjMonYXtQ*`JZUnwIa(ah=<=Q=ABCifLK1kvGBNU{!&R_Iy?@#I$YA zq|gjPUwuvbZPb^b!9$(2Wh8m8A<$M>WMb6j_D|VK@q@aANff%+hE+^{C>0c}?8W-;^OqA$MPrI$gLQUIOB-UPS_d3-2+oEK%dO+R3 z{2X*)F@42wI2DWu{4oK=)u%p5)`FTU*$p5pRV;s=3UY5w=4JM!Sa2<6w85{|`eZF{ znf&d_9IaJgRSR|tAevC}Y-|+xQhaa-!T<$rT2dgOM$0fdu7qQY&!PbPd)Ks7*>Bk6x7u@XK@>ecycx>j z6O{Cw*!3$*Vw!OGVn0$=C83cF9NOqXysZxt>CE2j&&{c9ru>K6ePI3tJDndPG2ZIG z-Mt8~gdJt329uSq7%mxYo+p?z3Ngs0dXpw)A-{=EI+<|i56f>-6Pd|nOm3TX?72X7`|)ZdI#BKVvrU8! zoB?`$giQf&fkhWjfpg)?e%&2p1)pY>R0HCi5$1bD5nLNZb=j9cV1Xw@a!I-M(91mH z&;0C@cU!9atbIWzoD{hCgj^==RA;tfh<)WSY)fORxwbt=$tm{w;3zq! z;2x^^{OyDTm|uuH^<#!l~rC1AdHv4>-=7z`;6+(U;nVm+rmCt<&>wSxk z7SmwZueps^G1Y;bB(3j5#xVL>ZAY>5hjPvD95nFNgyEaMJy|dZF)*ZvhgOj5e!tjj zWno{S+2d)wJZr+Dl{9x)hxi zC-vAy3}E)A4b@e#9DUl-%W{*5%e9PM^u2ZmBdx|i3c?+1eBnPk!(lEwoZ)r$%Yr@r~JrBuh-hF;%|)NVQ< z#Vd)2$rjScJ&M6=ZJkOu7{ULlVVWL6X}*!{MOiq4FPGJb@lU@p%2SU0sOMR zbm)c-S^cv(nVNNDW#|-?6KMBt5;;E8o*@y|9Y5EDb?7fBuc$|xbFgIMyYA+2vMl$t z7^)Ftzb$*68PuVddd~-Or9@<6h4SoaBrU8szPhubvALqMRum9BZ%jxqzUD4`b#eFl zdaQs~hnlN)T=A;R=jRC z*XG%ksq;|tGn1O9p>tFHHNcj{t(An+eIo270OXjD%uK1I;E#YIi0oM@_J6^uk&)H zeeq$#2zI_bICuXu+uKR(hrrq?Zj~Hm>MnQP`JSvSrV7=KsdZOD+}rEx+SXgMbAkcT z1ip>hhIMbjO~PwLI)60I{Mvfz&$e1cRcTX^4L(kcc%q><_DW^VzKYj$1truAscNj`*ZZ$_QQX{ggY;@ge(!^hGN?i;R|#kyG_zjLli5$HU!DrhbY1ZIt&wHd zhNMJIy>-#@`H7Sm#%qrN?GRxc$zr?s?DQvQW0^?gZ+kP!M6O!&Y?7;6-!7Cs%uH6lS&MuaxJ-zOX*U(Z+=X5q+z-K%*W*h3LvYetPTG~$5nM&}+MRQE* zC{z8hpeu`xU9Cc&!_L*`VYzyzRjp~^Ie+;I_uU6~;be)0qH4|}_nmfTmQM5$$2a1! zoFCCe>4OBwKoK6LbjF7czY_C8E}*tbO|&FutFhRybDO>y`^JpY+TzY(Eho+G4ygT< z46)RL&nuF19Jj%({i^KErmHcU1?0d!^XO;(nH-$HbU@2!8K+f=YgOu*1?djLFBc_L zgmnICxJUK|OUZ`po4D$Bbyp8phm-_f!|l)TL3`zK0r$O}ct%*f{ui}M32(Ai4@T)u zRgQrH+bPGLZTlaF=W=k#sg=TRb4>6vT<~>`TAq(!9%Q-{7^Y?=ov`?DY5S8z2A9Sh zx-7E8&h=#11OI*rU2ZK5W0W=d3d22CSf-1t7=^`v?xAg5QT%$s%*(Mm16zcvaMvwP z>hn>nWv9ddmc<_iO!`AUE@~#!LCTpR0X0murUY(VZoOTFPaW1q+C5#}Ap_4P{~qGo zNoItdwp61QaqQ&+ClOaTT@7hJbTDZRZOOzs5HB(RNEl^KE2TW;e73wKU~9bKNT8|5 zOkR8d_q7hd@S1<|t5ykn>b&(VAMZI>hHQk{f0jebGrRg{M;jmg*}c;Jyn?mCo?RSA z*(%|icRJx9lc|VT^~be7bT6AMju4G)axgpnb{wXxUUSVCCxA9*WNuEqrQRykxj1C8 zGL5v!0UPvE`Qu&ZUDqa(LJrcGgXE0;&evGJ=lY3XFPpkMJ|DZNt#hOty)Q+8zNrHK zy^~%!F*?U$GWDK-%Xz^vHrQl6MGK@vswu;$f;`SoZ;;f{yc>TN!f!G~Pw=)b8{cez zX7g1)FO8Vl-f(2C0Rt7~(uTs)sew7PBWJf*-bx|`yj+Q@c&;FQM>kg8RH<9Y`nR?YnhKz=P&x zisUWv3yCUKjS^;V{4@Y7q)8&TCIXHK5g|aq|D*oR089xHhs44^N$7x$A$RzHboj;A z#UP>hSlaxO>#C3*d@LP)39#S_vCz2z&H?CWTGn6ZhinoktMaRXbK!CTdghEg z=Q6krpqM!$*SQF;2e4vZmR@fHG;8q7tQ$hk@W*sozQD=xf0cmpYGlE+@RtxZ2s(Z; zlVM4X;<_?`h>=A{H@8L|oCNO;N~;a)4wUA(tp)Pg?#fm&sTDhy!Yu$P%!awnh44&* zUwO_tkT%8&ot8E@42}Yc0i@&i5mc#vt8i|FhrxLO^GxsJ7F zRj*w5M|`7-CAK1TxRmuDt#m;H0|C*siv&1aQ)Bky~d4 zIB9vM!!g4+&C6tXGeJlG@jJ*7<83qi zf*>I0_$`Ez@m6=89w4f9nF=2#2*^EFfEY90>aX(wI<-nz-n`Lzt(m;0`hR@Wp zgJyVK;?mbA8X0wy{dfGALoi`FZFIWYK#VCFD+lv2aP4b@Z)$+ZR?BBGealNB!l9Hj zbge5rMe3&F;b^pG&NCxR6J*xr5IvMYq&nDVJR`DLcFy5-_AJxa)2YF)?6DtUO<}hjBhesiO()Ki3Fp|q<+jW>JC1{>91dX!% zbcY<37F?*fv+D2|ggC4r07lWsQ)sBCHDJ3~JwRVItVkmOW!nnHH_TEkfOoqYjWDdK z@YXXi8}EQPP2tKrF`E)2tf}}GD{+nE8#8{cAMWL??jR`Tr zJ@am`How4;dA*k!UP+we$V^gzXSLLnj?SO+)f2YoZe- z7G|T`8@a1L-)koR7jJJF7T1?|iDE$uhv4pRArPoSf_rcX5InfM6C4sCxI=IV?(P=c zN#P!#sKQ-`e|O)Wo_=Qfx$k}Fx%FwEZ*|uB`QCdi%0v}a5ejlj$PZtp-QTZdLKf8h z5qAZU`*J}nT|~RrSTO*Y#H}Aom!YGEWxxoP*eznPUMN=HLrfX8Q=(}0857b_sB*!BT%zbZK@nHHMb!*t!Z?&h^jf<(v#I7%ApB$z4rAO8!Z!?1VBr=!-Fm@dO+KuWh3%+I!t{`-cB0WoKjC{5TMVz)#r&uWh0Q=^Fip=VXd9)J$%+utnD z(%g9731<$fPcS3ZeTtDTh1=_(f!qM~C%=&Z9CkE6+1ps=XD4pbyO6USwWqp`psBsY z=b$q~WCaOB)hC;g0DOJoyX3QV)u($S-F=jiXW84FAmLE|q6e_@rVF79LJ*X54yWWsFXr-PF?1tNGDOkb7h+vC&G&(bx6cVG2iBq~xj_wRN@9B`zG z^jN2$L^{#qqc1eCFcejp-Mz9gSj$O;k0&86cX=1dM#Y{+(^JSvB|pYJ48Z1exkWYU zjVB?|KRQ$Gw`EA17Qf*OORb4t6l$K?-HssPN<-_(G7yPNeLt*-ezbKq+^-lnHn&m9 znIk>sIy{DY^ye(Ce=L3sYSb~>MDtm1*p_Hzb=M^#jV;ZqCv|iWzplf~9rbOquZ#(8 zJPZ2U*7np?ykW^;B~C*z#Zt4^$lIJ;bf1}q+0iSVz25N<#+L%#wzWs44#ex?>BG*f zO|0qF$rPL0V^Ry_bzkdmpY8USe;*s!_?U96IK~;j$PeB+Ta74989VCHN*Ri<`mShN zJ-(~d-_KCTn(FGs$5Y0TfZEvRi^*fdFpIa+w_DL)FULrt*wUVr3ZhRyFEYqxERx{O z>cL8>qWj!o_7+LlpffHN#89X0m^FIM_?c=LN~V8&_875f$cus`(EK1~f)zj3(-X}p z8j>o(;G*NGl0v0Ch8zEmw>f1rmiCY3FggCp^6n6xOQu;2_R;nke#ARfUZz*qZnwkz znY3x@!S^i>Z%mX^#z?T1*LN-O+>#3>+`;giqTwYj3~t$dSgyCXk_ObJ7!>Z`N4aPr zCUOQ_)xie-EUGDT5a)1;tuwZWRy8&4chCU@2F6jcv-2xmA2?5r)aRYvVv2uhr?E;IKS z@7--Y)cPQvM;SlYhb26*8;f&UQb6efKIII^EMcO*Ea+2qyj7P3agk0soaY4rOe5bD530W!jMI)JCpv-|Di?xF5acdh!G)Etseh&vcnd>$ zwGSmUKB&d?ae6f1s8$x-2|>}d4`nn0+&jvYsIBt~&?(%5%amxX zYYU15$6OjpC6yB9T*FuQt@$F-SxR-W+J@&p<2OVXG`fMuD;p_PUFi9L8)xX-QL3IZ zG<5XYJ2g;5EUBvDhOa`br6dUze)bzTwR}u0c@@v<28LBOelOvbgY8rc>)YX~?#BOg z1ZP!h$!R1NycULXYU{n%Xeh8IcW)}2$J1mgEyQXYnoq`U&{tz4cdsg|ptrV=gKbsc z>)UDPxhH6J^c{ILtVTx3{p>NuZvIH8suUk33>DYblhUXw&=Q8yXe;0}NUPaUTveAf z;LNj@z6}R$SrRwBYL1kI;b5`*}tHxZdOC*w6 zETwhiSMg<8N^|exg?<}zwJmu`W^t8bkY7cW8OY8_#kYcut6G;BBn?m9Tu4=j~}A zT5_v@sy*~!?s-Sw=d!STe$OA#LhR*Mx2v!9VW0Aj66PMU?wiU$VspXq-oK2G+m`wy zLA0eZ6jxu$K+<#D@!q}0RIN)1k|2iCVv4J{GLXbvUHn~2pNM^8{%I^7j(LTJu0s# zRM!2(4Am}qh(P$`zI7M=Wq84pD_EuSibzd}PJR#TesP{Z z&sB~D>waKfDUV%l5$k?_{*@|-UUQ>*UB81#6<+Sr8GKy1mQf-Sk1hno*7k@%mm6^d z=Txqxl=#O(j;p)${oqs)8Tfx~j?JUs^Gm8pP)rzPZ2|8b<)R&%|3C;1r)A`=6Z_n> zi#=mSKB}3L+cygh_+C^n@K0EK@MecW*8BI~8fqBiYeVxatOZ<&8fksOmC9de{Nf5mD2`tKNZ5tEoaQ^= z4upVmCPnt=(q?6udWdXQl15hFeXG!`$P4rMk4Go|mC8=EeuV|@?w$eK#UJ82%L?3G zZs4?wE#o@d3QVx5_8|n^Gh__&J163m$~<&_Nd+%le&Bf)+X5!~hQUn<{VZA;@2>?P zDMaSxSv(7v80L>oj4PE->0T_SzAwB@DD?Y6?&3Z zsVvU?_*!lia-#bJE%T$h-0J4ZVx@8}^CPF+D(u8gKPyl5t|Pv6a&!6RGZb8)&|m)O zYjSamk~_dwfZ&EtI=P`M9K^~&oWdvF+@cf@ROBHn;gc?I=*kC^vJl26gW}ZQqYaQGZB)3(P==+W`bp zQf6R&*rLENh3E%<(_nfI*pfRNaJm6Y~sT(!c4i44F zmMbuha+$~|aR>_zJYtH1`0Wa83}*^-r|;H@r9iB17>Yq5-m6J~8}xx{1fo$2BO2um zO&~L0fW6=nfbKNiX0Zkc+yka5h>DkBO}JU0J4d%`>?$00pQ!-+*aesat`6uf+-)1X z`l>p5=;#%A!4wuWYxMmNo@f!RUPS_Jl7)SxS5)$h- zb$}=Ef*J&x#CBkR*s6(z%cHy}F#0mo3CDa1{tbr#x}p$E8}dg251V$uv7dpD;dUwS zF@E%JlZq7%DFw2|VgwFQ9-~$FZ+F1|1RcT6dA4(jRScoP&3XB9cdNx>BkKG)Z7(B0k4{_Qcw!x}r#4Pe#qx&~ z;L?Gg&~dJBl;O&NpWvsUrvq?hpihY3Pj1u#`6&(Is~5K0;OafwDSymwW5U@{#v;;# zI!S-5Zri|Lop_RojcohC6@b>@r#4S7;j$>#@r|;EuHki#PaommdOlDGMpKFs7^%ck z!B?jY#Ug{3w};@N+o$;OSC=;|aQ9vh7o^}g*zsu{4))1SO9YDd144f=(4S|khq4Rs zA{=BG=~*&VB@P_h{!K@DbV`Q%!fVdhPY3cR+ft?M!auc)T@UvBHgqflT-e5@q1-!_ z!HvDX!H;0_e6Z@r2R(81Cjg%iwuUJKNKOf2yTUww4y{W9$G4BEvyV;#=(0CYv2iCa zZkQr0ydGTo>p)M0Tkj~JU!Us7J_mYc4+TgA*SEW9K5d+e;&NTQiSdjpCW#>ONsso7 zEGDG>1hMMC;X1FU-rCLnL;Gpd>Jhi%OuYXZ1jFse z2Ev^Bu|Y7F{#YPPw?7sH^XgXt!WjBhKrqezNgxdKg*6#w*Utrnf%>^XFvR{UAk4JC z3IyZpcL2f^`W-+pvi@Tr%%}et1Y_!_0>ZTWsX#F7{v2Qy%@g!MXp1Y`p5_U10Ky44 zzku61&R#<~#a6+lc{(_F#CcKs`x2Pxb%!H)bkK*(uR;}B;&W#y**DuH{RZTRkhgn~ zfMchU6U7YlLpH%y$%)q4I9R5+y14L)fLB?EuSqE;qPe=dU^byrF^nL-xR8p7Db}V9 z1Nx!m9Ue49_<{ULOhi=-Bf;yl9#Z5R2W@m%7Z=j~;@O?(FI3%3IN_e&7+W7yRA{lz zF9^0ARgNXeHxI~g`m#HTwq#Y-iC&J-Qw26B6;pi^T$;s}Am2Wap^dq`FvV%Qy4c1Y z^173Y*akgn^rL0_BX3Enh?3Pz%}z>W?i>)&DqmeF;1qk_?MA4B9$EXXvi&)>TvfW@ zox+OOLj-4M9mF$t51QyEt}fbenoci#aGNeKP;i>gFT!#6Jnu{+TtJU<{a)EmfGuB@ z04ygTl>l5P6qSHiPBJP16g*o84m7X5?%E;-vY$juB8vk;h%YZxaEUzch$0HJpWMcy zzpZa{b(+NN-f#{`E`$@-Zrb8Kh^CF3s)K3YCRLctf=S{{%_;=VRVNgt{U9>ZAd`J)8IIX8AMxkVQqdq|`(ewv7>_pZw?=N4W{pNOfE z2iGj9xo0+{Q#inem8)YuGkx5vO(;KH9A0>Y5*)sA|9MFxJbss!WlvPi2hD{l`tS;m zuEk~9Y1g?x8Qm*8VzMl#CMKFD&4|F-br`U=7o~$bsL4IZJ@OIMrlAAn<@s*F$ym+S z4|FdqG1HD*U7V*Kufz?nwHY9R3OVt&eOl?W$C>0&@$I%J5UtDbzAzKGCZ2eEnL22H zpxSE>tNFINV2at+F(d+wp&Y6c_R;S@g49H=u5R3_y8`_ZVQ2X1*e|!yfA381; zaHVAg^bzKc?Z7WFIYuT0`+QNpI_}Pp}Pt?`>6wL z(a{S%|HKC->Udqvphy4Lw2qknYQ_7c(zAW6syET`I1>>K{My2zWma zj*E1(%v;bm-H+|$sjwVRTQG3#&yM(9E#{!yW%m1Awj^F3xsV;t?#WR?&)<67`Ho76 zC$#l^X?Jj>JtkVozQ*RBsam?Pr&+_ohJ*UVasJ+>l zq84G$_*ER{zA^iL-q)LX!Xo7DNm_3HP5D%dulqi7r_#Q7r`^7Jr@_9u2-5|Mt$%R! z@+x{`Q=PG>9x@r&z-TBvgah)WnhEskZEi|mh=(!VEyxi3`;WOF%6ZnE z^48b8qhF)<3nx*XWuE5i(d|Evr+uB)&u`*8DXWg|ajFjP(W_whBvps^OomI7o1=Hp ze@5@^`m`^WBdefIZ0jwC!s~_W;=aHAi_cc?40;alSBE{0uK}@_KCuE9_g@6Ah}uh^ zaVU>P)2bj;o8yl*w~(iC;B%^D*u%h^53~K|6i&r{fqeN|3Nsn zP+jjY{nMu+j#V|Hf!Bm53tJTetwB6^3Ln(?#lNNp@(>xYruguG+a5%le)_-~5O) zp^f~zyj~*_D!jxtpctehX0BqzPiaA6 zd13KkUSY#xFX~>9UToV*zq+fCFCdH55^sCz7PiBcgQ%LxKfz4_SFE_m;}`lY?(}_q z>3e#}$BuOjfLWU+G~@af+f}~)7#5-Un{So%6x#>XK`gHh z|0V34w~ou^D^aeqGywjM6Y#}0%K8iKBA(N@DYChKfnw26ph7D0dxtQQ*WM{kp;G{D zr;30)@vD*gUAPqgdQkuS!+SR?+kaBL&TFr_EKB07f87?; z(%eHNMR=8-oG7GR!m=q$^Ig#CaI2mMO)lfaO{=m|P1o7%ozmS10LU{d(#Ka-&-Z40 zisZ9rpz$4Q0Neuupe>%Z?a7+LCTw%_O1XG>{mK2@Sq$ZxWtUg1Hv`JP!6P_=6PTY-t?+}+|zf~gI7g}*H+o@n`Ck~`VoE>7xGhYk) z3>yaf(y&iv-D-fCEwd54KRx=g!)Uv$+$7(MG5N^$Ud8Y^4gA_W^#e{;taz?4>sX6q zb6?mQe-5pT2+4obL)~8R+08yl5jRK)S#6OT@m=9zucBqU4uK_PbOBTGtyW9X$K;k5>htij z{!U;psQE(Ts!N`x2N)#Xw*JZ4Okzl&uZJ6D{^21=N<*@tlI;EXpKP6gY`vn^;5*#t z^_2>MkY3*~f`FHQs0{>Jh7a)hqpSOui&vER*unal8gBFHCO8o><=p#-jcnl-y3`($#x((uQ6c&Xcyp% zIz!US2b|Al1GEaPzF8O2N-_o53!vE^?hfXNxv85tM{R21dpBr~Qk@&W>4LrYV+p^0rBjZDRO{YcA0O*|5pG7c%D=kUD}ji)baEUJ&vF^>^~}6u6eoF7?S%<+?uP4{2c1rL#~7E; z;3w`rGA+}l@9f-h`Y*8*bxZbv1v>wfYQ;w#+pMzrMQ~MUSi`zH6n430MK)pe*YnBe zw}&;u>#Kdw^Vi+m{?paJ%BOP_$OHygNdzNBmxfLZMF13u>5g;ai^E4ehVa4LS2sv+ z$E>c1XVX`)+dzy0Z9^fSuTy8MkHrlXLzxYGiUqF#_eM~W>b9%eI_5U$u=)+DnEUJQ zGDj>Q+;&}KdMF9n zZ{plExyfHXf}}w#0^CG6JYsXE`KI?ci^16tzq^q}-ktKZa#`XTZ0I$fVjsX7$2yO3 zg*Z1R-EqAab=4jxR~I-*U|*he*^R(&v`!25!0e9qBq6Up=L7>Pi!|fFi2EHvq|MlV zK2wIU^J_v+Tx_l&Pa@m)&AS~Tn_sKqE*@mx6>SVJmRHgl81Oe=RKjUBt=lzZIgTjZIx0oW1D(#zg(E zvHOLe`$bI6j$YH=!`#Zk@MzhDVdRWq3UwH=mULZ3;a)J>wnX%I(Kyr|ld^bKrHORxm?uO?q?7p3|hq zM4C&NFrPzbhc6~|Gzp<9y=DP-9xXDR^q&%)nO*_LdZ$bHo?(ZSOG0w6?1%57T*@uZ#HWb3=P>hc3)h zt;)A-7tRfSUhstmEdyeoKCJ^>lmuCjA8#(o^z((ahU-D^3XFg?vd5)2c|SDf*erGd z`!!^(I+&k!7e)PT0W&BZ(uSSXLa%0J4+-iMYL%9Zk&yTg7@UI2iwQ^=y`)uObdG^P zvR5Qzk1=30<;7vwxQoHH3h?mqaG3->P>wt(#m7Y-*BWeMBdTdBAN(ZAeQ7G{27lIH z1&kk2Wnph_gVgY0p_T!G7xH|_a=26rhSV43T5o7Gp$Y7Hng~Coh$pu6DI9OOZ(Iyc zj0~!si63@798oO8h<YBPIkWVDN`xkR|?+U_Q9am41t;7^Q=LaB-t2nw^*;#p;JJU;=zZ6%F4lY)%Ru1;`ynlDG3eA^VUlr#Gi^EoL zL<)&EA}VUhS&x%7CCHft$Hc1U6+m7Md)ZXCcD15SPtx!k*Arqu&@m)fGV<=I>m=MV z(*P%UQ>{7!+A<+B&@fA!T#rjugA1aRq1O9O$}ygP6wTz6{JEEj#|G%-<3Lz;?-k@ zg{B&RHqYK0N&hbQ)?z<7bNlLJ*Mnq(9WR$nkY3|ueYcYFFkicouG8t*+Y8AxEf)xe zaU-m5W`W3h~W(uT~Nkd3QPHMq}w-Cfv_PlArf=WTPH9 zELT=G`5H+4n-q3^utMYKhld$Ji==zdKJ z?1_Zxt$C^sm(a}W-`^B*_?w5RsVrdr&g;|fs`bQI1_MKSsMERoxgAGRDMASXLU!aN z)^R>-?MHzn;j>Gn z7b{$BC8o-WP%0$CJJ6tQe3PU+K4|gUbbI*1msgz31<)6s@JA za=>g37dd@C=)>WV!iu^45w!-|W6SSCZn*fFnX5|Ge)8ei=Gf9$&*<17QplQ37Qr*H zZVq|12K!P_rX%Gj^N+y;o9r8u-eqRJqmpn7j9n_#>02~4lC^=RO~a?az-tWF6p%qF z2U1tdPsp?w#2uj7hNNZ55G@UK$81cPktWTO`PxRd#t-|(xsg{!_f5f)fr3)sUCyva zGbMBTGu`8Oy}A;Yzr>u%#H_#{3DI%Y!+XrXT(A?iEA{x|f>{621?B$BF8HsR?*B=F zJb(AO4$ajUDNLMayZAq6g?85ScaMY(a;8-SLlJ5w2=7^EH#Z2Qjz zA6S@gHiEIARJWiEU~1Mua>|vXiHR|X&lc{VyZrA@(7KUV*k_tEgM-w7o`8(YQR7pA;-_xZdx@ZF}SBGI^{G4ZI?x4R?T5j1~XM(ujPa$(=r2|)UN)VT5V zTHxc+Z{isbGwN{z3+0gD-85?2Gmlc|unnkhS76SH@|1@o0$cMVpyDa(M;RtRd? z?Q170toye2qJNP3tHElN*US0}3b6v}MNAUN+ys;0f$;Qyp`l|2N!W)36Nc%VO3D#(w?9b~F!j#8Ua0x#@}luaosxnU-lVYf0e`XVxK4| z|0zZM-?7hs+OP_rckCSPE z5XB8en`ER7SaL6 z9LAI`y~ZV&4U@r2_GViuOm*(;bjaMzhw^B%7@h=Z=?9bDzTJK%=k5Mq>vcRA%=gE| zk;8(1WcIJ1qx>e3e*~#m51edazek}*5?G@XPa*PWorStWP>S*ERwNb7Nrb|U#kIjx zHKzk&jA=Sgp+Rgax17cLS4mX+5uU3=?&UIAq@3xNEsh@?RVA0jhXydqn+0PM3a-hW zhpMlRnQiDqa(kUNc*ZoLX*x>BgCCSI?%|Tw?hl_0e!8$k_5gL54DxS(kCD9I#jZ;E z_3OJ8Jq{oJ=Mf|W>t9}w@$!#K*>80*E(lfgo-`N_DQ`*cQuMN#j4G~t*xTiU^-0eO zkbI>>2Mb+INxllA7ieJ)S!OX@^1M1!SH#n_>VWqNS42qhYr)o*C+fn9tr8X2x}ssz z8Dt3>*>G*$15C__esvLyW!2?RA1#b~mD$bDzWep>R!J6r-bnRgmEOqzYL)*k)%_pU zd;Yhxoe##&#&+he=FVC#V#{X6FO9?BLuOKR4OY(w;?POM`Q+h0ggPq`(tD<5juS(Am0@ zxj!u&@=0}~Dv8sf)#^6JbxCu20u)a!jIIKW&ZT1wrAm*4!V?2um;Ip&(Y&2J##i{> zb8ClN1>YPGMr{U^`bxZ1gPTN;u!4mJH4d6=n{7B+ms(FeQCJr<$olyQgw&dLKh{)CL%tW zSrpBlKdyFw>O}qh@3DTMB(PdLv4xSk4u@Cfk%7>?H9uYq%XCFC+p{&Rhqg5r(}vxn zQ)% za!X1>U$LqvY3U3W7^Vtj68WytD*$cwUT9VYW?F5(c`EdpTe3dOBvI79W*iB<9XFpE zWZ9G6FE! zp;S~YI5AjSSt^IL($%*W-{nBUWT^_BQ0nLeq2no?*V^O|jv_}ZCPF-`(T~Z&EX1~N z&`+qqCaua5^OAT0M@(mkZ zxbmaOv|>*8NA66i2=CDJtj=_&#p5^9``WR{cTI7h>vnL9Y8YGKlc72i%!@5yClNwGm_J`!})MtkDc+b?w6y`;rwAbt`d&tWof5J#w0`+%SBg%;k%46fQ8?1$b(6)(F34#CM2f2 z3tvfm&=uYUCnfjqs@6r>D;W$gYQP)+KU9N!|I&fI?6!n0*tZ${_#sVjti`cgYlN$6 zzwjC_J_-pC`7&rWZEIc~ShT_q_|nzw5fI45h%S!5UHANpXlt>MR=gc<{IkboX4-A% z@mS`&bGyA+A~*?V#_y7`Sctlq9dh(j#raf-U(6v9M%&$D~l8~mzu`Yk(Uy+Ow0E*xTSbWNFY`LUDJBb~Q9FM(&4!aK`15=LL8ZyBsowH) zApr_yW|fyVuyD}-Is}0TRy(SxG^5=4&TJ-*&$7M6SV_(3E>AllIkhI(^-zdj2^nEE zv3j<0*Hc6l`1n?qIhW(PmDdsv zBNcLddd<3G682@xFp!+pPd^NGA@z#}`^a`i2K|NA0q7}C42dG4WoA-pw;L<`lF>8mMxXT> z+m6}r9xv?Qi~gz+t#3q@A^6>=D)1faS-^?yVoe%(?-zvLkarHR*ybLKvma0NMbi!i zwZlB|J@ln?*!+(Lt>S+Kp4 zXKOfb?O#0R_1H9*SYQCZ&=TsOM4?@3-OcYpd&fLC-!?gfCe(kVGUd zSPI}MG-gkD2iolQY*iF5$M1z@9eoe{133YTH&4&cH&u6~QAPqa=+_fFA zQWWe|7Ws^6<;K-8If)sAs@+mf?f|~t@}&&RoWs<=cWDANd|Z$+uDIiM#&rvrpZtS_ zQ{=%S*Yd5LRerzm1JNSsYZaT*B*)VLEf4Dgiie3xjxnWbi+~`%S&6m<-g>vyp1*Ce zlN0)<_P*f4^}itZ?**;Ge;GMRb9)za?f=7kyCTWpuZ{Mwbt@a9CC&PXoWPP2I~D`n z58K-GfynA;@ap&uW3D92JZ-|&!e6~N17;*mAfck&ROY}sJFz|)%N-Nj*0htd$CP=(kw*6TEV zUcjI}?G@lk4JX2JZCjO|Hf%Q?Jp*ff!(KtK^30D=GG@}vX32}GAz6I(6e-rV zp5*+4r1H3+4TS}R2Byl*cH2#OVtInM9p4-vDfl28fP|f;+0&7tAAUwR@N%0-48jD+ z`8w2A@u^YuC!g7$`Bo$1l4+35{aVN_K#?jBP9aqzNlhP*MC4x>?+7?O|E+KDUgXWK+1nV-VZ1TviUt0JH!z(=* z$KQoxgPkrx>sznM$(ne~O>sPI!Gd<%0Q9$OR@Rj*CRE%rl7)?jOZvHxPX%xChRXZ5_b%Dx|BI<#ORb;)UK5r28+*D;0^BBJ` zLt-u3Z*C>SmA!%HedR#htgF;)e(#^BHZXDUEjt1W!8hY^Hz^*zL$beh><=~n$k=|46If+j0RD* zYMug%+x^8CyAHoTC^R_*4!jVM*&E&o>cW8X3;*V_AoJ z^Q9ab-7Qk~t{8^sr+n{C+Ic5^$({erpC>^u3HJQAefiZlvlY%S0XX|V_HO^ZiNZgp z&i|-!R7RB%#Bs`{SH2M9O=iB^ABa5t71!S{Tg&JxUT0Ga_5P+^_ojNG zecPL^^=jgl(R#@0{D+~Ee37mV8@al#%{$qbyISl4JqjmmZ1(Q=*wGL(21ONnixB67 zE_!Jrt6|+3n+=`#N5X}avrpkaM&G9+Z>+tWmQm zxbx+=?+MN}TQNsRwGUYLdEunu{ONM=-}{+lEd1yl+kA693Z;5Yr~l~H8zQzZc{unC zy+8#);Z+l)O{MGiM37aP?98Kr>7y^{z9n4zZD>pOYg_;B1y=MIGyb1Cx&I!mRsKH! z?{02yV(x6AWbFLc0TVOVf5QKdM*1U~Z{mD|=-!$G@9>yet^Z~Q4gw7tnl2-T;5d>w z3MN7iT3!TcxEZQxGFn2lZiQZb1xMrLLKInp&S>3N3{Ejs-=&Uutz~OHo3aM$3Qe1a zhL08P&np8~ zOmMW1@(O(?fl-fC^k|D5TS`zn9cXn{$nrh(y|}r8I{mnyfN+q&My@>PM5-pa_Z=6* zImCR=Q90_~g$!gHAs^B)gVbA)uh0*kF^aK!y4opJ+to>~Qn1j#`jAQzu#OZRr z!_K*fE}-r0iLUKs$*4U#reS3rGPU$gcT|h(_IBOgUvIzU+!2J*vC0F(9?gO7PW>c*sb3ub_AowfU(CVxhsEuZnXRQ=UR4ImwoZ#ZV?t$iYtV3d%KqR& z=D_I}@XY07nd$KE^t_+5r&Au=QWI_Zw^2cm6=qd*@Dn}}Q#=TBy2tYOl8%ISUY95j z_uLc}#V6qkV?6(Zzm(_##7mpS0V9U;VE6gE;2f-FOp4p!T*t?y$ttXk4{g0729+OMwC3F*9ufq{%o*wO!nZ+lPJ3Wma4|ezOJrw}MmGfg zms97AxZoas+FQNNotAjtKnf(o@I+?^(ObC-fx~*x&QGddo;9GQ(M5a0_G;Zo2w4&meOC zl(~7jOww%ag4-t*s5LcV$3EdwI@p={WNWb8hVT+lz}3HI5|L-`D`k>BEXG*#twZg0LE7T*lsq) z#+zl(Vg2-=c`o`>V7k%TAF}T2wBTKLLyz&PL{}(ZezJr~rx_4jiL|qlglDal0#@@d z$p@ynWjG-yw`ym~eLS?rd`JonLEsvgPiRB}{O-!o)0to%;h$%*7EyC&AaQhK2pc~i zT9*21Ci_s9CO6m+4Hd{L5)pl5Ea# zl9@~vC8nO9dOu73X0OKBy%T+^$%M}$TqmdRtz!1@S62RPOZnzy5Z!yCp>7qf9BrHX z#>djF9R0zf;@V5_YYz(Z^NlLc8e#Lhpa<;+lj-kn&)x#4a)z@+L@+QrB)RSdN6P$G z7?cDgxHqu}<%L?T4ymB$r=;H%EqMCfL_yRA2!?$Dyvgr|&0Onr05in>?Bdl6<4#m+ zKR!`a5S;o$BLq$IrQNEFDeK+{1ef@SjsJ;~C%em|?((}_Z2mQlMumMQ)WUfnF~YyG zZEUr0j!XqojBWPHj}@7VXX5cxMSc1QCUvGFbG*Iu#F8jpS-9hr3Px=ZhLc41>I!My(v3iRyFOvK-!m|`{#;%Pft4O-5Ym4-osQc?Sc1o<=$oeR-kAO+!u+`a z7&v!yP)_J9a{VYZbus;1WFqVvN~^i|Wu@-V<7^PSyP$Ca+?oQ-=Pk7-CICtu^5j+Y5E5bS_Ea7xWwiF;Y}*4EY*Ys@CL2C~kVgp)m_U$bY| zwc8B@P3*$H5=s7H&uR)Rz5Hczhkaww&gMO-QZA5`p(pv;Mh4Srbk8H)zB?B`HZQHu zkcEHqn`SsJ_8V2Vz#(%NT9;&Yolfc*Cmm(%cxfNATQt~E6IWJUv)%1T@b$N)W!IV} zO{y%rrs$E0YO74#3-gM|>&s!3g0eqN4J5)ohV~r0&Kn2e)D@P_!*`vVH%3(LdVQ** z;-Jh~JekzHUqhN%SL~;`jbHfVONZ1{uo(}cusNb>n^9Cg30WMO;5zTszKRQl#W7?t zNeS(7rT*?T)Af;AK5M)x%)05aoM^vlv2$^xJ`O~eq6D3>NBvyJdYfYx)hA&&1 z*{zl})es(va9_blcB|*GHHy^efxAo z$GPX%7vH}XbFDGwm}9)}GxkBZnxo>9^{bZ6#3-1UAS2@ta_eECq&h=HVJ*{?zknaS zMEN&TL^ga3=YP2_$jk9L{+I_fn-41}KyHi>Ad9o$A7qh*COIvnPPeP z8CxtT(8pn@l-$k-1Qr{7!{RDNW^JG4KJ^fs!^l3oP21(ZY(e-VyvOUo@8k~8z2&(k zgzcM9a5deB8p6|&HYtt!X#UM3Q)}yVhJQ(m7EI}5LDr`Gogc&t-wETz`x+S!)m}!h zpKTk{{&Nn0@;0RN)3zznzHo$AAc0)E3jk9{nK%g7a#`G~p;w#sC>NK%n9o0hhc)EL z#!By^aB|cD^%0LWBGV|6t&v!ij_?xddCSQ@mq> z#u&(+2Kkv>tF}&E7Bt9_9hA@* zu2_QubsKD#=XxqaKF1X}X`4(9KnH0157LaLYSpA}Wb^^T>pRVelvEE=I_cqT@FvA3G8y zb+P5mIwgD+g38WG)9L`uif@53f0Z^Yrjnqsa@~quud?4rr6QF(yd*Vba-Qd#yoWip0?usC68*=>Y zyu}YNCRY=ikYRq58M1d+8nhiwqZ2uNyz+Hg;Fv?EY?Kb!RAqPawpCCPBP5?c3oNWY zyO21~1^DhH%Uf5s!R;m>vYO<>G_%u2H^*w&QVT&xfWgv+*)GDVsVA!y%T}3oo@!7b z*qe{T<(|WuU?%kRn&V>GY|2G!fKX@r;AvtJXr-Mtz^EoW4?I|iZ1CMFnVlkyz41B) z7-As9CWhKaHy)d7c(UI)mG?#q@R}#lez%{W`xvqr{wQ4YdejJmOK3!7a&{ow-6F`u zG4sG;8mBi~7ifw0mO$9ti^U8QEQ=56^Bhab0w#>zU&o^(EUm@pLBjSv7fhbpqt0E4zz- zT=t%uJqUlI@>!PM$2T{0*Y`@|E#y+bhiwt?F3Hm$b9(p8*a`N5{=D>x^%?aE%~xf! zvvtbz9@v$WGyiwHD{CvTDQjdM)%L&i*QAjZmrCLYNhgf zx)a&g#_5iaTHkxy15`Khd+-CM_gGupR+BSj-6K^~S4rYS?(Cw0Z;l+@8D)|_Pr>@) z9o3k-yiq#{)s%9zx&#h20}^crt?FQZXkzFzrNW#NIf$nV3SQvm1+*;6uqSA3I1WEKHLVJ!fXn9u%Y%4rO4~#Z zX1*|>t#^FpP<_+&!K!D`fuuudJNR{fpeT^OLeI;W2-K}FMThZN~Y+mm}``w%t1Y|xHXpTQ01Og2+UM!O1!bU~DXa#|e6i1p1jL;sL?mDZ ztp!wOK^Y@MFeHr56GixK%M`<{gb$;?pWoaz7Lp4>ckwZM%)0Ofg07-b5?<>ba7gPQ z3}u_bPHNC{IZ$fOVgODmKDO+sBkF9Y_3!KFTN}i(L~)N*%kRoGwfQ?wf2|hMq_0&vUlL@%ptfepFF?S9FT~?sonX|B8l` zx#rfsIv=tL*V2O~U%N&`BkDp$K-$RW9YF zs$6kZ2L2$pknf#uTn4d#^q|JixZC?&?bwe@{9O+-3)YeLMmX1n&P7xo1yRN-N233HVYJ%4k^jy7Bh@ zDuX&=^&-}O|*x} zO5?QyWJzzKj(0!+b2>f3L6=NzO6T3LWSEMd28I*Ljh-4hLH9O~CzYMeCCaGi%5KTS zy-CPx6!UD$s!-3bDH$D(KFqQdDZ6vxrf4jX6FkK27c0o-CCq*gSR}VEDG6XNdWaW%8ztT3o1Ul%M@D( zzyyy+xMH2AOW=kiA>~-R#EQS<$OTvqfcH7)K+$-`AbmZjZ=Y;X{fA!sq zQ3=#M1~iG+G-vygrU?`~B5TwaW-Oo15LRC_Y9l2uS=lh`*LT|btT;D~Cv`^{v#s$u zZW{kFfrz6u95VsAPSR;{&{ZUf)%UQlqDSjMN)WlR^T5)@Wi8^BZ%coF@bC1_@nLHO zcB~`*w2i)iJy>zG-{7+&p~o1lZoW%5e8ac3(P36dyk4kVLD3o@=sZa7%AGT@GM*G+G7+IBMixFZ1aoni~L%9 zlnVd$hW)h$C!(5Hk6aVqd9&9x!O~=7=XCAfP*&@NvokW>5%k4poK}IscKjCE&=#>O zQTXd4HY%uYcc%>(s`x&HLOr$9*`0xISWW(lE6@VNM;XH_R;ouV*(rE>KDHTFqzB>a zfIC)YH}O@!2Ea-57rrF+y`5uKwmABkx+4cwHvMUk*hzHBg)K1K*+7FLeSycl_50m=UNbm5?5I=9y6Q^P|UmPpgMg~EBKx3V=roYy=7j! zWL77{M>TNNo(N}zx4~sg+NWW!1aIc5CRytK40v`@@u?Qv++Oi!Yq;b|v#-4=txF+= z@GT-stn5KC$EdP(y8fgwHN3eo6r{IOx8&@bj1ZUsft^4B9J<`<4hRxk1>pV%ffa#W zOR``8P8;B!>yI(UG1{K{#wpF77;_wWCClVbm=U>tb_MvYkkzXvkv54>9r#N2KBjXx zppfRKSbq=GI1yTBqPf{uFTx5PbCQ&cwxPLnzr~GHR;yyOddFb{kNv2L;6_kO(V4uc zf`;qR(*arc^j>d6Yww{L(S2#IQK>b9_>e1XLJTcP-3P3*ic;3B+=>ymLv54|bk2ldYKLsq*>0fc`Y>kus2 zEZ^47tYqsiY@m7nsm_EFt8*)y`ER;pvAYsq$7H8S zZDeB9?ld=rgKV~vOqh=V%M5k-x#PS5PQFK_bOk}*SE5We_vv2<4cb90oN|?kU*%)E zvrQ~`nEHLPHlB4lQtdvNcUwI0O8oXp@b;yf-71j0e>!3M0BuwFifuZ@pNR^6Xg_bCI?;VazmNU|##u5rU;4Yt^nqQq7~@d?NgMKTb9Bx1%P-2(XIFbIeGxeT#|hE^-jZ|^*P|n^MUfvnS;O1c)c1# zRG$99i3)cJe=Bqn$e7Xqv~n;^wwYpnKB3N zusEeFbz}+W^WDzk&JvhPr8!U>)~9FTI3=}JpGrS+#T+`}`19I=^)m4SKBi?@^-CG9 zx_|BqIhQ+nC;2Ff`kh_NG@Ocioe_Pvh_6q)&acae_jP2aISPB)*3Tw2CV+;0LRFgg zAV2Iq-wqv9DJ=2?eD9Ze9HZBOp^fxA`^WbWJxD892eaP|sXIrK@D0}a$l$0LZe2-{ zQ@pskX-ae3HYZc$neCZeaTaCHnW((0F}R@mXU)(gi$3;%e(jzBid9p++}2xvCJ&h& z@0qI{mq{KSuPc31cdRIUC}Bn?ahho}?sG*z&@}YP$G(5{y@r%qGTB<4X$Ke`E!%>6 z+Pt2Te8oW?@=T85i)m7lv;_^Hm5>kKqqgNi+Le}Q_ZG|kz!9d&1_$^8;TjsP5n+gq z`Tc2+#<(fTTqgF1zenI_y8WqdzaO>O$9scFN5hKP7RZ30$Sj?jaIYyPC?Sz`!#?<+ z>fq;}0+*>os&cP zywqN*l?R6SObsXSkM?(bzZKqt`9TRMHjj{S(x>gR5pEG-6*BmD7y_Tgj`604ubXew z^)d)DEMg@0=wsgNHzK^PJ znd^j2v&`}wlD_5^tw3mtS}6kGs~Gy~!sC?d^vWTGepUc{4i= zkuISXjwiF>B1#TZOd4V$**&ZZRW6OY#4qyR_KCeYcgu$WfbF<3i5pWVLHAYM=7t_V zARk>(n?#O<-y8s8ZZKCR2{>3~+f}Me!nPKpHTEFpWY}rn@kVggk~e!kSWABuOwH!8 zqoEDj&GbTw(4wGXDGv66!GHlYQ@b_b&HxYrak3_gWwxvSoaamMMJcl@G!=sTpKKyh zbLfP!y08f%g=LVa3!$rX`>S*7tLU;HEsq>+y1Si&88KQA}7A(qW?#PydKWG;^>9im!7kU&N~N)IF-E=6r=RDaX>A{yrlC zRt!%KFR`l-wQKsji@AO&Z+WlEy;jdYr+b4l@#Vt!HLrTJkv;wg-guSXf-B~1AEtp# z$fwkT;vM`SvY(cEHDvE^WlCYhLbu90$@)mX2o5`u1k}jz<5rkE2qS>mORn zhd>g^Uwx>@xjnxUBPbMwgmQ%>t|G?=XU+kxJk)RlP!#MyA-|-K1NeIvJZA6SJUzQQ zLAy~il^DwOPW9#$htKugyi*zk+=>1g-IrM@p4X7B=@`Tg7q%EeTRbK=bg|P+k^$p? zj}>N67e^kcOZHvzfp2+<*r{%SVM z-#v(Sw`btPxTY{h!UjlXIZdS{a=nkt^qg!WgC+|F=K_DSdah|2>poLgnNiUYbwi z5n;9cYl2;?JTk(XAJ;$PY=yc_<#XSCbrTrKEJ)k!;D6{2p~q51&*Jm?%Km-18<7|95J+blBzrDN-$pXc@B8k8t>EGw^0Z=uVX(0;5Bp4}B1!*w`ttc;t z4>kxc!R&H+bXlGH^u-LNsH<<7rceWunI%c*Y8sJTpanJL*?u%Pfb~R35*?*3LbfK2 zE6W?Ea%^4{U9z{uErt89MSrXwB-b>O>NpCIs%7nQFjqJbUtn>FvcdWT*w;s4BuE*` zvD=sjujy7P?%l&HhFF{Ww=+nnFjkogy$+M>dfg}Mg;!6;Q#tDPlj)Wgq;nLfF9=FE zLrW%y-_faGrZmY`5;5l0`w$il&1EE9NYe$WojbTb!60__Wf; zuvp!r#|n;GY7#wRvgYZNF<%R6k!v3lxstnNE(z^(s#!M0y(}tA;;;N`9+Xqi!$#!6 z89ZOEG>d>ClI~xn)$wDACrGr`WNmFz|Ng5fA+{;5igL1w6C+$xL#>fmqqj?{gwUh<0SYqb=sctQvcfH5C> zm*5fbOnkxj{SUQPQAKxgj3!Y9MHUf={fNm?JQz;n(Yoj0_0UQw#zJg|_Tw~?tGct$ z&LIPWHYVkxyF3+v4u%JUdAzvT3*%0~Vuz23IlKM{UER!i{2c14S#qtSDNkf=mNq?> zv&7~JY_5(*{P2#rdq8%ca+(S+7V%9#T%tD1fJgIA#FJGYzN{s2jW{QmiFh`#Y>f?M z?Ukt!-*g#}Hgtg(fld!UIvvQS)S%&}l!$Ui+IUHrGyRVJ&sRvZLS<3U2!HFIzX972 zfhZl-L9k+=16M)v)PoBQ0M*iU=va}0`4`e*{iADM6Q79}jS08jF$w#cpl&~@bkuVK zPmF3Se4WNa=MfuORGYMAf+~dYC$d-P9#;6*`s(a2+kxUibx5}I%plwPQFX{>?#X?c zaEu+Q{zjoQVYaA^!ia6)Nx{!KVOzh!Gt`Ehf5dgM<$V?7x3A_3>OZCq{~FhN|5xMs z-_wT;wGCAzWt1;mj6=9R<-}?rTFDtbe)0x*Bo@0sEDT=zSP)uHz|hWVmd6m63&Joj zEuZCj;c*r5#vXSYq#fhH`=7m%!i_`~!?RTZKMKSTaH7{%AX9BG=KVY#9g9 z!dD!ReiSHh9!vFJs5I^*B+8MI60#T#lR!j#hXKm{`P3 z$ndu$F;QW9<1!?c)TmOnE|xaaEHph?+lW0Az=#f3B|&)<`Z3VGXzCj0fje!%sPO4X zu2i7h%UP`22AN#oF2dw7E5zW?;UXWUYP3pzACm9C>=| ziF-R<3OX&lX>$Ui?wYV;w(ty1jdVFp`@56x*Q?@7Vm}0%e$r7Csz?P63Y{m~YV_{p zHFA}E`}QE`=Q1Y>K`P5~G7@Ea%eW28l`}c=xA`xwNXKv)%gNwP-JHL;ZT1vRBs5B* z0tLxN82vF^ZiilyQy_ir-w-11pc${pX6-ZlJl8qse3T|*W;M@6x}TDrb7(a%)ei8f zvo7s~$vXgAQNsDTi{>&HtvCLeW9+oKk=#s0S@hQ6LPDBpSHx*9CC`YmxS*(GRVeGA zkOt4Y8g5M2x#9HCs@=;Q$LKqssZBQi6hY@OX`U(i)TD(Fxmtu;qTNT5f_eHNwi+yq zR!`EmMvb6Owp=mZZhgr)7+9XXg`enYMNGMrmr<%(6-jC2un6Ne)!TSR9PuvCbte2W2@|i`&TQEM`ugJue^P9vr=%3m68N){CHTVgf29sgRHv z;}WF=!iUtBS%fn)lwhk&b3XEW7UTNOsPLdTP3<{bT=q!@G(rLr!PDn3QWi6382vst z$?W9%5~JDdk_jKKvvXF9R%xLQabd4cA$NGd-w1!Hox8$bow0|&V}MXsW8>misSzpi z%#Pk+(J=scxIr-=E4#QcR~NNp=l2fl2QkyndUuo?sBX>7bOcDtBo*BfHdExOe*cc8 zm1;4`rA6Z9#<{$VXmDwMx^I36@$eY#lr(VjolPD;EAsYYNSrxyYW}rA#+XR6oF5z| zgT6f5|{(L|Au zox=5?uxx1=^Esn4^50EAN3T_7*d5I5KJRXH`cSi!`w>P#F}S0#EQ>YP{D~4ryC8GZ zG>Cs*4Of*3C@?>Wv7pcB0>M)76U+Pj5@ejv_6yI4wrM;9SIf1-0`m(tLjiY|?n5q} zE|y0reU$Fg%+nrx4A#x{@}q6u#_ovzJr#2ekH$K#w*k06hW+#PqN$)7s?BnlSia)+ zyaJY36G35;A~(U?tMbU`Tq8T(&nry+251j^as>zXcZHTqWC@^@z*5PjFjL6OPp^T% z6TTRj8!e^d7EDx?pEZ=0pEbqLCe@fSx9GhiX^lAsX_(fbew?Gostqw7*@N+n@yE1m zDR(U-)oGpLRTX1)_f#(gK%gZ((GYzd#2DAsB}qQ$l#4k-~D z&l1>2<=*EYk0-(_H+ub7>^*2jtuwGDo$DrbR$XYsW?O#vOKMS%dY_Nb zqLk#_HQF$vbHG(HYv&E(ABRsPXx7=)H{}ZHKT)p!6`%Qk1|s|?%<7-we1#2(Ujhi( z%6G>jqvs)bxiFn}Wpq&l`TPipaE^Rb)k~-2!9u1coX|dcPUYRIXXEArC)-N^v>Yp%Br{ByYRvPAnckG$9Tjm{MaRrz zN;>YynR)ZWim!c8Hs|kMlTw`$hCVwB+&N9@KCSBEs!~jmQpN^tis|av@6*#d24IjpN|z`5S@A=}SkY9JnPp7O>q z?0v$lDzrX+{Nv?;k907KecuM~zO#q_SL*+-nZy4TL=wwC-=@-rIkEr-PeS2}bh<{A zhE=7;PxD!!B@F=vqJcpP!pb5_;DL-0W2s_G=iN(7)GJg^?9STKZO~`AT{bfWq9n4P zpm$$ccOR4Q?++IczNG6CecxB;JF|Y<89)k|9VQG~m0HVStS5z689w9qenq=y3>V&$ zri?VitWDAqj8kxbxjA(3N%{SN@w{26UI-gE=ZH$uSSKfZ;mQ*{avQB+a9Oyma!JLn zvZ7l|rn4@3f905O>WT%!xsvj@1+GrRWEsP^fEEtW+&gTP`|aws zEQul7NS8F>VJ}iH6(H6aSd~@>hjDonQ}q`(1)grb+0pO=nG#dc$A%~ z-X22yl|ni~zBw+Ro=Uo+U5vn51});w693#m_ILasi8#~(UggZv!qB+Y@F<)MyV=iw^QK%&ML1D^R|nw!+v)({|2WnCr~OCV%GUCq-(}Lj zVS0zY=BTYwB0>jXwqc8Cr%?qE1rT9UC0YZC;JZ@IFxN;udNyd~`4Ym?#Q?m|!0&Q{ z%wrl@t7QJ%_v55T?~`BWnQ8y-9fax#EkJ%UkYk{nNMwOWI_?oPD=u;)nTTYGDN0K+ zrVA&R=Z@ON6m-ow`-vzVP1r?pw7x)-ATW|qT;ss$g0sW$2bHEh|CUFm3cAq}GuVi; zyl3OI@Kwb@d*V-N+jjI>M}?gxySV^exM&3I8r4ZJ2Jhe$6N!+QuxoP3eLD5|U+g%J ziTU*sz`*>A@#N9m8XzyTkr<;5CY^H8Tts|XGm{(B9Y!VXY;ApUe{~DcsvN~Kk*zTD znq7hUli23`M9EfFxJ5GRCxoI|d0Rr$9c++fb7mtwSgO&>!NUCSHm~1V(A!OIlr3GO z+L|7+X}_(LW>smuLU_-K1R)3`GzPXye61qtELMJCQ!Ndkl=Y^|z&!OW+66<-u&GAq z@Fda*jHPr~CQ$?uW^figma2B`DS%2;**0WhEoJ$TF9eO1v(ZeDD0P@FoY$!>?(09Y z;7B^BTseS!s3}cHML>Vg^$}1=&uA&yhP$K^BdjC{kOwocXN~>?f~p>z#@q~A7MrG= zl`!XSmck-h+h1eF0!ycvr1SzZ%(yoLEfC15r~!HYtZobR9{&pmorv*t$&E(nx6i-1 z%LCA(1rfiG3da8y;2`!tj=ulO0sZe`IG}3bsHKehDZ}J&HNM{jYgWQQT04uzHIgV} zK+6Bx%?fpq$YPbi68q|#ktS(Bm&Ua-nN>)MGQSAD3)(|OkYD**zM%MpnQs0dpi%47{)E2&YCVlRz0mA;$Usc{6vx|n{gk)oQKpyf>lO19Na>&jFvajQ zVi2*%3Q+mRT{Ap{8rMa-#ScWv#Y|J;-*Qe{;Gz~g^x7kYQtc-9r>{ss%7v&at9v`!O&Si0S zg?24TC!);SnaiJ!Z|I0e(@>U#72D<-Io%^p*ozl1rLo)xN7mC9tcZ~}3Qd^P$O@*! zHP_s6n2j!fo*S89Hi_`7TWA#5>*TU)t&nY(Ns6nS-bb9$j$_@`l%h-n@94W-N;9xgBDl zeqgz~`QB&ZOQTy~)-if9soear!cLyEG#nRFkwto>p6nEj9};aYm;jH7M0A<8Zg>OK z*N-tGY2LfG_03nNnJ<@fHMNFdg(I=uW|A@UfH;APLEM-}wyC8|YDDY92u)UUoTZMK zj)$*_gvSkY7}?LPKr7KjUL|)f9H|`i(u`(QFV%3tQd`d-pve~{$J{?Qm~kj*TT|3r zpHr9qHQC2n<$Lp5L_@d~88$L;uIhN7g5)gQ{0zt!w1N(meBldE=noQnC3EDKic z3cUi~Em!rvX1k=|3cE^@CDYO#We{xo_g|`ZN_~6J(ZN>|w?DebZ67!musn7}V*0Hc zC^Mw2Yq;ufrPv~Ee|q8%DZTUe*_rJ@ahL6cuov%8a#!l}KZ4sS48#VTFwodeoS#o^ z?bIsCDv0ceVtGfJD07$Wkh|(^?}mk#7%WPW?I+baQcc-#Rmf?S?36sGk?^JLqhs*~ z$5glq^hL0j?WD|}>zcVjmHfy*8v6oYTYMYhCy4rJ3{JVh7Wc0BmI%>~P=iQL!b`Wl zDsQG4Y+9Wi7whO8fw^L+hoI(86Qnnzx9K3Zbos*n~h~lYJ2pgLH2I^wX}L*#wy?Dz>%t$%81J3Ji1%U!EnE= zH|kCpqIz`A>+$Q$oHL3LLvq)=)SVo}s)4_~PK$ao2 z9XhC~>|Fjn8?R4dc#gOAK0^!k5WnFk^1kRTdz7bJi*?%x=73S*eI_|Pe_QqD{>^xc zi+)Et-N*0;y@<0~1IBc@P(-HfFQ2zYD zVhU!~x26D^I@6wOtR(aVMc%s4NKOvSJ(P&%*H7NzPjlY__&g~U%No72IF?6JM`vW!6{10%R75OM*+B%khb>?=l8dN z4KHXGGhGn|EfZDW$7ddb|KP@jRl`vtu|5GS!S2G&^g~&X8XMndXyuu58_G>bXoLae zB7njzS}IDax>UIeqdPNJp`uC;8_F$&p&7DKLJYH)TjJTUBoX)TxfaP%;5>Q__x?^> zT`X1W9gizyk3NklJmtIsnF%-|H{BlMZHOnRni@8wo1h=Cmev{1>trWO-Lg|H)Sb92 zvt2dAd-d!Da|=qf0p%tE!>4bOYeM%kbHFEh+p{X?2b<-<)=Y4-+VmG_=QH_b?_XQU zufc-n80>O9@H}ws(7ZVJ=HC#1$-c=0eyhP3fDJ-#u3?yAy{O=OhV+?UxpG&G%H%azGSoz>(Xy34$6;upYCA+H1_AE~lfpJh(#ip=1+Agd)Syc zPoLVX4r6Fh9cPTsqqd+48Ndn>Ctq+|V^ zJ&w_73qL8=lpnnPnf#^0@inJo&QQO;{w-l@8SblY|4x?hF#hBH`d^D93jgDT=|6Vd z{vXo!zw*6{;wEH37*T>`QBCyt`+e}c!7NQ9B~`&$X81{@c0ZXG^9q?4ngl&r(Z88I zM(2@(Ez?53(Le0bj@BI`RPZ*Mv?U~U0s&3%@XY0a}DWS z^XsLKl1=sxOSDF`Vs{h;%%vuWOPGV(VnU75XP^%?~xelq*N{1@Lqm_S06%`Q~={B`}mx3nQ0q!&<79yLwhw(8DcNY zduQBq-H18)#lxegrzZH)oBkKd-1i9FKb-Is6+4uQmCp$#19gqG)2HHGvfZp% zPHA;x?xtt}Azl$F}TEe*W+r~P@=g(KoFsy93dl7Lc#>!B#&Bs-e9 zFdAXp@@yvNluMUG8Z-0f_00trki)Vbyo)eVMXsR5;GTv5_Ts&i$UJFkbxqd+2UsIKhRlhS$zXMLdY1>}vX845H z);(r70<{&hWwMry>>fl%n~iy)oCB_I#f_eiz*?h!xBVl_+P?Spm*P?OiAA&9#uMAP z59ksl{tuN2cXRhSaw*i%mmac!4*L=LfL*78VQeuqo8(#rXTYZm{hwmER&DfJ zD-#DE##l8w{4@Y4=@=v1X(R63+AbHXSKP0$1MT1q%M(Vv{q%_ue>_*i(%7>g`m}h> z1Lq)*WLv^p;+^Ys%EPW}zq)!;4wagIhS{Eh2d$un0I!I;l*LM(5D2H3)LnJPxO?rl zSP}ZVFZ?iRj-Bi#Gy69@@>%jAn_iW1^KExs$(a;AD5Kzzto&n<{3B?h{pAGpnQ_J% zrI%S!gX!c2i)v% zq{~`jAdpOnx2~FGspx*eN6oy2v+pc=3*!5q4w?se+x$T7}fA68J2f!&oQ1P#ia zi~O8hk!#crDK}@&;8Gbo$Qo);ExWb$`imO;e$$D!sTU+uay|kHGjQjKo}CB7*2+yq z1wz1qHxec$1I^*8GS5w@D7Hr~HMimFC!$C)P{4xV5%ugrqVsD#gD*skF@^kH*pS#0 zulCwv3n8A_Ce}TsP%bn}ZdkseNk6rx$Tpi5q!GQ>CxE@vm&L*C57^0q>O83yVwWHc zV|~~U$|*$}g0_k{Q6nNr&tikD6XVs`P?`JNebu%8>gOmHp(__HVkXQbM(j8~mZp{b(cB3RYN1flX*`SwJa1Xs@~gD;`sJ81OWsHu8X-L*$n0Ig6D0wZ6_}Nh%d&{3(uEvKfEX z7-R`Kg;Z2rqjU1v=NBL)uBqHcL8dhwUqUj`%4?Y1 zAo^^U*Tw-<&{c06XA(QLTNpH<#ZXToW30t`8_gO!b@33+7^6wXOZ=GO%t<;#@!Hud z=kZNxIZL;CCXEV1yF+_D(3|u`WQH$aIKPBh@PZJK(8;fZ3H9o`zK&kg`Z6WvNkT6$ zlY0zY$1L_6O&x_nVpE75%K!r+Ke?FcRqTV#;pgqoJ7gpX483RDVJTr^7{sw-At!Yy z8*OgFk?T+TUV9q-Q}$jxdVQW`{*Yox*L7vGYN$I1F;e%@>|FLAaWS0b z6jktj^2PtR0Kxw&9f5x$I|o!WzXwgBe6n^8+bxhZ5XRb45BNG%oTtYll@Nx}o0S@5 zEJGpdk=4gFH~G`F#^a>(c4L3}=5%viPXpoRPQCxwd?sYbOq%;eFen2RAhN1$_FdZX zI?Cj!$nk!=ga8unKpzk`l_!af+@(^0-i-bD31&l;3bXaRyCmzwQR;;kg)O|6M$QL+h3 zlt*tEt|n=+1aqL)+B!K-&OrMbTNso}18mQPlZ@0=@mu@`Qkx0a$;cceGeEs*Zr?cC z)KLrZtZM5Kph)c?cpAjz4qz@J>_u3v;QXNC0UsGQSjnamUZZ;J+C*2k(>#nirpaip zh)6aREhh5NYIcE@k%FMK7O9+&4u4+0G2}4ikw}$&wH@m9K^+qY!Kqxf5=D0t%*W)T zoTwU(65t{*IU&1gK0WKTSpJDxFibgIp*A25WLi3Ag6Lev}vUF@^oXIdS))fjWo;D)JUJ%R^xc1rq~l44qXl)_DRf| zy~L|cRAa+ro$TUeNSshFW#}5_Nia zaB5%I43`ksc6IBs;|ZR5Hr%Op`(+F+p8sp7#vCxBXg6wHWa8!JrZ;WwaI=~8p?1s_ z9!T`?!yIt+6!J78lXd20DY-T0tzHZ$J2C8ZzCy)J1ru)D|&%SUeH z%rTWeq#S-)x_36Nzt@2zx8V1{2q5Gsg^Jfb$iW+s2Z8b`dfbyQslR&qr+0JATY9u^&madyk_ zKb+zNPr38rDabs}TuPl70Ws4JW{*IW>vwS*_e(iFq#aUNeXd|BCs4ENKYqKS62^Cg zE?u`xG5PfKNAHphz0Z)0!0MfbnhdS7j6j%@bTURz^IDwzJ@S+S#v*5k!zHPnZA1}B z-eg32!TrakqPA1!F!g=d4nhCNlzR1FhSiDuk5g)a-wuxU-xHAjKUW_WE5&ss6z@8E zC~Sq&h=?ky8LDI>%0RR{=%U*?f(RHZb)lZ6bL%$jbZLSSrd<=0dza^dm{TdR8B8Bv zzCQeXUbb_~vZlVOEGg^DiOwUABkm*8m%VCT9|&7ezi@9U^4Q+U(H&?m66;-Mt zp@9wnW$aUHe&soz$&C)hvVAD-mCjdbfC zF0$J`EB_&hQeadv)_*^)nl#b zr>elSECC@GHcFDWDla{EB(kZb$u!T-qgRz-3ks1`I!?uga;E}Nwx)6WZD{?Gcm_FZ zd3h2a*o=s6+q+sHdAwKzJ2Z}mO7r&Uro`a}TZ2lmlW~T!@FZ=%*xWz?1m>{KEp~MK z&AZ4xa@&Rcwd>KtI?~&{qAwA5%O!ROmJa_ImX64VV5@VAXSF`^<(X?rUSfkIv(CRa zKh8id9AI_3<>Y4N(D+qv+Jd3SS*Je_0{GhtcYw>G&9P|Csa#8YM83sBWGw8q18F?4 zZv^5FQyFhabkH)6YuhXBMcNv9zAsz)@~Hj!u5B$xt$(Iox7A5cSAvpVaON}{V7JhV z266N*T$rCLL{?}SFGwPdIRA86zLf}7_uGu-g?V=$afa%DnC$Ls5_Mztl>pBC?h$Qv%-mUJ4AKylBaPwn63 zr&seR>J!&kdZnfPqPL*&@Y#Y9x|@QkZ6b2jAXPfcQO2$-3d{ces#2uC?EQv0e~Rnw z0c@U)juI0MU$Z>C};sUvSfhcQirP%a+2SDH4dDYaByp zME?;vEUP7K8)N{Vk28c25dCA2v0M4;#H=HH$=8-lZY54w(c-taBra3V$~j{GSpj*d z_%=q29_J(W{)MCEF~%rjTk+n>GZYe%x8;eH0`~Igt}C`zD&e7J=~LzOrKO||nvGuU z>#l3U(oc<5QTh<}2>D_dOn^g-dO%#Ua!iZLbLJQvt^lgBlVobXz^XHqb0o~%&2eI8 zykhN@Eh(<-NI~Wp`El4T`aRyx?o!?T$Cgj=UW^qk5>x7SR<(0?cn@%#R>jMhPMX! z@IL+$5NYzE(ksz!5R!a4A{HzlLiF{J8I9F}zsk<+ zLu1xgnJ{9xu&Tc2yL|om4stmkCU-9DevWgsf|EPs%v>MJhX5Pp{@HVuIA9ycEz?oz zsqh-##sa;y1?cehodPnLKmR#O&RjRI8nJ8{DoeMd!HT1wvusQb77N<3m zHl(fgR$N<#y=zQi`Kx2BG3`J0OjdX4y8#Ywdu>vwh8R3&YtZHlSCOqIb}~s!&;d;A zwixKvw)(;*gsTn~(&l#F#$qqScb;lmbs&!(m%Gf)fkjl;jfV;SB%S(6>YdAsJV;hM zQ{*8MiFi9~3)t6B_^zJ?C6wEhN^omx`v%AB7SgpCy;oQ)Y3w1ieLm;Sl2%B=;gJ;Z zL%XY;rl#g=@y#YbhiGl#`BC}Wn3|NQ5MskQo$4s^#duBC*Urloo6Un08AGmWG_6=y ziAiq%kf|7T{HB7q9o`1CEV`u=W!-Q2FMp8x*bA^~Ij&UVg%%nxxG7j^#yBqTA}lPzSb~n&DGGucegZ13 z-ZsE&5#Vw*dZ#8j(f*8Un>oNTm_!5=2}yAd75Gj`wSTTjF9xq+T%7I+rK7@OUI0-H z@N!Y`X$*_PumWbFKH-{y?jwvsQLx#EOmMLwNCf-N%Dmk{)*H_XgG%k=Erm7ewvt>%4+zVLllR4o; zBo6UC_6Br9(zLv7-Tnu- zt|n3P4in@p@dk2Y)epn^QIxk=j{7UcDPPRKPIA=yK}b znkd_mLxnSt!X*&ae@=U#OyCke2f+mj?k|*dEu^D&;nRspBpL~thd6Std)7T1*=QRJ zql<4dKu8x$EPlv^V*@eG8Zq|lWk<$!OSgB7!C&+D@b=`BMy}3Jm{jyn?~wn!y#Al? zNY2up-^5Vg{69zu#lLqzQfExm7tF|M<34?vPJ{?Y#K8siLj-{1=YZt3={7g|&!VLZ ze}oXX+8qu?gn+fuR=&v&+S4GUl2U?c-f>zTdL44uW8c0^MrC~&q)Xz1=p%E;O(r~z zgeAxj(P0dvJK|fLmw}g-G-)o{?gah>ln$LkEgI<{*@aVSvzsm3mFpz(k|_XLM5&rr z)A8!`*gTjlENrd&mTHd)n|4xx9i}dcS9$zI#p>Mrh6DFztu^M!j+JRvdE4xr8?>Jh z!tbLH-^NOgnOR=Dy%Er{AMXbWb%TU-S|;53w2SR;nH~$#^n7&?X%qv@)x0M6rxf~WaljuzW4c{c1P%NK_3iLqN!j|d`f&G<3 zX^9x{FY^yV`cvamx6KIAM7dLtkrVlf*+~uhj8N;$V9(17&@BGPAJT-!rHc09xOc@9 z)=@1E_}0!W)#!it6u5@=WCO>}B^?uEB^B4F7@lK^QfnTY8_^N^XNPlzgM&=d`IXVp z@QCROwq?<0NsH+GYk#2oH`+<$p}Ya2Cb_Wy%ia{-v|cChQ{hPc79~vBpsn`!v*5Qtc%BhE0ZShkx3SmE$`rSZeZp3dlH-&;cYd|q?ez(_~~&Dc(0m;tX^ z5_qI&btc#uDDQx%ap=nt>A@o`1@tAasqXn%1uRaP6k^=p;coZawi8_^_M7i`Zfa@REgQ-dizU2m{rvdSwNK?bVXqaN?%rnl z10N5HA(kj9r}V|)v19XX!g)e-yX@oj{==proSLtM=20E3o%ig+~-MNdMysxB?s5{2H{n)!_Ha#wX4T}XNhAlgC;zI2*;6wZFq!+T1BDL zqU&O5FokJUjUh5d+)4d_vWcW6WqVzo(>``JD1aYCyP@ON)>tvR z#S_QIZbl`_$Gu1=UnqZ9$7mIbz7;sntG;!%?8_;b#A{6i<34}YW0muY26ruN=WfP4 z`IFG$VKsPu4Dmjkjm&XtbKHwXo~3(BA2>msi-AQ?EV)j$#Ax>V)+U>G1Fy}M2fJz; zG2|Q((@Fm=WmC?VnqN*?=xTSdc?(IcNI_^ksT1M$W-^7iQ-SQ)|CNPEq@c3L>o! z`Kbg)M_qEpDY2+XD|zbcN*t-0&aw@sf0VCyCeYuBhRy7VwVpmx}R4{Th- zjh%}2(AAFAr_{JcrX|=5#6$*DS*e3tGW0iJxol}mnz>l zOOxpW)cp|DbpycT4IHnAC$O}agu_iKZyre~nKiW!Z!3#{0ObXM<$f949Y9v8&n9vI z>Gjz^<(1n%mjvM`UXmN0`GkjZ19?nQyDiaIrtzpd(4F*S@my9hR-uO6)mMH&VctRXs%y^!!*~B4TK;B3N+xo^ODK(M$#j1~nLrulP^>=;e|15E z69*Wav#;HW7|lxY@3e&miB^TAqz5>rxHYtTsUmhv-Z5&cCjdDU$N{ek`8H_ys> zG!~`~4B#8|+kQjW8zF_6rZbS1-GWl8PEj z9ztk6^!8A&jQRXguXOMSRj2f~yfj+5nM>?r^{T_ww>!dUvtgPAS>a63rEh#=R?YAk z@pEl!x!m{YpD}mR9YXNXBI2;nVyD^pof4ng5rj*8q?p(cr&yFMMQ=ee&HcAtxedj9 z?4nw;?XKOF4JARu-ZaKE*sE;y46qLccq=}fKl_iwxn6wmR`@3*gxkcTT%=UIT!ar)z+5{IF4xrnd>H@PQoaT;-Fn)W_9v$Q<>>eY zEhp6S6$hW5aYuG!b)*#kiG%j6rwB}Iu1b~Z6D9cHTVQyZ|?S>#*}G+C$w4tM|=QGh-d-z;$dfjzcUyevE)?91hv`A(cxW_ z5g<^oKsuw?{+!|<2m8dv#4BzUb->043&)=NggH;MGuY2IM~4YdZjmPJ>77l{c}`_v z9W{h-{lsPgt@BlVA_p%(_}kgr$9vt|8Ga*#)aoCRhVwD*i(I3g%Anp8ncpWhDVBrK zjiByFUOtusyp34GDjM*c(z2%A&`0sGU(rEVXr++*j687A(8>rD^uB4d+Q$#(yvO861AU!?S>NcHIJv?t(Lm&w%89W5bncnOJO~U#JHfc3nSC%p0a|Wl_y|961Uo=iCVDm&h<4q++-+Bfbt0|?4;@R0;H|HPiWD3P&jrTWUDRhs=A+eSRBktXw}w43|t$=od<%fUUl^+PNA z>dh@HJrtDaeF#T=7wB0k^AZ3Ij|5)q4>)${`Sym!S#10zchJE zr^!7+(P<2NY^SoRa*jERka;O>1I$CjyB=zG6r${BrL-a~eO_2Efx0rnC*fW{fHtzuLIf4`FBd6-_g#= z@b4#uP{G8|+Ro6yRA1NPZ#`u8|Iojwv?-6EjQDOPQfsgbQBbT?rWApm>*%j0<}1e- z>i1QSSM7B6x1A{U`WbzjGuoNG@t+Oudzz!N2?dTusiMhuNYAs6>4!BalK_&c5&2>mQ`Tl$k^MycVWb2F2{Z&YaR`~sveE6wu?$5X<2^jew+$_@(rr(t%lAF!4 zO?qc;9ltXG_{W&GfAWb2wNb1^2(Ti!M#gpy>HK!f1Pi5x;fJI5@vWefNP5jSyM?-# z3pjteZ@mn3$|zeQN^@W9z!{yQzV%rQgvhraic8~+)(F8`0|(v#X}AQVL);flSjf0a z3Q;c(9w0T<4%5~m;~ma(FI#hM+1q=gDgS&%9XAnj)xgeE;Hw-UB}x4e_c~+$I_>pR zJyr$VR--(t8Yd=NW#&z0&`{WaqDO?-Q>a2^J~Z4HFisC(oK8{1-x`HEqAoFuof@kW z?vevn?8Z_I2XhBP3r2hHyTjG)4>2}x#0K(L^zmM__+=*jp2?ciqY>PCACy8IrMf3s zjTl8#ouC{k9a2PueT}j{YOU6rsGnuG zqRBG4{i(*ar`Ytjxd1Ax!TiY3yFlMGWTVe4ePpp82UL_g(|l;!wBe0OlE_y2A!5aK zaHEkXonsk89VT1QeSF5UCCNMA9NA2%l@>}!iy!wK5}@i!HOwM%UX}Xk=h9mDohI{< z1({}QlO8U)3~9|cHDJ}D^tBO6QLKMB{Yrg0a*`-`R-_bD?VNi~C$^?(@()3{)4eQ! z@%;A2u4y`7#gKS_=ot#5A8iFRd1Q&DHR(+FK+=4+kLsS_;f>WL_r5E+1`Da2CdA4| z9hB!UArWDC4M1=+qJjCc)iqy0k4D9t~Bo40mqtTf#jiCI}f$d7U zgNaj@&xz8honl+IU1nUOQt_tpN%2#A*QRG8`uU|T;u>*EZefJ-q(BcF*d*O&jWM00 z++qQFTYFstd*7ov2hocm5BmIaYRzz-{Y67bTLe?`LDAsF8T}=Wmi%WC7Qwd6GqM&8G2^6E&IF* z@V~?toDVAn5ZxO}m2}%+gq30ytNdI%jK9v2Zt)R68qxLBJ#Lq4ijD)-=#vL77GVZ& z=kaTIBW9}hAA+`bM+bIHY-PeH>Yg!LenzSwpfS1%z93M&?{=MSVZuN1Vuj!6`DscK zHx&_&pCC_9bD9{Z96anzzmghMNLgCFgq}D2BIoyK(tNcxR#z@GO7nNGPD=G`?LNbt zUJ;+6)U+jAsVkWFtgdnp+orFODtA0CO#6kC@nc2lXea@dD6A}B|4uFrp`5L^QE9#4 zQpEBs&%8eHE(zKoaok7QyW7!utCcPo1AI;98;ifg*|fAxN`xHbvge*!^Az7Z>5&*f z%_NN^8*MGT!fIEleUk|K%%11k4K@hWwQzU=?~*eEdk6WZ>u*R>)g4SD<#R|v{L>-% zFZoLUS3{EU-}Iphg>|VKFl3n%@p1u)pxRiwqW}#wt8(*o;F__EJ5aO*^7&#rJedc>jq_ExYuNLutL6UI9 z_b)@1(5TbFt7<#dZ1&Yf07Vc)AOeP$j*)6J(~Z(r%cAg-#yhk$jdZ98K-OH6qdfs0 zaxcSd7XDU?IA4IfX8VNgeA;X4FGO%fP}HO7+3QM}5c?i!--TQf-DbuNou=pe3+^C_ zsF`1^uz+SB(C3!3J`t7%7__LSLUl{br%~Dwk_^CTKY*KQLnK7bnY%?cIjX1i(XIHc zcY_q#kXJ$%+EUG=yq2o36T5=nzy*x|F_W2HZXD}L*slh&GevZ$rtzT-HstIYC+~9G zc?t?wqJ~_GZLx~l*Bl|0-Z%|4B!q^9!9u5-YnBJobVRy}g~P8DX3Htn2xHdPs|c7K zsnl?} z?+p%}bo`aE1SsumSl0@6q$weLDg=|Gimqr{30KB=16_WHUBWVw$uMVZ0t1_u%f z&Kib!S2h)7PX$9`qW$yDI%&ht^VgrNiz#D!A}-Ut@SLRKsQvIP$O>(CV+A4Z+`jG= z2LFyf?~Z5pG`+lbpq#`xFNF6#BAHVRUOr@;k^%}Lq+z;u`d@&B79-Pnyy+yo848>H z^{MzTvKqLQlA8ko+wcY74UD%T0>9rR=U#)gnk0(0Z~ZMbK%9*|KIHQ-aQxH5!1=Er z#((esl-9F1{KSj~GS;S64u5A{Gi24x|Ms|iT~b0~m9bInw4iY#Rj@4-7gR9%M-I^v zA5%kA-0x(Gk&96y`HGLCNqkfgoY$`q?*s!3aa;V$BsfL~X?-npx4V-~mtU}Vq(B8V zX!`m>m#va58v+{OtrBg-vzZl268#&+g4jc}tyw_(BfH0y;9(fhj4jzv$*f=Q7LO<6 z5XuC)o7F{?!N(gM%C#bMBgM2wCVWIX5(2{G z0Q;U0t*Y8Epv>x`E0B8}Xb+08#IpU+yo7b{d0Q0|^jMF6-_t5v+pr$EmDW21hL#b0 z?W7HV&Kga)`LAo>TN4lE{4(T0E68!nkzBK@92<<`OjI1-bwXlDuF#vXU>b+ueDBio z(A-4>5TdnZ5Fo*;RYyztdA?lz+1&$IX^l|yl7jn2)T}bd7SE>q6aktpydJ-!!P0T2 zT2~}K!D;;s#U*S@28!~JHr{KSKH}>jYGl`5#I{$X666{UJy^5wwI|SGiWK+#OPGLX zE+g(CybcKh<(WY)7DtLr)Db+jbl!J2jKo84-tF10;#^Rc3P(r2WVKrYyMYPS>syWM z1dSSZrS>?APBYcTzgLK(m{sjge46t~K0(BPn)Cm0)A*N~Wd9vN{MSuGM%PZ)((rRT z7j`tX|NNZ(&AO|sYNMct{{DVvH=7|9^lN49S1>C4kp+;+?dx|Dc$0A>_(UI6n%|PM z4n@{y4z#?&Sj2w8kkkygTl7c4_~g{6$VslLC8>7UMx_S>sX?wcuA_@3=m#84an-0| zKLbxbJUl17-*2*yef3P zvAz81pvvYRi#!m2#8WaY<&#zHdby|Chj@$mOSY!#&i?y8}k|;qVRe}?vmdrh98P|QS1ZvO@3tr z=X~%%B5;Dbh=gn}+bMA=l$C+ETGzi|It^mDHh5#_NU6_FY0gknZBX6PGQO+@0j;=> zpXcVRo)vpc=7>vASvC{?y=TOLrMyW(yq>atjn@+{#b61of=1EdwSTT@jF64RP$ym!^ z2Nu?H#+oR8(>)`!4pOK6rRrQwF(faoyEXACXi~Etk9W_1K95-;7afxP0j)*>H4Fbh z*>39+&{~OPQKD%uNFh7mo(OKx)Mw{H9j4ix)>6>aEDG0|l_{kcjfZmz3rnhQTtk$C zXvwAT&t&N9h&K01SH8Qe)XIX?+&tikV|H$xby|u!l+w24>rZ>5NK#5D84%SntSG%FA82l35E7dgiHYX8 z$88LxSKgl!Gi=lfbQsv|+B=~GMF`T)xP~?yuV0Bp&@AtVCrX_0Lnx9G^eFQZibl14ZeJ)Qz;)xN&t0i~ zsoI5Vb(hz!h$&_&4z1x9{~eQqy?TL78#i(=f&^v#{^)Afl1IJg!Ji#d& zbKWT%b|2?!tuO0G;MvHIU)M?mAe_G37wb!EP+c_~*Rz$DYGkyt`Y^cg_|!e&`oLVv zemT7I)tQ!V-e#t-lwLn60xgKxBsg14PC1)MMl&~a|AMoNXxe{GKhj%%xzrM5S)uVN z&{y=;19qqskBIk{=Ck{uvoF*(tZ)~p$n8NjGID1k%Vv@?rno5>!?|I} zlsvi;MPQ|krJ-J6K`?dI{SW)axz)wW+S=UWGMwq<@n@FOqhpojsf8tSd9y3a>oDG4 zR&N=vL#m9X^r|^=P(`E{cg*%M$f{;pk0nR%$7Rlmsitd0g~f<8L!IORvkTY2Oi}oG ze6HJIW79^mYwae?VX}YnKt;|e4PC>@!HE)ytYm0y{7J8k0s1P-sswXdO+`ytUR6m; zM;_HoXJb*GxXoropi!$h9W11k*;vgKpPQ0r?&!s~gAmt;m};fY*mIhWC(M2s-k zHnFkga)ra!i!GRKv3D~^-NGF}Zb~R~dd&tJ7wiDsa1XrK3r4$*{hAyXbV*Av=D`)B z7){^&3;5b{2;`N?YxB_dTWhNkX6mWl4IEvH_V9X=g=Y?XVMCgW+0(`PCH*j&KZ$B6h3h zGP}cv0@k{z@1##7W9~z3M|Uah=Rw)hu@epVwPax_ZL|_DmV|I*#2aYH?Km|= zQ7o~2DavR!g%Nzpq=9DTL_L4XK4R6#WJX*9=WV(cjLA_k%s54tv_HlM5eRudQG=l3 zPsx}p_^!&{?w2i#%4l@_EHu0>gGpZbe1aHxn^uW}T4&BTfG`T3-I!T*N|&cVGi5v!PT!%B zRWT_ggGiX0o+p8rv&4LGZ0M%SN7E2tcL6pK4$&c#g~9}Juj=MHm#kQze1sHoB(&c5 z+$%75b%b7oIOBjbO^KhCIiwhPGZ>n}9=6g6f^-W{mzSJJBfGy9OTM0Wz_i2WR->i& zGb-a(r&jJH9(#zed8eM`?+WnWicKRwez|HRbGl)=CdtllL@sMDwuaFP)6}(v(k><| z2dqZeIr9q^^9km+5-V(jWXn~}9Zu&LD&NE=xIIrVVrg(I@xpw_o|5-sxwUZ9Bp$Ix zxOE6*(B9G?#0ilPqa^IATsc;ZU0;7gcA9U+BEfQLcOsc;#9;ZVh~3jf?{{f{xH-msJ(>p}Jyf8O8U1{dKR4{9O02Ip zEI&i~)4(4y{$=0vIDx;GA3BU^^2WO6yWSY&nri@ucK!jytGB{Nw7#8?RI!%sVtma( zmVVM)OgFkMSXzitT{+fhh0Kr+HR<7%k^v1G~g4COk1xYDxQrCrp1|2~` z-OCATT!VodlQOSZLyf;lWqfWFv#B&dPA{vLBqDzz2-E#6Zp4d_UZlb!bx$)$%|6-J zSx0VifU`X?Ljc=oS5hE^@nDbX4F86XVMrHlpN@wnCyO*o)$Ipe?zcaVux%j_DK&H( zmC$v`O(Zozr2XL^Sm3#O9zi^Kq6&VOw&33d?2o>CpBr(g1DBTv9PajY2u+$vQkOZV z$6GFbcn?=WEG%>gWoDMKFY@H!>EX^FB|gWBRay25e2CXp$7aOA9y`-y!1^`!--Pn}>YvOOtI6`DNmhcF&)2^th9_2qL%>Eg3k z;@Hd_?q3XL-0j4e3D%q2>%tY{-b;(`LFCb z|1KZ>GramAyT0Pz9-F;OwT;af`r46wMUoXDtCzFFS1ZR?l#{0k`6090SC6$qbWXjz zeq$cql}*F#5&|>Gg76VH$gpbGKEzm`lESc=!e;+Tg^zpvxw+u-A+i{R?MnwoxFrVU zOXSXfK*_|g%`{cmpU5i)?3leU@4g>R}Y+BwbaFfp{7FstJc#_{Y| zYZ)u6#AUpErC#YQEis{Q&rn1=3ygb}mfc%7a>2Pb;I1MUuGkF?yPh(NuU?TvW$lZ~ z7+GwCL5wN`xg|i`XAaO65>`90(p?fffM%*z_zT(7giHnP%BvsE^O%tOic5ryc$8l(lFLA_K*}e$sx}1 zl)tYo6)w38*ibsoAz%4(v5xQnDsWT)CNV?%i+#sHC*F-th`6u>24$Ep_D6IfFXa?0 z$~Em`KbV!=x79OO-@zJw1Q#)qt8l3tfwkXc)KVJxbpEJ3sf8e%u*_Q+Dw@cB|VTK@+ zp{BhE>4s-$_1~HUz81r1KfOTwbs)>76pfKTmq)-qecvYZzd4Zqrc(XSyJLa!v%UPM z>8rAlWWEWH~_CeP^numPJzujOryo{fg-<--HR(E{jUS+F5~$HZid-?L#2CSWby28SB* zEAG3-3xcoqMBj}zP|5cPq1>yuGl`14y2VbHjU86wZy{!P zB~tDzUWC=x3X(zv2aKo1 z3?4ZWk{3D3nLRP*P2hK{2Xwv5y%!E$I8@?Rdu&B}sYu6TGNc{V+0jD`#o|(Rd7?xj zSzYuGb17T6$z(N7DcNYyq#kP;jx*EzKnr<`&&-gp6()|7*ne=|AZ#@eg6|0Qv&1qq zVu&Z;=pv??naT8?0YNc+ZSW z18&ZD#01TlR7uiNoq9%3B5S%9b7m@FDj8GGqTtEBr>8B2*{V_ygoiNw(eNU{LDC5p zM2LPV=iGLRcq)vxK*0YYcbaRa*Jm9uW86!SJg>J9ax}1&rOIXgW@Ov8jY$W%$f23p z+{EGPwqP$e7MDoqZdM$XK6KBoT@8+z!O9xTL!@@tYf7SR^2$fK~ zti>Teiso7rngp~CxRUe;(-fH3OiW2e#pW@{$13@=Dp3hqk_g4Dx@NAb&&HLOQS{D% z*B;W8U)jXJ6i$VAr!Nd7rtzcENldBFJ-Vxq7?jM6NFowlgRU&jSYqbb;pA*w?<{Z}vQHI^vG*Izr& z{AhbojN=d%>XdpG^Kh;@)P#Ww%1RlloK_Omxuo5pWunj#XR9wBmq#Wv;^oG8mY12S zDnxArIL-~6%*@!B%?$4IL^{V*m1kgRXcdKGRxYu|GK6SY&EkGi0{FK}`)eC6EQdbz zTav~VoaXkbgloS!Z{5XIS`6ci^gA9*A@y z;2;Qw5x|@7EWplE7z;H=;&0NA1cx@`~f>1s&wrSf8 zGKStby*BR*Giipd#M`Qu?GVTt{lK(hBmZuc>AWRv;{@Ul&_BopG%j_ z1yV<16>mQg|85uDwblof%0VkS?q}niz;1}4GUK4e9U*4$3v-E|si~EB35S=N`@zYZ zgmXCXDk?`^sTOHk4eU!}M)&NRk-J!$lx0Z0xq?HNbbT(y>dnRog9X&i$%r4Fo$e<9-cfDylT zZ+#4M%?T*W38+yF+&L^7`GGVlXR-v;I$74bE*L*17$TaCsHMRlVG<{`<@5WPI&hI+ zY*TrtcVl#L&(pPLtOJZyI5^`XTiXSGw+C}xjJ}H>S+TKfCZ7G&2n3~ZvAYgZq9J#! z*kZ93nwwv}K`Dx=wzf^nII?ZR;rpwTV1eI3qEnptPsC{{4}>AKfHlRGNYzOFSbV-% z?=?42<$IKgph)=u1RQT&uwF!P4uAi3vdNIrv@e!kN2p!=#>}Fb#j==1teesRamgDJ zpjHIV6NaOk8#6mSs*NYy-zCz$4(NVoD(B?^jKw~QejZ5U2TgK}k7*tsA1W~QuX@Hb z!|?b`lRnU+8bCYo1@i-l8$MR=L&V$RTg?@f- zj>k#0a(yeU!*-h-U0!z*say>>Z)UO28q}~@R$T%QD-G93sJj|Lr1!;q0CuIH77wF` zy5?uw04a2E2kii^#kB@fC$m!;JqUb1J&1U;Qpj%HSLL3J5NBnqFWDyTt$%QVN^ax@NE zqS!7jK4AMCUBL?bhQO-cQx~Jq(J5Kvw36IM_+1HCyFZ+_Y#qQ zE%elBb28XTbON8XM1u&<+DL}Eje^!&a)-^Izqb&qH-{K`-@ab1vLUWj zGs0lis^|t+5Oh}ExExCK9OF2ycU`jWcZ)_flUUFR3ns+15Ke9(LZ=rN`)aYUC z>)*uAbiw9Hj5tc}&W}7*F;KxMCkg2+&cT&s-rui@EZYlw6iC5vXD@s2cDLQH8*v-qUdce0znnVK5Y`N`G} znLzS4hufCGtQXC3i9$}~Cp%0;7X{O*cB>SAPh=B3%J#oP5#TO4Q)S=B`Dz0NN2wD@ z*^w4iwwK36GGYayqCSP2FF71iLXw zJ2`Fwdf_Nr^Ddx+&Pja1F>x10otJ6OMjNh9PF`=%?+D$LrG2RV`S;r_HzcR))wT>{ z^2}Dt%~U#E)4o#3AP}?jj$iYzttfnNp|FaLR+ieQO zgC(W@=^J{|8Llt5FG~=vR=Jj-rQV{obR58Y=43FFY47Y1dz8J;on(q>jy5-2T$U-T zAZz$gD!}3*wg?4|CJ*v846GZG~Jt~)Tj6` z_IJNDRK7V){5A=rFW0Uh%CXkCjYt=;jW1*?yLDW0W;Q9`76Sdf35~c+G{2*NQ#(gK zx6SO>q&gT}1KDM16K*LPS%uZH0+8Q@bGo!H`kh9Y&90<;Sj0&|XdsVu*>wsgq+0_A zwizaEk-{Cqf>S{&lA&C~Xag~s;V0~-3LtyfWPb-T-H;Mns+&zi=RNr?d}9akho!H$ zK58H6iWj z!Xb0She^u}!QD8^{7(YwdQRmy4?@0}RV?A0sjB5ze5wtYqv^DrcByN3Dyvx1u2sL#W_FSN!|sy6Nh?U)bQVhTGMs0)RB z2d1HjzJftC8d}6{<@c-&FV^C#E{fFJ^0~&Nlgf~SuKe%=oLtAQ?|8?XKWx zP@c$3Oiwuu(eNKQzl!1Xs68V=JF`?}jh-l1N|%~}DD~>%VYG48_4%5thaF}fblWx@=PfBg?z~~mP>+SMHc-8rSrVJo zI;Gflb1Pz^D+_5u`M?an^KE{ACu%gN!}0!bB*~?^IwxkF3?@hh_1xJKKD-1;AsCgC zJ&B&wP@EC<7Ep7ueknu9)s;ucdM)=+cm?Rf+J&pvGdKzsE9?;&IW7~D@o_JPB)MC| z9HnH@eb6$Y@pLwGr1G^5R|@Gkzh9JT4R#%9aq?zo&n8)wboTLu@ZZzbTc%zlt@0#S zZ5Ju?o7HtR?gY^)+cWZ#!_jDfHG9#argB(=?t!cG4hb`%U58V>L;;WRuSkU|dUtk- zd!=EY!L|G4Ad*-}@e{_%e%V9^_T#E4_Al#WUzcskSPZW`IL+`3Cl9S%PCS?X&8F{rB@26)yzx06Tr`)EWspZ!wg)y3e`kdBoMAgNew(PgXK z5bNoL_9;49g>MCZ&T>x2Ro@EWS}S96&W7NPjgu2=8@%d2cu?y?W4(6!)^FTE!EB!DeEkDjog?@##H;9Ihs_)B+mYpf>wXSc%MoRdMUQHJyY zHKTGJ%wO?Jd_m&=6iln z>1C+pWvwD*(+2@t@y>yifra8t!?tsl_BeLbWeaOFoT#X{Zpz3ph1Aj)C9E@?270HBz}`+n$}XLLGCSdLsW3 zCrx?c*2plP{B?VimjQg4kDQpj0yqjt^>M6C@2|XaigC0uLU%$F-SI@#UQSDZ1`ox84jkF1PAwrExQ7zxTHo@p3pHE=hx(3 z9eM|IxBnU9EUgmJbbOhG7U_I+sD1RPjRx$(19t7QzkWw}B8lAE6xrq(mg~aZS#yX- zX4e1NsLMfML-gUSL!zB|-;AvsXP*a;>}0D*q_geu4Y_(%^cPu$BL_IxRY_|QhsNHs zpiFqu>EYbcaI@#?Tdi}ko_64NC2czru&S5z)WMMfM5u*92|WQxNHI`0FA0OUqKH~$ zal|EaPhycG0yv?wUR&EIqfWDUpFdr!d;%q!Cu%*1aR+1+HDu>SGi^mKv&d7mo=KZ= z%d@Pv5vDZ_xFhdi(^WWTaue?@HeKX*Bh6SUY9p%>BLOsB6o}YrtqWHI)1_&4OLs;S zPm;kt#XLr&u^G|4$UK_$i>v$dR`rpNy~QI(w+_wgr#RBZ(|e{yv4@HbV^s)q4uA7` z%h0bf8!U?HtRb~YGF-OkOjSblYI7%&4<=Mf7{42)B9JRc5CJ8@4h}!~rM{@$D|Mt0 zceqi|ESEN=v+iF}iQ~CFod%a7L%D@*q)S9`2Ni2oNfmp6M}VBGEmD}UM>tjqX+%aD zPjRA8W0GJ!@FjGJ{^Bjo7Nz2Z50F+Oz;!G}#G0S+`Jw8MY${MzE~t_U8{>EsbH5~( zeije4M1dDBg8DNbi$&}wGLc`~9=#Wo@O8CCFZl5wLoMiL^w{mGy5nfjz=ndI7jTX9#E2IRf-j+z~wfbD3HOooQAxPN@Zs8z1u2p_yp1fHEaTA3(-!d(xR z%GOZY3ErL{l558RRCh0wN-D03BcdVz?FqeRO(@`buS~!SV;U{GN+&!$iOm&#S4zGj zF;2i5V>CHSxH?ONtctmpqz^S;Np#<w^iPJH^lag3=)w(dN22NyD2No2K;fp;I zoqMK`g;_=B*jl_pW>?$Q-p$oRMTGETQ_uQvi;TX%r0wYz-6NS7S+kYK{-@dyaYYUBc^s-2MHNTC>1 z&gRTUkcKkDo~5-y^}m4VaF*Cc7o z0z5b;5Mds|;BK?vz%dk~WD?0aACg+ef^LdF;QwDp`w4 zGBzpR+M9A^oWnmt9_>kfD_@kSq7$>YPxpY_kOvy*M@w6Gg0GQml|otYD#pLISbJD(qK zg228A0W!N-bohuy60H{OlV_1e5|$&&PRbGCjvNJ{jdXb0?KsEgA9l|#wkx$`VY!zY zfZZaR81Nrw+}d~98i_Ue`hV#y7jHh1M zb*Ik){`q?mI0ooa@l)EhmM_%9+FN4(|^ci{8=wBX#&(=yE z3lq<+e#zQ6WICp*W-7#WOua^u2%i)dZo@w3268kkj^~IsDBj*Uw0_cD{60N zaI5c2P2^XhP3K&$K#=~)o*MAH^aK2%nQ=N_WW4WSFSVN(vaht%lqT3UmfoRyHWqTQ zr9n5horOF=P3@SW3qF1AVzIz1D~sNlgwM?1WcQM*?>n#Unf{yUA{S3eQ6_a7iqE4+ z3y$n;vQ?XBM5?r$7#hFS7+Z*1gT2wUVpAT4mxs_xYE*#2shya?^?@oGSlFV*jv-f@ zNtVwn{(3))AZ~E4*O98E9$L+!+-dCK?QYGKx0G?Ls<2fDgR4c;jMfzrx!OoVPFJQ! z7O+7b$m5YLrFg^+^IXX+?Oz~~Fqr+jbwHw%LjO^@Y zQM^)oJlC_zAn~20iH&n~o*2{BzZdXSP2!BzH#S!(+O2coF=Rn=?uxf!h?v(3@es$q z1;Jv)IU58FN?i=@u)}4XcakZ4mjTfeND#CD8Dkl>U9`szT6Z7`;UAla^-S$gadR5P z8XCk|+-u2XwtMm%7H)|1jP7s0%jvby>v)?M)OL$;KR9)3;~l&MZT94JvQA&jCSdg1 zJRRb5i3KB~w*R@^%j>n$OL(*G0NCD>!Bd^1citB4y^dN}pYItN))P%zxCsgp+!uu> z#BPtJ1)+Q_vg5heaKvnPcXeZqxKly1lGi81J}dKf)$}^5iV1>NxYs|b1F2X%KDH zRZUAI_k38zHV?#PtJgwl=9H2a$j4N(0Bv!qg`QX^3;4u-n!*XBfFrStpBgA+{f!An z>Cm$Y16aK$-18WA!_s_k)w?o6J5mRe-kp;=Zsz^g|lF+D{ zF2l0s8LI7A9!K4rHh9D8+g57m{z`K4NDislWg=lm`Cw-fSvygg*&hC1cmN~L(}nVT zoM#k*jbg>3={ZSVFg!(<^lVufgctoVh8ybUDl3>hLneU=)Zs-D#YFJHF`Tsuc~W3; z!6`hYY)kr+2cSO~K{XLtg_Vr#yXPx==kA-VToe2#ZBpX0<`gXSZLN7)eFZgzJ(q%!T? zkJQ&xp({?sPAfD?FCt_WHM`Tk#55P3cVVkI*9>H&Rqd39v&&A7#L|-8jE0eQdsce| z>YI6neU?&E(K8NI6(O~tT@kuB0@s6(?Gc==i~_|j0wz%UrM7x~s?V&y-!Xk-(Mu-1 zug`|?+l5x5S&ev^W0BD*CfvapS)n9TgVR$hMJvhG@hMi&57(l<-`dAEpp*Z~I>afN zi>4c47Vb(|^ML_($*#Jq>o-0@yLP^~X$2dlsW#y@^wW zzs4|s5U4%}I>z=DU7{#O({E_C1^jkCiuE;M(iVuE{rtPi%B##nLwxZ}L{a`-xA-5; zp_Lr%yd50vt&Q#e5A{~p6IC7UkAlNO>4M67aI^T43cGz!q)}Ka(JX9fv$dTpGun6Q zZ&Ial7UPq}m|gjiU%&G9w4U2T+VW!92^C)#`n(VRWj~5^3^`f5x9|KX+1w`^J^?;? z-K+s0_ZMF_Li=fi@>mQJkfb8nDNN@*jrH}rWn7b?jtY>`bVr@*AXP?>|* zioOt!Rq4R$mSkxQ#IW$v3_4P;EQDxwrV6%k_#@8%@eunrWjj7Iya~k+6UJ$tQfZ3O zx<-ppdV%$3l#(QLtCe1Z-Gzz{^AGe(%;ddGGDroBA8}gNU3vR9B-Z!0eHlYzbV>#avWsahGyK+0a{#Jm4pryKGvPtXxWhy25kL-E8;yAfWH_LA;(0iS=V~?(84((uwIw2B5-v#bMh8iI?2HglR0o4_?M~t}g zQX%+Ah~`zhcrcAX1~5CKnza|9I2AECS83O^J1(0%6i$=MMw*A}pR%)`ROAI3^^W$h zE7Z@-%x0(BQSqO1J@M5oG{(Fib&iFK;G8&O+-1sfRyNbguQ>dEPEiEl;Y3q~Y_1Eg zq7!&pvKRdAI<4CwZw&N5ZVFu|Meop)AeG`n%0+nnB7im;M{ZCafv2U)ji;rkT;{Gn zytvDbiE=!*rv^~%Z?Xf3mb^}OJ5`kqTn!@dthgZ;j#nq7UV`u@or9g{nlyTwEr|HV zv?myyFoSSh@;NNqFsrM{WkXYAyGA!W*dTSNg`lUFw7{+>QQF5r^vHQeB`N`@gT&t? zoi6F7#!t7dmfxr>xtf0mp_LkTj%*#5kPB8kF1=kB1@HNQ4N6&fMUHz|KT$Y#rwA`8 zbyM=LGr3Jo`0G9U5G>8*)i<~!uwMxn@8y+eNZPw0xc{6nMdjyQ@nZFoQA+H?Xdn%F z-NI&@EMnIAl{v5sms|T}eiMr{V^L2Za^;!LhRo2KNZQLq=A^a@;qWx=UEcqfeISwOscJc|1yl2P)Pd2c9bk8g(cn@{pu`0U8#Jnl~~w zN6_>@pVAfMU`0;Xz%w3U51g__|DoGv&zt2Zz(Ee`?r#e_knFCLr?2c~bHslwF#lZ* z$Mc`Sxc`Hs_#bdi{l7HzX=w)B3c_mJzT#D_;@sZIhB8dW5TeyWp+<1G1FiZSq$`~r zZIZ!)1B0JIhD86=)wcu{2aEi2>1<+ko#Er;ZF;(2X(I%pNMto8F)xJld~j;ReENPZ z4xx>D(C)Y!1Pw|JiV9%|iij<-T-Bd0!cBhd;KYg6XL6dFa^M5EoOJT#yz7k=8A!~0 z;uR0Dj4WZrg}d!C#DMbyA3>ckuAw^QVeBZzrg}!saC_*eh^?v=#cBdK)UY!+DXFZN z^{+Yh3DQ5P|Z&&swV#{WO^H_o6O@k}766Gk>gecO%TU~W@O0_zdy=>nZ zT_)JjQSlA#c@9z+y+Gr9yn;I~)XXb$Iveg3hM;`cbhHHOGT5M+9fO`|-vQ;O@`0M2 zJ$<(K}opU>EIN_C$37+29yJIF7QE$B?kc!OmS^t;>}l0K4L})epbP#$;^_!wNy5 zoiStzsz}E-#2Q}mdDKkLcV0ej%g|Ek>y>Azupk2Wp`5F)@R+)fQIcu=!X{N=su1f7 zd7eOg#%T^gsuH0Vp0|L%x)RSORXG+_d8iJ#ciQQ`aYkd2!Bv~C&*S`~c?W78XkF5< z&F*oho4RV;@O#p)*@o=WWHJGXPZ-qK=#aCd(uO>Z1vXYdXVaUJq4a4#IF39Z2-{_Q z5J*~M02U{N9r<(8bg?ZB=Q7#)94_T zB0DXdN$xRGgQ^Cb{7gpdj0U*?!OkU@B<@k#KjPMbaBK_XN+PzOczjGE)=Q7m5!Nv_ zS2xiO_r!{Ts3M)kY%ZsO@Z7ENg!3<|uay5AVe8kB!};G*eHH$b)A27&*Z=HB^DpFk zRWwPoKY(sHI?{A>cCBswsq0`kDU%d(+E8=Q4p=ZG zwtC)+nl@FlhUNI~I6>Owo1PhU30;!k>h*%9V!#Q@4)@31FUy}mSbbLrc)dy>`t>}s zF?(QV3?3$Ed1puW3VQvR-+tKb$^^p=qnrxWq8>cY3vKtRgQCJYt0xNE4EB2PAFnnrl{b(7V`2L7eWs9%Q;#c>?6kC-s%HqY#CuCWKT2QGPaM|ha^Fr?p_~nHn-8_O8 zj#vDC<9Pz&3MtDPX){QIAalZ^E8rZG=g?)YH6X@W#VYJ^XuKij^@LyZ*@3xdlw%vZ zlbmj>3U4-##H*rWxkRsM%;6^z+)0khL)gQGA7of?f<#p%9^r;_%owyo0u}c^GUZnrxbID&=AGJy{wM8wj^4Dt<{HvViohtDE5E3IAl&g5o!B4Q<(jw(Tw%kq`$BihY!kg&>DAp>>Kyvm)4Zt@?*W6ggp=6(@M|)4$ zd-)KdjnnTe%dvfgmgJ`R_jDrrwKPE_g=c&LC6%lo_tbZ8KnqET5Kq;y$Wm35xDJ$} z_Oz@dL;|)z={oDx;#m}ls9oO&5f+5YJaS!SYSIl%m)XL!(KP&mBt^4>-LTqsxS5SR zR_{Z1rJI2omaGf;3SV8E`>_7agGpzR;Yz4Gw5o1HSVdJ-$(Z(wpz4hHi`5kD>r8fI z@LJ1OA}C%LthZoY2WgjnM)zpPLMe%pG;&|T%$!n~w?%^-yyQ<)JU;6!Nsdv{j~d@|6l!Q^bZN{=szV z8cWFaWx<-&V8@B)`WUA_vQ%B55ld)*eS6o&z&8jqZXMGLAkzU38x&8?jgB1=SFo!C9A1nZ%J zceDiZMW;zQ3i$y9${)$A*vAkniW>lY0!3_QN!GXbq!kj*)u{uX@l8vXDa`_JVYCevq&8)D;DX_?N-xV!tjn`VaWwc*tQssxJkdH{*kcpa{ zwSvj$UK*>BP58j9NDo?^hDo_91J-~J@Mab?CMGbY;!}7>On4e}2PdW69sEtl#(GR(WsMZ|qT2?r|%|ET>S6Y0>bTB>xjgch8k0i^B+cUow%3SaW zM=w-t8}|5wqGcnR+xv1-#BVh3PW-{2s|El`%Ne=!2;1Mw;qJa?HkzPmBB%WJrs~mu zE+C2}2A^83G{S9Vy`(v|N2XGg1v!wE zOh@w#l!f!FnxF+IW`lkcG~?2X{RJ>yIFACE{$KFuIieJLE%@iOY2*+3)7=~Ltjh76>SUCGvE%r!-}U} zBcTBmc4rn@DI>=Tzi$Ko8{-LmfgArSA-9+_7Rn&`S4&Zvg{`Gp`u!rIY_nZS(d&0n zZ5`mMKR;!D)AwBoxUV}0DIituDfp_rlU(Dp?5hCGR>zQ_(Py7AO>Xu1UAXZJz%rK$ zC0hKc&y@*Si*OiW_z!-OJP5+>ZG&FwX8uu^@mGVZ__D{s*A{x(_*r-!HuZpL3j1Mw zYZ77w$ySL%Kj){SS!@YJFn7>wC4J8$TA<3n+d<3mXhbGGA78g0(?(emvudZ4QAW{8|(N+;Eko$BC| zHbc7CVD;VlL}zTA3%KFW2xI{MVVpj5O{e?iwu<)0&t3dWR?b((s}aj|R=OC?dVwea zOH%?acVxX6K0WToWL33VC!m=Hg1!c_DH*F@7WeuoD#z#k>940N`}fz63rTVTP#}H1 z`YFtMqEfMF;XYK3iLEvFkR@z15FtI2R#Us;f}PAyGjuehf~NNOaFseB{rx|QVn*QA zCJT8)F4(QBZ4)h&aWnf!)&H<9$J7@iqcP#OmNYnHxF_a2LL`*lYB7BuJ`k~!F?GdJ z+;piR&fWqJGebdvOX(~AOhH9sjlpZ8c0n-b7MIQ_Ugn8A;F9IV-0Y1NEoE)tlA24Y zPb_zf)Ivrw&Olt2@9@hACf}oU>(HYbNC<6Bb<^DEiJu*nT(2$6^7sf9l>7D#YKR2n zVZJt0pkH}26sq}acF`X7Em1@uvcTKG+oh|rERgLzxTP)q#)c9f+oO(PK=ol$NJ1_7 zl`<;-_n{ssKkZqLH}H7CU-&E$Dux{Q%m3;2f16(XcOLA26nF98$Q1uwiuq4uR`L&7 zbm^A)S%(!c^EQ%rib&!Sg+VlWv5=IKG*ci7Vd>Q@gY}mMTAHEhJGkF%pDdelq4J{D zU!Ql{zqHXL28HIFtggqKGi{a@c>&!%ghGPDB$4^D5%CWAIQu-`oa9uxU0B#3&WdO2 zjD-gB!->Or1RcHc{cysu3!65N#P?u5E6Mm2+u??r?O{E;daW;*v$LExv&S^ODHtbX zRq1$IEir!N5wfMz@3dWJa}UYpS~~kAJ@#L%Ua|-iOVVxJCBvaM)O20|ER}|Hs*P5e zP1p8CDl#yx$#WTy%B+XSZu3`I*pldUOVyWmN?93_twleD&*LS)45EX{)A3yR- z?9QNgV^7R+r`u3mv{_-FLejai{l4rx zb*`L};!>{fc67#j?2$jpaS7=d)Q~{eSE;Jk&)W>O92n8C{Qn)t4R#x_PO?JfW z!cV-+nKc-WHvqCATseHMMxxj&_uw_vrrj|S6hg37&DC_-ZVV|Nyo`tPeaI;J6*@LW z6=u2tN4CUlLz>@a1&SU$0`54VFet>0_S}us4m3u>+;i3*r*tloVxI$*Jrt=sa2x+8 z^s*mr0d6y_G3AtdG3cf!?39Gi#cJ5rcTc$AqC=n?;9+b*N6!!>{J2U3=7oz&+Ve8p z{;+!lIG*`rx^>e27r$u?$$MnpjZ4I#$>_&DmGPs_i>2(9X-U|T!X^Y8J4Jo~Au1)f zk6#eC9w0A0Wtb^S-JxB1g%^3nV;Riu?2~`Hg@NuGrrO@c+ctsu#T56HF#<`qM_Rj& zI{zF?_vNQSNvp0-o3 zAcZJOF(gV#2UZJ*AnAMKlbd5XyoIeC(pePtR=K5f_(FeiTrrFWNr340~v^I6=9hRC{a*d0BlG z1AP5#*tb=jB=V~@*_To*tdHZf)23`nh3Z*zmM0&J$Bi|BKysUnOTok-$5Kj5!Mn8i z6IH-{vmTlq>@lELJn&Tzs~WOPC{3>*YGkq3= z$heR6hw}lOWq=O6lS~3zv6DvL4meh1Ro3&}NDN#y6>8F)xG#y<;ofS!gZ4Kbn#l%K6GvR%_eO zO=R6be{5Svk^O0^WeGABbCiYLted)S{nE|oZ^{gQ{1n%HY8D=sDlAlK#HO3PClTPr z?vL9Cu8gACSV~Q=y9kh1%j+SYRTBuwo?`L{Bbmnorlb`g@GDUg45U%5a>H!#^*~Ja z9NYfHSEKo9iC9D5Tr_5!@&F1}8@2bB@?@IDKjb~_YXXy05(arAirI7C8!(`?0p%@L zT8fBQ$C^R%u)U%-OWHMDvy-ujYV`I2S>h$S*9O*>mXe`NnCA3L&2|Uqey37DOPI@s zl&@uNCr_tB4#wFwk&hHXM^h7xX?GRkWKjW2+Be~RmK9gw(sjca$4ek2XDdw!Hp>~M z%;7!j@$vDaz!v+)?3t#37syz>Z&K_D9FzGarXLd1cxEl>M;vS;(Df464MaH3X;jms z>Yc7*W?7k|CC$z1K=OSX!r22)TD_O_S!OgN-yjegz@(ObQ9b)3o!o+2taqh-w=}Ty zNHBgVTQqYSW)Xzjmwawm6b=;B=W`LcCg^mRg}lq33h};n-Lsqi=ITkfOcrd^s%sHc`*2 zZId~1$L-Z6y9Jy%<5rPEp*{^B+x0R^8zWTg@#tr9-5KL2Y!MW{VdTLT@&SUlwXC8$ z;K6Qtb^N_4NkU}1?Gkl3*-wT+pvcA@i~G$+M>?o>&CX<=t&V7OJkg`B6PK+a8xa+e zkl3NeO{+{Qbwb7b3EsnSkP|Wnbw~Mv>lMsE*PtpZIPwp|QTkr=PsFx2&KtQtANFt1 z0=Yyd$USi6*RiF_hX)BeADS11s!*4;Rb{@nEni_5E z6Ap7et;PxU`U4{vH;@b;k~j~PbbWc&uZH!&0phfO!U^8--)<23;sZ>eKKsAP@WxxG ztXchRVq+`FoNg|}pkEb>_*S1$G^J+>`;(DkBynBmyAA0tWfy%b$~w@ERT->xXi!5_ zs5k$b!7X=8<#o)bdfJN^pEdgPtY%8-1;5r^%2sJ%OOBjB*K6?{B3-!LN=ag9ocAWZln0k!fE+n!2lK!OKpKV0t zcn736cow%}6tBambUrWLcEt$hn#P|LCO@Yq1?Wk*NZU47-in5Ltn0Ur;X-?pM#0dr zLu9?X&(Ua(3Wimdnj{fK&_Sn$Mx)A)gQc;(70uD+5_2=3r_rwwhb8CywB}>tiJM8l zk@v?vghEE}j&dATbo&v3)y^T1gP(#MMK2b6)`~%12%Nf)Oow@)%*bIBvKl#Mg1Rn- zx-Jg;7_AW-P0wL9!sW=_^1!t6QC@c6T^tQv7|fVN)38vKkkX%@UPS0aCHVx)L^xtl zO5jRh>IL^^tq9E$=^CEJ5x)yW&1i0OuOm@$l-~`IC765({TAMryjSJi_KibRvMzh% zq;LsE2XZ(0WVgn_Z_M`KBOT>ZxsFH<@p#c@R0ajKVvr?)Ki9ammW*68u(__qN z1+BVvO!ulkx@(ESo6)IJc~qaVTTUZS;?|rlM$wqN%|YEgGRsT6iSg2vlY`bcudLw* zRrPGo_me~GXL9TwB!-SYsz&T2{JYg)=qz(rl%m$+0S*X8w603gKn|;$NMo=eDAaeP z${{L^XtL!~O3cw3*M)D&n!YRHT>h`*Gw66Ex#edc&6cDlOZZei-DbJ?E4&ySre)NlD0;Q5vsM zs%r7jYWf5q8yD2ozOaZc20zkMnXVBqe~-NU2w)LZJFG7cP?^^MmDT<@ZLT&VnrpqN zwkzDJKjZ#= z)U?fwR9(aX8LR?Ajygh#&k)FK0OZ*PbnOMadCS+%x_6+@n0H8eNZoi>9i7b=(p&lc zX^}gn;h@}1{cv$Zi4XNlwN2Kp&o^`!``TJpJc+`UC+zPd3rL{H_;Cq82~ z@W7uXSdygLRm?3 z2}(Ikv(>r`X$(|}Mt%wV>XZZ0Ifr!F*sd9b1%-VdINBzXrw}qaAA{GS7Xno=5H*Hx*9t< zN5%~3Wq{Bjv)8|njH!?O$k?5bW{8L4qAA391Miwt+NR8M5othgVy)0hGhvY;*4Lcm zkS{G60tzpTFUW1}Q*ulQ)WjZ)jjoWu_VB>Apray8Dsm>rVn=}%Z3~88i+4mA@2JLa z_@V=)Ef%%foc1YjTWeQVuS^kN68Titu2)ubBQUi~tYe3U@?kgr;G`SewcSf-o|iW& z=2sJ(+_h$vKo2+9udIC_Lq#6KOCiO%Qgg#r*2YbfPpxCkBH*n>xmzCc!&kM}T{3MV zXeFO=E(zg4Pv(0Nmltn^w$jb-QHpJZUW!LtZM1&E{-OY}snUTLp`VS1f)3YbgL;-N zkl(YZ7H@zS1Q&=0Ur$>Y#!`FaSu0_n!jT5mhTOH|$*osn*s-$7JCApeBB}yNbX(oI zsI#KcFZW}D9!NkHJhmi4`F1=!tNo&JVm8LD979ieYGZj`$biyyMwHlRhTJ6J2vW?r z5H0Ujb9j+lL{!}>InC2RC~*|HTBSlN;I_dM6-;jshtUVr?3RoH63thmOxXp$uK)as z)@r4eyz;iL(?v_f90ZI2&Np8C4wcdl{J2GJsM&IA%-X$#;?5d#*r5N|U9U3&e{R>8 zmXlYS144Lvc|*92$fl@{QYp>N5u!P7xyWqhMNv5NrA3euSnQ||o1IeRK}NjbN5JsX zZ+N!9JAqJwf6>M0yXg1u@rtHZwbIDCVpLJK2dKkyeI{t3e|v?#1ptf{i5phv@$m32 z{h$eVMZ@*O(mgy?mL#~>C7-qWDfN7#Sy4o|24GQ1?SWK zqTMW)mve^56`2CjJ8=`06I;wVE7kCt?rk5O99B}(FP>2le}U*mW!9_(Gx(Y@i_;w zc^yW@6&(j2V>5Li!KpICDJN;VRB!abKeg8Oy#|*QzS|AQ$BIx=x1Z{aq2s6`ITV!d z@oZv?ukZ~m#0xH+jaYtEh{YTr4xn011zwK_rnxAIxYkSqdpZ#4ozdx0=N9LeOB+-6 zwR7Rg&Q?bL>74gM9WpCB_AH3-pCWkDV6=}yOPKl98HEyl4|T&E^%Vq?6$Ve+e z=>L<_udVvCI9)&Y#S-Ue&#=DB83uhy;Cjyx>E(!Jyi^&x^rI3@gAI0}96@of2gVVG z)>}vA#x+A7S4E3I4p6_t8uq5@)%#0!Pnco3xSk`-T@&Bt#)wmx#2Xoep#W@WR`R4R zrRi5B&Wc+*tb%g&N+#Ws*2^SRndwfwn>T$7#^u~ z3Zy;$Bd3DU>dRrYtJ=RJNnM(tz$zK`Gas2qifaImQp#`~)YmG9tVy?2Zdh z7YZ4dG>@nTf&<*GRy@Kig;iUeThUp&#Ddq2&fss#DnUz|5Wi+%~P&9Mu({LwK z6%jI`(grGIdy{sYw1(KV9BT_tT;|)H2M82-Um(J9FAHrLVqx+QOx7mL>6e_k%$M8y z3s0bXuhag%;t(GOm<$)?em`D5C#I`jQ!08H@?`RG__`ALkrRD_OBlgfXKj8>ZDe+{8D^eoUSmUpwtOKtB@}b6o z?<`yfuD0$Lwy7G(pEu1Tq7chwSeL~lrR}gDRfk7BNAhdReA4jb#|};dq={JAOlklb z=q8jqE)28ZXESTH#if)8sQP@mS+oS#LoAP-ANzxpu&I?qi8}K5BlB8?o15}EfWVtp zP|`Bkw^ROK&MG?S`lKK<(+C5rRcgxiV!FdgU;RjmLc6#sM-jd4ZbWv!K&!Qy6R3f<^-7bs871Ib)z;(y~lV|Q7E8ok?^BJ4>qYd9ZAYg9dz-*_y=-yk*=8)3< ziu36ak4SF5YPZ)P)Tq^%t>d9h?3YB)v5Ma#&?RgQOuJN3mUJ026e7A#9Dz+iw2lO| zF;seFUpe;xcU2h4T#%06J1&ePA`??v!v2Xsli0W3gIG@I^0kvCCveTC4;%>=$24Dh zO2*{Y--b0OyK8=Mxe#?ZP|fR*nyh&GW_mLZBhIW@j(Z-h0hDcd`7aV_T>2iHLs;WK z|K?LGbK$3Ie(fwRz9?`1^JbsxKiTZ7TH8C>ng7e6>Yv?|uI67+QVI^B#$qVQa!Upk z@WRr!1~=0+R7Nsr;+IEccu9R@aMN-?Ej8=w%dI^>US|zwH9IxnC+3&T4c|6*R6Azm zg3ANhZoc#T5g- zFZs&oA{#s6iQS7PJAkPTS58PEe-Y~|GZwqa1R)safRjy1B%>V*B@^j0!(u)x{+@1V znUgZdJ?1~VkzWD(xsRd^jNbDx(?-E?V*rV)z zzzyM`sr59%SjJ6NLcKu1y%%Crif!RWKl(K&Y+tRdL0e8YN%Q zG1kG{61SCjm`kc3{i(E!Vg@p>Nujl)lLK#;L~O;o>4J4`$xfM<<~zO!r^AI)htoEU z)MSmwL1G-y)$D9dFMcWIn=iA=1dOO|LzIoGFwR1aspfld+ea-hkSs2_ki1n|3(LrH zp;Qd(!29@{q%AZDFGXY>b$qvY#nEE)x~OirgREI^8yWS4wUuaqa#IT>P|?=dO3$JY z6H%3?1aLi)ddgPwV!3fzizV+a_JX(r#p5+ftiCM?-y<{3_tOdNZRoJAE-a9>0pCoKi~D zUS|S(lUfJtb73649{7E#BFAZ+PDeXBJ63o>R(*>hPUDsU4&8Cj9{pFo_)zESK>g=u z9x^nVCRuQlHTa6UR=qkG6-|aRa||~+C)1Qudq;VBdz3DXzzBW#-V{B)^(!V^SyjSI zW?`w~D3)*32F zzz?1O**3`Rg4`OB`QY#8CDDh(58}06NH`>hLBzps9t->&y~s^UK5oTRBg+NOf&hM?c5l|{w3D#)x-Sd4Whc%I@hm1pj%Gv~b2Pji1x%zo-964w~- z3_m!k+_5H^pX$@%UF5v52SyGIFJ8ONCP?t2{w&twXz}@FCvd4#w^%bnmzQ3c+w9bTM=$|TOqSWNST{X zodf7M@9f&r793OCM8Q`BW$Qp}cA0%+{c!|L*uTf(;m3)6LD)zygBj9wY@OcL25&YAQF6O6)T6clw6SM z`IcRlEr{ZKP3k^;v|t6dxt^Sqb5kybJz~vtkUJzwrzDWVUEtJS0vKuh>jgf0;%<00 zycr}+B6-hQdB>2@E%A<5=p#|i-_^0qLYvy0;3ub?r!JzWMV1-cVy8$CBLC%`44nWY z6!mr0ZzKG>>t5kMx$ghvqW?GiO_qNY0S#qU+%G{5gS3{GMz2uAVuc3o1{o1-%`y!0 za#AV0JW!Yj^{Z3U4~q1)uS7x4%w@~GcgQ~=hVG>{8`$`HZ(qrRUf`ndx<3A+=yh6v9fQmt()a-=M370}gw^tg}7zUF@Uv0G1`-UOV3kY-H zG--d>;nG>{Ee+dPWpNtm=MW$>e>(q-x<}>8P{vBTgukcM;UZb+n$Y-Cqu~zpEmNsD zNlPbve}~^9&G=ZWvh03gWKGfKAf8mjgK7OyUc&a5NUAgzEQaBl#^2DRW_OsrXI z6SPqkLG9#hvT1_sMUi&NIwWFZzcxDX8mSVKe)vhK1FgwP$VMUgwc3;a&MM!Jy7n%R z6I^=s$I+E^W0mWOv{)M{irU>5p;Pj#8nTNb%z;LtBcE3r*z%N?Q$*ey&CX4&4gB@_ z_Z)i==IFO13vnIWn9Q749J)99*PcRkxMa6qW&FJ}T;iUzfGjWMGHc(n??>jR!vPR= zZcG7%$scSE=D$L=Brk#Y5fhD`5k6A2dN!<>CPyf(S$c1{8^3Xk-hfWN3_hGGn#%q1 z3oIBLn>1%7@PV3U2zGI{Fcgm#ZY{6D|Kv5SCMR!VPn-o-Gb? zaypUMZyR~B%cJ&ii8rl!YMK(u#*z|`x+u|u2$;u>cpSaE;Do49t zo8Rnd=RCqFt6;*{C|mvdyO$Vks_~O?)Ks^tk9vCJYlBZbM+>d~o0EQZR99-ZJj?-& zF4nYP1X)u~PNzMZdVN6ya{T+EnO*wAdgl@S9#wcIsB-(rmSh3kmCBZSV*#gF6pCh$ zZ~Mu@Aba@H@?9~TMkvkPnbVV+=VP)zYcjvrC!%o1BTw$!2xH$@mZ+Nb3*Ugwg`$@m z2LKB^?zZtaR>bHa45F935=8dfwt>W-(V@#v@BDA&V7{s_if8MYD?_5rn4jcIaP#16 z!r#ZN`97=?HMr9AkKfgb9c!cy!vzD61V|nk8qZ34a_j;rxg@&L$Dr{>pigNJ z$X>Gu3=;Km;}(8A8Ra4EbSJ*Tm~snPKVVm^NF_XC|Fm2OK=?@*KeMjGR|{~gX65Zj z?p%}Rk{I@??!U#hUn7mX((L2Q?THT-N=fl!^#f_+;53a%%9bTYlhE(NO$}RpKuz!C z?LQz$K%F=TNrd<#V>*Wx8_c^KrUi&;4R@3FgK@$wG+LU3VuFVa+3g;g>~VD)F^SB+INRJ6r1;%<%*pdm?_ zRGEiP`c6Oy>PyB05G`qT+TZea?$1u%pmwo6sfVc@pa;_KC7{;akSlZclCBJ5;l+`C z?P22IG@I7aEPCj7EIvs?Z&}z{73h}RqvH$t4QUAM^1deC~*`*B*1Nm=HEG`rj=j zjJ@)~KdQrK$Li+3?TRoRq67oKU;-QoL47a*(k+ueKSMZ0K>ySwS%-5&$E7X7^ADsZ zUaN{BvL^6&th%xxwY`pu#;m2KwGrpFy7|z>y7}owqxH0AW?X8Xqsu8WVTON(xei2?GVyPY7($W`FkMCbX>w;ke#xT*x|)?Z6YV|7w#Mof5QlVQf=soe6t|qpR%K z32<qTevH*+C=UW4iktHv|3B83!2*B-w}gVN8dEbZM~LO|cPYF9Z+E zeNFlUN>hskOPWPA%9tsYWM3OACPe80%+AD%W>(E=5YCT6{Vew3X(WGa&6gNWQv>@r zdYSEESgXHJT;FDqEnp1;1`N7kZD4jM+5awD zEhZcb_=gpAjP5{A1nDCRRlRe#d{)&H+#WC7?YupnrcJTxx`(+n3oBc8s3@pxcF-YR zV*m*D3lT6yBiYKLg}(NL;T63WhICPJAxYXl+ufK|n0Y3a3?^z8bF3dnz>&Q7CD*c~bUJUB##30RN3#mDL0KTr z5f!Qo(47Np3*x2(n~?!#v#~6|0DA6gG&nJbtPmr2L=gs3)*&=N&67QIo@8@vmIjbJuVzRvf`4tiV7sRv>xBj8R4iW0aM5S7OzU`mIHVh(zgl{vp}xS=2Saly|@l%l~>un93uePg%>!$w_MP zSc)xGDM4-n9*4$Lh5-rG88!xuVq0nbX5KuLIgleiRrVp8$gH^9H`ZNUX{E<;fMCP6 zXHuz|tV-LUJR!Zvq)MBy;;B)B3iH;%>BB6EGo3m+jq_R$_lenielT=YGgKEt>aH)` z>N?qe2KyAOXqt5=uo4jHP&TH|w2I4=uc6DY{l(dL1{npFQ_9;U;c|Zt{i;;_n;A!@ zY2;Ov#tdPv&ZjTPUe=GMo6iR=sGi{-8n=4Bz9;<23T$r5+)mx_uQdF<{p*X;UV0}W z*z3uNaQ{H!lkPW_PVjc-sk<^l@RvW1-2=z5#UW~?NxIc^a{qLC3KKgyZLmw_cTflH z8KzJzo4UG9?G4|~wJLh7P#V1In4}7sx`igq&%@f@AS-@iDH!W{4Fj8bgB0fT2pati z+LdJ3%JDBU>l2QJliCVQR~bNUidJnEz&Zu|>`_%MX5g|Zn((Mx;@TUam5jEXCSBm!2hAr9dD zt}O?-b_RIMWMUM#>>DmQ%OM-u7XRagv+# zkuxol%tmi?$zO<~*M_3sfTsVVv=>+V*v-Vz4#{*EOV;?NlJ2iYR?^1aYK#-^PwWo+ zS5bV95mC~ld3$c!R#&Tnmo%k=ZWceTt$0e2gq*$!cBNG5>Um3-_hb{o8Wt;Ddq> z;zSgTEC^3$$4(=~;a@OZgWB zgOIO?!#8-Iw)@cRBFXX6xGvRdY8Udkyi`6P&Z7^NxD;*X)`7?rVr%e4wTj z&2ED z=NJ`{1X9kAniDZC^6TBSLt!TkbUWSGNxX$ynq)t;dv20Gyj{`4eurXcp&l4w+VF>U zqZ;VS+T~5%No@LqWZdapl<8GT(2*3paqO8kUzj7!!f^OH=`~gb98V&mSGh}qL^7QY zQ9SUC@nwF>WgY*LdhtcIw8=2EXwBuf3A@JyadACEK?>J&V;f1!+p}_fD>ET zWk`J!zAoYsT=y)SyW1Zz#jMMqm8^j-E%LzBrf>bA3#i5k&|z&WC%ja6ugIxqaUauR zQqXxI6L}_%Z0O3oH$?+m=*37*V>&d9rqS$9)r|7W zX&L1W(KJ9v+cC=@Co(z}DfS2N~Um!;iP*O{y`B7~__ zj?Je~iq?${H6lB^6Q&7NVKZ=g-slIR?=UP=nL}GE2e0mnFsc+}CihEC*hABX#;WFJ zd#lS?{gHH85j?BSI^8XSJ1&5LRV0R2WWLM;00nK_1K9RNEJxhRe%j5cz9(?qc%Ald zpGYbmTRP6WYVvcBNiEN5u8BnNm)QQgrV#g{5N=USy)?ZvIAyP(nr>6E?c!N!ja-qI z9cp3TAW-VjzHj7W9%*A&0H0({wZmld#8}R_YUlk$(5GQ#v|Urrvb8U3lz;6x7bW{E zXK!2ZP}Ko#;O`(0M;PcV^7B6;nXhj%E{gs|l`WwEci5Ne{{j2T7&x2%C;08sfN@V; zO!NJRNhe7_(1X3-jK2BXOB@OkNK)+PYqKVRk&HG`2{HNiF+hWYGBoYXyP8gyG=(gX z?1z>tXD#`QG|#HmI@T|mH=C_>Ds;TIE$uW{pSZvHK&Zt(D$<%VuOGw-8{+L_QlZ+EuZqXC1MK^7UkC>~sT6&7f zWlrHsHp>@{U5{RnUwj`z;Y%J1UqaCrRTsY075Uto1(NLO-FD$insg6xZx19RZmi^8 zISU`UV~xa}Cz7v1&=6kH&obq;R6A3d zU@h}#&D&61)m34t;H8EF3EWuTT#Ua|Xl*_H=|&?_!nJ1FqZV-bfZv(~S;pcA2dvc@ zrI4n)23|@cgRILtS^~XQ0nVwbE9=#{%k;`n&V>m!#vtbWaA#Y;%B%lgPPsr_F;bZq#Y&pxBVpfWbl;5^f4p zHMXYBGj43qrs49*bPw57)kLvA)36%95sAdE){ecVl`}; zqD6=}vvN}Kf`wqEHXKaZE))78j$0H|9?ZI+W#MFWf(w!cyJ8j{Tqv5Qvv{x|Krlq!cv>J+FxuOgzXeMZZgq5?fxD`xNuoX5XR5=O9nXx%UxrwSkwOEcv z=@UdMLWo9+wh`kekKs{n4&ynGYg1+|KBNpRM7FdPUyMUwm5DC0A}f}u$`aT)KvJAn zu@TP-=N3ApF|ZG@*Cj8sOW2h**d?BOi|d4fw#ym%j7ukV+?>LLzoz|ENM4xGW@qd( zz?@F*dfJr?4i6?->rtAmkJeH|#(c*un+4mALeeeJM9~@{FoY2j!)#Qw#M@_nU;6{o+gT zrGUX7L*8p#W%TJYCMs}OO*vmJuzO~zjmbw=SI6g*?VdUocf-ZjRAc-X5m$1qE=5d1 z-i_+VZ-a0Gl_m38iWs^NTfqtJ?)*k%=v$k!QQEaLB+NnLw1@@g=W9cn31;YKN?M>3 zScF>L5qmi&=zG)3s&*U@fr!2t=e+D6UY-O(cuj~Rl;UK(s3Wxe;1U@(9dJSbTK|jOE5%QUl;0OEteL2wU-Befae_~j2H^BGVo#L$L zc(R8Cf0UH1_kT9?FNbh>AU%q`?cTY7v291|bI2cYM@e?LuYHG|QJ{e4_S)V4tLF9N z^m=T4kL(rf-3o>5ocmX{#zMkT!6PcKIB7zGA^<+f2U20uVYLy4w#;rAH)TNq6(;LB z9w@98MiWOs!3w62CF$;mBM2Nw^=Fn3we*H+V1&72fIKp!Yhs9Poe{$Z=raTM6lwZc zy`6BEx1)-lVbfD_(r*xxcS&hR+&DgY-99qYQP8|GhA@V3>c2~XrRtq_;^mEqHvVW{ zHg&lepcc=|$_%+-V!Htf;mHxmRO33n8f9nimlHk{a;@BHCD}e$8?tX>@czx88#Yh; z1@+4HsxTKTuQVzA_k-fVPF!j-d|0~b0&a&XphLitH+|IpmLulAVBfxrl|m{-+q9BX zrcQexU(n0~nap@1ha(Q9RN$C7e;qZJ!{&5c;vgDx;ozD<` z#26=nYs=7))@S4lVd+3U(kKMS1qo!ca1L+jOm3-RQ`wIe=&mQUwNATa71z}Hc5Fts z#5Um7=@)@&;uARGm3?pvs89Y&F;l>g;kM_x<%5Rpu43ty_3K*3+OE&y83XR(FH6BX z1mkL)Sv}#*em)RH(+1q`%KR3&gOJhIZ`#1}AUntiI5D6_A`kT#(uF_{okHo{AQ3%ML^tHXJ0?2g6}-kM-N@}Z0)u(nvDo)8H-e99 z5oZ2=?=(l^jV-AxUbkz3Z_GZvs)ZLuwP2t-ML_u?VO#>5p;KC2w&mC^%3dVa6QIg) zIGZKcXOo%!W8Ae*X?w2Mn(kdl!RA^Ukd{8gC>^B;493UD50X^CoDF<%vTrwzCzw8g77j5YZd z+_@Ig%0w1!MG=>$1K-yKh*}LYjRhar3IY1-K7eTwV_78@k7d&!mcPW3$!T#KyK=3<(Hy#6*OY7bc=0DT5f4WkiKl6#6Zd zD=3P~Fiur)U{rocDZ?e-ZBnUZq`0&ASOq>nu?x4?x9oUQd&OB?6sSJtMTxVk4~f{b zeNY>H>=b7XzQUI$`{q6}-brm?N*+EDox6~q7XjWBRzv4SToSDf7btU3qq%%7oAE&+ z1t!y*m8LQK+Qs2%mgAZ3_l=Y$AEo6SA(oom(xO!+&zAxx7-mnMJn%>!AU4E`r&WgI z*k`zu!2$S|Mq%#|zotwlp}1JnJy_Vb#>_A|o4QDEHupAqt5=4tb(-|Ci$))>LpP#s zqf}M=onNY0^UHW5HY?D|)?0sKncp0er52E0w6vYF2(kP3>GhwFZsgaHp*i0F{)x^E z9F1Rjn=PjfQ(fqWS?SvbkBXgl$(#09fMJxSEvBdGlV1GYu=tW%lWyN_In30AlTr#( zE76oIR3)6!j<~+4sa?Iai`9hJQjYMq;gkrNOV_8+^nF`i;+@}Su%aBzu2kl^OY+XP zO9W0Wr5xIln*IROCFWGoYJsguz=ZQuL9JBRC2}nufvFLH1|lUsGQ;MYL$B)E+8&hN zH%a+vri_1QmhkUovBWIaEE<;o#M+t6%;>xFHCS@f&iP7T6FqQMCyV>ggODdiZzf%D zYrBWbZqtO*ey)GTt)mB`I7Q9lWH@DcW>BNBMR6;h)bkfb;|+2mk=y?DxNIA#A%?vK z7BcqPtFC3nA+nB^=nysQ`Y;(d650U8LUb%Pv?il{KAeJY470kGr`YrR5Xatut7p;+UOiaGIBxjM zsn_I;f4d~&1r2RJES()OTW=e5`BIi`m=o(V6AzQyJf}ptmqa$)(UmcgrR7?cb*H|q z#Ey5KbqE*;D{XvHm@*@e6B(7O(Mr=Z`H^dUf)})LCkK)p$gaF~dk^Iw++mzm zRk}IaH{-_riLP(yrcfOGGecbt3|&AMi;#HF@Gb7C~< z2j!XA`Vdgf__tP^o-oVX{bhN8Z@AxP5a^1eJS8c%isrIm(Be+5(YQM^WH}{JJyxuo z7m8aj5kH&%Qx%%07Teq8iE6uqbiQb0FCRM;=!x_C;EuDLEQb2~=vl2JRZ ztX|k`SG}5x_H5D3qo22WK;tT_*)OkfuIbj)tEpM^@r>;j(<{M0IJWpu_^9j_@YC8Z z)LUvfMtN2Ji0R(MSVBkcfUk$h=+zXK6tD7{HE$4+*PG#@na~Zt6hf=9#|*mXq0uPP zhdV~2QM)p%5hq`Lyiu!Mt|!=}u9Nc1n4PKyrJDT3v!1E?eR}`o&KIxFkwN{`Rwv&x z`W7+RFY@Z4weoroJqVnbAto zi|7wdpihM|7oJKG%xtdBY3g+cbX;crPE6k`F-A#&08Q_LMj$u2&=HxBKZH+g^Bun( zyb^?*31P?tk)3%l%HS6#J}Gq16bNj`CcVP6iu3)3dyQP_f6{r~eg7y+Uk--bs-iqQ zh$dju8bl+tYbmvW9T@^h47@rfRbk^w7dPA9Qyp~NL8*8>mFUo6{g89Qqmd}u!VO>4 z;Wc{oNpJ!$5pj6aEbniVLDJ*k&;0?Q(ChCatkwA?MG{7Ki=T6!b)T{Ff!Q z#GF7ckC7)D>9vAGh%XZQm2>a`2JF--RqBEMkKTymhfL-2wjef~5$Kby`Q`&YU5ajO z39()~Ve`NrjllYiMt$h`Ho+QNi+wDHzan@pFTSR^_61Q46fBc)?yucerKrp3Gzw=E ziM4sON5)K#Rj?t25z#3aRL4R>F?CR6q&pbj^4CV5whqZEj3%-z2{9#EM4fFUW_QCA zf2yChRA=pok>k~-i4yf(b!nz~%NfQvWGuvUJC#?IF9+u+a@Nl+Vf$lB*g~oo;;?UuXp0hw+ zH*@?x()18?=?SBXT~nM>&$^>3ZQN+yvV(tXIZotxO9?~jPTY`>3&gWa0{hic%|sd z@I5A!0a~({4(T6nQ!F@4^EVz&$tvR9Kl?3z9G4SjsmZX_q)$MU9p-gf@}{Uw`FC1A z9;rBmmZX0KDm&SIw(E>6-ll0Wy}i8Cn%v^Yt&hq&wd3@eFxp|Ha^spqi%s3*>GOX8!P*~8R<@dqmP1b^qkO2)HyLIw)%AAek+D( zfCf|T@d^1t_48@k$wCHW3+$9O$23rRGzimbUZ8{y5gIGjQi|j_&QYpR{qlwsN!7-& z3r<8Z#IHWcZ5?@_N7J?*znYkoX2X3Ej%!Q)wAplZf|ZmmWk}FY!-oOqcmR_I3|C1@ zb>C8gSNZT&yI0dTscQVv|CSzkH3M7L;)>~+EPRT-;b5)j3nVwiu@ zi`syuFdwdAiVaAoL0gSBDTb_=gx5B7ovTp?rcTTnRrlK7A!!>__ro1pZdg_iWgT+8 zEg zG$lzm1K=g?7e0X-uEtx__~W2;dcB{|+SZ4M-K;lTyDNPRTM^0Gj*<&J#SYH+A)fx) zyzFbSF@cR-0)ky0P;1`MMTbbRtYT%WBl1Ssy=jLW(`<5Zuhu;)MwKC$K$E(K!Ciy5 zA*EfZ07;j)qp?&*S{Eq|i{}Ckqt8Ezd|HF`2)WXEt_AnJ&rEl3Cn{danZbXGK<|=(IyqFuj8NDzJ2&ga*!}JNtHIAo!NA0cTxP zgY@bmB1a ziW}}7>Xq>o;rfXX2n&%0d&n^A7-=0}U@%JSC=#PJX%aW0kN3S2ZJ8mp2AVz=24lZr zOAsOwgQj>jj1)GRNqxBU09KWOLSKF~H>^(*KxrzU51m6M$*MrMbApEn^8hIrh)evz z6>pOlhiCiil^BUf(AdgrAi2vXs|)VJX6i@23_*bf32OMO(5$YXy>!d$FK9!mw!`MF zt`5!ij#Nsc$?C1-%caL^>@*AXQRPY8tf~2pMhiY#c2*V}Gu`Ch+>R95izskP);~Be zAm3Y_sRKU$=>PjdD5(?3o1S|5EWo)VgkfWiIxf*#=?Cky##w&Y#e0myUm@kl*G&$A zeSc2JG2-zapCDscAR&G#NXC7X;^85wZ}B4IRbI!wzJ=UJbjR-+j4KS)@^LBa%qlKC2S=A}|?mBSicq zd^YCnpd~>MCo_JV`N%JRg@e6S6Wa3j1nHt{nay9rhoiq{yjCFeovEIwiDT47l<&ZB z1wV>5v7prky<>`~YPPNvufp(^#8u%H;=$Z)uYWBgY1EeG-`2v)B>Z4#L!}TW zWcXE3+sa7F=@9hETJNnD;o4Gc>P9`mRzfDFQ~7WzrJj;r=d0VfnnlTKGVZM4U}Ra= zAoe4W5KHhAvCN|JvO{^>0eJ~6LS<2%0t;hF@{j9u<&MxbR#r(=>=@hE)~gmo@tx zcd)}hJy$EbZdgINZ{)Si5zBA3~e+yvrQP!|1V zp=Qq-$MyfCZhVBL8KuC>5q=hi0^1hn_^CWAkQxa0# z;!H`^lS0kM)9Sa}Rn!V}b3~ViJ=m3zeg99sHJ*H&7I%i>9fmdVWZkLnClM-m=VCdK zAF$5%3d9m8un#*{7*9K*8-uD;Kn(q#M>i%25RChMvY&|hTXe(l49yvJfl(I*G@~mF zFx!*HVPi;S+XMR)pwQHf3FFi;D9~GK6qARrGL!mLZiE19AS>+BoKr8c<@Jx~n=hat zZj9HUrvt6c&c5n^W)tiw(D0|M=b)&<6;j5v1VVST-~Eo5`*5HcG)hJ|ITi*BlR5Gf z-Yk)(#xorP9*K_h&OR)@FnPAM2y4M7c84C! z$vXq_OOHv~sr|eCk8Plx*=Kp6?_KlVNd9!$JK+;NhSi+{>e|G|!#|Sv#upJ1J@fgk(kok-j4v^t8o|NX3 zx*4(JsXDxvPm3|gUQ;M!=oircKAdQg6UbBvxKf!ncpR|bqlrOcn?W3?YK4Xq zir(SyC{ScNGJcuD(KqUz%F%y@e@xo|gw-`FV1Bjj2f9LdjS+FTf7LUmqAi*PD+}8)ECCb-Bx&51$$0Zy|DRp+a6eF$S~w zDpHA;=c;ERnJ!=&U5(_-TZ4W67@4}Q%8l<4fcGt;&O&n z%Bhz|Urh&DpM9u7o$+$X!)f^$tywacq}mo{w>xOm*TqV=AQg^87yb2ZiizUk$GA!h zclRK*m<;4;Z7b$&?=_&Lq-Ewyycm!O>4gDC04#y7JZ4) ze9&hL7X^PwC4b^K-S@C)ys%1r>DAx&SR+@^zJK-4eQ`>CQ70t%S)KUJ&H43_l$*Yl z$QmE`jnDZh)YqHt>fK%;ht#`=cxqwYY&ihGR}JXeRn)Cp;uL{OyLU=m)+`%=Q)k|e zKMZP^<*29T$?8lY3#{r@`F?XkxLyR>ubjepFMf=UIT=TC-{E|$9d~2B#+BF#$Kg4yh~*x1kjZ=*2xrQ$tcW$bkgb_d7JItEI$h$K|Gqf+ zE3EQhq{`&T!s8LTH7#DHO$gJceKK3$`PbQsq2N64Z}1?~0YazTG40j^ZR1goQP5qT zvZn&oU7ZA-aG-X;*@5B)Ns2)VO>ZvEpnyhD98Di&Ap$;ix2Wn~rFJw-{V%?R zMfaFvDMwsi;%MwiJg$Pnd8K1Ut_arCKo_#%<)IaW8+bf5^4Om}#oSkjBIUa&?g6$r zY?^H?$AC>)IL@DTJJdm(aiJ5=6}}Ow+fzN_X%!oCOx8~lp2^-QPEd0{=AvjF=P~#`I8#L_CW+PrN>tXkxZ{Fa9~F#~85Jw8wQI8YIJ;y;4wD!S zz1xc`H>~(#xkTJ2#;1(}1<{jJl5$2wgXtA`=SD|Z?ArEB+RPYWO0I0GM#&n#bJk98EK8Z&>_l>^k4CH1>TU76v zE_d`sro%ZzX`F){;#w9yW^H!J4^5AXL~M&(l2%zoCPj%eQ-h@H6{}Wrw{!J}vOBUh zT}uZ|PNM9~?LN9K%Qj()#a{Dc$mDB(?>xf_cF4w^t2WQ}7gw~;?(6o7*I?;C7>VaA zJea%E#s^Ik3>!kCPJ}e%A6fTW$!6^lGR=0lvPIua29Js^RJgkYxZfb4s_3Yit{X zbm={I48;`__(osF$@2me_c~3Pc&Az0N)u^Pkh@Qdj?)F8cSuW4m_?L^*ogk29*6V^ z4Svt_UG;PLH6$S}Bk?Mp7|y-aS%C&MQ<>b^v->g;DrP`{>u522%>V_oWVfb(mxhNm zoa2f(rkDKGnV?`n`O#bg`A$O1Jm8ta#-H09WtHXkKaRu3qbEI?@qm8?`e)LOAG6-)allznBc!bIgrY;t5J+p)8 zeh!r3q$UB7t=MRLhBRO{;`tZ;v?RNF7OjU(HcMf_H}C9IRM&ripz8%RfjCtz4OEyK z#uh5Fi`3}eFq7VImGR7qB%A#w+V2~h2zR!h!otkV&=*I$Ph3_IO`i|976#k@!ya%YsxRZ%BYRSCK%Ga#Ijhg!)zTxuj`3Afw`u1Ps%O?Jg{&JRu1 zpPLVQsV?Vo`J5*!C4tsUb#mh<$>X$?6iQLUE?*_jX;}0I6{qe2uO*N+8C_rh!4X^R zv;`FZvujl&{r|WB|JAbf|E2x^r;qsGuB=&!R&w+Ds3Tu9Y)dw%sqVXba77!P@|YA< z`Xpz7a3fOKYjFDeJnG6qs}$RT7P8@)Ju6nmVGQ2idcATx%M97`$m}R6vxOfyM{b^; z*-mToz8^O)7`-^EOc+B$EU)&IG8Ge1YN*;K7)EWwj#(y|B1UQYY03;mJ0ZOhsvake zm22(R=Dzm1V%#YY2Bd!%|#oLeNF>bY&YBv5Wm+AbL ztB$xc7Cgvdax>>pB)7Xm{t16q4_tj_;G6ferLy}H>?GX8AmH!9nU!wV{Y}tuLv+_h zYpYg;JV+>o`Wm!*#@1J>()CpAmHKSZxGqaE_*IKa;*=O;!TlAwMcj(qa#KDe*UN(+ z00F%S${Po@UNn(3Pa1f&Kw}L-S^a?5<$})#(C0&~U)I0J`bN(0P^DJcW{@6gY#FXf z1naA-8{Cam$-U2%36$!9(GS{dIXRsVT#(qDjT2$yJab2ppIoc(mHzw&9rg^|orZ?~ z?w2ElFF(nq{V#W#{LFRiA3n3UW0qwYxBTd0UanrhxWRAl-8`fRo>h#xYgO|(!*kV{ zrlyoSJ8E~%F?^^#?oYzb8RQUZ;`%XR6L_TVaUC?j+wltE_>Fn_)LO@JhI$I-<~TwL@AWbMrjl?6<3u|m$lOxF z)`MH;3cAA3>&I8+`;)B#baz=-F*XrM28z3PffiBI9CSeygyS$I41!!jM+7ggsr8hv zVjKPEf8%rhrx;366`-p7PYh-Kf5hGX*QwQiYaH>vWIg{ewIWfpbFnqHur-shGdB6p z5muJ+zdbCE;XB^m)KTYPHtM3i!JoDvyg4|fW30(0WMVoyn5ZB+wiI7?6Z=j_j8rgt zz52DI$Jl*TnSd0ou(t2>+IiHK+<0xitDx&}c#bJ_x#3;%T3rv9!Ow4)M9Elawowez!eZ?!qmu1fH*%zAg z8_bipsy1@u>8vtc*_GxaBd>M8Rf<&U#TtpLoO8t_n=G45@x;nC|LT+0xA>t-T;Q9) zcGa`bW0Fwu+nTL-Q1-5WZb(yLPW#|?>IjsO>4<}hJA^=TMRe4%#SIbP+%k+4y?wQQ zvnYvEa9gPKu4QDPopH=k$t<0FQg{y_8YUpjlwcHRTdBG|yi(h=2x5hgOkcsQz*2^; zg#*gWO*!+~PWN%(wrR9#6sawe0#w=6k*PuEmMU3QAMwFlQJBTED~Js4GDxfT{+-y6 z5Hh`GSSCtVEN7@=07DqZO69stX54Oz294;=!dEz|k)oyahlFfK_06qq*GQUnNapjE z8PB*OCun*wnlC?Ogu^^{#6BJ=Fox4U43xjp(hQ7agQzG1WW|ha&~%LJk)Kb35pnYjNgTlKzuz@F8MrCXTYHPshp+WmLaH^dkX4%^+JU=To7 z1EbMCJj77hO>m4pjP zUwQI#k1ue;I<@*NA>Kd`O3G+>21;xe3O)HIysUTTGpVd6$4L_B$=|~5?Ply9>px65 zw-b8d>zdAD5r#0fP3Cre6#!h?=Y{+Q!C1{itz)G~Uqv{?I9qX^KzmQl1x_q-^NP+! zT4HbF{)Gi1oiT`j z!qMa7kvA@0e$|0cE@y8NGeA)*^-u!p1lFa+bLw~4*~-6AcGHL5^xh$tm=kpY>#*x% zBFoemor6=f2C24n$6VbC`+Z9;#622JhwM`GB?j@hI%ZHaZ61ApTFf~O%d|HTx2U#j zEe<#GtsK3wyprFwGhiXL01936YcG`}Q=vq)nf;2jP3H%}>}SyAqiwDt?ssWk^ROS; zwI2E^!fPxO#@!RwqF%#6f3dr*QUW11dQDdue@?h8wdvTV#sXeqRQ8*RdVA|(U;ASy zCFhowYy0iH2?FksLWRa=WlP1c$KzGB3sx|^i*e3U9KoR3Dz&p?+5#t-Fa<>>;{OGOb??W{ z>vN1@vFx){GQB_eRrdC%5N{&1qL+3_$e7I|yYkN8iZ2gTL)n@Yei(RSjRU+o4bGF{ z(?dL%mYFZmT{8OR8o8QWo?x0O6sd{cwlY=h-Q^#{@}5vR)oe9gTj8P4I9txsh>XT? z;9Abo)LJ}(QOtD{fd-16x3D)!^(g8hb+#`66Rrym+g=qn&|=)TfkW9ojzMWLhwoMj z+QX;=MXoFb7{kh_YK7_}9~8WOffS+)WxMkfyaPv#HnPr0usR^`?l|6_M28ULK|%?; zu-&C_ZRSi%8BEg{7jk$yv;t3m(+`#9so5!`{*ZxrdQfYG0$ae9@HR8n1u$!Dn8tb>rgVqC&~%jN9N{+rOX#fq<=bGr}Iv zlO~_=kC*5<`@R(x^Qya}# z&?T*svZ#p%D6XBg1~G_0NO;c8(LXRHFkO;FBd>zi#Fnq1K9pnEst(bW2hA6Y0r6uY zD`5Dx0eY4ZJ#(n|76ComsC)s&w03wb^u9TBBR z^dSo4h)SBjjHvt=qn2;c2f!>0igbbn+T=>D{WsAIvy6XVL#EUnm_o3 z!%sK;GPJB1%VFw3A#^%wud>7H+=a>z@Sl;*C<0|E>g%i@#dt?{SaIP-lEZrZ= z5|I=#$QNX>N9GNkB8^+sq;*_(@KY=_`FylB^O^!tngT>+Je|+RpTk(?NM*<**Y--+ zY16$a83Aux-{zmI>)XRESf~HI{4Tdca|s>3I|ciLE%E{WpLxE6eyps{{~!eS{}EX5 zUtt8<|Lu_brw;zlb8NE<+FMx!nM3>Gl0A(C)EfjV!7;$f$pMD}i%h^z0zK*@8G=KS z8c9Oo{>`$}ZaGp2O!%*VKnE6Lr`(d!;-XIMqKlf&^16%KvQ~Gwubr-L2=wITQOow% z(}>=y%hOqT^}nm2WBd7h1`-eAcl=xp&ozhdY2VDX6UzHDIQiGkzLf0e*jNuR(YweN z>?{YeXV|Yo)i-P=aC@hPiUbevwE*{3t6RF$z{KS{va{`kz-NCcHvO^Rmvh5_M!EyW zlRz@YM7v3)LS^ktg zFvcRE|Hm$MMm{pNR}^%jOL9~k9+Q?eb#P=NZ{SQD7}J(LWE}LqP-yrAihx*}+Pi9b;nh zBYVecx~vi@n|5d39|Z1^*jVN1Y zY0HEGx|-U}o#wkVFW0-#qeK0{+QJNxrZc*{W{w6DNKG5pv;k~Qt(ES!NW1AIcPvC0 zLnf-YDbVU^N~-F^9^tp->mHbWLaPT(htqU)86k1n^;FK9=I%PB1_#%iRZ~rH)FZ_A zsjN=Zj@au&B^I&u`4(bJSiwrgG&$TIapqCw}wwi+Bf%U>!B z%5XL2l{Fs;RnIaowf4erW1#-fu{Sn3nj zLdxq|AE?XIk3v)zR2Z+YsRdo`gr=Ibo2iqQ(lv=}dl|V2JnIcfjgaU4t-gMS8HR+l zJxKiUqy5MdM$uVUoLi}_Z%oFBiTwIWqXd>rIT(o6R5kcBki53Jh*Vf3y>&Q*DqGHk z_B$ag7n^FIPa!5Rq3W*~ZP+NmDqCbnBNpW<*rugy(FS8xb`@2Xg{9EbQb?jjtCV84 zYKvU>#lz$^=F+q!b)8K`5#cl1pz5;ngdqnee?+#bqI}idhn3m}ENG-^G6PeCs;cU$ z++Ddc9ZL6j+&ksSwiv5Yt}gY`lwU-|PRF(CgBE}ONH8{2$JA~9yJa9Nb(Gafd(eb6 z9+oGwy0FlC2o+4a(_la#WT9f$7^h1mtp3XT5tXD;r9@lAOcO#0U6BR$BLla*QU@CV z;c?6`XThaHUu|hycq4CXDwLFz=Eb#`O3T``SVgL`Se4Hz5hS)SS*@cXq+(erdn^=e zn!rFP<*Z{QWku@7pDLkL1*dXtSW#J3efYREUs_>lk*0-W8RqaYdm5{?s*Pqznnj+A z+%IKr>a?2P&Lx1udV6zQYF?$Kc34>(R6Lxl=_XY&Me_#!JyaEu9oR%W1h-h3Rwh|x zLkW|FL~f~Ny`@~Gi&9=->ieWUqg_{Cp09#f%GSK3%<9$@^k{`;FH>4H{67f0hv>?} zZe73?JE_=7#a6|t*mf#T#Wrilwr$(CZ5unbvBSFg?>MJ%Z{wUXzQ$^NW3}d3ob!3- zcV5$>{lXpD){7Ncm*gV+;8<$IN_-Ous(%D0Al^Z$t*~=&H0-J_DaV*Psd<$)=f$6@ zYGR8L%2%efu`WxHm~N#> zOAD8#+|-;OMzK==eg^-xX3f7Z3_gejYQ?;YrwmM7v6@K7RGmT)vT0`Ht;bf{Q0!X{ zQF30kt&I5D_323@Y^&R<-D$nW~QRI2v!hB$`P`X}&3A)zCut zY9%doPN#k8enxgBQcefUMh-0=lsu}k0_x~o`3COr3k(^9lLu+-4|n{PMvf{A-MZrT zbSP!`TV?CAGE% z`z$^5KXNOpgN@@!YD@3Zvu+FjG#);L$(U)mYD=s1M%IRlU6RdL-hWEdV1dVaa*U}r zVyU;lD`_r}4_Zp^;{hk*UCrF8^Si@V?5xzh7BHT+jL}fh5YT#x+t-)vjZ98zDHgSC zfYPps#jwQPhpH2cQ`PXlpZ3U~vdjyu&MpmSPzRFT3CkGBZ{90^uPlx>Xw~JfX>~(J93Zmksy(6X(r$0h(=3WY03Cm z&{jky3RVvfBs67}`uf|&N^7+?E@TRq-I(1-jS4TYGFZyRcvxgA0smYhw%srhwj!93 z`>AtymYnhw2M2;Qa4%1$_+6R*>QhYgpHDNO@ViuAqkqCI^>ox8Zn~rOEKd5MXs^I$ z3~=RN>~TTbLZZ$mg2O9zIwHZn&yw*w3Y9aW0yV|oe{SfnG7P{mwn%ZLaV z@M4x{XENlJ&PznAi0vDrFs&rSQWzJDBHSg?2}Tsp@uCkzl(^Oy@La{9%1P;9`GKo4 zUf^*@X$!5zZTXg#41YVImyR5B^gsk5r}IO41fgkqAYQ;pP|U6g696%!^9JttSI|r; zCZIwl#l1+TXu|o_vBo*bnL@b7$mL>4T=ss?K=yWzCKKPErrkLS`#QP$NqJM6T}@Ra zOL}Ej|K)q%y7cekAvkx^TWTsDp=itBrIU0Y((TCv|43_`vz+;ku{n8)<(@7Sq!?C%mZ)=6z1_kK{0%w*{Yr?5g8%d6Hnqd(0R+31~`T6ACs za7{*taC3v*cX9>s4BckZ?Hb274n!E)H)2aDkzNk2>CyM4>78PYOLeqzWp$Jl+ZJkj z__m;?En3k=8H-*yWKJ1i6?(EnNa@LjEi!Ih72yah(QWnNP_llC+s+3cd))rvL+QiD zMMJxs&(iCJ_BkA~YKsX{mjGkRjyOJ@*VVIVacg~{ZAEF})4;tCj>LoQ}cj#NFZ0s4*i5w48e!%X4a z++hg-dDEK>arts?Zm7R*X;fBX3Cj^4QVFEo%k$&pJzk4G-6+A#jKO7l{4@PWNmi*? zX33J6Bj2>75BrbSm(yR%m)GI3Z*o&ZFKKtrwWz-aOTSy%B3JDjXcKr7=FvqIsD_b| zV^`Z}URPkGwM7A>*`zM0X$mK4Drfkx{P-GIU3HCk^AzdM@H}>Oj=PqcSS!d}!v?6p zhdT4RO~u@e=uFHV92PI@VYLqztz6WQ=+Ydk@+lW}RxNEh6^{5X%a`}^^YhDG@{$+~ z)nU6Wkkm>dy3iv0thB7ogR$=j>=Vwkw!g0gGuF9RDhFH0evxB(Yl(*o2r|WtOzHZn z!Qai6WEs-9ojBHrE7;mfTLT}&jxralq@WUm(^D_guu6W~$eX~+o1m5a>_Gj~RhI_e zNs%y`!K%A`ION%i+9qVJ!ew# zwGyx@I>+SS*IZ63YjUc^<=~k9$Oxu_>)aU( zedg|e10cGithx6z-R$A!&iQ-`Ax%B3m7G?2eT2MUpW0QTK8M46Vy)SNhZ720U9*!j zXpWpQg^!+3%7OirYmNsdvyb9scUxyo+M>E?}dT$HezvJ)i z4X`oAD81lNXKq7p1arBMI0h;uB+sb8ckV>^_V4$GiC9~BsC<9C-v6PI~RS+JjR0F2)4q+Vnec1bC3(Vrhl*%vL zcMa@x)4y0PG?;>zo=%5~XD@Pma~Dx%iF;?mAk?J+4pUMP(=!*ktW*RVkNF!vGseCF zq^BV%Wv}yt5H95a=>=FxE^)FEZDlW8>4>v=KcZ%c7m$G98@3UpPFTRM76GER1MJ0M z-fZ-M0g7p#S1J;U0V6?g+znf_zneW9z;C4QIW;77#7M#M7b`V6t}NKNeddn?V;(D9 z0@P&W@wIuOHlKkRw)i~JOT&2dAoD})odg}(K%d!GeBY7lOW#~3Gu~8bJssYIKr8VJ-%sHCZHw=Y-76ovt5}yt~%%DaJm#u|o!cLx?{Y%ox0v8M^#gmM&}IW;lY?f_X5`52C_s+0vcgQr5= z8m4N>iA!g4OTOGeI3wDdU$DY*^=SZRU1<4!4?O(>pM@!xhEz?gTxr~>A>-$jbdO>O z$~n7dn=)g$yem*%l@iqDLDawF4dM<7B#b>#Y>il?@9E;rec8WQ_pou0O#1V%f_fY9 z?(jM_+rn_gY$8g`-};C{gm`;m{|4+)so?5yV>KTPi<~l09vJ6Ci5j?8qkVMD7WCO< zlqBKG+O;($Uu5y~P7Ks|;ZO2bu`6H9xZC@1_ykG&--Gri?)ebaEn@7c3MU?Z>Fs!c z5_~D$#StwcsAvTmqTqVA!Bv8A!&)pVW#a`Zft||J6#6D|+$pLR2X)fv)JZee5i09@ zVdVirq`mYj=aQXaOzQ)@d1kXwwGj2#Trx=4BpR^xlnhO4g=I&v#pyEXmP8iiFO3IS z!jz2uB(15*+h{luC9%U=$YPqvREDso1{9M+wDUSkg>CBbM_N$q?z9%wJm$lm=6y@{ zlpG09mL!)hJUYQvK)m`p?Hk!v%o+a;2mZ|%d>{)ScJ|=?E-qgV+X~bT#gb1zN^gui zjYZ9bQXieth`!-Zy@;+Garm^BSdI?3m;oCuWVc=CO(}=Rs#agpD=~~frlQtPJU1hT z?Fbi;mG$t>u2v_?ii+fpc-==3#;Lv>$-gGh_pAO88cm-_Ek1d>oZNM)TOj~Eai0hX z?-Ofh(CpR*04C7C11tfNdiyZ}S3od)ku_3i-Hf=PV2lu-_;*lpV(_(08i>;Z)|=b} zI5IE!u7ek#FG;nVGH?7|q8k1$-W0ep4|ta^@4qhMc^9(m%PDfYt#zg;n>s&f6PqvO zCD-*-2v7Kx`(C1){}7c(PMGXD`in-av>VxxY&g z%2LX$M@lO_QD0L`d3yQA5iR{e-Cy>UwO(8xK7~W{HPw2aL^((3^x8OW)eVQPE9}-d zkBv*Eod~^5UPAY7HI*r0nrgxYRyIANhB?fUXz!`Ycnn#H;1+~dZzh_f3e^EsbSupM z+;}p;aavaHMs{_&W^kA{_0$0rHqvtpU|cFCuX#lx`7M zfAMv%uV#_fV93bkroNhvW;oi}@V87j+5yUbh2ur^=MJn=u!o7rIGBa<;%>dE^VUFi z>ah_M6F0$aJ>b@5KwXyC^AWRfI*QahIIJXs6o+J(RD@w+<0PC6v>++Bras*G9pU($ z4U<33L?{oED547oqhl^z0g7rRD}pXD{+9DuCd`?ks>LaxJ%GG=sd{y6fA=ny7*zkA zALR+%KeE%q#)uHPUkn0S{y{R(tnEPE<-qj^cOupeHU4U?M-MOfCm(hvuouN~SsoJL zZTv4qG>CYU5Ktotswn73IYs{U9nQxH!##-e!Un_|O2_9=U~L2tUgtO&dSQ#BPHJP_ zh_ybaB1MZe({eDRp!ovQjK?-Pl-)T+>^z?mTw^CM$}-syRQe^jnfC5Aqjb= z>rT1!evwSU{oD#nWF&!V5t+V4 z=KhT#qj~EdItt7R#XkV|01p|rNb(5R2Yz>_dr7jSJ4~F)9q$-mad=_Gp?7a29)?-C zYAKvM-XA)@r^xB06h{`$L zC}g$M&>^5f(yo`FPZ6%Vz$Big7STxuQCT8X*5uH!80pE@f61vCpJdarlz)o9vxtdKs*)CS(Xx#E zYZGdD5f1qFv)EM{B2=?UdYh@ej3YoDkP3t7e%eD-^ zV(yan4Cw4@tD0VZkx+Jz@VuRe0?ob;%#a7?h#~Im=Kt{*8G_`SE8dg#H^o$qeZ&EA z_N~&_e=kb5m72hc$!>NWN2a5yx9PK}BgsK7H8jq!jL<2A*Q+y81 zzcX>0{%dBJ^eYg8wm5$5;lTjNNk?F zMJov3yw$f%CCBUa(h!&MY;o*X(8S$BG7Ow+Wmpo@CjTb#_8|tNhKB2Ab=hzDKQJUu zq-JMOC_lg1X9X0>k)qsDU}I~Cwu#WJ`FR=M)eq*stFRaRgy19Xftwlg@#j2j*(H1-1buzZ0f@Qm zOkDFif)FFIw&7>yVz`#F3y2-kt9})C04&CyihPh3cyqb>Q<8f^&myoTf&^&b-&>S` z3gPeq`;zWZ1^qMjd!y>w!;)38H^t6^aQyQ;xs7Zc5wk-kFjbc)7t=)X9@m0l0pt{5 zuQXxIs#2~&e}p8O16&hRA;C5T6hY!KUI0gK8mf83uc=6bGF}yGP**dKYqHLwvwFN0 zf9}FolbR9kTbD^6fpVM)cYe~hEnu&M7G;AQqu#*{a9JKFHGAMKOxo5R&W^s8_8`p$ z{$;r){`h0L#*os%T>UDGuYPP&?lmFEd%rgR%&}6eg`JAprFV=lR%;nq!;vEDsGs1> zvsul}l-WZbW^zg+b#@-Wp8L}W!qQjuV^PjnrmENo6gBmp={sJlp5c*UK%ml%Bz_dw zMkXF#Q7J&{o^sP`s3Lzncomq(R%h{p2G@Yr>xa@QN>?ISY#yS&wFzvbay`(U0)~>N zjadX2`92A?RuLB=X`D;5NY5W#oL2qt?UAAI(V7(M>wZkT zL?YUG-af7VBuS^B_}zE#@<-ajv+>}iqpVXfvBbecNOMl^yY1{iB{-d%ptR@wcYP$Q zmdMRJe~z@p^^V`kq2{MmP}Qy07*#5Y@?_056kvQ1p0s9Y8!IBk^2mA#sv^ zn`+2aX*ATd_lB^x3wa1d6&tTy;L;kZ9`4IEW!u!RL&_9SN!LY@dP2x_19-7MQAX#` zO>6wuAX}tZa-UX&PT6KXk-!f97uqaN%R&5@dvSC->Vgh&hGv;0ZIa(@Nb`vsQuEio z`-vR}<@NZcw9l=rb+f=>(hz*6_03Yp*0^RUw1$NTo^w%x&PhUt>DXe<(?idM*&l4D z%K{wi7XI+Qd6%=C8^@=$4|Dj{G*!qaYdA=F^VeiQlE?U`y6 z>eRoCSID}t)>oUOQ@Jd2jWVtrz!`OR20tHof$rNyE?EaTBrM5fc1X7#3g7dm>1zl2 z1Mxg5_7L$HR;PIIkqeIGjNy2WLF*k>q}nzm;e#2q(zYM>xc(2(!=&-Qe|*s;!;$_f zNh*SS>ySDR++u78V@p@DzH8~w1`80}Iiz(d%ERGH#e*f~!^YZ%do{SkHLY24YZAE@ zar7-Ed#MEct(w)Dg2!*Gy%)E;fJcbcTE#4LmC;}A*tqiKp7!R>UwAzC&gjjLG?vut zQ|5RxX1-K^flu?IP%v>yDltJQ=nK=ISZHvn+yd`OFFAI0L3XUKVm*`0AsH!8zDMMq zIpE;#S9l1+CamR}F%NMEn}k}Zd8Kh3&kgA&M00#M{YqRPSZ%fL>HFQ^KhpiAbRs{x z|M~9F#=Tsyc};VSZirREryz*hgw*r< z*TPF|J&B{*LRWj}(Yg1gw`0KO${XGw9Nge4Ck@5!%bvHK>A=bN`OOn$j(ei<~2 z+El-{B_py%$iAiv+fjv4tsp;gNreZO0%6F+5_+u`L$9X`c(oeUo_G`Nj7rI#+8Nts zk^IP(CCe|-L#jnwP^XrEO)1qr@0s83N8%U^-OKPx}wmB&IEut(gwfL}j4D&-Pq5MT~IgDc@g=*1xhydK~EN_^&!e&@sr-gpIKBLB`I)k2FjM`P1aS$sRn;s5Z zS>q~mB@F?`ZyCcQ&w3vZofYX?4H|c5tFmYi242Hmd^e~j1YaD5I?&UWb}idChLD3; z1&d6wgF%J?6QA92c;J)*`F}f}fV!+@XSnEA0gg8o5@BDS(A(|aRZlyTrP%plcw1xV zu~qq)bTy!e%1KvJdRIs}wvHW5WA)`8ZjQA5ecGsNsfh0n`Dr3-wpynm=-3;lG+hE& z*+Qww?#(`+u0`Pf{>upc;ULR9g*TxOpq#+5Cy#n`{%bzA01$j*6`ykH?_N#*D|+4y z9V#q(=K8*k)1*2?h)qQ!pimD2eaXr&-jficjI&?X1%0x3)w0bKy)5{0w)D!^6#k?} z$u8)8aRd145qY)bDtM>dZQ%Z_>&9%p^t$|Q*ULo!Q1 z!sWY4lS(&s1x!*JqaC_ z9?#bzb>BVHD28uOt*Duz(IiE!f)rxjaU*T|Sm7X~Vw}}3u--8?{6o&SiV5npReo*$ zJQQhY*Yxu>v2GZEZa=a_mEL&z+Zy!OoEe<*oSOOL@-sS`+rUu%Dx4dUcRSxjRvmkP zq3hf}e4oeOsOd;ZAx%4-?to7%Q*G@~Si2p!OMjvYI3dJMzMfUM1bb znEVZaKgXDGvJN%nP0b3|y1qk=_C9f%o*|QAmQG@m?lIObKNO+pOFi54cyp$DSpc%U zs@*BKNhHnCyd0fwtN{rt9D9^)g%(w{@?=XoD6s0tTQ`Dq#haOz!gU)Elv(@)HVhg)rz#hGDazBxRONo0WAIU~F1cFY_%o=G0 zLK2pk4D((UG%LN4td@KRJRk8}Wj~T5pHOPGKTy4^J|Sbu1qSx<`mfpH^j3^Pf-1Wr zawD=+gVs|4BNh&+H69M(STQP1O-)nP-TYd&~f!w>2b>??@1nIDK<}gYvylSMBVso-0?sapEJP!5p z#bK!utCxAtDnTBFj32srnBkb-P`Jb+t9za}q|5E{rnWrU;~_!D$k?Gx)ykRO<68ef z@Q{@o?I0+`W=CbZ(f;?c&SAoazezS$cSSF*#0~bO%Y7k>uipv!J%_2PTB2HL*~GcB zwFO_r28}U>U%1kNS!0b}wV79DU0q}HXbXoD84KcwhfaJ$(?Zi?32WXV4fr#Jv` z%|MxEF9%f0NhfC+_laZ-_sp)z0T;4)4iVR91a=)G8QiG80i#ui#-S`5&g72NQtQ8{ zB}=W5s;(Ghk7z=1S<*Aj0P~<)OyiDAwMLVKOAS&iao2Kw2&V&&H8}SHQ9;OPH37gAP>hgdBPpU^s>_y z4$BfJFb>w#_Q1=Hcq=Ofez}=O3uJ3M&@vWw%R$csV=PG^>|yC*KY_$$jFtM&wh?kKMu{@YZq?C%R4a>IK$n zRzO~d9{lh8fohMaNm8Fg-Z@?338Cu{(&X(*QX*(=hPEag6o-+%if!M?-GuB%uQw3& zdgNU>>ppJ4Gj#vdf)zP62JeItFsQ|$;3|l3Q_skl3uKCmH0`hoY5y1@iq18~9+S;J ztzNU(B9|u}__S=@kOLs4;X+gDBTzL82&4^kz_5PsSl|eZwTpKL5-Psq3AgyoJjoAU z9yz!gVq@3Wn`FD@?3mrRm^JT|B&r<$x(}y6K=Z<@Dht#R}xf|=k(;en8=|c z4uYOgo!qW-cY=HCB+*(fTRiqP*kmz-dWY73Dc8eD_7MeYH^BgZU6QPp@Jo+B zvbZb#CD@+L_H}Ed0-|5ifOP(1dCzB)4ZZSFS~3|BU%DL>b%v5Prr0+=!DE@%?6F;< zaB2UAz_zm6gTGYJEa?ieYV6r-TkrVV7qVi0y&t8zUF;Rg+Zbd2m9F!v$}8H=TtC+A zj>0?d1HEUyyFaJVj(oP8g6WXgqV}naP54a+ujGSTuBaW2urQ5By5uCjQ7fg$rJYn) z@^HdMq+R@3lJm@A9*bY8UEx`3=45Oh!4u_Ft*hiAohWvD@vjW=nZ-P(XZu6fwgksx zcfH0n1JyaiAtJxZRS8NQ%&EvBJwNsF8TTCyzeaX0N(#cG(w(qZWTz-GoyO_N1pAl5 zQlb#Ma!NIB^Ux{!CfO~WL%NfTJ=Suja=7)%=27!Y_Y*0Jcvj}HZXqpcMIl+0m^X- z88YjHWs&$i%}%*^^$nM?dFwmns`lrLg=BL0#`-|1d#UF>+}89K>H~2{H&7Ky&M;M7 z+FLK@jh=O$4!C#tMs1Q~7zpaBmmQ-j?ape*W+73!O` z81M<34GhdW?)u4e$#j(pT7+Wy<@z!eWr!W-c-&@%5#BpXFXQB$=#X3mq|8ZOZOo~% zU>eQt8R{cEB0#&BQC=t1#Ukt;L7 zVXvOlOPsy3AAFjXEq(AG04}wjZ|M&RK*SGHE}0&T=_RHRjt}@&@g6kS6AhsbZ}yA1 z8ov+K=UQ*V&fJ}EOy`{a=dY9?R+<--2Zo!rZY1wnJMq~TqfFZ^V*Y?)2e!fuy_K@* zDK=$`=8{d9!4<6E&6=(p4dr9jQoKK+bH*7RWmc2R z0JDcrVDS$rXBU^9@Nc6sSjUR$FQTu!YfIZm<;!6+qW3y3QfJz#38&R8wuR}&ZgQKS zY0FsfH5EVQ?~*DrkxN%07cROmKP%}rx?f_o(&Z{z>e)iHk{kfpTJa`14ORfeG9lxFvpCIB#H(>4OFUk|20rHRQ zRfT`wVa|y6sXtf=O8%iEJoo^OKj<>^e4?n%{|&#qa%xulL@d3!X;%2el$;6dT7FRR zi3miR;lt~hmbw=i@~k+eaBFwsUljH0bLiP1>_3uklEx1^)WULxO16JH+7sXI9UfB* zJ`P2)KG+d+U^LVA_sOS7#cejYlTWP2j647%UmE*(qC~mq%yEclAO5_n+o6!IZMie{ZB**Q7a5~1QrY1rsLkZf6i|7jtq5t{vw4zq;D zdwl-;Gxu!1>Y&ut@2)bE12<^F?#99?%TDx#{eCm4dz>eyh zEP`;dGICns0JM3(fanUs{QKxZ!&N-Gp28ZVwSzcNmEX%_n*G7(mfg!%FwyZekh4}J z;oKZiS$0;*4NHe@GBNzCbnUzoF?`>lN6+H2wobQ>sm^Mw3H|5$0m`t+tN~Rc@n^bz zTj&<_N2S01L@h`>t(b4h_Op5^OCR`|xz-i6iN+l4JAwn>6^Z(tS-k(d5k{s#WH9$I zj;09#%z0V$6c-UA>m5+bh;LKyB_k59c8fYtJ5tI%g$4JDwYVS5h=evSY<|0_zY%xtb`%sko;>W8)onYkqerc=LLi8e1*AIMZJ4*YDXOr{1P=N>67mY9xp zd*8p0%f-egZByPFYt3wWyl;UqG#cuj#{j~+GFArqYhIcdW=Xf9s&qHxfo^K;K|8va zr^V}7-iORS-{N*j>*NX^?Su5!un_VVA6$Cc)9B@J`XKB4n>Qwotr!pQ+*NU!nrW2dtcaN59W#85xYNBGYzEfXA;}rRP~x;0gwI8n4PUO#v_in(yBSv3 z;Y;BCb?9_p!oqvrcP@Z1!$sjr@4#9P6sYXI8Om|b3`&6&k{$d>;*IvwASV27eCJkz zaI5kIGvY@1uG?e(^k?TLR=e=I8$~Tg?m>k`zv;ft3LJsHBVFAYv$?>f0BCisMCm0y z{qPf7^_C1W)%=Bttb<4#(LUgY?T|~GxBMmpYSy<}UIB$O*0e?W;_u4(Q$Y{aP6@-E z7jLDhBZG)4WAu`z1ilRKze2x1YP9bpO7p>XRd4)cSwBOr=3Wdw?);}Ck%~=@HJ?H1 zF7Uf;7hex}et-BNj3RgXA@_f$+Va7e4By+=-;!3c=>;zhUmF(O!s{5kqc-E!4A>0g z*KW8Y5V36smqZB++z;ym8TNJOJ+I@I-@f;OLfN)QRwqChZ+JOI&9_jG^~<)fex~pIClr@_*$0ImE|1n@w}MXsK7L|g!f8` zn2tGXLIGgKY|q8L3yE*1`{t_QdA%XJ^_KSOWy*PW5>b-*t<_ffB`{#{AHY4pK8LLy z=Jd&>8GoRoeI9%xMW3iGXX8WYpln&FP{%-@Nki(NS(wbz-iep2dq#@hP>G!@;g=_; zFGe@v0H8nDq#Hq&wUNBD_u?kMpB_fvfs>n}5>3)oY87&V)KS2;tV8q^eR661CH=A| z4YL?_FYCQcFHg^FSCYN%(K95JfIHmU_BNcQ;tGXWNP`b8W%?c56bq5L!7wxpf@~^| zd7S`ie`-$A;7BNr8_P8Hg?Wbn{CyM5jsNTCai7K!K-38p??@Rjb;91)10I=EglkF1kM#>nv{dJnfXPac zJtN6U#*=ww)GmJcZrIiUO5P~ZEMURs3`@A|svYqcguq(;KH4K_j_?~FPM=RGS#xKn z&>22-8~yD0A#j-gD=`;S;~FkG*4zOhz6=gGV}P-J4P8qz9_`848k6|0Fkwe%ulcAy z+kU-F;f94mLdU#4)k;<#QsFTIN=?&PFgf@?f6mgiTJz78&gfB)@PpXRGmbnxq5%xu5GcIomJYdR?bjfWx zSf)24_$U9e40WQsr9K<^G(ZF#LAZB%e4|Q7*~7Req30mRoY!FRt|}c&t|8$XRo5J_ z|Dg`|f)~`~P;rBqyxyZIX} zqc7Ty+tSf({wIr2m3UFcvp=|>KCSpY^CNcF4#L6H6{{?t-oqFsQ$|^k$+Y8-)$L>a zi?-sVSs!ywh~5zb^CEy{yaXB^ahQ;;Ve~wL^6hUPz%6J6>Nm_-GxFk4HthM$NU6S8 z&K{swpzjlxNr9P5bQaeGI0o2oxjO&+?p6Nr=1eNXD(<%Xz3ce_m1?T9M8;OeF!OFlE#?btT87L;K$@Z2I0)$|K@ zUv4uOWIM;BbLyKwCfg+u0vQALD`sR#$fqR0_4wzeqr(_cAf`rhXn?wMj8rn^qZY+g z^rE>j_E_xIDVP`E=ZS!7NU_&_^%l??-67e|2!%-a+$?^nU@gaIeab9^JKtW^XYVhe z0#9i+;>r0b#0UR}PK0^w!m+_wf|+2@r#mkL=_mCb^2&_$Xx5HlwOoTY68#@bev$SU zuMoU9Gma}~E)C-XnLo}Jzn51e$_VYf$;WlDrH>`FevGN>jS4VY6%ZKCG-Huh*b9+o z@9U_PajUd#;O_j)$Th?=s;a>cEgt`{C(%DAOK!JpXI?$qg~ZMqAP^4WHtOlVNR}qwk<# zi{<|&P+QqXH(AN_wb}WBCP95x{gPb@sY3v#gP!Eur372svl8xKz(Nc5tV~ZT@m)|) zMU;MzdtVa#W@S?5J!%R18vW!dh9_Hw)S`{+%$+A6Tpte(pr*R(rR2vH0ohGLd-GY^ zn<4>j7Xkk+sJcr>>Sq@P5BNcQlN8t6Q2jg*Dm z;<3tqF_a{af(M=BCF*$Uft}*XrQ`X4Qz~7M=Se|ZK0=^M^7dB7Ca(5ppZ0K8gS<=^ zfI8vWEtPzs@cr6j!eprb`BGJ~Zv={Wj|42IcK?Pd>k8gx{BKxUlNzF&ouadgF8Ski zTj}+o;=e_uxgyt?tNqfGY}Z-LHR3Kf*~kHJEk_q!womU<;k2V%05r-Pc-I8h$$Mo; z193Ml8cP3T1Xl-&t-EMuOqh%hAocs`*d1L#{pk$a>rd29uie*Qssuys-4I*%{0}$p zl4x(}h&S(u1t;8$$OK_>0g*RFt&9SA?3g}uCzB%o`s|Qq^OW9Nr*{t;f}g z=!7q@u)DO&3?5e%aE*6;TfQbG-@Cr3sucyyA%EobrCeO8E2jAbj;4qZ4Ml-5sMX=1 zuIUF?2;?l}e9@V|ACA#K!m=37uFd+Ob50b{Ke`ZsIk0hJK7Q2$2&DvZ68I;()A}kw zz6%b$xaR-0h^UXfnf@qFckO+@FPEDXx7;_h!D9jWrj<*W4cKF|cM)28@>-u<*5PVMFO~6_dCicEvu9>%X{Squhe3!^h9sVWQKUaTYe+kFMKj%Ja48C!IA@PivVM z3=NA1`eieMGT+FSJVc`{9$(?ZmN|dC^D^K1FL(EmaL4!ysKJ@P&q7cN@PRS$^BAZ= zrtP|7ziAo6H`=Y6AKyKX^a=#__Bh4M`9$*P+UGm=cR@PKBhC#R6+C`-e!QXT2$5nV zCsMU!>*qC?n7b)zzv+Sk?qIG!?Y|O6?IEvvvUPswxbHOIMz`Ejy5u!L*z(}zlVj%# zh=3#VUt+B0r$bd}GaCHJC?rhj3*SxdI;|uN;r<`>{*U{T<2gzETvu3Ce`s3Ie%#tAnKDr|uUTEVK9SD!wrBBwW!QfE$LPLFSU;K&Ul0cF z{XrBFPg9ZB$#4pE1J}i^)t1At4Lcl?)G3#$uIKVCn^4h>|K*jz^}wl zp_$wr?On9VuLy*jEQk0m@E^p&;t*OTlK(6HIp%-Tjl}-9`R@M>vG{NIs7X~@0bK~= z(^OkiOI?d)PZu>J8S6J~cPeS1HhMh#Fzv0&D)Qx?bMi&enf^`RPJWpALm%iu;jYi! zReQ)_o`LO`^Yq$+UAI%#{l{@i%{OW4qTGFT_k($yz6WaC{pe^wIz73WGlnw;Zt%L! z(G$*<24Rcg9fU1=kOg;Dasgk%(8rPg?;T#|9GZ?P-Hf+CUe~#3)Dta)YNj|(8OH0_w!ib5i8!Ruks4-?2Xl9%YX*f4I#~F0v-?;SeI%S&{GJ^87 zEKRu>zvXy@b1vs2kKDAf&M$&WmK@j3C7e?)%I-@-mg zg5*l7jh1_LCvlnWhXwHppob04QaSCxuyHB(|K!22?#413$7sX?fr1nlEffZ&S+q{!UZY4v{+UYs{l-vl3_m1N+kZjQ*iS{iogg*vn z88gZ}#WZaeZ)~m~#(Zc-($d{6a?eJTWzNrqM)(qqF~CG4^g=qtI!`8<7Nf`Tge*8l z<%3YJTqbF73DyN^h0G%${JWOjANXS_8FZ}}ojvUT)bx@=(_h0cm}T?-fm!~4vw-@4 ztLZPZ;J?c@E79hQI{M5c!Kyq~`)ZthE)o)3^Cya6(uROGHDxL0fP zk87TNBq&Z?@!z&}k#&&`C-ms_3Gl@jn^>B25jC5^x@(E-{ID_3zY|=C<}P!!klx$% zlA^{t^?p^Jt_^5SyL8rnz3hC{pA*|an@IeqZz0KL+{ixfh$;b}J57rhwC-Z(j&<`Y znXM$^0!H)Qn3HFrSf3^tpZv^0qKpt?ZOqD?$ekB&7`YRjcU)-c%ANkp9VM-(ZZFZt zj|6>Xg(E0kAQ3yq{6%%4>iuz_7x)P;RA-@~HI)8!`NJc!UlmCfOO~LI`JG)$PeR5l zK81gI6xDDPrG5|1Zl@^sn)wZ~5oyP*-$h~hTweFb(%Lc)m+M7v?};yzIz2&?`40^kih18BdjF37y~K61ly zy7rVdIvpe1k)D!ywAMhO2LssuYjq(K?h)|}SdGTB*9DQT5q1X3HAmu|8RNT0aT=2~ z5`{Xcu%M@m#mo{8B_(r8dRTxD6tX&(SX9Q)6wTKF8BH}pe8B%xu}!sWR61W3YxF;2 zUEKdu#hQLGLe3U;woJknX5#;KENzb#YBnzZgli}gZQ3lSCS zOXKs#sK$5$2OcQ{X`V2fcswoogaebiGh@o`w6Y?#-=g9EzOB%lgGGWu5ayI87Oc;}ud0ji)ew*%krtkSu=gs6lkLO0ftb22GRwJKp z>={s2+U)sl?eie74}s#?+aVe5E}DH)d_6fKRvsWanHW<4i?oW-bv z6ATl~z9R@Q4m5rd?;itF?!=-JNyd|QS9un0X|;?Xty`mNUR|zYZxcUJG(kw^&`hlx zsfC9eX!YuzBnqksA)D=WQYYihMcV(gMTNpbv8)4y5=|5{gqchI`>Z80(Jp$#Thjto zZQ0z(Q#_W=6edtc$k{YZV!*l|L(9rkjd9~eivf5Of{7x&o3W7ZW{{DoyzP#bq7pAf z<~o0T2iA#XVS$t_->}-;mt>0)S9m}ofv5F zCl?URq&&yR$nk28JmZxCOW${ z5#r2>r%5YbjTM*(Q95bpAM#12vEtw_BF|PJpgAW}LDI^R0Mcq8jieYzZ(Wp}@y1T? zAsz$--KZ00&l8q|C2J<5-nnx6{K5Z-MY7|Q=4zPKO~^ZPSY8;Fk#FUOVrnL=EVSup zVaUSicp|TxvXc0^j)$7Byi{pSk3*h=!owL_6GJ$N7&UH?Fg0>ThO}!%#J<|TZ(75R zxTX`c5^rZn4okWGs8k>BJ|bqkcVvGxv{HkL!|i|@wA}*(383omYaltD2PRN^ze4H8 z3sayMMU8JLL!e*EZrcJN{#NyqbF%vrjFTGG~)ZdcT9WYml z1t;+#{(m@o=jcki>|Hdh*tTsuso1t{+qP}nwr$%L+o-sblkPs<=j%TA{zl)s#~%Ct z_g!nR^DC1)0!=~+0oWo@>Yq~P44PX&>XcF@L{|Gn zQQEArI`?J1%a3f3X&a;h{HZysyI2Fi3ybLu=*Huvx>TOwv0Dv1xdr95_R5C1=Gnba7&*C z-$B!AjxZ$=Gk+_ka>Db6zr_>Gz=|e4mdY`muaeL}gM_ISP11uy#j!&8dX-TABa&Mth0!8uLii9zv-n zz|E?VNyG|S&BV15w)AOijE{xB>vx%uIo-k^QKg_=L zU>yHCK7oXq9OSAV%p3zRsZb<8tIQ0diUw^5dNzhonvce%sB886$)cJ^0C$3*W&xp< zMs+KP>mR^{897RWj0l_I9W9KcHYA7v*xcp=bOaNPq}EWG?{x-3>4H$75H?9|AR>hV zVZbW0C1KMIW3wfrvgI$bMIpSJerdh>cB>MgKBkOUljOfUXmc4qBDZ5g@x-=&TBKgd z2l$LWad93yIK99#9Yb_VY_W{a?W}0`JTIe+Ie9f5-PCRXO;y6CDwW3>{c!o`o}%i~ z6P-mkR$m$O1n+^J@i{1Rp;20`q-QH}_o9-B$FUiuEjK~+T{Rfix z2h{5B4!h8G#uIb8rJ&1NK$L1HiIL3KPq_Ch5OofPFoPg`4e3$?A;*L%o*~zy9PupN zQ7$vpeDCx8>Yu*BGq*_R41gq1tEnu%q7y7emqmBWejS$C%?)na!BL)5VK;GvM;ns2 z&lALaJTFry{a#jOYNv>1W9GtgTi>;hS!~cS5EIBSI`0|_D39s$Cl6Mn4$`C+C{&9g zmG}266OyAA47DR7=6>v~lF0CFmzpF2nFOc6ET~0(ngqY7Cpi1ZcYuq8*rp2t%_*(mZsq-J9!Pj{z zU=|Pn0QsnYrPcpQLH@^V$bSL4f1)`-Tbu7hNXKuC_nnboZ1*>?_YY`StoRR79pcj2 zfZ7gW0b2ZfpoNkONT4b;E`?N6HAAk7AR|s6V~vTfLe^p~UL{`MK2krA zz$a=?~7=Y4C6sg6)kcg7J5&@~XUmL>T9b-h)n`Oj}I!OQ#u&VIum!n2uYkb=x7 z){r4SllH?7jXeY(%02Q#Mq~F@lvCy0S6q6`Yc813vedJ+m|m%yn*(*-9@%SAoNz6s zQ8c-mfZ`00IH5^RPs=pT*7a2R)bp)H^oWuH@8@0CKL$?j@sv$T&z2sB3zkM*&OE2{ zlDkW6BLj$xr9MhtmSAn|QCbh$0x2xwwlG<)RiYP0V(NfVM6g{Ms`qo6nCu@7Sz|b) z%G>DT-9tpboVi0@6(5HAI==5Rv!Q+F}nq&+u&CW zn4&LFU$4Q+^vnMCT_(FRd@6SK>QHw#9g#8X_Xy7lQ1)45C`>8DO$ z7nFs~8xa^({~jjuJ1>^kgAP5qBRzC*Y;NhV>5T2&@RJ6Lm9NfhNm zP9M8uX*v`JQ~t^lf#G=^L-3^2gxG0xd?`F9?n?VT(%*>6j3?i_={HeH`!}NUpJCYC z{}oY@bFj5DcKGM+{&%ioX@{kX^0|`IbnlVK9&;pQuA!x%pq^3~!Ym;!pfC!zza%e^ zxW;m3NmE@ceWYElL1ylrBr3VnG^c>Mu>jVTU&OZsJLWI2sqaS*Jw@Mliyp#ftQXP? z-OJ_md@YfJL^T9`Fu(0M+kNsUyYWJ|=WDPP(5n9elQ&4b-b+9bd{k+RlC{-*Eoc+e zIW&YzKg?KS@W0{NK3!pGhII2TYW_n<1We94NV~bAfbWmc}T$O7^({F%f4PBIa98R4Imd zI5-Ms3vkkVm++RD$G zkM4svl%Fo6&Mf{BMua+XM~OOdQ>KjG8so%98mpO2 z?n0pG&fh6>m+w>H=ngJ&_QW6@SCMTKz097n)7X^E)gBnGmF{D4=Ac043_b)f)f{BH z2@OMW>L6dH-Zlgr9;vFdz0u(8pmOTW-%-xk%`u~}$sSELB+bsGNC4aT6unA{?1iuH5Y(OIRho|rbHgA6W|gV)5d0Z3SFeaPh@lr^mND( z#P_dUq&m+tB-T!X(M&gcXdM9`#l?at4;2a?1EntDEkSf|)AtK!Y zht>V5rKT$Dg*WUcWN?LU8JS7Ik{&&-8V>m;?#2Q9u(0V#OfqVNCI!_^`#rn8auhE{ zdNXroNt!@mK>+0}x>;;feRc-QdLn$5%Z?bVwVtPiV0dA6i2#$jnvK*K@TDD1A+zCHv{u8dxV&&Z1G`vb%Dh5ZY&lln-_Hdk!b zhe{iyUIEQI+*LwA&~As+!`Q|or=+fFF~{zhPUzQ&UD8?pbkRwy`zO>I%-lYevNl{i z(&G2$vGyFn~ z57lPHHXAY}Zzl-i3bh@1_9U|Yneh2wSM2!Bq<`L>tM6e5c~gOsS+F)nXu zD1<)Th!|>!1TEx1j0)7-Q6M42I*=kqW{oJ1Q$DI4ek%E*P?0L&@F-Vh zg$2*(E0Yct#;BFKEVXw;%s||)3=OdS(&7ojfd+1iKDG^giOmE4p~w_W6+g&Auij(c zp{}G%9HDY)R@4}?%wlM!;Y0Ooec99zUIK6&Rn<6n5&&?43g|!;UUcU-8aVW zORFNnri95E)>8QVtxdO;2pcX})RPjmg0N<48J6o~P>g%Q4n0<>{B>$C-CFrUJ{AQ7wzqwo#ik#;W_@yR4V9o#U$+$$D(P3^=Tn5S zu1M{fWLYF^hV&J#9`%7^;t>5fHSj1C`{lx)vqeudPt(1SR9ipM@v=roTob%^L{|r} zPm_4Qa94Zh+k2Vvzs%C;?>sDr{y;1;;Pc`EGijp7r4d>vAb({*<@b~Wo?GCYBi*mi zd;$LLvTl%1ixUI`0J!_N?B4&ptl9pn%lco}^xsBU{!9PpobU!GHcd=LY3Ve zXwG*7soxdQatlZsVI`3!F2|h-2D_Cr5MrbKGx)JLc>8(a-U&PwKN4n09CWBhCo?8s zE}n)G6DgyvNM1f^JXo7Wzm1+>ty;1%UejV61wqhSWAHI0Op{(`Z5eG!b90Wu<&AI| z+B^n zt@F26lA*y8TJ!zDK!E=fF8?2=BK!-N|5a%HKZ8B9l{6I><={VMurM(PGX_72m9mF|UQqtX8mQDn6`-GIq-Id4vxzbT)nl1pQfG8=n3CxDhDS+a zJ8Or5D%qmA{9;*i10mgN$r4e#+}7Hf*X_`DEl;?CRM>%fy$Y?bLVnXzak~;&<#gYi zB;k5ODq=H%>OSUj?%&7g?;2#dm~7sv-pXA_3gmzhGPc9Zx0^9uU4cptfw03^f%<$7 zE8L_(bI;^ELonvHjLf3%{tBx|GZ#zl2vTbWxylMh{&CxWd$jGH?`f1I>CAtq-xSGAyki94b*OX2ea@Xr96l~*a>fySb6s}(kwYH8>Xs3-< z!<9TPS1UA$RSB&z3MadvzD-Ret|-F~;w@+16m0-6NE~V|B0?`<|T|&{4&QSyutLE0M_Mn-!ZCpYq)>O%O1__ z8+q%S7#BOAY7$`ZPzn>&ZfN^f~->~23`!xA~AA!sFU!5fXfc<~{ z^Zc7jq4|ycF}{(%3ypg=yUe9gqJWlJ1ob3>b%3}rS@qT0P`PC&adW0*rcF_ES9w=u zjfyxn?U6zrO;eLxMhTjSKPwE(Fhq40>*IYNd^4DaumSL08PE%!r!8S?ibof;B`bLmO8YiQ{HmsPuqoMtXKrdiesC$GvJLVx{5jA$y5z||B{`V|3 zUOL%l*exZnpGUfST;inlPJa1v%S7%}Ch zBQRv98!Od=nj~VIB+M{tDl^M8u3EE)(Yun;nL6!fttT18%(&?dOe1kuQWrHr%0!`$ zgC1KfF&%gFACLTlcd{PDW8Edj9h$^TqMRcnAU`gX2=vdw%rSURZ2stlB&8s5iNAAp z?>fe#+m%jb1?3=YijV%T%E@Bf7x(nYkQpxbu@LlHm`|kTiMg@6tlE3bJj*96zU@tSG{X)Z#ZnVL*{KaiYT6IpQoy zzMhqp!IUYc5-f=qzp8UAA)Awz77!2|4+wILwh;sGbkSwCR4dg;b{|BOJLm!mpH7BaZ(!9p|9lPkhqGawyR?_f-`W8)uJ#W|FliNI9cMjg-9?y3lOe@7~)tc zk`dHBC32l$wWX$+_t53DFQo12UJsp4xT&gaUh!K%Zdedqz8-;xvL`%LePH+kUyU{L z2m!@&zHnEQvL{+p+3VZ!+-r*%wb$y0K#|=QN0ALbGPhE^)8;PRH_b_(lVcp}~YxG&WX#L6s^iE=1c=PK`XS%7D=>u+(~RocUNXjx9wd zM%sd~BqUWc2bWzsX7oD@%PD({V$&M^G%8zTI);g~ECS>m<-oGC&iL+RrwQq`_T`kJ z$OIiJmq7L!D=VX$o|)ANjdv#raYe8FS7-(9&4x;0Q=7)qrDhS?s69*V5QEO`MIENL z8r<=)=NmhpSFPR7&kYf;086&q4)IhF77y43?DHA7t=vP*V>a?aISVA$irG-CxZT#d zdBr7$fzIAtZG@{!>by@JkO*BzaGi=;w8{GQ#nt0Urlz{gb9C^sL;q6S(sDl9f62fHtEGPYr>j!A@`2NLrUQ+B0mz5{{ zNhMz5h(%L-By7s%%4qE7OOZl!oeTypq8rS5Q+J5~rraBF1Ip zxXz>L!W7(PdIVB!5$7~2dr-Lu?Uvw}(+x1XUZvz}aKY**ylNbUEJI7eKK+nFF=%Y# zI%FjzwR?^zC--v)lMY;O+r8;#{*Xh9#}jeV>rSmwp-+^y1${vv8C4L9+M*v(93o37 zuZL?3lea$uOn4e29F=mn5QuD**yu|Lm8`*57iwC6+Y2}M*{eIYxHC8113=m>Zu_2I z<*sEtMzlU=bxI~nPnSn*g;1l1|1!)KOO@2>J~>fsAYdGAQ)3k=20-s}s`XT;8d_XptD0N$PL zhdAUeolbP4502#Sz6~^&&~`f(G4Vy77=g#4tQ}41A?>Bf)#jZnoC3c@_X(g(Nor$T zaw()YPq4j|T~8Ki8YsBnYrt@UCx=V2torpzxoRgY~}x3jd-Uf5iuC|4;^Ph~2H7v)NrftQI=v zm=o~ib=s;IIh8-i8*nz+Wdb1jtBRXxh%C34IU)AuLwHXE1P#PL1(~q>XHugwD>BocHXT9LH-OQTGR5x-JksHlM3e z+BEJWx4I9tK5;%uyNJ+5A1`Fnmn%a^-kDk1+qnI`M9Ax>!UVqSesx^l;eF3PW_{k! zj=mhYw+D-Eal>%+FZ!Udx1*-W+~=Z5ypsd76mC^OxuXY=Ik$#bIZC%lcx=1oD<43; z*@|{Kxw9|zIJ!o6spwym)bEhKKFR$(BYL`~>uhRI(x5wtWfEs5T9Vky(@I-nxZ#iB zVLtv7Hbm(SO-0U1lGLX?yUBbQXK%k$K_+Y>$qrOf{m9_CDR-|}4LbTt`rQ=pG}1Dc zrWvdm`4i6hi6rVU{TEw_9yOTmlKOJ^2eV+!A2ggq;Dn>wIT}zh7OT>`^C=V~HH3(l zPP!g3NT)B++F0q?E3=mbQhYWb*GsZEj^$ZNc0e&D%popm!tGcNrN@IgwwI^}5g@H% z&cqFAbEZ<4r7l!nicn>5MUGaSH_WW@-L^(_>h{CqXvj#htXtN3Ah!_ILM5NTtfzuf zvS4vqrraDd=!cVjZhFXBEyTCGFQ%JK~?=a+XSMN92?FO5Y}o< zXOBguuOU*8) z0KRFBy8YkmY8p+;ayCq`4Jwh!&bqqc z!C5}RAT8eA1nP00mO5i>RV}{oKnzqQG^S3I_bzs4d!Q=LzrK?w=C z0moL`35h`9pzhv6I~i1Myw|!m@ECa2k@fT#TsD zAe_uMA`*zk(sV-Xrm#c(^d}0PUizPVrU+qib{HMNaMctWd*eyNH|y`OPtBd#Z}EvPvHJ-{P>p?1?uyRCH-7?{jOZD{RQXveJ0 zlbVs6cuu_oybF~3%4U~xTI6ndOYE9Yhgj9T@Mx=T9YRjLw!6eUZRRh} zNfd;T@$QxT&_$xxfb#SN{iinW_n1t<+3v??z;`*}8>KR{u3%!%Gm6tQ%kiJwWXd+h z^RlveI69X?WZmU0h))Ns5E8;OfTx7gD>Rno(|Upg0$|nc>V!+{8n8gU&U=2$GR+J9 z5q*Nb0L9ggx0W$yvyno0+!@9LWj9FB&>#7XeB*_6eLO zh?I)SGIU$@0KPy=NEn$T3?+sz!G&Eph(L?{{vst>gSrKV??|!Ta>5_&H|P`=bGl}? z)X_@->=UsHkKG?TAXhoetaoz4I@?MVScz}qrJAm{Ak>?y z^~A$1rFKJ%c8e(ZVisVhOK(~Gu_d(@EgumPXB)~u`e4E~d{wsPi53$dRIW|aF3{N(?mfYs7fXgrVp4W9@xlH@*>)JHXTzKfx`*O5UH0 zbTN{$wtZmr(N5*{b}f!8cTRQ~Y*C(!ZmR^G0_I(wVIf$#{L_prv5mVWn9N3X2M(Sw zR@ub&l*SX5PHbH<9_RWla!`p6HghBxLm<3TAyj5un4}Q-5v*t=9=PJul8&1s^=a8a z0ph8PQyioV%Ns30eo}yM&@LWW-L`!@Ei}=n^<$7Yyeno`jC*#-=jMKi1g%#<8N*ApVaKXk6%^pQ2qK49DrT9KP} z@=<$BFW-TUKk&|2|1iBC(m7##CeIA*kfZyS@_Ytz-^xzy>ZT3%>hJQg2Y&6_5ZL9e z`GEz=zS%AP>b)3rjDdT-3VY0lll@s*cukP`Y>)xpZFEIDBz{bk+4y)ug#5&mqy~|p zTrpteJp=KlW(zb+r0kY^C(SjdG1Zn;K|I`$J=EFt*O6qpBMbg;HSmMNMa>uR-vmE- z_H#HIZ~y=}Uh2BjiZm3=ue%3jo< zfnt6IAzxu6A6T!G?=BOGr|;*@*4V^KN;B$A1L zn>32MZK~zg%9?8aXq4G5G{cl!UM>kP?rg4|88+SP4>`yONxgmhdWF6x+1u{cAXAD$ z=7ZlG`(kHTWo(uw@~c}7W~Ghq z)FT3meKtVd8YH~=9{xe0J@5wD z(H3~h_^eQ}3qk3nvQ9}~Gu7Hf{}S==_mc4ba{tAYZ_QT|_^;dGKXK{L|8KbT|8Wmw zD@@uf{zT?sqvIN3Cgqk8tSnJLrHGU%kf0U|3IdWR64s9|Q%Fr5Z?ZpHOTHrPSCv;2 z0t$!QErfU73PW`nr#891nBsVz`FQ*Dhs=)^c7ohslOJN1=8}D^&}1(-SUZ3RJ(|o` zwEH>ei9UiZs4KyuCO85$l3Z#?pya{O9#=B?O`iOXs_^DQZ-pSK!{@Zr7X0;ik0O6A z(j-F;<1HUoo34a2XUx1W{+wQckv+NI_CvWYZst$WF7(lfESWt0B11n;P=1W3zZBwh z`*lYKrfX_FwdF=SSJS`Qi_9ZM8b>q&@hd z45=S2vToh(oglMe@cz(rL!oEID&@hPfI+I$&7*7AY0p-*FoM~=8W17PCL{eSxExGK zG2D8xx8ntJUhP8HA<@`cza-Ufad7Xif1&C@#RANVpv0=~Zc_sz_XPA95kJ?n=6n>J z(^sos!yV3=g%7aJP5XxNI)3{;+<~K}$<>4hlwOlL{hm*Fe>()m)q-l`zE@xH-&TL! z(q8O)!TA9>I*oScPBr(&D^{C{?%n0)L$&VA>4^Kzc2 zS=V(Gj6>kuYfrdOI8Jy@jC}vR&%gn=>;uDP&`*UTz-gf;+o#!%yc~;RROjpuwtA5z|Y6%K$6AgT_n1Ez0xM(~F4YzVHuk zf|e8!5m3%Z&&a?wG|^ys9L&!HDc2QnkIgToQEnYsG74$8wW|8^-i^)uN|3`b?1*1* zT4tQ$9h53h2@1J2{~d){x7LIbW~6{L)pM34S8l2>Z&{23UlptdkC}_5N0js;rx0KEWoFa|jA!8F?UU)gy$PrMJ9A3Zkvx=nTs%`( z)EGdr>Ua?Qbn>*seX%0z>Ao0s%c%O(j%-Q}!X3Rg=4}1OFzC`qGxBAh3@Ds_X8;qs zq*NFo)1RBelw0^r05;z<#3PE#okYTJz%>dZa_yG^N_t{=-C?C;Uk~n;$ZVGv$1o}@lfi^?uGop z^E=$(zv;GkFmuJ##5K6qP(HltXVhQyKQ6UIvO}>eDdK1AZWX|a-*W4827HHxz zkWnO@#HrYt48zKjzR^`xXiA~6u`Z_lD<`Ee(k@U$=qs=GnslCvB6R9U4M)7azNo`| z{VZV53VA#ra}<6nM#0wjJr+a;34YLPaR43qT4m#=6Jb*;>!IKlFG<%#L8!v_d;3W6pPVk$^^a(+VO_B$->zAhSY(+T7Msv6xP?z?kus^OuoTL9IB%HzxU{NzdOeZ% z3@SCsreckJ@`h= ztqjs8VKY~Oz*posH_=d6uER^*_M>@sRX8QH4)=Xtkh3cXHSM}Sy@R4WKnYejs5MX` zAk~;d_zS@N_INIY%$iTce3k)ur^TJw#_Pv157|1H(&^jj z8=4u@8QNM~+uAtNefRH}G12|YbN;6$_7A+7tp?+zw4D64!-i*T!uUEPB}Td@NiYt= z2q*z0{u4-?7#(p63|($84tl)Lh*X9Y!CbkjqoM70;kibc!uf`XHnkavekAHu%W|`& zWvlk~^^>L+Uq!XbcE=SZ&v#c(>bMb*(Zl=E*28t@iSG>0v)2|IozGjfEwCEliiT?L z>&wvR>f0~ZzCd55ZMUaO^<$s?zN44&;FX`5Z?0Vfhu{51dp{w4M&Q28OOwBb4^OzC zp-?}HBXrmAEI&ksZE@USOtHrXE=s&Xh8DlB`mo#*(Rzyat#N%v4{=a#?k~RkG_h(Q zGWh7-VXSnoBLD8^zJaj}u3VvnFDb(vsSc zwo92Xj2kA*4h=#>G&0|_7URuzi)BB~dBhf$sLxWST4HFG>b+HL@`6%HDU&qkf(^Bq_ z%HZiPYHjK1UD;FS?QLk8?bqn-ZRy=jkXyoYE@?i%{{z!D`y=jFX20$@I(iz%T6>`> zs{beRDV#N|5ZL&BjK~5JD|k^&q4)5|-kOQ88M&VNN{5qchuM4NPY-QxL2FS(Pt`vq zEh8lXl&C%#jqlEGq=EOLA`JX?PJX=;k2K(16?gj0&$4xL-ggt;jmXV>s zGD6>6K?<%uaR@TTEh3x}X?z;Oa(;_DR?)GO>tUEknvwnX>;MM7)X8WaJr7D|P`L$Y@g9T@aCv&F|Q6by&&WI}FF zQB8V)Bn6hLiN}`I9yHRUa1;W;(8G-q{t>o4@t*ubdJl?KV9pd@d+H2l|A}Lyr*1zE zZAgiUe{tDl*M|qwBnsj+%*0Qge^4*tatY})y4Hf)QdCMZRf>*5m}~9LFQ7*L80-e(NMb?CFPXmY=vNa!#;mn6 zk`SbaC(JTtlHi~a0(h7uVd*hz&=!HDmP+9nN9|ybN|+%7%!{gDb_#twmuUZaH2e$o zvN#JfBH=kVGI1W#`nS7_93JH3BH+r@p_7X0Xt_FBC8Fx}7n%tDzGWf|MO!LEn_H7` z2zeQ1z!sFkDCmS+Gm<_u(<^misuIHv1uY^Pmwl=le%<-Na&4k=E>_;W7PvgM5plqU z=ver+)IeLzI2uSri7;H0;0x=5qct=7#Rc3@!1j+O%80B2wIsO*X>J8&x9kEXYJ;oD z>;kEzvVoJK#)7SIQM*>Z=K;2(p;WuM@B=piySh!Wf9NNmk+Wn{FE@nQZ0YY6sy;OKX!03#%(j(@Kq{?O~pRE-j9jJ5a#$t!88v7@)8pyFi8IF_cD&8jT1Js1z{xhqFa z4-!1Z5}f5A&&3U${|yd~DTRsL0xju|!^i*w|$)KR{k(i#`Y;F0NQ=il0vT%}H=g|!-g zfPww#&8fs%e$MJ>w6?ibJhrdAo2=!JPcQ9Z9hpkH0z8~9-aDktMX)w4irV0+0=-pC z9T?z`Qa#oy;HEhLxm=6R1aY3xjOU(&fGv;2z z3Fd;lQ{U1tqt0)qCw#Q=%US7{XaT19Re&89mBWyh6Bn>L24@&-<~NcZhIo=POM#vg zksc|oEI5>DE)_pF$oYs`211)J*)T;riB26pms@=2h`1pMFrJs*nZj;P^fU)c4RKzx zxXcpIIb!D)xd7=-q}a3#!F8RmaV)_dnm?^?=BP(^Mn8Ne*LGvcnUtzu_zKusw7@&*gZRWnrMN{wwr5xQj4Sd+QRIZ$u83`Dm*Y~3O@7W3zLY@6;|E>KW&8zE zoTH8lp?gZ}Wcp*f z{8IwWex2X7qnB~@YC(xNjM??N?Fp2`{25Omg)5U(D@F6h8(;-ND?k0v;Y1=+3v8<$ zjF9T2?Otmow9aY;dwS>{u5c{75@OoLRHdXtJ30N@ijlFEaZ_6@opG{pffuNko4FECjnb zDVSkeU?O>OPB+l(E~3S`Gkdg$7udz!Y#a2BFjVut3b*X~6Oi#*WRf&r-jsWI!(k}$ z9bZACH^%D0Xd4V)f1q3N#_viuL_VUV+{7U|yC1znnJ*~6`fKlSeFEX`G`*r$?NDo> zKyATMY{QwmXzp)o(qeZa5kL5;2j2@IeTy>tL>Xgpgjvrzat++jl>PZ5>Mkg>At8Dp z+2*#eW0LR4iDY6K_aDlVF_MFiyckWtn|FD}OrjN8JG70jM}M^3^e zN$@@(*pO0Xa$W#h;Zwyw-QZdgQ>As>(R>B7BE241U-A94?&q-9WI5Xgvif)S0hS}i z+nu=NXNo1qSZC0eFBoD8m>A-D37GhzE5R$`#V9{xkij9IKw+fVe-CYqiYwZIJIWGN zK8PD>=J3muh8Juuub9*B>O)^Ig2L&QlTkfW)u9<3;bQ1=Q@t91~%*9O1KlMnde-vD*mdN0AEPwfnMeYYCJ2`7t4TN zqhu_=bT1&aIgyOYrt9}sXhwp%eMWYI1l^>Ti1UMHe3O}*E{~h_OPp?xzG|a!n3^+6 z7GJ<;VQ+Ts_~9@3(hy_MRLwe0lk9_o`Y^w6vda+`DVZB=N;F7Y@I^FcU}vxx8)Zvw zBl&uXG!GkjivMN9pRpEURS&~!-@JEVg}e)>P(y6>$d8@E`w1Cy`XhPLNAh?P0d?zl zbkNn~u=S{g)k&qBSn88FbKk%ZJZX5`Fr*grfv-3vb{cs%S%tk&m^}-O6l4wzD8^(0 zk+ol=B37~>9Tc$SivVvKfXw57uEY{MIZJ@LqhgF_TzIl^J#^)dL?X1pWfQlZ%2s@; zF~NzHV6zs(fv&7Nd@}uuT$2lfEp>gtd@D^v_e-z7kbSO`#e;rh{EBydtOC%~gS>71xf@Gq5IEO=R zN&l&!?NrSZ{z~LDpRgs2g#O@$)UcLQlp&-TOmHkxpC@5(7wEds6pZjN<(?u>O)L~m zRnc&)4%JLDTu5Fnr+rRP7EDyvxg@~YJdk4Qyxs)*i_$a48@U+65!a;G;f0QI@^-cn z>u!chf_d61WfFBEnuYt9#4}wO(-N+3sl_)A9o8gA>=jIR13TL1SqgiWr{ewD_yWH< zB-*C#6(G1zog)XLBRA!yT)!(l91@GnHA4v-UtKh@xG5RG6LsVS1ts5OCCIS-*3>E6 zZZAr?Dj3{edKyxY7h+>VW^}HqYc8+6m$ZJS{~IPSpj)fyfbRW;V zxp}Fqve@2vSu(xZDFMfZ*VOoXV0(&I9qg+Fj`g1f_D)RbPRuBWyGM@Jc53^~%$de% z)2R1R#%{e$$6E{=woW8kyoqG{K_1{w6mok76%8SXYJA?jdx<3Ix^D$jSdQ26bYD(yU z$UDau2_T!mK{o&-lK81r4G!=0mnc^a3LS7PQgM#f zC7g)JCoA(rV4@QEAXo0&c56&*!3e(+Vo&hcQ9Kv?Y=?VDeyVs zJ>vI;+gY`yTBH*>PE^ZArwu)rS*yx7T1vQlP^48ZY$N7JN0aSVioY#Xic6vxkfi&$ z_JTM`m{xj6$2rBg-ReTOV_7=#K}_z6os_IHouXG-0xDUBv=~sY-AJ+&X`jjx(%=DM zI^Awp72=3Xa3b~F>ND8=X|1WVEc=WWHxt$3N-F=lA1*3_5yN789?Gv_PxmeX_BP%M zpsz4%5%u%(lk__y$kL1Ffizlos>>qLD^RQOE>+?e;p^`NRgxWY_sT;ydfVj{T~c>z z>BObVY1^bO)*Whh>6T!3;YNKVUsVjGxJZonP&@l&#ZK^U9)xzwE z1sBRaf+c-8+F_bUP#-kb1=D3xhk3Z-LZ6`2qnCr;zo(+io?%yQ!UF&u;<`A_eT z^S=^K{x9#2;U5x8ax@q0cMF4%=_>{hqWLLBS^Y~EfDkdHP(MVJA);tZ^nTwSIXgh8 z06M?$XqAf!QS~qGoK`MBj33ZZ1cX9huH{7%P4YqW5~kuLM%CHUO^jzv@T&aiHdV|s zmYG*d*_}!GvT7Za2m91UHEmADXH_S~We=cy-UuIPZ0QI;(XFbLmp8y~lF5c{5N(2{ zUq02y)sc?B8V~I8*>2^Tpam@QacrQncf0H4U-DfeI{z*y4b@x|Hhe!f)W5Yc{HLA8 z@?X7~e@aRsf9+w|R`~X?K3ia5X!Ohce8cn*nnA5JBF*wuaH#*@!{E@rolrxPMkLU>-$JR+x!$*r=^iaZ*t-~vL+ zO!W7Z?+)W0HSdAG90us`B-#Uq#qC28$;Ur0w>>Y{rozTy$xe!{lhE@{CW-tSE$0FH zWfhqQ)yrF`PmVp-bK`c)3uDw|2akO0Nn1GE`eUjzo%#2xTAK(JCM=ml#jNd}igLOe zT8`rg&LnG9rvqh)i@-2@HE*=$MrCm`S^XkWR!dR=rh@$t6iDBJ@uMjgldHS_Cf1zYZN#VxN z^y)WTNmrfv80OefU+^Pq4UvG7NKv}^H3Wp_{mA9uX$`Oxqev5o;D<@a^a#i{*H3$K z)hVm$7AQ_d>7a#<)MpqS6%DY=u**8rirFC4(5$4N3ii}kP%-WfL5{8kAw>5RV6ue% zUyQv|kSI~GrrW!1+qP}nwr$(CZQHhO+jjSE8?(|k@~ce1L1rLB#+rFciIr+DQ)}JUn)fM3ETpgbuLNmSLE*hEcpwJ z%mD8bPKe8EyRIX77u3K9-`<$gOT8}O!#K6yOi_o5!!FszPsSPZF^o9CM(q8E_ooXI z^Ev*nbwTa_*}A~=-}+Vlf1AkvOu%aXX9AY*bw-Mm$>Uv?lmHJHUSb>|;(*B83LgT3 z7zyT2NF}{Qs4?@z@C2}eRzf5mzN(ZCig2@~h?eqjX1(G_oMv0emg~*grj478+m`Lx z$Hw2n>)&m+vlA0WAmN88kFy=GxsJ1+za0OH5(nLQJq}0+JNcozg2j%zDm0PXFGLw8 zNFYTLl#shbBGRYnN^GIi50RDLO)|5z54lk@ZUe{PrA_br8A(s1O&Kffq3Y64kef8j zW3wDbJhl}l>Qtt6;+>H)eiK{!>d+_IX?{r*Oq)xTS-l4-t1_ld80Q*rVyqv&h;d2x zh5;3Zj0=>g9ha;d()Cj5+md6nPm!lI4h2ck?hh?9v<5y@8P(2^pRIL*vQQfua2qBm zFn5}vjrcRut4$k6DKdAO0gdoi28YLrQ$%P@9Ub_gn!T2&i}0LUfK;3RqAzG>7-`HSX?lA&YyyplSVjendTfCQHOzdAry=qhDI| zPWG+P5$uPsJ&OVE1kkVET;g3q1%D^VqZ8@`{K)Io?|DnfiP32`W(nogufk>B*J3`4%h|)L8_8ZP0JcPsIXSzz1`JA; zQ`Q}o7T0uJ^9Qh8;tYT{Uj+@=LW@IKV}U<|eGr`wTi=Nz%Jet;YMJT#v*8FOOd+V)1zO*2vFC|_0>=ehNlZ4w<+hs25@rOQV=}ZT)^l| z5vouR8v9SMBpR`-(PNaG!V2F7f)W+{smE$4cU+?E(dJE@%v!#(d~|8?Hgy9dv$)#;P(o@&pdBL5SS>4tpd!s^H#H)+uzi0iwoL7!9BtGu3?ncYFIw5-CxDu zO5H@k6oi$(a!H=6HcIjg)XFF4z(&WuG$FO0iSI+JO)tZ)T-)2z*`PerVnj+f=w}X> zkR_`5o=-xKd;%WKwi$&v8~AhXOoaTMu;7tU1LC`cz+*J%x{VrrI-cENWCfPRepdix zemwfZ686z$LYCMRAiHPoJJZ-lNwZP+9p`jG`t#G6xF255gcLAh75U_g% zpy`*tg?B*A4G-={NcP@ElMcoXb@4|pe``7&U-fPZgaUM$!R!NR=i>|BFV?Fw3F@ z+L%{^uO?H!+_9#bGH|U4lX|a*l^K}K65O$Jym?~U;7{4Q#k_3iT>kfy34Fo{avS=g zssk42*x)I08Uuu^IC_tLA$26Mj!nYz2@OPhf;yG++iM?ce~45QTrD)Fm7=7uIr^eVKzTx_as8w zQ`LS1g6!_&c;`B{T-Nh@48cDFevIdK(>Z~tooP8HWINXL77qOsxrb*<(zynX!|3xUe$N9 zqS?o_o}6|=)}TMQx9q8sw$is}jnR^Jq;K^b!zOa1d;5=RN!^;zj7Le)1jB3t3wV*KmYMnnLD8!=)`BSeV~4H?NMMrD05+8{H!am#r&5Li z@oE~8Q1=?#cFg4t9eXGfgbfkUZu@2eer$EKf!Y*ZoQ8Kx3n{DGYKNdX_kvBHcTlfy z6Kr6%Q{U$Y|66C!AzEjdEvwFwkvYm%Fk*pJ+eG^YjeAno!UHi z3v#`dA7!7v0zG$2a^0rP2z(M=67%T-*3NOekBouyW>`|ZZw17 zsfE0fM<6WbrX0crcAAW>Bn$R9!)K3Si^EM^qnJeXo^i_nuJxF^qu6Dt%VVrn28}u_8g?ra-xb&yyq@CAjmCy5^5ffI>6xVp2aPl z21-5{VXE>#T|!+g=8?9DpRpa4a+L~63o#RLcE+e`a4fVkSY@5ezw)1YUa!I`kK`3& zS#LO5ZxE%P2=nQL_Hrh9DTDHwhx)4f^P&~-7pDJ(RDY6QnLi26>l+;P?|zA<|Fyh7 z{VO@UjNl`BF7yoTIL0~G#C$SNQMM1XAT9qmlfYdzzg6#wroL59v!Nv|ifx_5V3E65 z3{u?0mX$Vc*;TGj@}17FYiXoVnO{ztr+*|BcdZfg&hYNIR1EaeyCWEB7EU9A%@DJZv!AFyZ{mYMUnmJ~ zsj?>|J|9qg9KdnilDB7W>LPtjF@p6dLuasVKFkx$rZkqc&UJzOm4zL7__R5bl^6X{CE&RFDoJOx6K>S$$LjL! zPKo2>_5$r(&E@6!;<5^d6!*p;JQhEh-1Zy-a-n^sdr4s&c)?;PQyp`88NPUeD@i~` z4~e!NX8Y)7jGM%h6++7L{O%OQrVA~GtT*sZ=dcPAaN(AolG7zbhP*xGsEcjG zgdZvDl6?qM=dXqwJyf*Ca3dm5W(rbxQ7Pkz&+Wd|h@s}l?}jnygqb7K3xuapstwxO z(YdS_YII7lA@HDL2SOs_nqB7{>~;`>h75ui4wNQw5uP~gCocQRYXM%mo;Xg|eiQxs zg8G94`u&3l(N2HjJiteK?iNh9&3`boG5@(T&w%aFno@p+NBfQDJU-#_J5W`u^IqWV zJ;`EeOI%Ng?cSThzfl0Z(M;t)YGY{#!y&A8XZxNiAZkpeXW z#Gp#XPwh49j#>>Tsa8(I)AyO2QH!PWYg_bZ2QJCB+*q>(Hbt>wGEpYFalgpUj=_FI$wqjVT zcfy?SRzd%yF0MlcB@u&GJ6L)L&OgBTYnp*|Gg`$mI&BX@l^Z3AiTu<~!3U?H(n1;fSs5AuZedmTsRC_f%ZA zN~^Tp-1iPVj}b28Ma_H|O+eTo^8=U$WE}GZUY{iOAGoEb-WGY^vWTrU+sFNdpHa3! zXBeuAXAQ8$NXa>1iV~bEGo8V00-<`dd&`V+o{{0m6d=*WOtHjZR+=KNOBHHr(XL$P zZkC=ZBdzhLU4Xo>gt<`4l4i3kdGfHyyqVuMB4`Nn1&>`CC)Mb*P?k^|Uz`b8#aoE0 zpzIew=qp< z2`2ogc!kw|Wd3>e%>V_7Tf0l93d2^I2~&1IbEi!cBhS zn^>wT<*rI8HT!1PhM0$lBL=&rHc+QD6zfeo8PUqt z{SLoeo=X+{0;UBg*bzCTQ+3Lb#IoEE;(OX@F#Nkb1|h+x+-}~DqtWC}KUBIf{I7%2 z_9R0#ZSMAU)TeDL7hcv|-C|nOStv8=6Cjktb*@cs`J^B{xC|gM$}S_CisRdgD1b}a zE*7cgk_Bg>^+4#W@Jd6~r$zlSXr(uy!oQA~rMwbQ&FK~lZ&0!vsA!H@sjKdIW0~wX z2sAH!LMmSuy#G!q^GNgJ%?j-q`Xs`3nMxHUxbu8v@^WQ{nJjapqQs3ZF}rhF{EaW| zk&?aPVQhZ=a|Whd>?5w!5?8MK*~ILITS_OG`Gphhyzk10^Sm>I*sg-wU3LEYH=0s!h0%s4_xln@4ia|=BAhQcz6;jyZb@Uj)LDp?B8EKDLe7x6$ zA8d`=Ul$^d*=AnWZ-(x5-4b%0#?U=P<#ca;qfjpqOni z6v#S_@q+de`=c5nhMlbkI7>!8b`P1tp-WVE9 zuVq8fnwhK2>$Lfh@vRQ^8C{pmCm7p=Si{OC6&AZ-)~?0q$|W@u`=q$SyDG~Qk@#%v zctw$1)iqv(rCeRM0LZgsS~l0XM8=1l=_(5JZlOQn+NwpswJKlte&PY?=V2SM$#sRU zGaK|~(Y9*UTIQv~6~mG8teCx~M6Qx2>ha-`TsN1m*b`lPb<(W-s%f_6ObJh1M_xbK z*n`uWwcw`-ZsOH6*v_BAS#Dn|e*)W7fZn%=wk1zd&y2?3L@oDL_aymfc=9)60VT^V zO5JP?%Q`m`<5~GfsdtenpS#79dCQa;kK`aF?=6aYJ3d&2AZMgWIeIo}h9zQGG;}xi zTSv_4Ny?_GT+s=W{{{gG@8`2G)2A-8XCSw@=ZLl)gHgoD?>%VX?JuxeER^%oYioS1 z+fXh3$+?<=m{&uV&+!VF^$UwSIh$}3+qIPXu3hBFtCJb+-vTNH4?fwITc)(vuU~9w z6>fFZK(4uGD1pedzU}M_qJb2%Z*lvR^f+LLUTEsk4nfXJFCRPrKYz(5Ab>CYnPt2{ zC2m2Lk0Rw7K2fv_y#mv32g|j*eBW=0PTk+ko2Y(Ss}nAj%sN5y3_ak=3YrfQ|KHzm zKvz6Z^d{7SSS*Pu?nEwRSQ-(6R=Q=D2h!M>7AKf zbv@4j=5KbB^Syk*ZxPBRy~2%;sb*2Xl~xOye@uy0@G|j)tW!i=lT&P!n~Sk>GS{oU zdXWlS%Zcg`>&tdVr}RLEL1ot7>EL=&=x2~wT5Uhr!PT`!l#G_AR&gcEQ_6H5l+)+4 zN~Q|O4P_FeWx|SUWkC~|vr1{-k)+B+6jl{U6-SWR$*Q?xG7d;sAL@UKdDM4H+P^y2 z9;F9KXJjI{@`JSUk|v=b6}hVN_l~1n5+Q?7isDTelu%X|){!`6-if)tnsx(bnv>Y; zPgACGoxy4bqo7k>Q9ZWxLr|hzqPOsa>;#+yuf~H`h8*jd9+ijFG%H8nhHuXC%*z#t z-Q;e(RGtW@Pb}>T+?8OhBL^+8aFcw73L#^agIjJ~TgaP+pv!p=I$PeVGde}jJg<{zw{en(~PCpqu z3+v2e;+j=H`riS*eMfj~U^H4Ca7yy_2fcQ*zfw{Zf%GA6eV+gDp1IyXj|W8lILwgq z_9~fHBFFYRRtEP|1(`$t=GTvYTjm99OrZkfgj*n|NM5coAd|~Ol;n;ljL-Q>W;U>^_IX`143YElWu}29;X3)VUB?LHK zG&p6dkvM-kJgRxg$LE$Ca=-%n>-jNXp zqzm_l+(L=Z$rnun794*-f`AAG_y>?bJ!zos+JN~4O8%g;6i`M+VHTvakx3Cp1_6xt zQ&Xr|v+By3!}(m+;#ykMl2d`R)gaU7^=gCoWnj+uch_l-=QZ1_@6qXR?$6(Q0Yb_$ zH5JSJt`v^R)mkpxtlbo^rTO`INvR9ml-rV=NtwKaFQrox&&DMmN|gC;%9}zk;m7=V zUvc>^l}#bItqX*PW~mZ}r*g$_U(*apFN-|IZw=LnS7l7OJ+)Jr30b<5G38A;zHzW; zp@JK+LJw_eXDTvk8p-Feg1){@-nZ<3-{i46sPkl0@C8BeUTh8Pm$VR>|8sNlnH%392|IW6o|PXjrd{?U#QT?n&uHZ)K` zraE=*q^*(l_s9NdJ{@Lsh&Pc{eic9`DhL;6;M5Wh|6UeHMyGz0fvcv~bM?5QHL(Vt zX0Aah+kw>47Pwe*)`GGqEq-~lJo+A|cg`DYe+!mrfd66laj0-51~Wc|Oeq(jUW+>v zFA!dRqYLRFy*U)=u*2gpc&4=t(U7CQmWgmpxkB3562y=;I_g0@9efsr{Jc4ek5bW< zc}|Wei)Uu8KytQHyfg)x72L*!Moeze5GD?SOfsvvb298!g|Q{enh zp(vGki6|d}mahbJTllGoL$p$%M5IBPxh}$LSuPT_bO_PH%6jWAv!Yo&;C=J-c(;8c zLAa#;BPgw|4G7larqc_wI=Xaes$uxC0KTazk?anv4HWY$2>gEqSvpBbujhI;sx^1hYq{|7_ zvu%=RnL)|Ap=up#wOZ2?WF<~AAx(N}2nza!m`#uJJ0wzEG^0an4U{EK2sP3bBdI&> zE(PYPC$~>Ax8PDwV^-moG2g(^=8}jJ&+U#^#r)M~Q=Ib7>1I_MKD-+M5wBdihPjnqT(6ayTNv*!Y%Hsk8u=+ zdN8wbs@8qjXN3YTMb&)-t2lXu?Yz3PIDC4AK_~1#4}dxXbc3IC1-IFSR~I~a_^T{PTZyG-%$*w@F0@bztIA zKNYyy13sgCF)>fbL^KoXSS(1y6mL>_Mjn*HlEXDH4uS20e&9&?F&-L3w zZGm|u+*P(!gpKkfHc_m4{nRRn_LgrkPXSo7^YqkMv_EhJ$1h+-zAA6$RjS=C zB5%PjEX%VX`6~&cMdi~;UPjXr2h$eVYx5<%LE_6xsXTC3>|tmQG%Zg7Y7Ru2Q_+;j z^hg%W1I?`LXOp?#4fT^+5ADY21-Yn$GcP2iY+-!MjgMCg<86~QIV}Kf083zx*l?dt z4ZdXYKcwg%W2Yaz?NZJ0!a5^pyF*}~2RKUg)%be)rkRjBoGT-Uf#yDBdf#?7`nqk4&UTB2_S84zzZMYJwJ zFKSioZHHyb7i6{d*#gdrcaZb51UeK#y%$$R7Hc4%ViRIVn5HSOm_P z)q%K!>+pTzHF9G%cC+S1Dq1KkyS^imFs(rcsEL1Aj$EmwmVlU9U0ER0NqWoKSB_m- zO&QWDMHjqyPtxv+!k{6DE98dWNmYy%>e)9;3vD2}YOFBLw{U=$&{o9=;<3qt0?TGA zk=2K1wN2m`kQ=8fRuGAGAI`^@WY0Ot7koRt4t@dR!~Bn@z5qRR?h@q` zE@T`nGiV`bNFG~CfXm!g3t}9B}ku>fyNYCPxeA|i>==+p^liTW+t;5=|f5MN!|1k0SUxbz6wi| z#A+eN%(`F_y}@`?jlrN;Y%$RV>`sLNhUTN;T$*ntId{~V9Wgb?fp}qebT9D59&=`! zIWG6FC4---J&g9O%$ydl7-U-t=8IV;D$FJvuHcee%I(fzb4u*O;kHPZH#E{I8?-%7 z_5mR0^z4ELxA>L+H$cvjwr?1+Z<;di(9kzz>P;ngy6zsDcZTyo z+RhQEZ)EL$%bVyo^Y7W-!_XJ)-?P^@fWA4fcOc&3z9Zisp1yv(hq-s6AEuw*k-TH} zcRUWG_oZx#ua4=#rSejz1ObZ-C8#^qJwm6-0L%;445hV2ZV#A__%f6SOv+)oQR^J; z(CKYTJSCv!aND%FiX>$zH-F0g33a+B3vGzqoWx4e=darNG056Jn?c&D{cse@_-vvU zcK-ss$qK@-rj|d-rL5937-lP>7#tz0Hun1i3EwpiSiZvHec}aP{kw@;g1x1v#hM;U zQo0a2o6CXp?cEh1DEpD6sA3TBS(=aomBL`V*v|T@MN@PIn9ktin$GTYbo^y0^MuZ` zh?PQNU+Rlb)H0}j=I+Z<4j8Q-Y0&vN`6E?vCsZlp_y0K{wL98~>k|q9AnAVt$o!w0 zg7&|oDZ~tHZ2p(bP1v$rmPZc#TGPgjR&dRM!YI_PKicoSV}FXmu!yVy)e%x8Ly$ zJt_;r!m(y(j&tYSho&~J&lM+`Dubrs!7Ko$R1S@81`djPTBWD1=AGka5lh{)!)SLKyzH!%_xDr#*%VIFK7oEbXJrG4iha zN+$~^&sEUyL53|ODiI@0d>+Zspwop`SH zOaIaOZx)-aXgksA-^y-62;TnIsZcEGSF2E{keG6D#7R|DEOnIyF;$-tRw!=nfiYAG zc|qgwK@W{X?>vPmapz}gIFp}xl=?Jg66>rt>xWf~9cP8}biU$PKLN$m9kc8&ZUuG> ziDeUPv9OxtjBs9{vfA59tdrD>S#9*O|n>*_0cc?5OT0be1E~MY8d38tZEo$wJV$Hj;46}^VTX#EJvBIaajEq z_Anot19;+JE$-z%@%evGg;4%?7Kw3`|Ym{b_$WEIS@yidm600-l@bnTjGMNbT8 z7vNa(t-IOl2ZN=;M0l}_Al=YEqM;bB>3_DjH49VnNvx)(g_ShW#330{4vb94>)`*O zu(WBbX-RRpNZ+W74Q>1E8nkz8twuPtzq;jpZhwB|eeQnt_t)6c0Spf?fLI6fK%N7$ zu@ndXhJDlm^ZU^PbSC7#$e=lqQsqN+Rv1h}E|!b^iJ6!3`PIf*LE0fp6UD8#SL9)G z35>%m1#M*v2F@=t+8rNxf?{Z9dz+34K0jhmX4|9D&TYSxscdrQ3Qe_f&v;=aSq&kV z)Gg|)@#<~nZEFnMe@pqs(QZ27*L(oUX>t&?EE?EA%{wxm96&$nj zclCL=^7(IdX=uk$*dm0_az3~*#dLgyrJNtSTu9|ux0IFIT+wcyGH25)F^^zKb<0*5 z?nJ#}0hNQm_gC6(>2493oZ8%Eb%Efo<;etGs;^MUoDmxwbj)mi@BTs6TE}HwIq%n? zlUP^jveJR*m%Qum>cuh}UrX<;qYu&w-2%=yPeFIy2d+&_>@w|n{zu>;9ay9DTE*Pz z_dh_a4sNB}_vd(74wbFqcM8{~6jUjRg3#T|07#M}o^roeeH!NSp99>vyWZ2vYR=1! z&eN&h#})?Vbk6~{&!XnXWiB?Knc0y|Zc21VxYlS}k5o^lp;Pq7&X4l=G>5-q5O6wW zx?|TDl}#~#D7x1^12{hHS)Ojq+2A&g(254e&c;UK57d`EtH$0RxGGpHV!jSHQ0^u$ z|K`SJtvf#6Q(tEBnr&%hSffm4bG)vfpZduQ86Olfx#eP(%xPoror|uMg?&4+^ZV0I zNoiP4lkzJZ0XHKwH+g4y}m zA@lk(Ovegpmq^5jkQ770z&0Vln6o0J=Sw`x*{e7xBE=or51Lo;?=gPW5aXwDf1`?| z?wrtPEYT#!>TmnbLN*9052CJ9h6PEw<7uAE*98mF=LZidE&doVb>^T^wdqv9)eaVt)|{sMrFgyP zhZyxA# zw95wBs#l5S=-f4 zCY^>sit#?bih-}Luolg@q1FucOWW%g77wV12W^PIjpN2Rb8vHqLIP-(4ZIP@wlp`w zR0U-w{^l1d*9&^^V-AkBNDpVqEc_)C62^EZF9HC{v`b1DHV$UMa0dZmTs_pZcy`nc zYCyqME~>OXTY(Q9Ff}iZKgg716TVXn3OHi14HvExH`XlzWufgFqSFpp1)oVzOZ4!e zV?qwBrx~+59!9F@mN|5EAEQ$!eDNQ~IU+-OVyVqb`IAJ_1g<--pY0w<4KwC71&NFZ>A^IK- ziH^cZY1$l^kdhFifI&3o&Nv??!M^9OW7N@JtW8N0mooiIA?m091YKk)$`buET%M|c zQ-p@jLa#Y=ZX#MouQ_FovxHL}`Yh2%!PpzDV}xuw!xBs>E z4`O{Li4l)hc+0gx_j;Tm3zHE_lM#+qL|PZ9n|Xg&J#5r6Dz(zqy~*up)ZZaCFL1H3 z2L0@THcte+aTRaOHhr*yc>(46r1Aruer{p5ZW_ z5-9HDP5UH%pm-iIALFL(aor$Z6SV7M-Sv6cqkJ<&_VL-FuM-^SWO+jbjxeC(H0;wL zL-=Tagtm9+r|<29v!KK}^adDcQAFEE?6b8%$=bcyCo~R#Y5`>(Sne2JxxEklHUW7z z$=RWB(%Ya{TtUyVPjARBB)}|_601UU7Kg@GkN}$q?r5n}9oSPLL$Ia%u~@zJltwSV zPqr?5xa&y*bbRY}{>!4s(rt_5|5x}g_Ah|@zn{zht>8`2#L3CTTJpcn<`NAkcV(5t zTF%!LSR1!!pCJ-p=;IZMXo5djnD+R@e}D+Y!S#nT=AAQ1ofmN){r%~d$uG%+g1{dz z5m-1c3keZX7BE!76z*GkMRPz>T)exkfcCEaY~AQPFW)+bw?D43IaORPmn*!eZhv2X zc!ZS)B_@vZ$#9ls!4mJ?C3$mYOBtS`y}7OConSxUJa_Za5-&tNDKelvIWm4^>&`<$ z#N>RPQdkG`)k?;#CXP$fo+G^Ih~DM$;%~jaccLE%b0Xt*@v_Z(3gy_%=i;@0;*3A! zILnuUhqs0KNK$(?=nGF8e9)u{gg%19kcN=Xmexm+`=ig^xs?UFdXrwerlLD{z;_s1ElJi?t5*UsLqP1`-yjOaPuFiYmuEZ02pLZ?p*pVtMZ-&f#{wAo91{&U(IY z5VMJHu^P--`iH_?uPL~ao*;L)Zf|npOfOMbq^y9R@mQ`Fj~@3QNowkN&`q?Svq1eW0tO~TtE^Nz7J?* zN?)EZIdPFT#D%tOXdRWuQjM{TWOexhP1=q8;=n&?5M6guV-pc#$)SM~v~dXlnL(GR zi3I_gaRRiFNtA=G#EHtRj|;q1*J@{<#{{Q^L;*9Rp;?!9kjgh&7(aYjm9M9m*UknX zW>?om+$&@T7i*8A=xC%ux4bbQWSsV*Iz&?VnuGz%)ItNVLp+bartI4FU=8+$6XdCI{>f}Yfg4Etu7eYj=yr5`ba ziFL$(6Vu8TID*zZfT>fux)pXJtPmZwpj%#Bc$XX_o$`)35XoLxs8Ww~L z`eRrkZ_#Wqgb38@w3RDq8IGaNKCt%a=xZ7!CTCIKa% zh`ECaGx>Ay0whqNd>oen@QiQv)5=cScg3wzvbgfTPdA0y-pF@Az{QoB1#Qa(rem93 z!_)<=R&}&^Qlp8o3X62EmZGjIQ(=j|qPno4+I8~!qP$1i$ZxaGufTKr^`V+@)dEdn zh&G%Fl`(@nVucU6ztDmYDH4y3V(PKoV}(!p(&3@=uCg_knj+Bvm1Vfrk|(Ra z#dV>fp{1pdA^fag?UE6lb&wOLNh_z*wt%f6Q6f2`r9y%vWdY&5K<{0|e#d!@Pgb&| zcnPQ*idLL2eK+-aFS0*(F@_ez*M_GD{?qOI1$=k*dNkFqHy`)vueT5<2jpkK_d|HM z^ZllLR}R`=(fATzncfvmJN5`^pCmB=$NLTGihy=}L+p^&bNlMvd7Xh$JQxU+SqGdJ z%JE*{j#4A(%~;!9!w`9CIW3V>W*DM6+6<4uLAP)a6n{t#+38rIH^-)Aa zcE@uyif-wmP2)ul!F{Q9OPQBxRY^7EJEOev&O2mfQMw>?xn3+F(F5F_l8ty#s@b@M zyD6Lj7q8&QMq&Y%Sfo2~Gg4Kk`z+ZQ1YXU z4u0OASXmLr!>Pq_krby@H%~ z`+!B;2Q+}CU#S(X(^2b!71QO&^A9ZAx8$6833H5FoFS`b z)0X5F>kDi#_aXCE`pC7jo4ebZOotmp#L%~N;&##* zWE&1s&n-nGH~bf~m?9O4uQuFdIIyL|5ks1S`7%fmxOXs$MOt2jy1E@GfyI)sD zP<;t~rS40FSj~1s9npKAa3z7#z-T#0BpO900rWb<9%i0W5PtQiQAXj1_bXF=2s&2b z;ZQ^d6OqLRbva5j|q9hG}ygANbLyv#~Mc~OVk>t;Wi03e` z=~A=nmN5_M7QKmP5==i>BQ;0X#n<($QO0i2#%{JkqduY0@R+jyhN?CxTTw@V)C_`e z`Zkax>57RlJ2};rdX`JdFG}6yaGlAI_)y;6{ zS!lFMOi8}NwJ;V7QsK~Q2o3!}Qw>RuxNz+kK>R3A^e3m#N^lA{)f0~~A82T{P4Lx? z_4rOLtXb>ntjbH{=iTL<4C+LL5dBC~EeV-0$eYK#F?G%qwf53)tH?B^P5J;Gw5>f! z_K9h5)F+(G1;k_r$52BZ#HnZ4ui1DuSm->%{3Q@;Lrd`9#&(aM1FB0OVw;yhXZ{3P z3Upvc7(f{=Pa*i@OZAnZ*txG~yD+KUcYj{>JuF|htqN)xYML1Zy|kQ(#`4jq{bLQG z_Tf~c?WUf}XFYhQEYFZ6u!Du3eU8~a_5 z$9Jl$ttR1zC-WDyb9;J^e+Qfr&;+(SHWepI=~@gsf!X0KzO&uw*N^O)zb3U-SyF8g z0oLPYXJ8y(CT45#_~fU+HS9`^@VuoDi!xyhh-P9u(N?5e>Yg-O_-n&m;GidoW-oAp zz1F%r1UZjl=@@jf={58@6)6t~cB120Yn;1kcrtc{ki{#ucUcI0AeSZ?IEi+d1td*M zH|w{N3*>4_Uf9@{ej)NDr7k`7ZbAc?^zph?!b$pCdM%axFqd8NlB6i7~7OuEy zy$}>v*g&?7+)N$}t{{p7N#}%Kb7bg3bG9^#J?!>CdviqBGyc(n4sAY3TYN5{cap?8 zUg`oo&iGUzd$_DV%E$V_eD;_jd&G!=DVEBeI}cQO$i)1Wsw0EUiA(O_1f3_Y>J2e> zvhU2IJG9CJsJQh``u1SM8*c8P%$>Hc-|Wsxd+t9n@^gQz!7r${2V2i3`^KHw!kdbBLgs8Lb9 z$4#Pii)u`*kzaY#G={K|Z@CvaGTABGp4Ck1cn38`wNb!5#7z3$D&(GNC8xcsp1}WV za7?#R*gf7%mU)Lg!2Fd5*(>67FUuT!t;F3e(cG?rJ^5TQ`0~%3>slf7m8Uu2xvcn# z*BpSWQhHZt3HU7y^~l3K8C!1h=a1TdsPOc(&xtuRSSSuK8;AOQ%Z!UNKYDkniR_!Ne3!C8^(&b+qQsMzFn2z2FlZ#EOod}%~4 z$3aeg2^C-C9sQsirq>BS=p<--IudTpC3JL_I=&1FQJX`0_e@~dz$1u!W-tuaC6Ro> zC{)g)5xsaErugtaSVD_j@T@{Fa)ape4M4BbBbHrRi;(zGRj7Rphx~SBQ0Y^XUiyo) z@}W2E{Qb93l#kr>JZ$9Rqsy@Lr=onN51|QKWf>zh-O4z;V$^;?|2X1(RDw`HIVxX) z1T#j1&^Vg{6|)Z|Dw_14@)VwKm(I4)CfSU(67FhHpk}Z|l#0PAoNAY&W_tvg(#RaF*?pzryyOO_0=E;4FJ6hJdYj@TdFY9C2Z~vl!{3wKEh7wzg9ev?CZzhU zx;0}qa!gJuqFsCjg&Ht!#l7KW?!`brXRtCFPR%GNnPSR-SC$haV`V<&wNp z?^aQxE_EJ=|6&rgCEgXtgnVmR+Y_E#sY7F?kmm^=X037OaJ?RJZI3FoGs2Q#aXx@=m^b^UC#~t|UxQ|N_^oI2k#m%NC zQV+&%a?^81NXhc*K1NwZE3VX9)5Zrfv@}TH8WbGVERda>844KY*gF1?xHx>b_?1BH z<2*NfT9_}?;fp+wcw`tL{{P_Y8-pz2l5M-owr$(CZQHi3F1xDBwr$(CZL7<8_07z^ z_r3Y?#k?DFBF_1FBKOYRD>GN-8ulaui$BYS8v)0G2+RSr1n6DX2O^pjq{e#=kM`ej z+`CxAW_qQ0`!e!+S`I}6xNG?s^9o2>@txBnlH=sC8vZ9mZ=3lSG|RU*R21glRb;6C zlTOJ$+G+o+$4shudd({*@jkJ96pGIm%`_B*DnJC?)D(vP`eCgxr@-*A36P`;j-MFY zRO&rL(f=c$2I|>JNbZ2K#|+)6w7-1OpdX4N0EUr*vpt`)Jb<94{@gDhI%o6x@`t%J?s$^AH~aNzoNP z>h>t;cn4+w+Kq)AIX;cZZ5pEMSckVacZ{4~g{Fq9(?9JZyx5Ip)zz|K1>wtZ_}L_t zuj#%`Y0!&x`c^GTAoK}zhCy%)khyUdEE1CDRt-r}`mPe}xW3NM*;CY=R4-Fawq3j2 z@dSr5y4ZAwH&QRMbycUNU*fG>i@DeZlC4M$FO4}nRXKY6Zsq8GSGDoi{W<2TeL40T zWBRV8t8UbXwe1BN;xF2?#UJKGp^U6mZNaEwtI0f@4_5*8>xElGb)W_?y6Pl{9V_&_ z$3qL+3fG>x+@8{ZUK~oF@}KgnVRY@~>yAvgZpu=5$<(v6&U~(~oDqr7$v=u!bu{g? z&NdsoKjPaOUKFPIbsi^XTO1XxbE~JJcy!hX|L9;l<<{RQR2xZq=NsNs=i)XEJ@9-i9hV<=#2s!L4=KW_dkm;I z=_PE(ESBtwvGwXr_Rgev*^1$?Aj;yERw7~;I3^nH*%>=?A&vAbvo>@ zRCpX!4LNS^@~KYDe~rPN}VhJywR~*tSd3Wmit~@GT8`wsnhs4_5M%1?E~RpH|}COvHEa@44qDg zUc6U7s}1i<5V>j{3G8UN^>`NfA06GUmz#A{V)Ek$RE@7aRQNeL4QSI`GxFWLZ0hZ#1x}w;)Z|!T1 zt%0@uLuf<~XX^3t)|5}1rnVV&Z9o22|vYCFGD3-z<1FeX&@bPGnTD41gf)!=ze z-59}C`D-(E4^~7gc|*Nyj#8 zurRI6As7~%qd|^8bSg^vV>=W~47v0AQFiV3;5pk-VX<` zr%H!lX!{+mGGS8=tUa*SZaC$xz3(fSs1>EysMcqntU#$07*gc&BY?b}ti;sMWDh?c zQB*hAZON;m*2$%)QavQU_lJjLNjK8`%0tsvDRuiDrpm6pTnkYvJ0G)7dX@yH45CoP zlJ7LjkX(PrS>a_{?zNY=BzK&sijp=$ObiP@-~vENfdi4ZUVf19Y31qWVSi^7)(rns&ATD-Z^VaEW+^F zYxt|e1)LL0Ai)SGHW*DnCOOxF(2!Hk_fK9iI#1-%zbMeF)(RpZ-Pw)iH zIad`!koA4JE`z42VKC0H$ADXbxyNB9X6eF`6&ha|=KWkdLx|2w-~?=U1T@vn{M(Oj2&Le8;YGLq-UL- zr*6b)|A%Xc3*gTPfMvk15CBgZ0w zdO~!Dy%_y^-3O+4HS}@1u_bkxk82w#VONL=O#U|L^zRbj>N|3DINZ8EG z*+sxLK={|`N5;%)gP1_)JemHCVWI`BT;6;MgZrevk!1IzdNNUJxc&|PDJIMfTNF; zgaJ<+Ujr6WvSn2HOLL5wmd^Z9aeF9q0~BTjoiLX!{b6_cD`>)dbtaxHXM2*){qfXu zCEqt+o0Xe>t;3O){cqp6!J)f9&Ng5TEbJa&_JhL~y2Q)mMrMZGS#37bc5z$=O>qJ{XiDIi`>6Q=6v<(X zlQ53wI++wwHIUA${ajsTqR{`PD^2HAl9sfBMq)WMV%wQ>bm60EZ_R9=&K6 zFprj^S)VZt61F4C8wcmx^hy)PemU4xHhTmN5hC)? z@^k!)UGL>RH0cRattyThdX2l!mNhaUcfUiXe$+DOHmCkZ>Y>jnX5RLhNPW(|{uHmxU+3wG7*kM*qd2xEvBeN`FVA8>!|dPQot28gQPcEKA9_$> zuzsCkkv|*ncnttu${qH@V1wuec^2XACwP(-WB4=x>{XuSX=S(6?#MzN0tfHC3o3fw zZ9YL=b;8X3vf+#vE9o0G$cHjwEQ3GLng88FW{8&_|}U{c?cf$3@o^T z$UvnvOhAPe3>YmzW^H!kdW1PCOQM||Ph5t+F|X4?_)@k_N1vLjsks9p^>d$REzCu^YGog%wm^uCoV zVtU`*i-&d(@|#?Mdi$#*i_?v>q;X>u_lTzJH|=isk>rby4r)i&>YSWyQ!M%+B|ibG zq!ET3{WJSQ7*AD5Lj^b4a5kiZ6|OvAO7Cj`qtLILW%w@Mg;r!o(ujm= zw5aE8aJIa<&5$*svaCN}YVvL7hO8eQmq!N82tPm30Xi^#>ID9%R&2OX={A?5Wd+M{ zAcG|#4qAI+t#zLT>aYxWlx{iPKLF8*O4oH-B+t`BH)B+5B;mdawfA6JPC_G`3Kh}v zA42n{#*>K{CUAbxW{~jc4Jeec&rwYi*fZ!C*eFF>9={V(m5b}#9eXX8_XzYM@9doD-=w0{AGc0X zmJj`)B+R_go}Y(dzojl8b@E=9$MLgb^V#o-(yPY{1~aj~@>P0{!IMdN76Aaj=tb-_q&Ix9Z_Q>~} zJpl^VUr=Ub0Q=*|JJ#Rj?p*&#?*1<}1<}906^tF7t(^Xu%V#QXTYk@fe%hpwSW9VF z-ajo^t4M2Va{wW;0ByoiEc!=xK?SY5Su@TR5S`k6CBQC&2>o4gm!ZY-*f}h2^Bs zqXsctg#CEHVV_#^C|}A=u$+bLrJH{gyftDv33p3y1sqdaiyIDviSb4^73aQu6H@lT zix&cl$qF|@Du8mKgc9yRu^XFv+;l;D(&9PL(QVOTLKD*8gK=ByJ|q#`ec`fW3^@Cl zhfGl?NohpqNr0VP$;rGb?2n*M$X+Z`skU(sre)2N4n;ZD5Fan$x%fWbO!cBte4H?- zF`XxW5f;*wk(!CEwsyq15gZl}ML>l)EXOF{Jlg|}$cki?Fq@n%2aYF-kI3hm0OGk35!8LN#Il~n=?=>!Sg_8Wtuj`xnDPT1qP zw?sDGDlG4KWEOB@X`4{hmg$j~ZyT_D`jX$X{AL(gh4k&$g=%>BE>V|ZFvGne)mWnc zor!n^`886h`9bzjs?>ROxWB>&Hu+4vf$e7~n#FwxLDMiOqd{;zTXI~>Lz1UE!HkZq zpYJE&R7~$7z|?-yu#`tyN>15(KCRFYZ-w4@2mIktAPJ@*4Wh8*4o&~!JSs|TVcugUmROGehEN+xC)u23KDt88(0!B zn7vs`q#!XENgTR%mUQrT#{P?n650D5K(E9V#F_M1K}98JXXkm{ZQSf1Hgx0kllE!* zk#v>pG}7Zuj8h1~_k)D`1O~Iozm|~^tBxXmLpII{G*?h8H%+;eE!umQTewgU-xNI_ zarQlbHX7g(SB~4$bl7>9JohqXh&gCqKSYpd;h;&R6#iT^(=2yx-KRjHd5pI&+tG6} z+;UDuq57IU*sfnlxQV*-xYiDR?|8&=vUtblA%Fu>5OiP0BQ#rr{Y~Hq~2Ps$|jpxR-2a2wLKVxyR(Mqxs=rGV_`YP)q^J%qw`~BSX`UhJiu1D>O z@KOXZuanlpK8;sj%*V(}=-9p7PVY^AsA&qtt=v)XLGIo#L)IU?!5EtZu9gE)SQ^F& zL=_zR< z(rkp2)UFbm^4koJks(DBaato$AdcZEfmJ2Qqkyz>Gv{W7;`qBI8Baq47b_bp9}}4# zZ7TDKR|xpSu{ zom6&aYh=dz7V^@x=C=)T(+Ris0lICxS&NY!CP_4ds0~b~MiG~rP_CtFfnGJz75Vq2 zaq<8cu&niQlOAjx+!B=+H=Cqi zlBcTy7Ag{nwELBm+MQc+_Y#;zw(Y(d?^VCg_A?h6wM>@C&Wmi2FvJ>cz_e^s-(VG< zM=!%Ze9Vp!uKh`!UZo+Pr41|879djH`)#8u zi-r$Ktb;Qag^0Z3mgpSqX+R+9TM5%^EpfDUts2r!wA^yw*7B7H6R)V|2{Ou0x2T}r zhYMKkm+<-bH$>glI`bu)CsdY4_SEI56;cp09(l2~DmKb46#i=cceZQoiD$*ieI+B+ zNm6XH7up|qoR3)~e*{1hV5t*M1f$dJvMY}18JINbB-T!e9o$kQ0v+-zW$NV4p~bz0 z#}lcmaV+=qOW@DcA%cV|U(dWTO#zcxtURGLVw$bmi#*Ti&Ew+m8@lF4UBQoiUejx` zKZBp)`$Fu00JzSV1s=g&m1?@qyl%BM27b!QCE&G%yai=|Rh@9-MH*M}&cCRpFI%L`+Vg zVB9DSQ~>#_U?mJY-hh?kYyjkJ07lbbIc!<@UhV*8Bklx)D{cj&Bd(YEnPArWd08w! zCFA!nrvNCismG2S?Ntbm6wvw z@A?|4X|dE6JGm~x9ORZ~UDxaf(4Anq908wzGM962x?-L{1E=~gBFrvW z1d6NK2V*`zOnDye^qmC1z!uSOAp5>oPInh+`JlS)H7_jrh_=3aQmnd?gMWr1J||?( zcP7@)vyq=Wj5WE0ugyh13?Z4^7Bsj*I4%UAoja7B{j77%N>c=F#H^A(yGlBg9Zg_t zBAuE$Ww&6PLo`TI(OJ_iJlpUbSp9OGu8H6j^No~(gtH&Uvxp~x!Y#xIT0#5VrjQ5|n%!xaL_Ao24| z77J8W8%w29>Z0a7Lque1?VpI8+|M@4`J3NtfcST?i1j~u*3F!)tY`&oZCs4q#J+$2 z3ydqQ%K*^BWfIgm$jiNeiA6%+iYMLd5vRq9Y3)VG7NRG`Zzegl1HJ$J8U^L;iD8(k z(?Q6Od!BKcn#gcmGuPG0&ia`HC=H8&bKz;%lY^1hE_j|e5Y#JQ?#)Zba$rDnfYi!l zZ{^fyxLZWZC4`t?Pszh1!I{m^E|-f!(>RhNv@jbR&ulKw)-foDKDpDdxW#8ra{?9( zCK19_9Itd}KyIH^hzJXV{_s`4hzabI4TS5--`wsm#Haiag88Q^Bo6Zdl(80$3&F^X zF)P=}CrdsU)a-ZYLLi!GiZ(S}>2J4Ef;8=qi4$O&>NzrwsaJHT&&Ny!)-M7EGcQ)t znfK95{%cj|cQm%{C2@|_Z&{gk$K8Qr#Y8kZvYEBKX(ciSvObnvh2S2-4nX5@ilB(Z z>Mm7_hC4IV$0g4X=)W>28Cwnn!Efjl_y5d?{X2Z+``?_CsIiT)gZ?)l`>z9=l<4P! z`z%^2s`UMHM0heN%taq%i{-2Y=aPq2eJ6e*kt8< zO^D0(mafjv4886C=n!oIPLn|q4U!Fu5;0+^^#y3lM?pcDmhnRi00*?iNQXLBwNpN=;sfT`Ooa^ZpiE1p6o}cra+B zh_oPRChf-4vZM%VH?#H*|LAq)r9l<+X5N1!vyfaNe#GBL;`6sh^0%V_|AvVFc>s+{ z>bCQIa9PrV7cFuUu2P}KK zYn_QFo;{of5d*CVL(M`b&fbtoNs@XP2!tZZ%&A{4v}*sRfJ=T#dMYGMtzFpyHYaO; zo#>MvZF0QEE|y2G*nXPGd`0CLqy!{`69pY%?aE}qHz!Psd96iZ&&Dmhw-3@P8V{*0 zz4ANkZiNPR{_}2YyFeLyMcPzYuXQT0M?{bSNW?eF=n$IYEp(f*$~0xP^Nht42+ZlG z+3zd3TpK{UC7>jv1Q5gk@%0B;r2q}eodte%uL80!cmFtYm%m%#k#6aWs^#^j(1yQe zXuDar_oyT2l}g+b+;#{kdSJ*+Ngc1qdqHsa(oH>vk4``Bj&ad(60_R$!O%Z6=SL0~ zHGuxgSihBj|7Y~%-(6nhKXQ3v8$&BwM{^rfT196&J6i`Q0evg0e{=l8*j@=hdbr@P z(nibj0M%_iT9Df%stB+%V@cGxgk~r3^+c;Wllp+_qh8RP+ySfdLRQC*D=<1BX7fld-WGcVV|RUV9F#?5j`wr?>b z1z-O93J2W1XrA)pJIQ4}Lxh=;{i9#zfkt#)2PL}B_WqA0TKQ9CJV)QwJosB{^8SBb z+<#j0`wIVcb^rBLDQnvziXw4aR=b8-^Q5))ruYD_)w%dlL*o*&*n~}*=Ckyf$MOlR zS&2*$crI&HQ}$xYen4IdX1^(vRxZdj!iJjqAf2VIP6lKWtcpDzO>J@>f6tkE-0dB9 zPyfj1zvQ}mc7Sngp~9tfUznwnPl}*)XPPD3q4cu;t^g_{QbUUd6Fg*W6@i85?D+bY zSMs-4?&?wAgv9NOrpwq8IRJ$;b$s##?n3Y)K9C7F@yXMK0F&VKgrP2$Su46)riwHQfVL%1Y&B?X%0+#vk23xpw zp)xaXG!|`bWMvh%i5IEVNS}r*bLo0}L>@-_E{o_{l%l<$#ko#e2y`P1J!&zgA$g9_2CJAKhe$rWZLE^Q|XmV~f zLs?lm7R)t1$)u7ZJAt-(q%Z2sehBg+`t{Z$=Fn`W%8L~3S5?bZ=_=Owhk9#aD8!m@N8k&=RzCo3FhSL> z2fU~}%i*yIJS%@7ZTFwZTanbn^4tes4`oJnFZQd)Rto!@$4sUEQu4_?B`eRnF^54b z#n~YO+hMNfd_S4MaJG?WINJ^=7(<=5!9VR5+6GelXw#C@bMN#iZhf7@=-ty3(<1^p zX~UMjg5}hg1d8=8ah2Hf*#f@N8#Ix;FB}oD&suVY<3zl&_^4vuadOEw`1Q;t;DIqW zwH<-zgAPVSzl@ZK3QxE|)P75!$rk)6EchfdJ`3APnD7peMQl}Vjc0CM(;az_gJ4v; z3rA3hgharPFhmze?)MqmAXoDms!2s+d3yu0@}yAv%+3X^9m5P81K5o$raRp)ShCdt zq`m;8jx^UcxMG?j(ojXT6Aa*evj%vYvTPaR(IQ0lL~$W-2~in8N=z;&{@URKnfsOP z<6rs(!Ob~pCrdv7O|oTH;_wv44^DCh}=Lh#MnI zd{|BN&Y+qH7t9N ziu#0=Bnn{2J7uyQ0ZO65B(jo3$DkI6=;uJusawuiV@cQpTqqr0b3KT2?E@e zdL)r_k#sV<^tCx~BJf3MRJCP9!Pl()BI+kt_>&YVmLefF$^)=LM-8!4V5b$aIH>*X z^zSvh31595gdOijK~KrLB3%lJxr*L`@?S+PHJ2QA*6Qo9;Ar zLrpOETFVkM(etTtT@|}x&VJSZihL`9bmCCa%DkRBJ02YrwStS78n!RDbo4+zJ#ZvpO0AZg5KP@c`D#AA6j5Ll64Fy) zh@|js))vJvoP4Tf@nzH4RjZ~pn;@|_3}0pnjqs%m9(`l$ai_jYF~G z=W%hcL@0=N=G25#44T5mtxmq>U^~hPV^4M36L-?{<&o94VPi;k+oF^2v7rdhrqEdX zX5X%jg-yKaq`qBSm?$u)Ow%NEuCvL(+LyCMSrVkIwNPbDXUvYlZHnjLfC>5^yg ztlxI)49~D@O)erx*#XB&TrsFh4+h=gsP^&##~_T#w+K2acH)DSZpv=H(!H|E?@+v| zw{0_Ci0sIQY!y4u$jSD?gS0|HwtLjzZ#E}FyqU|A(fX;S@I1#t#wi;3hU-bxk<;bR zg>;{k?;3;aEoFPGEk)mYFjPCu6h0xY#19(}%tJm+No~{NkBlvb%Msz@<<8#p^)Z+- zm)^yM80Ee+8q1ce8m0|*WS-TQA1OhgO&+rnDLV*^`c9Slai%BKc1WM?L+#)kmIS=6GA0hyQOiiZ^}gI$X_+PLL@ znlzZEf25a|DY#PXvQQIEQoMG>L|8XuKz}{Sb>&z#y|rC%RY;@P8?&bK%L}z~{ET=9 z>cFYrw>jxZC+(D4&ui7P`Z%PHgjM3a8$v5(e#di#IB{?ev)O4J!Au(;Gf+3(3_VvF zK?1z*LT+P$QL}<`y*odo5o^Kx*$_T8LK~+ti&YvS4}%vCcL>x*Mp~LG49Dcv zw+)8_f9s^21F^`Gl^}{*>)nvWKuua|0ls6#m0F<(x?O!Jd?6LG7bbQ>*ieK?kShkL z2;~*DP7^4*Oy~e?ZJ=GyyN(WC_?x+XaO*L&Z#Rk+{u2#b=-4rvD9~WM3NPM(XYaCP z=MhgU0#Xvyd!}w>^cIdC-LMzSWDSwc&sLsesC$?`5YY`P;eBj!AB#7CT5x!rEv%W% zF$%ZcR|wo!bQSnbU%)AHd%^n|gtu(k5bmQu5WeOG$V-Db2iSKAPzyC@xt!?Y$G-SJ z0SMXX1JCg0Q@zwvRbBe+rHOa@X4fXpw#`tp=geQ9^ukT!cz0b@aURi5Ja-)>jk(I& z2CTTS95kNpi4$cmoDEzH*h?QwmppEz-YdTn5C^h1ES=t6qo@`(RAOLVhu_@pWdXEy zdE5=U=Bh`voU>Io*>dwrz^*{{4*_)zH4oWAl7(+r@hC|;;UnX~*(RfbZY6Hvz`p*& zFXjd}P>kMLR$Y7(Izj%D2Uo~bT6sszT@qS5ZzIUr)dW{Pf@lP3+(w=&#x}5+ePGV` z{=cR-I>zG)Mx%%RU z8am2LNx%R7^*8ZkcH$Nz&^v^WN)J;v55X;Y@`StZ#xwX8l;nm7@&FLEYTwHH$pBP; zU69;=oqozW%FNUOk&EG*pXAjNT=t8G=%=)wPaRtyHvbj69c-9X_6M7Ur%vt@BF(hT z5cL2)ZcDC(yXR6}S7W3t^}gV<^(WUUe3IYu7v~q~U&+)UP17Mg{o4T*{k{QlS)r!FIBg*Jqx?^G6gqeN}86=_-Qffc4$!mIN4uA4LHCmksx z09bxhFFb#_j`S5W&AY2>G7bb3T@)l<@a;a+HS;(H(9Hwvhj^H|!_$zh(v$9g zV5Yuc{IS;W6zJ~-SULZrBbWhZGRoKHGkq<$bDi~%V)OBOCj0oc zSROlswIXMKo6VxwSOl_|Fm7yFdy|dZ7TPV_6<`;CZD(A8b^!r1Rj_a&>>Mzjeo!JH zgc#o-Sgrwf*CBEH{(M9txkOIWsf~NiY0s%YA={nzIDX|f0$9m<9Kp;jzmwP9*n7q= z?Va{vbgm8#tJqWoA`C%9x1D26FO(T?(nn|z@8dK|rjl>k|1l&4z~7_*7ou!4ZZZBDSDc)8ibUyww}GvY zXqTT~WZb3+q;m~zrLEWNrPu#f1k}fQf#AL^Pe<)->+K@qO45iPJ$x4+{Z`C0eBhdm z?lNv7t#|)YzM;;*rf?a2CF2%`b$Y2OK#>pBkWi0Kn72d9w6LE1#K!qv0iwW=z08Jx zSuZ_~P3YPD=g1d4NrzTtBECu;z4_vVBVEhM+LTPz4Zc!=+7civ?dobVrWFgxfA@zl zVL$o3DLhPew8db-vHuUXuJ&JoYw*;Hu9Ff)dP^IQTk4w0D)vs5PF^u4=D|7^L)`d{ ztcF=N=QdFSJqiGsm25~V^BT`M^P|Y!L;`7wNGnb{G%F~BZWH7PHl$(O1*%NTTysKF zS%dM1c}tb~(JGZ^#MK^J?RlJO%0%r6%A&jmYk$&IjQ~(TZ@{psSz>ytP_jh;N$eoe zvD4|GB^}RUc6}bojcHqiyD{LFCABDjlbkW?WcvO|XBu8AgV~@;o~c-~{Da<&moMb; zTU6-&J&5v-Ea-&{Ebaq)z#RO~y(SPFkN$FIo=@gzG2>8Dg{iO7!(L0cqY`AI4eMNZpPBjxc;47Zpq`Rby7PToN=L;6?bUE5EkAIZE!Z4Wkf}kxod-uFh2Qnm?%g z9}6SgUqMX6Xu8UezZ=u0@_ofsZVC&$hZ-c_qT1bJKi=#m_Z3Cg0ezt>%Z6@+=<;0v9)3wyv2Z2DqYpZd>(6~4(3W?V&Qh!pT{@;UjT972b!$(|dV z6+4GESQB+fiy1I}^RizjnFU-TaB zSiIjD9u7X@9@5P?nQi%$815Cq&a7{KgT21Arr4DzyFKOgsV1mO?>4#b-kekSu~Jh= zMft!_#;HusM?lPX-25628^1l#-*xV&xrc6Gg|o!dvBH~$Fc%wvH0JX>>faP3SEuYg zrn?Bl&Ef8_RBr43`CC!CcK70S+8CM$6`?aj0ZJ{=1~an+VQ;sdsWNT3AsnGw#{y%p z@ga(-aWe#HR50b(Ef$h7;=vV4v^^i%si;r;S@4#+LhM&mM!Z7Gs`A93LM@G!-T^{K zr+39MO?pTl+p#Tk*8sA=7wKUnx+C zH4L|-+HVP{$7y}${aC*`Kjsthr`U!_5Z@CfkdDdfokIU2iVQAQe}^OhV}7c_*yxpj zXq1~?lIN*xQ7kP!tpx!YO|ha&yiB1PW+PynA&WK-qgyiM9>WzG)|gE<2-dmDeHboC zL|;K*Ur}h%TiJI=+PUqoTig!+uRXwyNZDInuL#v&J(dJvihB|rbhGD={S14u5hLTKf}{xEkk6bBU}yBvGu zXej7fvPw|vgB%-tN&xMH7#9Q<=r%~??{RISpf7vLc?)tW%W`QV|!1o3-n!r+pFlSJiW+e*3) z@m%50IMVR8-32x;IDerGC^y^W$NLi${Cq0)qp0v~)ABqt|wDY;1b1S&S4Pigr16v7ciZbvw-sfn#Q zH{xIpa^()2l>-$^=M=mfK$#T;s^>9k=VDBW4ht?1OD#q5JIZbu6ugH@KI)1w61@eI^gC#=q7T=vC0RS6lYGpw zjB7&a4%~UQIM`Y7P=wS`2|sFf6buFWD%kdZy4~{Wm4ZmR&-9q)h*mu8R z@bGE(GD9!h3%YfT+SyE0`vt?=O9~1yVdlMnrS~0LLs#!4n&}v~+@(zAK(&6HMj-_U z-b-S>RIs_3u5WA;sYVam*|SJAeq7?=rl?vZwpm1a{s<(9S;2(qPd3~n6Ckiprr-Ky zf||8ghEX*7_K~Vkiez8T{+t2tN=}Gl+-ta?zOr5#I;8*=%nY1O=eH~0QNzu?zqax; zP$%`cw{pbB|8$QvcxC=78&Mf`^=|%(J6z8cPihVg{`%8GAGAX59Vg7TB)P|N0Y@+% zK$kBZInMarEoT3B zN&K8I20?8hx6ggj|GD83*MNom3Czx>G)R!NW zKFr`nRY|;9jCd2Eb#gQXSq)=~o+)u5qW^fT0`PZnC?K=Pe8M2Q!F4pORY0tYY;+QK zv~@u;>~`<7uv#obfDUty=!ONKj{GzzB~~Ga6Rf(f%mZKM(|VvKIK zP(N?}*B(oj2OJ5zo`V7d_)Blin<(_(5nD>%!(GhQ%ILqEZj}nsvg>?s-U+mrh7xH_ zeB>qkWB9u>-;8(QGJ$X97c#7XST>ssWdkEm!gZusUF9`E1hJ2wAM&BAa6Aiyr#LRA zCdZSWjP1U*Ri8grde)%s)STpc;(s;6)TuSyO!YzZZe2UUx^hfb2Z?A71LBL$VN&d# z(k;jn2&BUBhWpRuO6)tvMFvwma-)YnNIeNJw^-CK;vqG?kI3>O)-A5V<1a6G3#Zt= z#hqmYb0g!9>GZ@YXfnQw4Rzg;_G)oFAO_4Q@lJK0=2RO5wBrg>*nlvIBW+)D>uP_i z#Xve29G4Q6E}T2}xiqpUFFz)sO1-+Yy)r#6WZ7b*wNJm;5p+wUqFA9a+JR+fNt;4+ zkT!e{V}S`1N&zuoga&@|2o)fW0l;+26s0`!^>MoCg?}c#RHNu6Ql;0{{uUmZh$gJR z0OwIByE{)F(W;5_ANSP9+8D&TzS0KJ*&&u|knbx8cQf_^Jn-@Ni5AZ?uE~;q8P&73mSFDEK_B4ezGA}LRG(9vuc3mgxCVt)<7+T$c3B_?0cZIlHG75Vh-+m|7_SN zLBCdo>uE%8L2o8g3(_?9;_D^aAlVOuNZzE;;VICAxQewee*UP5j3G-2Yp0M4Yp1-C z_mbkeinFhdd^6gp)`Q`x+9Bi0*#YA!(W7wzTN5;R07uV8qJ@oUl_h7x$wo2t6&WG~ zur1EHK!C(W-tbZxG7OlbC1VE$bkpj!;lekh^CP`Yj4Vc`8e{}8kOj^f+zdFL4x`RS zb@1jNa%9L#-eFcGm+U*8B(LWzC~Q=V!3i()@KhX?Dp9TXkb!YNFV)#(coQ(6Y=9aU zBaSk1E#X;P(m(Ua4B}fjk+D!&S|B#k?xVsT?viQ~WsOQn0#jdCxRq1tIFrOYn}Xv~ zD-HTqM?-Uu#ULW{=+L|tYb@9!k}~JfT`&7pmlOw9xjd)!xnLF^F^?Ih>#7!nyeA{B zP!pY~M=)t3jO(a?yf!fDu}h{uv>uTA{XG)m-J5;lA0SS4f5%J5uZ z)xrp>e32-E;ZcIDIRs&$$Vh>e5S%(;mi(izidpB-VPB+Ibxcd|UhvXAp=maYi>r-8 zNkOW9aWk>OiLsP8Lr>{grM~?> zXyJ%xooBMGi8!0A!Hp|kf+OIz#-71-2Y>Jph;s?VGzkc`%Kh@dHG zEsW4=L0WQK1}Y{ik}=-`K_(MUf}(U-uzV5?e=HIh!6Z@)TDk)UqdLrQ+Nd3EM{>3n zsJqm5aWawyZF8UlzMfQTRJ-TF!X(n)?(8Re6r-i2gadFV*z`3o)s*sUW9nL^rlmrd zkOihbrZuf}JKUhl{B6)$?ItJQmFR-~E%H9!Y<+DI{Bonw$XPB%P{Q!ZFH%-8-ixI< zC{S~c__#5XyOPgc*R4XQF|l|gm)wp*YXe$Yc>@gwn*nCY12y&}G5S>m#u{U_WP~dF zUG1-I1V!@=ocVcxq={E^`}QvVMJ09Tn?f~LxLNN@(p?fz%3S%ZrK)>#lIGtoJow3J zd5LBemO~HB!C;j0A}Agaz{M0xd%(z)cERC`CCPAD@E3a?@m7B-7a6!K#+8L;atxx} zyx?gi*z#JO8qF=d1zZ`r3iig`#0TMYl4{DnWy$s^-F|hQ^Q@GtM7owfQ|QRwGIxws z956JLJ#%#R+RRH&Ob9tk4zk)8hTHBkqi?I+VqYlUYUdUh+rVv(>=uZy5(p))`11`u z-FWXZ@XFl^zKccrRO~tPzkzSX+J%=#{IbAbp5Jq4V4@>9O>r#*l*$34-= zzHFHemrhm20j2gWYgeE~L{R6Za9IqEPs^z7k>wr)lPHNyLW})VP(^j-2eVWZ?{?$% zQIc8Gby^;WwZshrMNF~E|HIikHhJ>yTi(@O=(26wwr$(4E}LDpZQHiZF59;KD^LB; zo^#Kc{a_;Q9g&gw0y6W8FV_03#*RO$k|JXyEO{{{+>YbOXrLN({TjQ)`IFbE*ian# z8XiSG6XL_u43*jT-k%s9(Je{%_)!t1AVaJro0Orf8$r22Pdf-`+=rf&%UD>FiUA@0 zQtbATmb^#KkF`k2^p2H>8Q4rL;lndYs8Ew8paz3#j3tY@S6~$<9)!>$-(jo#t(jajASms;7rQUL}i?7u{APReiK7B zHrCdf+nTEC4rx3)zkXP`3Lwki0dzB-BVvMz_4sMyfJJ)ac9?s$c3%|Og)9{pXN_c%wWBA zn-0FE#lCc)%3$XV%{t$}L$T+104X}l@Qs&Kz3rCa2DUf?9e&)Pgxt~6KIr4*IPUD< zGu!as{8%t#><5o;12wKnV;XV55vaqZ@#S$yMIq`l#n9wXy-!3j_DStyjh-3~=JqtZ zt%~f~65HL@VBa*m)-uUqo=Bt1JQxyvD9$6Ph=!ve3M zoZ>G3DL#)x!Gja-*NQ9Wj$$;SN-VE%mGpK1QNJ#%=|$gPY}25LfWr=Z;;t>Uhs$9r z2-iIV21v=301g9pct@^)EdlIBj6_Fv51@Moc2l5{;Ew{cXsRg?|Ib{uke5E+566Wp zb`SUwS1`~lDm3sj2w--G%8TB(r^p<~sYsb(o<9O6aYm8`+OXTIqTZANjkYKs`Xisw z`NjPY`tp}Q%3VoK^hAf6OfNnX@Qp# zLPNglOg-PfaWp}5ivGF5!pGME-GWqZ!XtIy<}>RpFUQvT{iNfXe1;lSMeT57KW08 zdWxVCjpcxFfrG%=a{8hC#_2&vR{Wt_bkopUMsxRz)$Bu<+A*)2d};)K`Jhx=l!VTz^!<@A5GSpRI|z> zB1`&;*cW45q%;(gfLdS%Xn-&lM0kKOEYGjmg|UseAR+DaZ{X0L=Em>MD*skRhGv&O znjcDWYeBy+&s3Y1*4E7Q-X1hk%$jNrKYAQ(Ng>v48TYBiY^QjhvmLwta6NC7d_At< z5^|<}os>kRIhkg$@U^XwM0JE7)sM(wdKQ&PO_L!-yfX)U%pp%y5p?-Zk#MHGQj7_O zyOG1)&%^VIrZe&-Im~cvbARH&uq23$ZrWw>9g-!8omjn|s^e0yjYu*{!pAJV%>O)L z=Zo5981mwdNg5#oya@A3m_{Kf4nwUuU}WLT1WAAAk|q?UQBNXUP=XG)r7weFyMN(@=rz2jRvQhwLvcAi=82%rBsYRR}I+OvLq)I7J3rfzq1isUES3V&N zIXRf_MbL|$bmP3~eK2#GI)9@&C5<02@+!tW*Tnu5RwtWAP31f)QN=93IC_WQ9T#zk z>3a*5v>ak47i%1cig$}Fsn1nDPSH8&+f%hjAU#fzg#eKsXd66mXBl~~5p%8%Ue?oA zJNl0yNfF0e6cacf2QLRvaWT%So9HlSrA;a;<5@?AFyT-{oc;w4K3*VE{N9Qhv(K5T zh$3EIhPk!Z^JH3N=&t@IS*w!%ZDhi^YFd;ZXIIJCz&oqBYF@;+6uf#5w8}+>8Do0H z&^BR7%DktTW&R_6uHAe?b7^+VstB`xl7SmTHKq4;*p8C&c}mE&mI4gs1_geuKCVEM%N}G`kC;2x|l-44Y1)e%j<%y$XNC?oVfgDKVf%pbn&j zJ`z_tS7@WFZ!U4tst$6>=-gI<4FnNXRvE|3ufq0Stjjcv34 zW{mX*euS;2XBlwi*Cm@Qc@#_CRYy25v~QGe@Q9Tlz8s*V2Q7|8M>ehK7LyhtN`%c& zY9~g_G#Lk$x!kb7;j65x54wCbVG*h-4#q8UgvlsYBx#%^$~ZrDTd2PT2Dr+0ml}Q1 zJD?C^W$j$bk|5IC{?TE^Q5h&XG&492GSmzoE()>h5HviP3qYr|s!@YXTO1~;6UHP} z!3jn_PChn7QoT+ezc>rpRhLG*=L}2$UjULo9eZlpni3R|QYMR`M(S5$znc2Ib zi9YsBY9roS1#_-0754DX#)Yd#KUKBJ4AqFt%rwQSyx$iX|Q=tKR5Z-k@=q z*rhYI9>M}QMVwWo%xb~3$8Z+4=%jzc?pgnYSeSO}1`_M^Qo#kV-H2vQvjLB;0@q<@eb(e+hzv*X!}6jj;b0atM6a{tiR&~^h|KUc*o)~ z0t~uyEK1|ms4L48g`qi_00@2W1g|ml}7ihF+KLy%brgP`H|0A>WZYaN2f7Sfv{QXxz zc7BOteK=8J3=x9iqfIwe%AU6bwP{nZ(aO0=qkM(^Ub$3?O5B(VmuU-aWT8`V9>nBJLGBg;AIpWp&vxRtDexeOufrRi)y@N%oD9k(!oF;q zNEtN|Z>Pzu*Ss)qpiH+g8bA24>OPPxRyr}9sobY{7g)FDfolNE$uGC%xKQ&XhHu>@J*wcGmLbtsiP(X=UK))7$0cOmOOONK?4){#Q+cUs8^YIiEB7 zq|59odbG3pUG)0+0u|L$;&N#(T5m$o?!xdETqD?ig8G#vsxFxR88zg3p4T=H%bJ-+ zGax7+5e3Y;3fKY)_bdU2qp?<4$K?TG!b!HR=p6g};4oly8l{t>f~Rh(9z}%;4;gu# z4oHh2MAd5N&hIMI4em6wg-kQwan6qHEF?J8QrmafHLGVy-Qmt}Pz& zH?^rdfYzjaN+G4w`3kL9xzjTG@G1E5CdA3R?s$u-T;h=9&)I^Oro_SZ$BZHg*+>!T z5%HuhIbnxMm@?PA{IOdDK^^@YguWMi-aZlsypB9QJeMx#^BqqZ7q$eyFp-FGec7tK z^^oDI9~tBimX+sbJ`VF|JKfCVxBjf?5)3B>1O|&c513`Tec6IZX5^2F6Ng5%oiT2Q z-JDS^hVBf20L!uDqeNS9b2zuJBZ|ksVpmGHpjri8ch`eTI~YC4QWIE!ivAt~G`H9C)e762F z@)H*J1%&?duBIkKKbQSnV6GV&ife*BKHyMUkO~>#uK#nsVMppz^p_XKW?*))2ODsl z)MK}33qST8(t&Q!yXs%W1Iyml+G;iFi^H)+xYJ|$kNXd|xdw6PH9;*D#m(JQ)(4p5 zG1Rr>#f?kIU7QeMbawb%PJC@2^g!1+oe&W>vdt_JH#q2H#SuL9c9K( z`1E!E^CfTbhz9Y9)AMo7LRY%W-cr3OV(b~8kgagLDA3IqB@6H+#=Ujsp(C|st8eb zD7Lq6lsr|jnOX8v-T3b-(0i^?5E+yQnABmmQzs8!!dB5!uJDqi)E3|IQ}0y2%1{bN zg2j$8hRjq(G?~Xi?G4}GKek}eqa_}FpMa2=;GW)S9)u~j!JLW|svza1c51sNJddKf zqaOhv=`%JRp`=)~PvST;`A2QelP#$Qs_h4W986 zGE70v?$|WKzPA9`K4(C7kZE=S$pd%e1J>`tlpXt?f~E(|EU})Fh!dETN4keUuT)*K zwzE02K3I<1BVT-{z)v$Fk^@>hYa?^yMFw!DF(ub?vXJ~rix2obAQ_twn>>-ThK&uU z2oKQu>w+#*yk#!!*ta6m)tn`S`=);{`dxy9hp<*|4eef}nha7`kpUvm9Jrp7c60y2S9#w`3GEprg}ueS13kZltGSF)7jT zgOW~loFtDwk7cfHIFtI$V(t00O*{-hv-m^1qsA8AO`B_4oM z<_oy}vJb)@pyi6u+#o;VO6Ih zV`^q1=VBtaB8t99}-Av!@~4BJ1h_ttKZzyPme+kyD!gIpW{b27e3u7&ijy+~A*H zoH)~F@*Fu3Q0kCS>Y@>CerGRMuh49BXl^J?x9L_-Yo1VmHcHSmwyK`E_1DRPKVDAoYYB z029gs85R_J0y17C!tN;8r=0DvH6=ASFiybR;%xU-PGq)0Le>F7n^l8e-wEb^wK)L^ zZeL_VY*du=GI71spCQ~or{=OBoQ^FBk4Ga zXm}@juQ#5!bUGA>hr-C^GC_(g?;`*>&MASA36YdX3ekfHOH%!vqm>K^PE;7io)bCO zlmT7=a`OjD?mN1OMUI!DJ+0Z6Dtd%eJO1pDHYzE*jw776Qvvn=v0+sbSBwC?a%f0T zFM|^HV}aQAL9!zSD>5+}i0fEH6d($ivZN`1X_dIhzn2k$_YL4JX^SE4wb1pQ?-VEP z5jFyt*gbO%W-ps#^h8(Q|61$y$+vuwSsV5d4R(*f-FH2K_{8cOzn;5(;qeIBE_nt3 zF9CRH58>R=eg2Nz@wNJYjm-n}xW$aBmzZ_)+T5Cs4qYZkmVb+Ms@&i6Xfp6sV!X$* z2KrRM94rKsk^8xb_cv8u3dbruLL%^S;gnAs=AOP;}G3e|Q)Ie(W* zE-1D1*6E5U|B>N1=H*m6WMkX#;5F@(E%Jh!EaaQPvjEqNm}QekNx|1|EOq~36GHVF z_89>E358Q~R^ZE?xj)Fn60?61Ly+4Efwqhv1yx7l*AQ@BHyZr~VTIxaeb&+w|BI2l z`0FP(-L!$I&NFMFjtt&+B2KVZ=TEs$EFM1MjZjX@Ul^L;YY31(DUEaUUB7{$JvRWLkVit_!HEne8OZ1Ldsz=XHUc(5{Lw zoPpe$T&JACa=3NC}LNoG?fpB9e)4210B2{@ll# zDz>4_E>#0V?58~&$fty|x~&;kg`1KBZF=>&*U2i{%Xy%4-u&|UN8kXSev5^H0tB?c z|34?P|1NNl_)jLX@(#9kCJs&(CXPb3)^^TL|E+l$QV;V)HpB5I^OSaB1d#-mAXk;w zjGw992m&!56@bxUrI7OffkM_XV5;wGnwAA4p=DJiUf$TWR3Klm@LS~khp>2VnRQna z?&DL;t$XD)Tf=G~ywm2P`|Hikr0YlZ^P5hF>*vR72GG)e4kT+YtbH;{08+osXxM6P zBod_m)~YzT4!X(>IBwEysy}6B;%ymxPfWxvg#DcbDAY|MIt)3ka?oZ!MdDVp<+yFVXJEX7m zG46ADZB-4`9Ml=s`o&_uOTysABb;wL%1#%mmwYROQ8Nli4vaM_`nFT^2@jTSJpMQ&n+2nX69^ zDTxX$|E*;*KKCHps2RbT*jibo%wx4l8+a8D$(A(fn53?G)C@i~rl59E##-v<7!eO5 z5?$Iol>aN9o}SQ9rahgxe`!KdpRf_I4l{4(B6-8+#QJnUZ$LtBZZJsyXim#hy8hPG zhwO?fR@s_-wrnL-d7t5JHk!MnBT^bS34PiufNF3Ym<0a3rYhQkBQ))zekvVZtB7H; zGKwi1lQmdotQj%hWzX%gmA}**~S%Yf@#XQfqT9wx2}aHMSOwg zq47kihDUkErjyv5Tpkiw#MaM|o)*lkMmTM#Z7_v3IHsPOErDfNsb+CTaR0xm*l7ZrB0hA(( zTO~ku@YuSv@p7C^jer^aPW)m*0;OcT6KIqm?Y;-LBCxu4xQTiz{)*_WG4y8`% zTkEE2Jd~ZX^r2BFo|xb@f>2ip-QfKgwW^~`xQ_sbr$8&g4}{r%9JEkEg1F~|iv$@$Z8TgZ_SV(j=n-sRJR3F5U2> zEloYQ8Rfhti2(b*Ikb54quylSweDov ztz>a?JsQ4;t2TiP&d#)V#HV+>SVCN;q9#AT?3L0>X8%S{B-aA6&rf1hO~HMY#CE?G zTHu+^#XB5U!HETwE^ibCxif-H$~^{pHX61!3t|XR0g?p(pAKB%(GJu4v=5}cJ$K~z z)doe$H87;NvnSRf^$34l?kRU63>kcRNFAQd{q<{;hrgXW#C@ImNYSs&3CZyk?5Hb~ zhkH_6Q>MY>DyAyU_l~ukG&g&|NJ*W())aejU!7b=Utu0aS$Z$J>sdzMzVU_g%D9gs zrkr8{eul)Bh2^c<$O81OeNAG)`hL5%+7=?dv!2%tXM)l$*J20K%lWg_Ernu(r8YLi zkJIOm9pc1`I1_2L2+D{ob?!$+s3?)jmiUm?tl0dkJ@~KKL4lRbtYI>3au>u@74$*g zL33Rq-slgnA9&YL<&(lM@Jq2S6>n!oprga40?m#5?!C^%bsRe?p~EYV>=rmL;52e? zF3Q&gzIf&k)O^31cQ@!kdQfc}dHpipgS#tDz&VcZ4C~D9xBjs4CJHtHN zO|9~fRqt+D=e5f}uBOPVpq2NX0h;BFbjZ7pm4lckD@p8jyNM2ldO}7gOdEiJfPpg0?I+A^q_PjSgx;TzB#6iMk8t=X91J`Xxkhvl{yM{WQ;iQVspff$%Tm!J>wR8@36~*JSqQ>4W54e6gY?1j#D#W?`9R z2D6NnCZ@#t%-}d`tgH)JMp;IdiOU=*G6)K{LZ`y5FfvMEE;EEM0vxyeZU5WPo-)0M zh!|epnAfi!rZk@V%ZAlFRlW$j=5o@v*oQy-pB5MS7Lf#66u5%boN5V-pr1YBOq z0wlcs7Q7UN2)WT#^ylDPiLJI6w4A-&dG3wr0W-jmnL9um9WL+|UyhHi01Ph3gDB&R zV{Th@`dD_t4L#=O6AdtkhVfEhkhyz_fouA*pl$xlXO&8in_y3Y3unX|NjJ9QA7ZQ> zOc!z+7-_0I3V;mY9ve^_0HjA&0XS`a0zyjM0H)~Mko)TfUSyFaB>eu2v18^(*^TKF z790>2Pba2?RZ*$GN!d(Okr01s5LHR6u$ZTorKYPO?Q2pSNK2!qXgR-?op4BW|e#c!+Ybb1;;r5uK4c>M@xUFFYVDF1TM>fmPaP32!O<*wl8>W^xup zXpqGmORXY~|6Pt)Eae;00)yc(d{&ODIEslqKbc8lVD{)H{>DLLU>uKl)MfG2{{u?L zNzDLkBp4c3GPEtw1cHc*r?O~-*olS3^ClvhWh8ni}{A$n%Rt2(zD+=tC zl(m+R8k{{m#*z}oVmfo!2@?v{FxFx?%Yh1e5Vk&Xj=~rfdC7P(12+e!w77+or@Bu+&HJmGT`iHJBp>iIogb8sSp?ylRh~*h#94ttOhi7+4d@Uov zZJg$qEV_wg#k)e7sX)UmvN;*SUd~$MHM;X^|iqw9m?P%iw`TYvN#K4_IuWRCYDSYs!W3>ax9Or z^|4xrCVq2aaen2sG}IEd^AwzXm34M)_OKv;t3Q-qq94rhTbqYF)u zMGoU96LpGI{23}TQfA;h3E_t_bBkVy?Z|L9#x@2|JPX6BF~gQWxDEwCaibg-C~{sp zrkqq*c54l^8uI~Eh(jckZGBEN%I?b!ZLv4YP$a=<0dCZaT$JPFB35`yip|{~DX>y$ zRpf~-G&mv%ot31BnzYL+TU)xDRSpm&JK8AYY>U}u#RXmZbyaq=V^DN0w34AdZ#`WO zs#GpUA+577#hh*{!$M?m>r_$)W&;!wn*k$>NWUY!C{VbV$6fj1g8H;nbtpHxkP0*z zB^sboxeg4B=A_NvoNPvt*F84JF;!+FDv%%aTl{rS6lW#}WN|$h^7X;hr~tH#kli8I zQf?Yatj1OWkl6;pe6@8S@_jLGF3^L6=!%HdrB7=O!ZZEdngTy1j;=-^z5UGw0A>C; zyT_2;eptxZBbI>8#e*)~eu+N1TPo0=qdc^pxZ19C(qsc4s_&1R<~Iu_Y5ztb9)A_7aJmheo zhp^sk%=ZbW*M_@T1+F#}+kWuUnahVlIl-7bDE zan=Y1F=|RS0X*Fk04tPaFcXV5>xzw1B0duua&np;oXv8R8o$iPo^7Qj<-?#^AD@}< z^|IbBsM`1p4yc%y89L4G$!rDgBL?6>8rUHN7dd95_BykXM}vC z3D~arJO%(4!PgT6z2~Z^4i4d`hD66lV?!7a1hi)z96S>#RTu`+9R#Bqr!nb?Q*8D* z+9+th{JMD^^2dC?viq@7b>4iGgY z!f)V3gCgG|M+xDyq*3kzc8HF512i4+PIg*(iYJ0!NrOCT0XwNP*lEcyg|+!7ZT`-S zh$N!NwTf16Qr0Gh7!K+%P$}|xe;Yc+Ok9y*p?D8 z!S01sAx*OT9X6yxZ7JaQ2-QN>+BH{VYTa5C%=<(~Hn@cIn~SAX9L0VtMbR!1xuIkk zRtiP`J|I6geuQ442lM$6+=2>D+u=WPAZ_pAvoJKpwLEvh+1K~T?8#zd=N7|33Bj0B zBBkD0;X9N&LHO7K8)1*|#(&BEdv7+GOo589(gxL1%KeYekD4ahnx+W1Dw;j#MAL;W z&Q4q>?6y4Eb4{zmr5t4M{sfLnxkN}iy&sGH@N?M9xz(E}B(3<8Rq#coU@%N8^bu&^ z{Xj3GFovthtcB=iE73Uq3tfl$2RCiB9&bn#H7F0AL7iz`*@A{Cr1??@^LbpcxtRcI ztUU~68yHMtzI%D4KvaG2r{a#;#Lw^Rmy}-)9h4UlXg!QooFF>_YdEn8FSC5eB-hXT zR^~0?24px0u6WG*)=TyeqM~HJ+4pHsiH=znMIsW&DJ=vm__Mp&F=ydv*@OiXF6;+( z1#PyNiM?5OtFZM0+8hz3GG-r&*y5?A;5Cf`#9F0|-Z@7WL&qO;uGf9FA*cLGUiZTL0+dGIW{LP*; zd2ooQS{Bo4_((k+lS!w}#@oyLFtA9V&K6Y5Me1R9MNuNor!JDicJN*H&UhGiG7(-L zV3$RxR$3SHAlzYWDL<}Cp#k_?iePS9CcQ?=Tvj_SBd)^R4M*BD1Zc17?k9^${B#AH z56zNu{0#f9oV~VmP@UwSNx!_sGQGx z&nh4p9zwCz)GMx?(m61$UH-Y*|8qmp2sgVffW*w#S(msT{xx_X(E4)&@r8VUR4}*d zVdKXO-#^o}Y^p=>LkJ)sX0rcRJ^3G@M*iDU_OFVvNJU2uNdTFrp;1R0tqkNASQ$An zxyHIIzwkG+vXM;OpyYPRxx+3hoogC-L^mi9nsc?~bv-@i^P@ zYQxj@X!#nC@5e!%DSi+rum^Lb{%kK|GEqhmQ3+9vk%*YU2oV^4s>w9cXZu6|KL{r- z6FN$F&$DVf%q~+Q@GjRz6$GDMVT%eaL#-<`(fJ&d;8hUIm5WHcQy-*M4u;}1_B4bZ zJ+w(ZOYmU36?pJ$_)ri%^$&wZ0*LS1A{cp@xwsg41mIny^!J4U5^?bb_cFbZ|n~;+5 zj#c-1Egwm7RC!J%I3=wwfj)yyG-<)b(P;r{R$g0W_0jrvIINthb?QLTRTm!=x~OlK%xA)9KD1z5 z3#)PK&flhl=tG{Fm8<`FcG%ulo~PA10zY-~(BUiXq$eHy`NU;5&j3B;M6xYNq0pjR zvc*4`p-E_nWCBD3l6ihI;NYFjJY@WkGYV|7mm5*N7v`1GQ?^yY34cvOdI&`6_b+j; zkr@G}TXHW+jeF*;;j9%$hUB?;y=Z3-?+P;JM)d%Z4^*NQBVr3;*w@-2q!r=FMRL$* zIirx*I;@hqQ?)`aAzg$ePT46n;S>Lc&^KVQ1|1r}2duPS_pLAAA zjPkY?Hve1f+okrVq6=)lNM!t0Xt>?ieZ9w zl?N)_{DLNBYyQEI-eT<`zK}*D5u~tAW-aY=L2vEUnslBoH|rDh(y4g<_+!do6aMm| zR~qN}E&D$E`LpZ#4afT}r)B#`?XT-#g%}JC(}B`H4vndhTXI||1fAHCh zW`TDwb+47w+tB-3faabzy=d0DcN_*gjTuM(BjYy0m}w}FzHOz)tsp7u^)LLwYsga( zfo-IRKVL;Yf*(k8Qi87nKzz_UVwmp(z(zzRuPoT;qsB-KMr)yDlj__|EJ+f_hDyO% zRuLqB|0Y_PO^-OtOE6guMJfNyo|GOI)eK=$UAxkrb+7{6s3EZH^qEn($TtEVY{?cd zk{>9>Zo(+DXUb?`JgxiWg~42m;mlqNMm1$h&fv_q9Qm z2h)S3)Y+6AefmH&>;0Fb>ROPuV#uOIY%xE*!P=FSTwxg5A(=oI1VUuT@gj~!3*Q2( zpoM8q8?i}vnm;d9NqNjxR-vl}lflaO&mSMZ?!s?37oU#eswv6gCMJ8gpMhGMhkQ@9 z^m|(`@VG<`@>aS`vV94@k~_WXPgcl@fccI1HZrUugykvq{4YE2k)CW~pL`nWimp-{h+`X-n{oF7+ z&N#L^zk!yG_23U}&)lFQIFoBj^Bi&Jg%fq)^fgANZ=0j#_JV_-nwG+&e~~;XiH8=; zf!;vj^bB%wt`T!sx2lck3V4EECYbbaU!g6~mg>ldSC+>ZDa$4hSAbgz{hZ zgmCAZI^L=@A)~Muf@(W{9M<64wIXA_=&UO5v@S9fi^`-)UjYImGpz6|880k2S5!b- zc4ex*<}Ad^b0Xz3DXbKmd?sn4OHgBCrYG9Q5i%?6aks8E)%Q`}Dts)lW+Kqh#X6-s zay~V_BF9CXDiJoLKu-ICt6THeQ@Ch)fGT+)WK3C)9LMs?9_EmH?DJtf$k|RtZF{`e z?w#wUCtP7MXkifD4}^GNI_`YL#XI`SFIY7ZsZIdUrABv|_w?tgdwX+zvuj`zuC(h% z)=7SJz@Q0xASDLZpbDe=!qo1-A0qeY9ddWx@e%=VxQXK;Tx+Y}R+_;sI3~-9!7=tQ zj=zRa7TI6Jt^&o}?4>o3iCLM02E%_nBY8^LS3TsL$T8)IqbO*KHt#z@MF~}c z{jIV9K`G7%jLN!0U4C23h)$9O2?=Hisj$?l0EtNE<&>P_hjnNRZ;b1^I~shPE#_W` ziISox`~hQ?8A@%GV1|)IjG!a7*uj-j*ETTG)INZRfE@`AyUjl-oYg}6ZkMHpT3r0} zyYJi@+%7AxrJ*&#M@-}v-DUqL)dAu3XZ+n~ETqrMw~uJg5yRaT@tLuClY1lv>4jq1 z_gAQYV)YTlBV+a+687OLmqnC9fN?L{AE;e6NZ1#YTMH9)SM-fW3+gm2h?E*s@1x}Y zoZc}1T2=U^nrg&uFR5LKOsAl0`ydTlJWZN6!MMs6{E4^mq)W#xo7mVC1y@j%J-%7& zpId4>kAG|C0E%(L!T!U)G$x{l3#1!6*FAv0BhQ_i*JjgVSCVIXdDSluD?~V3P@S?3 zZP`W0hR8k;!dbr{A177_UmlSu+^R~$1cTCH`+6<9W6%OPRyafS z6W2S9OM`kQ)M_>Ag|%fbj=IU;xKh=2Tq}LI8w5T_p8!a#`_tS3Jv#$#F+{gDLAOn5 zQL*__d#0`gIGdSR7Kf%_^VJyz%ZfuT?lS8;#|n*#E_@KU}YZN zQU(l*8a$-EKJ_c1xhyBbq=~AG}W6v z*XOLcd+9{ZQbc20H64Hb7qwh{~xv7@&5+xDLEVd&w=Wp`lKzE2=bTAp4)PU^L#M;-pwL^-c*T%(AuyI zuXe^9e|)h$I0W*z2hU2xg-(O+{E=^~y}({Pu(-H(+rx~m;)0}#t@u0B`w#I@HkbDB zHv)H8B9Tz>v@Cb7d++P#qb~P`&-o*+h_qBELvMl}BGS6aH-7%SUZwhwRQVbx*Gt6OCg3ICTUJzb%v+QRT9U@} z;uLqmmU5MeO0x2FrEH1BR+Yo(u8dNPW+V20cB2&bCN0C4nj%c@zlj_KIsWM=5y5H}unxX`>TcvMIsWy6K%|pB!#kM|Nl(A|} zaa-eJY*(#v4!B>_j;?q}_H)iox17+u%qdJemY85*AeF0N9uyYZ${4bh2U8@H=N~jl zq77s|pV(FC)*Q}6jHG)oHxOr2kED88xqBSM!8dO4yw{M`#kXKKPtjo+I?A=SWS7-6 z+A^ci8OHX{eH}^+u~^OEjF=&pj~XfUi&4_*OAU>zB-akuJ%$GG-@FSCm9$pxF?mhd z&D!FYhwcZ5)A4sxg^G&B5x62V^w+{)WEzAfw>qltdTluJHf7~~x3De3JJc?PVQdfK z3J2+FcH^vMZ_TY&>QBc~_NT)A1eyA~s-ICcW#BwX?WeHsE`+}*kh{e#` z?z|@JmfE$8d%6_rG#SqMSqMXS=d#cqE-a_SoY@Lyr#1qlR@^UR%*Q-7n=!>&TjH(7 z0HYbz!;I58>W9;4aPF3ci9+)xl}nS&^2;OlL#c867)iKmIMI^cSWE~kyP1E^hep2VgqzKwncF_(3*J4Sx=an`HT4lJgaKN zYtao?+t>@4GuK^cK{qH{Jbp9_Vkb(tnI@u{j_cNw-J`QIq0#V&%GS|wrGK7{1UV!c z*!wib$s`@f@z+t8L=WIR75fX7G8aVL5??(+=}<61=Hy@RP_i&VVDJb5b8|Cc9i%^j5#M0QK&2G#1*J)g>qZmi zz$Jn-mqCqWkjx17x$~9rLKs3E#R;N7jqAjNTp`v+cfe>_Hl1(~;%kh4CLDBI5=ZUh z5Vp%$7F!faGi?t+KN9-4pHFoGyN(0=wx;7F@&VcOW@FI?7l?NvYvj9zO{Xhez-TSl zTw)EHUBtVgX6e+wUdxsvp6Mmcl}?0y#`*mCr@_fr`ODz*O^@mQzYe>97t;Jkt0UEK z6^)78e>eIDjz}Wt-mGm0YX{&Yjf<)j$_jIZmjVcu3GhLJO?EPV`sg3Ix(WC7(heah zP;)tZc(FC?Mh4|f(SX^UT{wj8O)lD|KscTw(#yiD$kpxb2?y! zR_%DS*zi)TqKjHKbf=wPJ*FSH(45yDJd>|4&pv+POzhJ%RJ`%ETX)qtOdLk*5nx}< zpkA#&SBQsO7XXn1!=BC?@b!(^D=oNU{u+`nX z-NWhnd`_iEbo7+cwN=lkRXa2%Du^_o{;D}_(>{Pp_0Pl}e$dM(*jSW^`W%C_(b)^+W^BvXpr{oy6+n4Yumuf|UAKYDtNae>Og-y8_UHR48Wb7sbmo z)MVdHbK|6b>t)T^67~#5*BD3VJYhkxX@B{9G-ocTQgJt@f zh{LzxnVRTV7IyXsc9*{+GZRkltSeY7kHEJ~FXmaWq#YZ$Y_CR~J1lp8u9ecDQC|Q= z$OOfvTeKnwDvGtD=uaexovk<>(eZEi>+{%X)LnDHci6~0QKo^V zJsw7Ij(m}9@~)iu#Q&kXGdHk%DkoyjQqlmv}R=h>OaaF!v*QHs_d~=tVA!IYfrK^j#`&i;bJVF3FO90m~l?iFDKxZ=-tK(LWjjf*|yhIlKt8XKtp!>8Ds zG+UUs9QW$?TXK@lQx8I3=56Q}Kb`d^bl*fZ6D!EdNg*Y|Yr|I9=F z{kYKi|5+Q^+L##A2{;)2V}2%SLB9}}crFkD&)(;%Vrj9`tO%8berr-}_6pk|kg zi1-fVjckZL4oZOxt8MCPy4|^&#rAgjc3cC5yXS(EVz)Y!gn4AYIOL4RhOP=}ktp6V zhfKL#6JQ2?0Xm>av>b%8_P<#B#^_wTY|EV3wr$%sPHfw@ZQIF-?VQ-QZ96%!(fO+G z9k;5+=-XYl`}h0)+T&Ss&$ZUvbGnFd#@`78G;OXLs<~A**2|)2O?qmFND|>mh8(8M z)$@#k&IudDDH#1u9u}qw%X&}L8;nuvtwlXaJ5kmzYRW@Vd3C8M@DPm}mL!AL`SqJQ zS_wIr_+5aC4Fb&&A(lAyj=I1o2ZC$uD13s+e3DBiO6(qw6gd_F(O_tV3Xm!#2W86%y6K#(|>psmo! zF>9fdpp!6q;>_K0t}SWd01@b^FGiMX=hu##+#Jm!KW5@{{2>EZ4~E5Ti`G$ig;?Rc z`Zt@dfg=8}orPHyIjC!p4z4WWfBKn*+gsX~XpTVx8iC4$Yl7-$-NFX8H{=>w)yXcUY8g#G26og zF7c8(NJXPk*%;jJ6w+pE1mISMvY^m=VDy=|A>_?lu8}>=Rrj_8OjPn>kxZeS%!9Io zqG5p1-->2rl!vHQr0ROvIx&DY^QtCE!bYy6KlLHT8F~{U0A5{*yF{9Gb`{4o^B!=o zhSP&vl8SwKYM916c~yiWE$O*`i82RQ#zh;P=Faft6280vcCm)Y4nK>ry`ZE?3vkADrFB)sUXLwghKkU?BaT zUu<5kYhe(8SN?;jv2F-cCgLXb8Bcn_(bV*ZdB%ys9Gv4H9@i=FDaRbotL&G{=|8@} zaY6FIo9qaKxLHwq$R5G&8qB6at7I9U&bS^#;cCy zDl_-gs?Joo&C+6%mNrd7+50Lv?T^mC`Ex=n)r$3}%1Y*m3RsUf5zFU>vdUU>CQ00k z`|jT(oqrOHTMI2alpEh-u+T{7T%7X?U>j{VSlcKNI{0TY1yTFUJV=z(C)7I z#?Dxt|IBCy)}1v>3-J`}yHR_gr`bpBGp)o(C?hpa^BNg9ZQ&_5c3@UatvBm!F~RDC zCG8L3b}#9S0>H3qt!ho75x}6AvB@1ZkLe%X^;#{=VB=S;UWA>t-^8I9MUQ~kLnu)r zBgjaZxt4AEmU9d_s5pi^vn=bfN?@dQA;kQC&eXr_a8BMhGo&e_T2q#pG*<%ZPp3kT z6CB3NrJi!Dj#rez_AGuKND-S)F+G2;B-o=A;I;14?u}fj*#Ssk)KR4OmjIdGbq9G9 zW(t;q)ERD!Vnfy%Vt`m*%Fk)4#9o#L!E8hB@G}9q6sH{FSEUa$2hoZ$VJN|mG>6ER zRm#zwcNa)%pgn$+?`q;a;@$HIEMhvaB4E9;QO3UO!~& z2O$9DsPv#@4=6yK`p_l8&vV(Qm2>Cqf^jlU!b)J3op-*P>9r~;IJG&FOZK%Lb=*J^ zg4nDZmDx#hkciN_vLQ@$ps)(?RCT91?TL5mthU6$m_{)vcC#D$oi)5n%t1_ilM_Om zXi3Zo9G)=Sy2bv!aPm+Ue_~-PhUA^`#NXEdUhs26nb{_v4>kF9YJ9ysuO8q!ST`-ICqR>zB~(z z+4U8K*mr!{peCIx@MXjCK@z3u0#e$SPH8nwG;dgYi>G;Ah!x=S738Kmsg=><*#X*p z`f)wK$vr?O`k^i1056n1(Wn{7MO|4oi})&|0z`t0w`6ebPI5ukAJWiL_x$o{p3 zcinC>m0D%^@MkMjq`)eF+jDO#C@*t0F7d8=N)>5h{?Y<3z);S3rH*93BL>nWH^3Pt z-WkXyZvKw}9xLBxVSYr(Cjk(yJlTqpzoI)~k~;&5 zJ<&>5JjLst82WhmbG(6Ly`!)$ki15C2W4E4npbJOdU=PZFJM(xQoC|wL?!`wh@L@0 z-ytRTP&v&8W+d)l7SOgYwY|y8#rpJ}Ko%W>JnGmMlVl!3-j~wIZuGGs<6tezq7qt3m$-au3aPbjws!p#HlNdXk&TzReWU$OR zlITaYoZVI1?Ecg6tf+UAm&<(jqd;x<-#TC6NiyG$@6LAt>K}pkUkS#)>va831mnM) zu4N+n_~CI0B%SQG1hHoRGDkX}JZ~Q6&oJX*Sb;)EpW7m8b#Rucdb;ugvY% z@#n?k9bkk(B92%b;&jy8o#t%}T;HQDd5`2vO=q#0aKc3e3yo6KOH#2-Du6+M->dhm z*omT2Tbm23MMb7{Pf&{{y4%srlClb#iwf=2Qu_cHo)pY-&^8)U0Fb~^-71OZ*{v(W z2K?NYsNNme>6&YkTzFZC?-LjFCT6dgL8xjx#P%;LHiZRs-~N38{j<;Yzmk6b|CcL@ z;qP4RJ9-52+Y&rj_q{@;7q>Uq63m|HN*Gxy3`!P$KCh}UoLK(af|lDa6p_dS@R)(= zZ>QA82O!NL{(VXybAg@ggPD>IJ$k1}e0FJB2g;Dp%cADzREihuNvyInXliPzaokeM zj1-#7OK#=Hf17ZUCAY6hsl~aFFl*4rYVBRr`It)Q8#2d-4Fs_pp`=K_g2> zL?Bzpr_#49U%0O%%!p+h89x_4mf#ql6Qzv!%!tgXA~efZZQ-I3G-m@3wkjsr)#WZs z-uNJgfZB<#(m8MTD?x|@oI~M(xj)tj5#1M++Gro2ggvK&{VTsePZIn}0K1|PXN+0d zYuUT4Z7sK+dLh26X0CC`j2YbXVY0QY$@Rl-sd;|6B)q20-`s3hb!w@OJCT-pg?7vi zoJ+Qt31kb2^UDx6C<1|05F>V=xwr0?3F;ge{_)&Vx^0y)b~~d0VCkhMMK7r`zRV9msmxM;qRM zS3U5L-SXedX7X=VVT*jnovX(rK|#id{K!I#tKdN3#Qx&=_`Sr`5Ho(Lq=~8Y?CBV$ z`tp&U6~AefDIz7SGzwBIez6LeSLnVeudgk&E!s4Fbd@h^SbtblRYCC_cd^-$CITl) zX!1T!dLM6IzW-UhYJEBc!{d3S0l41jhgI`~rOnbJ*D|t?pB!YTb-@0$=T_{HK4xeE zsECBa4nd}wa*%uDW9c0{9zn~6Y|sVdP}>vnU5+Rv9C}bWM}FK{HtGh;uN>D--2D+u zm2SmA#n%%cY9oWvxH<#lhp=aI`h)7Q65{sZxi|!v}kuN z?2(Z#TGTsB!CFcjb(ofE^MtghOivnAIg_0!cJZbq8Jxu_4s}tH9%Qt`C|X&D!9HA7 zZbilrW?$5)T_p$|W1v*k4m})h)hJjvGk(b`Rt`O_D;EQcEkhBOI5Sb_ZeyrmjRsWB zRmTQ_C~OW7WG!vc{x7d<+U>R5pU_pt%Q%AlF_*SC!9#qq<^2ZwI!6tLEz6M%2cC>3pH+rlC zDJ8C>-?{@~bs+F{pC=cuu=3s1*g%W4QFiLr*k)>+LOHu4rH$FxTCH!4(XuR54H33e z73^AD49F@fg#=iLkrbH88?t~us*&@X1@LCTokPU8cj@pmfC+Lb2bjf#_P;w(Zyzf5 zGw{j8)Q<1~=IGlJA07W74jL<>vD6?c*C?R*cA@F(lO_{LW0u2h?}tbqV9IiwJqcdv zt0^z(Do#0E+4}?OVR!?szmi?%Gz2Ob*3`4vvf19Ri4pq(lsqoz?{{WMs!>qIgAC{5 zM%1qEC*&g3VmuNOkB?PL$oP<4m@Lk|0~2GfO}*tUM0dW>hsgN5dHBOWMn!)nGWgEO zW|4K*a(oY&%3`>YF~d@e9{KbU^c}4XCpv?yWTA4|YmL-P>$?3JSrTzKzYg4{a^lV` z>knYW$~dC@ci1msyGUU~kRUORX;S~I!f&R5&+L*_LYgf4AaWm%ReS7wS#8rOk_xA? zI+Raw=A}{(E(Ai1;c*5vBv6Td`8hZK=sC2@*d1<(Y7FT2gHm# zo;cQXaAoE8VSHmnIjdDJrX0gcDCg&b(V_(-8?#J!mux~Lf+g0vh{ImkIXSsa6ie^~ zJdjR*6M{{M-LUT!c7zz13fIU3Cz6i&G1}%w{fB&&M>LzD1V#~ye)b3Z3AdeC*h=V>6!C@eJ{>$Ii4|M_(y^7?;5&`Pv6U@l1({gzmTt77|Sfqc@f;#kcks z{93pBFiiJCdVv@Y`LzM_$cUkKgrQKPyi22^s=Ojm7c}hf!sVd%UNz7g_2YU`!wTc* zRR}Qc%~cHL)oHIAa8I?pO-#fAtH9eh_P!_pePVd#TIL}va9bkvb=SEY$pQNWorkZ*2ZlT>#Xw?TA+LyQ@io8#&T%8 zI9W*W3Q&98ek0ayd(>QJy)EP#8uWVo*`rsDNfdXoGu&_pXn*|$N^1g_0hLElFYr4i zL&-O-PD!7=0^nRy@~BAn`^NTr;utWP@$wz3$PCfiZUAq=r?_(_IdQ#kd)oN zP}s3=zy4sR4m*5YYZ#W7z>CW%8=t0-CEx)~C)b%0mlO5)?80PlVV5cqBg`Wk>q-i0 z&{ZM}vh=nVs9l0+4=XxsBU=hVh(QSxjiJ-a6a1)XkErSQ2qUCi?#j>7n9qDgr)+$^ zs5=oQh1R$i%pWDQ*;iYJYkD$2@*t)7b!oQi^nor5{5fe;<}!0L)yoSDs!lgTm4?#b zjlH~?JZ!5iV}}TJbgi=2iY^P#K9Ak7xN&rHWurx*Os8{r`WEcaXQOwKNiH+8f%o+B zLx%wlkg=PJv~vyskFEjtN(_EvCg2}U{X{tJSV(R7iP7;&9QFdecUs3Wp$52-W?(2e zf$#z#g2RJn*BG>iklWTbZ7L#ywnBYX-IKZt1<4H#M`6e2CE@S+{P45*kaT`Uwhj9}P1~2s|nbS8ztlUd;k8FY}BKro}-f z(*Essggyw}Kv;l$)J>2*)s>tb*;RhQ4f;mNp79ZsUy|?*7NJFgrwgoVzpS1M>-Enpq>D?WzK9gr5M@uO*lNFlH3oNz- z9xrV$&e3EaTdxdvbDw&fyD$Tbi`h|aT}F0S5q6&vtVemrrZj~%5*pXI`JzVmctm!r zT@S)>@b%Gfq8?$ai97Cad|ZJW0&q(#nFFc~_FT>K@IQU{1=Tq7q3-V`_Ah~GhbE}b zFf~UAyO_?HJ$8;8q>-|shGERRmuOjvz11r1Z83#xEb`n3#JWfdzQp4{)#LfB76%Ow zd_B2`(C)4hdRNL++na`M^bFCq=SDOynVIb`r_jz`d$U!`aMnU)rA7T<2qH-(y>+=? z7h%=Pp96$(QITd%(E@KXD2`)bMl%mb-D_jNNTQ`ZZr0(!lM3ipk;ZSD%fZ_)U`UyZ@ zOqTsr3O%byGjfmDqoAN0gvhnMke11Fi{InOKg$g*31u_zlJv<0KLZyHvKzr z&8=ES?>oABwP=up_Ku;ped1$BJh$OTySx4tlP}qk8*xG@tZAkAq?5H5%r)?`R4(mS&DK6#`5R_?MRBA> z!N?lMUCpFRkQ8sOu%D}YdwtlmeLF|X%&w|;i?MtX{B1i!E{TjH&*Nw528YH=PDf}VPpcYnHpULn4!gRz!pN)c6)wDKCt5$o#b;+JX*DoWQ) zNi(0j?lcIin_cbO;mEV@eFJUG5ND96`k%FqWvn~KqKCE|4-#vw`CFL#_V_r9E$5&d zD>IfN2fVCVwIwj79N_u*xq6@4``+|eA$_EICYH9=4!8))6W75X__HX@4}ouWh5A$Y zZUAsd8#ReskMViDkRaDGYlsuZohwR9S~tK(s?5nM_du*qS#Bkb9e9!nW85;pDJ7-v z1S`8_f`0qE>WGU>^e8&t52btA6^=>z22IduS%t(dgGOs}$w%eFmV9HkbcL!O)`U8l zS+IX?_aYRqk<6qP7kt4acaz-HA%&`fe^dm0q6mJylFw|j65cl#<#pp+&CKe`%EI;~ zmx&q;>1;-fVUFkcLA)FAiq}Qu6c6Pf*(Mj!9pWh5>V|)`1MlGN1i+29^9Dc;Bz5M` z(PtpC6Qjm4!&mFqVh+&F{rUNv0Bau$J3DzH#cWB+#S38aLa&;PsSMUS=Csno8vY2u zPZl*yJ<^X&KA=V3H%gJV5hAx~p4ON_T-<)*`ZTQ1$&NnnPr#5ZkTyjuEfO>;lSaun zm@uO-N^tEe~3Qy4w2P@e(_B;X&@Bfb0OLqu-Q z4&_9xp~;9`_rZI8Q#uwZyAh+vJe|i(X_!VMM?9PhE%poaQ8R+a2IV+ei==U=bJDe}Hju&R%Gg8>M@&PJ0nCgb31vfXe^BIuakFJmH+Vooc zy(sQhatv!K5F*KDC|m<-p5nAHDNtcN*bW+(z}Y+S;F^uysg&(b+h*ADOWT)V<3ba6vV_wHESp?e4P8Dc3|YwK{ORgi4&` z1$I@@ILC|=oX4j4X&cs3Tcv7}Ik#^{#wPW5#n`CzRdqRa>U^?@_X)c5PtA1pCN+s# zT2sEt3zoAMreza*8X3#mnee-@h_QB- z!i#}wqpoiS$}1vbwkM{HT{%Met?+t+WY0LE>U1!r5}z3{Y}r@Q^hnE&j3L!(5->h+ z9j;l@!fFyJI)5lXla}pG%f;FXA$0+r-)OHy{fU?Ozc_e{N5TL>&$OSq4BRsc09$j53{6ybEZ~nM0KwZdoL_ zK|Lv)s}#gV(o8?xPOj#DnsmpGk&5*0bo4@(Ur$a<7hoIN7OIb%?cXvbL^?8b=0|a@ zs9))l1%5ZE#`V*G)u0k-`Rs1h-Z4K$h6zC}?Awf%HoXR>hS>0EpUAdaw(p7j*TK%< zwYU8&1A=Q0Tu>tV5Ai6kF>ro9;xn;pL!P;ZxbUC(zrCZth|6Sh*lRIH-a9hq%^>pN+2ati?wp){+Q0&GeBEmxDTzZ{r!fYMH#VPYMQ|n_&+w&lvAnYrX_qK4njz$zhD& z#P~Nl-Lb+YaCw_7ntkG@RSrO6_$H@rayTxHw2QL3@Iu|;Iy20#SPGsqIqC!++IfbN zmf6@HTDK)V+!^3fDt)85D{} zs!UsN*j{cAyWtH;)#_Qb97!g={VK2_)k0ifakPj!p_?UZda~y#?7HtcvEx4hwv)E}{z&-- zp_vcA1mBZE^4a!d&FSs{o!XwnZS`}XdP8#I>DAp6OeOR7H5d;l*9T!4VXPY?g%~r5 z8dK@euHR6uhO>>Ywx~`au(sy9)Dp=7cN3IM2V0V(z0=5Zv_zbxjTOPqQ)oDv9ajZ@ z5sdxFJb8ZX7N*$gmwd*NUzHOh2=ktYHEz*GGo5k<<7Y<#-tbQMan!DTq~agap_P8Z%^~%AagBf{VhsUHy1ZN-9t!t?^Ld) zgrI@k$$rXQfF!=>UL_iKIYq`Bn3qD{X=M&flOjf1${i&>fX-OExY}^XxK|$6ezQ@?$t2(B(&&pj zD_2nlC(;vNt60YJ4F30PVG|?A!(u#u@lQSqgRiC^vBLV<@{2TWIAO{LQxLVHl6H-Fhks}0EB1UqfXp$ zfOZbpPj>?8lnT8NEg0NZ(3J5=y-qDC>s!R@G3TAsR6#YJAGs;h{++jy?8G$zUDa-v*%%85e?$;?^yk7Xeh{L0rwQ{_8Qim@0BRK4;SBNU}6tt^seYpe1S2~jV zU({N*pz6cx*S5XspwZNz*{U$ zl1;Q#%ebA(?FS~|GIzEd&d7vY^L(olOHZ6of1Gj5v2gSyuhL$RF&SR}V8k}{@{J7s zo=x6Mg!4;hwLBjM&D;g@z7D;P=WXE}%~1Ht6C>+l^49Y*bUVnq87UYv6ugtW6Nig-z#X4C?~|{Jj8aa+)|e&DagmI9aaaY`uH`>zNXuEL zcy5}z1N2~>X9Aex``g+tl@PX#91Q>!(NQmqP>^XP?!ocjFeMLqmOc5A!U4(B-6iFW}nqKnLDh?R( zh+B=y^zIP?G)p^7%rd`Xxb$7!M&ajhuMN;`>+qpJqAMw6l3xOs2#PgJQ2F{>E4T)ODz4MS;Qc>W-J((HUrP}Q1QpdIuYPL;ICX|C( z*@yoyb!>-KtygY4O+8=}{h8&h+~&4=`N~*rN}_=diOa0-r^)OqxXMa?0#$-uV;SF@ ziZXAZEusBjo@ldbQ-DzeUFsvcz6mfthEDXKWL#?1hpM?;=yO?H^z~LQS8v}tctP34 z!^YHkAaafN3<;4r(NBYRwV1KPMLVgTaY}lHrzk{`HcJ~20a1j$v(|x1IAiX&;xb9n zN9qhddk7bvk8IWlb5Z1W@4I<7RPfNA{me?3J#VVzhIHvNCU$DU$G>yEYRU3gz4qV~ zh*RncpVv2u+O?neE~$$SzQfh(A$Vn;!S}_{b1;nClEM^A`t(b{#`J-D%oreNomcje z0uX~A255?NqIZMVteb=@_yxC4k(BgW7nrjp;n4kuWY}eK$R*JlZWQ5yWS#e-q(YiU z8udlG@VJPNvSG-3{8z3#lxPJ82JCm5L=H82B<sOyN#Qdngok0TO6@i^Y0icpyEATj)Xp z%A$_k9tJ)j7Uis7d8ZHHzgE#D?$?LX--Ft_8d>4`LQ5#Yo>;$9M4DY;xZIU}JK2z<3aT0gJ$1rF0L2%K-8$JRb$gN0y=zU7kIF;GxQS_|=WL@dx@5M@n zik(PrRFK)=*LN-l;jd+=)-~6dO5X*|M;}$#FX7+l~haI9nf&CMM~!o^m>hoca4owm7Vp7 zU7D`3ey#q3r6skUMDVU>rBxx2r*J?~i+oqXaiyS`4L zBUl6$a}X@nJ3-t;(c`%SGbKjb?X){>Iwg9lyvX*6z}pYB`n;3;EmNR;-t|#Ln`Sf#*v!QvDPi zHM_)nkPevDgf)41_AtXQ4gn2Nm`B(CL9;;FhHy+K%;Skwsa|}hAh4E)3cVd6gp!b` z%+z~AHcvz_Qff=r47v&I6}y-zB+z_PyTsVLyXYv9a|&wOrmTl=Z9#R%zxDR` zS)ymE&>ep?Y_`Rvu1LmWX%Ck%9)G zd1qKcN|RNdX=>#&?TwNy`bbX-9?^e1&xC}ts~vXypwGgZ^IXqY}8Z2sQj`& zJ)G>&_2XYo{8}c)JBuGyV&STUF->2VprB5QP-i02-+M8Ym^#XAYa@k%a%bY{CfKpJeu;rt00YQu&8V}n+;rtLW4StMX01_|zJb@*I=rlyb z+1`oEv5U#OyW$y8+~kT=bXxHj)Le#LcuSKw$=uebPsSgj)!9KT%f&|;vxzW&7mqdA zhWG2zo$YLl?hn_-o;^MF@+;{65+5RBmpSK}F~ccANvIR&EY;`v627P0Iv5*SfTIy)S>)2ZI zDyL!p{!;_ZGYlY0uaezfVkm@72B)6NHkI4JYDZ|ntBy3n+trg?(`>_{$23Q0)zj2b z^ZQ4nW?8O%REG3*>7~IyJDfXKrzXvEOrrb_tif{@81L5T4y{_Z4vp6LEs2tBz1<*b-6>M`lw-($j>X!mDXz7<8y-&Sn@C651Ba8mrA zfYX0UmWhAbeyceZzuz1hi?|sY+c}xr+WZ~0sub64zL^HkIx$N)wnv}?)e|5EoSL$( zA3kwXVFE!NQI@bEw=kAzMvFs7N@ulScK{kZqIk!xe3<<&z#k}RH}wrno<|dAM;F7g zw%b4}qE%6f?AANdAg1=!0U}oDEqXioJr0r*`29af%zx!~Z6d?Nft16b6lsWh;P*#K zP5{=;e|#?n>B0cLb$`jNV}c`NSx5s)UE&jxWk!>qj>?b3FE-t#t1xoB=?04Mz$o~$ zh`FzhL>9?bneq;1P(h`+Aj{8z8)qN}ZZt`frWnm6QR_~cY{ao7dbAnJh);@>O;<7J zI6P?$D#ypNL zgH~s(46q=PR%5jg%)Hb@Loml46bQvF>UZN6sbg0N&#y#N#J}{rGBAJQ4~bfc<`eDc>Q-~4SvL*+Ur6&ufTvO%)!*VAQE0Gs~>%okF^tQcT$ilb_OvV9DK_h z0q*{YQ%p_o7=PV}Mn(#8_um?m(SOp(|9|1Le~E_wdXb@MXJ!7Mp>#@8-(q>>PaE6u zB4^;rh(BPE8lXnxVfgU*h%m&52$96pp$_w~=B62^J482i4##kEhRmNp{1D+#skHC% zLypBr%t65zs5VoUM{iR++pSD|zTR)J_^~(8b0?$tftKbG)eWOXvrvgLc$q$|Y{=BX z0{%vwZL{#`bZ$PY_2({S`Be$374A0u<*Ne5E0mTs#Xw)_i>0cKf08cB4_iGZ+s;!l zMR26S3oT;CiD?pJ&VdyHWgTu#_lP`G&9lsHWuO|-uvMpR7gTa0(47jG{c(V?cIeT=ql{*9Uo zroBu;89kgU!+)e!y^GEk)D`6kCB+0tRCk5eiv|@Naj!o)ITh+-Vtn%{gTH#1_WRm9=m3C~IKp!b90vu!t8~o=L zST_f}7wR#g9S7i(-7($><1k#Qbs=l>Y<+7grKILpoNf@|ZL{1hPV_sj`pb{(TO!&K z*^`9aFN?K#E6L6^@I|XO{=GOWITPJ4+JU7mrgnl2tFHQzUwuVk3h`}~_+r{Ef<_Qp zFdS|6j2jXGOI&_PM$?I6V&{L;Cax#S&P0F9=V$-F8npbqon!b%gO>jwg()4>5bK5f zP&8&V*1>TAR0F9^dC0{1Wj{24Sa(9H`F6MMhA@U5T~gx|PA__*CJwe5p0@6?nvXZe|00J}e)bFR^Zx$bsR;$c0WCqQ zB87oz!+>y+0&eykVer+!vysby#KvxFkOmm5_&USid2G);lz5$EbD7Y0DPQ~DdLJNW zAJ$9mVgv1j$UkyGj0JjL8s%w5zB7MOlsQb3#zS-x$0O9E#z7XzD@>e)s+A)wl*cJZ zR%aGFvM{=>%-Yi7?OH_7B`GRYEHm=xN)iBrqyS+j5yQ$(OjIZqmGLss_6l?%t|^Kn zloRyh^HMBrD%_1|Aodrao5AlWe_aQh)yHFf^VU~;j`8KDnG`xRV? zv>QBf?QdXo4Skx>&!8%|q_1#q&QdXQFh|*Yz)}s_A0@2yYeo4;&kF?=q@}KNGCC*p zu2X(>>V>5lKk@Assc-rI=m4@i{D>KdHp96xV|gp=vz`ivCfnx9T0zNU&1lLx@dLHq2JLU@~v?MO6w zBgVyeuJtw+BKP$qA4CoCRp?4PD}lqZ623+yhw(Oc)_y@k|zv#?l%& z8O2=a>Z*q;1$%&;Cy>&o>&vO_P|kF(+)0y#^3A${w{FS0*K?V;F z+pD-m^!&0ebimjJPjBpw{?Bco@9&bF% zPhz1l{AN9O09(me$CAzeJg%wj@C#LA`lDe(@FbyZViNo#>GZZCd z-ntX<6})aIZQ0iF8U;+c0D}GHCm+R<99--${M4Q_|5Zl4k0IthA^*sVf4S5-mw#@3 zrU1p&h7_}WdEpEc%IbP*s(HVj`D)KCRifq_Z$c}8kNF0Z2ik|-S^~0TA(ag{sRUZ; zGd=$aC1a<!sSQCkUJ}FHT?((C7@zs0c{XSM=4*9j?b!kBCfE6gYt#ubmK2eS{I(0XLKjwC zb*rae^VKq{_QPHy5j(8upBZbXHd65(I6#*JtsG!3=u3R9CtiLtV+c-PegzB4eEG*Y z%9Gi|u<#w)eyKMREG3^Hf02ePeI2i{Z>IVK`X8CYY?dx=9~jnQ=%wL@EmLEk~KIDi%hr>zHtb~;OYux{Xu+k2sHQ22%jI{OzIS} zi8zyx33`tE4jF?N6;;IkL2sSOYrUt7>M_?bSE}~M-FB|;kF>t>7=a1Xyj>&?>XF@V z6A`D~l{{NzVFbt$uGDAho1SxP$9p>=foC7HX;!*NzC3m7IzlkI}n|;>B7@ z7JZctk4?u+lTApA)XDPeGs5fUNs|InuXY2D;^PSC2JVNRhD|*Uf$g@-NXcLP?xpxx zZZX$1&4evE$GcINYrR{KbX z=IEKTEmt8vh`5WV%v2-G%K%pid*vohQo_jgeR zYjODjHd-sPQEjwYJqq*=?7ZvIAL!OjP^|MpR|g8xld{tid&cc&8okA`1un}2iR#Jn z=gpaS^7h4!?kOcx(A43>eYRtgYvpxnf9P?2`s=i=HqJ-}4<~;MsV@nwFcO5Z&qEo^ z)-aC?7GED0E2Bkr(QM#bEfPw3RA&OPQuEaog47wHM36lUiw$tg=Gu2Qp<2h!jbp8Z;X!sHFvtTIIn`u;W#;`xA+koRUewXG` z1~woTc}{#ZVTaB_QU&CgKpj0x_9p9P_Zd_bwp)oKm*PT@BI*ymGWw=KTimw5(UaU8 z^>F-kCWI0CC^c!gKH?jqXshN9?ZXY}ke^(FOR`)-ieetIbxG?uv2Y3*`*@8)@U{V$ z_wLjp{IXfLXbWU(=VbE2y}A4vHr5x`nd3dmCx3+E18wj<-He0mucM}%n@Fdy@=)Fh zMn*@1TlXtPu17cMKRenQ=)^ToC*SB}@OFFQE!jGg%3TCFLk_ACMwB;1 zOlt57HS1d7Iio@X1aV8%IDup|m&DY5@&|gt0PDysYIHA#p3g|_AiXQ}!a`s*cq{zc z8Y=*os8)mzQ^t|lbM9z@9xxY7B zKy)MWUKI2`<0!ecd)#-nxOso~P-EO#Mi=R@pdKZ{muN9V9|xpwPjdll=Sg%vKA z@>D46o=as$8S{{bra#)0kFDrazZ-@rbqAsilVqJsykOa4 z<#{)Q8K*TbB3n?Vn*VNn9t;NMrumIzL~#FzWdGW8)BIl{*+0;|XnCoh{q*qO^NliC zJ|OmBi2k*dE;5TK2FfVJM5q_Vy^`7_3=Uev?3hrnJ$djy+k~j=(RpG`w}x+@rjOD5 zD5eCng3^N6NunGM52#Ed>@dir3>|yBHp%1D>zS2lBwaGG;;9rVO}9nbvk*bsbZ#Qx z2SyuG-DiLAm&dn8aFueSYqv7Dl0+3vQMquPm(5Qtyc9^I(R`WHnl?SPIL~s^CzzNrIhR1?Qd?-(WGeTG495kH>az8{___!I<{eXA z<00QectZok3I)-`&_B+P$a=D0|K`KlD;?a|{p)h@#QxFr{C!~S-(BT@jWPabmxHmh zp_RFjvAzwRlbM6@_bdPJ>4lt?zRiEGN7PSUk(80YI$2MN=gr4$0-*?Li>MLcYt753 zY4TH8nf;n1At1uY zn93Yt9{V$&t|r=_T%Vria=+MbX#A9)rH2qNQtUdTIDNKyrU@{3q3`U7;MgQuL`316 zLF>TEqu3Fpad(S`#^rTLjSGL>)vEScGaeC63WZ>pVCmzN?Q31^_Z}GQ1fU52Xl62w z3jN@YVyfXH-k>mKxJs~V<`+uMS*)`89;D^!llEKulqqbq>l-nOvf|B>uUg2kQ($7u zFpddzEH^(*u`znEV(hTyE=g}~%vj{yw82?OU_RGs)9h&;M4tuLc)hP&(j6IKaV)`< zMKb=G8!tECuB>?cz&vYObl=evLJ4dUEUbYyyI{28guJUH{2fn={t-M)WZGL`Lre~<5>_Fi$O`g>KHxUQ= ze4_dyWtvg&wk7y127SMJ{SPt;e4UwjqK~z-p74hF5}POMh+`T>8MP#b!%@PnPhSr^ z(FxUt&);MPe7RERsL4m@d{i?KRYOHMo}$qxHaI zqu&WaX)|N%8RZuR>1q`Tbw9DE91=ril8GqJC6P{tqLrAymBoD2yT{U;v_C8zbZhw9 zdsL%I`6}=YQenx8*cq8LQEsfqMRv@ZrP?LGhx4=xk0w5z>+%8V9tlE?S%x~u<;Md1!LCE>2w0qH2+A?cv5UHX05+E(AF zirf*gjEp^Wju=Dk24qXA7Tb)BJ-80J)!Pnu-f`F-WC*#{|3-ZTgv+aRjllGQo(t~O z8iLI-w=eNZU93KFspy}R4(nU^k1mXk!v$Gv0bvY~m=VfETrZGPLK-H1%#^Y7iY`P+x8>O~JQl_EG zg&npnu68|_brk_%t!ABKf9A~l84Vg^P0B1L&{@byJ4F;%?IlR_f}a~VW__ivC`{*H z{XcccGCZ9c(v(z{lM8%HpiKq4^-Z49FN@(3V+8}ZIbV8`59Z?d)bnjMmLajIH+?{ z(`Uve=_^ExfQm#*syy0mE}#`~GBy8cOeJ>r(Zq1a?@AS%zQW)B8t17j4LGlBUeV>0-&@gYTE-6{)vU(vNKzjsB zogMk&1z4N)Gd3$&4W2SplVo0LFjo6n>DB~Db$U)eiMG=Iym?sUS`pTiapbH9gje0O zWQXpnP@d={eS@o`LY3iEiSY@BeIVAM*i&MQ-|l|Zd3t|Qj?5XPQx?ju5^0iaLw z_AM&DM7o}D@O_DZU>5dbmc;pt`y=K=PclRBTe9l2E)}leJMV^ImKWm1k+jokAg>Xs zc;(NHLbq^{SKe75pP?{-}GL=Ts9hz(T!;%-KCzCVN|m34{*h@bQ8U z#Pq?fLIf1ZW)HFkTfj$RMwy7<5+ssDyE<~d*vAV5#InCw^63eL9R!E#YGG^imXN1# zUJ;LF_THcDaOni2$s`_Afu94!747%)nQW7&*l6q7SR3Xpc;-&}D5!BESr|GZN0Lz% zjtG+{6>sgatC(&4@HWl*l+!|^)xsv#f^csY=-i#DIPF+i^|7k^f3F1pAci00z3BM? zy(ckn^4XMFZQTxj_uzzv*~iub(Y<3rKtRh%Xg)kGKSAiD@01_8cLNVd+>p5!_^um8 zk-@=mhz3fqDsKP3SUblc(W2&DpEI^?+qP}nwryKyY}>YNh9J3_S5r3@kH)~`dOq;aOKoURggn;`sW0L;PgK&IEX#o`Pp_Zh%10E z(X%#!ad96(mSA;KZY0(h(LrZuZ?)JE`acy?6X~EEha-;!@W*J0MQ3d}5qA zgjj5198L)?7dTkbc~I~=#>hX`FKv;Pqpy6TOdC;@@E?f(@U2@Lr%snYsj6VC|IWAa z{g1+x|Lj|hO|5^RIsdE&bSX;9uKyr%EIDDsrStrYsSgV>F)&Xkemb@qu_Qbr#_`FX zqZ=HeKIGXkiN27ei}nd8_r8X6BXk;(z1T~<+m=Pyua<9LHRH{oLm2v<^{BH zSe?}>54j+7LM7E91RK1}Peq1B>Jngy;~bf%n;K?AFrVFs9hE5!5vL^3g@-B_X+=Yj zhj!8mCZT2}2!d#u2!fD?GmhPu!`IQsi;r?gG^lwSx0-X86@AOFe7<{Q^tX74398NY z&WLlw4W*$G1u?a|lf`$F8F=UT$6yQ@h7<@>c``^C7n@l~{!!|3NEo614)1Uhzv$30 zO^UBxJ=rzLZ^&Bqd@Te!j8)_Po8kPqtEB}7i?iikYA_}!9m+?*vR3BvGkAJzLJB!jiZ(RKk7*TvNf@Fu>RMkQq^_abtSZK z?Bl)R`}p{ndH_sdh(dGD=YBoQ4jb);dH#;%qQsbvgx2tm!5FO2IZ(bm-`(I)b1^2& z7Vz7EAUFg(xBXbYJ%7?c*NZ`E$-X-fj;A-E}r>5clLV`o8X1}PT;yP{GI4Draed6l+c%wlB=X)X08tE`R!O!uLE zV*5Xh*{n((7Uoc{94Jhi*`lnInGR*Q9NFm>k?Ty2Bv*Bdi%@Ow*~`$I+4`+KeR&tQzw9SC(y*a$7ZwOAMR}JLRnk14zU2 zlB_*wDbcpBGvE0bzS?5(wrHW4=5I{bn@cLvicj9fHt-3rd83N+ZK_*GA=iJ%CknHy z7t6V=$DQ`i3vAo6{u0asbo(ovGz*+_n<4(H2Gk=r{UYd5gu4~^u z8Mr2Aw_Ex-$j{X`6`Q( z?h6YI9W9(g+)4HTD@I&lI^~W$7@#!A%pr_f*_;eNId2A>etUG=J!*8>eROo&eQbCm zLlAXzb|Yc9U64D5w;Q{TH8(Faz#9=wk>4CE^aKV8`j>WZMj=;SdKP0xpL0T_;sLs7 zJW_>T&Te0=ZNPtqgOli*4(~w@O60>2nAf|G88T&GE@rziTNj#m+qygu#^B5{WBmr}bOB&exO5Pqkbby?H~k{(XUgss*Km(Axo;$yB_p;C zBo1xH_d1(>Tws)#$MXu#yE_2v{($PY2C|*A=>3CD0t2?qG8W~@urH<;*G+0p^-e@ga)cWBAW)d(|`dbdibrM8EY5z6(+`pP$J~cPss9Qi~fNKmF6RiW|vebILBV< z1sJfu1`Wk$pz@|;zZYOmh@Ss@A55WM^oD9m04+Btd)QINB8BTY`G#wn&4zlHik*V3 zK|CE8E9KqY1G}6&)?%>$qo~FPt+>OK9P0SY54|dsGZU+P*IyGyZG&&y>B1=x-G$n| z)%0mUrm^=@-5v)u(>}TLu+|VLLiL8I(D%oVf`VygvFc3!*i?j{!Lk3fT~+`8VpkPx zf6#UR52LDf?)Z-j?%NO1 zxdPuJ?DS5;96B%CG}}JgJ}H(JUz+{L#mn(apKQ$W#gV*@Ongz`r`_{LhNsW*#(nGY z#@FpkP0#O>flvm5R4{!+on3te0f7))MTTPffyD|0nNcu1ZlebEv`&UDw7g%-_ zhmyG{;HIU;?yj;=PJ1E) zNU?~sY(cPue{?_qX`OH%Iu!(()r*XY@-&5-fK;Ch&h)M}@Nr$`4nQ)omXaO#HMtu^ z)+5EF0a-#FbXV_(F?ouSazzmM~OLKxC7zj%du zzi4J)$E)2kF9}vn0{BMh803SE%pEMIvYTC>{GG}XW#Wf6$144_odNHb1ZI2^ zPr^P_U7@uA8OCvnmt{ilND>M`44gwrcH&#z#Ji1xyfHUCy{X};|N1LE?X_Huw zC6R|-=dEQuvt3TAz-C=Bv-6Tn!_$kHalHrTFyZnyDd7sZDQ`XxtgiCwqI2<4c2H;V zh-mVKxgswcyN8SgkvM;a8r%j5)&UUADFvKN7=*2?Zm)iFe$3_Iqs%!ypnNpwXW#6c zlM~nh&NHtaIucC`Lf&#A*}EqVPDc#NJmkj~lAZAJj-k-=RYVj3em`j)&URpFyQDa! z;bRGiP@WmeWN6<+D$-LQsx_rIUG~(&U2xeM~DCj2Su7;L);2c zNE>AXNhTbT3D)q%h#U|siwZCqrCJ%*QzM#JSF@<93KlIjXZ)=VaA6n|nQ!b0iz#P+ zdj;DQ1&dG}{lqQM{s77tlAWXW3DLiGj0)G))A$)N`a*m(SaTEjQf1igIJgo}QY77gm04|-S*)j>#hQR~TpoY2EO_!%gFQ<%%4 zDjv*6t}rv9Ee5tVoo!?Pc@Ji#S9@-cEQWo1|HM8(H+N%sOyI8PAAY3^RE2Nu2j8cO z_V4}5f6PJu&#Gzv=~Aa+Z0Ka`!1%AQ$|ZG3uk|Hoo)r)Eh>x&+qI&TJHd;vstRZmm z`~JSaF!DGu7^EPAzK%%hbx7+91Y_=Uc;1zlCxKUe5a57o0)7H&5KQ6XezP{UP3I@s zvo4w)(L8?x1=g#A>-l>eua_RT>odVFw%hL_XTEuQ?z4Vae#bhuk1f;O(n8V(MWGfa zH5*FOzEgX)Y9CdRU(jzw#H(A)JLeXdK$m5PmrbjQyMTiVr^ zJHUpvC&c5Vt9Dk`X684vn-ZKi^iR~5Z`Kr_t32J=b1m<{AzJm$u{~e458B8UuEwaX z5V!+`fF5Eq6c!X06c`j46dIHwstr16w@g$W!dKjt;@X>fGDG?4{C@X`$3O5%(*?=5 zidnXr7C&R3rijadS8FV{>!fFqH5E>~<&1oZFk*xA%li717!Wa{jP@r4z3UeBs4{pE zBA|sq5xVNc7!spP4C}V!RH@RXi&9#ukPkMxja5x$(O9gZT}$IF){N3w4%1mOND{5E z|G@Aow%DFST|>DxJqK~J1abCrcFZl$`8Z4JXd06w%LswA8=OiJByAwuAQJg$ExB`MzN)jQinjn2xTU-0n{M}AJiv}(P-x0R>Ldg7uPp-!-%HMaeX(32+et zc^V;nc^U@!`H3QmX)MZCw=L46y9(@fgK@b9h=b{D3GrfxgK&|f3^e>)kCw*F=q%Kx zl6YGm(9K2+A9n2Tzx%gPCv+kK&tV(OBwF6ILiaPJn+g};u^2jddyn&wF0*DM2p4u> zk@y8*M6m4X^{BEC8oNu~Q6t5r@(Gi0tQ2askPeoMrUBWS+OcG=lnXQ${SWhbN}I)O zYjT5nz$hf{*TU;zP--9`9pNyYhEK$tjeKb|ppl@Pt~TRrW|;k48An?=5xvL6T*#o8 zU{SB@#AmtXbFL}R!er+GIG;sYsZI_!XWzbi#f#GNxL2844T}=knE&_>LaUkkM;(h7 zHQXxcQlO*vs!I~V67UvGOyQ-uS>&c9=-0t!=YP1VAgSG zonad!Sap$$nKCS+js=*wgNRbZZ*efiNnhad>2=I+v&e&TAfUUi@&gG^J`gd4ae86< zbC_QA${GF2&b->Lr*)u1!0_u3Sbw@0xM<>9OOCmpB1noJnfGEvX9PP(j5XRjV*!M2 z^>f#YudBJu3Zi=I+S$O4n$28a`dD` zke0*|p)SCzA?I6XNJ{KR63Jo|zrjs>ER^=i)rN6AMCy}e>Xa`}k#ROzj5x-_ztqYf zm5I32u403}njVck9kQ6@3mD3H5hpN^kidVH zeh?Y`n?^g7SV5K=h;W0@78A2xNs<8hEHSoy5ZcR<+~iqmFKcKa4MRfI5ECIYW8C50 z44mT;;5nCX`054-?WQcO+Ycz>VczheHAQAY zwKM;ZwC-LJs4!SS_eoKx&?s@Thj4=0QIVrlHmJ|Aq^a9DI|`~A7vS$}s^|FzfY|tC z@V_-Nw2oT4Mf(r-v{`!gQ9Kg><+g|ORa$Rou2v%sv+rsbdUIn2q>}MF(L~!6$3pHT89kv?UVL(#fdUCla<^fXeu=B2W9YgZq^`39l<}#U7s%+vMqg@ zF7;)NU1Y^O__`C(_!B4k6(B;!B40l11;5w+-#98F9a zu-93a;XfjxKEcvtKBjE3cgX3n-ghZZ4HPwa8_c*QC}eEQn^45H&|>mVxyoZJD?%sD zqO3_AlHt!I>~?7TZkP0MKC~$Mx}IIrd|u9PTRuE%yjB(2w8sEx$2x#_<&?99=V}eP z3;7Vk$iV-jJu-DKf#NfM~}rb`6)FBn0-VU>)1l?FxdPve0a!LI&30+D0K zEB{@OTE*W8;P*xZO;cxpFIl-pB3ZeCuRP*ERt~GL1Ktf?*}iLj%&p{;jkQUZMSL8r z7g!a(%JerQRW`7|94T)#-kBE?Kl#h%$d`j*nL=BMG443Soz-mNw z4t+NJh3qT}U5~?G-=WF{==}DU{VfeNqNv^sGQYtIDNVycU<+(EgYU>Bj$Oj>H1MDV zR-FrpP6z<6k_#!f@F6brsMjwu^vO~JRPH$Kerb=%CrttgHPI>_BIV)}IQa}k>H{eG zG~u8?c8=?@^1j_E**E&zK243tvpA?Lh7u! z)Cm)b69ytj6Sx*f01NXoNMl=(I_|8=XJT;9?;nJ@T zEV|+4d%bre>cSE;KyK)D8Zpgn*yNob3?ruI{_t{Z9kb29Y}Zt1Hp5tAsWyXHXzgr< z!4;lDdqeE8`O)0R;~d9_kBQK0FmlJhusQ`2tX~syXxUx`fl1fzNqgk%?m|xqJsc{y z#>1wkNwqgwj=Brhr>R_=Bs;Nn#{oa8foq3o(M>+j)iBq6V>Tz)>A>`&gL? z`&gl+f34x=kV1a#OYtwcd60-R9BR|`V^E0Mm#~*$?f_&iZh;F{|1O-LMQI1JsfBw|@~D|m>;s}yq!xRtAMj&oyF=-!#bvYfK*lUY8!FnKjHYU&wbF|BYJtS9V! z2Bpn{AXJ`O0@e%2pH6^Ls=}mkrE||j3fcwg-aX>*oF3l8J8q7m8YfDU!CN-WA9(jA zzh;Vgc?Pw-ZI4P_L096bv?yk6kdg#yB)AiY)hk&%Q4d3NaPGfKO$V(so}3wOL)~o*a_WA zt_s^VjXP!MYT^#Yr37nMK}QiKE`1lFjPn9_Yje^`Mxf%+3Xx}{e;39R>I22wQDyUc zg}KeQMaj&SBToCiOnQIt`t|T-r+(^D75U@pgl$j4xTVDJgOtAF^rP6tH<{N9Ej2fa z86P8;x(o{8prbGy4I+a@vL}UxFvSkBS(LiiYIwj#)r*uT)x0qJRPze5Z8lVdI*mgalv>}h z7(C;70T82Fa3oSAq#}hzJ0`kV|GlWF498M6h}y^KZyt z_fF!$%`oQYI7u)6@u4mz>5b4-M}UlTeu&6WDXz>As`s#{RHb4MVv*M``NUo3S!t+%$=2@^7F$nZs;8ua-L*Jy)+FCH8g7X}?)@pk7j{FLS0Z z_b8kdQwK2biyV&AKbfcwIHT&Zsv~8cSoc(wKGO)7=TXwmBqNg;35I7PhpDs$PHRS8 z9Z1d)KMh z)2QcM9g)T)3tn>#@38X>2d~!pwLc94%UZv42+tgaMYSk&S@wW$JpYsrwwP7Fuu#Kq z)5C|=n6Xz=La&faH9>@)S4MR>`ZH0n&LUV%kseH#48|uJX8KO6)dTBprOUu{_raT- zC3?>w&}4>$D>9zr#}_(Q0-!joWDfi^xjYQm<^4=lVUVP}BS!*Mzj^y6+ld%wcHeik=7FuhQ?j zvfR3D-*>rkJf&=3N>|mJimiL9F}TznSo)k#CXHZi_~er1Px1x`M6rkcQ1OV-tZQrG{N$0FJIk9zXNWW7=hy^(M>z70^r z%;{*`aC`Xi0XL6?RRPQG@f3-Q`Nq_@U@@GGpw1Q5tq#Dkls-@7{p$;jzhgC>j3Li- zfaH!ASyTfNuIVYUT{d|X;`oTVt2`FJ?$DC_F4e+ok5g(g!7B5iXZuuqr-by~8^vc? zo5*Tma{YZ{WydZRH7yWA^DH?dW^Gh<(Xp6P^A5(NDTWRCj@5kSo4hQ z77!Ib%YA{vd4o9r>x9uSPB(f1W3VFQ(F@8O33XvkGiqToZsS{%cQ$Qk(o(wDl!wj_ zpL^AR>#k<|6TTO3Yxz&e zYIs&EqM*2-dMJeC@m?bu#n`8B&&^EF=Ob)|f$)dRWMm)80J{BCWem0*6O~m!WO+=L z8qzFb#!erqU~XQqzPKnYPszSXCZf{u(49PVEI1D;P~SelXAl|>Et^jsBI%7Vy_fhv zLckTdzmLX13bU7RU-WBupy3E<32r(M7rVWcm4%mpf4r*QfZNg|-~zOXREY_>9QOL* zL$A?N#lfU-1C#Bc#8NPD_BeHF-^Z2KP&tj7zblXFl0=MlvlJ`pq-V17v~;|aS|7@c z2A%ba3*|^tKfB%>cqn| zN}p|cGo7jX!cnH6)QVA)5eH+jX{2+IQlR^~YHba2bYxT8XqIfF(QTA6METa$N0WNj zA2!-389LrhzP_(!HS#b`8+CqDIcKUFCrPI`9{Xw|YLH2I-2qi(E+1@ZgJ3x$0IEx%<+KKNXo9ES`cPqo)01lD7huugIH_r0;8$B2%#J^qI|?4i?6i{nWT+ zYYZXd;>qXpdOAU!8W@W=%pq!n%u1VNt<{IooW<9gT;4n0rS+qfgD8tukZrZJ7ixxV zSP^ZZ<&#TRC7me7TkQ}&zS=cC&6p`VmCK#+&a)`UdO~v@nnua~+ArWK#s0Rt>VVrQ1CDN6y{^4_TTa9UBV03FwDTGRkRUpPuE3Yi zP+qvG%pbkIu(yPOyu*@S5RDfBDrSP)ut(6HREt}|s!$(5yv#R@Ts3;7j|fPeJ~lhb zohCbEH0W;FwrDTFKIS{pnG83SnFf)Tlp7#E*k>Oqk?AZH3d3Xc>J*{J)3byZBHu|l zP0NCgp{+D*G0OB=^fd~IDy$flA;!RjmrLZ=L5&xdR-$?N1Ewtwy6%Q@#wI@V52VIF?71(6cR2QWR#yCo1C@Do*YS8o#g@CpzVkz zVc^Gex4Gs_p?+)ohRNFJ!Wx%4u)elsU$iyns%f|7qx`t+FW+FN%_j1~_;M!|2L-#Q zz@#_c_Ewjd7pJ#^lQ!kyPmo94XzRQmcnR`^O7|q#GC?un{h&({; z{6K^&1nIJWAyg7g@Dbu>smFVNMb!?se8}B`(D2>j4TAGMNY=NbV~|fUi;&HhNi(G8 zG3Osbn7HFzgojJH@QJX)q^JnUU#%yM&i@Y1?6?N{o&WvV3c)e1jZkp16-!@zuF zN|b24%ju6@y5G!UgR9VnJ;Q>Juue;mq_EwGU1K0gfp2QPgP>%ru6ON4J?Icq8+{Vu zdbiXT8aw@dOV#8p^JYx6SOx#c(6GysW@jw5&(?;{=8yhHA@fH6 zc7o*H6e|8~E&y%Yr#Y~kJ|(gu%W0im`SCijg|45M8#OCRQY0sH_iTnv}y!S`zefe$9|<8#;lmLp1m5 zy?eo!PNSX{?PyJ(AUkR=TMn}m^-sxK@^5DD<3_=D3+IxqA=g&aTcaIpV0CPE1%Ed*i_1t~ z$?oFsdV7=>>r9cQVRUPYQUOtGb#re=5RWi*|So``v~PaWQJiz|qt zm9Y|<4NkNG18vyp&o_IFk8=&_lE?|B3zX6%x>_Ji#voI3C&*MmW!FGEWmckX%U7LT zVc@(`#~=eFeT!I5U`JI_ves!JVb?q+|65{MT|7?N8n6p!s3#QUCzyr{Zi@>*l+#IK zhb#wh)Q1NA!f^E%CTDul^iH8wn!S1a$3QKP+RoVdBcAb$tJJ?ELOdb#!R$lfGok?F z9EskO;Fp2hFyN3%z}7W8T$dci!C}ez|3t6Imb3EH{B+t9{$HxJ|4&t}f0Il6^KdSC zKzb!ECB3w5cRjzGkR$|&l1%y$bq0+AiIH%T;=zge@rmJq`j29aqq1go6vANu|*6!W0+w1xUCFI%)Tx0g`I6r(74)cK z7X)+Hgit-E&kN_KR_k+dhVSzflG=|gI=^2Q8$c@soX4zd5pY!bZQzI2xCr5+8y{7dj_z3iD3v3BWh?qeO#$ukGD%>5$uc#O zAqNVIGBy4o35xPkHDO`qy6QXwW@O9KQsx~K19j22GSW$ndiB7*WqLd1WL2dV)n!)t z)>4Wz3-Sn?@L`R8;W{Hx(fWppQo^-Oj)GF+?29nhl4jH)PlHSAsarEsc~?sc99x=l zX&2Fs_4urNG^q24lC}Ix=vyUJf@PItMmzeZ4~MtUBBp`ixjjT|%iU6eIVJKIYP9l4ZoH#cHZ z;g!eG#-s9$yqe=Ws~j<(PHn8u1tMgyOjVs3mf)>zI~1T%hN?~FP`FaSSqBX_#}=dR z+z&0Z<|xI6*~_MP2l+%eHO+RiBPb1SshNa~&d6hJ#fJ>%uG|;{`K)D4T{T5J^QtPK zkJXk}&B<}V9V=*JZ6Z;c2ov(1aE&@F!x*t51ap^KhB%WffiLYdD!QCH2?LMQ(HRqp)k{xdZ~LuPrh2??E7 zcvyD#m-eW=WPM~n9AsK@s-$pLHGl>!6k%L;gl*)4g9aKEngPlm>f0;kR5Z8R+zk&1 zP3Lgs{amQZ38fQm(Qxm8Ytv98|89GmFhF`bYyG=Ipyj0ieTD)^=d1|U75#a^!-d2t zxZ`I2%dkiR7otM{y9&5R`=w3%d|S!}VL&A`Q7i%*n@ z6ehi@f)_2(%gVaEYPk^kx!M4LK-5r{)bEL+6;qkjWiJZOj{UM}GtTm@J~c~*7G45r zb_7<0shXquTC>!)z*c5pCQu$PShTiWH-IGPP9vN1+m-coFtk1O@$x@)` zu8Hh2Efinsm0d*)$tbk2$k$45}l>eoW+xX@n+3AAoa(D;|oLuT0r z*?WrW24&A_tZw1hhBv1aX?SqVI%i#W_t8AoM_VCg=g)h-rcb39R_5Lcby+dOgbbCM zg_Lwr$qX42wZCB{DrQ~KG>}?zR5BvaTIy#&EuRT9>Rbi;hT?jt2hd#x@k3+z`99Ul zBtO(s-&FQBd(h+P;ZSf(LMIljwQJg|S=aFpbgYulUY$3)tJ88xdUyx*b>gFK>Z!V| zx)=>r7w%CQym55$XDaHjL5X%+fnMCySLlzlf!7DJp&w(=b|haoV7E8<0K$5# zK9c?F2Cs43Rdx&JzhoCvN04R~<)rjj+b7=uYKh6&3E$1(X1cKU_l01#b#ng76e2Z91k6vPKs$iiJzG`BA zG=5BCUc#KfpgfOY$Xz%kE|+_t*+4_m}6#4tGmgqZo{5GxKM(WvU=) z(3sI{WPDOKer!sL#+;y3RaRQT2OwqOno5XQhs<(`vUUf zt0=A5R#VjM=`>N7c2-ZC@^)9>96pOMCacRcFmxC87QQSWKdV1`^O3LOS}pJz3GJ3+ zhKv5_s#B`3m|*|glqG#em$D!CY`mtVZ9a694#98jcc9iVK)I_ve*H*RA zuIEtEQQ>fSl`yj-dx$JaSwUHmV$HOP)_{OxkQFZb?nx4(z;$X37AP#ZIi4X}#c+P2 zY=Yf2e&S){ytLLHow^OpR1JR0e||!iKTasD)J9}$rD3~JQ#e#peP@Kk3Oq<_W)aF- zZChWavSX;Y??JIrz}DOkq;4^gM2k1993s4niDX11Wp$}y26(lM*uj)Ks-cstpHE)2@R}Y!9 z1%m1TR0@p^c;vVZ*ic_0C60tdWZ-j}qK4r^2+tXVSrBF#v7Ml%<2M9hbx%ZqfLX^N zpcwND78&a|{M`g0o}kY@*vU-kt&^d8KG6mcz}N4Mn^-z{8-Kiw2*);PlYX02P}hEf zR!E8+$6ACh@a0~dlRlh@K0Xazs{wmYv#8k$6Dhc`2F zw@G9C4Sx_=ongowR};a z)yhaKbDRKPUr@_Lj~<2iWxgV1=xQwq*^sdTm`$V&PZz=Pq(`R zk7Py%d@6KxxLWLVRAC%Xm?Qc@x+H{GaQ=ki`#!7;Je5 z^8;-2ruuAHeQnsG?5X$@J4BU!$9mLUuo*kRV!bKYm-}v6Z7rORwk=08v(UAOZ611z z8>NlBpeB8$Nlz2GaMoM??NaAqO!X6sU`HOXZ#cc85`?rTu>Gk5Is!if5c1BV1i~Ky z=}w8F1dv~e%S*#iyX~+5oTUT8z&St)Wb?>l`%)F);W~pt0RYl)c~&d6<&T#J#aEjUGFl#z`54@2DHrn*$R$@ zdq)lWDu-(Ng$=WGf_6rzWx`4+=p7Up4b_AIvlrii-iGU6)Os^2_Z{QE!=mLCVwf#I z&ef7}G-pAl*E%N!OMWlK4e=_fuT=&$DuAdJ{McG<{#(E4+^kk4-U|MxGuSNl8^qmefL9Ej zE-yciX50+?!8z%uDdZh{fLAfzs;XQyHQ5S$;=1gA*c5`DNksec%N#%eYb7JLQIR^R z%N$_r2o=QzgG~JH`-mF?*fA~8r!kRQjTy;O_MD2< zk==$xzHJqU5`w8fD&kW1uRZ+Zu1qCat-!vJmUhDAtlKX6UH@3)gM*#~KR}8uybD>c zak6nWeIs8@+qm3P*Aa)HGeO~Xs4{+3;i`{%Tof@~mVWF77FcjLa5kA35#g}X-MKS~RYhl3kpn2CY)nlHfzwhT?K2`;pLhU7BnaC7_nTQXNJw8yyFry)E zzorK7Nu#Zb$E($2E~wmo;V9KN?BG)p8ug*VBS3hd;eSH8-@-e7_l4jm3+Pg=eiKPq z3NT91rbei@En0JQS&I+Yxr8(BWJOQZKpO{1+LDZ520_h;8BCT>YO@+lM3dqOb8_uDgy4-3T3xdr`DMvbPv-XAO z_LRU@xE%BNqsF25vDp3sE=VTzhH`x|f`IP`9CP5USf8Gto-i);s5>w&5Kr~A`}yAx zTqE5O+a|RAuB(zaD4ytB#=4=r^|o|++eQPclvV)mC>ecUz=2Oa^@kUnR@Cn_9f@7z z@fX{4i9N$tdc1ZlR*Z8+&1Jx?Dp$@d>fTOQO5=sF41=;k;S6fve`yClu=}zlQvHxpVJ5 zy*VUH?)w&8PyjiGX_89GDJaGaoanF=0BIWQPgTT>mF zyVHqJgsQK(mClmzHL<`in8Jz;=`Cb;C^bWuF* zjiJvFjZhzd#v3+tl@chNlBDaxP_@46NV!001=SVLZv4tr_hcK|uVuS!tjf|~j>&sw zqY~$`<|g}_W==EYRfXozL`O9%p_j%2c-ExuJ=rm4AB*UA$1qcfnwKH>Wmh5Pg)|QO zCR$_=XNka`;HpVJDsx>SbIwS51C+<2nTBf^)VtgEEK7VJxgw`FR4^OG)Am3{RWa;w zC9ftkLbh>wz(-t8xgMaJ-`z>7ubjXJvQ)B&liEDiwXo>Z1oDHOfm;gp)NHc9Qhs-` zAhgx|BpZzTPUm;<@;-Q(CK9zCTQGpr+OQlOyCf}MMlzH&o!Vy2%Is^X8#+*PkfwJo zUOs|BNLUb+nnpJj)R+*T7!$XoZfVKM^iYhcYAW*0S$6OMt(eM|sbS_yfN^RocJl z*|qF$M7!rZ4Kv61>1ndK;;zd4qBQmXPHK2iRGrRUeermw&LR#}oo>6w-7#nbl*-vR ztH}Qz|M28u$8K@}t&-+khK@2lM)*Bn&Ez)q7X=e;W}5g{p|-i*P9rr7UUrtGlZFH|v2X zx$fUFQGu`90di!v(ob;77`JE>V7+GD8oC9|YThycxQ2a`>Vn#tw+YC*j1#152HR)b zNXww@nQCnL{#STyzfy~Hu)J}=s_KdAd^V=mdX2vMNA%B~*EN{Eq+>E;scTqcscXtR z*Ij08u|4O|$l3_mcx{Pl!8=PczqOcb!MoVrlw+xC-ZO7A>r=Iv-&Mh#-&Mk0_DS0O zq2np}&S=0Ra6-!^_?~)fmUA5=-_u=&q=@qaqMOD9^eT*63Q;1vLHk5na4wbuSt@T%1?Uh?t?T(imE!P{~ z4w#!*tKyQ^x1yU?9ys)B*x(gzDWi5kg7q#bt(|Ik!_8=dnJ(djj+V$0xwK&Q?U2D`CuI4BLGze9)GOzRleo9y>eS zH8$7iXh&8Kmw|#TZ#JRP_8g(n&KxORM074#S~b@wj_f~#+%mVOnps7wT%EZ?M9C`K zC<$um(ew#*O4_0t+6$pKQ#+zdNq(Y}epvK~cSBTQ;j46#lm5a6G?hs3W^hGt$oIM0 zRDOwSVCzE!tul#y(gxrc@P{|0rGA74=$%B#1J6Rloy02rw!+9>1S)k_@&zz2s`D8R zEdBL)p=~>f9y3{hzQME=8HZjk++M<)RG~YnH_AUSE=V6J+H%&a$eryS;vfb+VlQkR z5i&%Ko0o6qpn80W8N6n|5J65Zh;2SIqQY6x6X|H!A}>UpI+_%b0WjzFPo%En@@Z<1Cs-rxFrXyF$1Z4u@Z{v6?IJCbWUywnARm3jvj}2s zg4G}d@X!9dMQe#&)*6cdm?D`(56PZ)5@$%lbiRnkIDD2~J9}`XuxM|c6rMw^d@kcI z{y%oVx{GY$7zF4TIIE4+7q+CmgW`VjmlWhWl`>KA_U-LMg`DW zRz&^FexLJ%^W=xMmN;1Q0GlJD7e^GP$F3{L^GjYT>Cb3$Xi(5G>#;RTNFsz6Nm~^n z6DRorgsPE`o0UoT0HpD;hUH@e5_80!1X0xilSCpdM$ojXI1L~gXy(ZN&UR9IBJvX5 zL_>Vg4q{SDD&vZgc?nakZqa$usTTZh$N4-5Awyw(lK=Z#R38)z z*K_c;?j0MqWBs=7oC=pRhGUBbRaxSC9EX$Bma!>`ehDfY_$#Wxjt#0{ zp6CO~w7|_0Av?OD>|NKMlw(c%#4JZp^qq@i4JVc4%D>5gR*Uc|_;Ziv_>**cZf?^s zrh)s2ZJqFE*THPmNsM<>;ls~I{U;jjW5Xv-~4NnXyHBnG-6Wf6$Mhuxo)8o z6k+?cV8nYm=$YNa>oJO?%?+<2$2UUUXD79=k0HD#R-9%P7Cktx!0yz%@=hGL;stx! zXN2PCvE>-}tTRpmY*zM|nWyS9HBZ@UV3N9SQy1}gD{ZiiV<4@XW4%AZ1myOE_aOhZ zturbqA)H4>K9s7cP!0+-GKvU?7IZV~FHc5@2cLi*7d8eXHV6fK5{8aG3%?KfvnC;f zpS(@f%2Q%vqD4a80~r1>^wFcL#~S%RoPASpW>L3o$F^HbgYhT zJNaVU>f3*vbF1!sIS;35R;|5i@7hmuuC?ZxV~$}Nzsr;NHi9(yTJ*d-L?nvD@?=SA zGBhEC8nOY7T8Rr-CY}nDW`|uSu7$Mbl+&o$qO7)yPDR2Cj!NA$OSNw-3QI6K;?y?R zt*J1sGD$UV!gXlG4MkYQsD@8oc8bQ}K&R8dp{xdC(%DeM92(cn1Q}zCQyDEiD#{Eo zmncY}3Og1!e`Hd9IwTWIfs=?cr$Ph7e2|OQaKKzcR%Vq)D4nBY-l1 zX0b!Kz*cEw^56tgVw45cM5eDn`QS4#r5b3de=lPWz7xfmlf+(AB9vtS4w2YYpMwAW z=Vi4-Y2vS9x&QiDMov9*QEhiWRF{-ZnZlUkW6UncPivZu6{{RagDom$A248ZnfS*2 z*nn$p27>qxDvPEK7=)o4PaLM^t}zpv_+tBFL;GI;UZ?i03uH_y{Z^qr`8YA{==<|y zQv6$7i}9Ihq-o1AjuQWX=m4o1KU}`Q>t-;N^_e&peN`+^2hH0?{;--Ov3^CYR|oB2 zDGR%NWr$k`?VBaB?>k=qI2@q-AS$x!HE$QVaZ11ax1Sltg6De?a(Y@jHW>evQPxG&xHp=W72w#xO{N937T^fHDVGcA?3GmdJY)U zc!!gS#2$w>?9HUN+{7EbqQTJd7=&F5y{YbziATBK0OF*}vw(L0H*va6hf5}>B;zWs zd1eEL2A+Ml{!PMxu?5h~g5rhjH zQxc1yEa!ta>&)b#xnHIou-c5SKH0uo+F*t$@yah*PNl-cQv}(=x_&U8Ia~2pc=HJ} zq-P&FccB2hkgyeNciA?)kT^B;jjb-w5;`svBcxD&JiSrFsXws@P z31~y1o%b-Y`wJn$*0SBc>H}4{zG1+x{DoTBu_4GEM^%eRy^Of;@v;g%y{a&P1=I&% zS{a52+!BgJH){ehy@(2jH{$o$Zu6m29}>M*z7a%BsR0{7m?Rfq@_;EMc8Z&k+zE&G zq%q>BF}S%cbHEn(XIa`2w?0^?B6$bC z7yT<#!3U)m`ny8G2hN+uFCqbn_Eqi`O{Ca}2Wc=L1-8$|;0F<~VnhTiA39LD!`q34 z2#$y>1u6TDnm_1zgdb;g`;aQ8msBy3^V}lFT7h=;QY|j>h1!nrwiM9aVo1AtQgSb; ze(lUM0~n^Qh|~BnNIh*~X>P7e%Lm_Rxuk0!PB!$5<$X@Z^!>kh?3d>@0KNo2eq4+H zPbdY+{~b!<|K}h1?|LskoR`{BBbz0W<;$Vj197xAia5x&omB8I5X_-&4qVi!Fr%OF z*=ET#b{>n{2*@_WB10Ow6*{T3f>G)^shED`{pd>7D;qY3I`;N0H@?2MwQX(no4&ey z5Bb020l&r_Qquh1W}z1l+9%#DbrfeKF@lZHp@Ib@HB z=e-SZ)p=ip*Aw6XbvUtj^de9^aLRS>*rzo6!Vqy3)1AXWJG{bDqcUL+_cGyghllAI zXO8#r87(HcC4+FdHAh_EybU0E8;Qa6{|VXiOQ@2YHe$#+^~RjI`UeHWIirYTIVo55 z+38LB(F09rklZKR<$_FdCZ*CW_d?r)qod8dg4b!18*}n8_*;_-X>qE}Yn1z9vFIAm znShZktOgTgjH(TYnzRj|7Z`SZ>a6_Ldq-T1#C3aVm=CR< z!k-7rbsXv1%~>7vx?o;&yapqw@Uhy4i)oHpV^j?kWdsXn}?@L&AtHoOYd>{&`M2}V zvX!#1&hwG`_X!*D8j-P*`NRq?Z2M=(cR%RkqwfNtPSF0-8d|F|N%M-3tl#IK!iN5a zirGwChxTwvvJUzc+jv&bVPATyc(L;iLM)ovSg@X{UcNn7+r3H8N{UGH)Ms}RU07*u zZz2M{R_%X=R#ypcJzu-~ldL?~PA;gmF<>7(KX?b&R}P{XMH?hUL5OPWa*>%l6@Hl4 zbKyTdRDJc=CBe>CQ4Vy;>58ZP1W;6x3TFuVbbR$RQaH+^oZPFKsS(&}X|>ovM2{W( zlejPTH#RxkP!nf|$blxwzpm-p=o;4*3B#hUgogm_^(ZTG*Vz#9??-fO&ll&pW(Eix zc*p^Ilqc^WTl7WVVO}7+`zy8Z;e2jhZ9lN~!ZFI$__t2B8{d$ZIySUCTh^aQ$uwveQ{Vuh~K~kVXI?3XO7_!|q)sr$r z;q=p*K1|+;_(J)z&-fG?8ar<40@q{vx3qI%YAsuz-oOYjoVnBpxgwW}gDW-JC_H6A z;?t|hj7`~|Y|_RQYkSq}ZAaR@n*2E5JK0A!{sH`GV3he5FdkBz8l6B9@4ez9G#4Ei zf}6+Vos4yQBau-Mx5Vm(@epT8axS17S@z&qFUtqSthKmh1V^#RxlGT^L`!jOGyNd2 zj_hFV*bWnmvPI!ELO+E)Rwq~G<9<&UVjIF`FeN*E6#Ki`r=T+7{@j*XTRnsO2qv|` zUSV04DXGt`N>s|oa**y14cr61*Apoiy=m%o)-DoVTFEV}Z@qAQfflNxO+O@N3-dDU zNxWZ`07%v}im4!02yfD`x4w)cG!G`;dbbvt?Ws{Mv45_;8arW?+n^Yi?zHj5a`)Jg z_TGIV$&D(Q=P^^zafetuKa2Zg*{XiJ9qM2pKDn&WBKG8dJCW<)k>8-t-@^m?BkA9V zHssA&^Fyhc_s|?YP@dNVUEyzk%Nk~}{<}&3!kaLX0reH6Sob$W;26~%;iGXJ4V1J_ zqK^^IPtR#9OrFHB-n48J>THN=jKU)p^(Dfot{f%0EY7vMM7SNqKfjD|x+iunqHPNo zO@t;&s^dEf3j(U1!v7_>vXt>KwYW?xmzbohAbek~N@WAhI zu$Z8{(rZ{baOU&v0fkXPn#h!#mhqs3;h}?DNO;eW5;+SN6zwNTox%_TP>j4dR-vKu zmv*c=CZ#4Og(ln`-d1V^>*hnmbE=jQZthEo}fg zXLW-#UER^X4~8HTRQuZKayE*LDw`orz4D#un3OZ#K$6;x4oy}$P$A>poi+d;k)>IG zm;fC318dc_F*zD<4|(7|g%ht-POLm%yd^v?BzY(iT7@!^z0Qb}1`RUzWT_67G=U$^aGF#<^w-c9;>$N>U z=fN>9JO+*L^&v|T&^cZ-0L7jjeO#Wb6j)~-Q=6yEdY*H*Oe z|LTqNQt2fWAUq6pE1cIAD00s&j9a#kbtg+J2xzN*Wfn}zLQ%pk$esgF;R{3AVb$LV z01o5t?N8DMKp^G8>xy7)*uHE?sZt-F-9dsni&uC-JEq?$r#+j-JUQd!D>);Fo8fER zF$-4iL(6vZ+m~1EYbMsX=x;eW8X@s`zmD37_ z&sM*>`w0&_{tM;aihZs-UD{p%Q}wI;XB_NJ-;MewV}RnwP4z2m?*#APps0Fa2(2(5`85@` zegKKuTb531{*7rrS|ee|#2eThIrJdLoMzoQ`X|*xTVde08bAa@2PL?&tb0aPKA`xz zT>)0r!*W~8k=!XO_x(f2+uZ)kM$z^P{7*{8#t@&Nc7ut5dbxAagPV2D*@D-ic_Sq# z>ktN;eWtvh(C$gj*hd~3csM(2Kb%UI6x{i}c=pf<*JO_EqSvYoo8yVGil9fpMBT>RVT$Msv4>^BttJL>igvOe(X!g=%y}n(l zJ3`+1%JKO~*~Wy;th6EDA0*aZ2J%RKk|9kF+9b`;_n~n4d&+Opn!@B#om6^t`(JT| z;=VQF?U&@i1o?R1ziie!@7k_n&a0xUb?NZVFRJOXtEzRfadq&{t95NB=&G}&@&mpg zC`~#oc|$o_ZOS8?RgTCsOFVXPl=k4$(Jc-VH_;6ogkUPLNb57Wk!- zOP0cx+;%*EYrRwYM=7}E z)A%Ts+1`4%j8ms5(^cy&q?BMCi9r`WU zB9H-)mE|0@)}FNGegUjO%-}kbPf$VW*u}pF4{PgA&hYrkmCZ6C^L_>WkUVi`2M7_O z^L4cpHnw*5R(4mm7WTTE*IJr;s~%C9`QnS95{0bD4KskCaoF!Kp%s!YM`H-MFDIqf zY2BMtysW4)E^+W;(Yh%d*A;GQr|zU3v4?P19JXkBX$-6u{F%;@+t3;2>tZPKXO_oU7CNUmOiQtIAGmQ< zcfI)a^jbtBBu|->R7zLaaYKD6W-s4b818dx=%;+INnajYJ`1)F=rL(i6AuDQ}J1_tAcz zGCLQkN3dZPg23_I7l7&z&Tebtn#+ImL?y~??uu8;3)cN~Yg1**LEu0J{}Gji97HYf zQ9&65@lWv`&92M^uBGM&*w>E?{S$;BU;_3c)Ax{gkqb>mAA&AS7UQ|aE45zn7X!SX zoRPWSstVD84wS?@NP>Ro3<)zUt0-!dMAjk7m<3Fd3w|d2<{q!eFmiF~-T`>E&m`xX z!W?4%#xG*8uXb>GQy9nyqgfc}YXF{tloOR7slsh?@Lnu$KlS+F5Sf1H18i8o9y8)H zL4vRyt9rVTLaeGfkn%O9pm3lZCJB7#5h3{7t>=hx4TGp9dxKp;kc_)Sdv!B5L0pJ^ z)ZIY1m&S0W?b!0r5-}tvzcN}-J3b$RZ;R5)20Xd|{lJ=ci}Z19t~MAgOps1vV$L3X z9JDi+xcb*MF}3K=Dc`a^Tcl~TUYWD;HTpXK2KXS>wB#PZl|z3drG50w_z5_dC+wt1 zyR6nVC9XZXmcZlTx`t-q&ukWrQzWz^$t3t?T*CtOwpu`NZKt?3IR|jZAOFl(;inFP z?7KGU*A|SFtwx%h&hJ{Yg%?7}cR~HM)r2s%v&`%g(|*xot;$|lo?Ec~K?)Jw4rfA_ zgZJs!3ofp@-L3Wj*MF1cC*N)f^Z@zdD{#MD8xNb0hmIM)mW#Nay)mxiY>v4!$8k;U zZa6zKBU^9urZD1ruKi#;S4Fm5?(LU$8q{lh(8 zZ-5|PSaAbH6-V(RLS20$Drh<&AltN`NTM|u#lN)ZEI=AH=s`_tsX_Pk%TY^5fdQ|e zKwa67Ly+L6h;u}*gaW%Fe~wEk>Tn;%a3<6gSwH$9CKUGAc4JvT===TF$`*b(hAeeK z(q{jki>=NyPZp{VKBATL4sHZt+9{JBmmv+44*c+zvbX4mo$?;V&Z3p;4lD03!aakB zP1&YjgHCa-v)c_$;1EzY-_# z^g;)fPB}Ya2}X=FPB?Lr#(RLw>(g*sO`?K2HY_PRR~lXBMEI^_9=6VvCYsm5U||dJ zxFz&X)re14)@6lD7H#WnFa37mHfcc>qYwP+b-9B#n`6Cp&yX~-jvnL%y~ZpLc?LF-Xa!(1 zrWj3szsTSp50z~|{2m|1Cc%?uMw?cOVO1-FAO(L>{otGm&dq@9nn(0JaPvZa0AkPl zvb=@&g0mbTI(^gRhx?BEt~yYE;k-*ustUVgl0(fV)%I0|*Vn-Rjd1 z{{fnehdNZEV@Xdshc-h_mb7T~<6-?ahIC$rHw>$vTgidZOhV%pQ&{>L_pEHgHlW+w zNJvHv*9$_?%#&Xb`^3rrOq& zeN-wF_L|~T5ls;88lVY1$#(f#`b0_t0^+YDs|dZ2RFwOQJMWve(u!wTM*KpbajT1Kz2d|=glUVHK)JcJgNie8?<+>8>ra50?rh=e|!Cosj{Q|QZ z!WjDnSC~rjwpxX6*0D&J^e!3PXp%umGH1hNW(U$ezC@RMkUmW>Tn!j(p^vU(LpCnB z=q^69^4qV$jE280DKbCmNU!u2I_&_Uj|om$1(2(Kklmock1_i?YcUtbKk9>h8!&o* z&W6vy4X!~t8bNhO3cd<>4CFW9?F@3V7h=Hp?7jA?RhC{EtHxS+gVyz{puK) zF>9K11>|ZM{9r`WFeSaXM%FMb*&35;l}-~IpWIa0q-=#M zCe#85WN`RKKn?icVi^;NdmMn?7yikSRP2g;{3;e9kXwstU}4ShXO6uTV{FB{q4;eC z_hFxiJy|<~z+TkWF8rIuWRG&*l4d0geHUu}u-(=jBbGGzLWA8>pCDRt1<=+?+1#(8>&aytWU0Jb_Lp#{~$bY#(@GRp;XvABlMSs zIN{9K{JvU;^LAs_<$+GRP`1Jb-$Dvyyq*YACviBU=b=Nw?XWkEn4n~>AkmT+MGKE( z<8j#=M9)Y11%|Xh$qmlvhc9ynV>JXUImneXgd9KuN_NsSQiQ!>7j=TihdzWAycyxQ zQAWKa#a)dEQ()~fXrRXUwudu#M@Q+Z}@Vq z({%X3PuFsiln}g<$HM7krUobsl=J_#4Zs^>hZS<2%O-y7iLpoGASZOKxY+NfIA19o z#O%Jrqp^J)ZGb2SH)<O`pZ0=tuxH?t-$LR5(#b-G0##R85J z)iij#8)i+SML(}Kr(MFaNShnuqtuCTJv&mXjCg}QZP?Yqn^QD6!#mCFs<97hEEo1yqt^}J9V^N0OM!U(!fa;nX@`U zkl~pouOwiB9HempzGR=|m1CMiMany3MqzdS*h#7BJ|8?2W|J_nb4*FB@Q`c&Q&mCh zZ}b8d#LCa|nPpz9#f}Zw)aKMox*f8frSiL8ftinI?iAPlB&rQ7XadvE4GN{02VhMO%{?`gIfx+lLvoSsyb*evR0Yo&b!sAkj%+T&*8Ja^u4-NvT$4f0noh=7DUorljz8J=SLMc@1e%FogZ zOrCvdW?P9%$KUNd_fgaQZVR0)FR&V@hZ&7%z@ip#>8(m?sKclt;c}P>dDU46y`x?m zv1!^Wf{;7P9DD)*c`c9dixJ4YccbQUfuR3k z3J6(7*>1u5@uNxhf2tHn{O>9S|FM<2TUnDVm1_1Xu%(i`&6&6 z$m+}6#KD?oEZMHt0&NQF?%TG1-d^`PehE~VHG)y;B=$>(slu1z%rqAiH2lV}bdEDl z0{W#X1ON}4~r9#)D(rI*%hk}bUMH{4f$?h{akS#Y{#D&ETAbhmi z&#cF0@nF0<6ick5Jrg1n?=D)-SAypWag#_xVncG6No^AGs^P%H+YR(ri45YQ4D^L{;st@s$mM?Y^DlsF^;>mKV}@4R-GQ z#lmZ_gCSKG6mdqn1U($4nK*TaWmewp{bwKFv-F~#P@BlJ%v6Zd?Ohn*6niKkt_S{u zxdeFYV(1K4ck!C~unx}#|8e&_E_bceluHy#G>&A}h}n(pk@=DJktGBEYpt~KYm%SJ z(qWFA9iGWF?9pQui%~&e2!lysG@6Y)1^#RN$JOa!n)ULyKAfj`PBb@BBZ{-W~j`JTUD8paO+d;QG5ic;7347zhgCHAU3SI1X5(hl&#l9#o#g-`2#hxfM#cVAR zk8Hg1d&Hv&Sg&9-TcUK=#Ry0Zkbx>kf0*T{M2#t9q=>rr71*_%nP9Y?xumt7g=lz* zh6^k3k~0n#M*^kzzx24t_Q`09!ahH~_5zPl>DyDNEGmOd3#9}>%sA5|Wb zDJ?>aGoYt8+T}1_Z&5Q{Bqu?aKy|PZ{NphGieNdHMrbdH+o3t90xG$i^oN!U)7?<` z#PrZ;8~tk|E(QS3he)J#@zvq`kSKfy=Y{RcL-Ni~%qJEoZ9~hV&eai{`{%~_LQ$`( zdIIQeLdlW$bC6bQ1thh_Ck}JJamd`W7$=6Mw}#0Hiy}tbqckh_2^{tX{9Fi=3yJ=M z|0j$o#=itq|LF%WLj6x+EbzYzDfx>`rlO~NK=A8N%b@;s--DRWV+FK0k+hb294lvHCiIT zge2{*G_5*`_|XdlVt_51ar{%(@$F5)$8y90t2mO;4pGPiLte-tnFpq^G?uC-E&$`js2RMHk0Yv1ING=mF>71Fb z$c!zo0a%w5UpJU$MOqP6+Lt$WNQ>@eoUNIiZO|;TEI2nIIs9Ho>k=ItY=K~5ifHes zi{JCugaQ3mt6#9N^e~%q^NH<8_ng?gYEL|8!{B0 zKv3MSdj1+AAr$FOL(1KW`@z^+TEYxSyMkMS@<0<24Y^jw5_L z=l-?oR>E8~m{wmu8J-V3A?YqWz}k;9jFS12q>dTRZkHQab{iBpythdnh=fxq7hjq4 zXp7J`%LTP$8s|8gB+@aQ7oOT?h7|C7X-|AUYQ`6uu;#99M+bt+Tr`=Xz_;|2HcYDgH2H;|UA z-qez{H`K5Bc}7b{SR`|rxZ zgk$Sx(U4QWjG74y_6f8R4=3@&lf;i`kP|vy@uSQcJE5ggK{q5MJVi$dt9Ih><_i1N zj{@`_Rhg zb$$8wd-4XWDV5e0%m0-32zLvH{qq*5jT4XDrhv2^ZZRgJnFpuTQI4qw#~1#sAO)hF z;}E!4;5 zCBAvI#<7AW67}TgT9Z3`>7#ak1fV^AENYQQYgLN!^GHa`@3OsdHD533GQK*nTfb_? zSi{8Ymy@;U3xmD4d71bSeNh8-TP9JJ?!tdOKYYqpqTy}R14dwtw>F=N8vz9bM`$4l`$JQ-@@;*w!_dHAH!0(Q+s zeSEhF=5KJR7aqqeUG&wimfhbxO{;9b1o__a;xXz3*~&3tcM1neru1r)fRm4rkPptu zE0Yj6!!1!QpqgKKAnCT7#991ByhmQxpjK-ig zMKOYY3rGAdf%_|N`<<;n9JnUiEt>j0Iq+Pka>Zyq3}V>w&j>NCBFkVY{|dXi+8LcV z1I{6(J0K-Hut@VSoMWn)tqC8OugG#=J5`G6T17XIA}`(H`RrkfqwH$Ig&A_N)>8%3 zWRPSN5+4#++3+k@K5}9RQW%YOd4f6vcFLc=P`3}Putz(sOV#Km=^hCGHetgJkP+6$ zvQ6j)m@FMBL;0Wgu2-f{2W9QL9_=gpsZA4o5dG)y*P)4NodomaM?2B~bol#U=5P|$ z=5}WPH`7e)SHU$`p6fqc#xiWO7m{bF-@({FeaRRiknXwPnLb(%v~V!o#k=HfkX_BFes2Wz%MJHgu!2)xCDo@BH3Zr1#@mV6x|r?@Y&}9MQ*TFBC|D9u5WoWGw@Xmh+8yB43tUdt$ulhunyT!pyN5 z4;2H5UQn&@L<>YAs-{bix?l`M1HpmdCA0{m2X2=k_}y%Vjd}ZqjlzmkQ(Ch7);GSw z%+Vn~QQoW=BlLdg>ohU^sKW6*L*2W5fHR6vKzOym)HucGewXkkp}~1bm%kUz>RSLZ z=~f*o+Q_x%_vGK5YLDQGKb;kh9*B;lH%0Q{awW0CYt!qltm#(zyE>DBmzns{rweY{cQK+O9 z9F94K5Rt?4ogCPxbh$f*(Z71C=wd51M#9@5jZt<+t{hHyJ)OGpU0kTBJe`|Tle>62 z!jtWDK4X&eU7G}c@!c9YbS1mKI6GjSTw4|)z25c{Hv_MUQ~8I+|B>oaq<=*vhx5E~ zP{lhh)7B{_` zwy!N;k(2C8Mt+yKwY87uY92Y^Xm%5GzZT8mcAyJxvH=w_v(U9WdksrPh@C7tz}wWQ zDVR9WWFJbG#}}g7m}4#G*;r89M%72Lk0pvlu5dKi*g(FC5Jy?+aE-ShJ<3sYVnyla zF6(IF37{WX*(XH)UZ`fo=Ry+BURe?IIhwI^h+Xlh;ikjQ-gMG{ONGx_Uy=IS_}L>n zt5LYIwIOZ4Kbf_O5;r?zYu#)w&Q7SyC%7@cwy=e6Z$&_4h#4)BJpu=F+&ql8&#t$W z3Z`4x+|$a?T2xr-ol9Mcq8GuuHXV2+qZ@{Xm~q9z9x;k~BN|0R_Lr*D)SQc~9qIg` zDE6*(ZRkt@2b2XA!4|QGi^3GVr_lW@=qXWt>bltIDQo0Z=9(jkgLNXiK zg1}2NQ;r%K06lwV70Xp0F=OlCSQb=gW8V^1o!jr^A!<4JimBr0Cj*J- z97nH0HE*=`yR%>7ZENyw;%CO(l8kDk-AYqf8ihI~_TxzFX%Ypr<`eMOld)t97L(3W z2ua3_J+;HHCPI#4Mq`$Z^p+N6kHjs&24-|Jh+|eC%;p1S(}|603T%ry0m7s51{>si zk@x_g)v;uO7XR<=3|A%N_rOTd_`HSw?d|^S-^s4IITsmY9g%i}CXHb&5r!9Z?cagY zVIOx%_25-QetPnO)u;6#-_#;w#&m8nHMNz+EHlYfu?s|g!z0N@0VSHO>tQvFE9kNQ zZ_fC1MQx4rJu#$P?@Iieb4@PVq8+)F4Q%W@wjTw9W<$eijl04GL4-WT^+P|a>}wC3 zQn5FO|6@;``M7mS$i|$wCv;@vsl3q=6~fp+^?R9okyP zg6bKHXm5j~e)17Rn|7bXa#y)sPF~uEgA=I?wkIm}`dd(w8G<jQgr49b>SulhIi6H!O|fi^GTu zZrNk?h-2oD!>oT4?JR22on&wj)#5UBwLAW9TO)oq8oInZwdkKR)mX;j)HR`~YshgE z%hIY}B~vVcXsNuwR^4cr2-+gV-hK$4mNE$pc)C5a`7f^<;*?&pOty^FlyMNows1B- zt`I#lwEJ>RzAHg?`9AyINn9Bjw|lzYSC>Z#up6dzUF(+MHD;}>SY7_jm=(|>Ecw$c zu|hd-_bgwegeyM`If0>Y;1V0o!|^jz)oq2BRTH4va~{Kq8tJW0bxEmWy0 zK?K82og|+YTqP8|3RxYasZs>n9A+1)@CQ`(Sv_Q7zJHAkgY1|5wBLMr;>f`@(|F^} z%hV*ZhHr0s=CUNA&>}t>nX^Q_n)B9W1>c1otZO`{Y}V$;YIL>!^u_BAlH<>%HuoXi zVz#W|C-QXcaMxty&mZ})z{OYif%Y#7~AW1Ph9gY(n@EFyefWXBkjTh zH(wQ?>F!REdndd9V*SMoKG}Oi?hXG73;Y9|M(&L#dc7S)_6sH=QM!2wTdE&_ShWpjV(|89O2`tggMt`xQ6EVV!?z;68);Se2ao!eI*5E zC3DdPY4Ui-q6L5io?sm`0=n9RUD33%$V9x*pSTr@ux?Sir{Xa_x%*Xj z@LMn5RfpzH|9YyUrqQP2(!AJet58PJ%XLeg&%~FS3M(T&Ek0-k1E%O^w5YJ7IXUZN z?(8K1=YlY5*5>T>J{wz|Jkb{lm3gY-I1geC8e3oc__{oWYi`o+;oJtdwk3oixw-(nya(= zdR&&*k?vGW%NoP|v~t@b1Ys@?58TU&@azAh6t~^Hy~o>A#Uw%q+v2H4my-?3F=&DJJUb~{*157It*4T`1-g!w^ztB*Yv z4eRsW>!mRFaFlmK$3LstnKwzJ2qZsR1=|xZ2#(*`(r5x>HvB`#7%%1#T+}C8kd_v; zr7$;Ss-1bkQWMId*{?7+|H(dNS*nc6N#2+r5>F_r8Xw?8FDn3fI!{WS7ouBGKt50_ z)8UX=QK#H%M?t3Y0RGJxJ5_C8|t1=ML*@Dn)atp2y_3sgtozf{t?Y-MMS=_BD;`Ejaz zYZV!*$V%DhC+Ud%XM~Yv5MG*U>=2HbqAZdo6VZWw!p$GkotZRFgtl#DSo z2lX$ZgwG=rO6Ib~^ZtqK>`m@G>{@cit1z|8NbqSg<(i1wwsNOGaVQN^i#$f!^8krE zFhbc9=E*(P7*vE9vdhR=>LhO|DH#DXT9A^$g^>;kO2s8~HM&L*aZcyKo^ZKU_3dLD zGUB(|0v{x`fe1v5vf5{(Dq1{=bvk9lRseh8$c3~B!u7s2z*heA^I#%p6NJn&T`bD8 zkD5@vR-_u*)+f}!*ppVsInyHj3NRnV5tEhG(wU{P-B4{?cdnCmF36}xhmBTQ^=Q{# z#llDX*deD{Ds;(Z?5&Rl&(b2KhPDy@RW@L34~4HG{R6fF1Jn+rR^%srfhM#OL<}re zPF%Ps^%n-h7#TC{b051`j@>+wF~Mi#k2|3Tth^z9FI>q!HZSl`jQF4vCtm(|HXuX} z9Mk^UZPTx{GxlifIlBmD2fD54f`To9hS;z-Gkj>FV%AuzzX$=0zuf6k?XdbbWWSA} zj{JsdA+Jkw^1Wiow{OTM;JbLh;gdzv4;!MnGu%9-J7J``NX{t9w*e)-Lh~(!+*`r> zV4zV*SxQT4MPfQMiqO<)J8-70gIak za0i6JsJQ+_v4ZL8JTX6Mjs~;ziS?6bhQr$0^Q5ip{;|!%vL#bbiHKOD9grxeWQr+E zpk}F+%vDPnTZqFhO0Pws`(Q{@DQAQNYNZM_6Wvh7aimXG5=rYx#WOKzWT=ekR1Ve2 zbH$7?QCmsH4a66u(anjKQJ?P)%g3+VDF5tceFoUxe+VT1mBSV}lVpbw4E?^vLGL?J z0>F}Jghp2MlRwTs-VYvO{}M7meqe@D97J~L3wXtU)|4=+TZjm!&UP+vp+Zz?HO;#x zKBkM`Gdgmnm%@QOg4twNa%emArG7y^LQnjFI8saepg3Ybt^W*;S&(N3iB4s>Wj=!E z*6x4~kcS*9-?GMm{KE`SgQ%Y*s^TIggD5>tLc>E&5ngiGAnVee&%H)TYLXct35fJs zy4R3Yrn|4@UO^#um!4*zk%ukaVJ^djbZ!d@J0K>KH3F9~;wMCu+y@Wd63dX^ zDMR^#=**AW8zR}y!3|S4S`0L9+Ns||_kxQT@2lj7jvr*vPY#h8U-p`s69YrMRDw%zKJa(fR-U6U_&QrTcMOxoRx(g0xq_2MS+RLxwI`CcoMbHZ`2%Zs5kpnf}k*aP-eLtmkkr_RX?; zL-Pi5eDcSCN@X~Iev+Gmf`+HSltIn6XU(-i-a9d*?DJNPxbDgEW9i)SYsH=nhI)bc zAu$1n_PNBV>YG6wyOLKY6%3d}EX5DM&D`&O=C`xP1Zb2pps@PbNLOe=OVQKyB*Tic zj{EazPN-Br-M!LWK&(ogzL`?s%3`wjHq4#Bk~!!vhJUQ%qb7-pxSS^8can!Qju-xm z;E*@XcVEOjE-0mJGZV!(Pr!j1%dcKvV0(ChO&WEilbJ1FZUhdQt%7el)Tm(>On_EZ znzXMe9!~gnC6oDnm^!~cV^On8Qxr;EDOslxdzOBVweYzt4QITQ89ob`?J6Ja5E*`? zBs)pl!#1XQjq3Bf!n&kolKy7+r4Hu$vj5n1f}(7?e)B``X7FU_+KSVqu7^KS)5Z2! zUaez`|5#o2ja&VtQ+mP@LzgSEjclxcgsmHyLmIGkXnHLd6Tlj!+o`S-;n)w|guELP zY4=m2o7WCj0he!oOYL8`qQi z2Kcp5UK`e75-v&h$LeIK(RG57Z`4&IO#3gUEdwBEVvIYpzK@U{iat5^Hv4 zpU()B{29pBf2Ci#3Xp&JNHhsEt^avRxWv0H!^n^;N3AW&1YhbDv-Bq){2ur$~=cSCdv88L`$s z$?zL2nIVDdfm3kua!l94qc2i-I;~f)@j=ry3C7A+(!!(C^Ttch#x`NS39-_jXr=E7 zT~2_dn%$<=3`$HrPBU`N`~yC2WY!q+8_PoZA3sY`KcslLE;<;YhTm-vYG0v@(lyCU zuqn{qE1a4i9^#%=()gB-mccOiWrFbC_r2?i*C0Hq{h{Dv` zITBd1*nL%kAy?M9qryWNB0k3fEkW&#ta%UAoiJ*brg54ozp{R?_T7;C`XSiNxpNW0 z7+wO>2v|dO@~@^Bry)W?< zy!mkCJWj-Z$_6$iC4GOndiHHyIoa4tOFR7iCKZZb9r%X`hrDFR?c=xX2gU85W7KN? zg(*^g!${*=<2#Lz%vNKsdZ!fr98zO$ZrF3@rutY1Lqf;=}aIQh9 zNWl(m#a4icVvW2*P=%MQUn70$)(kVhLeP}d0__~KLJl!~`3cDq<~@v^*29G#!Zt-S z!+f%b&SQQb<(d|WF}k-Vu=LQ6bBs*&K&;&)?>2FaTCNPARPDL7|5)G&`};YnT9h?% zz8QznEgBef**mP1YmyKU1D^0b~b!Ys4i2KH1Te=|2>vwJ2wr$(CZN1BPZQFX+wr$(CZO{E0(>)zA{iEl{ zMC7U3l_z3HR8-bJ`()-?iz3loXSf;XBExgAi@c!RHEj2m8bf=iS>}=_pr#v^c@hfQ z)VUBhCcanYXR3l$HACd0N5OP5xitIg2=)CxhE8y~C2gy2``C3i(NCb)k@NaZKimh} zeVD(%)gAx>EuWo!9Pg{zy?*z!lD%{p0BJ{Gj0w+o4XxeXOUo83^%&pMNZ)_bOb1$^ z^iD~)bqC0Y`%n_A0CMIaKa*h5%bfevO;{Glt@NYoV5=0SLa-9Adn(5UYjj#co+!72 zQWB+V#aprARH}v`##q=zT2axcmUkIVfWOpN1DmP%dU3`~z0_CztI3;pxW;V8gb!s4 z6<=E!g;uK;sJIeg4|NZ{4tWn##sbFd67{I$C}POzsA9^}>%=aLxr>&_W6F!ke* zta%&~RZ6|aJSE<>KB=iJ>ng!qdM_5kDSWZoK zJsvOgKP)dYy!|>;FW{$P6)htf5_IvO&BZlgE>DO|u%tYo&8k73YNjA7DMlB3^J zkz?jnwesp;Nbm|NWAfgXm%F7=k-Kj!z4x|S0PTV~6WpFWJMBVSuzS%}NO{{*O?l;2 z&iFKVwEiY<9PAd>In~RndU7kV`ZzAP`eZ9T|7b2de%n^0d-&Gs9QZDM+x%1ILr1UL z$xJWs>60tc$v9J`i^VS1NoybH;jLfaMqr<^hT<;MNpTb1MskzqAqBsn6;QCS?vL;o zt)I}w(xSbIV6AoylU;rVZL4?GWRRyk0iPE~rJN2`4$-guR!xpQ6q>WD^yyX`Pbkg0WCHna8AAMYn0athk@DUfL#@ zwERLu<0)CEh-KAejZ)(&o!WDoc3$g((Yun`QzzM5KLum5W{8@}u*qwvy=IQ`eI#WjvbYDcJ@8r)T*MkhIoYJ4ls z1aH-ZWBjr%vxVAIA-U5wS>j zfMPyAg+grN{|~plolzQ=`gdNp+>Vmf`Ujx=pvK!s=x@7m?ib_bBGI${bXCbPUC}VJ zec4ZB$Hi%UxlioAGhYLC2Wgy%n8bD~qFttQ)hqFr4bD_Nh;Ni)##VZGADCy2U-zZS zI&~(3P0}OD5UY1S?_jicSGQ^>)Ja!Bc-xr)6h~lx_hlh++SO>m--p(Y?F_bCl$-dQ z@2k9x9G>~1`tWIn^Y)NS_mGthGT@ydEj#F_9XSu3(LqSeZ%Fv^@>?I-2Nh?%QgYpj z5PA6@jCzy>dEzxg%&T~(BvZpv+gq3_fm$oM#wo!^wAfVzW@t+mI<$I|+PpDIq@c@* z7srm*=#LP8`;bThRec)KLX7FAxB)ozad`cTeLkH0G-<`kY)8_ZRGPMrR?SOS8x?Cm zpP|aqy%oWsxs1}xON*M*yH(-p;$4H0%F_HL$>g9+<=o5g86|4hBEu=vHH`}EI!+%{ z_B&RtWGnzslQ(h>tY6p$T-gfLJ{>jK)P_8>045+%6`ajd#J-so2zN=ew|vc9xk0E_ z9xFi1!pI>{HPWFHgl?J8Jwi3Sdl425T*r)XSnveE3n0J{F}jb7UQD_#tOY^H5K(pi zxh98Qng>SB$k!o#Hd0{%1&wX0*MnPlhs{rg{SRGfUlcp;FGX4aHzNetd~JAKQdqA~ z7O@@f!EUKLIq@%uQ9goKGUD&RgPhn8r1&3f@xM5I(Qes}6>%pEy|AUZSMiyZIHsrT zbY`0Pv-MN&dnZ6Hq~(oA04g3bam~dzVM)j4em>MDaovMfIL9b)pDQXwF|!~m6BbF_g|xfxnJ&*IBopc-{&&T^jHgL8Edb!&mG^20hMI|9B`(D_)d@) z=my8c`C`+2(h_{s@9A$+I2tJ~qkZU^J`;b6FgCkI4W+qO!vgZ<{z45F^g89J{q7Y% z|9~cJgIri-hfRzpe+Prq##L}k#|qs**Bx;S745S-fmR7gO0!_M9w`BP>RD>j~8TIOIa;PhuYQ15{cvN!3$jHngq16!dNSOrs zeXoXs_bJFF3Lo3}xGckM>P?wyO4OONEJgx9A_dFO*TKgY-5Dbn9rK8qI{=d#9f^9)7ZUI|3B4KwV9Tf~FHFabr>=i(8N$C&8+eFGX6~ zo>0J^{ueZ?NQ5Al#_wy5F|{ZQMyufveNNLpX(|0}4q=Fx)sQ_iUkkalIt)u9ogV@# z34j&qK0mJA0`W*B#DZNnci>}AAzU-%uWR=|mK?i)_)o&kh|F@&GO%Y+97;{7k`4!< zYD_NN{4n81V2@X0AZcGaSWvE+k+(SsB5@4j%=XM_6`f}t1jcxHksX6Gtp!n(-z^^J zxDLGQ%H5cW$s;_BHtj{*Ig1*2zs)Fqa_)r~iLQzhLaiJ^%?e!Y99-=fv1*D)J4>#m zjUKDYUKvc=CP93sFeEI{W?^Ya1^>}T5Uom@dDR_4-5o=wA$TVbRTr{Sy=We5JTcii zq-B%GQ$cxzkhQD^D|Eow`ZfsYDK~M9F;C?iZh$ zlaUF*H7)`3Mx~pU1cTup$HYYbdhU_poeZ+8)pl|2kt3vKmGeuHEI0IUXxwF@z$7Kc zLc>U|X&AI6CAL76`bK!N#400!7OC-gpmiFg$xwU{Me^*mLLmB(jh3Ep_f&+aS84Y3 zaEj(O{>3{xyLDo#`LhZ1M7avuZ2;;wtO>ih4oDIfIAsPnB^!dW4~SDk299Z=OnMS4 zL`pr0c0M9)1c^2ws`k;$nN{YnPNPKq94UcwQ=q)Epm}Ye{D6O~1kGVpACR=FcEv$L zy`kIUESp0ulq?`%F+aQg452Zp&rQCOz-L5Qq>T8cNbH(q-0dbZhF!tPiy6Jz`qdxh zkU-^-$Y`~(lNW0Y9JbLD_YM@C>A^T4MOnE;g8hSA)lBOp$=_vyfGAvsyqg=J{qA_e z6SSExlE0BCz37dO=|!e?12EW-fO$Sd1}2Q$G0H!~4KqS0nqFB3Sz{Ef>wlSA#q@5j z**WAsaak|prm%fkbP!waG1^9tznB(AW~7X_{0@uE7_V&k%^HpRa?8=hhm%4|K}&Sf z5}B(u2JX=snVT{K-nJ2*E7Mk5xrPAb;7aWcay!a^;MP;y0OcScs7;T}ovOex&sT!b zsDC3OJWslpO*+6M6uK@I>X{7xj3&6@6xebM;Xnt!r#lwRPL=OUWSb!zjG;gmhv3qR zqOcwcRn(<@BAAJzm7-PK81*-oXpA;l;mJTbfJAE%O@UP`y__sUzm)k9?}=)`Re8Ib zpG(EJyU!Z#)%(|KDcC!bq36gmbq}k~M#jP3mxRK+7BWkxkivYsece-b|6pajz!N0~ zOXEn1MQLO@rtyNZsfY~OJ~~hjE0rZ<|D_6}s%2d5oFWDl%ZPd@HO&UDKgm+wGSKwp zb7}UcmCmTwI}Tg{HfMA(&>cwhw##Zazpx+X9h{ct#o9>%T-)8Cj@t-D*u@_ftsXpz zJUP1a-Dte_(UgjNnk8-0=^`3}yF&O^S_0VO?%Sp*cNUNVRZSM(Man%6vIzI+4#Kpq zPk4#lmjScU9XYa; z-E(sf2S_?~8XA*EG`c;V6tClJbN`-+~f$=oBO*F zEfq=kD+BWzbfcc>Ztm_ak?lvs$CYWKQ+N)kjuBqmR2+7b%#ME0l+J$>#z6)LS94E> zf&=rTV77WV3FiUAPWRC98I-X1!hV_`@fnU8VPhBnxyd6|n)Iw_NrCEb$Hj;EadMfB z0>R+hCQFY|7mv}`EI&UIq2SvoW`2fcfXha0BNiW>HAt&JCB!BK(Z~wUtiN2VQbt9* zcY31ZVW~}5!+}C7+3lbXgvHPAnOnL6ewmdr)%#Sw{@%bUR9V&p&9=(4Q1nHYHv1e(qDWy1v$5&A&}0MLA<%@F|Ijv zrsQ@cS~wo{I26DUnXvrN*~NVnl;_}SKA;ub(5=La28)u%)sp@xRc`JJ5%3> zgZ+kr<^qn)UoJuqtd!Yzv_KJ!Z%x4>H0Pn@Aq)?)^dSQ8tOPoA`>q5!eEX_o0)dZ8 z5#x-nRqxEq@&KkC@GK6P4m0%ihu%&C(<~ISG>S)H<9P21}n%vjE3n;Ka;R8{M%5@ik+JKkMSYi8w{Kz4t~(Rc4MC?`?k#3YXZv?+}uc| z4rwU@0uA?yfMaNiv0uvHB_0W#%#a`);t&rB*!%c}cB0W{aqkB`Nr!H=+dpa!m7aqZ z9igGqc`e)J?mgu#OPxP`m=tl)T;i~g@z_TstCf3RVyxodg~-#ll(=`4Rc_VndNGp( z@c}Oy_T+^|kVEpC+VavC5&{r~g`kDwSY*ej2dEEP9&}#yFKt*o;BYIJu5yK@u409@ zWqKB=XR2?~kCdN9oJoL6A7i-`wkFXOx+W#~ZjRkFc-!V*AlJ+I24gKf)l=_hUfBj1tNl zXNS&a9MbnSqR!Sw-VYjL->^vB@e~yfLobv}V9;GPkd_Y+ZS@FN$g^c3wJdW8WSxF# zb1irH`&8C2rZZIgRxqUe3A)ezDO4~v!V=9kgt<7BHY73R zxNlsrSi-~^r4)G|wK_C7guU-ru+=h@YGutR%fgCvAITLpA9*?Cwa;smcl*ZyObmz} zPBgBf{}#Ok8mw38jn5wP@UEuY=NGP2s~5L`-Ee6lRwUY4k~{Wc@Qy4_ZMY-oOLo(* zm||`9FmtsX<}nzR^oHN;S&sb=h3awIPYU8R|1Mdz0bY&(b%=H>rgPCcd;EtSl3p9ANO{e23mlR!-3-* z_sQJL*x}QRt@E?npdHOCst4!E(ee?xA&-$_e3-A$_JH=d{)m2aYllYY=Z5~x4)iLw zL#q3~82!XtyVThv--U@~M(i5t-zJDs8^Ql$h;Ji<;}#d4oue}}PZ7!oJe{b87v7n> z0eEZ^V&@4YzpuUQ?^ykDn9f&h<9*TC%sXI*zm|7m_+A`%gSCRsJN@SSPgg9<8qq;M zB>+He(tqxX{jX|wa{n_(l!%LwwS}>Xfi06Tv9y85Z*e>8{|#}hR2-KDVnF6OWZ7q@ z+S0xinV#$iNvad7iIvvITn zACEUkr9+K?77MC;d0v)EgyGWHe);T)Cu?fcbUj#^N@_tMWj-Mt(x*?{A1$Lihi>#e zhh9}dZ6)fU<+Ib1pqi`c1qikzxB|YoDvxo1Z-!(&5i`r>rYTodOcWM;Oo(+DW3M#E zIK4C@#w8c;`OCosAeEZCijCVtT;x{~jcwXBQXYVV{|N5N2aj=hmiietnoxmxL=~TM zfl*3U6T%nCXfX|gJwYU86`jv~TU0WZzGwC*_fJIV=jU%F0RjM&{Q%|UrGP<@0l>k* z0sgBhHt+u|BIKw_XYx|~Q~2VTpgz8Z6e1#iEE;iaY=Z;@MVO!ds3;2<;vGOdtAvu^d~lIP zMi;sF-#i+dx$lXrPS3`8{YI<(gZW}6r{k&2`|014Y36)iJcFym&T9BDi_4=D+w7!wgADq$Sg+jrPnGj}XRr41@4}J;lt{ z4>#YdSG$|r3z}`FNpSpy+jIA%B46AYvE^{VW28^~nTZgvA_t#wIhm`-KwBrp1lrr8 z2K1HOsj)HUG6;uG$dg&3f)j+a(!pGel;uc^(jUS`#Hq_d_GL!%0;|L_U{B)y#;weC z0oRe<_=0>Vto)uspGDer2f5qeGP+f-Q<2y5)SC`i_ME@>mT$hW6nzd0&6-?^!Klr?;_2_-s>@l4h*x7EtVl2fgl7U>oPe! z4q|gNZz0~=bIB9NVU%=^=z^69KOV~bEbKM+h`cFbcjSDWN9X~r60+yAikIXK_?0_C zr+VUi-_}+BXftX9>>*)+_j-jNU?ZyB)d*NLM*_rsA9 z^a6nM(wOFX1k6zXXc!3bH@($mCg7~b`B|j3QUKY7Tu#yrU*<|zppUQ|@g%%Gu~^)h zw?u)RVJ=)By%jx{cPeh`qN_DISybXRYyEXw%t%+R{tvrHlrhh1+l}r zV^4Guf|1#D=)L01ZhayCR#sv5QN2y{>)f5nL>^Oy8(MR_ku?<1J5;xAn6*QXkeLkA zedG?hRj_Tcy039hR2In~?ZJ-OWVqQ@w>P^kaXhOsARBcpZ$`o1lUJU*;jOo+_c80j zVm&$Q78+JmR3OrO6!-XW0J*FDq*K%m zJzTI<;Z)(Yz*nIGfCTUa@&tN0Tzy0XL{Nvoj5JtrOao2i#ohLT7Tr4)DgMR61R?U% z?dWnPK^+UH4w3u=xxomzJLN_rvFK$(BV$YP7*hIXx#Md?WTxRj-q$&}%yYto&GYOUraLK}2DuKi>(Kq0RoDIduS$Wy~(j=9;C(u)9L90qDn zp6ct;)wX=MZ*%+8t#i1GV8&l4g|fxKnJZRsa!AAVZ53EOohmN;Folj*$(#1ZTImg!Igl3d!9!tlQ_@DtRQf`C`}_I0Ir#Q$`OmNN?3T{a6uoT zDU&G%mPnv#;movIHcL~Hv4}2o%^IjZm4a)kR~*LTtc+wOaML1N&_4KzTdRwNCEO{- zY)(jy$%0^*hBbNO1YzGFjIkq z-Ww#{1Zg?mel~N0@j}NVHtlq+g~=l#XXTupy>J2#V`@_Q)7hgs)n(7h|B)xVokE|F z^uf|)?_~(EjC5rg7s$YC+j(1J_gYOxg@c4Nx+0$Nk%`-`8{>Ls2OyEzw-tcX=~=y6 z-`src;+yUT%sYag(mD0J>BjOazI(syRU*^((Y)Ml`Wua%C=Q!(hyBB7c+~0DNVBUs zq=lFKdZg;j^*+Q*{Y$d`6wR4ZPA6-8u_MFjjf*UN{xO0vc54j-SMJWQZ@CgsII_Mg zOYJZo#Iur)Jo{#4WdzyRg3|-G%X6jMEx178J|*YrA;g~~OHp)VuLZ-y!BJ4-3~hmf z`_I{t)7e}pyinMM=s+5Q8eK*OZzi>B-I2OA8+I-yWq~ARu2e}Dx3Ub*f`tE;Xkabj zM*(GmH?nqJr*z|H*=3v!MvA?8fO-TW%>H%Hyn$mZk_|q)5a9~D5NPk){sDM0HW^v4 zc8oY|XYS$wm`(phb3B^5>s`$6V;vB)~dYt7AFu@3u6>zPgS!9)VMM>umVA#z@Qo!~SDhM0=^A&G`9ElE-cO2U! zA!v)slXe{6XdbZZhT$_Y;I}B6O(@fkJp-bsegrz&V)+PsNM5l9{(BkQul@m&g# zwc;tByv?`mm@MK*nnvcV;|f;^3s>2I;6Y6Qn)PX`*Dc$=j1G+DgtR;|C0lh|Gm{<8 z`DA@;H-|?jD}k@lg4@7c@!OCHuL+}gq0L^vEC0sKalWAko$T9({{R5jENu*^PEQ~{ z^464Nn*b2)#<-+RKL0d+7)V8Gb-hFy7p5g3Qwa#s7oN5l(CY)Mr293vLnlcD@q&;0 zB7E|Jw1rqdRW``0YCcu|R1#1#6^|Mv(_mI98JRL;grepfB28myWdVjH%8G|=!mVoX zS>&ZDtNzdxS#B>AG28{SYpQ8$!nw5_^HOFM-hGLc_Bn)8_C7h=CzriRox>Qno^gOv z8gKA|zA>ZBs~L2emBe+~Dv6K8<0|$Z=EI01In8SVZbu~vI{(myQlPln%hoacJ(

Ko9yOE-=Zg9WRh?9jmhI=<}yOH_0`f(Ip|hU+baf* zplDsqXunSVBdT@mZ|f!otEpSqYj+HNkM@>PwYg;_OkTXluDyEkrS-UEjv0Q5r3aAL zaK!Q0$;=>hQREc*9T`2*TY!+hfx7M^y*s_GETP}SqSoHcw+QI_8(J6B$ zz_FlNgQG~?Q4wzN+6jyNI zY=@~+*F?KN!1nQ9Dn_&+f!goja~Jez-Ou*4K-pT{{40LfXNgru3#F05Ny%b4Xkba$9>SX!`w8ee_}ZQ|kBesM`SKvFz#!9WVF{haFm!v! zZ&AOgaj1NSB#fR8=kvN#?O4P@G7Z8Ytcy?pW0?3uX<&(D)Wli6*|#j4qa0$)wJG)N z7m(sQQ*6vq2go~k@*4QUyje|8mL&D-P{3}_R+$X2;35v*kIuLV%9lJ!8W(yG3^Fvs zys;(iY|ztM6H2qhzXTOs1%L`2(CV`O!4tAqBC}b$#hKr+Bt)b?f=36YCf-6h#l7WL z!5@*$=D6YbfI@|KB21bUoyPWevT7@kEi$Hzh5hj^KIyGMMOT#Mz@;+DRW7CjStXL& zEbFZSM1ud8hi_gu{)RwCw2_H3!01lnHeLcY`}=1* zb~5dUW4IT_L5?gJgexPGuxaTuyaH%Fe5}uQ8|aKG(Y;5~_1jQt9dM9e$SM)<6vVtn zRDxPG8AD+9Z^T` z$@!uzKinxYCGhXgEn+`>pMY_aLdWU|WyKTVV%`^9jQ2DOjTF<>BlxfE+TrgkhW^k)2pN#Dfh`Fb*I&D`ysI z4JJ5OyNBb#%gqPuVQ`X8rwHsiWfHxPTkNk}KP$o~EDZIKK_I{zDpDt33dc5=b)5u;a=-8Sio2T|mSm^=8 z!^-cCnWr>A4`qcNrZTnA=5vGw?KuN>i&1Eu3C{0&Z7dl@b@dKeQa@o?gwe!ci273A z+ST;VeRfEw-rXyytH|BCRLUB38LSV9Ww$Mt;9*we3XxPNjAi~J&|CvX4&e(e8UPT_y3 zw4rKZ!38Z92Dng|hAoJLzcxBY=+p{YiU^{y`Ks>s z!Q6b&2gNWs9TN0-P0v-4Nt>Hl9`L6(L7$SXX+#u|LnAd%#&OWV&qhW3X8!8L0)?1X zglCqg*hw9S|85uN(P47kqNYiY9=z5y8_{X91WI6PQevJcOVdjh-J(sol$<2bxVo!R zNOaX`o6-?lx+f{epA6rn=)H`ptr>~0 z1C4IDM`S-HNSu(IRkz0}SH#|wiRr86bR5+@4B};!Eogj;$Gj{VEjvy9tG#olG{<9` zcAM{9pOkK;dWXDC!P82Y*Lg-!*{(V&AC_3~9)L|j!OUkp2@T}pjYbSJA-3-vCrF!h zWG z+S~lu8Clt-<{UO>894l>jdqI1vGjK+8AqKeor1u8k?MWjSZ71|RYN5O4gXUaS9Y^a zvA%*MiNY^i<0h)XuG{xws}Bm`Yhd+!C%#$X0Ke6=Lqo6C*M-x z+b6f=$w)Q!WPV2CBDWGiB#B7q{F?fP(}&4KA9ke-}V{Q zOauyg0F&iLBKm)68aLKPhNwHKkbUjQZZK5QtyuipUotB_BPH2l=H-&r{G8Vz&hD8k zQp%}yZC{_~#8`+@q&aOT@wEL4JnBAe^6z)yFfW5`@cptYN4dIx2hemk+Gq%Z{Fd45 zVvI`BE@-8te?JL(?FMoux=%$!pR4y83@xP+6{wg zC@)=?EG~0Pm{d84%=V6l>|-IzH)BjYAk_UUb*gZqhwY3r;Pl{?y)^_+3dNp!hN$CL zwF4%24*o641K7bY7p18W^2;9e)0hNvi(NKUUYv~kFEl}|U7rx$ZhkE; z3H5$quIR2&0f zH(WNZJ&E;bp&lufWLfm)>(5{Rtli1UNStDz001&S>-T@;ga2!VK=^-_5B^UTf`47O z3srRF=H=0SWHG3g2ovyq0Kz$qy~KYZCGmr|;x6#F?nc|KkK6?~9>sNTydq-R>x7dz6<(o3&ghke_&Spj)XQ@w_a zLEB0?>quC9Or8pknLJ&i;Mm#LtF>Vb-tU|tGsl?DZGI5hW}iWL^8_=?YEw?yVgv#s z7n)xC8+!yr6@zw3L>`)oIqccOl$7^JfDyEu0^36P#b+>DwpE7)iQ&}xqk77-S;~Zh zdIPEBN%W(dyinPp-AT!6ZVJTUOc)hr!CkFey$~ zHMT|RsZqzui>9LPx}Hsut>Fl+sM8L0cjywi6CN#wu6C`Z|U>sIp9Oj9Txt;$(A!}kt4 zrjY8GRE1f|j|m~Yi@AB4MXXK634e(`MC5;K|4ZCUWSijNH`(ndJ*U_*#6~3JF%bpH z>#cBcLdxZwJRuAz8NDE_u=t!f_LF`}drcU4c`T@#tkJti?X;YclAQQ6t%*d1gW;6f z!?Qox6g?>pB7<}xKkjyfq5l}7u z`HO~^%{BsBO+zmr42b?VFp|K@126i)E|6BPW*H^~r`=`g3q>+mIqwDOTN={9vkzgb z2V1R9d{eD#Oz-d0&w2n$wYVX{Ng&y~t!jZUmC^Jx(=I%#EIPQ(tP@Q)+6XT>GPCvA@51&LU^sfA zNcC5s+%-HJPsV!Uja2fNSsoVEj$ZO~mu#+@={(*`<~j62$m-G6P5=nt>hO^O@sff z%)pHd5zCJ&h>saNWWZ<~Ozfu5xLasWzqGfurrF+TUao4>emR%iG*+PAxU$*RuGLuG zI9>Uu(gwO_d%ia8v(0gw-Rg8LgWeaE-~E=rbez5X?EQW1(B*VB$@cX&NCuz}=9z*= zYfu4BnHmBa1z8<~@{;!l1+}02=)P9rK}$Gj8xF0`une?BRZyf9uQ;-(i9wmFAU_j# zy1VN_$jZd(g3Xilb3Z7UQxZq0(%BnSLaQ*-qhZ=!gryMD@KNp zl#XmxW02a%limEe-j5Q=19S7uSbl__o{Abzw&^qx?Xl835M@>Fo+O{vNLBtCVc8-= zYDB5Jpp8^%NpZekxQQ}#aeiDlDP?-8dETBSrK)`G9Nco9YFTCenkAl9!M2sxg(jHM z+uo^hLorSEl~mEgB8&_43L_XvgrbKYX_?ttKF{YZkTOk;#{84PF)P^akaAl&X&VKm z)PR*?>6R|G);!iEvFTz(q?l(i@jg#hgy&wT0}oS*fPz(>RE+7{yaU);naWCE(|$J& zG~_YKqp>MqfL6Jz!5|ZpvnCesb-pqgBS#xU>2Suo=koA;dH%U)O<@NEicn;JC^GN3 zs2yqCg^~T@jBwjt>6SZbXD8_v-noS9P=SXGXxKu&?jq2;oD}Wt%Tlfg<563tP)fe6NQxnSg2RZ^!`xl8Xqv3fnce%LYMaG267I? z3BF1cbZX4f2M%rO(lRFr3iPMs_8N6n96pZrWS6DM6{IXb5k8dJH0Az$b0y9s2@`q` zhL&NGd)H-!Y#ys(vZ)+7BH68EQx#^^d(w zXtpXaTGnS7w3aE;KVEOwxcHmkHQStGKowF9Z?8_YqU{*xa34fV-GE_XQ6{W5)b$up z-J@)%Zp|ej-?buH`_AH0Ygj&1&IVK_1>4+OrCjX{86QQPQJWpBx2}Us%Zw#e>8_G) zd7vuuFDB$Nc4&N7=r4?=L8s2nTmh#l^RkzYjrf$LsC&W=lj#x|8;mW6>`!-X`B*{N zti^MkOtDfLCi28ql^Jo_6>KM1^4T^}%g?*huDA68-!q6%gCf)_hoBXxmlwwN>-1V8 zTcYPfoA2+kIS3ZmRhx^~mc1>fW_8~U*1{48WzLZ%Kf7=v28h$l@{Ouyiz7n#HFqhRMT%4ES2-y;; zE)0nnE%q&O>y5&`Bbi2Rquvs$dQ1FlIM`?*o~cr^uTog-pt&k-n-0>G<~OC*w>kb4$hzJQg0wjw>`Ta zC1!iv`AzOZIT}Uf*AjP!^t^YoSH`KfqIopL38n-(+I3{k1U6P?;cop%_I|SG6yu> zMh_Q8B%UQ^fD4h}RyJH{vT<2al5b}Ah5(+>JVYbQVovm63h}GhDu<(7F$LgC&l<2j zkA7uBIJ+>$1YUez%dL*1j1D43KHW}6y!Q&4REb=&#Uu-0Q?kymzUEdw=nCgkG{Cw3 zGU$$gD-RDL7n~6cZr+~2i}{~QGY0E^Om0G4uF_DYTEB2wN<_e9V=V6qt{x9{x`5VV zgCf8pq+1wj6#b0QMzOHbNp&NOie6pAf|xZ%;;W=$t4MLkwou81;WuDwsJIP)>%V(b z0N4caV&Ey)NR4aU3k!kMQ1heGK&50xl486~EIm!LIVh2}YlsrDLd z_~3e=Zm2Nd5K*dUUWQB9;r|pYxF)VeD_o*4Mk`&iFUrbaf-J4zx3d7`1j>Q#OkZR{ zqh<%&1|h|_H0Or&>HFQzcH6 z`stAfjZ2UCq>va+9hwxzEpBXh=cSB5?7=Lahmo_eV12goFIsg&Dtu22M`nWzk2;NitAaSWDDb>MOOTw_~VVGqX+Zvt`Li zC*DF4K8TP`r*@38F09kY*fqo_AE)lrtrRlAx5DM>gWzl(x+%i%jDNKP(F!!P@h#U}&lErRru*$rFu4);XTUbu@#%Owo9`%R$EdVW>ND$Gp+aQ8)^-d_{z(1l z#k}bQQHNSK@Wugf-@%cWT}9!oKAvXqx@zDacFI;W#7O|CAgej-e>orAuFV7P5!@Z_ zK?>&v(=2&oxbcBqXAw92%{zmKJvA72p9_8@L_z)Meg|?Tw32`UuPra+iyXnqAFm97 z3|E&3m-%E8qq_W-frYndXxP4EhhvaqD{y+?c9T74C@^gQ1}O-R|I~ooe0U9z+=~%; z$uu6`;944yNSmHXEH~MtOhQS?DlqIB3wDAod`FBa51|NuzRXJ)n zdL_r5^dCX$>cPcz1qv&DNK7%B^kGHjmEqCt6&+UgK;@9C55!9;pck6Jj9DX zkQkCh>=p${mS3(vz=-j9oWgPi1{TR-1wsFe77#Wm2wcH%Q-~*_TLN%%ji0kblfXVq z;m=GU84jJyk~1NQ#`6AO+{Eayh~QTBQur@hgRfnK1I=o;I#E4p>90dzm2(qptnO4H zyPjlKu1I&@Om{qgysk0huLY3q*5JL6wt@#Y#$J7jcQRgQ{6~YeTDg`{1N}ikPEXEq z(Z+@7i+bP%oD*-Oe}I^zTw}k*emC_WkzR|&Z3O`C$Rh7|+H-Wk8SUz5SAhD1lBiN` zkS@+bUhjd4G;VIll(=#={dOo6eIc`^+7UEco>|0XXbi4e3N2-EZWNUUjpkx!zfP9? z#EGo)7Xrf|m55;A&O9FX7YZKbl9a|tKOsNFDJ+7;V#gCT<@LYVh}q%(v%?*_gc1?lA zW5Qv6lkGUG#0!n>8MiC9k9vy%U78~T{$vpQnF$f?3M$4GPNgr z)S?I#(r@Nppwl}$MI)TB@4~_xybp?feQ4hy$0?H)NJMbqUqjC!Q^QZlxD*&V>L%=~ z(WIB~ITs}C`@3m7cq(D!TWMrHB@Z!r$Ml{V?4;V>SrxJinG?c<8sbpmpW~^7a(e_8 z)Z*4O!u_rjYVAc^n~=WG3&KzxhNkl|iO;;;?Tf$r-o1pjX`~+?rg|vAV~zk189J)a z5Vc+}<*h7!eDBvS5 zu4sajOhPOi)vHn>3=UTfSo!tD*uNt8zCnxn^$b`(U~Gjaz-M6mH9${fP2#zd>aUea zTa`H8|G6lvSF(X)lPKGauqmkN3JTC35SW^qL#a&7FQn3B5Rp=AFbq$wG9N^y(U}b= zpvg;qZ_(tXUKDI?6rp*_<)=se)L4yR3>7w_FVG>^rV*w!r=tQwhb>9%drv2JbD_7c^2YC|asX zIWUKDYOCC(Ht{hx9M6kn*=rzmr?Ltztr&F9lPBSz2!Pr_N`?xe98EYmR}$;+?Oh|= zRZ>TE!#VLL?mg(YH)!9nCk%k+Q;Y~tQG@N#s)%h!!%wpgFs>t>-qAzp+kBDoX7Qg9 z`M468>3bt^FBfBVcfza)TuuXDUimTSS~UiHrYa#LR0Lpxc@ZE61jZ|biO9gnc94Qw z_>L$J1{5}i#*v`~LM){mRcV_f=}8<8B~?=onTd%;2Bzhq2{UA->Tx395Dk$iNwJri zzYjvsG6uFd2)aHeMD~6qDp=E?i|>T*eNC(haUtZSwa|$*KB+xT{3Pp;DYZ5=i8di% zuE5l0Y`vPUOch4$(#>)>iY18BJ-p*=`4BbeaLUf_$`DRB>PepO3j`vl`$m>OzYWt{ zya@O?YJZp|GH4Rk_~mI`2R>ktj!al5#;sF*1>)3cBtTkipZos`(QB-&A&Y6XuM1O} z6QMN3c_8B|^_IwQ6krEKUR@c`#xc^+Ot56JG}5azx$^=jRc3COL5dz>W&UjNgf`Z# zhtd%upPa5>#jkApc&Jjie3Vp6DXv~b(mbAmUwP8pU3ac_30kpYH$V?~5-@55GK+=c z$s{$*(K5|%283P+N)UUgusHzcE1aLxuNp}y+mLo67){bgZW*@8WtCrMN>VYCIu*Dl zT0OKKAHjod(wn6T3TaWC8cJ3#}lE)|3drU(>YA# z#Ae#@PmK}*54@hpn>+%7Ygq7^BWo%^KvL$G{%ur^gGBdNCw#&@S z>@+hoGcz+Yl$n{Cq0G$8T;=h1U$^?r8_kvaN_(erAL;x#CzP>r#aaN=c=%b?#^J9{{$ClX9Tg*DD_Av0qY(rIfo&$k8O` zb*@aT{5vMxDU8gZFsx_bxP&6oIe1hdCVN$ZoLMPq^@}^H%{>k7*Bh&sNH<%jPB&Xs z32%pj5m)i^2HasN(Bu6$U-TVC+X2J`AVJQVn7QMVmTX*}1^$309>m4`%$|2m`rZMpfZVL z>KACIL1to^=~zFTXgm~>H&xVZaT?}0m^l)6+N9m&E;1k>0X#bZ65Gl|+>_aoo6XkV z7pbNkd<~aHl#pSGJjTv(igA`L<&m8+qI{J0ugigz{;be%HpQ`e2-+c%!|L7%@1@DH zaH%T|(b;bc%7ocOvKj1sVaqw|HdtI?t3W`fk1j(?Jg#xX+IZ2tu!K=$hdXdq4XS z$ys*3zsUVce|1Co!`;)&bmcLG)2=C`W_e-}ou(P+WVAHt+GdgypRsB*H<>(axteHZ z0{olNc4lQs?w=u1V8UKt;-SF8Z9yKKu^N>jQE2ie&+?}%{nFjc4b!#@m$O!?calB4sXW?R}5k7S}16asH(X=@b=8K5!uD!|0G;U zvKmyj=Co9Brt7%VWcT2+fXrgRV<76_BC=-X1H!NDN=xittpF3tm6k!+33NPZVzjG) zNx*4R`8{fj@%4D#xSPL&mCxDBI#X%#OyoxwR?AZ7lnkF+0qJ2H+ag9 z>n=xbP~G=a5=#GQlw>zw>9(#k-tQW=wYv|D@b29EfOW3v!tvxXQ<e5q)vQvgS{&M0&K<^4vP0p9npy*cn(~SX!_Q zb4N|FY-)p0ggy-AWqc*4%lM+6X_JUvz}rCDGR#pgx0P=YyQYUP-ncah>9#XyvKxLV zM@=S8b)B(V^*}EuRr*P$N(Bo>TK(g0!Qd&0Qny>H`c00!@|Qfc@=8n?`uGyHLrfTh zqv}^@md?MlG){n|9%~??)d1T;W5w3IB{o>VuDuPW>|CK(m29-@J)p-U)YV`CYszWmDuRWo z#dpR=!Z0YwYtVwcA0eioEKD|^h%;a~K)eqO%heC*$;G9AP+fUC6B|niOGCH4^6Rjz zJ-FV4hqFPq_Dq|Qf}J{pk}N`u2K0zk(EcU#NU=~qQyeDVp6I3@2_e!be=JqzOD1^! zgasjSAfJCaa#3KdfthmypzNPWgt7u5UDzC zep>W;#S(LSlJVC?Bo;#p6X~hRrYOU4=D+%W22JppA}h3g2=bapNtMV+=+NWiL;~2O zaA-h6NXplr0#EiEwTSFc>)}r}YKEd$JY{)h5M81|z}b!(552*BHUoFH;%Xs152!aq zsJHn?yKIbLU29&ed2XU==f1oYzxBpwa(Gu7c-P9fL`A;k5-+QqsahABfwgKuSxI-T z%)4fH_5p4iER0N>yi!oeBgL1hvK+b{#%rhY zxRV5&%f8MVj@=G3UuW4e@kiWmQ7pLSRr&xweL$GL7h0d2nK&cl9T>@TwjCc*X9U+_ z53-m%Q5>S`B#=TsZNYp%z7FiWZgEG3)IcZ|NfxMJG;mqYo=_=igMNmqI1( zX%aB+I11g(R2ziM1PcQE6BYndnVaQGQso5pkc0f#axImbtN4iCsKf|@h|>z%T>Q5$ zbnsX>9kOmzeB+4;|6JCv%dTbS&P&3+@paX*kkMo?#B&n627@N}%YA;H#-gjHWiBEb z^_$7G(+bT(Eb6ztX{V|>)nbR=zrJajH$`LB>`%L`QaZ(8)u2whHEB{6>GYllvFKJ- zH9~&f3G>gLS9nCa@VbGYi7i%A0@`{Qgh5NPoIi63|4!uUc6E<~@dUYK&DpUB z*#OFjCcNl_0C*|1^$m_Vu(b5d`xcaSyNb{)yMRJCX?o_4$%8^7_+6lAEaNLyqFB0D z))9O^*pC8&)E_&QZb|cv=6Y#jYT+wEWdc$_wRAQcO zw`lUBN~1Qt2HM!Qj~PXrZNSaZXm34?gFIufgZCOgk zLgrpWih1! z35-iZ1k8rJgCRpHoXL1owwKf7G+w#>j7`v(j&#WB&F1~|0i(a!LQc_!-DDvN0a>i( z_;`ovt}p_brCH3fl%Bpr{1|h*V3ZQmv{BR;ks`gSoR8RkAKXPnO;2Rx5)Q5HAJ!)} zSJ>lhrw6;_Xfk#c$j9ZsFbSuiYjaKmaxNTOCogG%v)N^B2BE(xbFL{xO8i?<61U zBXChZdzpWf2WFf;@OqH2*8j2!=H?BPqqe$s=#bCq`cf>2D>SCk*}iZ~PHyb(FMuHi zam>k#;PG6?klQ$HvX7#m_QNw8S*d~`39 zXJnYStH}`QQMN6$J#Mc!)#ER3nw5z1G|cVQcVoGIfsp+6!+LGI?$7Y0+a~SQEdj@Z zOE^0XY6+<7chAsX?RnohaNNn{`d?jX#mG;KGX3xT-iKr?*%)E=mF$)kC6{EGpOH%U zs>4n&@Y@$y>^CU1DMvac5Sk0J;U7T{p6v-~3{U8jYzPHC-_T@YQ#{^((PD9}Gdl^=t=v4|?(VO!y@OImj1(9GlO zK5#Va5&_c)-9aGL&Ja9mL}b1YZBP+T_-n8MYEZ?gvnah2v*g}v#Rcq(^of#+I2pH# z2Ni2cH6^+NNlU5{rBL}q9>g@W*rMZRJeA5(i4KFVdCK^M#@m4|5V2JSyj*BZlzB1v z%-m!3EXJeKGr#g^epMClv;`16a=Va|2@z%M9L&iR6Uf5{C%aB{hG~tvNogPYiI=1R zJEK}sZrMXxDl7$wa93l+s)q{Ae%os)YLW@UUFi0$OC-06Co84x7kjBbsu%YUFLA$b zeJzi#HOsVwI2Uj1h|NAPa)JpFI4;ZA)@m4`q-0U4SLr1a{CCVO<>LM+Tg?I5lT@HYq$ z5wPgc`L@Q@AM36RqwO>2EP}>YP;EJ!5R>XSwt$VV{rFqc>l4r;JYCtYj2Cy!U4g)s zIddlm{jb0$E3+wF7rV`|KyL{3X}&bA{EH5c#rxoc9H?msI_H936VVxR7^6LGQ{aiz zue%Z9Q}AsuFc7PBIHzEkPoVmP^YNVQY{9f#sAiYo0|80|aae>wHbTiwTw7Ff<0ttI zse}J<9AYO3h5WF=jw>hT3oop{ngaZWAMOi}q`$Ae1PUj^N2IP3_%*@^#PCp&P7r7#E~?jWQ)?i_ zQ(hiDR2Qx|;~4ekpZCpHJFsw8Fpt(Qe~UkVOty$S>hSc%C(}_a8vhYik8vh}=M#5YYn!)~OQ2 zOSRh9{o69&5O?y8G>v+@9?Pf+09&rU+O{AL(kP@bivAD!46?V)bF^{R^pYH8Qc6|F z6t5%@-Rz>~=eS>0y~So}MhtaLwRnJ(3JcYG^RkuoB@ETLVFHwmyB*lThoeGh35dXY*Vh!>{WDZBUwOhUX zOVt^Uy?@;K1*HhSoc{ku)%icQYZCt%*phR0vNE?Z7IAZO0RE%R|KDh9(-Bn#?bEt` zjNJSU0vyF09f?T>?lctR4K%np&tH%x7z`rVy1qziVY9Zw92Y!!UV-q#&He+g6drK1 z_ib9docr$JrB`n+a;7`Hrz1GPkHtE0-^k%9%klcPwa4+QtHbs4?ex1Jxi*Xe-FH|A z@wmT8%fKH&9Cqq``p{x_tl<11;I6bm`a$M_Z|rA}z4^3_qu)b5iWY0hLe$$wC@&O*i5A_vI_O*xKVvqDsKm}drZ@H3%mMv7R#KN z_f+bClPF*fzN=TslHqoxuMyEQj7^ z{b&jR#412|U>)~vx;^lln?kfP4g3l3vnr108E&Ek; zZRmY#ZTS5J=%?@S5Z58M1oWXy(GviWoW46!Wf;6fuBB1(cd#;}Q22 zhbJ*MINUVbyqrIx+E$j6HSQMEXRWhoE_KHXa*hndS0a^+%|L(ohpG)o&9dp6<;r}>n4mPIZF($_Nrmo z`;F*!#na#ETX93y=^;x-D*~5-FICZx#R01ILiw`CxaRo99W!AGH;{~nc>!yT+E$0CUb8sLen zH5M+Ytq1Gp z>ELbc*iqB1%11)#JIN7RfkmU3Y^@X|PZxA%h0BCa!sl8f4ZU<_*IWS|z*FrM2{ zZ>~-dTvcZkmuaug2p|sHQP0?4OojWi0#I$Lj!~U9e8i~=|3&bAr==`hNz?rT8R7M< z{<%ZsrX@d$Rg61^S`a62%x2s%{J0JmgQx|jTIdG0H2?;4MQ$ZudyiPUA&7PN>43I_ zU3Mk_)z0JenWYicEPab#go2CEuroIM;3G>>dUYR)--zuJ7nI#j)qNBE*+Rxi6Jy?fgoQ(OF%*XE;82hSoh{5saOAFxwyHIL> zRz93ljD77}QP&7=7(-}hP6!I>nXFfH@kt5r{a3=yuAtV0{Sr=B{J(4k|1$x}{AUU1 zU;p;a4S`ldwzdvN<~BelW5@qWLe*;Kc3Nuaf2S9`6O1REFE}3^Q8+w}#_ZA7C2)=9 zs!g0zxXZ`p6S^rGnu)a>a*cRgz+{wQi;0Ziq;zWl5B#j8BTqF)D z2ofcG2n(`;Nw!cJP7@v>Vjkh!*DC%qHk0#JuKCY&>IWu-dA zhPL#+2It=U(Xo9;>I=27$1EXsBMv|myFnII8m7&JvTl&)HeY>@$*uotIc#N`ufN(g zU{Y?B4Ba4^lFbqdMca`?gFPBcp|=xtjkPn{Wj=f?#wIh_Z2B;^~4+z*QO7V%^> zj>%XhqDiKUiDI<17^FpfEP|}w3sY&PP+C@Z;dJe1hAY2|v(}(c{ASf<_H4A=@ICX> zN}K^v!#EKM2Y(#dLN0+AzkjZVpZaUrhnyVIW|7yffZ-vM7U zZ!s=W+X6J2CGj%sJjoN|a~6#vivwldEF{|k;6l>d^&n{`Ss?}?s~u|08yaDUkDdmt z$;E2>ePjhZ1xx&pXIKNr_bwdfI9fN^cYyP%^+ilHr>jBZ`A0 zzqFZ_LZt^=-ktugjNGctE-KTa9q@?RN1vphr7MP>Wh+x~fI6^_4&uX#T|D#B^eUNg zpyXZ7)`%%1Yxyu0S4eunVi1MSPsZZVQVG)x#l&gLc|r9%@t?@5JV697iz}P&9ry@! zFg$9_Z`E@^mWh$#bVtW=JPxG+6CmT^A_-LI(@*=!Y0Y(qJMpGzCwf)Ma;)W@zgP(; zVY?DW2I~IPSbWs^$tWJM>Cp6pH%!`5L}XNQQYZVZ;_AM*VuEX%NCQ6RUg+%xoTT|S zFps0aCOkf(&6grPKC(-E_gGkiQ)vXNch90M&+P{*yBIVoHEDc#YbK6EWse}l&#eO9 zJ>|jW-8rI#@+6X=!_TGMItLrhrYYLwXU6dluaMOWvzgI(SSr#%=L<9L1L;tAYF>lX zS6z)!-+lvOCd`T2tX<9)Ai||t!ie84xjXb?=X|!3#j;V!;>P7P?^UPflyj9O!qw3& z!LZdyCm3ns@1J8aG_wi#YRK(iM5cdW`yFCPdmt1#V=`#Me1uLlC-$|2+yT)3&vm(C zvtfm1LxJKuf5h*{vtvxE20Wal$dZqXE^O^CKSTbQ@3hIS$!UvObN3tSa9f<9lqV|b zwDV!75|9<~K=Po=Z2i2j+Xy>|e)HN0<5tr7i*x1Z0Pg>*6a|ATiyxWAJ-&Q#g9Wl1jBYDK%2D9m@16X8U!m)#|GZi=i zIxnZ#!7Wpic-iz`=AyfoE4#41(fh8yp&2876v{`n&y=wgwvM)-!)`9R(WBD zsz+?|=TFSL{+)ph)%#i4{5yR)Ty{$+bVE#^pZ@4_RAiI4&JP+oj2cvd?uRxg?~lBv zW5+UlmwGV0@M9roWu3))|I}|_1(H9N;W+tf^K6&u^5k0NlesXEKtUDAepEmJ;5>fz zt{STlXhGmUUAR(H0N%4>P;>ss{tj0q0>CJc5mk^0{}g;Ceeer<_)(?|o)ke{T%cKg zlN8~ns8GCUI`@s%16|7a9nqy)9@#?iSG7E7cJPHnLnKHCbUj?I4q|O( zbvvHN&wOY~G|*t;GWi!+k$(co+Xve99=c|D?gCS%Wb7{HgUm<5)?iH|PG?E= z!1_a300=@^1iC-xVH;*80JDzd3WiGQk1=Wv%g5zLJxh=kYY%{I5#2lcnyDOXK^#^m4sm!xP97B&8rBNs zShZiZ9(LDsrXXyYcvl5X+2DO%Qv9|JiA&K*3itCc*Q{UiBJ(BQF zuc({hS0)suf>oz31%|?H{Y6~oRi{GK(+4Yx;ZrUfrv*Cu!tOL1nNj;3rgbyglJzJq z2TlFPQSKr-mvXY< zC+}->35Kv4J&qZHrWqfGB5ul@j`%#7)0|*cvB-*aWLpCpw*e*EuQCz zR9t*_6fI{xI_np>zcxmPaf`I&08qt6VrnO~hqi-Wru)-)wR*`yMPb>n0Ygz_wb!$| zIHEq@^{?q)(UU=|txq1euzW7OV2+o}{KQMm2b>tD#c^bJbVL@`*!??Z>5w%}ZiYQh zAvjLa8Ip-vVw^r2&c0a`>iy7<Jn?yvt^Il+*>~#_=a1`x zF+Gr3u4gV+{dWlKF5g`7T|5KUQ8r@i5a3F>R$o!d0Y2+q#qMn14a+@TP<-KO4`!m* zKEJpODCmVa!lj+BN$=cf|Bl;G|IeVM5YWL0Xd~imW$d72Ze!|f1#~cXau;zkG`9P1 zCOt(ROVlru-a?TCs-jk9^&iFa5upVrs9O;V(7PTUN@;H9Y4Z2v>=eB(7oDNp6#aFSR9WAT3W6_H-@88=z;dyDG}=Qg?`Dz zs*$aB*8`^1;@_P}t@>X0CX0#|kIwlE! zD;`vYr2aO(Xpv=&0$q|PD%@*TzOF`)f(^~p39Bfi`ZE50vQTJ3tOiE<^dM-^bp@5u zwSe`>Oe>aR8zAI!{*zZlM7w;4dYQU4gv}?Di98zi+pC-1&z$PKfOD|RPhSuJDJ7Xx z3JJcwZgY5uai^;KhscjBy-}sg=t+aQnX&B{19CeYsb~++%B{7U78mW(hHdj^7Z01R z&5JA84IbWd7B8+?kBb2qZb$2MmhGA-yc!tE!-`hAwd!|`gv?s7DBiya@T_*Vzb^%9zR<59! zEZ48n4LA7zgxB+%Oy}wsZD#&&8)Pc~XW=Dl>m=~Mt)DVLCkJ!4|4(R5*q{m^Rmonc zGr_>XTr0K4Lq#F&8G%QDi9;G9A?Xo|Sj1*-hMTxnt!kjP-b&aB?Day~?eM(73fH)2 zfe;NEx3{aPR3sejr#=&cXb%L_AK5ntI^t(hRH>rizsC=b2RromhW>npnefc7LP<3r z>`r;Qxmh@VZE=aLwOdH0-y{aK0-%{#0LGb-b@`OaKv>yVXOa=s5{W<3*;yQc`l}sk zfTwvLEWBGd_MC}H01jceOxF~0eiJ6SpgMM|Vu&+S%1c!~>aximvZeTD51|&7EBfy3 zHL4K`ti)|`{F(;`GQG@r;piZ|(3&?23db#hL&Vj~Rcs?~zX2Qic@9r_5bmdP+-#16 zG>+{bOdXib()<|JtG1HSVZwQB>p>}X;Z(+t9ub(9&oArUUH5ZB-FCEwj(EBc_YTU@ z11@M#q*;Eoqd*In6Iz#z;5i^awYwfi*VNMU82@A{sYAKJag7()2W|dTjz6d@Uqp9z&2S z7NmIIuSj01x|LLFg?)8s3bII3pn6&DR-tLR-y2Mo*#k0?G$8nbD(*=cZmoIiNd*|UGq*Gfh@+LiA|0US>4t*iS zTs->%Jl9q`G*{RY=f3a`?MBT##azEQICp4<;3ywVVyxQOzo7R6&(yMlT*JltQph6G ze&cEu^i{(@KHD-g=UxMR{-Pf9{gFL8}wG6D^C27SGQHjzF zF>%GX0c^rIi_+1upfyre;E4~u8U4vy#3Y-#W2Yk(=^)eDy)T*{jvbKSpba)6*(xg! z`Sm~sFQU|u+-hLP9k^0aQNM+iyl0=DLNJwOI>xU_65ATmy7DX3Sf>|S=ob}p6#bw; zV1f-Lo}2>7R*3$HK>gKyQ5(}(`5@`fNvn#})y>m8eRVc|aFRe4AZI+ei41q2S%!l0 zi+9uDIJPozg%PO}u>+Y7gQ>qn^IqfRWS;6$oU=*<#F5!oHZ=ZsmR-uM65*nd0+(!BTH61%8qZmoSwi6h$8A5(w91?}zY|uyNVcMH>8f9fE|% z*6{U#AMlDp(RPSenzRn3ctqj9c_dQFLh7Q*jLGCe7kCDUtr0C9X>D6*bH`~v>+L*P z0%w}>6GKQD1VlS8y+R>3qH)!_w zvWg_L`Yw0npChq`(!!u_^87-Dv-$_%ozqj4kYjfm!?+hC-Ox%G3MKM6DucsDZd&~) zgaP3!V8bGS;8GDlU?OpjNMcw67V1q_*zqmcBkCyz8S?Q>LD;>U#NdRR$Y7Ge!nT2p&fd`y)1CPJ%XU@BwGj$Km2bi&3G} zv!jJe%eE~n%gZ`vcM8G>#7`%)2#YTI141(dCkW3#9fU4?YaM}*5?W^<&q84Sb99*1 z;>?p4&1Q~eB;jp|3jUmMCogaieT!$Y4Re!U_YeG(ltFU^#(_hI>o}9dZe_I?tkBZl zWl>I9vbl9pDHk#fHH8sN&7b>U*?LlGwn+5BX3zJj5`R^XpFBNGlq`AVs)Sr+xj!+@-274YYMe69AGUQVvh%-oOZyp#4XDxBFWO`--gWBKle&f)D_YC!g75LlXv0d=l4ZvQ>xX=gOJ+E z-#)AbyD-km!&m=#Z!obVm8aBRZNrq000##F_qWWk5yfNM4sD z%EX0f&Ds-3To+>I=M4+>4i9nRh*rl?8{-Yb@jg!4yagtUd`}wAHCoBHh~z(x<}H^{ z@VHGduVG{<(ZV6pJhT`;2dCz~cg~fgPZfB9BUkI5Q&!BtCX2zjE|>2V@6&08BA8q~${yT*udeh)zamMS*$+#vGdNDA{mfoeFQq=j7`?RgWWaMtWsvsMzDeGQ z1|#AURh`BEJXVcsIVZGmlu7&W%R1x=W*Lc>PbG<;apOf*+sGk1pn5=wL0)GAdu}S% zj_N*mhwJd%LTR)epM6~y{|AKO9eL@3qOmr2Zpudh@g2SEf&;#O+y0B_@F+>d(~=om z^Ao*Ohs)R%Lj`wAq{uM8+BueewZ?m&wRp44y1Q1riw$g_WXJnK9^6U@x(3Wd1$1|B z!V~B%2~^U4Zlxq}kFgUX8brForO2lt0$HLDo!Xk0&_5CW$#T|G=2mK7M6D$Hzsqu3 z|5=v%pOr#VL0e}VBcOx3yo0U9zxsOpuiBwHoD-f3_TQ^3D-&0j1gm+Q(VzLsVB}Pn zDav4*56P@B;0x^a)_EfSV^?ujo0Eg9t0{hf!5buGci2TR%^?u5X7R)naY{&+X68tFHHxk>~H<5rp<4@$Sdas9~fUQhE{uLh7MCM1gj|>X5hrxWq#ymUD)gqhh zwI;SnwZrn6=6AiB$%c^POMA>!iFO=!Kd0~BVIZ~YQ~lePdHzbK<{cYmjUuRR4*iW7 zQp5_gF0k*nA-~zecKu;OUZ;3hL@AvIW#l2BGcjX%MQ#on6h2sGCRxc#Eq=m1P<$ zO|n`RvcX!y^Nae#Pnni3tQ|j0)8HK8XT<2wX4^5sNn(M+Y8 zM6{;%8LDAVPYlxVR+tY}x8{#LPRk1wS)*5LsU;Wc^FRqwT7v{h&sysdWYT;OsSlUE zzQlI^(BL}LPMct7jdq!|tDo zIl=2e8R=DFoPHaVB$9zsubTAz?o9z7ypF+^OsW3<_=Ddy^F!0@TDh_$XZJ#}4kwb1 z#c4!XGrlvMtzW!i-%XOXfg=A*b5pY$UQ6tgE~yu0-~_1dCi!G4&>r=7QAYwXpJ3@c_#7uD1~XLc^h+@hT=H>O;q?IJ1Aj89A% z$(m)aT?9KR6$nP*L*1xenz9P)%#}GTLlI3NJh!3?Y#CWx9*IVK)x)WFSQu)=HS>^L zgBD<$f{hVfD7PCr-Phr7_9Tdj8P`AOcJ9I{K#~qRlTo^~j;44;&ojH=o2wFKQ#|Gx zpz3O@Fj@2Kv=C$FUCXLYe#Dn}H`-X&jMV``AJ?Z^o0AD9#1Moy-aB}wxX%RY)1F)6 zO}Dw|O-~75ABRQkbAS560Joh0%w(X697!L~tqlCjIbf!1oeZuPs_Quvz4PPJHdyc8 z;M$kq4E`7J)fYPvEVs)(^mIxn9EyYD=?c|c)3Gr-TP+uDc=b^b&=X|?NZG!xoc{Uj z9DyPqlEdCuM?bEPbF-OaM606=?W&@_&_R^mK1ZX}>sFKzAP5<|a*lo<7{$mcE20|i zCOm9=OS$>!NCw32889R!NWBHmLAyYXJGz*+`a0k%`BQ(B3+Z1wmB1p2VTlGr z6;Awg^tLPtXK#0&|DhmI>%c5zF9YZ3^SQ!Lf<|YnQOE6|Y2-X$Ze3kTlK$r;eoQM` z$>~qd$dXgRiNuS!yX--@azZmJ_Az4cWSLiw+Gu~{G{&Yvx^~R_Hwr&z{Kg^9+ zk!>*0<(_9f!3y!0M9T|&z#Yqd=rlH)oJ66UBWT0a$^*9xFWo(@gCBRK*c?5 zEfUlAgg690cN@;JO&Z0tDECBn+H+bfx2!v!MUxN9IxfdZj#$=S8)x@W_ruA38LF3) zdpy>PhJ2q0u`0_T8Lib^)U~q%@aw)pD|(3UP+fb%PXDm=_X#sed>&|yN({eJdv?|z zjSl+kOs9nD1lrQbI05Ubli+lq3F-T#wWDCQ1IQMYME8r} zrRv~oExqh9>6XLx%MPS+e$w$twc^fWP;WL5gPlRpM6IUUcHiig2Y27??E z3-N~ys1d)(Mq<9$6x`R3yQ6jhBoejGZx%;J<5E{<@k`&`(~q~~MtEF=3}G~kR=jvQ zkiQ!<^Tt?$x(&9IVEl>7u}`H1(2q=A6D-~jlB9r@!R-fHCZPnsuW^J$+&Be)c)M|8 z(QZH!()q9)-Q_^T)7*Ai^F`K%mv}(gpAM(gw_Jf%42nMsm6E!3DnZIKInDLZ5 zCG9{QWnm%Tz@qTvap+Y`f~DU0)7Otp{}A#IvgqD&_d5>o8TcW!xe++Kp>Ko46qx;h zT|v!{MVSI==?`2-?!`yjaW(jUMI5jy8Sjn=@y_lQoe~2?g0T`q;jtsX8fsw*qAA}9 z18xMon=dmy0>pjSZ=gkQu)1Ph=bm){F|jw`G=quKeM%RMfGM0?TFW7N7v>zpF1H+= z2+Y-Fw{YwJi7LXHxCK2!61VKj{>%&X&LNk5>nE5k`*61zm7vXEiXRgyA-)}GfTN7? zXC22||4JCbJ6c18q!m*`NZJ0eBo&UmI48Ogr8-DUqImR6&R`3l@n59fl7)QrceM3) z%5LU=(mA8uenrWn?K+iFQot8_cZ|Hrl6&$XiBM_Sk(mExjJ{}vH=R9ksy`BRDu5I4 z8Z`M4<4kE3EIs_&yotC(zMew7Ij!@Suf3e%C*LYWc4N{kT-%x`^*+Qhe4za6Nw8il zK?cRHN;B4WUIrnYHnTJi`dA{bQ8)yH`yNQqN!g8k36?QVMKuNOuzX&@4k?0oYrBN;|Q)rIF7=a20Mm>;9DQZvx|+q77grH+A3^ApkYn} z(FzhAGeX6-QtAeV$%T*VVdjW<<#3M5GWax;QZe)UOzb%zPRJLPU_UyoDg# zn6wNfB0{4optT*LsZd5nq_4FY(cJy#!d zI-SLJ`(vg_4YX=xTO}yIQj}yE4NpbkR5eDW5PzRqb$=f=rt)SVb?-cpx`~%ak^&8Y z-75ho-Z4iP@RIB+RiW)O1$&{Dg}8y2jjWlWdg+WXehG+Rc_|2BD2LwFKxccYN6JNa z(^I%nA$rY-@W?{lpLv)4z`bMetJzNqu!WY%LEM4xQW|Qxv4+@IxY2>wHY{_gHy@a1 zkqGp6W_qzUG#eb{WFOeeA$dz97~?YGo;O^R#eIy)6vEyd(^%|a&zLfbDk`Ly7u~=g z%yUkhj3{wlXNM-{f-hVNCMs8tk*sBNv1BvThNzp5Pxq1VE-@{zXY)l`z;@5blSRT) z;9xK=l-Y2V7@Dw{m{87RUvFDti)tChe|v@zsb8ip2QeRJNvNY6I_s;oVsF|nY&qps zB{e}Vso!^T7D{c5{2g)FbkH`@#2{5PG;sSj&JUtHY*{rYOT+$wgDzrH=86WuJw@SX|~l#p8TpQ&tfht zoPUl`FCRC1Jw|noL3X@^yBSl9ETRbpY}OQ3dDz1g6R%7!`VsXE#6dX4QmJ`)_53s$ zR&(+&W%hImlW2}fk@$9CBP1_y1mb2|(4PmT+3-}t^a>mxV@f`7)Q^o3S`7_ll7j>b zC70B=!Tj=ZZk%5%ECSm?W&7aairqzKtk5u(bhA=E59m0EZd0?r{yYbdW1=&|HHVd% zb4s~09?#9y7+v0=Yu==Cz{m^_(@!MUaK;TsQ>eN=LS1K`EgWv( zqA|Z<9Xd3)jS>M+IxXFRe*6?-S!UYckWmOVKHU$XKtLoe*bQyX+ZB6Z8hBDvQbOSG zi^TDXh{SoDt=Tng9i3H)2^8y_Vbkt64v7}QAHmV>XTVyE9Ax=P{WBCY#ic{3)Nr7&%shR@s4+LDrU zFVZtnKc^Q1S>2c0^!X5P9j&GOGI(HWYB11!@+u0htqBc)X=BpWWrtu|t|sN?8HK!w zCgT}J`V}j>cG=`66 z+h#N*R^e(2S=?xulKZ6wyUR|tK)DRuD=ygWRxav`NQ_>n7iVmZV=dJqm4=ffx$;p$ zj~I3=gj;*>5QEf=*`RT^*FGWGymc5MprY#YqzIJ^j`aC<`#lzQw^mV3fuO4q=u?F< ztj5F7M$N{2^^f1`X|mO*7`4W;>9Oh-Lj zG^lSj2zD_7fRIN)W=!hIpG!s>Vqpvi5N<40fd@epZtXyhSn9ASicjlSzyejtE6kz*(-)>&>Y*wr zj4vTT%p}haG1!oYyR0j5JmZ9dOu-geM|sUZ+x?@m3}p={v;dxjd-KdLm&YxtcP2v% z8)>@GJ}v=XR&+?Fxxg)(FprmF}Q-f_60IUIN;tzmosGjJO^CBTMgrLPJhd=sMzP@I;gKbURfDV%IdIY5#_t6V+?G@zv{U6RT!Xa}XXwz3i&Jo0Y9J!rbFQm^s zp@c)0!FeFwkj;gEMB)LNJ@wbb`(|r~+plII_JE(oKi0x?yjSEVe--2Qk#PRhl7aW+ zae{-oE!#-fa;Tv;8e>CM;0}t71HRrM0z@5EfiPRWV)=c{W)rM z2T~b^r}JP)?6*j63T%gsda~LWg!@KdgZ@ORP&{aB?!lwm_j4j2E1wvQiuwACT5Hdf zo__$Burm4KEi?!SB;mgUT>sa0hJOH;^p}%?^q&u92cV6k$=8s9|Dq(P)LxZvpV2=r zh|S|0>GgR`?B^k&Favv$!7>+!hQTbXV$didOMf*aVAM4isi@KzeoZJueCAuAk=blK zjo&KI%pl2^*!Vl2{y~v_8vCc3CA<5133!2{CjL~EG3R;x{`7wJ+_m-otaS|ny<5Y# zxLbgEDb6U)EY4JmRfG+=42*_X`W{FdD8)y+UvIi&tEQ)-2be3;ABr@+sS1#LlMj@m za+?n2b<634qy1}M!dJM{z-RV?7f1uoH)GMg!*#`bQ?t4|fD_w2`oX~TQctMYr-tq| z6-w@v&9!|K|J69{k?yE#bY~sDdw{UJa>o<4n<1Z?o1Z}d$HW4t8-)o@x8o%~3l;)S zL3$Jvw$Ei!B5f)k&|<9qp?OT&+OIkpC(mM25;bPUY_QVcK`QY7u=b8ol6GIVZ>4S9 zwr$&1rL9W4GAoTp+qP|Iq;1=kW>wS zQ(bBDtYz$gf8mHe9S5e<^Qo%3lr<_PJ1GxPtQtz7c$yw9k}EaBz(=^a;O#mFEm>_g zFKZqov!!zmJAy!G&HW@hJ1U80F*&OyV!0Lxp|jVo*Mum26Qd8nwFZ(q!#D_JD^^Ks z+tG;pMN3Kl0jcY81{qaOSccw@?DJK}{Jf?6GubsC z+M*nhV56OgEQF+;ReIXfa?(@Qqk(hHuljIO%dV|qoTr#OW7!^fxXr3|yDKwZldX74 zQ;5H?*}7RHC&5ts*yqkT%PW^wRa9zcgzjVG%wnqix8t%d*_hq5q)cRLkpgBW<$6=# zwEO}i>E!*i%2)QY-L%!RA)Y~_I*;Vag>Prr`aDgZlhn9Qm18Nzeq<^sCvMjR)~5?4 zkyy_f2I!%VL1#V`q}F0xgiofq>b(>c=v?n=(}F$b%ui#Q-m;kOFf*X--~w}de5Wsw zzN+&HyD|KM5OGANu^NWqb0f&O{dw!w{keuvx zSN#x_p`HM%%~P+ct|vJa$YpB&yNt!=4qPHy#4U{7Dp4)*1W0)zSz-xPjE>F9%_hvq!pY9a ziJR?x@Ayk(V?CVRGg0GeY3(nF!2i0_3GjphB3K%d`*3q8^{Yv}=Fo7LS{Uu1|@=vG>btv5beO1PKdBNB{mRc(?Jt8QM;$THVP{kVL5 z%9boFR-3HpJ6`AwDm<36ThICEI=U^q#$>VeCiqkpMW_i{jaGcd?R3}+2;3I`gzbe) zLeUAgk;RI6ZKeYaynM-HV~?FZ2%n)Z^8=XvSZyj*j*De@pimKLhoN&f!Sc*@L{|Jf zHVmQ5qp5U)V!x*42bt=H4SC5hQcK~uhOE%qL%^SZs}6~em4uDiG&w}l4+{W0H@x&d zqjh&Iu-HRb)a;JwaJ%$>jvXij3EHwV^8d!zPH3nz2z3Z~nfz?p`$mj=6gEpA0KIiL zh@FDR!XOk>dPu4LgAEXWDMNk9M>yy#teizAqnuStE8?898MH5dM9!^cDB|4mhE2LI zk-+g#%Ep>X&;`(C38?!G`6S;|YkW-uiuBOVRc{%%pQs1Z#?B?8GzIyDQe%>$SBGv< zUHE}(U4~kJMTwVW+;+tIa_GJ|9wvb=6&&zum>ZHM8s)3K=7u{gHHt?x#Y00{QH%`~ z7caFcp)ELiEsem%(#b|mwJ6f`-C0NQ;5^+c|u@EenQ=zksy5|_VSJd8xL@~ z<)Squ0;(iicEHIOORBLSkv<0fHE{()((&6?u!8fs6>&g#zJnwL*ckqi{#oLs$CO}J z*aQIMQmfC!Q@JWo$L|MurA}_cD?K92O7v+>dXixnS+1$?iyE3nQNF?NsxbMrgk)m=eu!#NbJspJRm^#yhNf&F;L zyndvDvgbRuOr=5~Z}u@1{iXc%w#sAt~@1fmela;4z$7 zR>Y+&rr<(Hud3{~yvhd7pA5L2GJ=8|ENjHD9TEJT1DK}j{NK9HZr<8qUkGn!#)zCO zpeV0D)!8v>QIsKlKl%$OA=ZUhi52^~B~cBEr2S*SznKB8R!fu%zXn5hvHvS&@ZZK6 z|Dz24SNr8(a-ds7M+r^k%Yma;VvY~ujE8|$HKCk>;*_7)hJi}Ph$0c8H0VkXmW{(I zZ;%rc&Z>=f7rz0SU0bbMeCzV5$9_k$5@MnD}Ve z>(m#Z_6?4m=fN0%M<($X?tqr%?_@5|Nh%e1Sv@C?eZ4p+Vi1q@LWVUI{!4@&n2EOR zI^;KE4aUi`ktAM<`H9zQm^~@;;_>0CwyAj)iEVdwLA!5!G#+ymq#^J#1R>_(qR*(R zAvqL9aNTmFzC}VITS=YR5U#ftAXBFnA%w^0Au^8ngs}pvaMTLR7_y1UYO;yV3l9mC zlIEGET}$dO!HZ!_su@2JD;6c+Mai1u-fGdZJ_I~Hw|2p}+Z3ISpLe4!Ac;upXtg&* z0mxw2W=AuRS6=Ehi}uwHw#g_uhhPiC&R^xa`tXuu_fT@qFNMUj5xV1V47Z zwaSbVO#i^r+WU^n=JX1)n-58(#1eL*AJO_CjZP?hvfz#{nWF~vMwnl6Z%8PWe9coX zP~z(tKkRJ5Mb23{af6tm8_LB#COv%t=f-6A?SZ$VK~mF^0s z02@zF0TZH*ZbVr-_G?T&%WHuXy&plJ2AVbsxvd*r7n$`hBMa3Ct;EeS$ zG^g?otb^+j!!b;%4h zz;!_S4kC!rr}EMi_Y&e`lOGjnGurQ9^ z9x&`v83RJLX{i}z`u?7!z2&&-N2UIpQSZM1K+;6QcHU^H)?SQ!(#&Py{yqXlD!Evd zc{cCfn5t~BMhS8KM;qxVZNW}rYS}EH^(z9RgKP+$3pgNYmWa|?lq>4}TaYdvIRjFR z4F{ktP=Zq3(mL#2!I!W#P@qUMn~JG#JW`-Eo1qGv@*hO)s*E3?!O0Lc?lT}T@1sP@Hj5bvN$~jqfRH+p`}Ja69}*r zq^^Gj@0f-D*3L?>tZx!Y`>Rd8|Mc*~j8+tu$D%20y2%uU%|U$7^>`OWRn`@jJq^s6 z&2E)41h$2$uw}{7p#c?Bty&N_W-Zi{h2+dLuzsn`;@hJpk+zthrX{go*xH7pq`ed< z!=5{9r3sBF>}z*P_PNUX{yeMJc9FeAMP_xd{H>nKMzkXbDVtk9TC_s>F!^D93Qdyy z_t_zmUy?^@TqZIE*@|0y(y8h^l!4$eDz4bCXx8t#h`3Y4?el-6?X9OHx5>4j+n2>A zb16i&oDG8FFD_{}*dp2&LtESFD<76n840{cBSXo?2pd_}8(A!P98@xOD9FFrsO}_B zK3CJ>4OP}V#e~)_L^ag5+ng%QmEjl>v7o{vR<4+9YNy7aRk^IiS*m!4CX1kx2SN;*9IL_-QS- z+czRGe3+j0D(;$m4c*-WEs2eDmi%}EF*$7h_({@at6}Q($a`0_vMX)Na>QVj2mnNd zK|NR`jMC%bP}^Wz$JpYp#i@uu6VQ^2*`wP!*-lCwtl-_dXQ@J zv-u?%V06Gk(A)2iSt*ayC3@D%>mRmrQFjAH5HOU>{-y&oy6FP+l9nGh&cAJ$|A~#( zZdb`a$bCr-4WMh9`oSA%_BnS8`ef^=a`IHr#xS`$VDB6S$+C6NAwwHm^CL-1OE9_e zz@+$Wy!Or&L-`e!%2HE?qxhmi7z6f|XCD2`rUscIh1jU_n1+2)(jYD6gUO@o1aX3| zrt{ZIiiJ~@i~;le4>flqR!vJ$ive@$)FRv?9x*%=ABM=Up9cUV7K^6DKx%fg*)ZFR@GMD5QxO9Ry2pt;V_f4 z7D2K(8;4c`?=BMWLd8rarfV$SjkRn71%#OB{t`{B8&>QY^WLWX{;@Frr;QdnnbAT?YEzE} z{_1gy3AHxY5#Y&KYu2SEA4Eh-S?tp|i{oq3P?l~}zw|1@C98nvZx=Z@hB^m}<4k;` zOajNrwPj#~&>Uk7+ol?Rg}TGMq0xzh`xQlXjjOJsyV~Yk$)o1WkCf@G=Ca-Ga51)> zV#>IB)R=d$r#x*^HColTV?yeP(&1B%U-7#e$~&9=^qDKZqu;mC&65lRZa(q<9_X5N zUDfGIe-s(wyzQ;_eGkLgYw4sl#bYCJqE9JA{5e2cHDKevQg;%FD%2gM5NepPrQOHgD@I75nfiY#vbYwBQU$cXXw zggeDB%0;ch4VexdD^&}AaK?x*03c%_kq(h;a z7)%K0o`fW}1Es{)3-MQ(JDP{Vl={2^e^@^R1-%t@e~RP~!COkDz)2tjJfpS_2~M;p zk_CSW;{m~R4?1X28+}~C6tk3BcL_Vi6~g70?l80=M`WP@x8+KdhXz8im^sgH%BzP$ zynAGe%k-vU%=PlrZb7@FM`vU#-tlIaWgYJ6dP_#B6P~9DewOQQyQ$v1X*a$LSZypFgZ{3!)Da5Ph+IkZite7j z*mgyp2R1O+S7e9mrksSuCVAE5j2iIxbA*KSH2ddVihis_|K^tGV>LCb&GZVh zcI!g4BpLBpr3(KRl?!+Vxg+)P}{f`N; zbmRmRbh7CHl51?(&LBfvlQZTNh;9tVzWReuMA+TTyn|yHoQ{E87W^`SWC6OYt_P=M z6JW042f}`VI>Wi~%vdK2{dK~RrhVb)Bi;+gTv9%uoXT#TD!O!PL0^$-)33HD=ZJ|l z7mPcV(NS(L3={?oRLo=zRQPS#W4mgmQ$O%#jbJ(3=8$#Kot6s+@qX;_4)s^)@i1_= z-wKQ+`YwsTXDELqx-IJ%oSo@ z2V~ar!lJB}=(Uf;*w~T^)JDktZ^l*l!!U#;9&^}=m+LW!l1_Jw^zn+!*Wbp|W%3na z&JN&|vb~MJ-wmi`hX5k?Nh&lhg2Nd1LnO(aD8Ivv)SCn~5$UBD_YuH1lc4V^YCdk! z`+6K;!#4t=^KgBXqg1@jncm%zE-v5U&!MoZkXQ)_M;JVl=m-a0JVhA>6BYR{i>^~# zj*6oh6uP(xae_BTZz^Ntn;g75g|o+86VYi@5Ip$~=A$HRV$f0re|RHaf3J++X_OzE zpgu`Hbm!R~#`SBfZc@ zs$goFF*3~_lU=kYd6s+z>y9C~>suQ-<;arHO+&s6p~LjN&oJr(^G|R6Dtc*`AMV>X zH>&?rr~l_@rT=zP!#@@DzXvO^ij&J5dwWSc{)dmDT6IEpQ21+xPRk@(_u_8|tbsa~ z;!<%j^`i#0TRt>n>DjDgLNs}KfzgpE3H1wzf0AdZpfjE&%QMGGjtkTMpQi`V?*tQI zqbB2`hzpPw^hGST->3Wdf9W_9=3cVf`oJ%R!t&|sLzmLE7y24Opgc=#ZXFVo`{IPH z=s)4l*vp~ZyvR1cenE%oJBQ;c+XC^laOR7X)k5VJnkfdQ2NBE~Pg>19Np%U$VG)j? zuhoNV078lBZ5NX8nqr&!M6|UGVvwDL;H*_%q>IE0+V)qi&e&I z^6afD|a*`zhOdP}yYbtV$iGv(y-nTM0 z#_ZKTR4{CtVzVfto%x;oj4G&2r;$H{Yygj7k{>v+~*=*|t~SZhmCMOULT{Uv-W zN}9~#t?#$r2C*UTC}FYxeq{mE2_F+)wkX}<*_ym%mPj}KS)Gy2t(P(*?7R9Pt{4)S z(_)U`Ujy~h8HiC%g@~ESy#D81Ac0Oxj{h2Y%KE=%-~RKv@ZW}k{^xh$KSH)DKv|H3 z={{lrK`!7}HTH|uZMRVR;c!aGY*Ulcl<_j^U0)enH;9kSq(MHNrw*`@e?C60k-nKe zkcy+21bRBoB=5WB>k#W?Co`(1STx`h97(`FXnkdD!6w?Top8p?Vx(=*l6fW2TB^3t zS39fA<|@&c>NV6l4CPYZX=To9-8#{K3)~*TuEEsh1v2ItanH}2HSyu=cm=L8C7B^( zb99vw2Jhlph3*K`Z7QyEn+;7+{HFTnSwW@LICgwld~m;>*Z+5YEAc-u0sV`r$NHa; z*Y;{?TIl``+iO*_{RPz3(nj*2#>1^&9COOqf}c#(Y3rIRW-zvim+p-sX#gVL>V=Qc z57@u?eMyQNj$c<$=MPz#<}eA`;AzI!?aw)X`DX-9wi`18KHh&LeG}7;*t39FW09vz z>t}%2YOCHwyrK;^=8W{=_s!*VQJJI*KL8Q>!GGt4j)Z~VkG1)lP+eQ#IrQ5UB74^B z1;*!OjaJ+kT3m86@(chAjyA>pt0$wKEXm@a7>=iEUrj)^SJHOWUp%2gO5nl6~%YJyf%U;Q&yEvW;i@9fw z0->;|z9{8y>5e)0tU*)evzk)NjYvya6TI^HhCqOvhI80X2(J~d z)HB{x-IjvZWc=mFcAZy};)2Np?>x9!K*fRA#1B}?;w9q!zQL-#H<8A_9yYGABF`X~ z27D{F^C0-%=9(pL1BVyO?cIk6cMjk~tq-4B1zekW!$Faxm>OBatgvdsYQEK^As~Ua zf9dPs^-Xpc9!xgaQX*MtY3cnR`Z2keNt-7hVj@w@)VcEpo$Dz|>%H8Yto>qBUA{y6Vq%B(A5c>hl&5Y<+8Cv!u!O0@#~+ z|6CP_)j^Ouxw_mwt!xM{q}s@(Ad3jb)EaYP@pHGurBv)LUdJ$oI%}@4})fnl+B`WR);Y zJA9F@lhCq?ERh~1{{dZRog)(j0(N;tZJ|F!$w0cqltOfOQ4#l8w<+YReGbsQ%gu`x z2vt+!R<$1E{$%dzlRYVsD{5`63>sG=U8A6q^<0xoqnU(bl>UL5p9;+HoRJ6fe)UKpqt{)%2LulhD!5V<(0C z&5lN~_!o3Fo^F5iBKP9TA`}hwO1bo3&C)J*wj;NOUDfO}A3)-9+N1Pr)twmzEOc|r z^(F>4P49I*Tv60UH3^Cab_d5=Eu{KsTn2!`=^yX|=4C_3y)Gq#03S&t9U zZfE360cTD(g)IS40C&=!(AH0RNBds6aovKS0%CkA&hT_ezfKS=NzUXHP1KLeWB#n1 zeuK1<;2M#(LSC^J6nDv1)gFQCR?st!&QVW$?X;K=Ap2sU6X(c5h0W*ZbKrmF>XP{N zmMVV=XZnk*8~`B+1bP63N>F-OMF4ET{4kDGonQ1S75@{-{4f=@ZtO@U50TxdR}&&* zYQVX~BYksLvUEiN2GFRL_ls~1E7~`)V40TmJLX?`0h(m|+MHj6Yux`Uit0ZfYNG#> zjr#u(IR9!!e(|l<7QR#s-a4dd-1t9yYuzGca)$6o=ID9S<#JZjkZ1djg;1HsY;uX+ zey-2Z-aaT#l@TbT>{}_G?V`Xl^emCT4Vm3v`BGe#j-0*z0iPhmVH5~3X6$AC%s+Jy zkXW#W{=r-GVBFJUs`H!t3vYdFf8{lxRzLc0cxyUqt&oYhhhST0AHB95itK8Wz`$+` z>`^)3efxosk&kpuon=g zVft>yW29}-rjO>&QZ+-qd~$YX2;)XduZ^$=P8ocyX;+z~m&`i%5fyi#8Dj638=GJ&?+aZq+2L7>_1M z@?5%KOVXt2<*32n`kvDwj`H)Ycgdu*#^*UP2;g-Q$aYerGU|j|!r(0ksxC7_1{$C)prq*s^&+ z`2Yz3W1@^4fjVdu8uzqZuu{JP$(Xv_7GQIkY4^Cwz8327g@^;bqpOalF~@VT0J31f zS|VgN=a-W}fJG1skav(4@RO|MgQ0dY3T*UR>dGE3j2?Ic&Kiy7Zz&6h#-_{Va7*aM zbtmC17h@T_J!m~D9Hnzl{FVx@wCX+79BmI#hfXSgSoKY`$6SX^TgH)@$}_%Wmq{D( zTXVIF*Y&sZi$c{HN4+o$yP&PAO2qJCp((IQh{8si>q!}lmf{CJwzg3oOz5%i*SPRmo zo9{fT%l&!eK;cxM>dOk*NNfF`KO-uHNxv!5KVX0kkIq29pA$lXjtvW3w%Eg;R+Dlo zUdNsfpi11kG+r~Kb_&;-q~7o63wg|?CHXO$ScHc(S`s;RdH#F;&<9hbG5M*11QX|&e_)hn1iYa{lFMAy zR{r8LM6@`ooi3Lsp|>+ws#Cfs?g(U%Y4;T&UBnPbFVJ zf(GsyiOL$Zzz@KlMKHiLC>;5S9V22u=^wctlJa5E_O)R2|H}pQKeC|xzZcBE4wGsv z11G$%Fhk9G8+-GEH+D|VEpRaFxX%Jg`>j7=KLZk0%YTF8XHhm4+gjV#(*35b)G*H2)xed7Ck$+N@r{O9@e^@i)))2=M|qbGUL3`VFF2S26=^v>dqC%7>-N;D}6+ZX~f zOAE+BT3r7;Gfj!osH<#flhqn2538BkqZv5fp3SJFGMG}RK6t5=JKQ=u7wS|(j;+EG zt4KCIsI1_4To!$~?WjZ&#{trj4-gs9CLro?EaL)G$^JX5|L(@X)hP;(DtMt4!)vieJL+EjL*EcHkS>?;&tgTPf` zmU7;R;zOir@kx>VN*$W3*qKJ1*JMMYpEv=F!Hn!^>6htQ9=9~wbGlL08H5cj=V+Ax z;ixnsQDye_tk*pF8=$i_6&l30G{|1==C1(nm_`jm^&$H6spTZwFj9riR3aZN?jYbI zeeCKith0oCIy1ElNn0m2GMVP2>1^CXZQ7g_u0gP#9-U*Nkt=GO?KtUhq;_-kqdYhrWvD8Yii5v6Z+ZNwc0OX2el6<3d4aEE zHI#cy5*^3=hr_g4cKou~~4qC8Wo471fKR-?B9#ubhd3af?(f~UoeSyhiKl)7sh zPhH@%lcwR-@=Y|r^41Sw=IjLoaP~E{No}R)QsR0E1R+4$lOPZpl4}@?b?u6F;Wb2g z33Jv5R&v+wekgT^Wr>2mWB`Z`xMnt9w-=#E?)uMB(3?@yG{Mnm06uTA>%Y2vQ90|P@^HHmzx>ypYJ}(C@7;o9xsLPwe!`}I zMfR3?5u!l+&bP86#6#B?RVO#-ms(w|;gnoT;jgf8{Ae!QAuQ;pv>;xq(5y_YFKpM% z1|I*cC3J`mEhIV5)o{dA(Dk(sJUnpbNC&34bFAXlAhx1AZ|?(aY>CY%C{4dI9H)WqMJ?CQ@xAX3>IcFJ26FKW;?*q_m)N z=^zLgOr?f6JK#XAOB_8pT}q`XFT#H_fJ-r;n7B$X_ZVyFG+R@MBFuH{e!JCY_+d%b zy*BiU7qe3LTbbp^v7m-WTebyPBeN#IV{acL_!t)VT*FsAPFLejRDqH8S8e{V)^A=L zKq8&47-24nti7Iu{V-HGY#IgvoP%Bw=e*M`Yem8OKBoz(E$>#xJ*uD)UinfxGRlok zTwJxr)RKn6eHokyCZE~s0A3l5gFjaJ?529&kiNYHMrsSaPDb~djxNL8@UQ`Xu4!71 zrLdtmK`nmg4eE-aae4Q+a;_AS;UJ4Xu@@t2S*kOnR@ozDbIp$@23f~MULoUxfJmbQ z%NGW}zhK+_M7J*Urv|>!M!VOGFHqaS-kVC)`nMff{5-hhA|0#;g= zSd#0X8$m}g(F(yU*IBA{mOmWAGKE@7rg7dF3Dc?s>52wW!N#*Yuv^UHxFmL(=IHMA`g2K}>);c% z`zcgvgDEJ(ZE+R6EYq5?ajddSS8mb_FW!O_av^AWbBcSP)vXG@2e8W)H+j|>q1-_) z|G>xeeFpo*u#Z+z1gpF-|I#O=oADi|F-vK|XUtViq+GS7+sVWuk$diuHt_1t9xK|s z-yEVSupxOnu)wb78q=bOQTVQRfni=%!!&E#wD~(1`{ZrX6d%P5JROLDzlP9oO#55z z`ND1aLA4^m=;mxZ)qeP7fDiv0pirI-A?r!(EKwr&nJ&;=iT6(b@!fU;QKpsGaDeBv zz5GDp;nWkvlD(_;0P~mw-IYGC?0}$)F3zE=15_)AM~C;T5d}JS1bN30!3e8wTlWeP znhPp|g5+7P<36P-h5v5%V%iqC#(j?8UZTZ%ta%m3hNM-+qF5 zO9)js+dust0`}4~n|9gKODM?`bVe)FjHsOjW>urs?PcDc+vt*CU;$M3v^1!16FnT5 zdeOJ2gVsjqc$jrd5dCmxnFj|?Fm+kwkd^P75`eFO&u5;ga+M?iR1piNx;MY-8qkSs zqy*SU5Q5s}zxtRz(e|=5vqWn~=cTGX14s?Ui1Nr`sL?muX*Ws1!kz4t>_`$$y~0z( z-$)94^0IC8ycN)hf2obq-WcM}S3zzYLZl`{8?ky3II3@9+aMNv{ycrh^;Bn=rWW>- z%7>-Cp`2ccmY8Zg>J%FZ=@_viAEAoLb<$v!MtTERm_+0krTdiZk-X@;BDGXp4n$L8)I* zIzfx%C`EerQM^3u+eRjFMV3VFVNDiakYI80ODz3jE4AH|9GSNFE*%ZH3cP55qNtPoj#_;%wAz8#i3u4;Snf{;ssEs zN`@o(Iw_OWamJXpr7v3io-0J=m!ia>--CAZt$jSNn;m&`jU2DPIe~YA*g@7|2*Z#N zC6G`Fknmq|@is6??2|DtRxcO%nkgLR85>ZWX;pB-m>;ZWfUhgACHvu?i zK5ZXj=d5%ylsARk(t25;ZqXMWN3AX}waWz^yt0bn_bjc}hiEz?*)w~%OuK&kX5PZw zbJw}{S0+s=VG!rm+Y}34FzRRTVRHt?!C_Id;0Uz~1}F05i75bc#pb}%#e_$ls&2Rj z=tVI#+h?3p5AcNvVf8KZMp-JBzx$|y#3&`uedqhSJM#O#?%MwU`{zV#?bIFJ zTwK2TFRs$&Za=JDT&+$2S7E8S<%s@;YT4RK&vx$&QKe?}g}yWI+-gv6nn#KXiDa;o zGq$w`2|2r3Rpjebv+%%xrX8Ur{gX#YJA^$5$A9yaMK?13Mm##;r{mq_uLu~GgT$B4 z#tqTmCIxbd+dR*kjVA{l{?C(dH!F{L-&($thEtqY^);?)1fI-Nd_fR9e<{~XG1e1f z7M6l`uU6(Wg%dx?O!=2bOxTwu{W-epY9fl8073YL8ww6;uem_Q zpvp|FRFk?)A z;L@e6^shp5JsX-Qhc{I5G>e4@$g&^tas+SsG$BHOjl2YWd6trI3m z`qOgOSn&o&&ciImthBT<@h&Sydy1d4+q8ImT!pId$-wIPrueD$$(J9uH7S?{+!V43 zo!;D*Yh!*colAN?W#FxD_deCwHFC?%$@?jWc5DhvCxkZc#h`7gvX-8lNd2grA85TD zzq*`Kex7eBhGx06TU^CDnnda2QYcD>S`?_6Jl@<<$M<|SC_TQ)xJ~mh+wQK@@J({l zP~~66xQL-n&|w^1$OBQ_r~@k4pi`fG5y+wO&?Gdel6FhqL+c2cP-cAG+}moLMKS5r zuwjhxGQ_Y$Fb2}}M~uVb5>#;keK}z-4!hA0^K~%~(yrGx*ont!jP6Ge<5dHr$BR|f zbb{lRC$*>?tcLZ<>F z&ow*Jln^#HCt-0kNfcSGDbjKM{-JT9TM~^hX+_-%jmiUVtm%R)dl$c+sALN~VSW`Q z8Zk$`f{=ZpzmQv!+(3Kiy`uY8?9qfX(Y(|}+r}y7<&2=5CW(5H(F0)xC+blvtwf-D zq^!}3u9N~YPf@xHBv2S^JaGjBQ+^Vrg&OVhj}#X{Zw9XyNI2xnuJniy4}2;Ki3zWG z<65{PynPuHlGXVf_57nj&FMAl4KXfU#;*tn^N%XtWC=Np(YXfB{})gt&gNHb_z=C zrofadS&Rh5xb?2GQq$nx8>X{9Xo2T!O-acBotG@#jM7<(BFX2m(eD18$^E+!ukoGf z{J!NOjq4t}`+>q`|Hf%Qk3VTotY2F+caNx0&j`pdbNB{6i_ih{mDAAMGz{6_9|_xo z*aL;y2r&rm^^mbFclP6|T7c`h-LrAC*gDLMF2c`#=Y~K5jT=19`Dx&nr|lr=?QN>I zthi|QnW?O>h&5Gkq`Y)VK@&T_XpZT0&FH2xVx~*Ob(vPSa>}ra!BY#df#1?;D@v-0 z{7p?88SYu!q3LgC60Z4@L{-!xbqs?|ca5THJ`xu4op{7c(E#D6dH~Y>QBE$4CYPe( zdKK|-_<_|xaF`O`j232{^4J1&PG4fQ;aEpT_)j8@ssIFv;fpQZoSb19$xDR9lPJbKQh5g^UL=inRDg1ogXXya zEhj`0Wwm4_2}LKa_qi?mk(I(OoYjZi?BTHyK7-m_%?Q?wd)WtFA}&aVYRx3*A|OOx zDIc`h8JG-glb6Q7V$UJr4@E{Z+1c3?&IYp)i4qj+*lu^t z{!lFV{+9ns@hS2dR?^$qFub6?noYyD>GQPhGA;0&wZn5VzVr4s%IllLi?jr?)SxGH z$GEY$2yZkzJVYU_nVCj(zq&FLH=z85hn^)millTv(s20RNge$=te2LA$_*Fn2Mh!d zBTKoSFp-v&yL=Y{Lj_;srXW%mA0w(4d69sOkA~+#b3--?O?> zDfpQ)OeOE7e*cooRh$Dx%s0nx)_;F8lCT?d*Q9g8qOK!8uPbtvpFBRK#mjFT93;sA zF0NLe%$Dnb2rKFGxWi567VrY8uCW{GhjH=l_Ebx2v?Q17DSM~wP5oqERTk+yrn92} zJf75bz0`a^k&N+Q_7>Bw8x)s->Y?%JKO`_e!m{&YY`v|G0-Sw^oDk2+FtsXtezO~t zE(E?AYA0>6Bp!Qgf0mm{Ovuh(qm4xPkqc0j8+>J+Y@1t^v6*4YZlDqx%r&3q#_vvW z&5hAT<}u}>4!R?zQ?lHs$?>`8Gw-gZo2)1AD#f1QY!iNPwbRsat3$@=GdJ?UXy^=f z*RK**8sXF|D;r!hD6couCv)|wA2{u>Q%378LEg2b9}t*tIdi%+MB`KCj)@R(WC!sn zuOsPsrz57dM~4&D`p@5VnV;4;_l>d+pt_Ho)77!nE@*+GS}y6+xwz z7Iu;=Y2=H(0*vF6eDI}8w+SYk3U07DYI-@;DDR`ze%MH~v~2Z?7)0d`$##~B{u;`= z!X&_DYuA7NM7p#pgD)hE9{q^jHvJQv)8x8d7jTF@XCyYt1$# z{>h>Q%O4)ZWrda9G-nU%TGiQ(`vnBUZP|+s zCNjWUrA|}?(I8kl1F~=2VVM&O;qt*XSewshJ$<`3or-^I1#AnhT^mc~=>zr)3 z*K7*i55G7qXtumIcF|FhX=qO9=x~)vU7JJlx;>}&gO>|uD4)GgkoKyzXOX`UM_R~6 z^zj`sD}Row9^!pfI^FPglmG+7bHe4wr)>mxI?o>eRUKWq*Kuh;WukX$PVSKxdKDt* zne_O{tfS+Zt?_5I{jX1fO_7yu`Y_O`z5sZ`kZePgORSjVWvm`N)hW<^1NM;wI{bKS_n}{R2IRD&bGPGun=_x{q$Yxo!Buf6jNDx<%9H7m zgu*wV{PM3{bo@X5Y&)8CpNN$Q;3kK-HYLv8 zoHs1)Lr3$i-)~F*43U@q3CRjTjNc0#;i)>IF5r!VvZyz9!nNFQrXVR-I)CPx5G|uX zMwsM+dY_UNk3hEbDGUrxuz}(5XULn!LU>dnqg<3cq|rgGz$+xl&sOvRo_t&e=wiD4@nL~nehZ#=;FnnpvY-6g)gV>cx8H>C1s zMCNn+p0vs{1+~l5HN4d-(;cOBD=2vI2g~>64UH&SWoc-fSo!FnZA>gVw}GZWhIo`T zgOG|9)H8=p2^mMkq#Uoi2t9`@P*90;YRO;8Jt^yNJKe&$BeSsV(ESE0c@DYBJ0bap zB;jpqCL>eagToSj!C>R+%Mrc}kK;Lp_L*&3FW`}s7^OXs$8cekhqTl}nM*oXDd4$Q z`~aR19dPdh*w_y|Y{jo-1__9z{`d)XD^)VXF1L|ub;z!^HF`_z!>Q&-X*nC$L)_ z-%s~N$8MO%K-P0P8-Gdk@Ym6QwHJ_@V!HRf`k-ZK|COxxA9-gK&0Sp0&Ey>&o&FcQ zty|0fA3@=-scUQR1+&^;1e%2^8eZpwo|S+M25E}t6ladL_A@ZFrntF_`0KJ0qs1C8 zA*p0aFA-824b)oBXtPAd%Bs(8GtNCjo;TZlJP9e={{r|CHofR~CEH+bqS|Z5o3YjX zoZ~Ys!1M)hJ5~Dh`o#T-;5iff;}rJK`;Bm|FhjyVM_yl9p9;QO+}&VUlQuhsw!b=Q z;V#Q<^ZV$)ttrY6SioPE5D^k{>Haz*IcL!u-)dANAlI8GJ{1Q4p47JvPXQV$C7PF# z+#R+3$7)&r7)PyrK2OQ691PzXjOCn>IBg$8rygSH9gL1{>Q%!8;!=7#GUJK-aC53b zUCAh<)4jH2MLi47tmUjgr~#QR*$aRG{<6z$Qv56j+aQJ zR{AU&YKl0(2H5O0&7!&&9`7by8;&ER=JKP3G5><{E~Pyef2k3W6Rv!Jc}y9p#j0t; zZJmxvm=RJJZNV36s$F7CIq369E|tW>Ei~%c|+;+9cR+ooC5NL z=_X~<(?h&?WeQ?e^ee5ItiR=D*&ZRlG=!ISIMG+wL6mkK0kH z_@OAprX{hRJvn!%F6g@46Q{I1&+YX6bb*3A%hl^1^4{~~&XbCmCk zQ_&rcH6!_0=TyBx`c)lDuXEtTN-L1CY?H}+HwEQao)1I>JFxx=-C%C{H}tg5ZWZQH2igS}RMda%jm zR4SvMt%8_CP<@V^3?yxpj~H!4L*I5UnJbQ(am1$+%f=%{EmfIRr#fS!_9fb~e~PMC zopmW$HAcYDs&OSRF4?6gXEvutmCbf#_St^u!?CU@suhDjs#q@}9R9Szd8`S704Njh_aS8=CYA{odKB$Jl6d9W}&v z7Mt3e)2!m{u=c=>HbnVzPraXY#QeH?b~zm*vU8Dy>^yw?cr?n);_nZA1{_&AUi`f} zYKDY&7AF?xy?+E>UXB&2!VWKYN720lbyK8T?VyA@KPNae;*TlI$jogZRki6LjhL=0z|3;1}?ysN$o6-U;M?aUh7N zm%%n!IM2$tFt2gyJFk8Ot=kn*C!kr3RQ2F!i<8;|NUDH_6S}Fv7bn^i_!!`X`bT%f zC~oqRSSg)F4dmES1=4GTqN@Jz<-6QxaeSCGud9Wfz*&9yF0I}ubX@>cJ+7cz?o^#){EEv0Ul!dS6Wqdv9*84`+Y`HPs5mB0to&(#(6N&t z5bivpFuz(dXPB{j_*p&S^d$Fy^aF!0EVi$IV2|OP>z#pWd@1P0B21``!OcNUZkMX1 zD0Uh5d{pk*$=KVN34>iHMB-K=WMt@!$F0k7JB%5|l-aQ*+$FW^u?4~sS0}OK@CaGd zoG<41v16dFNZ!g@_(@`e;udEFyRG`= zaRP5$;2%y?0bphbgLB3(sc!j#cw2&}8D4*Dod*Rzp;GGXd=U-!(edM+No#``H znlkZ>NG8s^G4;$5yvH@hIroJxU=0-rQ|w#1kaRM+uo(m04GC}wkhpoWhyR}Y!h1!} z1pEVy>He>62;Be4IOYE(7R+cu`zWtq{>uGrmzB`g3ItVw0xFdqKq{aL3YCg3LZwO( zGNk%*VT&b^OeabC9GXqv)^V{68xFVEB+D+~sZu>VLwQ*?`<}IQak_hVk>kzb`g^y% zm7Sd+wHXkzSAXXBdYp6jnSbZnd-u2u4$mVa;-`3AhUB#!YRC^Se}7K`FW+Iw_8s8= zO$aalcbl1q=ZfcK1$xiprGF2$E7~oPiBt#323f&d`Q|3OP>Dk zJu-Wb5dX=6DtnI@zwxCj-tN9D|JeaLR8QqR{f>%M-=W~`Cu{vX?C+O$s9*W~-HysA zzkDG-#gjO@>b*4NcVy;IW@TUdMg0?d=&qA8YR?R_|Jea9-cR9t7u2_Mp+Du5y&%bW zGY8Uw5%iE1Pu&P8DoY5FmaUm_FD&ufRP|jbW zM1>-;`S%myvxOQ^q=ohA&JIqS+G-0l6MYQZA;u_-<)qtLHQLpZwk9$utRg_x?V3@c zFFTn{WL&~?^7<)y3iO3(qp||fj+}0}Lv-Ds$Em9~{Js}FLfs}C_uN&~B_JyyYh)HT zO?MK+%jGQL2Lu&$>_`!0D6~lj5dF6qpX%^HTdp9OsjywRvwg?ipX0G5c@ejV@~N=*&`?z-}c&^ycoE2&EpN3lQ-9995!W> zgtTm}&1S((3|LVl&du$G5g8EEA<=YlijtQql>!4`nFNvLJu8Y zo3L>V?(ivua2^+)fPQrKfO;RnNJIT8&O!$fWLzvd`ci5%-Ed1m+3;0Cu%L&~-+BN} z6~{Y4(8ZLR55=+qSBlGv{^g7IWn*260|tJ34ppQo%wh#6>9En#KL#A#Sj7js1ZlKu z>lkzecote=`tXM(OW{s{#=d7`nkEAO_HZ1`Y2o~0Hs7}Md1zUa_RtUJNV75>4^>CpjJp-1 z%MKdQ?4r(+vi+<~1A88W=h@jsv0e`u*nCg<@Apw!-^>br+axz9O^tMiC0UQW6%=`V z#P!j~f67@;yz=W`NJs*zHecMX)+%f2no<}f>`vwsB_&J25kcSws=8Sjg1Y>S1+J3t ziBLY`3)JE8$8m&NU#%WgzPl9E7`ZC)Yy(xRJ!}$>s?a2-98>idG4Lle=MmRb-SoYb z`stT~3Qoh&hk)4Lvh0eKSYsTRShp z(xb>eO%KPn&d&_V;F~=%W`tQ&xNO>lmbLki=xk3edBeN-&$OK@imte|Tie(a#J3xF zriynO1KKEtC$>i}dGk=O3cakJ<||p|gj;!N_6_;qpIcUit1oQu)I2J}&d`)_e;Xpg zNuheq3V#LIel*F%8=LXhV@AQYB` zuOQc^a}4#Jg}1Yn>>19r86ZZ8A2H{>prE-d+kN4M{Kgf~oaK82VV(1bBy=o#oGwy% zTrh3TM7uIOg%F8(28p3SXmRw`%f9xIfoY!R&CiwKb%pX@=BWm28JT!1nwcgD6mwHQ zn8Qm8ki#>xKxXh=%GngORdPdLM=G9ztlHVou5U$6DHj&7y8_dvq5-e%V2)v`DTWgNZ9+N0#*j zC{KTJ6^)^bb88DDs_;b;|AY@K)8QlG)q!MhM$ztcw0IA7$7yz27vKRF8S^)FFZH4A zXEe@>iS?Dynff!!mLO%xdaB5hCkP!`(9IAJ(;=RU?Za;A&L_<=IN?U3 z$Qv`JZ=x7ox?dGzbK2)z{1czkJ89`H`Jj4T*sbd{cHz{Ad&G$`N6MZnF4~fYW;{xM zCccQ7M6GPD1l-Q#idMlR*=UoU(mtF}VVI9RXQXTNt~dGWd4nn9W&k62%+;W2kEm%A zMN?K9Hf~fI^6za4ZVMf{uyNY}2B0}6N~cRarw2@2zItQ$4PQM|_zfRDbb_~GJSTET z9PxJy_5f}84hv#bCHmN+zlK537C^cZ%I8Fp)na%R)5EG{3lNes=}-nyGlvN%*kXw& z#;%gjIkBoSt$@}ZJ=midqQozXf=Kb&dG}J+>og~F^XgenJ7tjDVUTGP?mx}%(Ejn@{2RQ**e7)74cCU7#_|I zy!S25qW3M0viH;2(^UGPkG1zH*oLv$46m#nV{BQH>`Rd@(IPxz>E=Xyk!nFg_@iq9 zfmUfQazyIX9NvY!cCJjhBnddMfh-SL~MA?~Q1m0rm2Xr3bWef%5 zAZHv@J#lM?vf{xP2gZh$c8AP|ACzX<3a5o-lUt#bIv6seA?x zi&@EDu$IKF1LA#E2m)(a=XF81zqW`X<=n@y?TV1}qve`m+msjjt>*!5&lwH2ykX|s z@=#Jb{rO;1<^WEbS@QCN?fKyKy#X=wL}a>69IHgZHhJnqVNJ}XN<@kWw!b-I_rb>m zvikx#4<~Au*n9E;|GPvDGQ0@5n4$|5I{Cv$yWG;jOMS% zm)59&hf`b6MlAcX5K?NFsVfS=DOx!0K$d+$E{8G*a|(!K8>Wj4_KnDpIC`#z1Rgup z7(%}Vmi+r_I@|I`+LM?w0q@rVgUD`q`}ia+M~j8HqVGm2pjmq%r|bnM%Al@O6;eV+ zdu$o=UIMnmxs}{|wO}o&G&#zCr3b1p29BQivPNe?*j&SMVmC|a>r}AtEsXaSjT>wY zn)$471`mRad1BE@SrlaRB#t>J1k^LZHN&d2=z|s{L(VZz4uEy8y2-H`Gkgaxl4IM_ z$xFOr<_|bmBNf%;l_>5}J#;{>j7gPsDOAME8$6!eO7!>#e?sDhU~pZSMo+Oa?IXpW zmr~G%oiwBI@|0f{JvT+krH=M^zEunx9!mdKG~VB5@X!S>UGU7Z zR)OsWSgT(8je!~eq26wa6>E6#YD*rR6ZnY4rlESy{CBalYYoc?>UI#%uuzAkvel&^ zv0)<}Y7D_CQw48A94|28JBgrQ%(Bx`YQg8M-0!iX`BSrwq-Qbm-UejQ$vz~`1%2T7 z?gA_ZD;Ucq1C)q>7lqdwXW{XLYTJ>F^yXf-c`x?YfMTownI%D*A?5s1L7MUS0y?WP zd~Ko2GN=c4f~6MN9aT4m-Tkqu@IA!gHb>HSh)V`urDpWZ6-!F2cdKtEXPr1dr8D6$ z;^h?0fD$ba;m}SSTOk{^DoM8{EwJj88!bnEaO$DCgSMpd#YD;eq;44ja1W#TGW2kZ zx|oPbQi)sHVAIGkiJ^3jQDlMW1QacseMK4C&;j;Y`hHP@rcR%jG;P|9;!-tV0lImp zq6F4d;7UOx02lU26`e*=oeBEa8(h}`bOWU8ahb>78nw!I}Y9}S>+H%oGk!h1>QOCPZF&qL&$Fm=EMIWGFA zxYa=-&$=;LT^8@cN5Rqnp1U`{N{h<&N2;rD@u1%2gBsP}wAUYhMgqRzJK~O90f)~r zkuCGKq>JQ7X;V%=yv2S$_U2i(SbXW|<2FSv7IDY;DHPG+bzgIkV{)51@fjBA&`iS(tOf*mv;?uIY1wIlNl8!Q=2 z@C~WImp|LDK(OIoQVR#TZ64;XnQ9CBu$ktjt!}*M;9k#BK-DvYuH4gGfzzEalV)yw z*qsxXf_QE>ACh}M|4!SUjm~u7YnT8r#~^-OVNcf*^o2K!K0@fO)%WHf%aCQ z?$dhcA1S(+nK^WQy(k%qngDJeuUSA|D?#fPRCvl)942Q67QP$OWuJ*5ro zrQB*Xt12a(>N221tu)_C$!3n$Tx!;|cMJP6?ILn8ntX-|(`0j=N=tN>CS9wb%59$+cd+O5S8TLyo5Ped&HST|ooK$x1TDIG)~8j+jaT1*i_LXM zhcULw9zB+_>o6Y1jw~XXx)XJa5(Al*Ma*x)e{Hh8U*gl#tQLnfW3nMyM{0jQ)%>&l zG?R1B4cB;@PKM2q;f^8N@Gwh94j!3d(~T%KOgWH5-)h#$XG&W`IQp31KYN4>=}eFzExZKW|Kd>$UJ3BK9-a!OJw7E(N)S@*}hB6*%_aC!n*70*OZ&- zPOT@0)e<~>qx0yDpszZNy+L|J6_zXwB(B#%(Q@3-!5Qv{S9g}AeqfMQ3>0>%0W`^$ zwlM6fePD?)7l|0WE{rMqh-2VV78b7>^$n{kMh%PEuCl$>5Y-(-jGKG)VthkG)J5Gz zOAKh?c??`v81*v_b=$yPqJziLPiR0NpPxOl ze@CM%Sn9@v?hI`fnXoLGm@O%ruz=Cigh9A_!I~C?qzP#XL?3urJYBk7h4#a(L*mcW z%9+P^{4CzY^ckqqw0)OyYIl#(-`D6v4bUZW1{~`>>2@XEM@`i8i7wSngl4lwso7%< zvI5gzW?nE+PD`~fOQjA5`^T9n8?%ONzF9DWdoJHu$>l{)VJCJ=u+|_g&kDE))*6$}e!!;9nY{BY2WZ!C9RCQqC|CUNcmi6#;CZ+4MdJ$B5d7iN z@blY2c!hFoGp8jQMA*cMqLd8yX(8I?%&<%+e6Va@qU@Upl5@$`LPnX@d2eAmIXxIs zY`EjJU>6C`nDe5i2$7<&UaqzTRO^W}vgWezEGsQNcEhVqNbNOwh~<{WjDjhpsC=xp z3n)R-0M>4iC0EXrLvjq_ijdV&6WuiBFA!r8)DG4(wQv_r^~-g-wfTHF_zSCo(k{%2 z7$UDfcy)&2o#OEz1!3t+S_x9}u-r>Mf>c;T6}#21P6-uwwjdI(tsJJtxie2(dJCTw z-)Qwz{=}(^Frd?5qC={QqWlxQEtlSv1uu%Y*X8;s;0$qs(*_XG5l6~YmEKRE2as|{ zl(SKk(~(mgLd`9#~08fkd?=G$~Yw)hL2w0;SjFLcT6Wn1VV^V5{Q?D9O@1k31SPU4j~HkBRT!r zAw?*hp?@Hs4aK&HxKY#x0Tsu(LOR>4vQg*GDHc`UiEDQdo^Xht^csxCE(*J9J4$&b zv)aJoNJ><6t&b6{zr@SX8uPL>REre=a>648hTW?A%ztS|16Ac_IK9rFEb7 z#*axxgWSIUJG0t6bHFG2&lGn5zna2S{}VOy|Lm#y=MA&_SLSMHWMlgOVJ4rb&)6?% zApG|5jFDLiL8qkMFWk`SM?$lP>Kbe*p+QyaRt6QRpdOkfl`m5?5|05+?hONy6s5lO zhaAz! zHE>KEs-q>-l)>aMF%TDY=xIXcphYqJJr?{0GS8{zS?vkJ3h z0RrkpFf*q3v%Si;;_JHekOdo9+nje*rDULATUAuGoPrHu@>9a<-)6;*73D)$n?KgA zu3ML&tqA(b7sD_@USp?JqO$WU6*ZUwI*bbFyXlx~AQmz8{tT{LLXjt*>AzCz99O;C zMBAp=`_el|g!^r?4)QJYCDiPu`VOsweHqGGZ=#NFyJyI)wH!nm?nQvfmeemct0tfX zjbxHa1f6sKPy-saOWvsyKThW6gRa|r&~e{0a#F`mMU@qt{4R9o{H->Z-Pg}DrvNwd z3+|OQ{g;}#CqCwVR)fAS^3*HbP2boxCKQiu%Us9>3bhv}W;7}d64-qgMe7I3`-L-B zHJVAk09~TQ)bjKRjYYX7!K5&|3G|4LQ~H|Z9a%B> z3q9-$Uh^Gc>zMfX*f?gKe4RRl$Yc-1de-1xm5I>rzF#o zTZCnc0NmonfF|M^%=1Aq!G|Vd754ElnE*6{q)RYqhoIg_0A$pGVv|RB*XOj8Q!KUT zADQx0^&Ly{olFG7%G>p_EF5+u5Pl44p)0~7QiJH|LF9>!NDE4m_8XBX7!eU#oUeZq zmG#1^25@lm5s{`BHHI~?m{Ah*PgfFFoFrACap6}c9btHhKWfG(TFKsj#|mbvS+pJh zMG74M*ERniIX3=}HUB>wwizx+50#abvu$=}`?PcfAuux~q9VjF8X!SnOd*nlfB^&` zK$3zqLnad7f8^y%07GX&D^zILN+>0C9i^+V3djfrE!3LYHnm#SEvuc@T50Pm{jIFu zoX=euu%s`15(WP^r#(-1&a>_2z0cE*`g{%mfTPfcq123-8O-gNCSk@nv+<#MjHwj% z)xP)5>d)5)Z8mmu2jcRRiVW*;lxbzgJ-Fa|8Pu^&1FX2_Ap@Lxqd;6HhoC6)4MU2& z8T!y|85PGQT&BixKR%6I=m^_`B2k0BFpxiCd>(bA3SnnOArk#IHyYUvcaZQe1SB|v|Rhekb|gr zN)Dm8r%fy2MpI!}9~a5>kLEEKg63P>J0%Vib3cVzBAiOSf~%jiBRe56fgmR?>#@ z-CTP}H6NKD1=~lNm={=?~ntjL^VVcCyb-K=`2d~6REYPWsj%XP|$7PL8b-;NYFHb z8QN=n#4ds+-}mzP%bR@kELWbKKxl*|3P%<)=ux!Kt!)ZHS5;dG&dsHi(`YJT#4pD_ zvV4ES`ZfI9DN7cfwM(Iez1`~stCPcb8 zFrY@IBGBbGGD4p+@al-6f~kTF1yrS%ngmSvnq{ynU_O0gp?wnx`ml4$G=vi}C^-Gl zs)k}~pIK_j5Qyn)8Xb%Y4x!&6%^S}!8dyIi02&QAP+(T#bJdi2`H>)GR@o7V5e$|5 z6A55=oyu!x9(L+3$Y&3a(B(b9Qd3k0fvO-^!+jdlAQ~Hc`+%?*@Rj;A^CnSyReKw0 z8x4-uFAhetjNROpHZ? zqnV??7q_K@W)TDS(W6xeJIq-_js(dDh7MRHd{wicK#lp(3|S0%M1+4d?pQ<29s7xc zm-XFZJL8t!-u?qt+HCzQZyE2Z$Z!8cE)QClk@9@u43T^qV&>>^e6oNFFM5%~(?l|2 zwfRXW%fG@xI>=k`sLsOArAHb*1K^hYdV&T&sS9@3GA;VP2P~Sk>9HahCDS8Kh-ECq z`##6jGa?ZA5J|*lUdBPBQb`f0j1iZxheUp>aWvVfrHT>pHQ_r4OyWDew2&;-!-#bd zXgH{-^V4v8TI-lkAnd)*Sp0&h0K^$kNI_ApiK<;tUey!g(b~LNL(in3R`PCcW5lS2 z2Y($Vbmlkvc(MrCvo!^P(1=?F=}_hQZWBhOErh8ImK!sGnqcyLgPda!5?lJCGEz}V zI@>G}YOZAk7jn7rR@2GK39p`xrcp=-wTU{C!1b-$L&9rpkdM4PU&h1}s|K#9Oug{O z!?mpM{hc8_2yEiZL1X!Hyz}Kr;ADNnTQpe zZ_+a+Ux=N$QGN!jBS@jH$Vx$~&dN|0&lQM_Sv^1tDPmi;FPtXYqKUnHB;&-DnHM9X z!s%chW1mvo{yY5PMxVu*C1u1sLheK^L#m7?;rq`KsRdgPCjw*k1mqV{E}mDoNIr5$ z+_9!etBwC@F=JgbTu%hddY_j_7{|s4y zqVqHAz=9A@D1N=5g?{W!(rdO*6evdNsf#RyoIX>D;)52FMQo^rVOsj;UG+dRoD}yP zbtw;Y^m4NJLTxJYiZ89l%?D-dr8cU@1yc_d_AkZ`JQYlcIVwX~IkF|s2Mr7pAe;`4 zT}f4KX%~4<*2%0(4;W09#!24Klq3_t(3ZD6coq>_I#tvNu>$xP==o!2ZRD4C6Ef=) zeDoRMXu+`-E*wa*dhBXpS`XPS@(q|d$Okw(&7{V>$nfqG3rB?pRww039(#%OjpkbS;+8LrS4$H1G;!!jJz1xq0U@oYhuQ$62{|P4c2`h zo~0YsUYr8=J}_8ux9}jhU3sYM-VXI{;a<;X?LOQC-}=N5Rxc=>^$T&g{s8!`APoLr zGuQ2)ILmfyyww|q!e5S8SBIs@EtYLzpn;yZkf=`K{m9 z^+(lNzF_eLFt&YzIcah1N>;FXCsq8V(W2`CZw_32gopMJfxdW+JK*ZdgZ_%B^a9DtM?ihq#D`pK-lribwzoG*XN49h<N`Nk zDkH3X!>{S1fAD9)iPOaTLDpA!poaYg)n@%-{|T@Cv4-seu>hK=INdc!r_ZM4zY4UxlB4r8dAn_xPhxfeBV_O(He zve#7k&CwfWw;NE%wWHtlgWzbSRc2{tBj_ty0930q|H(B;=XH-PShPs(zJ9_>mVA0> z4O&o{-1;f{(MU5aX8X=_^^(5E;BBm@7~WJae#mXatB$3%rXFa1-&M=AG%jt_AZf25 z9Zm0HmZG+vd~aH72QNDcHySAgd*-_N-rl@?^nA+ERctK?gQ@6D!YAEetqx}NAF|PRW;>W!eK5oJXeQmg z=GeV9>E7VdYYc%=fEB+CBGf1L$2;sw`2iK)X_rrE=fIe?j9dvnacuV~uwvjNV_1zs zpiS3UF=*+o@B2SVlID(CUUFA;vH6buR>5d_sybTyd+0I%BRPbZ#Z@k9Y(u|*J48QERSZW?Hk(* z{m5+)nW3tb)HyEm_Ua(QysSL$K~pe3z#_s+NRJ)s&Ic@2`0hsWIOt`AWXEyR)pw32p>VdjAkjpEz=7un+#AyW6Lhq1i=khq9z_GJEk=(uX{5s znR;O}eszI3#KJu(bOY&n6Q=llHD-nZG`FNKf6ObvuN!_bu2}LnN8+~#ezDV&BzZNK zDAPq8ela(U=1O9a&8rN{jOfBzT>9xx0#Lo=hq>fRIoWwRnG6Z5AyFkHvLvfaN%`@O z&v#8Wlo=v;U1olY-bsu{^jF2J?{^ z{Kb$9<{!wsH@_d$Hvsb?3UvxZIWVJyN|^UuRK_$?%pe&qYLJNN8Ij5ex(B%?R?LA! zA4~?}gt*dKmroFDpE>{#q;!DYo4Ya;$q~ZPP|-ierI^@+tNb)@xUrMC3nA=kdJzs= zD?!Q1J*~;zcgxOc8H?HEDeovi&SAARv$^{)z=x@wxePJXYgV#w)Ur5a%d()nuli!3 zow1_3*V?Jt+61JlpRwhJ87eVYh8vW~y;UT^#UfbFY~`7gMLf~=Hf#_0yF*sLW6Q5_ zt^mbae(G`^5^2|^OnqOLkh9{w@8YF#7kFTo%^k|%DzJ*jVY*Dq55Nt(&SfByEk?t) zWmedh$G!?#?nPU?jrPYAKE_4cjWp+wXc8tsO<^94ii-djJP>-xfCMh=;VCCVj$)*c z0eXi4o%sL=2M~}4Rc&8lJ;J;n_B;^W5r!wePYVSIlXp2{QHpXHX47 z0GiXjenM=@0@mo5+I=XDBLN|tW6;YBCy#tFRQtaBJwp}$2ILg!d14#4+=R2%VZhY!Gvb6=&DX(9h%E;)VPnNdfv_{Sz2GBK za2u>67jMcYa<5Tr-mED*jeoXil$Ifcbl&GQ+%Kj=T$-)}8v80~ZmTf2cM zaFjex{;MN0O5p@S+NA*W4$H+5Z^C%aWTVV;S>jLms{qNcXYIFA34hCQG_OA+`dA*% znmu)NQhL0Uy#_?EWNK#^)k{f=T(DtENoIcE?ORRg-4YL^wkVWlOG*&W03f{S-N(n_TeU-2~q`l#pH@2BC zX1fvpLsy{zY!Rqk3Z@6L#MrG8;kytP4VlzY>T3}V*{W~Y4s$HKNa5if2anX8MLC{L z$}?Ni@Smi?AM1Or5+w>w5PJlc2sdXo&hxv8LVFTS9%z38a`M+GZWcj%Bv?X1H$5ut z5zBkDjy6adBapAe)htOi?gLw_)`XC@0dA1W#a7OtOP?m;t93hh1MkF!3u=9t8lOb9 z%eY@U%p32Nnh-^`jM9g)>)^x9?HsraAyrv-loJ)0!=RETBGSZFWiJ&LN^z7w`15Lf zB|$P|4hw=0;XI(_h_OkN+rV3fUU7?nXVYX|SzZ`oi^Wd_GFJf?TLi&TZB1|)iOtw% zZv7o56P%S_lbAfLsYvbDUsURp3Q%ybIp1T;QOiWiR*9tP#$$m(*-94fo4IYd4z*jC zE$AM&DZ{wnGOnPw3W_DJebZD@uH55Si*P7#YEVnL7qbK0hI!mGnR@%B2?{9(QnXl? zct!PCL}y(U_NCSp(%PE($B*qgKTuWDI?L7X>L1bVB903dRDBwoit^L_mj`c) z!G9Mx^I-mI`g_$=DS*wq)I)U9Kg;gBH-2jhz5s*pW{3b?8gQ0Hcuk@RP9snp+AKlp zECVu#VV;LZ6{v{!(W(dt)rEpJfvHBcEs?Gcxf<|)B4HcEZ9>RLNF5Y(pu$H??}OTL zb`i4oX&1o!5!L(EjevtRqR|{#t&EuA5Z8>-)`NgvUk6q`DAPYEu+e zH>6Y-1gkXp$Sf#0#~`X=+mv25ftMmB#gpU9s5|F$YsqJvh!7Gn_TH31Ky|?5*OO z@T>5{Id2ZLd>Q_zxtDmRa*|~U3buy*oX*WAzqgQ3lh-4oEvK67fWbl1%LL8UQ%8~u zAotN9+IT}qIc=ZHRje$XTl^7aOnNwk(-1n|Aq!=`0=?OH$j0cr_c3<#UQ_0@J3J)H z<*)jFyV;5vAFrxsBx$}>qIyu7D1Mj2KnK4INYLg@+6}c^S>8F|hDjBl);Mi#3du2} zqM-epNI)&Q+_c>R|Jj78xC%MJRgiyn?JgfUue2PCDwgy`GB>6qeAG%6!ghDi6$mZq z1zsOZ*d8#dAF|wnL$w2U9Ehz4R&(i>ssd~gq>IgsM*7CHs3C`M*MD`WDuZ5s zWO)dyL$W(4_P|z$dbbbuKzEC9ca(c5?4#lnG8Ym50Qx}wCEyd3A3b+({lIRB>W`jz zh)*Q%LpeF3eyH<6>UokRaa{B>yEsN)hzje@X7P0?Eq;aF~j7fTkUK7lS zg2JI5WNFBR$)k;IcO0zi$mifJ}+u zzED9xNndU=A?nkU5fl+LxajxQ&mpGZ!8nKnUW|j4%q<++APEIh$;Ea|4Tu|_Sr7gu zPU)pL27NIBK3kni*|8W^^$3ftm297(ux@>*Fz=HglaYt+ZE6zXLHhy3i#ATWgu%3` z@g9NB3)At{y>8o)9;XX3vVH1ph%tf}qGSU3S`^lyRTYASts{CioR7tB z?z2*2+{GIxi>AesA7ZD%p#ty^Sdc*YNG5!|TNkI^=k|1BjfvnPiCZ{wecw*9{LKVs&SV@8?A0j(dvO$zG z=qhExp_mEOPE87lsv=Y}45}a+E56#mRR~lYiE2GfVW2Gp%8pM8 zl&ftSgiRN8%d5gbK?rmWF%{*quRa{g?xHg2U#0vhLQSfCJ!X%JSt@E}7@UodS(3Fh z1{0bxO&S-*%-pIlO5zOCCa`rh4qdo(Y18aMn>Q_;c;e=+Yk#Q|r2zO83@`oPO!~Tv zI)NmqstP0^Q?$xs9wkZAW9nu}QdI`UOyChIRvNX_K`2wa8YQc7>eHcRDHm!w&2b`buV@9jog8-CjgZ-0WzkfF)COGE~FsEDGl4S;gd3lDV(PW zoI+01=4kRk#_ilA7Nl>8(6E7E7kKJc*iJ{LXwCJU zAYCHv*#CBlGDJriDXa#oZU9(LiaAiFCvwn{E7}C=;PR1fA*abH#e_nf;PTuPrF;OOQ^YnIA9h8-NxjPq9u4PhCJ}0?z zNjhqR>kO_Der?01-v&;#3DV7MgGXCidO*g%d+3qt^rEv-mSi2+7FpBd+V1;Y7_YhD zr;9mysNDj|c3_85z9tOcl3FV6ly1w{Jp;7NuXCLo44cOpIv`4(P;2>eO(%2if*cj( zkld&8u>P5hnE`9#BW!+FQknp3)0-r>Gbk@f9rWfHd;?&LQ=5WU)9|G%qW{%63p@~_)eWd)Uwz1fs389^uj z1Z6PIl#Bu7D=H8qf+W#Ef&y|N09B7nn2974k{MY-z#4tas#aPXaX_uQR)`u+UBJ<{ zwRT-}t4g;ex^1;it5&)?_2;aYot-`z5++Q(?}PDm$9<3Y?Cal%ZO7xO=M#^lh{@1d z5pL(C1g0}P+#APbUQ~_ixM;|QzJB|xh}eZ69{&EmAQ;cd@ZAs(@8E!&$7fA2p6i0~ zBQLo3uE^#Cke+XrTHNy`#CL*v?3Bje^9}|5JHc-_#?MCoGUr9k`T3g1?=vzwucX}L zO5XE@Iqy3syxh|xEZki83HqZnI_g55=WA1N?%}WJ&kHu5-_+2Z#~Uv^{rx==ynloK z6WheEMj`(uy_f6#4e2N2(pEmsQxm~eXVyw=5ZX#OF)m-N`d@c2pC1Q#c@C84XN$(! z_ue>xc5;Mhm^UEbpIZZO0qA$5t-+h#v;cmzxan#=lJUg?RtT)Fs>aH?j=EAaVO?Qc zU142k>QyYO**YnWsW>nq!P+iTgh;TVLRQz6pkXM%%qarqvQQ&hEqDEXvkvd?sHFFL z+>tTAFOQ`F0&h_Ulo(nx6Y9D;I!nMG(}S0Q0>YvBxU>;;RrBA z4|cTL##w`u$TexBMpcDPuLif3r%&J>#{Pjd(vg+ohOp!6gEexCu?mh@G|?=zu)=t7 zTf8|2oR4{gSiS7`8sMxL|8;4S~|mc zxiK%~kb#Sy5mL(Wv~0vFID|TAk-;D;{iee7X#LgJeV&OAMU4-ji)JA4Q3o*>|So72w%H}E#&vDiV^#VN@irF#)af#?> zQ34P9%T=t_;|0ww=F$vaQgG|Nk_Vmn-sFUL!fbNh%{8=W0QO5U`t4eD%UMhz3yYnB z8xD&BQE6z`hCi?+PUpmtSh7fmNH~WY0s`g??W&0m-uT9CE#Zt@#<__CEzH}o9Btu1 zxLPn4%|#KIv`tO*+-TP~Vt!gWI=o!k8$pU2b_Bn*!f=pciG1yp0SxBe3EU9=01)Q+ zGGu{PmN(x#0ETnmn5sEdM-`x{Wkg=892ilOlPWNkcW5Xwu6LBrE$CuMg2Bsj5EYb|KkpD;rtN2^GFvb6fxsm!HBl);I=}NZ?3S+QIPbIj!08zqBDL#GF;`zy<p-0eh@eo9f|AZ55gEmhzHOOl# zxD88ys7{w5&t9M!4JQ0`A6_gxSi!Yj{;LYIDlSOP)!5IPaqsA;yL6$joECeUS5dWm zm@M@oDRpq1NNo-+TMRQvn8V6Rk-vn8n3p>0-1wkFl%H%tscLwqnNhyLG*9?xls5#4 zG1u`HwjJgOx~nxI#Ktq`0hf4>vLkGnm*hR}6i&h?o}|gRYEVN;u3-|`jzk2Ajwmd5xhS z_)>gaw8D~?b-|(~%v>RAlu__k1;b2<*bVxcY#!oW8;(m?l^?}a_t90=d{5R=mnPLb zt&T)0Ki&}-Wmm$pBr|1J9q4c6gaQ}-JQYmo8U_&kh$ZL!Qx?dn=HHvICwQsVbee7! z7$NjgyQ~P4tHOj3hcF(x`k?(#S{DdCEo#F1Yn>X+lNwZOH%RMTz$*ZOj{6!JFzUI) zI~>UTA6m|NTnzdEU%HU?cbbtyxOrWId8nx9Hg%?n0xsn zX|lZ7G0^<8N%wpOXkTR~SGq9|(A0uSws}>h+`j-IMyXt}Qn_NKa>YvJij_+h%a$z5 z2OIAi&J!D8H5~)svEhY9@DdsIGr*{D6b5b`?b1PxSJ*HNLD*>|!)YRi*hxsAl{*A= z{Z#%_jXQT1tqpH0wQ6Q9A1@$s-m*DPDCGdQOdK-<$$gse$-IefeUYnG77LOji@TC> zBAeVvi(siA(5BPKrp#|cDYN?z_vBiK1(EV?hs~M~l}s(v8|S*Hf~Cbct(2WO^M@>VFPZ4J$I3RYr!6rH-F87KMfO{x8nnIk>iX%Nh+& zY}>YN+qP{RC$??d$%$<{Ik9a!FZbT=@9Wp^)vfB@Rr`;cm>9lYhi^N#xSzca>3)emrIj!s-Z| zo(*ZDTgU-EXaY5q1EVDHeSXD7_N6y!?pgzAm`4*)jQ;_WN(CW0PS+W`;f8R@O>pOC ze1b&D5nQtzG|v|{?VAP)pR^QIC6CvDHeRn=_9H~vT_KPO(i1}zpW)9o6QiH=XPkR7 zAjK4?SMZA01cqm76Y##yE8Bp~uY^F>KNHdr*I5mCO;y}$j>P zW@<5wTI__YH}G{FtvQ1;)A7g`@)K9e`n9aoTuh)7q=Y&^MN$UKlxdIDNQ(ExvmkC3lIo}eLh zP!f7@PwM~yN|!)aN;~IQF(}~g(vyq^WOCm18wwSw+3W}0BQ4yefbw#HNUO4jL~TK$ z`yyDfYjV1Cw(T9%^7?4A&5U^W)_*|G1#!2CY}j#e?X#N<06lwZM@_e(M7k;ICS`@? zvEKxpqGaVxmW8k5(7RNJPHZXuLeNQ!n~4(ULdo`;nK|+@A-!rlYV!uxjJOCMH)7?C zhIS0@cLiH7e{PA98?j9-bYW0Cm!#XgT zglm~+twNz~izy9ND^u7i@v^|uOsyQm1Nd{+kvJ1=5*zqtcN_FtGh&))kjf(tm&p7i zz4LVF(xEkSJ{mGu86D%tQ7=nvK*2vNgtYQmw6&(&GJs4noxywF3XYOXR>j9=oGi#Z zcr6tV5H5{!3l3Fp2`MK;jqR5hjVZsG&hx&JhF?%7UE5(?90g{J;M&c_9ZA{2nWpuk zlK?Jqov0Em`V7-V35`2(@4bj9x)A9*F|39eSa(v?0Xp#6hH*MzpgR_x^x}NsC*#I$ z7!dZzVDuhrH!3ml&w%$I7m;?7wb|=g_H!j<*w|7o%az(K0RC1_^mE6rIOwLKg4$fu zIoR=_P2SD*&aLgq4e-1BBzk)X`bfM!bQ3?uwqAxJm=!9`pQA~RsX0Dcm-wC-%l`gn zl$HkbPHFy++OmZF-*tokt7M@6qPQehHF0z{asN*PXBj6f5qKY(>ZX<^g{Vv7mOfda zU&dq8h@tR?6hI?*d3mFNVCg{%nrjKHB$tYnDq(aVa9;o%fUv=d=oR?(MG>(;SKivK zz+|vNIdhtbq8!2n$}C(9O!se(=T}RZk(|5li5rw~9e4YXgx)!QU2eN89NJ`rf0L->qWR-btsMj!= zu#a(4q(QGCS?*T2r9>6Oq)n?a+rqDUC^bO}*$+>Vp5GJq*+FFb%A124LUNz-0aPok+dz)q@sz*4oF5TbUQ5#a)pdfOfX#0p;O zH69znW-l_Z5LVebPFL}rugoqz)?>M9;$w4<$p&FiZb%pzOd&nm1GgA>gL0i6;cmSJp6sM$AK1G_JaLZV*SFu1jwg9zS!hb_L1pn?6gUkB2& zgkL=2rQW6O+Q9jPBjDD5@&@|F-AJOAxpxNQ$W_1Z7;{l+nY*h<-5B6|MKg7UFXoQJ z=DT1yH6vp}Fo=uZiA{Y5>0Y71f;;&)4$JHvT+tBvJH+paC0oI0ayQns<%d!HyaXpR z-l6i_ZfCu~r);)6zt5-M_2ju~D9R>Jt)%DKMrZ%1mt5CLZWBrI-5d|ZCYXi%s7KhG zCTR!jaYrChBzC2z_ApvNIU4TgN%zM7?2X-{%{N7v;g){5)4o6s3G@CAKd`}WjaJtx zL@x~R6%6wo27D_PD*dr_AgvVN;f-9-nMd8oZP{)wxoo>CN&<_2%a-`;EBf*VC}+rB zOs^?Q`Yif76QuM%K6Fpn6>$T3VPc3Bg4c`C;0_q&`v)m?#l^1%|C0pZ3Hk3}i06Mp zO8vvS=07w1vZHk@fdt@#DnHj-A+Heb;*OaK3BbT11NVNDp_^rX8n}{PL`A6G_W`?; zJD}R>v*^eO+%J7PbOELrW#CK1Am)BlNo~X}s1fNg$X?RYu<@)3hK;rjn(> z`|4=by{WY$FV|RPJ#LiA)3(B|h?~<u$w$Hl<^H+(YZml;qsRwqh^dc$4N!Qp-)ixZPiunr&wUt`?}4kDMBa`J(kOTDyWz~MP(AI5wG6HX z=`D57=mY1K8W`k3ouF1#uQH_%;*MkiKF9Em0ptFwe>>Z28nVpIC_fu#Eh>v{A&xUj zpD@Fc#??(XATwjZYN8~Rj~?W*&f!`iHed5AT6Bl)G6V@{v*n!8e3YEK-lX!Zjpg*k z^+89zaU#G?vD5?wV`{j}0|w%Bh501sTngrS3%f}?2Bh#^AQ~Wr4$xlu*pZ0sMyJP? zuPW(TXbk)`LhCuZ3X)}-|s+tV0>=9kI{m%U)>u}vW^PMa`omwe@dbz{#CMi3*Xa;gFe>HYp| zFyI`kNFJzZjew*=yjwBa4XaOdNt7g|!s|p*7gaFFI?}iF+1Razq2CEgi=CvCdREbk zdu6KRd{5KKGY=PB9z)`k(F_Uf=cLhzO4}hLTut{ckMs2VYNI_J>-5$@1tcTtt-jW92yLcY^mS6#I-4D+vmrnbJN*@5 z1UdJagm9iD7VC%2y(ri0pH1v~p3sPHw-;&Ea^-Lj(rx<3WnHQYut6{wEg#*=GewTj z&07fmzM4niid|c|q=MLnb1_Eid5iFC%!2Q@Ot2;kctt03^=pIm7_MW-li5cry|y_7 zJ$N2J>l@xKUC|T3BBLY-nKg1J&1hjOOi(5)Owwdt(BGnla2mF8Pe^~AG5MON^ECb{ zfm69f1U0)uZqCcbPioS|jmOjbDgdxaOwTSr7(%zBi)l*h3u_Ogr41If#$@jOG96?t zvB*Xd+UM~GAdePWOd1w|EOtnPXqb+}1v6O~txQ<1h39i?k*Qahq%>#Joef#0Uti*I znB!PqdL^24aag9~q;qlkLcec{$ev)ni&xAVAugrL?_{z@p%RZ!38qJ=Ju4zvs+ko8 z%cfDv&d?|_iMP7G^9&n{B(QacVECm$yiRjCiI0r;>A#tZ{+2P5;S=zH!6@fg1l7<-O^2QcmLO5YF@7%DZ(6KSJ93%Yr5Gsb7LvMZeqMSTtOkT3F8WmYCPMSbgLLQZKE0~n% zk|UusI-he}URO++JSSRlkp zsa*p*P51z;pK^qb?sIk0hR`jEXg6nUhS3st;_k7Y9YNVti>xhOVIiNIjP&tlalp~v z%pErmn6DS=27s=K>LImGu=H$+BIo%!Nw{Y<_0p0IC1(!(9F4DzfSve(hc13foT6@yeQIzT1rk#s7MPjV(mQM$L`8(TpDe9y@YB_xL z*f#G^*HU30i)1I!`O~j=hJj4060hMB$;i$%5Y6bLI=;2o0Tayu)@l-{j%kL_ux)<+ zThe-=MF_wyJN;w654tiRSGi9r%;?Qn^UhlH$R7qeS6--j$-F@7saC#f7gfc)jkBs3 zXcse^vmbJEm~iOV)$BV1PVUz|Hq?60KR2{=%aPybe<~2uzYTs-{~uPNpR8SDItg26 z6GvAAYbPZWXJRE6!~gSJ;^(@7vz_CAmZeQO?0@9HbaX&h0b8%5NG+kFTsBBykn5?C z)99&OpvDzb%|=YqvQ02|Fr8mO2ja~QrgkreW~4RIVX|0Ady|J3N3$%0DItC%;(bC@ z9ZydK1;UMII45R%O?MsdKXV;#aow-y@_j+)L8Wst8{tP0p+oO8hZK2=N}3%Su}2|9 zQKCZ?qVBWAe)&IFzOJGbJ#tvQRCsrylDY^=)=rFgfR51@pex%GM3JWFVI)G9AWKuZ z{}vc)Z=sP6-Bq4%aLUkKY@86B&t5K7UatxjR+$(E}GcPuD?=B!h z#fdywCT^fQ#N@6zBvPc(8O{Ov6CXY+H@&VQMolHRr04*#NvV006*1v1HAJ|j>Hvg8 zxfNd#!x55VW1grwK1CaQED{j2@?xoqd>CWK-i`BGpy3!PGT}NnudIMb@S8>oh3CX1 z?e!aL9R9D4(wdi7jd@6C1 zE=~UDURfaj_80eQK|UlbSB#CZwpc~_UAg$Vhnn@uVNun@du%l=)Vg>(9$iAc4KWX* zgvjaTMG;j|`qm?~91#F59ezUWd}h`@`sZmNAR&T>%Ge6`r`9c@MyK$6ZIKhE+Fm%9 z{%yz3?H~`x6+ZemV4utb31R?D&{e)E@Hk!BCjTZ3^N0{1#eD#IKhu35`C>Ykd28?% z`~5Hy#HlA-G@HG1X+9qgg%(xPd2f5@Ej!OXcp`f=C+}}yZ`4o^OtKej(N~kK<4AEQ zoNGtG)MI!eujCsf%clIzNP$15=?GRtqJSCi+9gt?xO?CbQQ|nA;i7unNu7@;&x53x z#0PnyUOW!@n}2M`F1l&LLuun^XokkMKfn>Uk`5)CE5XFufPd| z)`Y{f!tMw)-65(sM6mP(!2IAazX5bUgt89t2*&vOn7@%heUnf023UM?R$kF`F*L`O zKN*8=Fqms!A0WbH6WAs4YMHNUan>~xv3~!Mp`X#Sa)s0uJO*~|;K8FHz}t3@rJ}TV znOv57*JLJl)q7wX#8z#Y#u!+vw}U>y$JcvfV2U#1A!N38BG!cBJ9>hXLcCG_enqmoCU)MS5SRnT3)0&|4mUkNb9ONBXWc;9rk@ta@85=<{ZG&D z|3uCou#|JOF!{kxV|lxu#H@b-<)NCC9FhX^m#r2jBQi3IcaMOSfasuG{-HuNF-Q~( zacgGFisO`XNxCdcS@?HvHEk5uAJRQh9|tIx`9LVi%sBJR$t*E_32B7cG+W#^r!KmruNtoYPM$PksL9c`@XeZiN3XEDBRpU=9Aodigf z)Pch8T}UB!;k14U`lP~zlc%1zXEOu!38%_l94`f`vlb$3gY^DM zs};1!4O-0hvHi#PtpksQJs&6Nd04BPE_re7MavRWFOX$v+4j}Z(9 z)M1DN2fq;S9GBraYBDoS?y^#7%}j0jWI~T^)%%_Ipw9wl{PS&LRURO^r=Z&7Tw^f@ zhGdq5@;g%4i_7EuT0O#u9?>q&@Lb4I?1CaW#t*<4Dkm0)~X>!h(l8bnay z)`iEM$Y^loK?CQykxvVpo8_HRbv{`KTBJ45+c11{4NRz99lLz@(-Vx&H9}iV9z_kW zzebMNllEA^3vX@K6e%(L^M|ujo-wVV<0%#no{I8QC9^PJ5=EEIHyqu9K=!|-De zLWDO1mW44y1O*ra8KS7t^wVta&fKjrr+uC%#RWoxof+zRoK`@dpu9= zqWdU2^M7gf9(>_bc z*l#==Z>irbVb0|DxQEyS@u0MG%oD@8pagh~v9}&DJrQbG7*@VntK?R<$5fv+s#vW) zC0r7}QKsuD9>H%We%Aj1_Ys`X3fdNe(5Gz2TF>DTd#7CVK-CgmN7Nvc({oQjPegT_ zO!jVlhoFzk+mQfb79}1jw?}&DN~EncS3P9gDDkPKO zIbpP`54zzlsQq*?iG^1D^eG;v8IEnYZm+BC`}^xuI{-=d0;1qRSQ_==`YHpF(1^g0 z5lmGUbj%1$Nof61Wo)rllT5Fi8}yPVlj`*{90#R~oV2~sKShNG(E_!1jSFb=wved= zKMs_8t~#x_L))sZ=&Mp8^$pJ4xm>>4>pBb{@1L=kdU$`n>5EutM(+Nghd91+{?<&9 z>7!R@#;)JKWDa@{VY9xIRxOrj${Mx6<5KCdiEpT`aMt=oW@2NI*07MTDH{5I=~75y zEcS9$PS9Rr!vg9CeHvC$zrLR0%8D+k)n6O*CT+MmeVB-78fHIo22N%!=-wi!T)ZL> za!92Dkr*!DW6hE6wusXCs_8z@OImO)>^vIVX5dt6g3SyYe2P?%CFLCUIxlLEH!cy6 znUECzuwuNzGUP>G&GPRf}&3( z{+QHbd2Bwb*M1jh+#}5~QZ<{pj$g<(SUjf`{LFB|B>VtNy5TppG(THFekl=6{>%kuY)$@2a+J1C<$Rrw9{<7)8Z((->F`TrgQ`9D>X{l9vF|7azZ zt?aNwka>{!SY5N5SZpNSlTvsuSZ0eK0<=PjWmzdoYH+N{3dG6Rs=&I8ylJfHic~*gy&zeL%F){4?cIL@$+ck_fx3LD`x*bTZ~n`gpK zJRv=|onbnx7^==)JKy2h@`PkkM@jQC)OjtZ;EJjaF4a6^)&8@^YVBoWC)(GHyd@&h z=S86{md;>Tbb}pJWS=xO!JgAk!D_Z@ys9iOV-P*{UIwY{VMzdv?dcq{RIN2%B)bA~ zlv|w~P$9nZ%D}mBPoo88EPG~N(~e7%hm@^TeqyzxSgf#JrHqw1G*0?T)f{c8v2&Iv z_r_-r6>FpJ=G7OhScb%-Q9NPKEX9ba%P)av@@*&4T@mafpAR4!|jHkL(k}Zup?$ z1V^wq+4au;#6@a*MOg3^VIJ}|7aI1NKEch;UCQf!rv$($^#m#j+7Kp4GK(Fv50miD zfjMUm%N_s@yf4y;%-v$iFARdK6dot%RwO4(q?{9Z=qvg$A`tIR@6G`r9Srs64^%7f zXiWZ!CJjqQ7bVV%K+pMC@7@x?&5{_+1pR7FoVHZVQ39H*HhS!E(tkqajILIe5$#IG z3jO}KPudt@ej^bCNoZm;1BA)1pu5k>QzG_W@3d48FZ7kQP%a+)WE=@gOZLB5iAjB5K9 z+>!JaFuWV(=3WB|?u(w}=RDTnsXPOhndUt@w|Xo&PTXxAp8n}o4|s6tI`dO5tAG6J z|1Wm@_j36^<)Z$3x%^Mwzc^Y3vY#G4Sns1!wGX#1*eY~Sb;BGKZLc3`(Ak{If>4Ia zodpfIS123-VS_6+eYbDlC-(Rf7JrzWA08hW9ImAt*$#3FNMW8_r-)jnGbj5%1TqS# zu*oHO%vJlC6^0&JeT|aHBZbmTv4y(YL3x}rS82HApuHW@FLM-A_O#R;6N+EIi6x{m zIc2*3{)8>2i5cTEmQ1y|cMngJ`8Eobci}0}4afQOI`8K_LSz#F;8 zfAId8|CaavU!m;3^t%6fs#wynQr1>O*-FJQ)o0{)PXcJR5NGaU&x$$66%W-l~ z%PCQc{s@ZZ6W@JMB&MC_oeraCFrb$G(5&s5gzGfFqH|C%@^{YyjYmL^@r**$=eL5A z^$RIh_fQBEEvMA6wzBN;U;91@xyECWC)*4dChOM05WB`*3|4K^fkx;ll#y^hgzo{< z84lSG7gyJ%TfT`453;VjxKDj6w^TtGoOtuu%9zTpxT8n0;bFqvG&gA$!OTtp8paZg zIf+`-=h!nq85l1j1Dc)7g%43;&F%TTxax_Oh`G`?WXg?|rG>5atrgDID=Vw#=4V*_ zsTEHzrTMkHG}NV~IbIsf1)|;0%byGuFXVBn5K|!-ET1!T?Frb=qkbzFx$Lg6RHPS! zM59dH}*_QesR8-YDdQPiRg=*ZGF?QvQ4=%)AcqppqM3qyE$Im_jVDmDu0jL#W# zQ{$yz1uJm}P)tye#~pz=shWLZ{uq2dZm1F$R{@;euAXDmQ6rH848)<@a96zUGXGf4 zU%9W&jx_P|l~abc^8 zA%L=}X!Yk=nS-ojt@_l72)SqCFbHZUHAmgE5}XKHQX8|Tw+daV(-ZQDD#L-HPzvZ| zn=q(N&F)o(uo}2el{7_f`kqKPZ!%2kQ7WgzL~qVS-T6~HoHJIuIKBrI%bqAYZX^By zRJ5OF750Cn@OKh;ceegI?aE2sSV9UH`_#;w_6+M3=3i!zwq28iYd>XO+bg-PV7D|xn6)nUUM7(ye7qSVR(hHU6XrBSkF*RN+D<8lAX*fXh#S%-=u?zPt zfIBtu&LZ(juy~2jgq$6soyl64p96zcE}MTQEhLa{ z6B!O#B>vEUxhtH%=0Q~bhouEsGc$$H_M~u&mBq9U$t3z&e)5CO~AaT%E` z$1rXs;`=^MKS_RwY&{RVpu{gfXM>TC7CaCqtciP4yaexi!|pWWW!ui0gVX}%jjZm3 z2L%$2QJK-lgCfTi`LLUZh~re8~XcXtz+dVi&ynYM9u4^J~i_+0)$$L1i3$Qi66{IWrO|Fm`pOskM!yu*8 z&vQ$vgeX9+he}{)v$bz1yH)W)(fApVCd+ix8y!%l1VxZz?DsTG6%?XCY8>4-lf?4v z0xiuG3Ok|h2xJN##FKEt=ZO?Ni6vu&PZ7v5mI7GNN;&I?3ou<|@SlM|6EiOX8<-H2 ze$#DD^tDdG07VJDpTPEMj|{|(`i5JZCA#w&?>0;6CdClIuWZ@{U)I1zt;MZMxlj%|~@vH>Ue*V4cIy_RnXN<@XArP$>k2FH~M2T(!pK>r4R zs>dg<_Q}D{P906)wuF5hptlO6n7JJWJMu7Ijeiu zQKa*Fww3>lz3$cOt8$VHKIKBF(uM;MTiky`{2uBN(>L(DMbNM;j{so< z1v?ssONt${15^f7%m~T+Lmf(c0_z1-37-S_z-+-?C~*rt=NN`&3@ZS-D;{z{I|mI7HA5-j=n?HtAxVMP33E#wCsej?bq}I<2s7tjQp00oPdgP#+})<4uY5iM%K(c zV>{5R8qJVdGk>bgAN*)WXU?8<^T}JRc(=FgJ>3HmZhPf4TbN5Un*3}sA*{_>_y#F# zQ(h#+Av-ll3ObFQL#gA#NW_x5U!0FBRB4h450c}RsPP{%fqtMHZ6C-e8HSK@2@Ad% z7cIsPwVH#~aeKq3b?n(hHwcl*h`5#K!axv&U>D^aM1_OYkUfLbdb`%XHsMK#7S`cW z%RmU#A}=Dl0GT9;l1GC!(8#=`_~8bpy^v0M14>*nB8_V@QodFW^+J{|;MI+o*n&b? zJ#r@;ga_D%Py1A+2Jg>{Vbtc$-_NVBVCv5!O;2*u^*sR2l<(ImPusv}t1#I^xpnt5 zH#d4I57aSI)D8i~?0@N4LKE^oaIn4sMZTN(DN^JkNRqryQQx`Ahwk$_)dX*i`0QXf zl7uOnd+D84d-C`AEI7x6RUD=&DM6hoB%x^{1jq(|9Q>k3e!@q}4kp7#yiB;eW1kV* z*jJJqB@+&lw1uW`7aeUSQyMJ=I3T-ndGQat1=*bwOP?IZTjZ9y`C}5BmbopAlM}^d z-K9yiqoZgNB1yWcL|q9@piHQ=#>%Zry^G@`l5v#tFN(C1O)Jzi4-JqPB;WAexRb_> z{sxs?3}CN`ofHCTa@pOBxC+TqX_w2PtofRew$0C0dE$DGl9BffAH&zxrh)5ULB_fwIIo_goO`Zgx9PU$E4=T|J1hj4`F24wiX~~ACgP0s z0*TP!@7Ig%p6@poxxR}S^Q#aGjeJv0hy|Wt&6D5sK4tP$KFB5Sd+#F!bHa_7CDLgP zQJjcOjkoJ##qUy3W9dUL9}mz(Df)|?Hkc$@OczZlbWWl&9!!OQ+b!rZWinK0OHi68 zIb%&G1p&E?K&Nzj5GNcOdu^)}tNRAY3*}Y+&;yS{7MiY4 zI!Q4x@`Fd8hSY$lvavrvtIo-0ozrD<76Nljip8j-UPJ7T@L?`LezIZsx9$;0?wkZCWf*3l$pl{C zM$S=aebLZkYILZAu`Zv&2=$L5chB&NXHkzsZidr_uDTYL!{9{%+BYR^^b=8}V5Z|F z`I(Mvt1G^^*3c)vjr%gAt9OstQz`gR&<$7dG4vFz767gLbBBR(-?|8$don=yWnTe0 z;~nDVXWg$xZab?e=UT>6ev7R}te#e1>NJ6Kfv$g zJW;$nZ4VShlgBV|v+jrigZ6WbYzM*3&QS&2q6A;B$dP*#%k2?XM&+Iz??eTJT6Jm8 zc!>Ky+V+f6;Y3|Y_E?BAu`1+9JI9F{ZC~|%AI~YI;Q$cL1CA)sA)$lS26ie~z)k2ng)C}V+biaSsr zt|xqp*=~Q0oR3whMU+hvRGd{(y(YKJkGU@!$PeOTy1dJHuMmGnP``kXQ|K;;4TK#e zM>_n2QxebgA4L{zB2mD_&-XHQv^EcIRN~~JP^|#CO9y$Q*d9eLUQwwxLMjR>Ih!_Q z&yXB;xYF^H24~GZIz^$`0O!wkR1g`^~ppB92u`;nb$&!oU=|y zCYJtgMZAZu*o%@&`&_WMBj`F+XUdQyWDX0_M4k|u103}Q3Hk}Y3?1q&;Y+_f*fMK!Zpl}s0PQ*An47W9Ww+aVUEXA zBc?$|@w`p5a#zx!O)#AUQxqHK47Ztf;H{T7yL`o9@kCw+$B6l=&S7S^L(3gbbZyq> z6*w3ej$-G#KITgi=5v!4aFbae5$ptwN~vbuA*yDf3D_Npi2x6|ldlH&rRW#_2@nWQ zNF_iYa3?8!M!rU9GP-ISFuc36*a#YnGl&l7Rz6k@y;HEyqqeV0*$sA=S6JOajp|FL zP_P~0E>(YG%wHS@f-XEjY?w!tHyXyv4onjq6q8E_<6$p3^#-BKN82pFc|>r%;#Z*{ zu1*Ls^IiB|S-AceU5Gsz};LrYz&;undr<+>}*V&9X;qw{&Ubl_x~YsWbJ;2oJv3cHW6_*GO>5I zu(SOaH(afxWrd^w|0SE~EVH`SwB%X&Tu}~3TTEvdfiD4Bd1`w?3V2J9a}hI^GR0v) zC-SNGRsas!{Z=^m*Sx+=L`2VYdh+!s(||UYx91%|AE}vfdZ#MD2_D74iptrlcZePLQfPUIStgX@?JsTmrL2eQ!h_`{R9dbixWR! z$hB;Aj8rJ1!x6pStgYIoBw2d;iOq}wCp5e_qOi;QM5b7-`j}TnX_{JpO;TYa%s2u5 z_tP3Du111@QG+*6y1l@%aLGQ6m9VFv#Yca^WNg2GQA1NfuO&`K=G3EJQ5lpnclHqP zWsnEU6449S`yD@KtKlAH&8?cPX1p@d1kP1rE@rE(Ar6~#TC2rQ3jeWRD%mV|N&>9F zGVMA~vhhNBj1uGq#Sr5+yP(rEoOuItRMp?G{#4|PlQh7M2bPgb*iPNj{VNx(senu9 zj3?WPTk91JcA)2&+%dbdwr8nrFU!g#QDi7|uvgEv84y*gC((B@kWikAPn&t~l{2|D zzL>h4>+`1`>1emY!9N3~y=KNcAm@xf$!Ir`Xy{PXat+6Tg&^n2>$LXY_Ws&)n`=g-*(6qO*VF65wwH0ry2){)cGl4z23O7i9Q8{+4BD;-SHukwl&^K4 z+y(hzz0|D|t?%$A-|-b1^^0823n5z1PKw@|`H9rWo8HIUHfpDJ>D;$b_pVypx5G+p z>&v$G2WIWTp2|l^wqF7P`|r&`zGYdIGz$ zZJvYDl!BVPkxM-LQ16c#7EGddZ;+NYDs;?hr`Qgj_fD6bomF&$#ppJocg%Cqu094k zV&~Rrtj8Ch0bRE|TJ#&(l~byddr?;KRYC#2YT_LO$(SeCv7rMv+=uyj>A716-xhXM zf2J!~5pM)N`W>jK<>tr7r_jzVn6r68Wfb+?a`=FGV;pSU*wbD45JoN3+SZs=E1~xg znW{G4ZS!87@Q|?K=5$JOD_q4sl$e^&E8wek^TFfVbM zm*Gy}?z&j)CKh;b(G6+BDyv-dsO6#KSwb0DmJ3#6Y*X&{-^Y_+7+v1DXb0Veeg&e& zwk`Q(GkhC#NQBzD@Z9~@C{s^>*{wtfSJ zGQq`H@g*}I)AlwTbw`;-ixF*2Ebj8YWjuuh9uOhm*=bhs+OU)4Pu7Ev>{J#-D+;!b zJV`8?LBH4JlTSd1jhNRmoJBkT5;aCF-i#+;r>!%&o#hhZrOStV{$&9gg%H3s{Bm;X>vcb3YUd-nyXM~}J1!HD>z=zQ!^ zkPlx?@MH@yF4?7PmG@bg$=npWXpCt_2?Vu^s1(jF{1lxJ`GU&%NDXo|0kwREM|JhKh zZ!6~}sr2i7fhZI0j}xqS3nB{StWCE(`~0DcQfJ84+yU>5m==h5Xuf`&vpGy`n}t*V z*~eq9bB$kUccTe|(_j?xOyX1wwX(O&aNE6zN0fizO$J z^ABu0bBhR}z9%`aNs$B+rCEdnVArg!jf`@{Yev;g=hI#vEmSuakTG94R5-CY{5RQz< zT1*Ph<%Rq8g({1M;ki6JqN5jKM`z&~?fw}bZcB`Xn-}+%eQQH^w{JkCUnPwd>glk3 z8SivSz~7BjnoOq~9Y$=+uv$Zw+Pw^?mWWLU(&*z939qcNj5iRb+QZaqQ#3Y>l4$Eh z+5XG8Nn#=2+7yWkpFZ=^{mrBOEX}mCQ7QMBKnZVwK8KCU9fCGJc@lBMy6JNgoz?u=NTW^rBb`euUI8PLajN8oLo3 z)VaJJ1a3=&N|d=#9xL~)Jv9uY;;`mPbDS9U!Qu$@SRK^4qA=5X0R$SuLPAyrHdAy9 zCJY_xJ|3WIjofhLjfi#i;%cCwTR9yo@&n#UGJvO|%2sg70vT%+d%TWK2})tE_pQ&5 zH+(dui=+kZcghu0``X@`swn03t7r71wfvpmt*!#RH>jun(^^hM39i}@sjYow)(!V1 z(mb!_e8=+L%umm8EZ{2IBU?q2gg zB&M_ZL;W?G=n0y&uzxjn!b`h*g->@8-J~GwwVKqFT&*$alUh=|EKYoY713aqI{4HP zzE-3lRAFY-V|~QV4nQ5WK}Pp+mq-U==#boGR&x8kv5U(&d4rSVT_>Ro=utQpS(f1j zp=e5%E#z&0(YM^aY=h&~!6gw(^H*KyFz%(>;r2;}(Ux{>ACHA7;kdtO%FdKX!mHNv z;p_?YB_pKf3MoY|;_k*sr&2n!xBlwQPZ*l!$ zT#96qF1f^JEYvr!1Fp)732C@~P1B4J8WmHdyIE=zPJ@HF_DSzfz43!Ju(A{)t05dTZz8YQ5rI6`Vpe^9l48bE5rDnKD+wWbuR-Tbw>qVr^b zA`8IFa(^L^lXNh9`>|i;t4LZQuf>-F)m>llmGire=<~v1~)?8CP5(E_uRhT(C zg`aqJ5TFO+ase4jv?<1V=!V#&%v{Q60BiQNI>e4{#131m4%5sB_5C99;j=SUaE)Nj##vAqp65uUsG=QeyAe9$rQMw6UH>Cak4~C z@n07`h8g#n$4lh5td9^5Oqa$bF7u-{Mtx%@M!)Fu)un~<9fkcRbwdSWN|4fpJ zNY1mI6Y~J*m8|m0VjNSorm_B^X)4?l!dipRZnEtiD0&{b1?Z+_>G_fA1RfqZfR&44 zCVqixy!%HX*Emd~TYLdxC+y?$7iJm6qZ;C=m|&Oix-1&_EE-@IubpEyAYVE(>t7Y3 z>z{fws$^}p?5L})vIkO*5ruTy? zsry1MO(&`|1Vd$OE{u=Z&mmLB_NxX)lIc(83NC^0X7%v+fgw0e=4s~rRkqCtQ1Y*u zU`g#YDzji!OU^8nKmV&sldG-mm~1vOn10P(DK44p9Lf!22NbPBrr>s8P43XJTUi-s z?D)qK_Y9`iXOX<9IbtARj%onc#D zAHjt=Lfa~Jl1SCL-I30U%u8Ad>@}%yuqgMXCv@>-rs}dW@r>@aH7%Q!?59VKM5(Q1 z3;Q??2TT$Z8|Qdbp^U1pQxxmpi7FFU%VOw7X@Ut1E1`53OqxVXV7Pr!F1C1ZqXC*f zg({iW$uJHC#q}J+FImP6ij2=}7-Z8Ivc1NN8>N-bV4xtv6jcS#9tBzb%|Mkyuj+KP zy{Prr>qC&x5y>}^lENY=HAt`<{P3x5_w8TrwvJ)eFmzqA~<%PvbTzaoZ`%!7&;{qyz^+pMra#R4m>FOU4p?-0EY8P7;#dT2FOU{cRqke>)y&YBP>VSJx}7)HpW8HuEWzThu_n(uE7<(oD{JNq5|V#CWmvYFuF%dG>3Cs zs8IQ7^7*Ie*MB4Pcs!<7aENOCPIGQAG05m&rd>f&AEpa2dWg>}y+ud%g&e1*YgJ4| zE@Ebs<@IAp2_qjLBv=d^P^YSqx%n;iI5?L_664-(K06;Q`8e_5hW%`*T)R@niQY{^ zP@3)-#-`SeB zw9tZMQ#9)eUpALW)(x?g&ScU;@h8uhS$0V}Pso=ZIeJ3XV#P)*{@id~Hp?S8w>;j7 z?{y!zDKnEm&pRxPCyT#AlT3vtRM`cQ;;Hd{KCzuzwt_~~@_jvyQ>3U{pr~7-D2GsS zdpvDXB74y{S~;C~=`dp9ERJ~(JA!?1i0NQ+Cc%v_RPoju$TvMkj}@%P8ush|VeOlu zG~KdnBO}AMZQHhO+qP}nwv7x&hHYCJHZrUm=X6zfpYu?os>dDUd-&h?zt&!J&Nb(L zKe^#VxS^Gd{DkcLB;Nfg^h9eK^{Kq+$y=0tOR2WI$y~Z3tesUs(*cP>XpQI)Q%dI+ z?a+Ug)UbtT*_m!fP&I?DWCkUrCZXA>=AhuNVy3mw?IvOHneE}Jf_+!VfTquorpK5T zZ&{b4tTNwTU9(`NJaBlz1wnaLL*ibF+@io!hykI`j6^ssm!X$WkS#uo1&KUaKNDyh z-tM9xP?|?Wx&R5@%wV{Hz6tn!Vd@T2OZ@e7sCDaLc~dUaPdU#Jd7_shEwLJ>uPTJO zth#O`*<(q~n*i9x8c?eqMwJV+h7J5uzk)kJl(|*p0%DLQ5<76pypz*-*uYG(l{b77 zpe*1cKQ9@EKGwV=&m+2JReYdBp=hT7h&Av}g+vcNsArl>o)j@IUKmD1x&f)apJtDRaU)TlL&i)m#< z3%`wnDQkdTI;djIOBtm}e-`}g^C{zKo`29ZeJSMNer&)Kse9Us>Nv{rymZX*oN7Cw z`Fwj_#|03nKM{;khHL`XGu{i_~Uw$&pXHpN>l9-c1(Hs|G9N`!RI z>zX}P#oKLaTXzI(PqOACLeqDWcruh3d<(p*Y&{WSV^>TffYin)JxJ2gBc3`5(sDv$ zY3a5Idgd52^6n9XVuzfJ1g^$xeUfDbW^1Mk3~0WoVU9R@D9TDj4Rm&wY7!!@F0-pLu)31G?$O<7In)JYC;GnuRe!M zTWd7CdOCD|LX?-ljEc7^5Ig<;fo0()%4&RxKVrHE86|W5c4PgfJFX?2HN(WcOSB!X z>lIw)h#xt2j?51qnUpfxc-jzWI&V~F<0-BrPL+9La1X^*krAVV|$9d40C#RkzW_Ssul z<=gxca0o5RSVg@cY>NBuhW_)4_0D#!On$Cl;e_31cr_K(tZ?w=vv47EPP>ta9a^vFnkje zw<&bp-q8iycoYgX$l3NbcO7YjJQ$_nV9V*SiFEIy2Afz0dB=!mt7dS5Pl7*LN zUBnv6;AsP{Hz(Z(p0kgVTj+oPSr7M$X+1af4e%t*(+QS4R4AY?ZupV-;)#?4p!QTO z$bv`!2ApOSiRi603N);LlUce3G3HF3U~qg<6@2h49H&OIsTPnXWtt5iJD*iHoRy7V~}+3{rbsS{`G^N@ZNOCoWDS;1I`&{S$-hO<2h{>C7Ut32$R)~pZc zr_{&~t*uBhx(=ex-4Fzqk*z-mJr$lAU~1d2*mBmB33e#rw7Wl%RUUt!J211_{o)X8 z@AMgpGcT(#N;7Now}O3(fsz#-E|khI#@fvepIN*yWk7t~4C}QB&pabMa5f&%V-4gB zftD4DFVbL)@0pV|owEQRj+a-eP@;h1Jh(4v%w&$>DQS^ez;oL7uN)rx^!VY9UlRoV zy(Ai54XT-_sC}5Cf0y?nsK~;71Cc)#*OjIS5tEF;FJE5f$J6PL514x+Zn+}ftiYwl zGF34h4Dv3~u_%Rs(F83cR-E{DLQ>$&%MH4=Q2O?ZSWvWKqBvIho&{1jceQT}k9sYF z3EOIj^V>|s1&hNzA}?9o1a|-~kD&H^8;pX$jU$QFajC=`K+fv3Po2*&e~4JG>l)Yb zUt&VmzZ4VxJ@by8zJrtbANrKJjVY~yvFX<@5q-li`?C8#wFGxPq($`4u5)@%C{;Em zb|t;uxJ|e|X+VFt0HHpRRW#`OMR5kA!pu!J&T(Rk`jsUE>vH5u?kd!JGh}&I5v1xh zx27K!XY!hw*40aE9nGo2FJ0-ItDA6;9ftM3byt&|KHKl!S6$b?UtzI;i}8Z z>2O#fTL-^m+BnaT;Lv*5XQFNo=&+*fy1-J{fqp)te6}UVZVr0BKDBqa+wy+44M%#~ z<9>>_%ZKv75^Y@Z^WyBB!PsfQLb#1Y2fC^C5aMKo+1@e7Lby!?ink^Qa!vVm_nX6l zx%CB-w<`A};yk&(CV|f1H2Gb5$OUAw?>u(8fownSfx0b49$j;NKIi-4y35C)0(Fke z>L6S*e16n}I$lSBNZI((n*)0{}!YYD!WDZ0FF~WJ|W-W|rRv{#w zG6@>fNIB-mxTR5ZB5d1qO!Gvg2l4IDT*(Pqw;`++DVjz zhCnjPElaD6d(^hu7Gksy!1G;{csB z+TXX=Yb0ypU{!Fm=o2BOl#((XMHN0FgDO_yWbo_~WK}u&V)-$wf&pwU73~*jC`eXL zo=UN$#=(y1E_;Wt>viTk#K0NMUA$Ll*a?vskReirR5TM(Cl{$2;!q%B{;T+t{)F(0 z@6|0ue4&(fn!DoCbOJ?v=aVL4C?j3@z?7cU6}n0d6x_-Klk^hHIWTulJ#V+lrixn!8B{6Ov@3bE)?Zr4gS!3zNH}L8k%qNTYOygK3(M^_QI=55N?CM){CR6iM zS~)xhHb0P08-PJ(^CH^1cEZs2MNt6B*1rk9pbxGiiVt8SYH021;(RFMGV^RGtPP_f zR-Igaj=)xB%n~-YjNi2SURJ3?y+TNhpGeM##tBBUOz-h3b)-_msH)(6mrFA_sIce{ zaXLMrvbEyO9V1p1VM~!)KS+-7QJ;vnCefua0Hr~N7eN$!4|U-^^t%c(8_@Xn6ZwYo zO{WJ}=ndW%;l}h$ctH22ChX_#6~TwUZ^RQSu4nAyN3d3|fAp@=GO3XM~iVxn^?V(FsXrok2wezAVfkP=$xjZLgr_@q0DKJTd z6&mIgokJapI2ubpqidLcGBL6-w@jE75his5y;ar7P(30V1~oqHJxaqIg29sHIEEx& zpssx@hinm{B*|`7!k%`LQ!AwoAzkjsP$M{CCRu~{Igx)hRfFP+QM|OiBDx5yynyiG zk>VXBBwM`nuZ~pp>RW=$sgj6uB^81O^eQEzZzxid<(%`kYEht}BV%G15wWhqEQwj! z$#=Qx8*M22qk%Z~`s%JT5Fd=1Mvg05?RM()XoAheo{C!y4>K+U9eUmQ_Dz^B_{m!u z%4kLT6dy$`WjmbI#`n_N`%)fjq$Q7p2%%s11Wk(QuE z2f%+m4jNBJ(Q=HZVyW-65^PE^(Nt&?_C*E=6g@Br`+n zBTNX}StgMUW9F|@tw)UCmeM_4Oir#QE4}v}?WgM11bOxQ%Gq6yJ3Txmysb{`-cU%g zJmYp|s=W4RB2{NEWAWy{LOc0FY}OXO&L4kRIr*ybx}r8OVdfZk(UA4TG{v)}EB3Gy zU@3A&oz+wuf!H%p&^V7rR|x3f-6S*bTSLa~auub@zlZCtQn=38`=iV(+2;?HI9g%~ zPCA?Bc2pQ!Z?-o>Gv~L{2@ilux+BRUIN$r;1mwHk@iHql!(iXV*!ZNtt#FM6cZwCo zQamF21XEh&@(ON_rEk~Ef4#%eJ`Q>CGyN*Iyxl?TWm{R`mLvo+cAGFxUGefoEW)za zwyLO3pS@HI@OOH`&v<8t-4a-3 z=TL)b5@#p71Yk}qbO9^I2w#aT{c?jWpDVlOVUH0icn(AuS?P3G!p9?NwiYU^?ah*m zwuM-1(lV~QnidAH-Ln%` zFW3yTKcUSMVhBe!DHhcW`hRN$1g#AXyntLWdF&TwJdamlaL`tqIY7@noxTD0 z>Te~`iajYdzf5G)-~N`h(tyjeE{L`r3J&X77M@I#tySFdcsCjXMnf zn-kS$A`mr_4kVHuUXl)ZaX~YJgR1|e3?Gr2^kAs~yAqC{`^W6DOx2JL(+)qwX`;~t zs@WiB(Y34DhxXbh4$&r;ruZ(WJza=(0#Ob_D4;h=Dq&9b2i8C_(U)Fu+_{h=&XRUE@*6oa0f=Ey= z72>=$bIVdM;ECN5zo8+jNrIzEf~84-qsh=}I@3*B;)>c6cU|^orZ$=M*p$X#!xT5z8&bjtY;Y4P0N_NZ~0cieuIEDSV$oV)u(Q3pwesZXZFUQ&26z zcQEm;Z1YL{E|uAoFm6Y~Vg78VlqxfSpS-7#8f5tSeVtJ-q3QRxgG&Eg{(J1B4dr8mB;WaPN~uKR4yFl{tD1Hb#lf zBg$)X;{!~5^sUL*ciIQYks_Pt2teg-w{5jQU^;!Elju;f#<|$9^d<*Ji+?rubg(mT zdNUSSc&IzLD^&NC+e=v)R*~JlAvP=rO3F4XAP~PBt3BP`-_}8}^Db(9z&1}z%_-KL1`ioO{ z&f4uO=A#2Vv2>^F8^ZwNH7=j9B%kU-0TD%QVCJbcZB|hgk5aHlJ#$GQcb zl@B1`*&tolb}X@xGw7A7X|yWluc_~8^Lvg@W!e%rja9JB$qz`Q@h=Gqr|xa2H&b+5 zH>;x@`FOFN8kkdK4Tj~H-qY}((}h5^x1T-Y9vOH7}%BBOakNH~ECEU1O@Dv?d3n(^|n1 zT~ou?E%q!(E*D8`hE$egopvdoEKV0x#0j}LvWve#TzkJnNLjr$8mx!c7Q4A7;M#4? zhq3NpdUz7b%(Fkv^cn*5IjP8N$}+N8$d;ikjd`vGt_L_zLUVrfa&OhNcuhI?&M zyKv~KX~U4{@FC>r@*(EvhES=-186lPXr@mJ0wR1@Ha@zZEzNDx3hTOvJKOd!(4u|~ z=ISAd)yK^l@`!Qc>oV$#vcKoz^Ha_(7Jpb+D7(fUE;i_^LN7n(7GB7(P6r{gOY%0*9mJkgtno<@aU%HFk^jY}uit3)(aw?hb zDAg{g|H2G6DqTWqe8|VoqqWr-a_REWWAl9B4`xD;{c)$mM<36-BD%>*yt!zyKiFARJ&QzFZl0v;%&DoSd z`}H(oyV6a-wpQe%`n^Rv;YF34H~wS|C$ZtCQFPGyrir=&FyeWE6ouMgMo^WX6{rJc z*stUOq7rWUD0yIbk^-qHdU!(vtU@P^_4QIrm5LPkWTDas$Pn zb8u!nFaBj>uiS9(R!N2)>&SiFVeV;Pcx|n9>=3qhrKSgH;MiV8TZ7P5IB^_uMdRot8`MWhPlLE|e+p8;NOVJv9Dz9?Ah4et z3f(x)^^4p3CGyC;5X*qDp(n9}KZ5$e-7_EmKpF&TZ!Y-hk5i3imM8m_D-LBQ+~!~B z0<&AiTmepjtR?`fVusnUa1Vk~Ck*<+{G*&WcR3(p80*L`5<0s;xFN=f!1vD(pckX) z!|AWc1YVGTRYm`vnfEVMB<5~s>|kf5Z}X4v&SHginLa+aY~dn5vYq!AnDBah9`X1c zW}Y}bDp{U1s!0WjHJe6lrnd}OA3t2E1FwBgH_6hatJ%@!E2isN|ks}{aY)Jg)ww=%cffVvmQijNb znD&%~$Vc#&@Gy6=_PDBqTm9UySpe*41;}4?MLNMX;kQIOzjwfI_1k)^g$9oLJVF0K zD;1JBv^H&`LzgHeVc*w6TNfKRL!hm1$c;#L0)BD`fZ@H;3W^0o%}U!tQwusxInge|%8uvJzW$$pMJ(}U zO7|O-pMat?VG@(&dy^~nV3Wl<3py@ao!QS@k6WFOCLd3)tF{0p_S^n}=}6ut*ibtW zf$Un%_LKYw%hnrqdcR6kXjask?8k=?0*fa%}HB6!*`3Di6l#w)ZO7 zQ*FV15-ZguZXfzPB%evDvfOTmfrtz1sQT13@`**(I3e@X$O;8!RM8PZe5B~1QMD;} zZQ3jf$sIDsGL=gBWP2jxw0dkQlQbbheczS{Xrm1X0YjU!REWsixuHY)?Z}N#e$$dS zy4)zLer|5bq{_lN<_`z?dEaf}+^}8kl$5ix&A1Wf zmuF^Vcia+JVMX%YrggWuUts?J2bx+ke&Geu_n*xqf`i7{D4VDACG5-$S!+(136(B< zYOn7(Dxl||>l>fD&JXLYlK>&P1T6k$iyW32V&}u?@9D;^h{!RwLo$ zk8IT5a-L+T729R8xP3VL@r@@ff$e1NCEM8g4Aqk*^kGsMq&NO4mn&*AhQPof`GN|R z-Ll{`^R1DdED=z%fO5NY(3wTFuf&SEfmdcsiL~=-gQ`%KSCz90$=#SH?b-yx>0b+^ zt37bJGtbUlycAB%%t0C|6n2)@!t?WpiJuds8p>x_2Em@z`c?|t8c_n-`osq6D$U#G zsv!h&mI|JRg#&aOlA!{c)edb3Cv?20uVWPtn$pA9bk%zA@4NayFYdzn0OLkZ=yPY3 zF=;gtb1<`2VvT6gGAxgf2CLiyxf#r*$Ck4gJH#O;nJf)~^G|U@j-pJs{4KM0Pib*X zhmIay>P%BdF7Z#;quOe*_B5`~QhTZ^+s3{kRP~{V9byMLQeDMSu1Sir9zaubj&N>Y z97iIhuK|+pF2)0NesN4V4L-GYkFcOQPHr3$<6J4xU^G*Jq!^lcQc;mT{`#Vm*0EmH zJ>8H8nqd&Vj004zF<)=yF-WZdMzoEwqo>|5s7+C0!SH+^5%zaR1r&AxHmH(CV+Xwp zhLXv&QZch1;t-EqQ*nom81d}BU(d>&-7IbzJ)3-6Q`e&_Y$M$~d32-5w<;?W-7QL$1d8nxH zTujAckOc}#D|_D3%SMt7nk<;|*P~od06a;p^*IB9MzoEe6K}lRUS8c@-`RTc23*3l z1)j=sY$pT|&UYtPvci)`AVwJ!l|`1T5NgZ-Nu;bU&i>ldHkL+v3n9vK4g>=W z!dVmb?gM$zvGrIK+*y1mn*H-tJ4P`#tM6Z}*6r(Z{hwC*_XFVh z&ksP!LEpyFhoA*uDI`I(EntgckA+ak0id zop*Jdw{IUf({omkkr5Ip!5{*+BNLtOv=gsKXP5w5eN2Ah0Ht8wCC(}YGmXIvm&FOGO%tTTBL1oQ6%ar z<%2ClBQHLK&F30@2MU5ws$3U57MR}c7Q{w7x0Cy|3lnR><>Kkf8Srb2O94$vhEgLxqKw5mB!6fU$PNwQ7LiEo1@iXb8gn&L7pIc8d#|z|O-wy{ zn@(k=|NQj%{07$#35V=z_DX?gmU=GyWFM+~H zG_KY-V0s-(u2@yE8gnVo9v+=dPq9{I3fE%k=Gg8n#yV5p{Ng*?hz-MguhO7$X**{z zS1+;#-MwmtgWd55noO|26-}738EafBgZ4|rN@hnF-1}GQFfetP#7EV3U5a8?>1HzQ zB~co$Y%nxA46Ww7T@@GDs5z#i@k4PG%xS%n0gbwi0ff-fXfA3?4q_SS$U^QR7BX%2 z(eKZPuGN>MFlTI1VBHpY>qlQGb90(XELEuscb9Xf%3jpfmyPLnYz&s z;s^m!G90T&-CsQDgE^Ckd+$?7h8W>a@o*DdLX7M{M-tLEWp7Ph8oRPS=#(;asE4F_ zTTB*j=^ay-J9uvXpze}u9L0up&1J;r+9mOwm{FuwRE6;i7T6=3WxNa(&7z8cNoWzz z2^Aqmcn6o=N7}mDcc&N91urOOL?h9Bll8?98fS`W79PUq@C8&1BBFEL2bbE0ed>13 z`+D9F@%|Ykqprk0`EYpca46Gp+3b>I6=wtQjO0Ms)MHzYR(O^6X*!vbU~H>zdaL{?hGQ-FGOv%%JBS|oI69I17#=XQbfr5x)rdZQa4`}SuzJTu8)uH4dm?$6 zmAZ^1qg7%3bW_OUiCRgeGgSSjoF#o_e~@F@Y6xNLPRi(HN{Q#aX()^1`49buhJdCi z%@TaB&=D4b`0C4(0|6s&D! zWNxZaDh+0(lFYz2(2^-829cRo>t_q;jiw9h`{`>97$O}eY+7sDrdsEY6k9KK_RG}M zRv1(I%3z_(-1xdKyG{TJi_i_|>D*qgvFR6eA^2*Fy{~4?Fl?WI!BsEkHKq_-`plOO zV{H~0DRlejs!InwZkA?FdBykliY&SxC&LbxuLO7RAGr%WYlF$@Q7vh1_6;Z1$ddBw zTZv&vUDMuGmDS5v4n}A1DXKU;6X7MUF-Gm;RZP*64a@O7XQ7%;z+sdrBsuS!J2Up| zB0%{4gxDKPj$#WqQ7lV`ONN$L7npqc;F~no%4ZjURrRJ-PUuuv2F>`zbhKy~Rdy#D zRt_l|Rv9TO_L~`n40DGV-&NdS#{Dw>Gr3k3dMec8E`Q5QwN`6%ZNTfm`%NlrI^@YJ zEEmr!?}OuFD=+H%pmGBdN4}59xgi<-38(IBg2T5wO7oW_Qxd8%tY@2SaZKDIZnT64 zmdh;uOtd0zMxYCAkAOw)jmM)s+CT27weRs5Ltm9M_m|4~J33ST&nxGzchsM5LPul6 zKUM<%3eqMO{&-$Pgtx;iJ`n0-I<_94JdQ2^E((#3o-CeP6Nacv33*e*fU4S(S@I%A zYd0-Zx7XIc601z2LV^7#Lv=)OA0gFKL;!7KP$SiQ_2lH@`6V;wGUxgA;K~;;ZCDT# z=1}2xx+`52EjHB-C1xZ{LaX_&l<%0^W(N(?$e1nGRSaqs2O)`$P?g5KW{1x(woO9a zyDjV8P^t@ISl!%{GSpE;dn^U(XVnq((rUelK%i{ zMt6opHi@<#dD*&bQ|7KmajMJ-jmcw6x2NajIEmKOUy-3p`8wNcRX_q%Kd+pd*M8?o zo_KNh;?i$K{5ME5AnCVhJ#p?67{C94t`?17`2Gdbv=j388u&$8K!2OV#A22H*eKbr zK!jWJ4a`wNJ@2Q+dAn{uv-TPX2+<{U2{CKtwB?XIPi22kH~lY=CI#-eVs3FT{02Vl znI*+~8e47z8vU{lf3AzRt30Z7D zlJ^>8Z0~wv3Wu0|D|0vrp`KHHYbc+NN5q)ix50S4_S64`-J(sglsH?GN$Svgf)ka3 z1a(86ZNds#DDbGPSjJoo*s>+h#Lde5ZlV#d+~t{~eCZr?BYt5?4B;GdAGWAI|0>hL zfaFgh-i3*298&M2g2Zu(le+$;r_cM_)~w|TJ43+E!(aa7qytC*))cjbzf{C~1S*l&;+|6qrl< zoEe`guqSVc9nclK?Dq(fWMrKp{qTEtd;m5G{|%OnuU~XVL_CSoz%A_xsT~#0 zGbDs-7(hoN9BFH4O$c}cG%e*@eJ{@19#SfiQ_?vFuauMz9TX(X@pEIcy*}IqZ7e)*I3r72U zz5jcT;lHpk;x>-vM#duMHeby3e^_t4|u1j=xGMDa~F3m%dQ++7bRJf%$2_Gqr;*Z zx+y7VHT(3?eiaIpnJVSl9A3O9-VNP^Q>;^J`<%rZ_}UbdPyvO>891dNQI{vxHs<3dHdk~QK;?R%Ul2Byiwi|9&b%ml z!qfJJe3eNd1ju9?L(qj#L0u%hM=Gw!TYOg3|Ni0D#XwNEm|}&LS8R`sJ{^~`<#Pj; zJbZMuJD1|DX+C_G> z$9ja~GHO|Ks;fF<(L!$dLMGt7)Kz`m1w>h5ZLBGSre&gnq`yNGshyg?p54lw0ae#{ z^gO-yO!}qp@42*ra)MCpmR9dP9`fAKpbuLOnv5xkaR{&1mPpL|&H1mWr$FydSkE`e z#hJ(yheGW2i}8WDU&B>ipFdT;w}uI4TN!szs;W-Uh~H|SRz;&Zl)CcyQ_>_zIbhCM zV$0vqV`tx1iJ=~=;3KE;ax3W_1xU}q!KDe@xH1AOPl!B7Qw>QCdfnb+O}u`lCY#A-9M1nwkloF5?gO=w`wJ^j&{EHrp}# zD(l(Aw=vsun2QeGCfMcTU5v^298;p9++4o zaVpUF%D7!7BTAkjI_;)&kBr(|4Z$Kyl}7XQYNtfb=o=?(HR;_I%oAlB&bjy$@=1@E z=CVYVamyHETO)9CQt1;Z#(l(We&vKnC~aWLW;7ZJ#fi4bin{Smi#Sq^CW{TV{U1sX zHI0(h0S%~aOaI`EH)H8qOS~ZDvT>{s1)GFTG1}aZu~fvwT`SfD ztNW54au#05vdVPc^X=WP#HLWM(MD{X>wp)H znJTNOB@E!fmgicSjjW3i=bEDru8PT;!wI}R5%TmVUm?ZFIZfl&5%k|xqD2j4>RqIGfRdf?Epz-ZLYuURzXN0X&c~4y^!! zNXnR)?E6%{+x^{ks{yK4T4R8NRf}G>Xb>T}KiQSB%&8`EvX|LI%ZcuHkLbFLD0rCA z!ft`;h^Q{oI}$eD1@)>=!tTNdiJApw_reUxo9@WLFkW;Q#RO4+6>!%%w!wa+JDz@4 zzi`jI5;!hRe9hS9K!_NF)(~<;nF21j_~dw$RlX&psTh!$75{6{F|5*E`E z|6gpf4WV0mZg@|B;@*8Hf|S0m>AfHHU*X>W!)^XoJ^CLdBj5X{npVtL91!4kbIDI@ z6U7=4BxWEm7bXt=*!*975@a|jtxqy2Z%-_P3?=>PC_tu_iLS}vWM<11ZmlhV9r!R! zlNOsp{$w5lgCY~usbKL86hgdl8vV5jL!wKzCl6#(c$-?7SqRshd4=+jqQ0prmq>O2 zv#b|>RI-W%vGRm%-)lYp?`c-6to`|Bc50v}D2x24<8%dF)UhThj!MU_n9S zS+e+z6LRr8R#uC?yq^aKLbGH-z+^Z-f$lr>OYdNp;u?-01KQNUbHEC4xF_fvno3bm zi^H!~NCuWatcQekrguCjMbVi)V~pumdP$Yh>B#tfvKRs>T7w?JlJi7X0^e=5NH?Cs zd)0r!?9_!xm&yGu>&w@?%=H5N16tt_>TpwiwKti+T#bKkZ~tC++h0blf07ac&gTEK zQs1RIt%#|N_1PI`B(An5K+a5|61M~p+*CkKgaimLu?AXoJcil(16L>k==U| zg({=dxn@bL!=(nBx5qZcrf8aVa~f6nj`)VUaJ5dX35X*#cN6#6ef7Ha>g9X+_vKLL>jN#Nh|OtF9qA?Ju*EE+eIytGD+xHq??f<#I-aGm zy8!L;n?zRvkb(cVUb5p7&<28?W)DZ8uf(E~V@5tTSJTjr^s#&JuA9VSQj_u&g^0*h zO4xk%oTG!eG>cOAmZ`^NfrfEdsZ$|bJf%ZTnUI4=Tb1Ram^w@3ulRt1ROI=U2qmL_ zC28elrE0kJd1`7}OijlWjWJ4*sQeZjpGpNp`fY*-C6Nf}M86&H=8BAQkb0ob{+&i~ z5c+cShY54)b6RK@o5V`64SdZxCdAKXZmJW5H&{tXrCi$d}xSZUTsVY-QqMNu#D z6YfR%!xeN+N)js0s|=MCs&?)2YNKN`3Wu1<2~{_IAnaNSjx&IZ65`C_B*rI3g(Dk= z%Hs6kP1%7QF0@S+uGEGI)an|7<}13)l@ z@mgktWHd_!pIL>K^%b34RL9a~v0-UeG*JVmc4r>RVWY=X7pW9`N{%u`&z)*9a^G!N zUKStfp#=pP)X1glhlONXe zJkjh_rRLZL&7*Nvu_Sw=X`lnWYu(9|vOg9csF~% zjLwHWHRsim5>j5lu&qy>7kTK?#c`p@xe2oe=&Jy3k^*RNrWb1yT%CM* zCzu_mUVwM!tZy0UI{jzYD|YA_?yYgPJI}Xp8b70#&d#q2?J1)0*RE>UG3_2h%x#0r zV5bn7Bj`mFNQKG(Z*m)mQ%vNqaMqSYU3Q9duP~p`UGRmx@wZ{ta0$A9V(y&bZQq2x zaUQ#cIeMX_KFqXrM;gl8j*O!ZyV?biacm5J?L#_!;DsFrz`cRx2A;${l7@xGwQCW9 z-hofS39eBrO#8s`kP@}_h``FI zGtuxB&WOYz#$b#QvE!n?vpPBcCx;mLpt{MZI$m;xutTPwWWU;q696m>BvQ6KUkw-ta4^F%k+k!$&W(bGSN&j{4{N zeb>yn!>T%q^{#6$)WakW?ALnWwjpH>8p>=B9Y>BPCYba<;dn~^+H^_IiDC%iM{{91fGB9(bZNs{DiE`^+OIwI3RoTKyCXcq^ z-Y2algdDJ1FZ}OV9Evf(^Avu;KgRaoE19!v+5MO3+XQ zl?BA#$JO-9NX_GK|g=srk6(Jx8o4ALmFo-DOe2NuFKR2eC>B*;DnYNwRj>dH3Ox(1>e|V;kO5IFq9+!XLA4`6mnFpO| z>NjlLEo+XGAQpchTtzlQlBcRH5Z8(cI-(Pnk7y{h2Uab23DRg4kteaRB{9g1T<5IF z;;G3h89PHNrAyQ;Y{#s})>JA!btt}dHA8Oa!FPOu6?HJh8XZi~pt3`3Dez7SLiWJC zLyOKToK{-E@cA=4wy(UXJmqUPB>w+B8~(Kr{^9510M}DmY(A1QIW#7TCDzC8iC`8O z87rUy2SHc@3*r-?+vy`h@9Qx#$#VY&s7xtuN!hAo3H->cN6)`7fF@jlJk!3g*6#h< zv9jb-{o(Vevi@;9-F7vZ&6>C~JpuGGxZ!%#{W{gXdAC*R>-zu(Ak`0>wbLICk@L$B z@U0z@%B|-64?PyxBjX*StSY^j0L84G9xc)$Lmb%WPWyty2P87J;~;&n=>TCUBMT6j z{uA_>C`PvnFC3a3eG=G4w8L|#tiVC8Br-PE?<70HZ*t`UcUg8UGW*HTFxQ6Zh&a6t zq%=LjUWV|WS`+;UAg2M{%O2*}BuoeI4aq*BHbrF#@4=FI_%GHke( zPY+Nz)w}A{u$Iryk=WM|OE+~fq4y9vdqD~*GsQA#({YEtjH$B5pW~sq9Pg@hdO=93 zdPPhI`WvIUm~QGu`Jvq0S0?&VaJ=5+7#UBG@bmO$z?s{nYDaqDLKx-xS0R2F@nPF2 z+hOXqaO!ja;OOlqfZB!0xlp>sl(GAj>~%$fQ=@X7>19gr*&5QeHrTO__RtKWQ@V2x z;Un3L2?xMmef`Rv56t7rb`DOc)*Lq+NayK}x1h8S(~imF9)STkIr+`EwQRN8IzxV8 zADqdvNzPJ!279hEgLUWeB{O2IveM#s6ah%Ixn=a~%kTws*hkbmQC&_$Zmg!!a|GV@ z4h;l}ir}n&1(U&Xwwb>K603U`1XltDAgbJRwhX4T%l9Y(RyTeB(xpMJKc&uAoI(Q$ z7%kLOccAmLw4u0d3$em}`PGcr(mk*DqS86E^KD(N$s)6pXx=?sBEO2KDtH5W%|aHj z8VjO#|QhO%L6$t!Rv+#DoWP%ExgaO#Q zWD#pixC~wnni`>`pSBmc2Tf}MV^K}OR8`oS>@}k`tj^S2CyIBzb-jm@D+@MR+cr86 z7l8<3IU)f770%vQMdUAsBXc<#raCE^@Kz?r5SZU%(lD06*H(4=_T9e%^#eRp5=b&R zMkO_XdZdRe2YtZKk4hH40jw0Y7;3<1W*w9&g-Fp_cU9>3IT0MRCXf~IPeGK4QWWWx z99ul4#Zy4>G=fcy2EvuFgbjZ~K{AZ%L$E?ssH{w);EmK`>eAVbR|Ci#8_Ltj+ui-M zI!1F1Y;uz|MjJNRY?(Hgj9zt2uB_j`HRNp@h`boiAeEI$IhuxLJGMZUv5|OM!*sO7 zr`iVso2-W0IzK>kB@0OrevC6w?^oN-KAlGv7>Q$e5MjX(DiH2e3J1!pou}T5PFV=;xKS-D{a#o}mAsabzJuhf0(EDzPAVN6|@EM%}Cm zqRi#7&F>dX^*!*%63REJ2ZI|oafIUBXLof5>fblD3lkIO0Rtf@C#|)IO8z zR9wYdN91>}-!s63^jD>ciKK<)E!vv*jOU@xnDP3Q!4+}W-NdpUTDyfcT8nXZLl#EF zRASzp5k=yvG{pFj=^aivvY(%v#+JuMlVbP@gb6#n)(}tAXXoTx>5eU{zxu##w7(o< z-&7EKA}p-H5tFvln~==N41pax2a)$e5_)bvsK6FU?Y4ArN;Cs(ZlQJL@5(msmOktW zl<_@mEhVPGQOS_E##QWnRa1JiRxi5xa#b$ypNpsc7D8<;55r1*7g0%2tcSaEMhKxu z1t)2~hE#^1dMP$iTgF7Pfy?ulHUrv;vX43Sd6>;lY=W}+A*`Na#cY#B=E{_VYQ47U zmFzd{8}PqGtJoUr+iDp;an(&LN;BERT{Dg8aODck>~wm?vtEx>P+^H=ROhv2#iao~ zC8d*h#yo63h^sPJhUywQW)Lj$64H2$(csUfgQFyav#-(nCia8M_M%%e`F3!SYy9FM zsOyw_GnH0CSP6|Do>2hwbtLe~JTVA6fzvHc426QMN2bd~x4Y20uoiY@% zDC2-VaoPNg2n}~}L&*`(a?v)5-1NG%R=yGUihy_df2_S@kZs|zu31=Rt+H*~wr$(C zvC6h>+qR8Wwr#s>pS@4q-Y5Fr=ySRwM#Pvge$ALMGrt^}Z$2;Kq-@jBbn#1AxU69c zB^}Io9K|K`$>@NZ;1pUVsb3a)y5pfTlb|ccrX5;0xM(QgI!@S@gdyX8wR)$GrykxZMFNxSGEuK;r-zkYE@ax@oA|5x$-Tp)ZaAl#}KbX7zgDhj=}mvK#w*?Nv$wi`?5|j~Bsl4L8HvDk$90 zYd}ose|s%pPB1Ke^q?wte%DwD!RW$d^$@_h<=6DA&j}`a7Z#sCMreLGVFmse+TZa? z?kle2>*TV+dO42@A|L$aDQxUKBmfyWKF-YiM%CqYm_8n4Tyd`OsuCh_K?jdBb<4-> zfo>JKtJHleRp+iXvE3!dr9DZ3hlwPuw;$5vWjv)&P8RCBt=)6rkv>4WW$aKC68*M` z)@dgB^|hblNm|woj7D3$3d=$bQ+xE(CFtZOh~%ce*!d3xRc|8egJ~rv*VEh%IZC|| zQ4b}m!JG$dn2%mdnz8_bf*Wo-&=O!U@-~5TR;#GOrzWa8@>yeT%1slTVgQrm=7_#M z(`QzB)(xIb4;?z_5NK0~|B5cmCbf@e2CYsQZz&AJ1aHaJTmgI;LZO;f>=nrB0ZuOf zFQ{zv91uhwH!>1gjC1ll=%HQ5?(dw6DXS5ZruI@Njofm0)Fxfv>!>%R6^$h;^r1K{ z^#0U92Oi_NCJmc;B`F0)SWDDk1?qGVUZ!k01^zfnf=7Ai`ou15pCipB7w+ATrd>en zIOy0X=nIRNs9jIrAoqmWwr|14Hp%mKvcrmCLzZ0v4cNo14p`N7*!V75;W2jDI6fr- zn68b^+5-+6fAR(}A$6}6VgnUyyb5aMIAwF2m8i+uf(b=IqWlwB-ik41krb_rtGf27 zHk}7;=6OAVwUc^>9yC8ov0(vTwQ}v}!GwHXQal3S6+Xc=F~c=s-lnX8CmM~P3&NU@ z8UWZ1f?MR^EAU-ZfYE2nf+Kd}5%A!hqCji~e%8}L|CAln6v{%6=59yfhp`-JOW&nl zh(!NAcRKkmN8~VGqF=3|kX~?JIoW*l5s;b4g#%p)J7+)gwlS9110C`=Z#k~Wgq%ijm{Ax ztmDGCfyl@Jktu0{{$v{d*?Sncab9|B(~i~tS+A`_;+q}MzR2&fdZTn$)sjHXY-z?O z>9~kH{iRVvN_tDHQFLnbDWdT{#@%+{VW`FO#FQT8ylRfploAE>05N|MGq$NyK=#0K z(2GfjxE0uT!$Res6Zf?pkaWYN1&!;6`4x6?Bv_xJ8>{0Zp8QBzU%Aak>h&vR*OlmL z8?iA4Vy)!Yp`*v0?&(zzgt3;u-eX(`4>%lrx3!$0Y)b-h>}b)U7f~g|P-NDU04Fa| z2RGjXM_BO4C`pyj)TL1mn0ORw!aa`+V~3m#l3>W-EIECnICT18t)>AR5&Z@^Jr_Pb z7eAU4CYRI__sNOa8nFYSryq@cUKi! zsUk6YYT6bkGTTYM&|}Yd2;1br3}GEtBG8`?6VE!aZZY#0AvgJdTB7tE?a&vXj+YOe z2S6wt$lE3-OQ@uL8(@d%bpc?hh>jwpkcZL42hrTbk>p_4J_+4c6Ad4=tsRzO+s@H0 z=OH*{EJ?}CP68J(#_Jn+Oh(!er|BX3Xl~ab?kwpAY9%YZuARvPS$|ct!f2gC?{WrJ z!FRLYzDP*FWFq7&?6|5f)Dz8RNT8td>JPtlN7Q~lnh zF>t3^(6Bl@MWZiTn=p zwoMW!L_ydV80WzEX9XS}nAye7Z$%0o=wNCXlMo1*BhfcQ7>0!qBt&b6-YV$0R{WYb zp0yz3w*AmylZ~NQ8j4yreI3D9q?M2y!#s9A?b++f0~}VMW`oF(T8bl08!upb)t7S5 zK}9_B<+uE%f zvesL={!G8Z?@?#8TSlvMVWV%`VM{Ycr7AqlcdOKg^u{pSQBgd>-XeW~O$kYjIoK^5 zuXW?ZO+pctgd6$HP-v4PQpM5@VSWj0=a!#6Mkrc|6GO%_4zRi zC*|P@<{cH&50{A8e_fIGx?l&vUGE`aux1th!GXWhljj0v&kwQp`L&NQsUl{U8~c$dr58ALxWpL$TryxFo*r2-C$2 z$4D2!r!UY*hH#07w3YqGdcZtzI9xy(Hy~!i1-}PT^}%ogEN_2Z46E+KdTEO}l8@;j zOa1xAM_)V9;)eZ_VUz)QFA98~_*JVrx+d^mgVG!exE#u1zJqV)sJS|ACoB%nyx{zsbmX=+bF5%-zNVzYx+XE_^&v7Oqs)Wq z-88oG#asDqu%+7#f_m|;SJpBg?y_+o=;Yfw;v?fBVeyxFn%2na&r{Hydp8mQ&2Vh5 z$quIN!;?P~)NhWMYqH(zJ`SWMh70C~93b?)y7C?`%#nlJ{Zt>=RDCgdu-^bFyQGDM zvb!iBgj|6+eFZP1Y<{}n#MVU3wtwKw@R`}jxDFOpzW|CN@FoYDXm0ahRdQk4Y*Il0 z8x1+azOh>QFZQK2$dgvXU^$@ixHqHGOXJN%`?cAGj2u<)pHZB&Fm~tZp_9;pC7=g{ z8p;&QlXhWK>==o)(st=1zC?D!1k-TmWmJy%H$O$}EQ7UU6Qz!wTH{jGjYa#UWl01`Cp*HW=oRF4)r#{bQ&Kts-r38LP%gv;-U0Bxrz5QP(V9nLfy&WiXYf z))e}_*Sc$bLlm8|iO1B=uU*Uj1P@*k$c9l793A;n_EmG9BMc_x`9x(mWRMk}Ev;GF5InexO0LgEO zxd3J$Zsz9Vcgg^B5o=7hYx^SlcW`(R%-4^1+|3k~P8c`&!T4ya;rR!txyjk%^Zf#$ z2Ny)8uriGo7INff6g^_jCB9ES5Pw%h$-QMrwv>3y;nlmYz1yhVQ`4EZaNPbrZy$69 zbs3Y@9-mFaXoNBU*oyP&pNGU;~FDu)%IlV%5&=t+>KMe6b~!1dA6K;+g~NS0 zn(y$~a~@B>NQ#L_i)3!PrG)YR4zGs!pqyCI)X_MACekReS<6QfD&m-%d&!O!eBvo--Jm zg=d9M8CVtn9LA8~RI|R_caa4(cyWvxx;_L&)D7CXd^!n6Pdx4%YMXNRYzIsmidYL# zmsPG(VZf$hiIbl*wp%)Y9Yg2GUEAt%263ker@@VnwCd8njNrQ%@JjiE?Ey zG*}*_zoE!@PQt@tzdZ;VfUl{erKYD=6DYs13$|emF#@xGNf(;Ml2Vl+qZnw7Um$qw zCpw>?gXYG+;7*ZFl+;E!aAKDfyVTj6a1M>hIF@T-37w|UN{cp3p@WCxyaofW>^?v` z^(t}V&@)UZ8|673`34bu(LlEbFRv&B{p9jHwDjPf4TY&GDO4d3PU@T8J-KhU4*H_iE0M7wn=~=pt)ZjZO}>6D7zT>IYOXC&X`}M`#r32tJiZ zy}=0APZ=!>_b(pc3dV!PEC;0KmH@T8-XdWsh7HWw>S#>#nJf1xzX=&3H(ywcI+~U5 z7WbPU=3vH(5x~GQgd|`6LVKyC*jWY0A{E1iETkyAa$X^O8TI41;}@~3my9GXYc`ZB z?Ac>K`Gq)+x~D#=gYfFY;uUm)yYZ3;?6Fm(fs{BgBAk_%Kf^$qqC$qgm^jYL3z8;D zvo+VCDfC#U-2NZb7BO8I%D3F;u0nYy3Ko~z2{|9`#bns?iR|KY;<}2{ddcM9(5L80 z1}#4-^A<(LQ5bT=#0`WD2=Zm+4J+DEVWJjb5Q{yC0XN<>N$j?v0B_x*F;?L1&PRTzeoD6!i>I5% zUH$N_Fc#(0mR<*TW$_c3G!Y48l=F<<6QB(*@AbY`P%X(yEJD_JWG%zdn|1Px9*Zy z0Tsqjn_;c$yM1{_{>)}CmT-{yDTmGP{xaJroD!#*^Z<}e+CA&Dh(XUloR5UUv^<

ynrU&8RI-4oC9OLA73Y zJrPfNtCjZlfmA@AGPlc>s_fX5f2Y9O>zbK&U???Sv+27O`P_@-RVPXocXUG?sF7^kI zPt4PrlxD+)H4B=+n(7B#n11Ab?zfE02Or+RQ^M#5pVRdR;uKVf4gckbD*xq&4a&OM zbFJpn5s%$~nBtCUTnpP$t2Q4HFQx*bltZsPJbC_K&&Sx9{ZY-`Z`Ho48jx%$Jd3qA zd7kG$p3p!uR|07njoE)Tra)!a@Q!)(gVL;t{34SBmeSCBiy2F{sK6y_8|>kW+01iT zlrpORcUE$4z z)N?^F!xu*d(N3N69!}re2uQ|q23fs{XMWKX?8b{?=DBZLHS@_EuiS@#yks7GDeV*5 z$?sYV+WVq|SvxH!*=w))8=_U?O#EVI`k?qt?$!oC=D9HQk-4Yry-XUcvT+%H_fxnN zy+%h8&b?8D*?DSlxx_%zcG!(ZN#^c0Wp!2gd(1aD_eSOQ%t{Rl8vZ^=bSs?(L*%-#$ zH>V8ys+AjDAYW~aXYRJsrcu}QNAsZ4Y)r-|Y-B3%`=BON(2ZA^M}BCFWA4i{j{WN= zkEsGEUDxOVYVTe^9@R1PG2>ZRQY$F{Nc9Rl(1)h(_N6}177B&<)%fiJ z(~p{_qyBOO@NA7;GjPs!p;?~$hX5JFub`%tjyLQxD8g#uWbO;o+jqRaaq%!j{HBG> zyEIC9UWa}L>wtAPt(?c~{NB9>HUBPzy0U2#^8ybg7W?{+l@fS~CYhtm=<6c2F=`kG}DHLrhStK zWdZR%hMI6bXZzy6;Cq|GndfaOolU$CABtH3lJJv3WNn)lhr7!Gl7inZ_KG&2NXah( zBukQ!Q8+*KKla`-Oo}V|`Ymnm#uo0b!5O^p!G>XQW{_cU9h~67AwdHKhv328rGpa) z5Nz;)QGx|0A?Q7OpUQLJ`@a9@ez>3S7glDay1Kfme!I@8T6K=+-5b%Dxw4~;beg>! z)nHp!arL}%#O}v6UGw9j5vOT;ep_UpV~c;@exxTk*JYnN*tS=PLwhERbM;Ds9CXnt zdSLIX)E1(Zd*#_<`?wd`HY!U~QPr=!|0=($V}sSNXO0v5`Kp;gI?;o7w3|F!?6Irq z3ff0!N+$1$lA^73HK!aU)oQf=n@tOE*Aq_B+Va~=pUBp0*gJ7exmux#bfW5f+p%h` z?}SrJj?8J*|4_vFb#X@FG-)rFiTEk4b7+EK@M>fydAuSX46FRYCE5U2yV=#I$)Y#w z4qp(}=IX#0d;ip!T)o9=pSFk-+rkNa#BHS_ADBzgXnA2q%D>@ZQs zuD(4d_hERc#3vP~}2{NM9$i**pKuWP;^?c?=buA{w&J`+wBdAHfByM1T2OHHW2dn+OqL!<#I1{e*k!NPG_SE>Rm)~v?&bM+% z)nJF3h1dBvi(`6i!W+4NI?mha$eCC4O0Lb4qtON%Bt-^)4i)?G+L9^qyCUBNqmLg|YTDj)P(7G>2bvK1`RF0`)HR-(Idci%Ss$V-N2LrUiLTXQ( zoKdtcuEjN#-xX!KUJgIEP&kQRdv6TLeCf?;+QMh2fsD>-0=RX0U%m*vbw;l#+{1*|+te`k2q?v`-+$@{BT`yyudb2o1bXSiL}BO`a; z&M-Eca3;xtbAus8y}6qW6xa9ba~%As>Myk+<&<2awS0Z)O1VtSiI3*Le=LsI^Kz^uehw4SyD-Tu+qKa0FXcjQ%-V|3x^@7Rv8xT;pSjRV_sYxc)wm+@5ydpZL1s zH_=Xr)8+FWt5Dn2g%tyW?zl9??c-j}Z>$V0D4c9|ORw7gggu1|ycbTPl5#!GLcg8z z=e>NwDIB)nPtUUEe4G-SSF}Ll`pA1bR;yJL3(WpjRLHnt_T7Uv^`iQ=Tq0U%apUC> z?pC7(?X#XdCn`YPOgXPd(5nBoqGP1!X~r#*y+13m=ZHt&tT`{7wf2=LJX5D?XFH0s zC2qSM+V1G%ISE<6+aa!lafjp>cUF}ReY<6L&J@lWSy!#fnYye0ei4-|?uyNz@#W0k z=iy>M$HmKgjKM}1X0+LH$|IadqvWxOuHJi}cNy)mH*)+{s~#HPJW*ft_2T}!4-n4x z0YqiH;hARFjVtR8#SY3ToQ!gaykO{rF;g8|MMb)iw~XAvmIa>XuKAa!BsWUP=S0Cq zGX})1%3Dh~7480ev$9Jj6saRxaX0GxS82Z;Fz(Aq@k?)n_mSHZv8F}zWq(!SM9Q&4 zgALzT%l4@ueOFg`U(0Hn^}yL;uSNUk#sEpBr901H=FxG&8D;lwnqQn!2?@J|Gvzn= zsg6sr?Nn_+%8j{B`KeZuBCi%+TShp`>&Y!_zA~gl|Ni0{cVokN`MX-Ltn6&^Otju_ z?3VXDgB{NIIWcUN=!xG5${_@Ub>h!D^*-WQ+&FLdshcM^oZPd07vaR&t&1wN3x!r} zCaUp`1ld*(wz}Ri$KYqZh4VBhoyf207QI_0+J`s(mcwNPn-7Wa_clS)jhmVru++*t z>!(JQ28um)(=W$#3U-*`&rso1mg8^+Yfp=QeWt3|!kcyFQ-)ysV~IaLzA|1o5whhOjLuna`G;>( zgwsy8ZGuhPdDGvRCfYwYyUXzpt>%^QUOHZo);zGg+~(?O-MtpSFD;zW@(zO)k^Laj zP`~@;)VcQYnm_Y+-&NvR+?;FQrHPKOzj}1WJHlBmM>PqyNj1x#sW(M98{|kVR@I7e zX~*;y=kv|oa(tU$ar0p7Rh`6{a5E?;;<4)XkN&QjC2Ho)bAQ^~Jno^lRXsuX&Fe4Z z?}}KJVXmG#mvA1um20j!%F)?%@r`hvNCtyt-qn2FuMF*zGyJ8d$H z2&cqD`784H=VdKDUF@-273E0I!EchrUM*;fGxJt$IWDLbm1}zDhE>H?@0LCClGV0c zHJ5UJh;Z84?9|%RW8~U6LCUQzYo$~3Le8)6YY0wn#r|lY3FW*i-JisD=hlePa?R26 zizY{`5?7F0le)_-ta;2=|LqIWg1t4{?g6!`?3^`^?qlCt@?R_0boaioOk5dnt&`*Y zTOF1R*C!SfSD9Pe<*>9?RQJr^J$fu^_^m_oX?rm54HOG~FhDq`<>)b1&7Hk6rrFd| zIG5$Pj=}PuibWMVC@R3MyRr7SuP9vNmr3M2w4eD#&dEJ$O_8#~d6i2#)oxGE`M$$S z;e31}o#@g9#>c(C;iz%jan@!h`M{Q#WrF3~>EzQ}D`Ihn7QgNl_4#%VIY4o+<)Jnw zhF2;soWd34(P=dP!mdJV1x>fh+V@G?w%>BDV|XFqRFebDTJ>@_+5LIAsH?Z@|JRnt zo9V-$u=~RK?~Ymf|L&OG?jY|dT8$geM~yU^aC#)k-`=d`h?EEJeZm>EMlO@CLdGcz zHF1XD9wTR}vdU+hm72*bj{EItdE_>iP3>CaV*TyHnQK1-YWL&0m=5EY31|6F@>A)? zy0#peCo0M94RSa&t66-?)i$j<3TL+*EZS-l6_Pv0(Za$xYWGH)7aDQrVoPxyy#1S9 zZ3-pSLA)l;-rLvY&`H5o&(fc6n3=XP{=d5r7cWh$m@3Yw+mD9Z=X}4O$yJ_-7VPae z1>~n%)a`PkyEu89duLfIr zPgUPivb%5^$YK4gh}6TL;-5AMr@5SkAy_}3|IL`z;#l12Fifteb-@x9k*k<+dfGkK z+Na07e~?}DsqYMu#96KT+{u;#WQPo}3A?eIIxp4pr(aW$OTpqX%f8Oh5W{cB^%ZvE1UBY0<*Lw>4l-RMrO zJ2eu{5jmZQ)gs-*oyBWZ6V6%t3X<>i)I6Qq3I^|7kprX$>l~b(-0?g5_Im}S6Y)8- z5|_Q7a3205_k8nV$C~ZQBUrxkN@kyejR&SF8o!9v^HJtof_bO^v1a>NLEK%3eC}yQ zY)AIi;jzL=yGE|L<&@#?R=(OJob0*eGEGLk-*+{?=w;t6DCbiMmb-L)?^rV8V`3Rn|Z_U1e@3*x|$eE8U8U8h$s{zA|>G_NK$~hN3>-9g$alD$2LL z@6oYegfmel%7Vq3y&Uh`E~@d}nXjeO;rY_ezl{hJ&Z4&Vai5p=W900e!dWecYP6!x zMqRA4RkS7UZnZg$I32rW<_u9=?(QEimuWft*Q@moBnaoY9PZKz%^rnGZ^aS3d%?1g z>7;vEN+;7Vy&-4U3N~9X_`u^1qN?9bkOS*k?L!ZS`!|a-^R7K}met{x?4$mfB3f~G z-^r19gAL<$R8EbcWxm>1v<}(RP6|6X-BIJ7$FB43Yo8i($T~1UKY+JVZ zt{GwCSKMo0-*Ij7@u$Wu2Tl`CbNdLk$n-}a=OS@*?zOk`BuxtKN@`kCT&eGMe~#{*S#h3zGyJAbE9g_CWx!Uy|w-Aqg=mn)=@`9d*j|VnaT^681jAXH_9>L9FWH= zSihU6ubGdw@MI?WUG>&Re}3l^N9W!}JKd+uKl;$~P>^!(rW}pmYV~-};0zf>wYirl z$I!Owd;h%g_XqmzPw&g`>X@(gPp>x8p8s3+wyemZ#cof$JJ?YpUa2hiMx*E}dt&0m zc^L1JvkU~A%}iW+XMI=UKn~$HD-15&^6^V?Er@St_Zg#-&P@E>C9Zn$-QV9WYvE%#8mYx+c!uce} z3_(i#h(F|dB1`7KG z`^vu&{rC9Q@+xDseY17e&E2A17r#Y5F9_zW();Ki^yE5zpPe}g``)#@#dTdc$K;5t zR-IvQ+I+DN2?F1VxD0BX6S;1HQYn%5b4>PviU0s}+@t^E`LZl;ZZ_VN1jvDtJ)1=evuh+-w z9quojv~slYV8xz?qD{|t!pSD5nzEV~Uq5=uYtibyU%>9QMUC!TD96zsg;R2pT&BhR zB=69rqLSR_`HrZaIe31vtC>X&zhB!XB`R=m$kz&D&)*M|_oISs7Eb$kt#rI_TFWOs z!Pb*IU+oed6i%lOHt)yIm3%&Vq;Psi$n}KW9yugirOUz@BIn=>b}Tx4c#a8zulr-m z$~8ASyWnJ#v?YWy&8`5||M}rywPNC0d4H}P3O-o>!#MxuYoe`wf2n+e5RB@v!n5>8 z(I>jUE=7J<OU*!GL|nVGTktXta#3g@7GhL?yd{bF%bLEQb5i|suYI^$U8 z_Ts8{|Dw%cWRFpQ_v)2FI5*`CfL7$N?o}g}i^_jLQ4Yp#HGk%C4$x_jJ(bU-tjhYg zmv3YjEu#BxzsPNFP;geAE~ZO3U*w#dR{LJXTl)wx(DfH z8qXCkdx?dbu}Rue)}#Jmq8_ zRJNZ*7XQbeci|^mPaXT2UE?A3w`F#c(?n)dtq!9Wras>_Q#fs8?km{hRHu#q4i@$2 zL5$rV3#ri|eB={RwI1|-AwN|s=dGEu9pc=0Fhq{iZng3E9sQtW1L2Idd;O6=d#v9x zh`sS(nw-xiSX(X$0Bgfmw@*|%!%`!VCTC8vb5RL;C+b$GgB&F&xKgtN}RYgBLl zmBrC({uR!4`+6Gw>S6WW(V~t$`0t5NbAI9@sC;n3zMBy~dqw%eX9a@~F3gj^tM1kT z9f!{+=SEYx=4khmSrztW5>A2~Al+)VYQVVaokic_!DBgbq*b%p!7qhpi;DE%&2Z_I z8@s7)<`UvOeDGP`eX?q9e_VQVDbb=%(B)v-R`Y*XxBjl5sKyB{`P;3|O9xMW^h}VF z;Lj(wu>Y|{@3-ng;iUT@x3I$=<>?>y1-S{C?4Dg%pw9=Tv$%dGWVdsC13lDZGv+UH#IB`r9s>@N?gB`4d@0|VK3a55Wo7|qg z{}@?8T&WZ4%X_(2M2VO$9bOp1X)Fhrwfb!=bhX>36T*qGpRtCnAJKd0Ia;QbeOETN zRhK4PTOATkR0I1AKU}o&q|BoCmk=#SHw}hdyq0@&QE??o=px5g4~BPZ^#0_2`lUTL z%Qe^B(01X1fwbm+a(+fDe2cz1LKD~Sgh6(zsc()4HN)G`r@ob`;9#R+OZVP*F3#|T zQJ3tav#aRm{=?{ajawks({b{X3WE>Ow@+?w|I!6N_9I$S2p_TF+9fWPpyv zEIaq!V_AU=j_*V-AYtBS`72_!?d)*xc^2U;l5@~l9k=zaHK>N@O(ZOrvl0jE4(On4 zo=VHCl6N739oAL3xA%ZJdlS~%&w$#Mcz?Om;EBT7ENATr=Fhb&`NM6||4P^qB7a5q zIcFO^>MmM(3481eaDy(T+84+xuDJ;Z_saEj|2KcVk0r(mCuk?D``n2e)3ArAy$L7n zCnH^_&Dp*AxTpyUXYKn@S=U6at1^=I&jmT1ht+?^wq1Wd6SXDbifnIKk%PDPKkgDe zvVo!X0_9$!dS{<-6$_MXM>{ft@z&d$3=l>=!Z$C&hktQ@?)M zQg=7gZ-1=HWm?RhRxNUx=sP6*C3~a6)@y3j%`}tFme+D-4Xe=ie|C(Jiau;&2Kn?hSZCkRe_xKwA)G97erl^ghI>^j{y}Tb zA=3y}kEs{l*PNAGICW zn7MsZ;ncS8!S=p;;;_Hx0O5qnX}_#)b;k9s?4a*zY`0{3j97Lh!^CsKiLm?KT^;A| z4=N(A1&J+B%DvI~ZQSFHv&A(oG19&>5Lx|c%RyE8%FkhGnZEXMZ})m*t`5(Z2xowtna*mPDR$n9C*mk44z=^x z4O;lt#TK|OoDomtdTK6TJVyCboMVY&<>2sEXEWpX&$x^NBaqH<5OK1w0SD(M&eI4-OXx`y6|GW zxS}O4vCrPt-!vULx#uO}tavDwX;Zpiz8;~1l*BbMhaYVF@9;ZmjujHl201l`)vSD# zEwAS`5zdxF_A>Qir=QzO=g&?#L3yy1ap**z{5OQN*UsRzYm>V6uc6t5bI5-8q-v#~ zi&gyW5zepjC|l(=c256qn5Zp@C++jF|G;Vmj?5QV*u>xDmC@>QboRlkFMbiu1=*Ic z`u{K`U)amZ!nq=Io>rwgO_omlBzoeBH)JwDSajOgKSpH~wI%V6901&kxq0wS-Dfev zc_1g73zpm4+1sk&aN#7|NrPf1BPtFYOh@pMY*AaW18QEb{wz{B&t6HVt66W`HSas& zyplQ3V83o!(|KP+TO#pqIVphE@C4)wS|f;VHt&FDEn% zb~`y=$6mc9pPAVknmuRA_sTot0T_mq&kh|GM)CHxsdaz zxaKC+zbu`aq0cfe8C_R6VfJ&Y-pAheD>+280g@ta*;Fp6|FPt4EUOr^a(ct0}36eEM(Y zujBu8b*s2~CiRiie+QcuZoe(%w%{vifSiTFidubZKn?ATaE2tvPi2a|oqovxI;JD! zjA>Tq?{{WaC{lIF`9qOHcS;vb!ALVI=5uX35FoIhVk ze^%7Yq~-E1L@@vLe_D(zOGkN?{T4~L&J7DrT_$Q>(t0_$NwE3q{7r7pzbKqd_Pw~i z@oC#{$}d_DN!#V@W5MX%W7nPeS=7U%-S(5>eyJ^gKOZM3NIGCw$S#8i*Jw3PRDh%- z@=mGMw?W9sdLQUqJtp7D3U)p`a7gH6(SA-kE$=Z}{kI-%|M|S=-6Wm6Y*(9=jT1NY zr~Pxu?zMIQKGVbc7VV#_a&B%b-(TnM9R5XAfTWvtvZ&6hZ8fjVrek{dC%NVxdG6;s z)AX=#671)v-F6L47ZKM*I4MKy-(K-!sqfkx5zc=Jin^SjxFwvwBBT>rZ14KkPl?J` za?XxmSLoH#pQJtZw|r02>J{-*=r=P1!ucR)dc{q)Qnu{V;l+NrAOrk}1?IU{O9a!xshzg6~C*r6v;qCKCSPo|x% z-f2s$uQXa*bCV0%X}a!@)*kuosW``yi_6LuY`p)6suiDz)>m?=;r2P7l&$BHpT+ew zxtx7RI_683@9zcX3a65sL)Oas$JFKi6tNGJtJ%re`W0?(c`#qllw8X`7QOoZk#ov! zO*r+s%TL9=dxkW>i1RtQq5ZV9)r*wY*T#!Vk{oV7N$Vw^VOLV!kKN~Z}C)o7`8kg9p!lm_Sw?9Sk{fFY71wPOj%gb zVf_oWPD6WjncdE8`6;6C=D5wmSt;jIx9Zj}dgs~VlEPW{Up51IdW2MeDV&YdC4;en z?ez;b7Oj-zt#WqJV5fdB#;v|0TCmBx%G *yOfXc#rLyB)`4I*Z1|Ja~>7Wp&Rm7 z^vL;Ya(r`R--4UcU8Pg6kN8S560>TXXCS|&&k*2tZKoSbw9ps-Db9MZp)(_>^5to+3w?Q z;l$hT$8{diwEWMy~f=i^KZyw;iNvYohsk94^Q`laGu!D8N2i;)o$W# zQCpIq+iwPS>DhF;dYz8)YdHg8uwAyRT|3r!D4c)n`y{>ZtzNY(ZFS*%v=hj6>K%3W zt1?J9U)Re06SKDP@r;?o-bm49(%Wh?dF__ERdxu+Wk2tZY`tm5tgs8h@yVw!Rx|bB z)q2(D2q&$40%f(1_jC*$BC1VFM*F!;^*dvi7pWpzrzu$*%TM(w7WH6_Pt=x_oN@;3 zV2^_{n=M@`uEHsK)fdC*saZ;~D0}}biCR3Yk7%8y zl$39>2RrBauI9A}QTUHszQ#{^MrQo`)sal2{V zt1m1>+Z?e(ek!KiVNXO2agdjz0s5oa=yP{ z#q3?tB$KFqDgWi8O8=LSO6hh+9_5HyJ0nXT5&glG-l{xau|J%x*KCd;Hzn47|Dwgv zXKRL5S}UAE_H`%g51S&-({qQEVREL$V57k5O1G=f5gaLJqYm~y-0bk;yyA+M@?8%3 z?G=7}+dt1)!E(w(Ict~|^JLnC!ExeTO_^$Eq`Rd5@?l^aLpamryX{uPx@kIXsVCaT zDYNYsW7iObx48DVaOT_Buj-i-s@}=6UO0<7$~CvwZZ_ZXqv(mJESqbeQ8+#7&ror_ zNLgvO>*@|c+?c<`bvb3Noe}D{!#b=L{#7^|<(h+SuWTy0aJ#73DO>F{W|eFU9?d=T zS~xrH_v0Ep?pJvHJ~|Kg%83Yr-8bf(F({YdJ>{VNE=*LhW&_Xe7qu=WDECINPt^5k z)qYwnoD+7dGJ3;<$uR*@AydxCcYK1K%B4FKzEJeGQqIfyse^r+mpRbAvuN|DT(VnV zZBkqPIjr^=;asy@GCgXh8Fh3~P&hZgkxu*iyVmh%gKNy6t|mxK<9) zeoh^b-rgI34Rv1pM_eybhsX(ngV7CU%nI%l*TK}`@_9k9^|JmykB=AZq>h%;-3BA) z=D7cM<7MHDv-fJ3*UQo`s3B^2>LmO9rv7be)=hISjc}$dmU}g-Uj^;WT2Z4?XV|}@ zWjEhnEAC_$&Ya`+v8aBt>f=444VgM$&axeh*z&8st^YIOEP5o*=a{m4t$Y3HmoAf& z`UQKNnJ2goioRazD*OIMi~V0C|4yK@cU>;I<`N&Ht4?1adN-*XOG&4BjXpy@_7%O_ z)U7q;es0^xiu}7pOX2L4HQZ|5-D8$dCTFjGm1&T=XG^vaQMFPJ$|O&){MHds$1c*E zkB*Vw-m%QttiJ_ldydPw%Y*$(Uarz6Q##?Cw%_89ns@kclqs&KspsT9hhU5B1@}Jv zP4stCFYc7z)wgfvt~35l63%}KNpM0^)SuM2bBev6yS~iXTGaW}+x9iL>iR6N?miIL zrqp=5SK9-N^M7lJ7Ex-V-6rYubb9@Vx$g=m^_AS7+S}f*2>XrB!^a=&Pkn4NIr9!t z*;1ctHU)Pd|1i6#sQjs~J#w4FQ(hGN^35sX{4HlvwnEbm8>7V1G5sK)aaf%`T`N0! zj=18dezA{5?=3wDC?DMeO^ZnYajG}M#&?Dzf4tA=& zx z@M9I;i0kshT=qyTW$)ely-uv?Up&lbKOHFA@$nyx*Ngr9u#o-kKz`@+%dhEa^21_w zjyliIVCVB|b~r=YIzu8=#a*v$M0CUOmeI9TMQd00e=%ySiiiF?w0W&M^nd^FKg9oW zhJ{BrsTJN*RrGfBDMz(lvAu>^;?E*QTdRsur+?ROs*)zGS8TWNq5V2{8`LtUb6?@4 z59{A0rf=(*LA~g2+cbvs>@`?bDuneP)T30)fS4{lyOrwFzhA%pv4czXiy6|hT&bZ$ zdi5<88Z&rE6Y*zQuOZzA#q_N;Xi&_E!Btho+qZvA*LuSTG>jc0Hq$6lls4#pF~#Qk z?7u<>#dN9l|NN7FCjA)}+axA-h^m<4^Rxn2wJv?^y?a=U`}hAZrK1X!C^d3Qr3RH! zG>S^4lTMNvNm8kCh)~=}<(zXwDk4+{A%sC_J0uD@M8zf{m9kaF+~4PF+P~}f*Z2L; z=kv$+y567b^Xy)0Js)eW*L_cBkKKOLRQq@2Q|5EF*;|K%r}q~8=2#t@-+Ul++>M>5 z4W1_&e4J`*J=M6w;i$vwP6vl?Jmc51@4t9p;CI--&-Zu@n_6379NGBQ_2>4@P2Q&? z8{WOW`ea3X;~Sp;BF+{~)!((Oz;C4I^jH0C{>&Ju8AD%mAZ=%Bkd!wPbllD3|7*8=8 zHbTyIoPk!(-hMNcTwM(INQ&>viI@Aor_0%J7hRSa!2%bbv7u^jvG)p#5KaeG&@eKa)4{RL1A{gW~Gj+z#t~O zU8{1SYr)Rxqh&Wvv&Y|FrMK6>;q}zPqjF{U);riZ3^p2}^I)MtX7)C%0kYwTcRuzS zrP$azeD}^XUMCbA<-;>}e)n42uTu6wUxUdxj|Nn#JQ!kdJ?D{DrNV3>ol4Z}0H(;Z;T-vgKULrcQLSk$Iq0 zx!KEOm&b;sDRJZX)=tlxGSSmU>p`E&NH4QpYt=uFZ&dd>v)dzeX=a@KUfo>toSI>o zeLku+E*kx7dc%|}o?XND%2i(R+C9C&-o+qO{i8vnrAO8n)i){5)K{U= z=A>EWPp`?jqA5Rj#jevC`c~1>v~kqQMi;B8eHsUzJUG4Bq1@rBYSe_vCa+~Xzpu;K z8fW-yQf^81r{Ql^FZOEGKbefb<_hc1(6QMqN=vvbRGUW}M5b8$kW%gN;~p7yFEC#znRX&iiV`}7J2 z)!~0sqpTYzp6s97fdA0qk6x5prHWV3o{){N_qPvtHoB6ReaY~8-;2W=wN7SE7dkY} zSgjfrQ2EuXWY0bOCYRN+QG&`tUcYz0+o0pNTK7w@N?R|5UGI`@Hn!_O3(alyO5O7= z)n<3Q%(JJtN?v8VM>*&@XUHw@9XbA)ORkYu-p&&anND5(zNqIi4w?2{ieJW5mU%Vo zv|DeJ-fr})Gq)n!Z0H}AFT*MuywZ2xSa)?>`^aZnxx(x-Bi5)cw`|ls8SPT*5bW8d z_C>x@loLDbkHVLMmA|}-cS%&1D>N#cESb)8cssRA>5E-ug_ruywd+@JYB%wH&$mdy z7r&eV>}mOZ9RbTv-VsGj87cA8Fm4svWTQ&KRSI+wtfoL4K^Fxa1o8-?bkLPC5ZQ?& zS8;wLhDFJvq)g@hC@>huhZ>qGtBf!mmxa4`|lTFOUzEn~{=^>SV zP^mXcs_W6HMU5kA)?m!?r;;C)EUBc2(rm)zffv%yXqxbvN@`T1pOHX#KHGPDCtnHbliA5vg=8TWNC8sM>}31cw25S({*V$h7^0dMqzdUlvXBO( z0_j2ukT#?aactU{UQjpBbe}2SI>PaYZt4TL5@YLFSEANPreSq#p` z;%r&HGCMtS7DM|8$(|f@*67JW))!-@LRpBNp)$x2%7Y>xQMNf-0hWs^7gr&!LR;%Bd*zMM;&)!%==Hhw^wT zkD-zYmE=)6Po*JLqAd^mptO`qlc>b)i;_Z8NA-`=p^}Te$8KT@hoWR6hmtathEZuW zmE=*{LZtyHHR%qzBk~_0-zwadoYy-QYi_gk5uY|(!kzmG`@{SSDG~* zv+}8Qno3brvO%e6E^t+vpn(a`Y3N0ophqQbD$&p!!tH=Z_re4nn&3pGaVV(};7((# z2~Y+wj52dfcrgSMF0KP$N<&Skq(i0kD8*1|1bVj8)+XvnAV3Dd@{K4xr4nTKQ6>(NxAGjFFugi$Ge>;ZNO)Cws0C(! zt`WDPTM+UFsX62GP`Mn@Th~mCbZ%7%EhtwdMq)v9Qe4A(hq&%uk zqyx!A10gj?e^eW*GUF2?3k`=fAajUnCXg;<3n@T`kTzrmsY6_d1My~jVtYYDp?=U< zND&%6;}cJDPbaH2s*ULj4S{+?10bA*!C4rbg~3@^>|uvMlc4wmkJvttBQz4?j6KLc zgiN4(C>r_-S;JF>+#ypa2GWCqp~(jxF*M5#lEFD-Mzv+(ES?+giw#TXOMK>z$8$f( zrb4{X@oXCMG+aG#^~ALTSLW7yNmgDC!@v2ram#>F0qXgMdEQ=uFz??pkWZ1H>Ij}qAP>n$K22Ic!vE3bwXF4iZNKOe8lHqK5@NjkkQq`MeM z#gE;^R4U34sYvZxsNLii+J${-rZN>zQ!&50sD|R(4b&q`J?=EkoB$XAC4l6*upTvjDKFFo(cg1+x|g7Y2Xho=%aRVH>LeBOHbax&mMdZ^2C6)0u|- zA{mU&?tm3M?o{MbH;P=|%)Y77t)kG(6tdF23a=){UjItYNEQW&H?=D(CPWQ9aSU0XgZw z8*YlyE;ZoO)j`c)2eTIiG-^CeIEcpWV~F=BUYB@1@PEkw`V)VT=2-PTrR{F~A_5WcAxG=}Q(RM((-AJm_vp#Fv0ms9&{ zY9CDm9d{wkwxA>E&=Iy1F_va1f#|PBW-`oSb*L|(&Shlwf%$X*wbOzNwBR)@h@tlB zAciZGsX!*3%7#omG8a<22F<2>kE713WCoKNOAF$OP@n~L2cKy{J7Hafts!hJVPlA( zI~YWF(3kE&p6(!t2m=uJyf7$?9(b!MzKo-%K8T+BHe#KKJx1&}VrPNB)y578Mwoqb^rfT;yD>heL>aIT015y+00aXl0q_ezGXV+! zII;Lx1i&7^Q~;>}(g1J(sNXKf@3^e+xd@OoASFP10Oi#!ka(7si?h}r!f&~(@WBY? zM3`+bMKJj54t0tY(W!(^br=s}1fWZZk^Cf>YF2F=>}O;Fj6%05pf`Zx0W|}v1(b$c z6sco;uULFGg8D<4$Qumd)_GcJHb8S08q?6o!D=4P#Nf~@9h!@&4KTSd`Isu&08lDHez z+z~ZyIMiYFmdXmT?`zv{yNeImUEa)8sRNP+RBi!p!EBVw^?)DL2lc2I%-$3zB3M8Z z%uCT2NPGeD6NtAZUY0Q0_=&J(gsmd%8ew)TH!v+F_+q zI#qngvCcqJezc_@yI>r!B5T5W0~5;=s|0pGv2MhM6MLT6iNsDKRt8w#^&m`cgV;yJ z10uADFeXA3M1dLx&8E64)kjfXh3cxPzo7Q7)c%v&y@;>_@rsVSh>kmfj-X3N2&EYs zAk2r5sSMNUChFzX`H4&wY9C4M%0$qDOSIq(E!ahbCYfqvs>58d4yG-cPsuc-*>vyU z`jSbVC1k#(1>cEKrv-*IgYMuPE%=A9--P`kY!(spz$elj452$vqdQQbJD5sD4hDT1 z3#=^&UzX8RpGZ%A2tDu}#5xljM(jCa<6FkEAMkf)mX(%@J=djnW+|$-@s#vGG2Wig+YiOUq;&j?9xi@6cI^=>zw#iv z9p)jJR;3Tcg7xX0waQ%lo1PH-ehh#bfJ^`-0OA2O*AH53vrJg{d(m6LSD7I7*Q@_} zQF=-L+|QGR_Cd_Wp9c!dVkU=vbqVr(wfgl7^GioA{~ZBz(2{?F;K5!OPWEFM=+;yYzEMVZ2Mc$!j*tjAcC26I2#otqH>a(D~i4 z!)Ct*eu%qLESLB2`pAjF-%ZOKmkI(s(i0voyIP}r8_7r{`NVIp`WUhmJsIeE@d-U< z=*dAcp$D8Jy8R)qL$7u~2S@9k{=I9B=(x%7YJ;5iS z`As^ISx6MH)Rqou0A3A;jJF0q9K0S5*-S_oM%u0i;sV5@9*7PQ9yKPR8i?v+s?tf@ z&=`CZjlWFJOva5j8^Ni-{NK8$Help++DeacqN<%*h(}UdYI;?jM%_n?j%h1VQbNfy z1tlLU`BF(0B}Sc_cZ*qvdR0B@eW|X2dc}tHGqMjBQL2EHRRq>>`(b3us+OfXiFVfx z%d<3*OPwn9A1peCby%z37-Wai`n0M#H!6*%(h!t{>(aiY{V-2FEYDZssNPMQ|E1`Aiv`&jKEnxg4l&Wdn5DXL1d;tv$qNWK{ zqWR5KN zgue{Qu4rj}Gn7v+!4EosF?RUkRms-D>gPD*N!*>iJ4SxNbIA6fU;~0!3h>mkLny%W z$X<&;XI)xHKoy?flM9$*p@$jn>gYE|$&1R{sH}l^g>pEFNhunQsbowgd6e=|@={rg zAEwA4i@ptDHUSd|kVWY$l~&W~H8J!>Du$}oVb4_Td98@jgcOuQsYeMts;OBW0f(qZ zk$}DgP>(6~xKT+NrAyQkL!}^;bd<2?7-hBu(BW6m;q~eb@k16WDWPxGg69ncFfMIj7+{*M-r!n(HDYWw$ECX{lMAS-p5|y#8xHF$2W-DNDye z)~Lmt^{J1L;8&!WQRlU>vM}Oc42EG2BLYT63OZ$B4u?4h<|>$NFqsWm__v|FHc>yB zPfY*bkJx!~2iTE{V_CQUb0z5pH^p4%b)Ee6z1moFn65DWVCKWD9(q$ObcC7O3;#Y; z<`b(8Qx&EzOe=H>oYr;LZh)zU(Yokf0YDFcEr56c%>*O?&<4N(uoi$U00jW*05|}6 zn80YteBy1w8B73;1M~rqVZXT&&tW&kSq^}<1CqxX#sCn&Y=BuY{HB=Q0Ye7HFc>4z z$%Da#!M9)6DcS;46{byZ{JaH#Du6@iE(Rn3R7=oSKhcqEy zC>6~N&cwr+m~A+)9GZ;KWDZk=sacpRngVk(Ol6psFm+)Tqq7+Ri(6(DU`&P~LXm?a z4SDwA4oVDud;Ws0_WMw>(G87lu|jSl6pnc-($nRd!_mI*Wxin3186{smJ|A`PbUC@K$*#FswwMT@?u(ic7Y zB1>O1=!;6^CdSmN5@Xfr3zxod=nGH6{pVfd!>2$0-1zQ#wU}q?xmzp9@0Nz(&83+C z@BiD1&6~ge*1ne4?7f^H_RK!*`^5aH!sTgd=j02G@911O(J%VRlH^%Q9;1<*L6YK7 zV1G#YoP3PY9i3+Zn=BUw8NA5W!%tfkuAIEUN^}te5$aH~iZgNK_ZXl*SJ`L-Y z<~&uK68H^Xn=C&cCdduYGJ^DJ&?i6C6RFNeT?L!t?9ptNi{@mld8$`8p;?=td4PiF z0CFS9g`nerjuW&EKf0BDhF5$w~hP@T`NZ2!BADq-7ngbi%Lf8SY^I==Uo(($_c8I>X7Tp5aR{#yLss5z*dKy3VS$g?^P}Afk_<Y1`LMaL(_x#y_JfW4X0Tg??poLa*u}7IVF$y;eKXk2pqmGq13L}2 zA#5MmxNjD_8FY(a^I;2NTZzB^_SYZS;Q@s}_K-K^0tG^jkRRj@1w&IIAIJ>~f}Ej% zcYpQ1@z(vJIKsyaK%bSy@vS$>|ss=z+)uP{}ceUn~f`#eOj9YNIt1ep|2B?$q$ zr%Wf#3Gmb(P6HKJV@%4&bMo8Ksk5(4#~1m%zmWsapwXwsMnBnmyTHCmxk$cz^dlXM zd=w6&(1wEP=t*4(iUYM4sLq~wz;a<==!-b@F=+>g66Lfp{k|EYB1C09Dyf*A=>pyy9Nszt@zw$B6*_H7;5T?-_+f(F z04*a(pP>8}Jef|SM4+^Z+5jqeIw%#Q`hzl~QFj4drQ@X&w3{GTKyCyLCa8PVN20EQ z3Lt6=QFJO3qUc7?(5UAGT?JH4PzFJCs%V1r2r{<74suK~Nf?Uw(rmzkHy8K@xQ@$QPOk`9t0ie0BKh@YCR@!B2yq20smc z8vHc)Y4APad&2jG?+M=%z9)Q7A32FbAfG>bAfG>bAfZq(i8GbYTX86tUo8dRZ zZ-&o-&wKMQ^q{4Drc@U!4&!Ow!vhtG%4htG%4htG%4htG#! z3%?eAE&N*eweV}<*TS!b&x6l{&x6l{&x6l{&x6l{FM=Ps415MY1D}D}SCYm3i zn(2s*MaHlupzHA&_!Bk5Rc-PBH4s!okTak*W1IKPk3>rONL8>g&K^Bxx#&s8x~rSe zqwR;Dd4PiF0CFS9g`nerjuW&EP`V%8*+=ZTdJSoS7kai(j|+NC=$u;UIdd94&k4E; zsG6V*g4_T_6QoB_{^w2X{jWwy>9%9(232X#F7#OWqh}O)-uj~F5JAfb$^m3b&^|!L z1Wh2wpB`1Q57K`qwMUOFJsCsvd@mRs-4cw$+{izQcN0Jz-vQN5^~SpiphPa9=0ZSg z2ofG`5oJN5qbz=dorN|*C!qt-WoRRm3+;t2K--`K=rD8*+5jDec0=c(EzoHw zLypaJYhhC4*a+7aWw-ySt8^hs!Q}2Ek=d z9lKOXB82CP3%n>?;LXMb-fAU@0G<;r@D|_#&mR|fE0iS7@H}vV7mEwL5M1C%Sjo#{ zY3kEk*lamg-KB*+E61iGJBbUj%W|wIvRqt{U65ldkQLy9?3x_QMRpVyWas5rA+poB zAiFBZ3Xq+^1=%Gzwi($OT#((6V>!rja6xuXj?F@L3KwKo=-V{isV=kvV2^SmB_ISvOHXn70ax>MP7g%9mToKWI3~8-m{)L10SE^J z5=X(RC_pt(GfdSkA6A6VHp`B0@Uy0(bs0fs1Qh~WMUZgba7o@Hn$)Qkrg~!?dbEAf z>SP&z>~37QS)Awhw6@tzszL8%GSKIjpiM9)6#xq%zK z72u7Y)70Y*D4!rzf=&UtNYEuf)dXGLvb`hg{1HlV+a2=gsr5pSE*?Z;7NA#4?ld%HSjOX4mnV>vC zzX*CqkTam)#`5fMBgjOaRTvE+S3s_SJQaB=@>Jxh$eocpBX>sbjJyna8S*mZWylSY z8zMJEZiqY&c^>jSBQ-Y9M2(FY4H-koBak;BZ$RFFyaBm3a&6?=$hDEDBTq-3jyxTC z0P+Cj0muW8S0k@RUX8pOxfOCN~OH z)(qLFceUp&Er+BIq2ZC=^qH2s+1P z6n>$=10kVv3`Zf23LqqO4s#SLP!JJ8=P*G*NChJ39JVMlqrebB=P*PeiwZ>0Ijm5q zMS&%P&cQ`NLu8hd7?8}_DaV7lRndBH~xq%2=G&*sI)&4Xbqm>+zk1y{UY z8t^t1nR$)?SBW$b$fU17rtMn3>gc1Zlf1)&j|_?kK5`O>1&~D8YOvEV4f}6ptm2KF zW!@~5i~c0LcW!xN_JD$e>N7W3w%u|)yTERm(u+r_#Vs1(pzI#U`!;{fq!k|9C#oU#b2a&5_|A3Snpc}u~7YYSF- zD213$63Ph&hj?wM?#ng46`hj4x6ZQkAz@mCohHm3*tIjj-Vr7sta$IBH5~KC7-Du1 z6F^KJF#%vWqrs@}!zgDO6*h8JdCTVA*A{g6x`db~o){qs!AQKpu*UZ@mh9eLFt}{*{PICwyDh`KTwZM3vu}R6wIc!_BiK%jEKlF7yzd)RYEW#IU(?K6WQi|%f(f2dPogNYGgzj-C(0Cb!28)q;Sm+`P`HMI3JPOTIG2mUc@#`gD4+t(SVE`3;B#k?q`*A{cM&!`#bLsNuwD+ju}B{w^;bJp{CB6(AudebNGS4G;Zb z071qC;Y^S630h7NCVjFbXg{E8f@}!FnI3&5Xbm6%O;ROj7a%MDEtYMgT+c0d=WF!h z(IKO|8LO5ZpJgt{(Tx6Nx^G_jwS6-S4i*zMfgpcCZwN{N)SL}SkDxt(;t4V%$PZ8n zLGc99q{#%O1Nudf9YFy`9krei->8E(1@eNXL$jc1kS{a?ngcmNGa*-KHsl2PLmp5F zWDj{mE>Ixk2>C(oP%tzV@`2o-AjlcQejfJouwR7zBJ3AozX=$9b2>V6YFT#Ei_KUDzg#9Ay7h%5$`$gC}Rl_!F~q&8SH1UpTT|x`x)$Ku%E$x2KyQ8XRx2aeg^v) z>}Rl_!F~q&8SH1UpTT|x`x)$Ku%E?#7W-N3XJ=#O$FVKWRQP`W!N-yd82{4$KiT!--7Z3 zz{6&uV1&X6DtM#dkHSP0KA|v+2yYZdqOhL|MEId#iNX##g#(i1NG4#@OJBHdDBQsM zH(38|ba}=(I^q!&exoo1g(W9ZI7p`~qBCRShXT4WcQh8!NHvUmd=jIWqulB}j>&Q-F?R z-L(sq1qaiyuI)V5g?L2bO$6&!^}#wJ&h%*?LFWMl5OkU#oas?ML8=7dOrI_ibO}&3 zL01X#1oV|4SwI4sw4I=HZQi3)^F3^3*2s#BtLXFU1=pYmby@Dn} zSD;l;C)5W@h8&^0&`9Vw6b^law4i;EAM_lugf2qMp`VZ{v>kGX${|yz5Q>4CAU!A( z3WnZ7lcDR-8t4xs3nf8Qp;Bl#bPNiEK0q4K9>@o(g3O^JXc^Q7sX$vHH|QZ`0_8)| z&{s$oIs^qlZy;N!1WJH@LkdtTSAfD66!K9hKw-%ooI-;V6Sz5WPrwaAp&jdA z`tR2Za|RKNBmRTico~4xPeEZS3Xkaq57L>pq9?)+)*>_>4u-#sZp?$AKAt8Y)9+?1I zjb3%`sJsFA3Q(-YWTqeh%8_k`~W-xIzkd{6il@GIa~z^{N`0lxx%1^f#5T=-o0T=-o0 zT=-o0T=-o0Lij@XLij@XLij@XLij@X0{8;>0{8;>0{8;>0{8;>&G4JyH^Xm+-weMQ zelz@L_#F5g_#F5g_#F5g_#F5g_*w9?;Ag?lf}aIH3w{>-Eckr*eE59$eE59$eE59$ zeE7BSYvI?zuZ3R=zZQNi{95=t_&oSL_&k4o{NMrdgM6R>ef;17@`YwX@bN!8zz-fE z_#*fWdREjJb(x}maQd(A5YKCG=^XjFzRm4vX+t^yE&=NS z3;>`7APRsbfM@{K0E7T)X+nPh8UPjmFa;0^b41k9T z49+0w2Ot!{Z~)E#(g1J>zyt!fHO!200;+Q0w4f@5CES5 znt(G%1_FoyU<)7~Kr?_^01PIubOw43VE_yPcml`*z#{+?SULkehiCv+00aPP0f+#w zG=a`Q&mjT;7XTlC2mnI>O`tQ-a}WUF0bl^IIjP(kM^m|SpX*ijG}f#5JT28eK{aP} z{(<%SH^vU1oOtV4Dt8)uV0VDHtnP5g(7&e}r>fi7}x~-~I`%8OE@+kD= zrE=rYGkJAK?=>}Rjh~b?3wy5-%OK#KL|{)r0RjUGP9q4V;0%KP6r4ifO+g`oaTMeu zSV95KQ9_VKb6hB(IYt!FoJb02&R_~?P9Oy|XCehOXB7oBrw;-?&2glF=8U9(=7du~ zbF?U+Ierw-97_sl&TnIl&aroXHf>oHZ2C99aZB znlqIGnlqdNniEC=&C#HM=J-%RbId8AIm;-ZIVuQ5G{=nsnqxu%&55Rf=IByDbAl+K zIkptgoCFGJjsgOP<~UP8a}13u%b3%{)`%l0IDQ_rC@4f=ML|A-cnX9F)Df^J z5qMHifPhN@%@I&Qb2t>x96kj!hetvFuvOv_T8$s>`R1mnoSe?l_T6O{dwxs%5+4)} zxjJ@TKIMnN2|*+U9tavKut&h2nvOrW2(SSrOoDD>q$3))o}SJzL_QDsUC?froQ}z6 z$A_(%GaH@T&=d$@DS(dvOaKG`IFkz?5Wp4yegL8XY|qD<92mhcQee2lm<^*7x`^(t z=&trdcOD=Luff%~43B-g^;Jw){)@R@64- zQIHNa8?u2`L-LRlGzwY(4TSum3D62i4f24@pjb#B3W4mPwU7*C4;etAP=Cl98V4@kO1O9{C)R77@nHJ zu{tq+&73LWU6->Tv@hA?cOvc3(eZ0)e2uHh+zSy{P>_!xjshWqz6kz!qG2##6-;P= zwEYj-nW1rxZ+MqA7}YZm+C2_9XmH?$+NEeXR9u&><5o|?J zM3qAnP$d-z|Wg`MNs_dnJD%%h| zq{?9msImcp2~~DeK$R^B@~M(R0aa2EL{nuy1ytFA;44**P(YRS2}oAXh-1iaZs0D)Ln1&d8mSJ0o{SUWU93c^UFDojx<%2#Ij$oa_m$oa@?k=G)xMP7@Xhn$C;hn$C8 zgj|GNgj|H2LCzp&kTb|xwN$8n2l%-LK2q6I0HfZeP+L?ok*t^#JlE$Oj-FiOFuK zTsi6f`|Qk)p~)Y>VF0TDC{V0Dey&bmx4J6Mp7^n!Ep*^BM7H}Ztf!mAqcc6@J6tY0y+==n8>ssI?r=$9b2>V6YFT#Ei_KUDzg#9Ay7h%5$`$gCchKm?>O>AF}``1Yir`7XS_b9smXaTL8cjKt2E~ z0L=h+02lx)0W`rGfbgEP*z-tk>p}m^ODZq0f4+Qo*%P4d(J7j+_MVpioHgS`RUKoF ztyr6Qi8b^2HeMn9ilk&lc>1c#kABsLN0p4Z8J@$MRlN-FZ?^SMe5<6nYJc5@XP?`d ztm3|TAD!~p-*>dE3oUHiqx1Z%3n$pPN90*r7h2l53-Xp*7h2hr&&^Y{j)Q+^ex>+xp0$C1nxbr-5WYhJ1{JG??SbJ&X4NmU`oe4csyUi?}R zw>wj+42255w&qMz)!^8!tRHipev# z&a|`%{}!i~*XER0kZD#I_w@7LqN+5FTYigIv%X7+8vYlMo zc;)G-*gS3P>lQYa-`bV)s-5yqWWK9wfARU*`6}DP?{qU0ZP(mvJofZdOrEFpnh7?` zzqR+t6FTLc$-GhD{`T{;qAK;nYjrZaR&*s-3653W^k5cuMaSv9Zp?ZbIj{1w#U5LC zIcsn?;>P)n^M)=Hlu* ze+9qmy}}_xWB967DzB9i+_!!EXgc4p-Ev%IdhyxJmTEc4>^mME(Y+bdC_}O3deOil z4N1mL{?<22jC-AMI{>d$s1)~KD=9gxqx(=@jv^jz1x8ntt}I{DnYOH*cy+sx~}=ncble_)L-aYTjOzFcV<54 zPSgC7(2HH6H6G`5XXkV7Hu;v+U+h{^<58qLFF)%}Q(Q^trLM@D$7gk;^0V$X%_ynA z)U~SS@p;{)`TRRgi%LR^yTWT8pVM8P&%fI=r=-5PYkAG%BHa!7wRf5lOF}Pq#nhOc z)!mX`d$-AuK!S_(s~eL)sWDZA_3h{*pFwq>Xmc#x>H7 zzkBX+v$WAi+87~itdKVHrHwaw8l@Y5_uS)lX=9MIF<#o(EN$dT8`n~!4g2TsSa)%C zoa8s%WTW`kR&-W%HV2^dL|d%@o$d{yT6AVSW*F+sWFC?_3CnvXJnsQ! z^#GCoPWTt7?g8fZ0Gt1vu%c(eD*!5ZEf!YaW=!!~oC;Q9FSg*dSYawgDQy3ni!I&2 z;vV3B58xQz1HA14R`vjm|4#T9s0Hw_v!eI4fs*KnY~Tjs8hBez?L@p3T># zn~(N1w@aH3_B221XX?bch}lU+A`TOzuH=}n#B>fveMYZ2A-QFQQTn52DUeR z;MI0koab@6TP4!g_MTQo+R92>JEg4;S!t_8+WJG8$u6njneBD=MkJ$HX-79ul2@{6Md> z0{b7D71%!Av(+Rjv%0&*+Go3mcW~!+x3}sH>(@teq)6@Rh!mps0N?-C7AFc35-ZGQvrCQw~Y@nA)o&9g~|2q$?`&ZQmQTIoq zHR5V~J`)Sm*sku^xs{KPU_V55lCRzW{4QhG(CggQA;jmkPCkeI`QPUMS00!u{d(4| z6RoFT&$42x#dw_s>sWbuomE?EZ_?{5BhjUQep}sSWa)L5?-11Cb*}Bj{)gsXY#&pa zEhABx-Q6wLzR*3qgS)W1y@mgzdwQKHyLm`X)jv**a^COS`u~BilmGnw zXXT%ttt+ox{#Eg(q4moZ_Qr4ac@}#^Bkyp>dIdSohG_(1`G*BgUD9Eec(>tk5?|Fu-0@qULq!W>jnC?85Zf z0ezxg9lbF~*L_z0?scPHwAhW&czM+}C_SfMaB$%^yAD~g_dWBVYq>5}N8iqmc>L40 z_VATNw)Lm(I(eNwe=k0^X=1_tv1x|}z8F(;e(|BX&0C+eIu4qU%szHVK3mgYgR5_H zeRAvZZx3&jz0*&ac=`C=8P~kFIW3*G^2Lrl>rMXI$lH5{>&XiFeNu5D9O7aC`y^e>UezWU<+%83*wQ^DY zx1@YJa(_tR$@4cf(lq#X>NEb_Ej{})_#F3usQ$Z%bc^tk!#F6^3t2-}fRi^YNnNuP>f;S=nCEG|Ja=M#|Z7K6(W|qQ{jL z8>kznmj`}u9#JaVZoX*p!^){IwjZAr#LAssSe= zhscPT;h~G1BEuKWA2B0z^{VNDMf1a#O1}j&X9m0J+G|d>;+Mo0Tb_t2yy$D7zIo%K z4V%=rWZMUYy5wxB`!L^pgvO|n@OYnvj9&~#t`D=0=X!0A{64$ow(91;-W^<4G0}Wk zJhMh6d;9i@nyvTjl}rY{v-vCR`E6U3Xu03H39DB;X&TaBXRW6Cq*gz62kZfM9D-s*n&?A($ANmE~ndD z`R9V7!n=ld)8$VkFYm3`G<&~pbaO^P^nCldnIdncl<4QP8b+rbZmrm-eR$Qi^O~Ag z!ks054^>ESsJyUpWBQ~LMy*b3;JWkMl|w3SMpx-&x2Uu)bNw+SI;?fqi3b-JT(3eJZgKPfQ#^Ym;lw7mwIR6JPwSwZFmOZC;%k=8Sk^R5D^ppSN zOYa^&KQc7dbAh>6^+^w;iTc#|H50=Ymzkc!c0NI2GW6yq0 z2)%QCVP=V5&H#m%?GG#ZzCPSOzkR1c@R&mL(OYi}A0!`;Yj`C7wR`_-@7>dP)@#*{ zn(guT{9pDXU+*`Vy8N#C?18l(|G9K_k?8G-S^kHd-&FYLcqX_C3+Q zs958{nOQsB3r+D>=ls>QJ-G4UyZm3F$I~wlewc9S<@S@NIXlL`QWa^ue1C4+8mBb( zrBSKzSClklZAQ7*+}14p#tfX%w)xeV^aRuBi&ut!`#kMDGchV;#0Jw?pUUA%2ipss z#>aI^=8j3*F;X*C@9dZP)pG(aT(;$0u!*U6bZ!bAeZ-4%s?Gl9ugH!C>GK3lh6!5w z+gmK}?L497Zl5flvh~TXoZp)NhqQNo5_DO%Kxf*vZQHhO+qOAv+qP}nw(V(K(|Wzn zIq${3C*t1y!;ARh`va<0Wv$FyD~nnO0t6eyHSy3~fT|sR>uivPn`PaJsN>I z4%;qN@WIxQdSomrw@CofFp*T^eNg8;c3G7F{v_FJWxT7>^JS#Qv}(Bqdxc7QnuAK2 zQdDO0gx5=`08Ikp@8$Y4RDT2J1Z5unG2CW2n3P)_0jfTs}^DduQmlS!_i&vc^0 zC-b5uiIl_d1J@ODL81(Q78Dwj9b?fXnCwDysf1cbPA?Jd-17c~eyo;Rx`gk*#|HFw z^soKbwX61z=oh#7hPttXqOrZRv5lcIk+_YagR!--jgzedk+i;>psllwldzkiv9Xb{ zk)Xbnm4UvY<$n%_oTLOGKb$x6i21#|q0`>a`q?0seTh*Uxzr#qkWE*PAtM7>*NfA* z%&8#I8##j+fjB-C4Y?fArHY-AlMT*alvt1tKrmngFZE=ri17{Y?_skY+Lk&&^J^Nr zbo*tNoyQ&XbbCZCeuj^Ux){yrv?*uG;8^fDS+s>3yY9_!oF#ZmjvsCG>;_n|(MSb1?>sLvSBv z8PoStUVG>EZH56 z-BWuwEMtBy=3sfWwaikMB?eLyou%fp8wgi@WcfJpbVJ1l~hoFHGGICSI zD8*3p@k^UQT2IgI^Ct+%3pfm`GgpLoPtSkS}f=&-^LIT}p7D!#cSL4z80R;t_wXx-POm zb~rhY`~JAlYEIhuw-&FlxaK$cUS87?GZVLvK0r5}T(|zXDL2CGAMvQPf9Ar3U-9xL z0J3k(<`_p10SHLsT#0fhS3Rb)7a4^Gdwsd=N!$$#?5J?=p}6k&zie$szWND2Or{%Q z!CM9P#D6}=y;C`#hfHPCD@;zKEw}O{>`5Hh@f4YoI8P)xn$B6zWB~i!*lkOQJ_2(y z+X^YZS|#_+Rocv4N1#|UB65q^`wQg7h#o)obA`xJNo6mcNN#csI|_3PDlX-zQF+C~ zXzkj{Ps@@Il`B4&Y0}slKSsLGp-mPMch4UO&zch$A6gCM6RKy0=t6B}ET-m}21^k# zV$PtcXP*nEL0nzYXKj?^8e6AW>9j%BfW*Yd@;l`XJr-7~V8m4RXWL zMDRN6s#cG}`d~T&0O)g2!&id3!#|C|v`y7U2ehys<-9AHG9k`4nyXJ zd*?5~!M6L#e%laUDO8};3)wRm&1o7FkhD50H`H2f5%y!sV=v{wwg=GAw)@b2-4J@I zh(#CVkJZdr&^vva^ZU%ulCAqg&TV(vZFk&$B@}g&N|=rF!l&=)>VDeDEQ8K_Fqsb&%^*=g%DekuHVD?MZp`1#jlHbS-uy;lJmQ})nt}@B_RNX?+!elLg$&!& zQZLazteEN#<>`kj^(~rXcNeX@!%MOV(-JtEqdHpe`gH~}G7M5OGZ=C(vQKybu(8sF z@ID|h(NnoBmyb29eyvz_Iq;%|&)z-dl}O9D3n}s=W>+4JtJp+mx?}vf<0V{ym=jX9 zy$#`r>=07Y2z_6>=#DK1r^yXY_NFWeX;#p45?fJS(DTEw5c3gWC_Lbn%pO?KUvVj4#t@pvnO^I{5=DwhHQiK z>D=c+lxU|uxEjbl!R^m=QQluu#BPMP16v=4SMB3gw8?8Q`{=_65*URJ6dS;26zRS{dDeYJ3o;y@$!aGG2Z*MT*0wNs*Co8!^;{jTH_Yx>t`? zTwdO2Yx~=lT%S2Fx{jJw#aD3JTqSb$MVmBgbv1`6i{2iCsQ3zEeok|}g9^NmzV-Et zt3AdqB^oSAswiqvnm&q4aaPK(-JV`(^odsY&E#EDGi?dzr5n@&ZTpyZY1GX5x9FjuVL`w8qc|I=gYl*zmL^J(-Fcb~7&Tb4ix0GfOj8{vVQYfybwdedC> z4Z?*eWzPPj9?tgb`T3m4U&<#GWHIz|R*29)AN-B|8o4TbRwjNCEeWvPseJWGrYr-W zi>D}kmt#!T4kO1!OvWziDv#&Ra&b%G#Oe89Vzq6|Qzg$W5`MJ_WSEdGV5aofir`2j zK!qqogK^%qk&sLSdtz_)9$C{FmtDRT(f{N1`*+U6@b4?QC{f)OK^|%3t7W!63Tbw^s2Ui#lv;b! zf|5oE5n&xwYKL|JIx?*YMsTCX*g$eW05{i`hW0GtPreWM0s8`c9erIBT<}*W`~6#v z=SqP!z)E7jIcW3aNdEWHdVNeC_1sKefVNr^xN0_OVHD;8l?v^OyiL-2 zeFY*#Mg|COpx5Hz1XzZh^QR;zslcCdfoVq(@8a$&h>Ywt+ zp&jAz{uOy#x>8T7*ntPmCFf^nb$v^PAW|mTpIs*(9R23a$maT*2&uYf%TO)F&0K$6lw9%e(`~Uf@ai^o)s* z|J+9W0*vGRGkDw80YFdz*(xU0XNXlx>4f`MY>rNkD=j?o<^L&^ag(-fqYDx){Twm% z8{h95kcwI_DE7XA_8`3HR(w4-QuiIMZHGwK2mhY*58_`K zU-L?$3Hs*w)&D;W9I|%CHs4%d$@X6*4l#X4GiiOh|F_1L6~%4S&j%N@Lj*?(LS9{_ zAlD#3MjFZ|r$)02knlLlt8uNdO&n6N`vVK2E|dk?mdW;^aPFCAWdXexVF5_oKQZ=d z%YL@rJQB`CnAXK~pwAkE{wUcy%dyAoH3mG#vLfm}s>%Vpi4su?Y{#Y)>ABKUe%(2% zLB|>EEQup{xYXDEp7>|r>9hvA50ocucI=jBqP}L?ehV@-SOw|snyOIGZr%!8sCl4$ zCt;`XS7^pCZhOha2gqMbgsONB+WvjW5&j1YU;nRENaP>GfP%53xre@im9dbm^Y@?M z!9m}hNZ8Fz-^TH;vZSq%@qg&KlC|uD9Fh+Wr4uH0q~9oJkZ%`eH3lEY~Kf4 z+PdM7#b4jMI%*R`Lfy^}2iyNFnO>4SmMI#S^I3|S7Yx~iCZ3a^*-7!2V8<9JJq7cm zv|_gEAyEu<4{ZDh&dX+ee#KwWrb+i;zQLZOI(+lXqUVn2aK7SXs1K+B+paIVrjxpLbg4a=bwW@sA$NoOqePyZ5dD&V5*r< zHiNw;+^jmEKe!Ydx4~IGCqY}Grcb7WtTTX=ZP6O0i5(}PF@W}MHQK6TfYPWY4c!%@ z@im9qi1OZmC=EOMI_a=-CWJEJ94{Dm9lBot<3$5!HM-QE2aNdD$VMQx-+kp%cV+7l6)+OCqzRY363-q{+NK_WS zPq>f~QPLvAB>Rl}jN^9Cm-{C|FH(0XVOSd)K`ZgTOXfZy{5=6r^e&>k8k{|; z{}9`LYJ`FKatFbcusv_Mu{>|oE+cTC=pRGiu_9?}%?Z_}KO&!>>%}_FHI$*qQBmzC ztkhXHlo5@AElm~+Ye}u=+V*~)grORt_K#M%mQ?Z(yjU!TMU)jO8U%TAWUniXdN zy;PP<@h0f?&yn~Y23F*)twtJ{?p1k7lpfty%N8cyl)4KS<4ax(Eak7pQ?+2C?t`|P zeZ6yXF_@rx4%&m{wK6EIlt(36+I9{7G<2b+YBd`uwodgKM(QS`9;e0a;&XQ)MCWU> zm%^tzX-a=uVS*LSOKj!;ByBE-l^v!XLt9Rm@e_YYO-!z>gIkIX3yK2XPfZQ%?rv-Q*++d#c=q~tznXsC$U$l=EP9bv;8O{%H zZlrW5lsVuIeDD<`Kctzea0|1oOtoqiJ?_3?$>@+A zZt)RkHGlO-nm1Y61tSncnR*~A22gCFQ%&R8)EW=+MSK8ZHQ)jlel2-$0g_Xk+>XXN-KSm%sztz;G4DT>kcEq z(9I#*Z2YU>>m(h5nq2tnUan@i*>Kb&;R^lTcW%w;W1r!6W~^_h1hVijS0-OVht-KU z5MAu1X={Dt^rJSgbGmlwxve8w!J7xU7nuiQW}tby)v%9TeE=YPRt{w4Mpn?^sewy3 zX`U!8w=8>*>?+>-mHXubdw~0`It$$?NF}3;d&rNBgyQlGG@oL2ptq3$94dD7xT&E` zE`;{xtqgaMVg$FB3H>+tIw>Q7_Y8vllnzcfK4IYMm-fF!m@HZ17%MpUyJh>N}>&lI>TrXt$X$- zKPlrn!h84vqmE~rN4(Y=|J}x8{KtsH?_lm^W^L?bZuqx?R*|}=o6=F*m-k6#8-v!QF$uX( zAugvqR)N<(IEkHqh%ARa!&an*8*XHmEW15KiTlU`ilN3{!p{EjM&|+4bN9d$8f?$R z1y&PX!TX5f%<2ud&sP{CGTO;w1J}DEY4(ugrssB;<4boyI%?}P;FYx9H5V&t>nlDh zZ9Nw4+701POKltA1K#yEj7AB+!5&*%y!`?GK3UqWRra{6nKYVWV(=CAkp{m|a zJ6&DDMp~xa=PQ)j#OCJYCWz3FhnqJXkI-r}L_3!2>!pwcc!Dv^jrDOeg}~EO_|eNS zAw$8q8$Gh(>rM32sNZvi{L!w$r)$;&6GBDexY6fbdxhJia<$~h(jvhRRdGUrgJz*3 zhGVt%0Uh3|ZnkW6Xwgrg#WQdt!0Oc&;YEcQhe6U#Y!lf}YCXRUO;6SXh+>ZsSDEi_~Q;N@TDOBg7dQ z(KalVz>SYqU^ zff;#{uec_)skG;g!!QEqP@R**hFBPKc0AzEsW-_D7+&c8t_PH(m?t&U6OHaGX#34K z>ZeNN($DW;NS}RpbT&6py>*(8O`skVEU}Q56|>72e%lQ=pd^xU0P^!cRXwtLi4)pk-ji?AI@ll?M<+}2SH~2 zcF?D^aolsUY1Z$6blsIfz1lyfy)B3KJ?hszu+>@(BSF3+{2;yLNxYO}*f~ z%l38Hi|8aBp5i@F#95g#f%ZA?59vIjYX_pJp=gZ1)&@Uk zsBIx>H>`WI>-0_c^_$Tq&V1-jR?B3WopRUK%wTP5blqw$XmS)4R8+KdwNxeLKeB+g zh$l+bVTFbthyi=|90(xqvLtPDJ578uy~;Jjl&Be_zB0>+8r7H%qvTx!%3FmS`k))R z*bdYW>U_*A#xCYjsac;}UGGxQJxm~P3Pcot!U!+e%NF7wl!Ka#k?@SG7#@I+#@%>i z8?kpL6F||Vn{xbfG1*a35!u1`RD>vEW3E~JUf9L9@Q~5M zO>gvZ<)5;WAVxU5QyDZuExq ztork7%_x+R!kptlh+uQ3t+P(wk+FAA2!a_xPd>ZYVnPx36x$dD*)n9vklo!2V-0hXw& zy}D>W{i{=sjg=2itYGN@MawEBC&Vo~LVHu7Dq*`fYPJ^Yy!1rERsaygI15Vv@lp>U zM880rujxc=FU~H27k0dklrCm_y)NOV2k5-nu~uCt*gNB_?Z?QmwFZ9A^nm-EuhV8H zy{Lk^bdv+}rkY?EhI<1pg`y~<2GQG+nk=^hsLDR1S2y`~B0A~#PECk2KF&A^UjQd9k;FTU$F$!X8halquw%RF((*I8WU{CxGf0$%U<@Enb;3_ z0F-H!jUjX}N!>b`TwSd$4ABVsRAmHw3}60g&8a9{gz!$I3o z!{fQlYwpJ&{%iZyaFM$8jD&k6EMa!`l436s){Yssh^y{jo%Yvp7*)T;qLizeJ!SRm zWul*vur!*yp;T<^x2uZG)TdF??uEy4H`2@NjyGZqb2J?_W1@Vl@7gw$$9R^>^L z^|S2q#3x5Q>V9Aj3T#rK?6JfJToS-?24Z#@&=VMd8}tXX-WcTE?CHoyf(GK23_-II z+6*!ppl2fzv(eh*d(MnH6uQrueBA@m@!9`Fh$H6D`q-=T+NbB?}ZTVZZm_kKKs zNw!kH*g_ysKP=zqA`xkT{W+)e!{Nw_v!2OI@lXkunaPh4@Z%;7WNX`I2Do|?>Kiw^ zjqF!o(-EsO%}hM0es+UhjQ_LQ*PjpQTv;)+lwNW}{=yaHy@c{KOYHob3`th{c=HL^ zWSD^KcGvW=fMGpI(67pA-TaB&FsQJ%DwpZx3uB7>rdf8a^4=I;zr1uwyMRz z8HT)sTFF92<}1ebG5pPR$H1|awyM);-kt8>$tCi=E6A|7KCjI@dZ>m8wm17_vR!NJ z`$Q5>BWU)tr-fjf(GS3on=s;Y^enG&8-0_Lj+~)&^sAdN2#Z zqzu@Qu5l#zIQ|sf0?nRi?)&hGp`!2zF>@zF_EyLRt%8|+F>VMS`$#Tf3$40dkg#F4 z2j}}x(Gm2S2s=X)`&8R-JEVm@zhH;ly@+UbeFr06bZ_fx!&Qg8ZVeZPjgb4>q`Vd( zCk9KxwJwrVo8x<+C8VzVTcN(^L0DM~#y-SN0--Zk_|+&_9e80s$Y~i`RUF`mT+Q=a zRG0KBUr&MAvrfYA7sFr1X?25lxJAsq!$1rYBSpB9^LWL|V*^Qhfk1nqz@Zc%`soPevoc{B;=W(wz4Meux4aD6#*0R{8EE(uJLL>NZcNz#vt zxZ+YePt3_}mWGy*i#QpnfNfJWr$Mc$MH4R1t;!jB))Za+t;$V)jMjw09>|I$>=ilI z5$PE=b2pI!Ug(csjWlcgrkqqc@-wpR0v6+lUY|OEAC1Hc)Oxtx{0F=}Cx$(ac)zWabDy1{}GPSa^ zsWQ_$#iWi93eJu8#tmBJ(gPik((mvbl0xEYxcrC43vS4C19aUZ_xoAp^1Kj#9@$qa zkYQ8E8e};jK#!9;1_JOUOtfEClC&`-pTZ>9bI@|0fTDUwu2?@;9{-Ul1Gd@H2uG-WTE z5jrBoE6IP_(gD36{^8)yFRrr#bVu<$i*_pkzQa(v0m))cuNl@D)U&gPrwUMubHP(f z3 z;F*lb=psqHW33l3#1CGhKSe2a;vJqU#8O7|bYx$YuHCqTXVkwVbP%s&CFc$VvR-+QV9|lDn#Ui*@v_;v`A&fG1(x!__EK`mx zZibiTs};Y1UAeSf#rd9m51)TyzL50*gfn3IA`C(yBL3qt6o0xjf4X?A;9zCQsxdzj zLZK8y{xsa7-IK2M^7Nlq{;iKRpCh}wFCR1r&rFwfwIv?k*5Up8otfhn`Q=5WoDG2j z(#W|zc_c>y>e*v5GU^4X@%L(+LWw^*o25AY9L`3;-X#piqoawN9k9;}W(hkS%solWyDN48|UxuNQDV?B<_9`{Cd^zB4(5!X|82b73sx?;*R*ah`t5O5dhb}X=W4{B;+%L$P z1w`FC2ppEYcNgQMF%iS3CLkV#LEXoS?R$~PMf{{#Y8+_QmnTV)3MC$zb7g@|tZlg-J?Kju8#-t9auLIjtyvK* z7J0?ec9NZ)a>9O+{r0#qLi>ZFvN!4DEaA5MhK!V+y0Cip zXTW>olGkLc*A=jfnI}!ax{LP2j*}al+E2lyoA>PL9lQJ9dFh&+=S{xr`eX zoVmKww|DE>J4Vs0`74$UkbwI76(*fV4k$}n(eVVf{b{~gw?bsm2|Qbm8meIO0hg*v z{vONMj?VL0Tw;l?`}Dmq6RbPJYR=8e)2!K+EuAhlgw@Esw9U1HZfZIMytN~5$<@yv zd4HCzS72Dtj%oI0X|Cj*-1HPb%A&U%-Pvx)6AHlv9k!hIcbDa?Ca@n?MDcp~t>&?9 zcQclgsm)|Ro+u(7C`<;Gj+8K(LLkbalD0_9YSL_M5Nn(}hqo@WBhY-+)rAHjY zMk-aXC~QkS&C>Agmp+j*^H?@F%xce5v|oe)9z}w1!X#)VEe?TYe;qc)t^v{auNj(VrATa$#LK^(BVWi! zBpVl=*oZ}*b~{rjPRbPWb_dRorC58QyCe;P5C%YkFrkL0L@uH}EJ0*zDDe=~X^cd_ zHtPE?tU@9Ef)f44YUBTjRsMg(>i;E~{EunjuVA|<2lr`W8>E0L#0PX;-LBV&kUg1C zzou6|Mi7REfIH(dVpGRG^ptqf5XL)78cA|@6~iFYQ4!C~6$)!Qt=02N!not>^$MZ~ z2y3-iYq3`zW!Y*|5QvFlqtR--$CB5K{JWQnFfqgOEl`5VsjtBjW_Hid0(HR`va zL6KF#r1sQ=1Z*ps<-)OkjExDG6^5QcIUsJ~_+aYGUCW-cKk5|6WQ0eHfs9@7qJiAhrN|Q;| zr%hC8C5AsI{3dc#WAFWkXd$CSFYqK`&!(hWY-Q&Q`#5msJ#rCiMUMP;|IG;Cz|gOb zX&lq=a6SJ8EJe6xR2QM}DE|&Z1wvQ*FtZamY;mr)Qmz`MNs&PW+tp&>-wuS;5DA@= z@6Pkw|B#{ow+MyrA5r!92>9K#`*#oeKT!KmDEzh|Z1N#-Cyd!_rlvc8R4R7_39NY2 zA?=id?GsRGZwO5I$26SAPO)T+62ZUA3Xm&7e4AnZ6qLIT8$+H2h>cFBIi6&CUQfP% zxH?1ca&Nbm?ixe0EI-_g_XP(?gM12RGuFZg9!U`u5p5cmUJaRRT_CQVIko(OdeVQ& zGVr05IVy4BiapCfBN}A#P$!G;maEf|73)A7W*>M*g|CoNL0FN7L>C|0bzV>^9}qfh zE2Q@9k`ne~L*A1E(PzOiHOGk*rr!h~Cy?@0Ydb^6B>ZtYWtq}pYa4t~c+GvhV&A%93=Ut&)?l&5SzvImRt_c2TKZ@YD z0^32~>VL5$C~Vj)@WF9sWZ*lPD~@jgYuJcW=;uM){s2%W7Zced04Ng*8XR8Z&|E$@ z>wB7qaT4vOPqV#?$=y|(uHFGGUsYiYGPahZ zU6wvMvWUYHDoIk9526)gZ3z@)mQYEu<;DpGqH_O_4X?+vyeB>jb6keRj4B?%q68@5 z0RvTwTdoMu{?21S;j|+g1OzHlyKvY9WX^cZf}9w4HUyv4L3;aF`j!G|-UfwN z?7XVIv!YBQm9tV&KjgUw9zpNS698@`P$(HkS57dEpL;%1lc2%#G-Wj~LPX46{&&WC zA&U<$cu0nlGm_YwxveQiBuKJGG-I6p7f(DncBnKcSes7vkkY{&U&I+EnTD_7=cB&# ztEhQJ@K~^qv?94xbe>#9eU!kdQtvvq_IC?bjWN+cNWQw)yajA>5<*(mX=D-N*IrCe zQwPLHQ<}p!<)wam1X!7PzVXQ=fgIS$GYJ>u<1dHk zuNH5Zt1J0NaaL7g9%=;V(-5=04&AL8wTfA|KM#Qz92 z|J|eeXRF=+n=aTom>W9&txZ>@=4q$2g#MLvv1L`SE{50f(?y?%z$lV!pyW*#4V*gc@CL-8vIka$&ySl0`(m_oS1?o2aJgx;eJ! zM?qE@qs-;?W>*JzyxMOj#%G_Mk7@Ru*Y2HXHdDu^9oifaJLc`We6)@#vw@Z)%NXR3 zmuN5O(HYPBnlHo$Udktf9Iq|Pqc`eSTGZ!*pOiR*f-0*wwZJiI^1rs)uzZxJ-KC~| zw4%LN{7Eax`kxP1e^P4P76NlpnWbFt-=_@cY(A2gJ-(q}#ka#qGRtbxnGGSc5$K8@ z-7qSwG{j>vltc=uq>srkHY`Zx^cj83>p{ezPb#_=q222Ql>H8zHUh>XH@W(xbrKoe zx;~5SvM_l^@CH!Fh6Zr&cCpngXmOV=u`TP3AEx%R{wd3l7sTCXCQFAN zQN|4}iw7TN#xI*Bv%W}^G@sk9fVWcO{0xLJmP%3kps=js;>1*0?0+FqB`R5oLf0m_ z0!hX^2d8|*YQb&c$WSjH)db2CM4q;W1`X1G4oENUgDF5h zMzoIjECdiXwNe;a7AC@C-pGKl;D76!IM`;7FWg85R~=Tat*s$fPz7MpvZ5)WG>F2Z z!-J6nhf99G*N{XqvgpPzIkw#1ox7ef+nUvzDgLk|lF**jzN}GwtjILhIc&zd6kM>? zZ4{X50_;D(%$JJO?(BHSnBOSD&S%{``Kx*WL)NUWc6ou?Fbxs>!QE590=F+pa!4Yx zZ(lSdvV+?!mtg9dWHEJ6RIi!ISpaW=P{`^ENiYdp2Yt+3h_|(A{bt%O9e=6}DmV&F z(|gW{s&v_MK0qBc_=uux6NHy#^@jSQUY`&ErBiPJmfmV0hR$F>C6JoUWFUggW&r&4 z>?dnQDg)r6QzX~aoRB3`HF2Z01&JL>r_n%+{k*?C=I{+-+v@}XC5?bKVo!yEhJmAy zv{_%I2&R`=3%*|~bV;GNPbYz#JN?t?>s3^XXhD>pS_=n%5pKE? zP5a;>bS4tntRVu-gOjHQi?w_Jc-yWtriXn-?|wuDbQ-V&I{z2?cKx1pW?~L+%O0vj z1SM@=<57D9z)^}u;suXxj}ex&VRsoP8UsR9Q#z`6aD|5eGXr!{V;+CI&LVb z5m8$%B~}u0ZmXrSaaw#4`XQ{h&1@L2)9Os>5nV^woQn~k(`hpV@?sim@} zvZA)9Hm0K0S@EN;Qp2)Ir0C{Gf?S94y7d|g80k_nO*5KnyA0{{Zav6zkqyP$#W;Ao z0(-l{a+CPwIkH_VDXz0DL62NLzv^ODecJjKqP5IX-FN03x6LPItmo~Z5%$)vjw&I+ zDrar$#MvRGypirK?L2jvMSZ^Ry}jN(y`Ef5VcXEl`pHViL9!<8!cM&)5V5JqG`nwM z>nNEZ1!jByr(DGL(v9bZLv!82SYz|g7sMQrUIzn` zT{2+@Jdn+N5i4PgZL_rm2ia{bgnOSl7sPEo&k>5d=zP#oYm%*|1weP0%)HjxDSJf3 z5c~8*-i3FGC6v0%3ci{as9rNnN1|YDd#1#1y85h-0h$taFC=%F5=thJh1#ZZ_1ZHq ziPthKt!lD~DVT_-pUEQ**7k++DnAY&AX8PJb}*_SYU zfV-56Vo>@`0-CiU6+M-6fT3!n4_U-cN53olZ7#*xE#o_gStPw~?z;!f;&sr;1r?cw zbb1PH$TfjeX&Y{|CEBT=QpJK8pqrSo52?5B&4UtZ@c@6HP4RWz&ZB>VdZP4NJ0Z<;-Ksy(+^ zYj?N@lMso07wKiYT5r?*W7kOsk9Yog+q56On&Op=WLt&rj9fjaeuBT%t2YjZJK;i? zhzAGK3H+pyg9LRS5>8GkbnX0|jo=jyXlYv7kK+jRYxvx6FJTSXY>hp;4=gKBufjX} z%ATOo0qxCx&E!r@T3QZ+DR03>4neqYF6`IfRw3X^3d}l##YQidgdfU;9S|Pijt(FX z?mZ6&xmV{jS{mZ6#u|@ACMf+qlGW#dkQvm1Xq@k`x*jQ3iQF#kP$c6B{lY0aZ5P1@ zYa({IU9Q~ZFcv-NP(O1XVGN|A%5xF^7&(%-ip=p}=H!4zHd4BlI@~elbOlD) z*}#_1sc4ro62n#MLR)YZ=2MT2#p%n7dVZw?0`f5obs!UBs$exXTVBKYfou4Nrtv6f zE;NHw+y?tx5ecWk*~msnYqLWfEBuF&5!&r-(Tp@F@~g6WVyI%ciSm;Mqb50nnJc?i z6rPx_C~T^zY`Q@eWs`-S@h7b6n%*8mDOosyJ&{$a@+{r)Cxk7Fi5nDQ21{W9i&UD8 zg6KkJG<%}F=)^+H1x4({hv1E8(tlb!=(!{Th1SF;yT-^_$EY1?oZW+s-H*>i<)SCt z)p(;PL*h)0%dTq62TtReCkn_~){8DUendEft+`BA&{0lM!$3|{7ma3C(xIZJX~RI0 zTEIYdbyw;_Dxse6c)&#%FXN27U#QAou!{3}`3w~zI?g)S9oh%4ORhJumy^xWd|=Wsz`})2EK27CcDWHtB!2|1L3dd6k8zW- zI=R*FKhatdl|h+mcWS^h#bPwTN3i6uiFi@brVqz8!>K(&W}YQA*6{IqepJS{n8Di#FL3 z$hNWrKD;4BO38(E=;jV>vLlL)hnAG0vZfEy;i4fv)nCb+tj@Q50bky z*l`_SfPdv&v?wW~4d1dgRHXka=VJKB4E+C_Kq2h%oqhc~=T3^7kQm@Y3jR7(_H1cV zwnW}~6bV35MTRdIC?v~w;f)gHB$g&hdn(%m3*YSry~!I)Fh>?(^DtdQSGr7*`lE{RG=vr`K3dbwI` zV0uh}{*#?2cg%XSXA#v&TKzCt28Dv^L!kMSI0&g(K@4wf_B{qaINv2tvz?(u;E^}G zYnYYi#=~4V%0C^Bw zWMr*r$|Q&!*zqFsN;gYd-zjrqs!-k(0j}4kpOs5Km`;kIt@5VlT%Drx2nR# zvNI4Ua243G&KIYDVX4`vHmifVeA2^`WcOAyNWlc?O3;{dV?`eiW>I?cC*;f2>+CYH z_=--kfVj;8f8NQ^gUV=#h`7J8`JbqG*X6sIb8g=gpvBenTUHvEc<_QIbI#(njjj4^ z=I|&09vlLx+h!Blj4mV_2|hZ0w}wGhf}dQ9-!{}q0$BQ(NqZ#sNZ~{9A;B0Ip;-GK%w<^7gr4^Dg(x**F zjf`nWqRSfjcmc&$GXW$)Oc65G+b=(3lv4$2OM+H77}y6J8bEAMaD~?S&Nnux2`pLw5#=kDBWJC%SdlGN z^f0_a$&?7-POP^5=O{qGs?4bmE7=0%%~axOUyXhAWbkcD-~K#e0k|Q8||@M z-)_@;7h3!+nhWD3yir`I&ZzJ_;ajWzgd5g?zjq82c85`o9(i)v)bV&%W{PKN~#Phy(N3k(x%lPz# zxQRIR1@eFv*oyrd<%@4cEmNzkuR3^1;-CC%Qk9y@iR&VO`U`%k7Zz1-iskW(bab)|QDl zBH=cVq>Dxl3w2#|#xrSI%7t}f5o-{S0I=l>Sb!eokF>pWbhPvukRlYT>;vI;)~vIp zFxAJz*Q>9TS7x;&)a8pNyQT%srm*cnsQWn)*a7Uuih>wa8hdl`hFB&_bK}PL4%%Pd zd#zOYwqYuITqOy+;VHTk0vHNmkfk3*bLnf8s1Itgm9*2ybbvxVQ4w z^m$;VPQe^ z@khqp6qP+z#Bj;OOQ9}3ly~lxT}fuIvS3>IqGaV;ZYPCeU6MYyGP*_UBCt~6$~NTe z(vl7yFP!dD*<0p09|UO9Jw%Wk%ceynYb7svUT(i!Bq!frH5~!*2isckg=P`+m5pRk zZ&7A);4-3M93(x)LV^-z?c_*u{wVB$iMyX>8T*RsPojVldI(XZb1v|AyX-I8JGthy zJX~RXU%->EGHMx?%WaHR)_$8r8tpQjfHUZFWJvCz1h7KhqC_qx6eRn;xRA8@Niv`T zSK^ZyAn*kK6+t{_NRQ@c_l!3O>ggK;O6`P77bj+u*(C}+e9)d@CQoD@w+sku!A#MH zU^NP!Is-hN(e|BwB{w8lUXZl=KjGgj)S0FVH!= z3_L^EhmWj0hSF>&Om9E{gN`T@WkXYgF6o~ulcJFJ+5I0xz+ty=!i>21`}4QI99K$* zREGl!&)i~_(0TF0`0WR#j4BDTKz)w;zX^=f6>TMch0yD#UsEAs%RWOs(JT40Ze4U? zZzTS?J;mx9?O%a-Ru?+quVF=A;C~Oq|J^R2`^P~1w{`*Jzi+joZ->wKpc?LlWSfra z#(mI6iu}se{Q4mZ+%u$hp%LP9}a$wqmqu^kiJUpRudg$v(G(LaN#^^KF!XQ(A1ObdzhFC-y11x3}WsQES zb@n%ZCQbZlU@A=z_Pb!85!-gd3*W8tBF6_%%HgxDe7rJD*+z?S2bkFvqo=`${bjAI z|4h9SHXt4){y$Xde^0$Q|Hmj5Gjw+Ok4XKGHp>6V7*zhFz4HICS+e%Xj0iq*3)?P^ znrcFSGi)egN*#pMUS>T=um9@TCE34@05ZeYRd4!w9c>{1$J!W4OO-+=s zo?s3Ykf?a*dN#3*k<-%r1B_#68@9Y!LOBh7+Zd5jS+@P|EFKvrc2Kkj!7!=lwvW>m z*NH>R!f{iuZ=6x^jsJ2+mE&q6(t&LYCnkkvjwa<&P|eWLeDJrECn+LFiTkIs_*9cG zi_C7`{_fmOWzMB&q4NBsREIeF1Z*2x71318>&wd4ib<;t+wl)=9u?Hb4L<42NoA^3 z0T>ha}FzBs} zX^3}`_iKqV%`E&IBKbDA)={Yn*Jg^H6&WBKk&e)67HH_Tv+DS+?13(yv`k5kJvF)0 zLz$0%7$V+&!|4Sx&vzU>NsXRW#+tL_tO%y;vw1zyqfH;lNF^V7*6a-5yc zNb6*M!d_AHpmfjY=}V282JE&7(FgB3wi9`Qv!I!Q|2*>~Y>MQ^|HX;qe~FX-jwb&z zZ}oqpiLkwihq|Gq%m0Rw6lLju(zbuM56m)CuD)g!TtyWWN)3RKE=Nd{th4T-tkbKw3`o}7{w<9it*-@(FA8#^GP-4z&1nAQ|~7gsEwNBbU<0PGg}bi;}raHcL12(1!~pD`pHw zr!S18FgTUjvxWK_qC5rN+v&QGG(CI-P`U>}uqSC>n1f5df0CAVVTV3LS)?@=i>g#v zTIY@jKvL_(ICMu;N~5_*R~f)*^evZffj7v8Fbjxc;ZRxks8)ze3(*=FxG*<<)k%S0 zu`fIf&7Tvdf-T(xkg!Y_d!Gm3Jlm{17omo{MURHP6$5Hut3{||VGY(G>iNbLD4j^( z(P$9GEgr1oyWJ?^ESXRxEf9%GEtQC>L>tYOo#Nvu3nVE;qbwrxQdlLG1A&Z7h#p#@ zWGj1Ep*`?Y(5X{T((K4C(F;geEfMF7$>@c230Mhj3Votg0`-H2>2OXr!6{qhrw5Bg8&|r9n@GU5P1Y;7}zM(W@o!*GkG&ORA|S@z)5#6>zR;E6A%A z=%8-YqfY#1_*)~#h-LjdO#iD@+kdBR|L6MD|DkRFY2%##k8?wb(zex-00!@0Z1zs; zjZ*7o{-355ikk2OchVH22yIxq&I2jRCo48gHswT_43cL|Z=^a^1jKXTH-!WChWwWa z{IRKQXENu9oblJ^%~NFn?6$>W(y2dl1IKU$)S)w*8ubkphggHi_D@==ij9+Tyd~s# z{3nV;T@t1l6VUXBrVo8pQW>5B6C+HgB`lsAP`ZN!u_0y_IH54t;)+zxns$sVt1GXV z)dItThGqoL4eF-G1^V}nQd0K$M7cN4w6Ofhoy4l=5?2z!W`5sW-^9KH<7Ii`6;vjC z>!_xMM%b&iTMqSsS#TR?92COb-G#SLc6OR$SWn!wyR}u*$J~gPSUU7*Z{D~jt zlHXhv_K6?8q}v7nLC7cVbAl65LMSjd@~``E5+bC7+x)L4?r-Rz*}WI%k3yHhWhoU_ z*0$dcce68DFv>wcf*3G)JzKu_G%y%!zmwByT&3GhH=%R71$a#rXuIu)|e+P72jSOzFkka|8XZkG>mTV|A&u+{{9Yg@Ed*M%+3 zHAHq6qSQWUo8S#|dsV8PmY-U-*3C82&2+jp*E>BQJ-=JrNrWIGv;+UNmB+umk9mIF zr?I>5ud8C=+&0M4;fdTV@GS7(d%<*xssOaL5p0f8KDIW5!%e;%@md4%2 zwtUymRtj@;N!|8+7Iay!5Z!$n=pCdo&v~I!?j0?o z78Qp#M8|I;ho*%m34;bacCN$l> z^F1`3@Az<(PS+4Febxc0-dvr`ePxtd#OmAes!rDpl6^S4>^)lV*NEu#0qY@DX&Ard zLF<7V-M!a+3+2k=B)-l;+yQRrJ^4-pf7Suf%}*5N&qX1e-pH=bl4Zo_Z5QgV!~FAs zpz_zEsNy|6-Op@9s^6o(n72 zMPwWJxH=>f&$AlT653do(GZz)DA#c;@Xvol4z39iP?EP%pu;>@Lk|>vTd|w_Y3Bh2 z14=czyj(4`DY{6RxN$Boqn_cXZlGc9GMK$A7&f@QP%E47-7Qx8fCN7P&J1eL>ozsm zjg4~%5Qlrk2-ff}L}6*IDDcpW9m?kM*A*x2?KtZi{QlTeM4yLd!wrcQ6Dw`5|8pK> zC!-9#s{{7AAL~=N%_mU*o^de2uETIxWGJ#NH)g!C8EgpH__5P#Xv{IU ztCN`lY;GF58~LGAxPrbG(RMLVt>$OLxQq)0ZT@6uvxT*VpT2>8cAM41y4*yI{QHES z-7ps=zvK^!ZD!NAVhFV-%LD3Ya2_pm(GNcbx`2-nEv`8P^o6r|kZ?V}hH#YUMwRM8 zez8_-E6KaLwlfoNa&8ml`Wglnc5rr9Zdq50m!>l<1EbeukdRmA%b}PP)&1*$!o*0s zrR;aFP~J+pu*=&bdr`s!w!nwMa za{;#z%)du8$ULehepaBIdI2Zub-io-s9$Ci^TOZP^1D&o#vFXEofzfzK+26}37(J| z*d`b_MQ5u2DF=1o1H7$U$Eq92tJIV~kt$9jzDZ%-Bx}ha zdOUM3!-4~dkUcKrx!{ft=={ae!`GrwjHAU?T{>-PXaw`BASPf6>{;u{&JW{N_xt(Qj=_DO9> zrV;ntO1~|xt9F04jyZUubHim-;kPg_?YG+3Fh1tIkPQ;9PVgEX7nSBWHO-A@xsVYv7ZNP4 zT2PY5rY%wpFP%z8x`w5^42z3OtX#EBh6QUDFlvO@lFc1hh?EbV!uROj;ea&fgn8t{URFJ!E9#-Yv$2YbI`?KI>39HU$E;TB4) zD|1pymTu!eA3g;eEyP#^V5LtiHn#dCH8wVa*TxO(&%titocSNSbMkA807lHKTcPgx zZA42*wX~9TFr`XDw$-Pjbh!#>tLWyfWk!_i>n3y6cX?ZD*m(*2Q=l^+scPHvHK^5L zOkMO>sLThw$AGd`I6u!ZqfBPHVar>=3b7GaL1}~^`P|;KZZsp=Q7aQZ#^3JMn1aIt z7Zg6^wbyvt*XimSjyMBcYi z`4@WblE14hW8xbIHV!P`4B#y=fBrbyp_-h&@^w}F>}U`G^E;`}=q%YX(%8;`=M!06 zf*<)^P~I!}nOEDpR(aDz?G2F>rSZ@J*t?m;%hMss`7OKi6B!SGmJY8p-m{d;0}H-t zpJ!7#Yw+El`BJ}efEk=3dblur$GD0tfEoOCrJD{zdVP`L*=V+|v0W`ijpN9<40myk zH5H}E*l!o=?ry++_Spn`HzEEGVO`lm3?RlD@=n{P8pT#)KHzV%VnDgZmmsmcyn+K6 z{Bf{g0J=gt7UK@IVmLLLp&&Y%6CBLT ztjVfIJB|cW@HBgUC@DQ_!duU3PNj1DiQ5xA;Y5Z4_W5OHq%*7@KZugRNsLv63a4zV zi>ut^8GJTALnx+##)Ud6*%=gcCS7Ux6H~{MDr#G*rg5l-M)hJ#s(WEiEmg4FkVFU~ z2YRuFM!hsssz_V2pxT96c7m$)UsXMQ!m8CmWyU#*j1DVBt+u%%g>7e%c^=*pt-G5; zCYMINb)l9ZW(o&8Oq0%fYeI{nuu(3C*_jHNcxSxi#)op+!Z6e3fm-1NOKYR*Q2I+e zcG>#2onuDZLd{b>gBR`MjWhK(&08ij6GY4CNWhCmbwrR`q<}G6v+a~&oOXLU=TJL_ z!GR`uyI*S?$l1{JM1BQKd&>0$Tx+8;C66E=&8Gu(Ckn~V5A*W98$#Ap~!g&}O7y&l-`wO%i?TQB;Qaz2%D4$N>kTqgu&FhQ*D$TTpi3SegX) z%njb}IQ3Bl5<0on1I(~G1Rl-dQImjzI2EY0K6>`n17G6SJ>9xa%(S%jrS&FORvKZe zhrN=uLcrPf_#`Vxsxpo1bw&u;Wo=lU#XH7&AGnkp;o}7sHr9pqW!5Hpb4#`L=90?p zKV$`O_uDP|{ z;oaJ|LltM~%gT+?5!mM}tSsz*&*mj)&6fcd%M4>KdOF`kVLKXCa+*O?MN4zD>v!o# z>4z#qfXG_H;x$D?Kl#nv8LMpzYrE}qWsB@JZ5G>7YYRlC%Lg?;Hg|ne4F@QpW!f%~ zrla!tq?ke;#|BEAOGD{&%dO|a2QfF+Co+De)EBudo_>)G!wy2kC{hP=X553Bo9O!B z+xMY_gLg)w*amdEFH>;Lp>g>;fuRvgbnZ>+B}$pA^k7VY!Y*4y$8~dzEP|o&;|1&W z%FQ5nQ}b#|i@nzN!phpt8ql}KeSed^cdw}ipQ?i5W+rJ%59?~PZKbV6o&9#Q4T8(Q zU*zRDEfd7C&?|CfPelvvikiA#PyW}*hiUV5jP>Q{`D0C$y-tfx3k#ulv%QsNC}cCs z=0tAV+*ZTr>s69=fxos8@QNTAMI%uJzmx#$m6ekclGLQ=l`p)Ff3 zkUXzL@DQO2$_I>;FxyO7mSRT@;FIPDPOjVs&$f~LPKYB{u6arf4s+Hr)pSux%vD)- zhP!7|WMb|LZzjjxjlG#KrzD5G+?u}=v1~px1^(=~OM(dsK@1K{f?Y{>c>v9}*eA)! z-!s<^U=){!`JD0!e@FCf+rc#$3?4ptU6r9P=E+F9_$gHeKQ9->bte^g_oqNNc#m@Z zha4bJsAGwq%AxeVEc3@d3%(uT@+Yp%(={XtTryI73>9&SEl}0K207E!(os|cXpg%o zF|}O)kKuH~SafAB9Y9-k#ggu5K}JT;$a9$jibAh}?Bg5g3PG(QO*cvIaQUjj(s=RP zepV(Q9Ah2wAy;GspDga)U>J5_jk5sjr+g@l;Bqlj7~q<-74h59Ca(dbfCg>&V{icL z==>;+^to6WoN$e674fjZ>#Kc-6bv}PjYR@%4+ZhO65zHbUN(mh|6G-07P>G}R`LBE zQx5cB88`=G7Djxp{VZTwZjD}E$BN4+qH;rH`9Wv+C5)W=6Omj`%IMeEzMk}vvLK_p zAlMktHq&fv)C*(G(U{rFI_6THGH6;%B1- z?xi!O=*b;92~&cnA_Fethg4y7!boa~_BOb|RtF_BwxQt2yqX)B9!W*fmcI42t6tZf zyoUK@EQ<=WNXmZk5O&3`;Ssj+0q=1E-hlVMH3zb(x8s9)fB?@Cj*^QB%*jDHxhW-n zIRd|^0JLkX;QUc}m@(_Q8D!4gOJ9e?5GCblf{(JzV@iHo+D#S=$3sLNhS2);v_X!Y ztd&F*KoF+_AC>z4{P>up=!*6tr%rSmgy%KmwyzKbO<J@}31R<1D5|`XReUzgG@$&vG)~c-0&Hv-V2dLQr^*aAZ%EH8yb7U& zBO+`~EZ!mmUe_@F#mbHrA?sj_bNk5j*ILKHs90#C+Ai{H`eu1!FipiPt=5ER>TX6t z9;eVVSUsJEaetZ+r_e5-8g!#>=NYk8sla=}a8s!8jOR9wJ)ds&TwD$kr!@aYoZy`) z%6vW3cpGKaYokKnk!s)jgJ)Tof>RjNIEWnPX^AkFYcd?+4e4OHXHXz0#ZX_#JW#Z}0oS_|ufMoz8N z8ey=PZrB5s=fSc4&H7C71D{5}sOk*+3FD6IjET}HrYD1iKKH#1g(J=rs3WTn7D-4Euj`S z_=+5-r0aRhA(#wLU3`5^M9Leh;~CQ_a#pG14d*yYTWJlAOjxb}*QxELn`E=hrX|Ys zgE*}aHpy+g}g3YK-3!F+BL7f-#CCS!al_Jsf}TccTst9)j*&IVgOwgQ!C}1k#_`RQ!B|x z>)rJmr<$F4kCD1-gSJ)q4uG~n|3z^fFq3`b^L?`%p(6U*3EUJXKccAAH1HlT$u{a; zN)T;ZDnz`(fY%L9xd0uS_9?xjhxkYu^#Y700c4>14K(V(1$Ct~OJq06)R(LJaCxcxkFwpE`cvH{se*eFN(#*wQc} zx529dC0>|PW**TTDUum-*ix7?VVIdM%9%kv7K%qkbdS-JCd$%4G12KmvR;DpmF9bm ztaUQ>02N{{sX0>!4q*{EB!&2Hir7sF&-!>F2c!sM-+`u{y+mw1RL`gD}DQs&( zC$oI22;kya>W`8&EC}q2JxqC^uMmGTAmgJGCQhz&ZTxgRp{z13M-p%dD(2j1brH)S z-V22sVwV=s!xBY|1%ec?YF|uKs!2#l5M_Gbmd6vH zuD5fIuPeg``~u7}4R3S+7vp>F`Zqe7p3~&0Uk@n%b0h&FLc1na4h!J)BD$yho7=L# z_ji&EoM;$bq=F;>Zp}Nrw0+b#0=>mMnukJSw5cqA5#~B@zd^z6 zENmHW0rY!_Cx@_QUw^fHTHP6`R&!3|zuD<2zW!f3ThX(-Qs(ypxmQi(-0%t=t0LBP zdQ-fd2s>bPGs2Gn0^;ggFn)uBELG&`gV|Hjv$rKO3{GSll?+rl-3_bR{;td;IlR34 zcrbfEJa!=3>o%>P&SFV(-w3>vqXwP&qiit>nNHbE$>Ie=zryVk>;{u@hMPT-$|<7_ zf8^(QjwLIVdqk;I?3J?~a5wV3(>juG=hcoWFO+jj1&=>n+8=;Bq}~a2>%PM6lyVDv zCjPplJs5Y0zeD;czEk2Vmlhrx(};`WI!Md8@dwOGZbB65m(0qN zMNy`(RY96OZ>(%LpA8Vw2kslKnMN_=$d&gSZj@zm!|HmCzMHf0Y2CQ1-4l&-se-b9 zH)2tj$lwc*oF~Dh$ityn<^wmXX@UF@H3Bk#eBCi+&`}kK9$Rzhyk+9wJPzMV3Sm4Q z+aqjB;fEN+I9GDh#?!Pva^5DDU*AP4?YXV z=wzkSl@{Acp_=w%?YoA6+Uq~Z9L4ck!kHcMTNg%|`727X9m(ESxU#C3mK_@cf0vJ4 zVmBoISm+n9En@v)wN;ue66A5KvOY6wjy_N5GJrOl8n;01bn|CJ;2*IX4o}Srbp(s<@`&%lhR=;)LctwMTT1;;YFtJc*+v!d_AjK(+C8}9Hqei`!f zo zhtzUpZkYGz)Jb$c8E>#X|8s*iM5dl|`h`=)Po$w%=$M6P&USy3(v8$>X_<>7M%Ene zROUG&htqQt5t`ZaUJX!yvyeQyUb{%;QP0s&KAbaqb+*>qMw3ypoM4D9SoJu+;ydm(!ibBxlLu*qy_uINoIq$xi}Y`RyFy^Q?=^H#Bd-PfD)Zuh?v*Um5z6-`wr8-vYPA zZ|8@7!9d3Xi>ir5W_tO#5ms(Vrn1%OB};&8d#ttjc#L$JeME)Rq0<@m zfla%k@>y?!+Wkn%oUl>mR-4iXk%}SyLYL{<-nml5%3R6-J#rVcMOr#xQculN5Q{B7 z&g$?IrIaFdevV54h43`EOS8o3%f5&cwyN;>O8|N-n-QCp^0^_Gc5;y#%=1*zgd&k@ z;eZk(D=-DRAZM16>VPiME59l!)Ax?d6-Si_U6;5k{LA$9^w5v#*g{OH-Hy+7@b+r; zw!A7NzRJMpC#|YcWNROH1$gJ>^M^pGK&l?gpT9^PN++no*O8qKi?zvO{45K*xG?qT zSCFY5(p>>~_8F~fm*5#lnrKCkLuPnc<;iCEdvlfiVX z9Pn6Q>J|NZ7I&LULD2dA^wO{|f*|b&)RU;UAO)*%O*wD0_b7Vqf*YOj^6)g#xM6iU*Y);<`_YJo0 z`y~!SF9Wv!iY|?&84;y+=OFS7z|%}YDx2v*o9P3Q^tMH7+~eHM;7~C75KKuX=fcYD zSpkP2%nll6@mAQT^)XCp-j>+MJN|BJ@F*L%w7?nuG~X5%X4Vd6Q(4f)xtp-sV-l9x z@Z5R3u+joIbHJo^4{ERO)?LoskAkIAssFJLqv}5n92^?l7_%;s`t+}K7pBF!K}uD^ zS|1$h`#1M!Z{g^`bHQ$%p6J9d;cEM|WjWT4Y#&x!z_a@E$2X&Qz>@d(th!L$r3ZE< z>fIFAw9#K`A-vQFF|@mD7BHYkFp5B^J4cVmH=G&9^ZH5h!X$eDl0@VRyCIUiLCM~! z(~qhc##apz?fXb}gC&2^$lkfrk8TYU?FUJA10;VS$==n|4|mV#H+DlxzkxkQehC`#lY}zd93qB#3d<&9Ta@#^CFOqqy@ylw)y#Avg?YnlNS{VCA1o88 zVbP9>jUxT`8+&xAQh%pQg$rY+(L#SU72`ID96AI$0)`o`FN?7?h%)1;8?eifZJT5} z0>Byq3Kw8$(6ueQU4W^FhL@~DKYSZ3~NUcjY4M?&?qQ0~r z1De=-&uC)02Tm=JTRQDYGBpEpWF(VOsoyqJgTHG}=19cAKMWs2G@kp{buFp$$xOaF zRdrc;3uAwq`D@4)%ae!Qlo{~~lz383FPSg!_@FIc{I#UKi19RiXk*=!2$rZeR~^731$iXrK?WmIcTSvWDy5jag4z7HEslsXhS>FTL@rxkfDy?uAev2H*v5 za0_y^?e7C=pbxdy3HTYw9J)=Tb#-g&wWs^$wYj($R&lO2!6#L(~yeCaly=v$6z@wQZxK%-(;`0?4xGU5l+YT>qs@7s5yfL|c3$TrS5 zp0Cs|!fqMA(CdkQG3`m1rP?n9Z}ijcd2oEz5xQJaY9n|x-FB5gwqYaneerKFD?{r} zr>Hk`D~csMj(#YSg^C0PnyWe&1GC3F2~y>~qEA2DHx zAQ+@M9_5HjTV&-wRAEqsz(i2wzMG-$BfSv>9nt*KsR#N7CWhx@M7uR6XxGP`7qQRc z6y96vO`4Y`ntkzNb;W7sAhOHG7Fj+ygDeFT5o+e6w?ZngL9O#3>Jy|g_dGi zDOi{+v*`klF*23RjTR*dveq#;|75T%;XT`->QEifl4IV%hjJeMO5(>vK!9BPI%Z?m z+UP3Xk}l&>$PfhQ-gL;@3-85>IyMPJv-#=a6V@G;E_^~P_DYmO^xTxZ$3m&1o5Y^B z{GC`nU5JxLUf-?3r!4MqIyck9mz216U&1D%xN4|GmwYUki@k47%vQ$jxr_0J5? zD(8T4d{q+y<}BIn7E+p#Om5x^W9TnuHCtyi@OXWO=(0itJ^+NBc@?IdD5IXP?DIpH4U zZf4b!J|9)R{My(Ez}~sie#!Z?;ZxW2Gj#!<4KHYM#lc+@7T0nfuE$f3_7k6ii(9u# z)op(n`f(+!RChHZy$m>4i*?pJZ6oCxfX_`1Ms^F0(aJfXU*g*D+3k4tNAjkF%Wjc6 zug}%jXZ|?#Go~GrLs#eh5zh10X4CHc*=*pyWV;Eqy$ze$6-K_NVd{zRqGD$xB0L^H zKpKy?hNP57OWR00S%LS}m`ID5yar(TFs>5%X;8J9imQpPEBjfa!hFIxfXeC+7R#E) z52{XFs%xs?H~s}_LvB}M^Xv0UZ_zaTJva>cY_sIbJP4;A!vc%_Oq31c`)3^0%E{nF zkBU=5$YMWA&GmLDid}6#>WI&yoFG%7lvts8l^K&KWHhT7dk;kN;!MS;SL}a}1RA5S zSaVO6W8Vb`?UBS4y-ViD43RyK>Pn`*W?2_+tv;^5lijvbb={mB)@^|GwV6p2?sSTw zn8`^Qoh>OQcaQi9ZX!3X}%~`Bd(I)6O=}Udt zh0lV#xg;5hlg(WP`4BU$>rNSe~60b=xI@JS35xj9WP2jZ2);gs^$AjnGbQNr#9`=sL+$T-8J9(bgB&=x!4Hk}sD zB|xJ-hqbIP&SdvpzWz zyo2QC4SmA8?^tjkMwSegI9H$kujYAp`T$G6@Du4NK1R_P&=g?Nz|r8z08)U+0LXwz|AxpX1Cjxk0+a&D0cXQ;04uT;0J!#tFo52Z5=zF!mV_a|r&QrKZ?Nm?+fXx3_?z6uR8N)*G6%~Gr1IN^ByC9(^VS!`QSjCz$ zCqyY{K(kd^!Vzv&MIfg%ets5NN|ZBiC&-%8kGLLp-%EhKgR+j*ul0`P-O3zryx-K~ zS~g(4czIc!-IHujzIhn2G^fCf9XBKcT%Cd)GrAEf*5>Y=RpdC$V%eUrn027rbs=o5 z!`FUgQ-^F*z%tv! zyz39N)Lk(rj&x_LjXZkI+C*A~yE7GHL^CATBs7zVL>yB;x+Iu!mg4g{#abkHqRqma z;DZxv9VBrK>laJ3fvgkqJ{&F5CW>7Cn-(X5It7j)E_)f{Ob{L0jAI+}eJw^>Df#&D z?sET4=t0i5JCeJU659<)oiTOm^>&V9X}H~12US9#nKcnDl6*t!%*@-ecW=@!Vd5Rz zO*vTqRJudkz3{Ay2VH(+}P9}~^Q3j;fy-BAFO=u|i zrXw@&#md5<6H}|G;tpfeP@}uJb#R{bPB@5d-If7&#EW_CnPCJ(Wh4DGh+MZi^q3U- z(OMttjV*516RRC`2sa}3>D9pmY(U(|x$z5ru`-7v2_h#;t)w`$Kvu+#42pPPOW=0~ z@tu^+cjwq+g5~|D!%7ziyA!T8uE`BHjC7-PDLf z$i=k|YXgQj=CQi~;|=Pzo}+APnjatG5e#U{n_mH=EcX z?!JZLI)Fp`Q zU&WYE*G}#tZKbcSo~_v4`2G*oW9> z*th5pI0tr?2f*v=3Dr&RcnI02>o1({guwp6Sc0Dh?qJMsfWN0GfS-@<=EZ1FZvbz= zZlLaY1s5%8&^_zlfSuL}pkL!$gE;6Ud zhSpL+jisAtaTyrjP}=3Zo?m-#Ng5$h*-e}s87y;zl@%BF6Jdpt_Z0MSsS%!2+xmNM zcK4V<=@nEaT=zp8JUf&U0Kis1@PwX}`ZnQSZEH!ABI9SK?YIzX;ho)g{oJ*$<@Hxb zx-=eA(4&83L~L;s+>$eX1#)cCpab?_i9k*3vh;7(T*ta1z3+(xBE5B~syBPg>*|CnkWY3kvEZunuHdF6i>t_uaWp&Ui2VJs zlhebmNKd66lImiQcx>3wmpt>yB)4EoPoUGecSl6s$USeaEO!a)lbx9=-})l03-xZ$ z35;LeqhW;wfBT9muTZSj5BdeETj}00 zS!*OrYvh^SO@GYxN}?^)_!vWC7vfo>Gbb3s0~l$Y+8C)U;pw>(&}U?dzB*NKE&d4o zPKnF7X@?0Q3Hgpnil{@GWPKk3O}=00tYm-p3f~B7qF3nsJsq)|`FXUr1e%KJeCK9z zmp8FTUK#xv6)X?-YZt;=^Jf6eN2`oWo!~E#kEGbVX3+U__(uNhG%EYok_;&@d1 zRYTuTztkDAyxE<722{U2O5i{C3Vp!GrMGrv+-l8&suDiok}gxpCtjzjvbeI9Z2Rh+ z$3youaq`{Yd2Ghw1o1ln{X}=gCvGO6UouNsV_Kf{Nwx*#5;gQ0%F~}3Xrd+ZAs8UQqN%A$E*)Sf#w`fx}1Kt}+m>ILu`^!_(7wp^_8Rly)S8 zDcjiOt@EiqGcPMa*D*BlSAwmFK8as={5QAe0l}PVGDtte zOGGjD43-kkZuj(J^A+Rqr3P)=0tweRJeHB|j?WmFU;B4ooq=LQ+&5&;Ot~2aWBH*x zMJ89MRG9MbtQ46(VUp6sRcj)p!kA7~vd7fg26JxjK=ickl>(n1c=Z;AQk&!7g_xiH z6`v-diy4~BpSGTx@6_W8r7xY-2X7tv*`Se2DgRc)Fil4z{1`-D|NBUU+=)g#{yA!czD6J^lt}Tg z3jct8DuLsZdm7X`;clSZ7Of7YkiDvj5^ft(W%R(?l$L;lh9?;W*f zgR05c)$^kQwk*waob4|ge1Eck;`&9QE@D34Z9gr{Lmr<}nPl)Q2=m~N6SQq0k`Y-u z%08rWCG2Zx9=yKCB@fx`uV>Yd&eM6f+%f!+Q!qiZB5&@ZDU$b+qP}nw#{j4x_jET&2M%$ z-iUYi$GcxuMP@~0{W=wqC*x$^*DWHTr%=ezew^I%eUK}&{?%f~GuX3Y89CAq(0ReFYa*+77i?wDxEpEnJ?6lbQ}g zn-0Z=f5!x;;=<5#plI8XHR~!+d0yY7D?IH~_W@ye-VHjNgj~^Qhbp0u2{k{f8WabA|KDOYGoS6!V~-g<2(BEC;^8S27f z6a~-!HhxNVQg_>v@GlCu)PL>E{`#)^en_|d@GQwJIeMDYQil!dQ)hm1sCbmnv#za8 zfto!kJ)CJx{H-$HBkfl>px}MFz0h9eX_=c6{Wts^o!q0B@9wws9jMnqTJk~2(>No| zMASus0@cLvDrujf-wLKZM%(JUqnXy@oH1>H?#Lj%##_U1F5xWggv@0^o=Rfc8mT}P z8Pr8W9Q8!Z)A%ga#P7?5IGTy$by7m5#MveZ{%SI)e_yI6YOInXnbNP^OK4YvJz(Oz z(W4jhs-b#WmZZdv9gM$2^7I^fRF*!@(Rf{yEwyG{G~}t816z9F`3uMl4CB1h61@xf z?h2}{+suot-4t{B%)MUEHR|-D^q%ruT+OjC*Pw$S5UG;dSM*VyX(urMl3uGMGB!x~ zs!Hiw#BG$3)wM}nO>1-FifeQBoR#z~Z7p1@H8D1gZ55dt*v0keOmA7n^~g;34%%(3 zVF)&L{dj?Y4v;J(&eA-WRKEwKF4=$-eky#6ZlvH?tD4x&LJ9gnhnD-_WmUc}6~BMA^# zLRmNi_n^s@6IPfRp;^uJR~ zaIans5XIyrC)nL+NaD|iK#B62-OqJ8;@ReMdd)*(1m*O%LI7jhpS#U(M+~w7@fGQju@d!sLHa`AD^I|timTG6_3l!9-9h?l+7ULIO|f5vr=UU z6MF@2S#;C%AYtIA&AMd5Z3x)WvyCUwdA2Td8okEWd&wUuiYq#;!w-q|9;|K^+PD0Q z)q`%ghsd4H$J9-GXGN&mJVJXCoxjJFt1?^rX}7N5blPFtWChU@WKIdhIg0+H3)H0r zj`z9!O_VrkVhGZ1T6glMHjHP{Iumyl5t%U+%SxP`FqDCBaP8Mo@MI{6dFwvS*)xJ{ z;ZB~wIA5XuZKHWrsHI)*#FM{w+t?)egFBF-NFe_lrooORlUHk8rBMBeyLUQ{D=l!ATz3pI!2-IH(fY+{FhPEm-TY#V4A`V?DP!=;DsD~*>e zsS(q%0y!bJy1OJe-}vmK|AbZj^{6a~fx2%liGc=*fB|=^Fp)lC3-C6jhs$EU0{Dyr zhkd+s;yPmE;uRw73d_U5R!FW#7UPQfKL8FgPae|a#R`rDwymIS`QOV6a40%!?G#hV zy4ds~k;)0uh2f4AA7}W^gcPRzln*5?Z&Cu}=di>t(Llf0_Zx_(T^fRZ4Ng%<6ay2C zZ9~NE!su%tr5R3gMgfC(1(;O67_1ve0lPRq#;?L_=u@}-TzxkRsoPTI`f(l|U}3>O zQ?uqRgcEdAW9!a|3$Z)cU$v13i>nR<^RG^deGn^nm=B#v|>&E zjDxcIhCZpc_M$mcXX8z_1zz5kAHsU>+eSEzfy*!t`|$%^03}3V-cgqn(YLhVLs;Y$ z9rYz9^o}QX7l}7SfH|(uaNizilRraZ$pk}BvF}m3Lyj>*D?9R+F4k@B2frbYLjuAc zip(C%-x$WVxfQ{PHG*@}c2VnivaM&MlvpeiFqez61et?rqQAH&qMU|At^^J^p{>66 zvTG*@tT8TCl%-as;@iU6BeBam7{)GHA@NKE;+qPp&>2Gni8v!C?(kNY-=P07!yp?= zrCj|JyjMW}zh)TT|5fy^05r4vXOp37|6iC#Nh2pqIV0fz;Unb4Fxw3ZB8z<^2cbg2 zJhP!KX=&x_62ZViID%ker6$-mZ?$xv<1vUK_7^B(%$H6QP80fAJ$xO$eS+opvx#Mr zkeYgNJZQ7W00z4+hV5)Q+ubfH97l~4?AC^H zhEor4Zh+AOI?ymcnx6Dv*>FqaJbu8+ItC_)hDq2&g+ z38q1;MW9|-UptnCL(oVV9R-{B@V;EmFg-$>i)j48$QaJm2@_LE5rH}VlW}Gnc~lpU zGIwSa)FKWYevRa>_Oe~nfc0QoZWdZwj$>$1lvetjf#`(U-`%0ng6H+j9O<;HS0h|1 zlU7`OmZmH!p;DE|&KP_Szec77)TJ6pEs|EWT=`{q&!gW{Dn;ON%@zJ4ms-Qs;w2+Kq^kTGlF)qx4 zeFG+9MM-YCC0%1trw2Bg(aH%MZMc-j<)tj9(kJKS_Z4T@SoT9rZrA_9w_DLN0-p}o z6it8K)$Yaz`QGIa-PdLVZZcFrxmB_q=mSZ=rN)30mIe~Xv}d!gUr{?~?F?efg<1J*&S09GJI2zMNmy{|J>*AQfnKYm8uUhVR@l1QdNoB=tWbgvj@lYuh~33c_vsFL%~=6xnpW&?wqN$2jH{lB(Jo zd9J~U0*VuU#r6Kc>8M_IpTkA+*f)CI7_$}Gcg<8PNaPi+l3-i8c^0vOAvrSex3}1_ zSYj9wXbA3?{hGKJ@!@BqL0IqwF@yRTSt$b4PC0G~&S$B+(7(O^Z^?uwcdyPh|-N9KY(>MG_PnrY;_oC+U2t&%1bm`TrgWG=tQLI zWK75bk#a;(3(-ru*ppYe3g1mCq4OevTZ>>3{~o17b5iDwKfqdvdot~8FYj04W-aYpB#19;`dX3uv zoI0bpN!IO{q*Xab#?KyX_(eaf54g|&1YDPK7Tu@+V@8rA{@+5 zAKTjAkxb6WUBuqS&RNXe#LUdp%v8k4#>Uvl#QMLoL5xC|{E#4WHo~Zctbg+B57-5u zaI>l=QAapc{DM6L?bxn2X3i|tw)g^am>ZztM#SG3-0SPN(G zwOy>VvW%pmuJpNm5{hwQ(bpLBu{|}bzzd|?F4dad`hRUS7>2&e$N-%X}<&pxW!~JJH z2cAkwEa(p;1QAN8w;4onBnBD8M?^;lDA)-p3MoYt8h8It7=9NQ8_`h$prhOOp5?Ah z2X@!>e&2u0KGPR;b^hmF*;!d;k^6qW>+>U?R=v_R`leLPU52w7)*kL!vh3FFN0jE7 zo*E}fH|6ss?1x23Q}FZQAW}?nWChXzn0ZFG0L6Q`?n7jT-ix%%Q`p_t_0&c0T;eAI z9DgEQUaqpU*mD8Y;ouR+7jH+KdzbFZ5$9JD9FnbJUyS1}D!Fa#kU+=Hd=ygYUY_oY z;cZnDqck2B=9Zg%U9gu|$KjyY{)+;`M$U|%<8B+kIQE)Px#?Mw9yB4f&m-VdUz8~D zewpE^ONHTsC9$c;b@MDi!fPVrXVf#2oi~A(UnAW2M2J^Z8=sq@ShsGw%l3xFHIi&R zT$zEu`#iRcFX}VnNM+1+3;ewahBrxGtm*EOFAbq4*JO4)$eS|agMriEReTMN#}qgP zA1jQJ9`>fqdUUr+=iVD^IR3PEeN?M9p_f1igUOIKIsX~2;$u02|HZ=UICIg+&`4fM)(p099I>x9XBUdUnZgiNvWB?NjbiZe<+)h zp|q1M-sOCkQLe~Nrot&)xH7(2&e@F;7*sgN-n4+v2*}zXyEi$0&(QNe#B_h33bna@ zH_pwdKaGMN)7l<f78eeo))Of%0Jr1oPut3AwErw^y8NK zAN_$zjspYDD_TKyZ-QIfxf>TH_C4mUMqK_POn<3f5LV=L9u~>(zHZ|*#vT=>nX;~z z>8?2_)vmJUS>6b>ZcyQT%?GG4J_eybQXu*!Li)_V^ttnc7@m7w!|I~E5<|?s8L$yF z#&-Efa;5n09;vJ6)BoqL9YlNztypee^%BP(|7%eg3xbS3hNV&?*yaYv$+kx}K=E z@t(pZ&w*?vW3zHIXZW0DCJ{u)+_v=a#4#Us7V(js4jpd&jb{E0HC1~!XhJcU*4tFx zAai7W_a!+4!uroMBIP}fg{zsV(DcdR?K7rHI@>eM=q|0rFmVw;@+ym_oJ_x5H+jC{HlW~W9 zy-#1UR`yO$Oh>(@LpkS&$(!RLv831MUWQYslb_4kY4F(uV6YtDSJ^bz0zd45*<)Mj zO_WtHp8^TDXBya?p9Yq?o9Qd^zNWHu_mBpLRYp0n`p;@*^Sa+a+ork;|L+ z{}LbL7oTs+^Rqa(kn%`!YxtfSQ-+7h>U2(&{V;lD2 z><2NXtmfm)i5rDY!m~@yc~?W<$`?7Nv$l)l@Fa)$gikL&+QUO$5Gmh|6%(}A;fD;u zPR<4*WC$TWo|Wt%=9bkFS+{o-NcKZkKchk0E~n3KLyI?>Pf9R?cx>0_pYDNPF1^_M zY%q_Op_reS@5^nNt)A`hTIUn*uH<}9f(+wz@9ur)`W&?*6G9?ylzZ)?TU*EF53O|9 zReXSByJekJxT9e`;QUu6gX2JG-l6Ja6YV>&&J3hALLN zP~-GTW2o|+9+Nrrwdq=Z%YM8JClVu`?ikoAxT9{~m{dxIEEU6?dN?-fq7NL!w&i3P+iDRr-WX7${Lf)^i>S2jh zMT6dl@lj1TCw$AD2hGzX?#;kToxAyHHTc2O=M2=*~8o7&q zNn9xmFAX&KzdsBQFJM8nrEG0Ss=t;8-rgcTqtayrYiscds&i}s_w~*0TT=l|fdvaY zOJ}fAt0DdfPSU?D?%_cfRx_4UnqcOX$ic^dfIfY>v^+L7yuBDc;)xQCI2u^>bx!*D zk_Qa$!4yqOizlb1U_9cg>#}!Sf|f#}DF`;BfcX2$5M9Y88;y|G3wk2Gn~g*VqPf(#TmN zFg#8#=8jbwGZ&NldN7Ia1PhX!i~y{eg+f43WD%?KLmS?30|_~K(d6AK%^Y0Vj!g^= zHLli5OSOU2sU~RZUZPNt3>0g*UmtTx$#I-0HzcM4)%p6`%Pt=LZkCw=KT_+im`PZw z%c;#$?0yA+R3bTs9-A$Y9#Q@?!(&K17E82$niVP)T<1)HldeK$8@I-jPNrVs)bad}(>m`->|o<2+}HPHzF`@`db71iI7nHiFAABOQ^>Ey)! zj%QBrB8vN0;Fag8Om|k-Rgbuq+(oW;;!GXiRzvsyg`TOc9^yA|h&4At)a%cOs7_gr z1OnL!z2aMht+k}+ho~(SxrBwe%F1}hz07PONPk%KSw_pi;y6~D%7SiU(rziV-#l! z!u}hhcs%+&!@+NBa|&nlk8hJ-RYN-I@s6jYO3)*^n0a(c@L4BQqKe+%zFK2#>`E== ziS(f9D_-`lrnO8J_L1c2`e{+om|2{miHiOav@-RXS_|9d#*WHbGq`b*YQa@Myu{$o z1D2d)XoqPr4yUf1Q4MmuBIAVn8 zQ;Iz(2D_;SyIBDrVAAcXYCw1Bpp*=k<@>Qh%_gg1eQ0$RE&cCK&)na`#%#)}TCsx^ zMuGG{pX7AXd)*4NGZ>Qc0sfO?Br>0o*p}`KY8>3^QSZVJA#o3mT3+A(_A$9vR z9JiJXU*Sz-74cKys}VyHD*t2Da&!qk8kJ@>G71Ya#Pk|1sAG=UnvsSVkbxpyEjt`LL;6h=dYQ3Y=)i{kriuD<;l$0&YE zi_#Oy$&S~6xEQ?#EUjK<<(y+vtGROz(&*@U)!#2FGt zuy!n~|E}a><@wp_st9_D4X}yE1Fq@pXekvJ_Yhg+lC(isj=WB5P%7<1g!6J0Wg9Ix zlPGET^xk5n0lTV#jr#O$oKSn%;tq_AteX z)*(*Rm=3<$Vz{#De9n_0H!R6omN>BpV-`+r$~0(b%|&%3v_2t{DzT`0Zwj7VQ{OHS z6cfP1za*?`hy2*aum=lkgy&R;aI=G-9eXEs;&z#&%;9Z6xCj%Ei~Z`fgv$t~=&G-hmQqj)kB z0)c~NMrIQ&{j+e+)=;NeJb#Y8q;OFOvj(~z%=N8o3(SL-LWi<6Zs1fzg^CFJ*&vEn zIG=UO9aC#I;E7>lI3Nxm{G+Iz1MZC|)Umg zDKxb)g-p4TY%wKdP)G491{BK+dwUU{#l`&C?^8%UI_MY^$D`z&BjlXTU|_25I#V9W zTNcx$E11y!K!~&TLiFJdF}}BLr4z68gqnWaztC?UHeES>k6o?mR&0=Gjo?YELVSH^ z`~al9C|<4Q-?bVV%R;aw%ZB4KH`9&wpLG&B8g8&*+%JpjGh-|&SqYZ7P@u4aL*nSr z$=425ql~1{oJ)Ww=xkWnK@zJ_d49n04U7%(olZiaAA)6I57AF0>_?5keRtzJ&g$$S5Gk|-BmR#s;-6qK@>ki_%Vg>!_tw@tS)%=j%o zCN6K1WhwPk-)Ho|Eh3oCTM%5Z1JA>XI*($)gU?fIKutqew0*FexVs;kl3Kr?N>ViE zB6ORcUJ-bttHef#q%=TG5fvA zK*gLL8T(C;r{*uq9Tg4YKNByCIX@zJf+DN*g0~n$Z`FzB+?ib)UdlM|P{Mrro2iF| z!iTH0E?mk0W@0K|kTXMHOhe+nZuB8D-M4P&;V1JcE>nyvc%54h_BQh3RZO}#tN(Ew z$3B92_k1)*#;rN4c$WW|&h(2pt6vtjeOa66-#+w39_qsg4k%t`S(~$IDTJvsNW*;|MZn(uRlLcF*O|+yZqqp4jX2Qki(PC^qFXIKS z^j=1aO~B&wSTT>uTR^%qNa??!d!|oA*-qNhER%)TbYCipO|V6zv0^Xdw}fPlIcJGUM3+ruye1!8>{~VBWj-UhUyPrXd$-9sZ4OB(g2c?#a`cDr@bb*|WSSXUD zC#KZJNoL)&jLPBD^Fi57F7@*k4z|>q84&m->5gLK$lGlVAsG=)i3ch7!bddzRCzQ!_G(}ZlL8Qmif?I7FOl? zbvXi_hUXH?##p_X!4Od%X&Lq&TTQ>mULM^Ref}0=*}ho{DjGs9AX=> z1^P9k>TP6LB2F@$IO~ZR>xmTM0B}AKDCLp8)U_T&2#9ePqNH;n;;eo#_WeQI0NFd%G}*TnCS$=*QqV&uic!h6w{dL@U zT;$>;d>5TLLJ<*pI4^{AMZoo}1m|Q&I1JU?z=RtK2nQk2@!#Q1bjIDFSqGinWCM6w z1%(of;JHjGKWyNmV`y*tqTwdSMzcG$!$_5LjBFY~vS2t@Zz>DH_J?4wNga*yKz&b<9QuSS?Mh9>Y zTdRR5e~KSR7+*N*LQ9Dc<0>2PTpfdBWCr*x3@j{LtRS{eT(kKC3buH1c`z!iLy!Ic@#-_nZliOs>-5^lFYVZp$qUV zndXVg>zT5}w&Q4Lq-xFhT7rL*N*;I}v8RduEFzkcUP`tu${#SSXKYB^kCQgTd1Shh zGtPP6(IdngSStJ~@hOkOm~+;aY_c@Sl#8--TaSAx1Vg4N4LUL8PEMTzIAbls4MR}R ztuH}>Mu!W_?5fowkhK#$IoJ{nxmxb63kK-bCs~7`Uxj70v(N1SG=H}QfDuR_3^WJ8 z>4%Z);tmgW&GokgWWkHk_csR!QVh0<6Bfg6vAz+(?T8g2ZCoHOxM>m|uw<{fX%UvI zT$f2`5}J~3$ZebW#9sn&%gA##AhJ&0yW`$>Am2cQ_3zl|$|L{_6L9tMzTt{2i(I8M zMVv^41xk`u08WI;_|CW@?n=LL=_ zU>(gEopW0M+)G6axS>MlAvyDAf~=g0mlnjBkgyv8m-EZbfZBg_bo}-2zjI)nIr^|( z^Y5>cxz44yQv92upbr$vf^CT? zod_w@t|*0V2~3*-lShck3T_GFo|H6MUE}{m0*$%s30bFnrkFix8#33F(+?ny{#WF) z^H3924@QoO{Ni85?-fD(@|zFTl|>y{f$CH$H26xEZ-cX?pj?EpnXslf-NrQW+U}{o zgXrVDs*HJ#5DU;qjzX^e+^f<8`>>|C8v`Q$+mmHFTu{eO*83Q$`SVbf?%_{U!l!SQ*OoGBi?SJ)6e!KHSu-x@GXWLgy@(WQsr@T{jMV1XAB(H*gA5L4W(fh zWCT;tOw`l;3l;oj3?0N#5Vo2-CINX6ms;^dfw6Qax`(0Nl}w>}9_h0~1iTj$LtDIb zI|T?LOVDnH96k+MM&C=*eYQYQ_EjX@DFL^j@0wrQHYu!dO6@5Zp*cjY;T)aC^5EN} zOFUFt*M;tcAUu4q1aHKVk7GcBPwIcF2sr zpDafXy*Ji{b727JnnTGgkKx!B3@48IzK(IUno!heA4#O<%DAkHdp+k}4qP}Sf!v-O zFkmDvCubSs!9&P7aCZ%!7hmf&Ky%~TPxEz7>$|?@b#=bqN6z~l_Ac8RfFxo=PUGlKRJvl;b=BRHrY1ngtr4>$8nvBmdkx zr@H<5TC~7zhgUP36K7kCgwfqtR6j2A1L>i7O&`!YI*HO`W9_iHA7e-tXDz>HD7RozN%t>pi#WTVhl^1+M1)~vHHVBJ?1@YX7%hb& zHijjUG=}qRQFl3q4HymkkdoBt#-&(-Pz}upPfv2x$}Gr=uf<8R`zP29SI=}-FOiy; zPI51isV;L9hEy+6*oNgEawef*C=r4Mm78YbiuFBjke@)vx6;4}py!WsFAp}jAsZD?jdL*(34oQX5aE_W>pDcpI0KCzj|8W5B^KBhK6G z8;r-_a(9l)MTR9ii;%?9-op^j+YZ3+3e7#KTiCDEL|Z@wz@FwJi^#9TFysQHnuN@E zi5|h(N1ax1izr*@u2JW()9N5a3kXyTK=wjB;;E*>RE6pu8?X!a>Zn>6?`Sh5_L`tENirtq&##MbIXk=GmmrwD3+!SP`aVU9xLRDjJvR|+-t0hE-18LCTJ zNHfAn!@V_<7qMvQNdUm~8CI6#8a&bvQhhB_eoMSwJcny(;=Ijpy~7UmK}5kkcy>O( z1E?!QdVhu=yrBr?Y@R90Npx1o8jQ?Mf3oe&^nnNX%%B)Rv!iuF1n`RpX76GE=50Iq z(12(1n;0vXtMPhnkT#t$JS_6Ak=P44yTsfi=3yf39$9y2h(v!hSdW$3^1GKp3wNe4 zfa>5j5p*Ytg?STv40>=yS!@0sh^f||p_!-Hg>aKQKq}?j>Dh25g-Vvnu0h@beB~>z zvtO=i(K?Y8SYv2eNi$T3YDFV!=1T0HSq&}C=``9l0ca{jIr9oOl=Gl*E?_pUXSIs` zmrI*2C#;=0-L$Sxr6xb^(L19ij>yQelKOM{fJAz3SrB$jf+CV|`%A_5)KZ6KzNcz7 zniagJ^_XK>u~@fC(0npIuqx)_H21EH4quLnkH^rR*0QnXV{yBbK>FAtL97^?PkhV4 z=N;sK7z8I+mSBUq)>m|H=sqFA7qB-Nzd_(GqbgU~uCP+*L?P&5A^Kn;EUPHg6iQCL zr1Jo|F>f^rs$tDZXiOnyYg7cVtbFLxnB@XfXF$amvYXC)u*(?3o1!(;ewZDo{4hY> zfd4`M7NIsp;d;xv2XK<4Z2+6V;6X9TGx1Qz;`fcI zUxn}#d;znRei5kUa@msmBXE|D?!>mF@`c9{NmiH*(NBP~IgmY7Zn^3L))DPa+3s|G zikZTyVJ_zw&a^Ee_Bn(-&{_;%!RH1-vfCt5Kxh%qBZ!+i>m0oWth~P#(}t>1RK9?Q z9D6&sr^B*onA%)QSBU(-b?>Y~^~M3C^V(WOO4_<1wLrsy74OtBqA`mtn9-IF4IfhJ z&DJXR;!1dAi4Fv0{c3yUrUL%~>>_AV#V(BIF12HDo=pWXa$`oJ zi|r-KhBe!2Aw<)}TWQS&|8j@w@kNtrnfnBnS{a5?PO5%6cT+s30qw^9$)BV67`J5CfxznlT7gsSAsYT z)F~lUvD(2(hfd`ZN}^~;h`^7X85;xEzi}c|4AC?}9J{v%j}K=KQu?iKmY%|iX_r{v zEi2@?i#!SjkKZ*Cq6*Ljo2__dwqiw9pM$^eJtv_J*4;~R)$gWgMO;9lNDW=UZMbHU z_1bP$E~aK+ckP04<44@vk4&c_c*QRTjb%OsQ8Hy{EsHbY|qBron_Ug^vt_VW|>c|oCpL|KmOV?JkB>TO`pB=wMG7)+`g?&?q^a>Z{NvW3zZDg-eOEengng+>Sn1{r z<0cbh4jm*1K;+-M^$%}No_Ju0M4Mzv{HNaO(g@Oo(dHL+4-D}a+aeD2N{t__^AJLH z4RmP62d;J^-KaB3ZV{?ZGwNThkRx?d3!MZfc&|>JCUl=42;~&DkXpK6mG1PMBe?nh z{8vq*tP7IbK{~@Zgcu#*&?0pTG&c~*_YkSj?Z+-HG3_MW2Aps0%F(X}E>C>ZY59N1 zjP%qCdn4DP5r*&#j~TVSfM1~J1^eu&+*H4?*@?~epYI8A(h&qI3?J{Lzwl-w8w3js zr$rF;3U}{Wlj(Wqyo_*2=DMdpplwrpj<}68-9l5NZ<8jCJUifeCM-n~CUEVI9XQ^q zIL5qSuTlBR+oAW7bq(8(i|kR~1-{UFXnn+VQ+x?+p?s4NhL=sGp~R!25L1#%%S)kf z(N8Q8>$E>9YTb}CUe>R^*^m&akO zPMN{9OQeA1DTWJvFNO<&Dv=uGw`#m;R;B1BkppbS2Mz+L$?#GpLljD2chlK&@{VJ} z=oV19VO=*;yMeGc;81p91gi*s(DJ=nS0RKDm;!5?P}|TB-mIP&{1|($<_|1*0F;-B zD@vdu(1ezO6Eg1JmKssMpVV7NIzKJT$8^ECDGvS)M9IU;^^P25D>o_I-@wDm;ehO8 zm|BvkY{yGJAS^r7Brxn1w*9qtmg9gd6AtOlSH;q;J?%M5`n^A=d)v9yM~vMdI67=c zeph5b#(rSBL3K6w>J2u2T!hU)a#%T|TTlo0FOx@xIW)Jh`W=oOYGS$rk#kVkYecZ# zNx&xsYi0<^Dt$3iW(c4@X8W&Xzb)raPv9Sd7$hE)`d|Th9kl zNG_iOls?uA5hL_96^yk!vVBN``jb@i)piim&4uEqFYZ!1o6eL|!Uq!Mol1XN{1tNy zo?G}Puw9hCx=OS6>oNXf;%QK^N+`KZIJ*iEXDg7G60vwv`p{ZsQt;vuMKbyz6e}+H zB=te8Q^#~NJ&@%EwR%Bqd_M8t0lmUF&p2JeNW?j~+8`%`7TTdC4~aSsN#^imaM(5s zMkwtsAM1u7Z+|jE$6#cp)EZ&6lOT?Ir<^9cO9Cg4aKC z0{ue*FkEZMhAGTdetcGDftHKe4`vt@l+XmPrSAYrwM&cnSbj=c3ni}v(G+lz+6IH4 zQb?w>3i4RdIw!OWAzAS}B-q6u;=`~;U>IdjXwyU=fMF1!zX6X@^YIU0YF^2lLGtE8 z6@-z-(bn&zPJ%Fc<8-ntJ76xS3NX{#B31oZiwl-h)ZJ1aDSnRWVkkrO4eaGRMpCt= z;9JSqMEzVhIz$t2^UaZ4EuGVQh@1j9!O-fR+Np`zq@U_Nw|mqsB4>v*i8xBwALefp z<{C|1T;&l1@x_+PEbmH_N+VC%)GdW_q#y!7w zpkBq~HKCH(d$VpVG$#??U}&~L2S$;$V+9&{zfGI0?@C4%P2j0ia{bV^bhrS|0F1}z z+^+#elD2_ppQU*xcSUj7;T9z4PvjjLSTwuO8`JG}RV`k&=!>H32K0 z*3IJ^^`vMJ_VysQfH`asCg~-eCXs1DogP~_r_X43m<1Ignb~|_PH@CiF3Hr~FuGHS zB_zf|J9ijQnY#WTr!MIp2p1 zC|n8WCUhlW9(v!kZUl8RLXD?6DmW@%iG3w{sYGpraUTd*{ua|s|MDl}goP3I+Q8l0 zMK*;yCO#0hV!hM7`5}wpi0l|2aRZKN50wFnlp(+B+&&8<j3K##bb6pTJukKo1Pl zh2(Jj882BI_)`~wECJWBWDZb()(C+CmxC-#`aIy=i`n`Q5EnH2G$?z=k9LFFyrRmX zaJ62@YK_TFN`LW01#oo0OmblSRvRDUg?pKhDu5GKKauW5?li7I@JuQa=9pScX9@2t zrY=P^ry<=|73ir~3&`^-)1MqZklp-uMLY1aiENjv6Ipn%@YSTDtal(KAOfWV!Zf_C8=@-QVmI* z%AHF3H>uJIGb%Tf90qKm76;pp5Fm$Zs}a;d9Q=9{Q1Y$w32 z#r4Cy9QVno#lfZb3dXy4G_PPh4eIUes_C z1~OqNrEhEoZ4z$02x30w=(Cs(eJP`(Br=HXSiwxN$7~369UK)KS-ukN$eNlhoMmI$ z9$RR@D*CM7;DC9${TO2)j+J%zD_gqRA%ts@zX1Qqgo4R@5JCeKV)*#SKxO?mp_dR* za3s%Rbyfiek|hSCJH1rA-M{4#IRv-1GV%5Ttfw|h{&*q`7@Zc=(gMb)wl^@L1V5PG zx4iKoNL$9QeN`FWi4M#t!3?>&89r1k6{UTK1&v)ZbYMDl7g%Nn&ZZ?ksQ=s2eUt?v zRvTl`B2^5y-WWWdDvn~ICC!^^Mz-t-V`bYBUH9d*V_r2eZMhR4Ro5$?7y_EC2IwAU z8YPpYj8yz*jz(w{HUK!GL&nQ%&?2>Sj!S9{bwp4U0=VN4cVCO($4uNe%+d(+Zd0TKSu^0g^_8?uX zHDPo*Y}&;5@$p(>Tk{X{QG#Oa+}Zt0e>;I}WaT}EfJN34AwPwzay2a&G`Mucz( zVY+T{W+e(qYD7YenB9!LOvd<3Or`f&$O~jAWJ`;6U9ld?qSPoka-38vtgk8MwYq>;v-K^LD(6NxA+vkC{$@kQlCni5gA z%{PHocy?}u=15vkjlMwP*@WU7HFebzlh!mYx}s5}Q~!vS z3SdtH)k*?AUCliD7|VTeS@WY9+cjOn((}@>bX05LDbA*Y9|8ofpI?%KAG!}C#22<9 zIWPI7Zv!Hxg;oj2g;wK&+v7Av>rjE_U-IoGQi z#5yubAKT?cGzsE+Am}6vKo0Xp@RUa{jfSrc)qZUVidFMnlHtP+h}>!-oe4}xL!X+b#DdhWJ{Dn0ZE08sm;_j-u?6iFlRm$D@V8wrMZ##oF*(d#2?J)qt8qtj)Diq-A=f^b0d-a|^HDl9NrZFh z=RrXOY(bAhl``ZJqQ#Uh7^RR0gbA|J{9by%0^G8~-@h=>IVCe94rYZK{rnwz;&St_ zbgiv9%6HbsREU(&JHyqdkd{n%)~?%p6D$y1%-mff5nfYrBW(TIRE3!TE^=^8?9 zcfW)6M4B~ZOmBYIe*R@7R>9!@blE=|yM7__T=K^QZre%zn1?D%;n>9ZYj$Yt4?}~* z6h|5W*(R}>Z~W4@JqmRXcW*VDQ0A=SwzD*y5!0_*8b;6jHndUsOCOdX*)~|%cNpl4 z2-@aPE$ZgWP1v=XMxmJ+`%2))6zGe`*Ky!a_cotPFfdx768^Uhl zCoCpXjuVL7M#^QqgqSO^uXJpY+cE#+m%u&dl<3wv5^*tFTMCf4DkOo>8CZ47_pX{` zei9=H&;&iXe5g=4BM@bB!oRZUK$;2kHZ=?=IEv!iB1S-13Zy-hBSH2m>A=DX<5z8p zpo0nIR|SZH8_95SNe&0f1@RI@Qk~?pBK2~@q!diWnkizZl&J9|NuGAu3>j7`Cx?}s zxXvrV`@i$z+w!T2FUcl{NG2R_k{SX%YP3Xt6lqFnj-bKDHEEUN*ZEV$xqG^4GFr{m-$vHT&JccXj=uF5;uyj3m?g(@8OPgKALMndJ5O2 zVJTpzU=zCU8Ta^Kq8{PjRovA6_hs<4+@wtk&k%1D2Ls|q5(e4#(eSFUkPj(B1CU1? z2F>?@bt)bj=Bm0V&lGl$vy^rawNzmtZYixHamjAMbSW>vdC73XQI5*eioD27$#Fy6 zM@SB3_ZjS(9Hg@HJ&2{`dQnWtc0(K!4h{+T)op?t1iIy)_%%wt$T#x7hyr)v6An;$Jnpiun_Yy+i9oE;t)geRcG zMw>+|AuJk<+b1UomS_B=O$9#!FGiH0My7<9B$KVrqK7GfPNZl-9WZAwNuV{%rpGB* zE>dTwQ6^jrttsvd!4Q|ydS}8RP&Roo2*FmC*;l*`Leo^?>2J;FA5aE9S5%L+R4D)uZ_RVmw5>%(<$x!JIdjj)$ z^K2fP&(}joG3!M0N?Vv4M!2n}7`-V-$%%+9n}-rfM8v+R&-;@(mcJDq7KMn@8%7!iLUP3mMvqY`hgRfO2q)q=#fz z;>YL~=%!ESxqG8{ECKc~+wn);w$p>X3G}gi#%t{ms_!D%`b@UXI2B%S152r6c?I+K z5R7E?U*cq0YqM*)P62Vga`jt7Y}Ao78Ix(OLTbK3K1(!&w+kgwxB1V@n&;V6>7i=% zTDN$o5<}_r@KW<~28ZDNDO%L|ly5Ydp1<|O`pgUZ=`?LDtcc5W52i99o_-BsTCt*> zKu{mu^OWg($_%%10bH#{6Nq$SY-*4Vp|%2F*BWe-T`0(EMtoN{+tpO**SBJcZeH#a zS=KD8TNX%hA)RWN39+hr(9dxJv~H#i%vmO>+vs5S1e${=4ypDBr3Hf119biHlXC{W z-g}r))o06d1M~^EdhL>8zk!*1=_WJMqRswsC)N9rY5S-AL$>Ew#})VEH->cX(7--Y~~O&d0icJkUz-nn+F-^#c!bOc(yf6r^NpBS@i z2t>v_SPBTrgP01>Fb6NcDh1jxuq~;ix$FXF{5#MNxO79VxWG*8v9#5!1TJ{uv{hR< z_^b$&xbVDIW8sf>KyYfd@)x*JJ+^KKI=WL$>|K$Ex#eSD3vzTJ9o^C<4|XcRx)oxx z7GQ4&Il9wL?0wm1xzJrU@Pf-MhwTbn4Bi$!A-Ipfqjy8FX~(SdEhH6F$Q#P=2mPl;(%LEYF#vFfR}2CsJObn3MdqJ4)^b@LvG*3P#5!wP@+5cJee-|E6R zTtN~f!Sx_&a^>{-hUfFFfm{ORUQH~egfHFDNUlS|y|0H7!FA=I&VA+>>rxs}@^ zcc(-K^|KlO>Lz)a6|cF|^pDZgm!vo4q^%;m^^%sI8jj8Bs+Gs-b$?;kqI-5`j*a1q zkb&;pObNuV%^kqwt^2b|(35mf6bxh$y#i?;uAUnBS{;7{lwr$`V;&QqJCdtKOc2}% zZ&+Qdk1(Sg&Ng*{wOM*<0mEKPWA~Im&{iM#L=<0*ci{TXQKZou41K|1Zu14%P`#7S z$pNTSy;Fes1`(>^C;D^;CEfZBDOK&)ceKps5XBB-HOJebL1G_9*~e1>9#@8VsfOY% z+B`5>0U4%()m3R}uk12VYRR1~eDs!eP9Xe*s31dJQGt|}DV(@uJg+K4z+p*wR$h_- z)Qo~rWEziPiHcF%LaMaLN?i3Wp0gf1rS@f9?uolr;fnuKhBH2BiMv+nN+4JEb{MZI ztgHBu;I{aEsN@2`QGlAXvlyVP2&PcV8BAI>Xx_k?-J&A)&)S9gsvx%5XX(y4-jf%n zP&OZFDT295m%nmR!a0>QgSAZQ)R9G8twQNc#ge02pgNzea^W=R+_^)nx&*G0#kqHa zZ&=VXzyC;RczC-hSsxN}3-ojC#Q9&y+b7_Ng#B%&0Pf#?QjTyT+STFOS<*z~whX;; z8A7F9pzlC0NQgo8-wS32oX7ys_oEBNBQk2kD1tMGGwP~awB}rj`6BJHhg!i}XE5Ji zej5}XXKzB!)7RjCV{kZ5|MXeObtFGBl67UhAf-5pSN?GuVE8RIq#lD$z7?isS)|ql z@>#ZrjbN?B?U^{vcPY4}d)sW55r*xm?IE(VuA`+wr8U&g3Dm{MF-F7&WOyf2IHN}I zM{>fTJeeejkqfdZZ{D$I#l3x95VCpDj2!)uj=OCH%a`@j;WxEZoHI$y>a(*G?;%wp zVSB^5U<-&0DKlN`w52XUPa^_1P&XGArsZtD7n=entn)%Dgi*KLk6afY-BmZVuL^%~ zNzzzGh3JatzEB^HaA3ak_3-Sr=uBtX$O*78ILr=-629kR@Ei1gwyXBtIviZ%w+h-h zzRh1V-h|o;+e(CEz?=B0LKd6AqM_h-ht%Msycv4_5;r%nZ1bo~1 z&YrCbhbZBbN?aBu{`Vb-G7n9ns-s>Z%_Ax;TlH_IO!1%R zsRxDwQRFjlt6(a17)C_PHyodg=rH=;!rFKV_(Q>}#BzHAG{YEegY9p(_%Io+@eo31 zlf@d{NFEX8$&6+pWnS*usxh zH@#OdRON3Q^pLQMHwuW*e|@wJ89Q@YZI6=&U(ztE+)OtuMg+ z);W`$wP?@GF9bW*I}(Ak*c6Q~aKDZbYq~53o=GTAkRgM@^))93_v9A9XhZVa?^W}G zcn>DDLO5aU6k7|&D_!XZ2_VdPOO!T`Kw-j!zg#gOklJ=k%0_?T6EF!6|K z5sbC;4J9kYHGK5>{{|2>sQ*h;p>41Yb!k0$=$nX6{Hs zpiuM0JJGBs-2TjwWcA~Zk*#(Rfi%O`yL=#W5ad@4=HcQJtQMkd-Hf8xF!{>AjWLTQ z@_5Q^xQTaYdMmbAG?vZ%R|SR>jh8UWo=NB-+|i{cyB`0JT&sV!hPP5w+j4>3k(I)%)5wICWC58E}zGKMVvi@+`2 zB`L)pWwXVfI1;m-r-+*9=|_YocIWK$PNQ&bATKLW9n3h5ej`==7ZILMLKIH#5wCd_ zb*hBkMQc@tOu@9oH*bnd7+8!xTpOn5cAXG!zpT);LW#A#&uU7j8o5q6ph`&C2P6_EG=r|+#6O!bI*U;w_Ve%o4SQs*0)KxY;K%- zdZA#<4q20KNF1^FB1*^dtllKL!fpGX29`FZ=|~PjST?0=34DUB+A@0Loe^t}Oy3pf zbNL)v`vqQw+hQ}$gz0>6yOXPdz3ok7Y{d#@?`uw)I?-R7q?TBP=tua(Hc>&mm1!>g!PM{ihJQ zEr(fJCMq-)#_!OAXFJ|)KY%V<==v=_{vcY9Dn#V?J8!s^4f*;LZb+b8e;}aUoup4H z6i$yz`vdL$sS$Pt2WN96NrcszauZwU2Yc8`Ahgf0E6@sQp4+<;#CCn$d9fR`iW#)} zc-d<{8nm*BuB=9Aj_n?sr4!kYUSk20l?eoq`Jdtjz9$mP-UI0y4^g_n0Nhr#-(L*nVTb|4y~+4F5^)RIR+)w@+Q7TZn{^6?4={< z0l)kk6@4&UN56FwNT-pT$-%r%NL19kf{u+=!5=kakQ?60HD~J<7wJZa)k~T#jhG!J zQ#Jb)k>1nLDg3L3%m_aTrg7ejC=5;6srKy9>N`5qI=U&b4f>wdf_4e7k|3xjs?L(uOa;my!d!}&0y{NRdLDTYE!PE55=|X0aw(bt_p|@W;dd?nf<-RHYGZnF!qB+x{(XuFb1XZ zZWKiKlDmNb?_;m#tzv1lmEp9;9IBmx+HGew?$kw!H_LNV@`rq_)ZG+r%AKVy$c>3i z?uv^ytpcjf!v=c{FToPe#kB{l&W*0fQ-w)1qtqB4_*O#+c%(#)S*m)jHHCTZ)EN5B zO8py3LazGz&+7@2^Rt}NIK97!%bcYmBJ(XjIpBr$=>%U^L#Ok%T21T1_U35(nXDL& z&5WmiK?_P*QT|vR(JNN^Ggc!`G-JpYtMqGEW1?EQ)CqQ?t6DzUr?7&tS~=~Z+5m2r z(}aRGk<`gq1(!CP+;+79ZU0jpAX}$=RqVv{{kPmlx6X2#=88kG{xnpvCBEO(Osu3O zci$vaRN9gOJ=Y?f7sUfm9Xw60$vOg^uyK4SxJUX8Qi3g;L6@x3?>2xMOq>ptch@}( z6txFzK;>8R`v6qiW4kOS(hXBa4ZEsQ@8uqf8k1H*LrHAvE!dhWWVHiiwSDfxU5w6z zjEDF^biad5lQmmm*va)A#Fv$oF@upbe{1#}h$1LcL^enC*`~k5x0f|lA+kP-NaC#| zpyf3~A`bqaB!--R5KOI#C5Mv~Sp|zkb^&e7anWD2PvTM;C4EC_t%724$^0F3BH9v< zV~r;SPL5^X2&NjW{@xM7^Haa{L#?vAa4ds(u>suS>fIsAhx=kFy>p{UNE?ex?y6?YzDoq=&+VzyDnGcUDZC& zcounmXzQi++8@|G3qAZboTB_6k?c)&;uWreO>;d$vF`*E5}gDP92THI!CHC-TxuN9 z9T7KR0_>65L++H&H~3`rrF3Y6lO-vPaJeF~hHPM|eMs3!t4PaQgkhe-Bg|d{p3Mab z%6y^-dhs|965pgkZ=~sXC4@Zb@QJyhNa^}LU?QFmn?NBv>_FR}p-*jRg9Tji zpj%sm99;RPn#_a>zqonbuHLrYT^?oPDnqp1N_em%+b$#MVPWEFJ~Pm>k~XF|3~uu3 zuD&a(mPU%2m`F(i9=CFuJ8)pNY~7}9jZVaOcUA;rDfh9L?AX$pf?d5e5yky-x%?*; z1u&C}z3X+B&rhr9P2*-Hvc-gxU8RO7LeVqI?~Bc>dq<+90ZV>awNds6f>)#A(II@;;UMU7?>XQi*onCQ zV%@}qSZkf6&@<*=h3^^?$JHR>^YmdtzF)l_De*cNvpKNQWpg5RloD%cG z8GFviU%haUF*_i~v`2o(@Alz!ZlW7Vpbqu-v4|d@-`E^kkgqk(B%Pcg4|$M*+z_R( zCJmDOy7W=?HQ#$sV|mjOzbgoUeWprCRuP|A(r>Npm+1b({d_?%?n~6vP#d!R z48vgD#4=tNgzE!!{!ES`a~u-#-Q|VHg<=p_Zqw#Q_F70r5r!e~xf~JW^MrGzHJDpe z`MH6D%6A{V`-?ov^rW0?}i*!;2aew(TROR>+eiL}y zB2WeiNDD=HD3Fbx?(G*=H%Z)6Y0*%AY1B-B-Is~Vl!#^he2ji@^26-PQm25e_BwsN z{dRJ>*36N&x10@!b=eqWMBWdY2@r`0L?JRN5WvL8Ffzo>ketXbw9Y)-^oB$t6Y>`s z2@3ox!is#DxE=o65Ffo#f-bughshZD z!N0n08EyM^qWmXC-)I(|s`~@kuXs!AmU9%2gwvWde4@Z=k#1HU=jK!)HOYuP><&fA z!e!qA&5eN3eaZNVM8#|hpW-k{Nr%gWs>so^TmLo2=?t%sE@%BkNxYsooN73(^)U2V zULdL$Bk-edgpY5%e`#v@)GxL0lilYXP?d^2k+4=}voMRT=vUC?UdNm{om#m{ZlNkh zQ?{k)I7+oh;T&9EzyTg;Bv}l0V4VRIU%)9JXp}D)lrMP7*G}M0%ArhUyO_!jgT>m- zo-?@1r~3dfN9~k#re|SccV#iW;9lGlPGYyGdwblN!^?!Yarghgae272#iWwOq{8mV zCwOp=hIdaC#tupPJSfz=par|IB`O0Ac@ZYuS%%!FX}lh9?Qv<8aARO@6u6J>$n!!c zWWObZ>|3dL>&;%0uM+a&ILUILR+p5@Lt(8lqL@S5E%)r_qafr7Pm zIXt2_oz>9LYz41RLV$XE2yOSCUNp?TWqU>Of^N{8VfZ>L7eOh7y4@+2gjNB*b0A&=vGMKjWuLr_DJCwigNoURl@=u2UJat$)$y|O7y2}0^=#XL6~1nOypVo*?Ue#L%( z)yz?xgEyz(y`~p>`m4c=VJgqR;)F612|)jfxX6UD<*KYNZawbg)ZHHfEi3nf^JK5hu%Zytar6k8P0vc#82 zh)URVl-%$@demh|S+M%0P-Su^6NlE9F(zd`Ukk5Y{-suw=pgNqK~Q zOQN|YJ!ZnWD~;7OD#6e)_a((>VG)8wNDMHri;%({vvYVxm~=zaw#Nz=Qh!Yrz*l|7 z^AHA`c-^fT?<2wr1^DK$a7(NXEoiA^4S-M%Oll`+JL%fUOznlfP!wf6e4F zacdcg7L+0$m5F#-33!skicX>--^_3nb@>&A!>SuM3iyYBI*&|@!AGOE8sH|ZZGHs; z=wn`_*phj3D!(QQ`6;e+_ z{(^A4xu}fmPeHAw9R#0#jsvd?AXBgT?aggR1R=sVpE`Cpo;WI`u4Xs%!TLtI?s+ zOS(0(gleVnm9~fH(2g#!q?tUlOQc-dGOlfu$=U^iJhF**b(#U|j6Bifl}$16c>|&1 z#5yY_3r>tvli**xhv`1(c)b2|$6_@qMb&!p8R6BfN~HT?K%iN`CEJy%2|Tj0-MKY% zVC4Bz?Z`h<)R<9wO2#W%uparf2I}v~4bvCsyX!uRyDLxiv`mR|2 zyetL@rMeoHpP&)nU4>R{x4zpRQfke*4J>LjnB=bDB0}dcR?jSPtRS%#w@aUfWTw?? zOr@L46N`Hbdn+@~)ZQ<-2hNYxVhkrAynQItQw*tY^+|9x>EKk4FsMOc?st7T)rsKF zAE3nrtRkyNg8oF|1=xBR#+2nHJc%msQC(Pxd}UYh;h(RVbW1FL)brkUaIQ->jQAUb z5X?3Z7@`QIu%MP`AheBAhK8sjt7;zPuTcg}t5R4ujtst3L)5&sC|xY=6b9T?xl7P7 zCY0+*_ma%A%kdyYlLcCfMpj=0T2ozsSjnFE9AHRnNfXE5d(j8{nt}&ag%Hz_-%*VJ zNwgM@@cU=RT0kr$flDxsnruutUP$Z#O``g~(jppJmS7l#9cXX`(>N{JcwOLz|REzyK;9&P zpHzT6DgPgWJ`ObhKS2BoApWM{0Mm2;P0~RB8X)*52>@b{{7n)3Q{@0O;{lrB0nG~$ zb~~`}r2#}h;0gT60h7glp`!WHKtsg*#USbAfVN2hNyL3<@cBCve7JqN#ap;&@XZc@ z3^cU(rbD1ZIKM?ES@^~S5C^qv{Oeexp=@@6sTiaoABVtnJhE_5_1k>Z(E(^n2~ncSgZlp>dMdVXEL^d4AMdL{uSv>Kd{r15yoWrr_a{rdEOV4e~1= z|4Yy{k|r1P8?6lH_$IJ&AM8}#B+VUuZ(C{S`Z{oTYy91QOzm;I(87Nc6T2MG$d_hn zyDB!gkLEc4O2KwBw+EQND5(~ICL?1|szA(scEa<^_2zL4&c?xf)=94n#+F%)+CeAn z^xw!+wd%d0OG{y?dm+|-!2ZLbbwakfLtF&_pd zrFSqQ-BYT}2)6&VUyc$~eG^GvL-kMFC_R8M;$Z7pN%5s zV)>HA`0dbS=5h;2P-S?~MVS-i{^gU!>MS9J)uJSdp5ttEG`euDu9-U|aE2H3BtX+H6EJI7N#+Lr{Na8Aa(z{T#t zbaD4b{((W+pEwuGaE*|ew>mXP3>P6uVlKG*j|dkDMx5jC^H-buM>U zp@$)%W{^EMebkpKx4}4a`{9A5*zTCKtG87!vun4&Sh=lxVXR&HgK^gGa{-*6tC=xU z$NnaJ-5N-PuMlvzrKrf~#Iaw}{j(UzdQR;B&>4IpqZ(dxOLBVluw3e_T-vg_0 z2zvQ0tw;h)pbsz=$9trSGc2Nr-&vw+Xl{^v9WCk#%Xz&SgalA8Z`nf6-}(V?tYJfd zs{>f|MlJQE#w^((LmLjzakl?OlEn1Hk_0T%-v#y*Kb7vL;QGm?Pc+2xrA{``Mw1<6 zh(LSfX0rZiCs-<1sEWBOLcP4vs4UhZvO*GeU@iHZAgo1 zj}=j~U|Cq6iz_K%BS+kL9k~82&8@JJz5MsC$DOj>zhCxqTU^shCc!3d<)XSkyAJT( zh7hl5n>Po0*SMIBv5t^HeEsMv0R#{=Zbz>%v*_zEQ5KrGFyed0oe?z} zEZIFT4r-oY;4(*(5XnOJF^MtEKWkqib__VcIJ8B^urVI41GN@b`E*2egy}-FNthUE zho6AB$(b0VSolzE`MDVJ3!|Dsuz-CbG?;CBskoSh;IEiSCiR)JUxQLQ_@aD-#yfd^ z2R}bNGC_Vqcu_)&M9fwKOv1V_F-GN5?NFYilB*A}LN!~VSu;O&0XDNmh6_bOcHm1C zH3$g)%dnBeKqujxG^I>^)+oiZ!~Sbz(QOga1r^;-4fA*s{BIgb*8YWzm5(Ol;AG!q zlDTnoY_wGILA^U;BK>Jg$ZwvzVXS=xAI{RJ1Fmg=2Fl69tFrbV&BWD#v}*4&rCTTz zy1g_?S~1D~TIEknI;ROL%4PkONZ6jP$QAahvdEoXRN4-Wemj*<*xr-F6&3A3RFt&) zBb85qVOH%yd1}WAt0q?o?qd=;PeKS3yIq;u1B`(^&N*~gKvrr;YrF$8^SJL8I|QilYNB+@WK5BZftSlCUs(k zyx6Cge=r%C$X&Jjc?}&(>CLCP?|xM8 z@IKW<;0aKs!5O4^rsoEBznvxgis%L(gp@)vQ!ob(PJ9@AnK8bFDFv(b7KdM!m8Fb{ zVggC-q6x5fv(lwf-Sg5}vO6;E{@y-#y5F1-uVkI0DcwiQ0)ofHlp9l5&TBPB+f6>o zNMmS`qRbSP$6;s-kDqzxbonpH72S{9Tr4me_#`HKm7QS8sqQ)R>b;11*98Fh z{?+M{iZG5U@nj1bZh~J(O-x?NS{E;5Du*#X?_|V`frBE6h(qA07`AAb;fdKtZpH5* zyqnf6-4;#`g9y;q@-gb$AUOB0s3{y@@l*)!%Je&*oiH;mrjHU$5^gOUZd;i6gX>%t zRWO7!CR0NoFiQLEty|~~Li=iXu$qhLrkGA&)5(%T^T&5bSNiYCi1r;K#X+;IJO-WH z`eZ#e%_Af@5_Lh!Z3}i+_-%^1$v*4A#+f#%o(y{oSHX#*QKu4O4T9KVMV_#p+WL4Ir7Pe01_ZU)K9zVQrAv0^2}hz-lsaR8*uAk*I$ns5-_B zHw!e^_)%Qr`?L-2I2v7hOf=8(k!{1o9;I5^{PWqR$|_0y*hrp{&)_K}9pL4cEZY@Z zAPR%GH>m~Ww&a;QDlQxFmrF~nFoux*LGp(NV;+I|K^tKp^t5*9&q-O`e504v3%_BF zXfb$6$vAmHvw{Lskl#^Z1(G`Mbman4qsv;ytUC1WP*^fXmK1#=iasSs)8UHaghVa>*yUHCF|&5SU+Ukaf`vT=mg%!==Gq1Yq{d$+H6#9H ze%==SB=T$AiRzj-z5E2N^(V%+%_R*FLl;Jl6Gyo!S=h7dyU8u<=Zui-!es|9ccVBJ z4fc{*LDRgDXvNLn`Wo|=jqWtUJNIWrVi2<}v|uD6j`p<(qjzd!QAEbi9m8}RvPN%I z)zipO`t5_*7=7(>?+*%3|D3d>5=bSF5RO>NDM0rSi{oFkW4=$QZRl}c*Q|^w_al}- zKX>H@5>;~vc$OJebIxL0dW~d-80vfZYtpolJXuW5(W$I>4m;<`BU8*%y8s4ALgyBL_aJ1iJ?yBk zTFHoF;r0@A5v{AvF!^x?o8Whi?RqY&jv3x))0tHtGD*o~VDjZ-c1dcm-TC9P#Sd&` zViB?w_Sdt{H}m`?5)#S+5?C6syh+)GfNb)Dvt5J@iBe#xfeA%<4a_6zAgEPRYW=La zz83tk8eyzXNUPPQ@cOG$gB3%p&h2d2g_!Tw!hjBUV4nq?Hg)MR)P2{iP1Z~fPB)ke zXj+mn>C^m-e*y|kAwEXSuz82wS8b;--Y3n-J7&vfHNq6uWzp1J z!H-gq@Pvkq%CgDQCP2CSfL`7W)FqF;9!wB9k~*fkd(q9V&=#y1OZ5L5bZ1`}%JmKB zjvzlnmo%6;@Or^6tUZ|WwabTFiGa!#E3OI*YM^FUr8Pp+aWqLmTV3C{kah7Ql~NCiaoHI;$Wae;*ce^)|c9HzB(B>){vwbPVafKJ?wP3%dpk4UoQuV z1PRzKd6HJGyG3tkgz21>CmVC5ayu3Y0Q zG2kd6T4^j2R-|8TEY^D1=U=psSq{KeEVxPhyHtKS#50e9o~pe{Ce!CzjvZD6$xWiN z4{AZEn>aJ1V1XDbq4Fx9868(t4n5Conlxh>&Y$%^4??Xqlmv*>72-VO_$UHJx_c z_{RcJiM?C<7Gq5!$$_*b{qjnC2+)iD4js8b_1_~Bu5cz>!q z+ySsX`}d(-J?I~BTF!8OhE$0Bgr91of#Zz*VRbnxV3(4(Zz$Sf4dZbky*P|VR+BcF z*VdDt|ByL4l7cAF&;S6I=>MI}`EOO9nTf55vxSipoxGjBi?xCC|EF~nHza`>kh2#y zESuFTzXhQTsd-yo2~{DZAX9ouH|k{8wvxB1kol&;`1;}y<r;ID*dB8!Fe(a~#dUI~P;F|?PY_Iqo)LdK@-0b=>D zE#eyWB5p>D%kltN_2L%U6YpVJ_6-sR!LL>+->zO(h%Y~jCAG|bS{O1)T++CaHpb^A zw;2*3f>EkjzcO`vWO)#Dsk~EtxxXE{;MEo`|kw#|85#tc{>YRXCX&BCnq~s6UYCBA=`4oT0;4$Hnu2yT4yAM zR8S=2*NQhmGAM0RW-Y1tL_k@Ct+%p=c3GYmT~}Ub>9jH`%?su?Tc;Qt1&}FiTKGMZ zF*MglK!5`Ax?eV(W_eEBW_VsUJN-UpvFw0P z``}Q7Z(T56D8>xb1ptT;u!qW`4;ZiGc0oprqp9NWU_w42Kn=L@4+KDA(vuw&1(1~j z-{PagP?!(0AWIx7a4}7PStbI^9nlMdC1v`2l8n$8X2ik|El2FjUAB0w&7+LRTW)iMp>5~2vbciXtDwi|JGMcqPFGF5GKS-4^^m|gypvyGofhjAo0in)Fg zW;0E#jsk(B1$--_NY-T=Zf-r@9Gn&49cIqyF=E~Q_wF%c*wR*XBJ-fe9d~2biDmF+ zt9d~MCV`>Q-10hm`qSO!1264{QmMpqWWm>YB2z;;W+r>?!Pf1@blEkzb~&se zK@XY4cq+5;;XR)~a&8;OL{Q=QJa#O7?K8iMQCW+Z_+aj@lhCcga3BZkqjxtdrcZ2R8vT-*{v10hgtg73*Q4 zo8FyfkAaI+LrEoC2&;!K)$CbesYlZN^^8rTKJ6%?)v7ObXGll&f;G#d?-7DplY=T9 zv?eR4dLgWt80ov?+V@%iWf1V!LVG|$!JW}Uh7p-)nAoUj7+8%~DxVM+!j4-`;Nw~4 za8`kr<-;DDujnh#SoPwYJmE#RJz^eW(sXu`?qYj3%FZ$lF0zdJaUtPc#~bVU=Vc7e zeMFDr+%F+c`7VzP>l%!=7;%LnLQ9vj9EaB6KK&i27IVe#^-g55ZJUA=cP|23Gfk7K z{-{co+~&^Df-%!&Faex|{gA4`J35kwP(m#XZpq8^)<5fKM3E;YS{< z9+a1GpLBp{(-p(gPKs+o@2>?0Oj4k=hTwq;LU5|yUWth?8R+zv`QE6EMaP5+ThYb3 z2$rVk12NiWI_wJho6DulO+?s2LR+@#(0bOS96pdFNId;LyS8yb_4}8vLr>_ zD9y7+fK$)!YQ7n2QN)TyMFj>+rP{=PuGs2Fd*pk(#r>6W|H>ib3K6!-c1(lL4$o+H zh9NzUDJd8KN5Xke?6f~FBY|%Z?o27YZy|l4@w3!BmM?L3un&s-K!kc1h{QKGZ=d87 zx3>?gXs2JKD@^ae=kt%>sNEgG(RWDN9mKc4-vJ6ma9Xiv*SXENNp6l=+jPzlLU9Rn zY@+3%CyL&H&Y=do5OY}gwGpXMshC4h<(c3)thWX+SUGYzfZ#mfrc66N&nt*tK`Q6_ z9m9N);Nvloa}wl2DIB>2nv!|s^R)n-+&1&vj+Ab&ZcjvQqT=a=Np68qS?Q=>Nr})9 zsp38JiFY=}{v*Sd?%<-{;G&!~Z=y7eL`f*Il29T6;*M{LDW4ElGsr*_!M zM&9?@vfj>sCjJ8ASU9hnHK*&hoLaBh?%toTh2MFP15G5oY^A$|2xB1fyK;5}VfZ(> zrUPpvfUasnEMcJ9;jDjTKRGkB2t%}!47xxGMD2bTb_1p8QD!~4CVh>e;4mmCj8BP) z=NDvPeXIp&0U#G0^5t}9D!LZ=ECgBUY|5C$_Wa|?R4z{=>_2B0)ADkXb&YIF)cbgV<3N`eW6g7ApP3EC4 zGev>^*3Jleo)gdCe0Yt8C(9^TtmzIyHEG|BEfqJc&M83&bZyy^x~^*phFX2S z=S*K6Icj%P3IY{H6^}T&ICPQ5`;0D+{~^Y0^d#sa6xZ_RtL0 z6Aym&lY6|h)#mQVVaVAvZ0@OUS}OIvC5VNev&oWw^V8;K4GN}YlzHqaNm--`MsZp> ztj{*BFk^SqLoKwG?M=~I{>Th;7KzHFF&3&f6YtSlr1xJy!ftLTSd7l487nLLY7Apx zZVzcunzCpI)ELSJ1$6xhsDzYV)HL~B$tPiyv$VsZQ5SHVZr&-+eL+;=kiGAq-$8gY z*w_Pd?H$ahKXYbfV&}?kXJ%&4!olQ9!^*%x&%nmR$-~6MS+8H?2Fb~~|Aakx>|ekC zmekqyBt6{1qyVSuT<&(?Xg~@z%7{+BEDin|L!f2Lq80Gi8{uqWZI++X+j+R9&Z~q! zQ|xz@u2m<^Xa1|@(MfF*d%aerW@jCyyZc&+l$Crc`d1VMw1Nb+JNigPQ2%rq%g9Ld z6t|PCSgTR2Ja<;=4482e*l`SzEp%EWp|hOVXECVOb2jb$^td^>s>@dq$y>x(~_x)jKK`##)1MbAju{e zI0E45rKZTPlkh=y5C0@&AX6(msKg$_73CXO(koV&oopvnFYnk2Ct%k zRwGS$>1~r;H_~i8G*1hWVvkoYN=dhbnwV zg7F9AUpER1$nVtS^fSPPe=-kLAQBAB~0W~cltuhuz zun(ZNpf5meYo(0=EOb24tbv4 z4~`iIdSI`3vf43!nb1#G+5BK)YvbKpM+b_hI{tT^%|0>pAv5&>nfaYP9=@dqb3s%H z?l5$v7v9)f1!;AbuS#jZu)Ir^lHQ;*m;*CXUQxf;T`OmT85nzLy?qZwgZEnshka@> zL_8!e*pzSTL_DEFy$%FNN>o@i8t32m08MV=QQ6F;w3S0?4I^*3B(M~1vk~Y`k+`<0WJu%k*s}5Gk+|ka)&dJWkMBc#Se+rTm#SPm9 zet4b>sqD7U;HH1}b^%Q-T1!RT0tkZ2=SmrwXuVU}IXOrM5yh~4EvKS*)&?ev2L_#zs+ z^j9$=sqX{b1lad<$rFW(+S5RW4-?StlF=N}y*`qpi3!mlc8tsqxslHp0!ke)(Pq)N z*PocrUAV-c*L&EHp|5@uwA0MS)6Hsw?vg3D3c!QT6yk^PwNaW45l^5yo3}Zj_oFu{ z_V`0}LQRLFg4SYj*JZb8n!~TuqAXDd=o;8#&{f6HnBDQ*7w}`cG*UWb^s-F|_`;7~ zCx2j@i9Tqw2TDMZq)@4;8PHw%cCJrgg-+tOEAJ@aprBUjEDOR^fLlPpXgSI{A^$9; zX5CE5N$q?I8xNVdTmRe~P22lscZ0^(%kmY<`c(ziFpHE?`6w*+ja`^T+Hl5{3H?8; zeN&XB>$YUF(zb2ewr$(CjY`|LZ96M%RN6Kwo!Pn1xqbWGbGz@@4?V^j>uEi$|Nr8P zh#7Ov;tkhc|8}io`Hf4bGCV2E(jp6FHgem9A{k*YwXz1*!nqGd`2v&#Gm;KTaRO

6c?ib#El^{ZoOfe_7fxH{12pAix9*w}zc60K%^CA& zqUeNOKM^P0>lZ!GZm8}|la=c2zpm=C0nOf{Z*2?q{Wkrd>gvC1TZX^&CMg=&8r#`O znRxtD)fTJ2XlXBD_|i4@+XF)w%cqzZAch98BQj@z$V0=61xN!Fny){Y9+|d5GO;`T z{JCbyg2}Rp)@&KAn7X{yu?QkwG1p?bw5C$MY5gXZTY9v6k~?pw(6b(xRK;BH)q;Mm?4KLKLTdfu=w_;w?1_puEhYvFDjivV9e?F2x2 zW5Ide#HsUL47=Tgqsg!z3>UgrAvQkO^xd_^{Rsw>gFGwkQjZime9l>Y??IE>2gBvw z|6V{+B~6l0f{Qa(n&>GRo0(xjya$;Ar(1eC7syn?fPu}dcw`ESQYcDYlg=ce)6W4q zsydHeL4u|jcP1(C)yzWk;pA;i;3H$pB>Eju?#kPh{1CS@JKMzhP%AbP($`8m zc~DXm^ppsj>nt4AyCK5SXAW`e$(UwZgZee~93{574>1mQh zh)NI7ERfuq+y=5IQIk$`myC&AJ}w8Inz9EG;u@gIr#4nDTNEKK{2iG^@#k*liK2`2 zAyj|NAEM_=^CsEDmdHk-36$h4O$o=eO2w?LLqaS>6d`|Ak~e?K|ID)|HA!ee#-mlN zwu~k}gg3=?!b8bkCT{5Zh?GTc)4Jd)9$3Oyl8%PRJ*2jj7+ZH8K221^lu|SaG`m9* zbtEVyS*r}yU_+WK^f1-%oA;(QfMqIyf&sQL`l# zohm|zWsv=-=3ri~>C3*dJ4HO@b0|AxZT($SuP8}P(C_J1JXwUw0QzJNnMx~6cAT=` ziEWx5!<>;OA^HF)^w31f)i{Gvpqv#8mBysu;*}_2lgnScC+4o2#dq9)PpR7nO6eQL zi*ig@wkLwE$^gvR22Fr+j_|M(9>Fo`RhPF%4oh{Si`V|R9Vxwf zsT9sj%FCy4i>RyWfL&YWj>4yM%k-`-uuh@OfKt2b0=Ff93)NM=N7FUcs*qo<@{V{- z-ga={Ep*FMfP93;g4G7rt9WbmPAV6Sf=THcx$SY|#n40L>@^egr1B1k=YAuG;y1uG zFzctv07|+$ELFD+zmh*D!BZmhht!CPxg_1FzZV=?<#Tg$s(fidw6&LGX{}!nKn^{P`io(c+8To86Op8ND_3o&%v@N0A~n8t5ke1KR>9KZJ^fjk z(DEXsma{+RGTspE(S0&YAL_m}lo5CQ2XAd>bCSqr))TSRu`5KB$_p2ezXMXT^NSF{ z%h2OQzrZet4O*&pjrHr@Wur}N9yvj>{5PHM_(g#S6O*(vP1{a>;O%iJ+94NNYF4Aj z@zGi0p2|CLqCsj#P!bqtUNf(BpvvtCyFk~{g*6{tag`~Lv;RKKe znadWcQCC~6RgQVCu4cbub8~X;)mr_9J(N3Q?2z3jaO;%aH_ga%x}fH=KTw&6?Fs#fz{7)E|9WY0a72xBBvx!yTiw&z8Ds3xX7BY~i) zWimI&wROM4?dzmV^IXbfsVX`;=$Pqe`R4hg!D543t}bw{)-kT|FghHodhN{guGQ&0 zlYofhu2|S1JQr37da}UNO2*$wAGxmE$&>!vhanQkb2YWjIoelBpd7 zW1H)>L`_@f*7CLiRYoxgWLaKRx`lG%F^@$xVXxA?aIAp3%P)a|^&+i_UrH}Ge-^q2SO)tnQ` z?pe%o^wK%RucJS|EG&j`_bf#ko3dxQtiiO=joK2PE75nk+SEjOk9R58#sq8uwP|d~ zs8M&!H<5SE=VI3%vRQq|PP5uZYKUs*f&`CTMRzSAL(!c|sfKz&5FlaK zcL6f?#!)V}76v{jNyCdLhO&qz*+u#@OnHU>e)WurNP!C5Iu`dEXXh#W z=sY4{k>SS{`VKIho!M9>3*v{5sz9@<{VmnY8+xN;Kg`yhKu`1vh4e-py8;^7UvEov zu&93OvDZjj5)Eh~=do1b_h%ItUplWo5(s)LU~L1A!#`_6-ehkrJLm246XI?3M)Y+{ z{kcZicw?o>&M>7xtdelF z-SvVu%{Oj=L#07bC0U1vL|@b;sjW8438J!E(y>(nnK&-UGKTXhFOj-fJ&7ULQl!c9 z053a%s(j9mEN8Wx-Oso2fQUH{vBex2;9_%H)lxwgY5BXb0HD?+t(6`9$ms^p?5xwL z23TeutMJ_WN}2~nWXGI`NRNiRJOXMdBC}s5#(z(ww7{^i0XmgZ1zn-Sp}7H@q4)=r zB#rIiXLf`f<|ShV%K%vaVMClN0}-RiE*7u2v}B{I*f-JNWiMgk(L~su`Pi| z<;;>IRk|B#vinzEIPqP&w?Vu(Ms7t$7Z-sb>c5wV5)zQ!@lbyB&PPF-(4;x> zT1-KFa(=J(Y6z3RmLlX8eXI?GDV{Ae0d};BNL*3GW%}9ncr>u&S!Ub`1>7%G=H5>8jmqraR&D z^=W1lfYyL2l7YH7_ao>eRRA`%ky$ONJ!AOo89xlpfhNqPirh(Ov_kVuJRNI%WAU~= zCLx9;z}n^h{O;BDQMH;B{{)@F!xmnWZ6m(Ah9>WtE8hw%fZuc2A=_R>pImPhK|HyO zrzTbfd!@#8y|bm4#!c%%TDhyk`ciyb;i;Ypg%!t;T9v!kU@WGJ&8G6Id0pDH*<@9_ z0kg#_OqQokQfAxAD`2H1b*$DP?C=;mEe)D!V8q1uC;;28lyJ zrseVr@E$a_{kqM|@(rrDPb~<*#v|KSDm3Pp7A>YqOgcvvaEgPDUZtJvTB;I@lg5gt z$p^!;2l9eg<40n5Y;vEozEtlPwU;mT=jL<{G?+@om;Xi5+)kV%*&WX`%_(cu)TWm! zPZVWhIR}hds7@}!b~onyF@*?Co~G5IIb;nj96VmGM!EWZhwmmWS4G&U?hZ92<&Tov z&;X<~<)fy6R(s7+8ekLeg8h~NmyNmG@&HIyXytked2UDzV7vXSfcrN69q1#F5jd%V zvtC)GfPua+ZwQyEbJ6w3X9Ohl>Dub@d1!v`%G%u+4hOP^#)V|al#{c2H2w(W()xm^eMF>G#%;~(=M;-QJR?yej*X{+h6`!7P$Ip?&FV6 zfgIye{t`7JcN!Oi*%I~|Tj)n?Qu5=vQ4BMp_?A*in!0cGLPqZxI-Q;OHkLRCgd8Rh)JKMu4H| zxZiJoZ|@l-SYi$~v6QTlmUn`DKwt0NlQ&DuYC!tNLxiapanu|TafSrT2Bb=00^K9m ziXBUdQVEdBR4_FtcuQ_ZE}j;1$_huhc`S1(UEKQeNph~NXAq}FAr&zMg1$E0W>yUw zW?5345&9ZWdF0#y6o!d#FR4vRLs#@iTy(yxSKfAieXC+H@JLX9h$vtHfKIS~J?sCj zlK-CHBIDxxkJ7xnowbG0e@NwISpiER0r)D_Ml2avKt2RIjNw8sgrD%?=)ZXAVW%!= znYbFbuqIa=e*t?d*FEX?3BhA!ToqJyoZY;A0P6?7A%7qP3+`o>5h3y7>Is=7Z&@VP zGxop9FOQ$6$s`{p7};7jPgd**;c(B0uFOFM9e3~QOopWH$=-OGQw~;c{CusAGpHfXo97wXUcMxlCE`tpqwN8!R%?zSB0AFc20p=He%bgNz{-e}ekv zZ_K=J+v!MISu##K`NrMN1jnUQm-=>Xv!9B_NApl!iQ}zRf^^r9bgrC(FF|s|7F$LKr%N_T>*YCp zyu@HdtSGy2px^6;zGoFV3%hMhW?ihDH2IN>L>de}L#?F>xb28Wk=*;AbR=fwKifTF zG}s_qeI96T(2un$)1W_K*Ap#O-uHS+-G<}cGaot7MI#@fkN2XWZRc9YV%I!81?3%m zPgYFJ9~2)9E(X6YjaLnh{hTol6M@vi;-dxQ-MbLOM8$VEEZR{BOE);rD~pd#@_&y;q{kv##`2% z{~z|AEv`{2vl7o^I}6-Ay2c+&C_wu)+n;^-cl|M)bn4M2@h=f z1|iJUCJZ8Q^`V3f&JEmq#8XoI$P_lABoQoYDsZXg5h6UyN7)-@l>WS zF(4OKS?T@9Tl%AtES>v1)WP{*%&&jH!v9{dL&?P2#OSZc&A*=O=-B@6;0=7}m&Lhl zH7@rvye9*4EKhiNU|!oSnfPFwj0B@p1J$b~t~UUlP?C1_p$Hp{l^sWpM*`yBlexXh;9~mV|cp*Z!MKCb4)* zU$m=*i26nk`jx0pjf1i~jS!>vF*lOz3Kv!J?{K%HN5jfo7K4|k96iB-F>)1MvC16Q z^-Ui&uhE-UvPbpjEw7d}Ju)tkn2*@q2>vvE=nRCCG!$NP<{p)?jzy%&-hUt>JIOEh z9?MXU|%olK0CEo@BwdAO66WR#Eu;C+MyQ>dYSl|~rKg9tsVzsSb} zL;xnG0aXMlkJ*Ta(l45_C2z{R->TU!bfVE|5+A7iW|4kEp%8bB9hnorrn7NXC<-oQ_^Zvbg6Dxy)9e4$a$KGs4d zu%RFutcKA|qO9>3uoLTmPNXPJWAX?va}7>+xbqlwo#K9SC7sNw3n62wX(xUXah=-( zReP@9A1WA#642Y22@fQ*z!TDAPG39p+MxEBFK~1%QKp7mXHvOhGQ@iNnexjhJS%>D zmVA@>si>0%G~1W@6;FF5OK@y2Le|?paTTS4VesVT&%#xc5~b--f^wkCC+%QaL9M}f zpN}xKbDkK@!jHAN5&HWT-Mv(OQxD0BtB(Dm`;CSQMayukwEn744imhx0XUe+{rCXY zCJS+N^*+ME=a9J=baN%{3H^jNzf*F7r7`V=&NQJrRf@4md6$G6Y_i=%|_b4AH1LI5rVBci<-rE8XfRf$88?Fzi94{bN^=`LmJE+pEaj!^LDa>E&kK-!FDqnap>>S3uy}{=YP-tRjX;aZKz^w-bK-9sb;N8ERedcF?Z9qBucL*wG0uI zU#|Y#xQ)t8=VX^Jxl_lb%Eo}flnGa|EuNiEv7$Teo=sSq(By_kjWz;mgThs>jO`l0 z`T|}RQ)JGN>SLv*lM*||zO=jc>AA<5GW&Yp!~@)jd_vCZPer*HR72hf7&Y-$5m4S} z)Nu#u2=q8WcGl0w`hjY4Ao7$DXq%?veO?tshGH!uz>PedmC&ZXNp7T|?m=Dm%sj?@sslkangGDmP z;FSFA?$76#WUn=$+O9c^vp`8QS#T;I#|(iZHkojWoeUps5!Bcftpyd;%3_cbW!%he zw~FD@)0fi|oV)s`9YCaH&S}S^C2XJv!ioBd!$;h|5y7}$C~8}i73$ONIN2_7OXYlaMQ9g ztBJf^kAcOjVbGM9aaFk!Qj^!YAOt*w)>&1Gy`8mDo9)_xAOINKAKq3F4VjD>Bjqgm zc&{?|AaR?c>|m&uB972%t`r(Y%O1eqSOYUmDiLDVUz&4j77UA8YA(u^T^3YUOohzLaYCBwE;fWhw(#Cgr?RM)|XR5Xbio3BRcI{ zBXW02DSboDjJt~VOu7p8RJ4_EF?Cbx{D`FT_82C|-GzoT-KB=t-NlAGpI<^Biy}Sq z;pds6^vcAE3Jsz6H_)(n0^N_65t&&0QkpGw#s|RJnkn6?RCGk^FQ~negT2gLeNGRS z=pFVP&}gJJS;^q7XQVBU>W9olrAQhfY&0i~6U(JtNt2fu*DivC2idj|zCg7WdosW@ z#~AK@xD|QJ(kVwT7OZA!y1%_LJ+CeLk%v_WML2m82Om~fshyouvGY+;+G6}9YjP&d z%$SVH~;BXT)M8t4D^veYYVY~Dc1%S8j2c&YAuKU;1!seWwFl2Qtxk(o8@}YdT`X#!;*y>M@YRB z_=EWe4_yt8Cro=3xY%L$^DMG|E*Kr=#X*wxLpaa@bw zo^$4e8E}H?N)s{hFY5VhQgESVdbpA241YM_y` z;nk0^;_v4Uuu~U~pfNmU^Nid|%uU)!EPbsvZ2R-(dlqu)kp5lY4GMHuw~XJ&c7u$ zs+o94>z;UeEpI*@p{_}6Z_h)nIQ~SykG@(xmTuSbeFW@YM*K|8|V|nAB5+SJ| zSCH*n^-ClE>(%`4%Kz{2ToqdjQ#(hS|4aBA>8~VPhH<8egj7BMERZjMViUY1LcRr* z%|fjBn!Y9wXp=45y0KLQmK$5K2&kCP%`nC&+O3hjb5=haN-`=}M9=dMUU5#Rh2X+` z#*hP}+jaZ#hF8xu2b7ol7ura;k9-7#9sW_DPxrtfM=VNV#6ud~ zTv!|b9TbpTcP}1(XP8(^`nHW+A1wihcJ~fedVd^Ndzj^qNBSt0^-Pq1w|jEfkWos| zL>#rsai0i#o0p1A^D77YM?8N*2?0;By?I1=2BX5SDaw%~=1dZ4De2T=Yeh!o7F{9E z>L^P`c8rB+XYp|5N_FsYf8>IoUCb)8Pe?6VS zImU1LaqFtJ)&7xvM7Eib)Z|3Y%~ms}+UUhlfw`YI>B%!w@%S0ysz`_4z*x}0INwn( ziftq)jO{)d@+6kINt z>7Xgrs6j$w0v6>=AV#6BDm7%4R%pC^B2uEODhxguHhN#a-VF=MS+#T4?kzLnnKHMFO4dYk~ zTXt~^{p80=mV|4kxGmb8*cPR(!t&T6mZW8{uoP-D?zKE2F9(JkESV`Hu+rfAa*Lk< zY7MxxFx{$5f?iw$D2c3sUGXx`dRqXj#rk5{Xr%EaTUU(AEvP(7X#2UoGa(0jq^PNA zL24KgQ~mDGx$^q-{CZ(;Ze9#LGP0~%x#G&q3E;%z{6Dx_RIkYNmiV-O%;V&p>icSU zp@#D`25}L@tkKFSkpmZGY1Xvf$=R zmQqBjQlNDuyT-GLv!tNU^_k8fs7My0KQicc4;bW@XyYlMB`eQ0pHC=H_Ra+@J^0gb z{h9oF1CrXa@MM76xgm~5RV_N*yd-`GfSnh5gRkByUU2}P5(}ExS?g})3o7kC-RD~E zg&ck0VQ#AJJ1w3QHo~Y0>;IFx^O*z74DX~5r~PnAR$?|6x&N~@Ar^PEWO{F<87Y|G?zxqf_SbxlRpWD28=(CPS$qFxr%smR@ zZU)Vpe7x50E_@8%#T48jhCuA|2Z$P`MHytek8Fp!8ewj6wkx=Kb^JBSQJ;$oyYr%J zG;`e$w~PRr33E^Jq$6Cj?@gqt^;Q{iG(1;~L$&&Daz=v`a+Rf*RFlt`csmdcIoxh< zPR~BJxs^-z0M)SEeYjw>FYdXGKn`eO7Ku*#CF4rh9&Md|e(e$63pl(_J{RW?w+}j@ z*YTx4C}04RFVaV4Eyv&T6GJ>2w(zZF9`g9h9dV2n5$F_zCU<0BH;2I5Lb!szG8hv) z++yAt!Zlt~-GOkA(i?Kse$8yQsQvYQAcp4KC$To_?SVD3k1X;E&N~1F(k_1X#x4_= zX}mpz5$Haz|5Mc<0w{70-5>%nCW+)Bh2&xFW$^h=^2>jG5K1-jCBu--_-N_J6uM{$2|DKciLu+dcjd15{N@?K=hi2`hol2^|usuTWK8 z%_spb6geyzhl$iDPRo+7UzH*oYQ*S5TQyb`$TzH)&&zL-+N$QKocbm$9x#i#Cp2wx zZKpTgBlGEVdm#tF)^8#l7e`Mc(CLq{kz_9wXKLadwazG*mN*wAXS~s0`jIBqfCu#~ zJx~w@xPg*7V^VYzvQrGoOk^N2z$kPbc$)S}C?p~%--TsGi zdy36xlTC+AqQ%C6lm~9f$y|JeXT=q(W-4*+Y6se<#%x(ytQEbaGdX#^p%@PXag#ea zco28{4|=F$>?2vn@`H@jL^=%Lj&U~4j}((Q>`x_%zUb_zyDL|&d8W-(op73j04y9< zG)*@tH%rYCn}oF@|1l}9AKR!H`O@Pit*02?zmZu-We=@2&E@GM7((6AU>P=iXfj%- ztUNl*Xd+jfsScMiSl!-JdnD8qZb-=0g~V#fRq>n#)oxH!Ne++?6yT>(P&Niv5G5hU z)f4UY`Z-yNy$kaK?Jz`R_7d*6ebhk2e(}iP;Pj;4$oG@tQp_r-==&!yzww=AI=Z$f zV|mXsO9u@&A7dL>k|;0!d|}$wbmak(KdVVn43TE&?NI(bxveKvZ4wzW6|Gob*N{G4 zJZ=*DvXVNBF)jkU)Rx=w@B;%=p>ULv0v}PoE@+6JpU`AstHoWQwLEK!lR)hc&q8_p z&KZ{H*OKqg7;)ZTF3SRnleJRD%1wxN@{ia@25mOa?r)o%TpU!@LgN*4AUEf%7Km#> z!caM-Z?umWRj;8A2cYKFLg5#B+@}arK|e&e(Fc_eG*cmiFdFvFaPq~cAW`cvWR z&ZvmcI|(Hl09sA?^%fn_@Uxn#D{r9Vjh@UY~~2fyBVrXb*z>;Fceq-2WEhlA+ezF3A+-D&#?2 z2YaK@*DGme!|#c8&`d@JxZcrO!yvuE%@4kT5)TH!9sUxSp-Xd*kw0_`9`wUkgcyFB z?F1|DitXv$^D89dYYu}7DUCw{J27MTpATxk`JRP__}0dbhY=eU`qRr_AhZ;nv#%JQ zwPb|I3;i?MIvA*zmmjY>(O7L*MS53=7=Do1XT&Tn-|q*?bnwE1pcp}^6ysB-{Yf#7PbbC9{;WOtg7Yq%|}0F6HM2f$sZt<3pQjj z*2D!wG%XkA_r%RlL-aLKN)v?`<0g~FiWI#Mr}Xl8+fXN()hC97p80=LBkMhm;q7k2 zKjj2BNhr~hT1{s)&h&VD`MqTw%=r0z!1O_Q;|%a-9U4^O;2Ct`KuF)vm+xqU3rJI> z*$#SmSMl#Zk`XlR1qK>}ciJ-qV@$T}BOa}K>h=qQ>!=^>GD<0OYa4XRp%j4z7M7TF z7y)g@AGr9)#HMO9;mKu)xDjU{f=jPqP}Ff*XgZcCtH)0l^dyi;sLiuJcuTrT>#BtS zvYDZR%97ZSVXdgS5RvVN>X5IhGU(23Zj8CBYRa0i|5{ z`HL#9Gi3QB!M{MOB{MOmZ}uDmNl0Y@LP-A)N)!^6$jTf{s?%@hCL<>5Rg%%T1yVP8 zJ0mIB`uK>ClVbyk{)UK|oAy9DW$ocqO6MwYXIrQ00e(^a_d|0Qt7xx+oB_=s$~ejz z0x2*9rjd(r7mGGZM|upDxwY;w{Q-vu7uoDqTk`L~r2qRWrK*Ec2(abr?h0QPrM9th zQeDX&RnF!>N5uNY<-^xu@U-J5Lk00sc0tT*4zf8*<#Awi!PJb@iYtYSt}Na3FRgz9j=`DG9Z%|^ zsMUn9Z2ahWVY~t3W~o**mW)Y`$aRqZ@VjxjsW|Y?RAL4VIPB!f4exmYs9z28-91P( zb*GRH9y{EIpF1xd56m3eW8SF92iqXyQKjjIbnC7Q!~s6+*MdPtD7mipsCzu;HK4GS#yd#Ja-Vw@bZ_5qKO+#(_aF;W z8X!3YZ*UXpcOK2b0KEDy2F-=uJenJj{3gD4@JlExdB5JLi`uF8H*km>UV|5ZM)qih zsM)U+1-Ny9VMwGJz#(z1{7r$b{au{eU7S+wv-81(qeqLvtnKRMW30QAQnw2R*Wx#} z+4zTCo>@OMFvHlo&f+K@Uid9WPMVG}3!3S;uOWRY%QrT2sq9IjOoIEB3LydL=e!c?Yq zXosus65#W9n&uSAfTlt>ek8~{Qk0jVc8OwX5Ka#nM@ zld7m>sIv&|YqLGO0udt5+E8>;Ekws475Rbe2_`SLL-!k4aG5+>jxuOwXt+#UZ&8AczOk zs)G~}a&ei6LKt_RZn;Y_I%K(9(u|DkL#8~E;Hm9Qk_^nhXU`iA5t4Va;*MGgu&n?h zU==_pezw)5y77+*M?rWJfoF@J@LX2jERYe{Yktq>ko=fQiMP-wLZiKAvB8H+~&5uuilqm z?a7;Xw9y2;9Qc>_96jl!HA8K>EhyyRrDu#L@)SXdTT?~iz6RNe1b{9L z-im|Ohfu}#r&8miwVCp0b|J~{QkG3}9vDwxU!aL~lY*$3JV|*)EG>{wc-G4FisKP` zBJUQ~KEM^Hr($RK!9s0DrWBbU!ok>bq^gJ$PO&MZYJ1Q|rC@$BRFcJy{;0W>Fr0R}PAty+2SK+CNr%ZTtAA}kB8~@}EMj((AfSzCb z_OQ2964<-IoD)XDMd>by?89lbMUN{5*@P?}l!7&yc5}jN!lv&wg`5T8knV|N#*PWV zXR!%j23g3N@5*`;>14r-*sYRYIY-JS$joJT z^HYatfC}V+Rv z^}WpGOWF3ik5Liab@&GFj%!+rq@0)70Mdr@-s2d_Qkl$v%LIzrvtYyoRr=sXt> zIS(JTKaBy+;OKoIpt`Sg_b)>(+!lDQ*yG-zu$eI^SH>KNEg$q!CHiLuYHv&ZqWv2s zh5rjm{yX#J`dcWeZ0F)=YhYty>-?XwiT^5SWo>~60YZREE)^@6F$YZA)a3(b(F00A z0*Pluo7jmLjO`f{Wl6zb4>W5&;q_kkf;y6rH7s*=K1p42A&3JM#ofh^E*kC3{N5a= zx4%9=$@~>ABH$4$hh3zhp2hp3#3wWmY&TGL1=RaStHXDY0G$Yr>hTLepFo5~n)ZAA zMQD+c=6;eOOoX=@fabOspg{CULaOfrooBiCslkC3fq0Jq{GhNzuRxhgHdLTtbVreD zd_q@G>SwFQ$lw{=fe?OMIYnY%q7*WdW?DQ{^p$E(7*CPq+GJp=J~=NMKP{Ar&0hGm zV?5c^(4Z(k&!Hll`O;;9eAs1pJaSlNS=N$5J1)^^j3KGZauHlnX`#gw4c|`32{Ndf z2Z%*wnqNc}W9bLH7oTNvG*ytUriMI4XlIyj>2J`+5mv<0nyCtvl@}+{i76Kp7Hc8$ zHV+u*6k!PIr53=o%#^(eEkg z!r2L7D(*6+$})^<_yqPriK7L%63Z}fI#czSt-fK+o?k2gErA9ks>?+?ECsT#@D!5blJ!pL7sjV6r+44UXPc znTE*xyEX(~&kmpq(au$h)ueT#)Xu_3R!xa;G}NM|B%I)MlslRm z#Lc(ihwzx?p^{y9X+$W~Jr)Q7ExXRg+`XAlb#>C#rAJm&QwOD-CdQ_2ESb{{(>xz< zY3ZeTmQ|=K%M2hZiJ0vAzd1a7QLy(xoP4NEIm1*jIqd8a!F zv!u#{>S7jS%dhyqCW6j1^K9u1&qhhxLh2*C>6B3oc&z3D#t+A!+I3W-qSBAKrRrq@ zZMp5I4_dG-UXl>AtM?BqEHcotBjPieMar2Lb-2duaD0sxemO5tV0g+M-GY0Dx{@T8 z3y9Gy85`N(c&B8rxrw)jX-`?TRHI&cW)d9>IHo9ciOAu_Wb@XZWF@} zt_x2s^hEX;)?nQ;wJG%npxq?x@_c?bos^&Ti+T1bXPfvfHQ;@KBl`I-v+w;g@W9UvsP>QoyC|R5BLz!p`MDI;vveNQIq9Biu`3 z=uBKe$kmn_nmurIgu&V;?*j19O1p!Fd3J-Hxa@+y{<+N%deL#e=?>$0yUy+R(cVXB z&khd^2CwsH-58`NKp4POI2Yd`m>2IK_|Zf1%Ej$ikdse7k9kAa~6wd)p**j%hvJB7fo}e)UFv zV+xp`G_akCn-XqrCzJl)&5K6WtaIpAES6YEHn&8Ui0k-=X3cEfHyvu-C$(OP{B_*PYawk5%lZM0&l38qq zNn!D9c_RrLWTtrwBBPM`ifn5LlBOura|WtK9waG?%@PBRktEX=C~FEgb|wY;4zJBE z&d{)RuCZb&`(UTC`Re?6W(p?BMI@>+s4SQ&6480)`B0Oh=0A@XY*kVpaTWKDZLy~% zBKmGMbf`Z3Qjr+xZT=ffI18lK+0f<`zk-+Vx|@mDSZsfnU^WtUnAFmpW~$qo17^8; z23ojkXDbR(uq1-R#Ne$MvdTbY=hXQNZPV6qlrmVHm&>m%OE0mmZWOO;YUbJOmswCK zX_6XzH_?+RD^09+hB5~#YazzTtVP~W{q~TfE-&5dlswpQe@wDPD062=S~1EP&a|9U zP&VRA&`onXyR{$`i1Lu(A#Cc~f;m=Ph3_Gmh1y@Ah<8q+_GCA*f>_I|YB4H*k$K=& z;E7kblt|3eTW8;QJoyy6hjF+zAGKe1+;gGD(~P_yU~u{+ep-)VDz%u#Y@}H`o%<){ zuF#4sOdehsiY*!v$Q*vPagGIleq&LY3L7rp_bg0_f+oMDV{*tiqfDEdi#a_0b>Nz=B4dorPR>EDU-y=))=EqjjO-kVQPAeqsjtwZ9L-|f= zQYYk=!H3%|7eucbedHTTSJ)GZw?7<;_J|lHuPI(`p2AMgq*Q)0$PJ?Upw4G1DkZM%FmwdRZ$XA}qSW4@ z6uPMHJCELgsy-7sw>y%qcGqrb)%!Z7FO+a>Mf?G2Qk+>Of{qaBjGIYmpi@)4I8TXH zOe(U3nFW&1NWZXh(idTtjjZ=2gVzNdmwZJ@@=&8}hBPw=q&$T+t>o0}-e`(f8E~=^ z^=eYfUEbrUNWqTTefo7PVPX2s^k;lT0=Xl@xSN9?uOwQx$2876a8_z0AZ0@kT&lk- z9q=V>ht;qx#v>N8r~w2*DV3Ranxzt;mMWmc|GhR`8e{|Mc#Wx+8gw^|Bu z@qH}8S^W6OR?5AqG-Wu?vo5PAybUpjRXqldr{S1q4 z*oMZo@FnOXZ6DXT;RkjSoq0*c)Y4G37vK`N0!vs%3*;5^5!XDBrI>_|k`@VEqVmeo z?jcuf#*Dqx2RAEMSyo3@bwlOSd2LphT;6BG%`*@03zK#FXe;(}{`O_!u|p-WO~m%0 z+R?6Cp30vw-&iKDcM{vqn02~50~pmtww^l=Igb#pJ?_x=91rhINY&(COWemmTTm~J z4xs~`7S%T@?&x|Z?uYD&!60VJr`iZ!9-11!WK_XySV2?C&h*?v+A=NF`ny^yGXZ9=J z+CG7Nfa{WZXd~}(hU);n4#(d@c`{VJ7n=Y_}QMV8P;#qcJ!))k!*L zHP{1q4bOZEM;;(J6T!n_hl}79o{g1+j+BL-O#>Sh0SGz}5!Jlt zBS`4_jYAJ;hkGnkHfH2m7GB;SZc!F)5l(*?CmbnWAVNGxm|%`DW{)ri2M%$~h~{x` z7))FM#=~(+FWPub^ac7CFK`g+;%oX2lTiMD2$RS;8k;zp82>kBAmxmuhVfZLY;|$_ zj8R!Fxe*K`;Hy9E%21uu!QwmQXv{St2m$1!aaXy**F#m zN}V5;IP^R_8sVgF-(l2`yX*`VcDIRPg+1y}H)X)^i6{t4Diub zQUJRxZ!g)e4SaMf0}4es;4V2#z+FukECO1p!n_lO&0V;ofr6Q%R994hF;mVC)r~Om ztNhns-1qoAWcj4%-{JQS6gwV2B@vTJD8DDsDb^8s^yKZ~TZ6^`so{H0R;69l@w3l0 zeOe}Y^rWJR5u~&Ze7yx()3kiE1q&WmR`?afBQokd3=D*QJH`yKdR<55@F>C z4Ck+PQm1!4G8=C)+WeT6$%5l%Cwg7yqz4P0`Jw_CpHC&dLjE-Ii?dd5Hj$)TQGA*< zm(9`EGl;z}q=et{i*nwMq)^d5@?kx~77L~IE2*Av_H3f6!<2%ewFvmtUo7@0!jxiL z4;YxSrYoIeFuB#piH&TY<;-6!dd-u>E*bRIZFyZUf&0*9)FQaLGsQV}_Jsy2ShAtK z0fMOxG-tIH&JvBtHEgW;C8l}=Z_Gp0aqkfe+J=9$(wI^FmhUM3UPqTLW*qTzor z_SR8xH2J?U?(XjH?(XjH?rtGKa2N>g1PcUrcOTq6cyM=jczO0Gdw1`9pR?yoPtVL> z(^b{qs;-Z05ICy35n-X+muyQ=c*iEiQqS1oCXly07Kt!+%PdUP{E7*3Mf>a;D;v z<-o4`9s55)l-pdbx;VpnT6kdS_@YsdTGd|>> zE=Uiu%Iv}cG^(jS>4Lq|k9(DDQgyz@>FU?I!QO=F8W*ayEQ;zB;r4k9Ogl9a4J8OX z&xu3zLAGOVx3@8t_P+Wi0SpjXSCkMwJ%579GxF!oeWi+DK0O<+`6)(Smvh=D)Qq@{ zcK3-3-8$W(hB?g@`-=Z8C=Q7Dpfk1WQv>F-g%KAGLYJH?d`7V$f4Q&gjQ#D&!63Kv z75x}cz)?ijSy!nKXc`_V(%=vo<;$S7lU;x=*}~FOw=+015Z8whj{%)Ei(x%`w*EPK zjyszfkh^ zxcuZ% zkbn-4#E6E)R8~Fe4F)a*J>3OY}kUtesYpXNcg$;un-%25yc=ZhLlP+3L!>ld=!-#stT*BSc<`MBdg zZzKP;&zOlmB-;IH9?0>x=7Iki!u^+O@Dqy>b+C4Jv-PlX{I5;MM(t(azZjQ_8D1F{ zE3C59m+)Qj)l$|6Bb z06>FEIhvNo^0Wu&!dV8<x(qlyf?bO-4&PSsUL$DbUF1fSXM#YPzke9c>@ z&m^h`*peTH@_`VD3&dAkRPYHo9W6OT%PJ5sieT5`s^VN4i~@x|F^~&{vTOyq8M9_| zOc6Aq1Hy*on1F91Vg*e!CQ?B*3Hz#yJY@(8i;iG!TqULpOEjBVzC;N&qpuNK5^8VN zhv+8G^Wi!oD+@KVxQK{!KGgy^6mqKV`)MKH>Z5lWE$2PSgC%5C7E(rr@FmV6?M-DJ3y8fkZDm`Til7#QH^ z(iS)Ys;dSN@F>&I+T=g35kR)Z6Dv~^C@n@=Mp4mE2Wu2wDb*M{w1st58j8+CYl^-i zk!5yb3#+_?3;WYFGjs~~a6k*ynj&j}7xjSBFUSej@KXz>4umvFzNBRO{wN2e^keJ= zIDwY4D+kaws%3c z3=F)(a-y;;5oNxBKK8dPk(`SRlJoXAS5BK+Tv%LVpPrjuWyp29A8!ZLJyUFCG|)J6 zZcU8ECT=Q|XJ$j>=yB<1=H?iJWG}hLHi&n1Qu->M|_IXxCUSkA8t@Kz2-@o$9Od_src-Q)nAR|)B zU~RZ1A~EC(d+y!FsfQ+U@&LcIWGKH z)(LA+0+KlJ(ukD`(oF}}yVO}8Zl3(ICV}{A3RG^v>mrc&G-hzAm&^svc-PglbS_T> zN{A>9J@u@U;uaaLT1LwwJ4TIeXpmePGFU!Ze|mzIls`O|PTLR1_S(N_8O6M)4I&d2 zuG0{jGsCflOD+L0d3wIxr0eYj(MpqNw7j`-Baohp8!CC1NE(nIdlHrF@wxI2II=fgmc$I@b4`*< zki#g3WWv-ZoU_{$zgVf}x3YLe{qY7G0LZtJzixF?QAU;OnIu^nEMZ}Ly{D7CO6!^8 zkU+lIXy;#tA1Ru#Z($dYG89n27;8%=JI zZnnkjy>Zu)-OCgU*SQ6+wyt2m|HG+X4!{8T{W*7LqyOE;^M592{@*9d|5MPM5-Tbv z{+FP+v~fxco5=^JofRX^Fj)-)q7YI!KAe=9@~e7c!y%(U96a)7UVn!qJQLhm56eyO z$JDEExA6wZU`y$AH4DkDVsf&@P{QTc2eKKu&Y2=BO9}|vL^!@hVwcJPqG$ehbW`d-LN{fdyi6TzEz~Ss+$`NcG0uP37D#%VTe|!+lA$nB zQ5pZUAva``D)4~Zd-=s$1akVJVP!dLDHn3K;3>Hih1Ax#j?o=|hEF6*xc$+nDUe=4 z{4vb9M3f7~=Aoye@49xZEsPC~4Zw5;#K5Om@J*S30;Xiv&JAaEQ;PfkP0g^kDJ*R% ztpYaKZ7Wy?eP?81Z%M9HepG(?#}-1WKDj$W}P*>5UD1ANY`)~#UAGAOSszTWxil%z= zp+E9o1`z++gYoWv?DqWZ6-TM@4^A>9A0;Nsg*d)`VNcSZQzDWX1D6KNG4?VK47mX5@jOGrRh* zN!=tu^R6h5M^N589iJWBz7a_GB=Nm1kG~wD{^$zi2VY2y>G|9_JLdXylTUWI)k3mV zCdbwHQo6G?vm?JVddT9!RfI9jIlKLos$WeF9d=%PMWzS*-{D^}9^p=kL*$n9^N_EUt7#^oLlwPl{XhD{N1xcfu$_XJ#iOwug=KS`Z4!|7F-8?lo+W~$fJzls>3Q9emf{K=9#)~OUUDf;m z1nbNUcjwdbog;TtV4#y+&oljg^9u(lH(&!Iel` z!jEi+sLYRb3Xl;^uwNRaWTVr}FmMLt^r0bPIQY$v${g#!!e9WO%**0*n=jko*~D_j zNT-3_V`fM`p%ySDDG+}J*@bbHf&hsao;fwf(6{g*j@Wk=@MVL8=t_ymakJO+6x$OB z*GYytaPKs_-QSMm;AeOAyp+Advg&wE1@oXasaS_HuP}9({_-63vg@6jM%@qq;_9Oz zei2w1ARj8@F*Dj`ZqsyDq>0Ddn7Hgt%#lEIWV;HTtlh@3)|w-3YN6geL=IgfxyH68 z2krZ|EP&_>OZ!~Vf7B;|40FMmabSZf2Bw-=YK%GvIeR)o@Jn}mKa{-Yr!2w_B_5@A zb{?`emTV$g4nEViWlu^+O`4QLHG%_d9b-Jhbk=n*bNh7l^E9$d-@`y%t9fWF3K4X- zXe$$9&=AxnE10(FK})>l;Qw_8MwG zF^P)Wj4>*|ES-{mAXtnfm@a7`CwD6(^E63o@)SbaY`=*O&BQ#(MDkQZnt>L|=qa#05Vhv?_)=_j) zENg}GpOb40Ql{R@XS&o@AHXwpDyGPRe$<96uXdRl_1-(1Z6*1bA8OF9v)^}K$fdj! zRcPPx6emU_+_&}jJSvDa2XgW`E1$8c4Um1=!AwJUrbAf4t7StONe4 z(qHHM$tORXMfPu3CI4B&{r_;T{wEbU`!gTvv*83+2c=eX@BA0xgy!L;P*F<{#Z_q~ zP%$=|U2U}z4P~3Qt&c)rgdRctlX)T~RUzbw>-gFE-S@|LJ36~Nz?OisAlKJ$$*Cf-$IoGkh<~8KdlM|X*I#+V1V8>?4WR_XwHTm^e%(zfCY%+|l1ib|q zGh;eiBpka1B33+lZ3HbtWB71VWjfd2u^D7tyA$zb|Wy$8&HJZI;oTw8&J%&Exr z-^Ei$<_;S<6QnlVB(4cE26N&-rL=HUCllS=CYaW@%|f2Hb~yq%>QlENJ+B686^@kN zX54ndH(c=^WuEes3hc7s&=2kLZ;-HR4s($qp}FX8-F>nmBR-6eM*98Ot(T5UaST9YY(NWk%-A;_|d01NP9oEk%Z{v`h#J>ux7cMkX z*DSPJ?-JD)kYz*4fe9oZW(~v1yRbl5XyNu@ki(iafHx_9(MvE#?q-=}M>x1?3`rQ$ z*^fczirA$nVv*5GsJqrh_WQ@}v!KqPn)x{bvOjen|L?h)`9HdSq-;H$EZyDzYa@&^ z=C3qpjL?IHm6DcA9IqYmj$n%uAbS7hDY7D&;;jplKp+4Ozh4&toS6OQUBDRRUWbk* z3{upveV0-S=%7ywTkhTxr{%#7V_F&DvX}`Voi}w@T8nlJb97;P9G)z=?}_o2&5o(~ zu+KEu>U|7XPBU^Sg9!!G)lhP#aR>TcgDw0cF~m4dcqaVw0)BiR|GdP1uMqzkW9GkP zE&nQ%OVRvqQ43Qx7a=?%Rw+#|oWh}{9CL&sZBbrWf-D##6g=IDhg%kcJ=+{7Z}0D) zK;lcyZ#J|Hkj8JU?-1B86qOu~y}PE9mOneYzir$+bWeRixZrLS$M=_nvm)+%V`0tP za)WbKuuGRC4L`!*7%y;vG%h(=@b`;c_P1ay-qM2uPuCvvlzft7-Q{4g8D_s7{~APn zfV(YKG#)<;!0dGyzXwxwnEx%|5m)^rA-kH__r?|{;JHCbWwB7suCQXdo8gzuuW8C> zT8RbaSwCp$IqD%vQgARo0m-~MW0gnRdJ80x|89S*Kq8Do7;#Xpssn#ws%XK!Udw(P zo^X)p^V76Le_4ofwSYz8%c&K9C|1PJ)B&Gj_*1@{D?Rzi4J%1)Qd`{HikJC99@gcHQ8VP3u+DbvJSPiRn zil~j2tSGXs(%0Xv@Too@dVP+BTyT8fX>42acbHN+D-K%#&NxuW1JcsCl!Omgm9d%v z(^n`PtO_3bgM^W%tQ)Z3rj{*QRzz#`S~Z^@{IOCBS;(N|wreyQ4jfJf^C8RA^^LwI zcQ+c)C2PrrNro>sYae`Us+F$!OCu98R?4xyObew~Rp60@RK=HVOJ*l_;FmNc@EW}J z4GQTA6&$-{%!vkhs6=q<1F|mE(njg-6!dKOMJX#vnqu36yic7GS<3lW;<{53ja16qiFS$c5l&oCID#+rIgdNy@ z^au`HOX@a}#xPsBu@@#Ru`l`N`Z7~gfTZrk9Pha%M(e71*R#rK!m@P6YmJnHi z9uA)DjJZyrKy9)|9tzO zM1z zOzc$ti)UFG{oDK1Gt?#q0M(29l$E0coyxa~$+E>JZb$zFjmb((DMCK8=(mLcroY>y zwuF$LQvN_R-_TBa-dFZCjvKmZ@>BMudmnPsP$LVvoj55>AnjIZCcf@>e%G}Z?O+&a zR6Ww6>3tbB+0huUf15h{?!R}OZGg(f2}|M_JLXC?`EHWc7l|t zyN8Uag{h;do5la#8Jbhh=+YSPgGLuCQKX~;7$I|FW61oV%%mngu%x!p_~H>EI}~9J zi1@zd&JBNJexJnWepfG->r}hzDMXXmlH(PbCr)<%2qW^bUog@yRnt%D(&d*D5tl*Y zzu7#6?b8K+}r2_l5W29q;9)pUJc$}RxeU-5d1BARjE%cR4Yp+Sf6d}o5afON&xrci*q5)y(jBmT1;u#F~!V1}oSJ6ZJu z&CwHkR8r3xL7cvHFwn3}(~iZ#;Q$JJ+_r`5{zs zy z+AIu7OUtM+oi-wlOH$5>(AB2UI9{Zo*&N+U%wYg6vXS{w4k?-Z>2aHTPXUORQBK=p zRgVyA4P*2acPG^VF=V)TvaDJvop#8p6j{IkX z=lPh+T;|PcrzJ1ln5-W0&}n?KXa+|tu^a+Cb-QFk_`|Yw`}btRnYRLe(xaN|oo4#c zVdJc|H@{H6<@21ff2W`8-kX%RCKJkMz8-;lZAN*A3L1MLh2Jn8`;^5(_SOQHp175~i%Af4*HyEx3_pr~KsEHH^+$c#B%4Hxf#JY{HK@DQ7Vj`-=gSpv4oVQsQpm zH~&!eTkTvO%`B=B>8#-2w+d|t1KcC=r)=}jIIG-)Djkz5uXbL9;oId115wL&IA*5a z%T6*3!C1dz!B0u}mPkG7k#6hA53OAb(t}C8qH*|?5V8Z6>IRh1#ET>IC|Etvnup(! z_}gW}lhfD=I+95XN8+y$#1RC~Wqm*XAs7!ue?wLMbfNh2w_NnU6*vBC`Ih?B?$}zo z{a@94Ko8ze-7;19;Lq+KuF$3iZc1BP9h&K)e1(J*Kpl<>*DGy0)G-}cH9iG8tJ0VHOzL(D+{d-#8 zYVci)%)kIv&87e*K7+{sC6>W=B1~rG0V#u`?KlQ+NTy~HJ}%velr&j(_B&Qv)h%)O z=h_qiIF>_SE@X8-<{F}Fv*ADuq?8Htr{qZc${7M zk@)7^Ym)uSBI=`+{M=v~G&;{h*0+r&ZrrRTk1@nm9KVc>ENa$AtFhTjUj!S~NeNIT zhqf;HK;@gx2Y8VvFtAH9!f7%>6zad;r+-oKBp8TCC2nRi%DR*-gH+>hs)PI42da-I zhsdt)AXAA}JB6kt|3P2usQ>aI^mFzFcp#`A?8_*3!7lzV7?p!pe0z?+^)a@Io-x}l z7;t6ntG7tosefbq_FNgTUUFMC^6|I|Vo-PsbtA0YaXYPAxR~^@_x`Y-O4C{OTAdZ( zQzv^=Ir=ercd*ha=dAj!opu)RJS105{!#u+I5d|0Xa2PsYp za;S7*-X~@qXeg_Jn>!4G1YSVZTg!}a83by?-Sc^l2EE5MX$Nh>Gl>BWhPuS*i9bju zonjTwF%K6QLioBJF5oJj(?Y7e7EkRojLy9qiGSUX_%A=_Bufw2YZw4PV6?P(PUFVm zzUHe2V30bCYSUmd*)kNjkL9G=l-pwiWlYGH>0Izq&J6GPT1neCZ+`{PrPN+K!tP1 z1$bqoSlp8#CB;D+EFv|~@HXm*!b4H0=hJ(IIl2ik4RF-TGbQ@|8pu}CqFLOSzb3}X^L!Ac>W(?wy zs*P{_k;SXK)1D??Mhm$;DD1X+Cf6@>{G(!TXwP_8B~gQ)djCK?ueK926MhdI9L%_3 zn_PA{=69OOQ0itm$fd!Z5FR>-@{|}BWuyqr+)cxO@=7;rK*)Pt(;1+2cUgL>f}2^S0y$1F59%nx-Wq|>i$7js+bYHoCwcZ>70eZ4zP zdB5!0Q%mQB^@Ol1)x6s~7m{el@L6NcQLtn&Hcnr$CWLU_T3!#l;HkeF_x1Ccr%{wb zzD8;yTe}gAo0hM&Qsls4G$cT(+NH+4nL2`d>6a`ob$y%O*39{7v3q)Nl3to7U}}fT zd>jsR=XnNbRXk>CWv=S$>6^pI!ygzQ86Ghre(ejIZQG}R>soq}d45nBmN{b-Vuqe# zAD{Vln-y@$@c8FdQX0XDb^n+a&rR(Ywpr=b7pYgFYlb~UKs!A_z9eF=O}yB1v`Y&) z6&O+2-6^Qr!v$$m^G{8GUgjTD>*rNc*wT8Ig~rHrGJ1t-o3=9d>P3%YBONr@*K+cL zuzNRCux?Oef}P1by6*IT!S0opsD2J%-8~;FW=G9K2;|UHu@Zb_TCcE5>Q{R7Mt~E| zHIsoD8%@_F%<7>D81>1L4yvx@n9e=;s6{_B8Q95!n6?Q{%!{`bwK{N}^OA4Y`75_8wK@=;573)+RYe!z zjDgx(kLZ3jVZwa?y7&3-UpBL~6r?o=+AF-d|Kx9b(f^5h(5;0S(!cWe12G*z_UP29 zBh*@pY_E7EId9qyw+z|wG4$sFBFPgUz1ePg59p^*Z=+HQZ=;f21{>XsN#`F zC@2>;6N+E%L~>7d08mm-^|M=$W=NU7#2B-HzP4voS0ozFLkdz>3Nlz#lsG^5B2@?m z^FWnFRp~sU0b&GvdtG(yhf9@mrcR3;zE%5)HF-4e&VH2+3q|sQzPu`@k7lS@TWL*E zgdBr=p1cGg@nS=W94)%B@x@$p!|Yh?upTNOo?q*U+_N%D%af(~tE7gBu?Lp3^d)*D zo8($5uR|gZ>v(mgeuJOsdgAi=o~L^%vz}VBpO&FxXLxBblrx4T&Eo0es$Jw{K02v7cth|TbvH=I_FG@Erz7M&eBRcp3v|59r|~!$7Zc=( z2#F5+VUq9F`R<5OgJE6e5hq)9?yV%U(w5I;{@+tanrYML6nE%8*60AU0S2hJo+{TC zl*fA$7&%kj)97}qo|tR?&ch4mh|@`t6-U~;rztdO#F$NU80@Eb_003ARJM)4IV?JH zuy>t_9y8L>=B|j7FpLbjQF3$%9Ag>U2ZLyO={KJrp1*x3uL40!OZ*j+yRb_kF6)N< zMo_YfYa>rM#K|-Y9^#^i;SR5+0WvJx&PQWUS-I`M$f^vHo;E{C122)%dyy{sE?@&d zK+s-6-FWU$C$~RsCnERE3v3j%N2qxS3l(Q80)oh$X*jevTh97|O+x<1!EQh)* zUt+qxCXR&lJ3_j&bUa@9{X;D68Na@S1}o3~|8X^mXM{8EcUt~YKzV8&3b zR!hq@M^v+#Oc-y;zMPyYM^;o$pK`8#;oe<3+b|QoUhMTiuMV#(QB9umyH8~aq_qY% zyzh<$i>uFj2@ZV=Djkd)sL+DT6r^uLx(0_>gD7yRe%VKe63m|me;(f0U@ho?J?N5@ zfo@9Shqw_aMlapl?DAbjNaam2BA{qFkY=q%hD?Ge)LyknH`2mJ9G&zB#Z~@~cvuF5 zJ_^LIgjaHf+0fZ;Un}Q6)4k|qH8R3v>j{cNCj@#*03x(P2*-~@HgB9__U~7)Jqi8r zgM`7!oztmK?9S&UYP+Kt`rjuy@WWG<)KXKHQ!t$XBO>_f!(PsyJMRnyKOCoE za*JD{CD}()9y$J>`I=MkbIr3c`Uu!C?8PW)s_A4|HKooDg3+?E381W)j6hiEq=%Ft zsJxT{j$U-0bOQ1uzc>>-Qgqp;c$WlRwN{7u^}M3FA5S1|(?3YYiUr}dkn_k{TD}AZ z3^VhSh8)18PC*Vy7dmjPDz= z)Jqh}U$CGm(z2##>Jm`>`i-_+wZte?*Y2QPtN-mB4ILT6rl%hqw7K5f0NDmwo}h@R z=IC9BG-^>S_J!MrR57JYk(E1v8PkWnl#)x*as$cSy1rJ8fgeysB*Dym)@URX?_hk~5C zrQSm+yd&-I?|He#msRE@?qwKqZ}>-;Zl$;sWGMPg3dxHv zc{#JWfW*zcOKF>55{JbH9l>a()PgT5$?v~ak5?7qp0u`okSS{klLx)jUj5UFUUo1r zk<=Sv)wBF#b3WiP5{yM5jq*V*slpP!uweQto9>bmKm-&{UvXNgz~BbAriUrb*WlI9 zgo)3DAUX6A7{p-ovc?Go0(Q=Lg1h*cb1%jdZjZRX3$4Rlg2WDz^FYOI>G%=BUr90m zwU6*G90}rxcOV49EY_O7@RUlO1wRxMgBW?dqp= z<6}yZHqSSR9os#6B>#$KL^?G9c@36D&)jR(iu&!^%^@MPR@12u1YjaZhiS24H;y9e z1*y6eN7PKr>(~8E-`dplv5w(XYVT?v5cIk|Zk{8AS1ho+c~Bnlo9Ob*%GXUvNzh zKu5c~#k#z znF=CN@5aaW*%64+Xfr|M8;Q^;=O`uaq2rOBg%7zXET;_ch z1|nPZjP<}>xk*z_3(}s@ z0+5r$fkZ6>o8rfH@V+wjtXK?y56<Hfkz^Vy~A)?S3np(*HZFZ3SRCruFCa;q6uN8|2I*Kq0fSIt%%U~sL(k=f_B$vGIVSq!Cdgj>bN>jL zD_t0muI%0fcyc!i^RHCoHTfL|t-X2{pt>If6A!|Za0qH6CBW38(a2Vvw+^4fdW0ua zH&#Ekhenn3BS;J5b}YHi;L=v6c-6Vjx+I+sZeTvu)L@u9X8&ySu-u9M6DsSctH4Us zqM}p;)bijK$A@wa50&yDD)1P-_U#S4exSv_vOgNU3o0yv5tHS-ZpG7B)#{o7cx&NP z`NzNR#PuH9m5FI)j&`oc@38DG&+`Gy)T0QC`dEtm^G7vH=JKNX5zIfV9ILvT(y`NS zwt&b$~u+5}Z3IGnLnVRECY#Rnm85=fuFmqFfpS z!c3lx-v%x)Zwo;m*#`12di@l? zNC&-`Shz7jF=d6#^()HWeq|!<2n9RJG1nmPlE;~_nwrTW+7iF9^-B+Scd7Ef+p}_I z7RmVmIoYS;$6Qk6#4@5BoW&|w<+JP2JXFxj(>zqs>)k9pV-mcYZ>Ms8Utq&Bb2gHj zCue7KN@izMlaZl;SfpY;V}i#S!qJkBR}RHqid!Ly$Z3l=o=0UEB408xZ9>E;&XKOH zSOnELZ(&;#kEaOE&B=v`rJ7VJ3eG9csUsI-7&2DsYEu)PL4a75OQjt`WfyKct)Q3# z#W;^Zt;r_E(i$i$l$4+##Y$_!mN9}uW&Q($jn-`2LT%iFAPJ3X=SMQzkDh{PS>7Z# zD)b);W@;n5VpQ0yrDkdq7Hmnh3Po%`QqTR->O9Nsr|C}rP@M`XExpN^KE&7f>NNWn zJ3T}=J)}E5q_nMTpLliaHNWVspPzWN8<($s>vVdEXl=lvJNP0JnVs0zq@7jwlAnSi5?K=4 zT=MvehP<6ZBO=vMbMW+cO>ffPheH9DiScf0q&av-g=R=5jb=!C{bx3*m@jCjAW;ZeKlc2gSlx;6BPU#W-2mZ`%3NIVuWtqg;UP8Sn zglyC-a(G9*74@#}w&p<(VEcU_vnG{XXUAsd1)1$rlDV~Qb`Ky6plNn11x91wh@SbH zJpIF+jQdO?LF1Fp8$|Vq!N`L{V1U5Dz<~Ta2==#x#eZ(#NmzL(eS%@1^i-dJuu}iq zbw^$QuNQ=QOWQJ-IB9- zQESnq#10SGj95Z5E9LU_cuUzZPGVQJpP;J{Jv7}J#%cj&1D(B9$E|Bb_XLY-<$~3s z8JUC9=eV(kX7S4SjaqvJ;sL8?a&NaaBbUeP!2_w2t-P}U1ZTEoNqZUSN#ATzRc?n) z*1EQ~)osHhFN^L+*SNgY(w|rERT*pN<%(0Br~b6Qu{c#$kpp$%AZ8Fs?V;R@?I zc0-~sQyvrKz=7pf!gN0#hINmu8%_Ba$hJE;!IaJSa1dx2>QJL)jI#u3F$md;p!g9V z3B8I#oKtqNMHqjwC@BfIk%vNBp|I7tM>4Q?CkI5eb9k}EcnL8RrY$5{OSEuAhi890 z=n>BkOz0!<-L=Wzn5j(fNlZIco3XzBWZX`!o8x+MC!e3^tj1@GP>l7!ryiyGZ`8+NR za@*#jLX?o-j&+LQw!i{f^$rycD~zE45+ri&Ki;G~=7b3>M&3KZmtxM3;O}5}yws$c zID_|QKOeG^zHB^v6`pK=x~nF(2Z5?N73H67y=;RtfyyE>J-DFUuo@wAq#~G`Sexi5Xd;|G z9R<1H20OgDINME>n8pn`FnQQuAsO?-)bjX>dT`G(wR4q{-J61AE%Gdst1B5+Qh4oa zhtUOfC-nxtmaCz>4Cd(>GF8ywD5TOqm3U5!GOf-ye6=hz(2J?kS=j5fX*5gGN*hf{ zIb54t2(!y;;rrE7FBfv}U1+whvI%FsebuF45Tv##ZZ?`|LWAVyM>DrI9`)w(rP8Ka zn)=u+w5h48f~1b|Y<>B=qvlz%BPKe%R+ma09XFmU!3NSuS9COUdCyX;FQc_)C2XqF zFoybGve&L_8R^%uMP05xtGj8-R!+%i_MTpX_QvH{CB?Z5pZ=!{7QDpf(4pwxZVNHx zczq3nd^z+TZj-E=I|cbpCQckBZBjTkl!A&Z+$T))3a)Y=?WZhKR9OWiCK zDPrR+km;!Wj9}4gkb5d=^&XhiG93Q&nUQUopvPIdkJ%y|S=F3zzpkp=G&;|G8^R0y z8nPdzKoMG@uCvpws_UnB$t1U~yIN+Ewk)!xAeMTui?y8^zKcTBVSPX)J61Nk`)=#* zB#M+eXrPwSxt*w&70Wu@6gWpkB!?~&Z(vqNa^;qx4X?3s5NVwX0|!K! z9fA+>c0jv?(mNZ%n%=550YwT-d&Ht}u9o%);PD!LFL8Uvz@@8-oOn~JKi=man{3t6 z?1~?0am1l51C2pV`6z@jvJZz;t88F~P#|}YdDiJ?4J)>)y1 z)}UKV$u`P9GZwuvC~J_wFm%Y-j}v|g2R|dr6kHu)lg<}ho%vktHna+akxG|@X2iqU z8~IJ0v;*=~9T$A4FKlVoO+zTgZx~83#yB z@j#p8o4G5r(;d0m5;~O$`m-PvMjhS4(q;1{iH#>r%P6Ur_wjb8fnfvonZS%s^d|o3 zefg#-?L>3!_0(HNxEg4516sumM}a7A=2hoexXXIy4dt8$b~l`W!wN5Ye%298!cJ-}Z*VkvZ%Cv9{+bb7-TE-q8`Ki*!W8{TAGoA^9(dPJ9>O!# zClZDi6kf;tk^FZcthrxM+iwl~4WFI1ojNm@Dj!gMZ;i~Vy8tcH$Y>$YM%zZ;em)WE zU5rJNq0Ny&_mOVv{-_xFFS4#e#Q^q~Pry+AUwr=leZBFw(VhRS?SJt-)NP$C|F_2f zFY!iO*F{|u=iSLIDKk`F)WHs1YoO8bJFA0SdDsdEicC^Q0f`1<^O2*Et($t1zRgJ$ z4bx^Y+;Mb!{$vX&-F#(NyTD5>au?rDzVl?sMk}mjnTZWQ@6%MkfPOuR(lO!;T;(0Ao<>_V%tH5u!_}g&qM%3BTR$t{3t#`X0PLCs;)5A6r0^QPC zNH{4m7CAjnpU@$WtMhf$D>=IE0*%Dp8h$`2j26prSdgF)1PfJo2Qp;384Vqdwo7qv zVrZddr-jYanNO($#>BghL~w&9aQpn1ZWG7cO4S~EKg=x?)63o0PzqLZmW}x=44|OADViG zwtK!^!(=ME#&Xv$VJgFH*^no|JGMQ*;5ci8d!Sk55QArVTrO#-L9cHsH<7h{NNILI z>4;JTP1Y!rkre*}Z;@XQDl{Nc3~hrPjUbp*-yo^x`E^g0Ca3RPM(JMhs1)zKGoEi4 zJA)vfsg>i0Bv~ya(72l=3@r|tBZa?T4FBd>IM~>iTPb<)*>g-ahW9r(_+rG$oH<(o%i0sool)h zpKH4k0^x{Mu1JUyYpyCt?$jg1IKM1)e~vh5HKY8SAs2Nfb40^R-p!qD29r3t zfIVdVxO|Gv2FP~Z#7m~8@Nu0@N!7JRU~9Spm?|cDp_R2T`H`)3L6^c|RR;ts)0p-= z&|eiGP%QHDDD>vJ{ebi@t0<>gvs9c1gl1y>iFH^jpFC@=N;HkZ@)#S|!Yr3+t!`0f zrj%xT`3_9b*Y~RBT~wiK5_rjBDZ1PGw55>@qDLPYH!*gTR<>ioB^*DMLGq$TKhg=k z>0S2G8sFK!=HsDxttk1vH{q3u2+T0N53YU1IwAoPqVg!C(a#N z>ozo0{$)E~k?7YGP}QAw(|1wR&ZeIB7r&~=eZ2>^XWn(Rm{BM3+lbMx6}fu|>hy}H zlp8_vn?05V1UCJ9EnsL>yCLI2^g_$x)JRjB^IL+-*f#cHuaHh1-Y{Z!T)JWgeTI9N!3S_# znwy}MMQncr9q6pOdT)d;S`n0=KMq|J#L7R4L3)V`*uLTXO6hCKxLD@et-;FYs%o4+ zJcwP;G0#8G5?>l=^pv0~xogQ`Tbw*YFL5sUB?Q7<2?5r-FSUG;6I8v9e#vv9Rtc&s z!W$$xw9jjW7v+MTy6uGDgN1KlqU0E8$F*b!Zd1$#Q1pyXbUce+QNgd*X)VEOty zrH%W)k6zau*RczPz|)`9XDeRYUpCE@HJK|K)1JABP!Yyw?%JY)_=gRtUHhbMNM0j4 z+_WRj=lfU4hE|atehCXv^j~!0;cx0S{QpRM#~|Cfc1d)XZS1mb+qP}ncI~ol+qP}* zvTfVydcSkx^zGZ--#rm`Ma=nQ{#a|pjAtNoQOI%ljc8N z^wd%4`t^1o2^?znDqd;k3Zey&7RT!svA)TIn3fM{b9{zmhB%JWV?YVl()KZK)_bYi z>M+)w$erY>iY}c*URU@;sdOv2e)^KC)^}@PJjn0y2%qqcK72ywVHar65w6qOi_1sL z(4>2GU7~8osUwV2bDQ?a;o9ZL`uYv9)qi~89pHL{t@tL|8Ip6u<8wHE{UYbEM|f)B zg{K|8@A5H%-ZwxMOe3-~bq~{;mIx;Nke5;Cvdb!>Ar~HcT*ig3EH0bkL{3nMCG^se zg)L+7o}Ic(PuM*mlYC|(@fvs1f+vElSuxa^nq%F3dHWx!Uksf=IO#uqw8H;3y5--> z(f{Wf_+M+ElDpl1X4_^dYRY2#1GrI>Cm_R<2^Mv%p;qb@_K^n7kdcr8A>=UTOY}SX z)4NiQ=}&vgQx}S*F>~Gv(zDggfXd7X8phZikF>h4C$nE)&(Gn05hv!y)*=izcE;8b z?HfZwItUyPs)fci;1RG8ia~x#3|oS}md<*$Y;zg8DLQUskI%F%Eh|seQH|h~qCUT^ zmmfQL+MTr~uYEOG`f@E#B>HGwD`iwsT(WSyH?=IH4m`cPQv}hrvM+!^bGChGffNEA z2TaFSqBrZ{YG`j--&c#1*6X&}kJ}|yWZgpj1GUSjf1tJwJ1?9{`H|Vih21hdJQCJ_ zKy5uaSCk*9tsVS8jU0WCJ^u6t>WpiR&Yj^Y_ye^a`w_~_j)-3EC|WGws>V0lt`XDJ zCeYi{eT=}D%Fun~f03yn-!~NIf+y*pSK~p>ttj05vP7!;6X;Kb2pzTxiYAbLx*}vq zoRVWvJYYaV4(6Kf&(F6SPLyc za!zhuXFymx1HOUx5=Is5Ni@(+D|l4Z(B`tgiW2p0>LVYv*h`$eif+`bbX;xkDobd!3JDxSrGQ1JpYCoTc2L+B7xYCA}@ z9U9V|fPyt^mL*0wsHv)#;@ctlLR9Z0c}~Qr|1Hwy z|L?1B|9AP;|Lg+NwnX|#Q*T%`NpNnm{0yhIuwG8@ZcQX0OA;`{052wIsw4AGw<=yG z?_e}`QS9R-dMWk~74!YWE794Z;{6v4;$pJvxc+&AedGS}J;m`CrdfMyG^R6Kt9r?W z3IHao&2PQgzW9I+==HvxrpW@gm>keGDL|j`0yW?`8O5r4yhHa+^n>7v3$+X;Gu&hE zaIQF8H<~7c+UR!ZCR2HWq{$X^im69IP*2eqkO41QirJiELj7Q`L^ zc_%Or3xe4=5Vf-#s%trZh54GkelCt((@Zp1<-`-I^0DkuLv9zlnZEjvcePu&kaK+$ zzYs7rLp3Um{=f?HmE{0)WYUKJi;K2`R*B4UR9q7 zE8&JzUxC-Re4*amAu526C0=k)B?1g#VKlxmgrQVJ^EB={2e>v-vmiehI>JH1S*mBf zL!u?W*+K3sd4I?mFmM*(cBzFQ0XNV8(mwS6-q8Pd2}HyHD}g8v|AqQ9pP`afnMro3 zf>@}F2hjfzh;o{Ufa3h|!y!ktHu@PqGumlD&-mORMpW_47ukL$2#nc2kZD5NWZJ~@ z)I}yPZ;uz493MV3LIwg?pCZHrVzw|I;eas9Ph>s2BbNbXAlvc`u@zKk6K9f1m4gyz znKCD-Gr&;rnUv9$|j6zjV+0PQx78nfGUWE>0f4Ml=>W3XD&wmIM)%;sD=VM7T!_7dZX z$X$4g49Egw6r;;Da)7#b(IrRwBCYZ7KuH#>By{bg6D(s$VvWg#)@xj}v${&n_6|xs zXP^j=X35nnz7q7nb&qX>tI<4(FKE}m@p5`;p473;77-J7{I`xl(z#~Q=<=>5_FGNg zkOTI}NZ{>SV{~^iKo`_M@p1i7=;l^ZLx=_pd!e&3)2;+~xfspDMkieZ&dY+J}wV~uE5a@r_8FEc8&7W@~LOIo7mSdjM-%xDenH4!)VRBGL{#tJ=Q z2kpoHbmnT+@#!b-h~1Ot<674iFm&IPBb^?(R|X3XFJSjqJ(@X3cas}$aNpwbDwHG*sCEs7<= zzYnq6%~=6}Syh;Ge_aIl&MTzU0H?@1tYD^-hpQ}>uxK5OHOu2mWJ$R9z0Bnui>){| zx_%mHO{PvO7D`z=I!%<#opbAi(Rq^9Vyc6KFFqm{=UIvgq&R_lvNbXXi6ENF**EZN zpRbZAq&-0%2p!!mMS?=!C@lvUsWOIM)3qa_5-%GlB%+ftsgE~%Nf19VAI^G*VUcf= zFX}O-*hK;oPfY1Zq(%<*jJELA(9S$|T8V~VXYOsGtSr!sr0s(4a7eo?+9>`uY+=f( zm{hRvH=d0Tb@Dk~OjEFBkZU;Bb-$$`zR^7%R25dqwd_0QJ@lgASDNRdMEkwp!i1>< zncn6OvI99<@Yw1B9K$^9A%vB{cwx?nd5!eC-f{!cU&Ot1`{C~R_vUeGm{1q|D75dt zesaZAhqf&An~jpPK$VEHnQsKOjL79ghQdwS;3Z>n>h7WkW1zW0j+63e(cI+G9}uUZ zoUGY$5os}B=za2)y7Rf*mG_u|QtVcHW$n|{n`SSJ_9_LL4AX{`1^AcEI}kBl&haK9 zG^skP%6l)`e%uve$DEFgY=hM{Tm0&WCB;nZMdxFR!8{e)gmhU(lv=-|!%eU|PDBK? z=^Trnl#*8Sn@HB&d_HUI_;+@r zQt+QoHZ3`~HJh@^;ty9|ivnOeSd`dJmFE*y9Z^ss{F)Ul^DKzPwY;we^l8O zQA9xJS2yI|4&tO}vL=mXiyZ~a;&!z>Zbs8>$9|s}r>(Td+k6_2P>?Z=H=MOe-wUs7 zt!*d2O~QtAH;eG`e#-@&WY;ZRu3qxwZKZ2^+$XJZ0C2i<>U|EZZuJF5ygWVvCghxg zEUf}=(3D=Vvc7AlbH;2pPz>ck2mv&SmWyV$Yv z^k#M0_baMaFh680)`7W8oc2`|xZ_;2huLcRyY*%2R?Y7T#p!<|Y-@q^n=&F6=yLY_ zriGfoZn3DEB^3w;Ai!$%u*1K&nI@-$@ojLOMpbtl3DUe$%sWU@jR`nnr3$?ft zb&x~DxyN(-`AlwD9-#m1QZ1^5M&Q<^ZOjYd9S2L5T2%)>m#nrdYh}LFfIlAfi9I#= z9)9+beOZXOIgK-Xh+A}iqIbLpAe&UiXNy`B0P3Z!8P21KEzMr`F6PSHGwLPG#n}yL9ran1Xp@@{$9x{M3CMJHvlm`R zQ)qK%iST8Z8TFb#;$S628cmQl`XwJ8vYqw%{4NwoF~OHy?zA%FrPC)Pg06-wxe*O;=@%|GH3IL@ znWpNMi{A@iHmQKl0e8<}qi5RK6NT*)^VT6T^bUi<3%lZ(bLKEDU6gJ;@jFUJm2Sd2 z=+=vhU($dl+O84ut8GA+`cIc5I)15-=>Elkz^ z{{;@DovobAh0K4lS{#22ZuG4LZLRIBjNPR5ogB>F{?kuUMbi<<7|rKtU7A&0K>`W@ zkeZaeP&{1>N*NH@0-)?E7g-}$SbeTYn`G4~9+_V>G0kIFpNkPk#Hg56#}0^50KG5& zcQj*kiw@_$Tb{3gclRc7nF8A1IQ;EX@1EzI&Y5Q$-JCW1l;+sa}^k7_?g=C*?=C{$&KJ+2S8egUUnWPUidTW z^_Y>v4{SnW+$XfvcO6F$PCBF9A+euJnbw(QEC2oLIL>8V>{!g0e8p=&KAzk{S-Psv z>Cz_1Pvp|lnwH&I-A{(S@VFAa$ePBhj{=uY>X6K&I-1_b-(WV;<%>qgts4dsBGU5hDeZcKnaXG>J}9Wp^U<93U^G5q}cJPcupJ>m5$0R_ZE5xkPaBnhR^U|@6V z`6=sBs>nNmsd#1ZnMsir83oOA#;7W+-c*TNJRrmn&gK$dJLK*N?VN*L^0#kkM7>ae ziB0_P^R%bzHZH>hjY@R|YOy%k3gWt>R}1XXBS_dNv)5TGoxV|ThtC-01S)2%b1C<~ zAsU1b%SZ?M=w-mhJU{5mv}ViTn|403XOb}HVvhbt18u- zMNov`q&SR&naonG6nf_EA&uv0ujknRC|z5@8L|iWtA!iuQ}GM+O?wI$Y~o9{$Gg;M z=TmX&?8Y&|F_g4$>2!W|Z|f+X}S z^cVgng60%?ER|#!IVZJ{QelNZze>Ju_Qh`WH&%WZJ~xWyndkBQ&9(%!DN|;}q3*H4 z)B@MeJ>u>{2_zT1^uy{`$UdXoUYI5P*|d=EM2j46UwyJ|?wzkl2BL(LqUL+|%YBR6KJ`9E zWBF2gxXOp5Syc6zRZq>=z498W+So0*2yoty>^4vc4N8dGVn~1r!PyKkqE=+VFu;sY zN+=d}qE20CmP7@QP$gfIDPNaqH&-nPzYa92u_Y&s34e5(;z&gjw<0YkoMz$O)LQL2 zho0Bq4t%GY2$l+|C+fV;Z#FAMYEO#mhVa@vQxtLAut>`6$#G#@Xeac{#zf9hvn@W= znKk7v9`Tna={-l#01npVMt0LN{k^? zD`d?&Wuw%0*b5ZSTdHIHx``>y=@*w9m&m$_NfC;)sNA$9mDoNGR$G2;byvh}_Pabc zc8Vsh1ZLixPTAcX@NrwC)4e!;&VJBZ}@iznaYSYFu z9(wr2a=ylfKY`JF4+xA>cQusH`g)Y6?v8%YFC6~ccuFuW zBH=>Q&bUttUL}wkW1KTWYpe*dv7h&M2bmLoBq6Cr2`J6K&1`=bUY43U^>bOCm< zT=W5JLW?^BV?eiv7=!FoNHwj&DIO`_12A5cnr(ZolFf48m%h>?phYd4=^G3lP0<#@ zC3P!B^pYG~yQufBF-zO}d820X)JUPAChL|9F5LN|7R9r_VT2x*r0B{-0&wDNa%HUH zgax|0q{qa}h>EbUk24*lLlovqUjd=qbDv~`PWDU4v-TG|s#sr_kZ#RxI8ev(d`6YO ziq;I?R&MZgMCCdG1Utp)w)!=uGX~eKh_7>1J0lAAyd%TlW5$%YB3OEJC+GFAulv;br{20-?qF0+fNcl2)F!AHWt`bDZVRhS z_-666WbbrF^9EP~$<7Dd{>%8I_Lt!^+s_il0sZfkB>!DSoF`apZo|0Zv8L}kj2g3FXPVKAlHW^Hiv`S`fQ=0g|)7qSw% z1&<-75_dxkilqA8Mu%E(FnJ$3MTe-xn{*?^r)900(R8MN*;?Eja}Fp0Gjd6O!9D-h zp3k0qxB@g}pyMlft7QTw^P_RH0ICsBPa6h1`q4O{##&)F>$bpZOj+!^lA9MOT6eB0 zf^@oZnl1)0n!rB#{ZU=r=wu$$KF*@So29erVsHErI+_ z6wkU*e1W_rBL<;G=;r$oI_3W(bQ*<>HXDf^L@+o53B3Q8(CNq3STa8~@69mroe8NL z_Y3eJcH#qp@`LUFlb!gtwLpG(rT=)X+U*1_?|5V4$I_w4n8C?oZMn{w5j8~KC!yMM1z~vnR8}!sE|6NI- zlzOo}2UK>gF#~W_u(3CZu$rXS;=xSBdr(wpFT))UL40s`vL)hYKvE~KYgo9Vh7r29 zy$R}wYdcR(wPxL#cOAV&_f~GpwrJAU#w)0+=KLCZ=+*Au65HH=e!CRfM&PMEX7N$I zc7T1&M~fP_b`+P>faM924+Yl>>ON^Uphz=A$yXbbd#@@JGM4aA(PdV0d8tKwNhqm7n-^5*x(jB`ix*9$i{T`&pInI`K`_v*U#ixhEt>8XSyDdi$e zX2G&YD9$rntcUU-vufG}^O#O%n2 z#HBH?p#>g=ae1i(Q`}Qtr+$JlD)Swh;=1U0BkIPvU1%P_#z*>T1##n~Q3=vjYi>j2yFYaj$>!qKh@cN_|Arl#Ncs$|Hy5?#V8n)6-Y|TgsBw79^}KibB^q zn97MzqEwMfG^jG(M^llc(TXxL2n~n&e<== zWFIa~%b)WttqxgQ80;r3ZH&Xmer|7vk1OL$&GMVlX~W4Sb@XR81O{etDx;0Bq>~!APZ;N_X*hb(M(dAx;Rhz}rlBm?yq`ktZ_U z%umiDLqpo2v8pD<=OzO8vBKx>nBCRH)$}*`&NbNcKYsJyKi6?~gX3k-wf8SQpfAKh z)Kq?GLY>HU{aZQ(e^EWgBr?AMB1Nz?SFyfbJb$`0Mh$;Lw($itxS0B0!%5G~GE!tL z!^3@ksy+zR7Y%sJ8)pz%Q2D3?s(Tnzwjs}Lqccs&?7i1hJeB=Ie^dWf^cm1wYp)RH zoc&#QR5$*<2>v;bu)3a!%=yk|?qZ#zU6d{FB=;I}Hl#t1%){MBL@!)ky1IuAPD=sC8u-xk@~T8hRtT`jv9Gh`Q|%VM+#s>~f~?30l8|>N&z2=q#FF~W@VGpy-&Ncuz35Dc zP!QkV>Fkw5*U3=r#d}3Dd|@+DX^r6;BK|uO?(+o!oUkJg2rd=^eHq9J0Gp=J8Vvq;7`f=w(Q&JP^%3fhtyI# z1SG_W?s^tl0~!7Ez;FPa*e4~a(U1cq%|>%K=A|8IjbC~QmaA~b8s&P2l;W!Qw=&b7 z49Kz42lBhpMo<-`Px0Pyr&+%W%5j}+u6{QZ(|R*Yd!2KNGub{S$~xMmf4DB)nv00# z(QZnoS4xQe1^zb`IM+S_3ew45hE(|rqK1-|P)hF-yZnRFoXDK{iawDUElcXOX>f+Z zEee|fVtQ#^!Do7URdwmE0;PTxr{VeMALZaVZdEd-D9O2RlrvK#$lSUcpg<>0~|P~7`F?C1!cD-i>JG>LS>Dvp@L zqPVA=-h|ihGlo4Nam5Bl1F~8ZnW;jCyBC(KIiO3(Tm?77>VJJQ9Z0AW&B2 zJgzABg7uRDT3XFixnrhDEUIx*D-XV<^64b0xg%H&&XACrOGl3v3k_j%KD0*?4{`RK z-ar6Dr3WH1O2p3&>G!Qs6K!J|E$;U&wl+^D7C8Wfra(Ja-zY(=ZJGf-|^>yMpbgAq>Q1Z-yJxSylU>~Iu zL*_IakA(FgS#RQWy76Q@Li)${Q~(k zS^XWP_31lPz8$coZd2<3*#dEZ_jlWhbtS^Pfv_?)Opc4PKOm8nrXMx_sB15_HINyp zbgIxG)+E#cS-#$gFWehX*SP{)xeGA42ysxDD3dp=T|HJsAxnceu3YO>i2fMr`Hsq2BHs7%}r{JCn%GrX1v*wl8WjTYv5LT0TWK^)ZP*^7#v@PrN5eTmNE=2jvkmGp5M}Ot_5Bk`LLe3SqDPt8FxMo7G zL7aAwEW?>^YZGtV8|Ab4hm;u|$`^vt^L2Vr6s?CIF+8E#`133ELF3}aCPRP1{R3|p#)qWAv;+GHu3+s^aBduL39CB(D9n6hig z9ODK11BarP5g^CLbyf*>jr#l8T1kPTMu7m_nsL|DyCPG4m_ zyDYt*KR@UEx)M~a&G+AJhXi3&BC=-`o~1Uop=>SSQJX4z6oREot(gA^{OeS)q#&rp)*m**GfPs^*yGI=ghr}T`y4i}UVv`4A3 zYtN>|sb<`o)im9~Fqlt->EtS)Ps09+W8~tBwjFSOJzlh!e|753?8CZ}Xdsd%20}T7 zW)NfKdYf^~{}zRuqu#ncv*qCIzd^skR=wD!h%pryd`W#A?yYCpxZ>+437M(&KrB@} ziQhS0(dl{MFK~D7)QPjwAY=n$Agpp}_ z?u2_UG@e)U1E5(MgMh$0?E`+c2EZ!2QUXU!5a(Pi*UTMQ05*aT{_xb0-zmBqd|ENH zQ28gZDg|(yxIW$?!i1PZ6N^BF>XJ~0>YC7=FPSi^mt-}iF+jEO@e$eFMIfDc&WZ2m z#*}x;I+PSELP~qQH)I>?n}#e4Jmw)s$EX31YSijM#CFTt>Q3~cQETz~uaX5=8!Zz1 zLE?-*()9m(%hA7;uHrtyKv zo&^fbj*K1&lgQ$}Xsbf?`nGcuAQB{AF;A zU&)|h@+fG01(#&}L~Et2sn&g47Gm?7SF!>MUkKCFC2X>hJmt$YW-}}-#!J8d#CBE( zlUC;Q2t13T4EnfC!#XDZg~U%zkh$rPoanDaDkr zLjF6j<$vcSqGF~b1o@$Z7@IB^-&9r4Fv-Ng>`&_(@m45QHb&^TWYRd}Ce^%He)If+ zBR*Q9Y)6;~v1zd){4?rru9h`*yUEY|Ex^?Jf0O&#h%L&L(>txrVF z`8zenQB4s&rjmMW%JL#c_7qI#b(w>CV!0G+hzh%n-oeq1>XJB@=uH6h&e0YM*T>Z@fc6A~?yrA4hc%GpUr@PArZwxvKaWW^3tb!@Z_Rr5NdL@>4qR?% z4?piS>>t0&|LV2eGqD%@dH7$Sf9M{4M@M5PM_OA4Q(ApHeM2*2T0>iFYg-#fT5EkL zGe+7UqfsMUYg!v)S85AeV`@uhTWS^>dOA8fYi-Fn<~*B>9Az&_GrF0@LWLx8P;}#O zW&Ze6&~I@Y2VGq6_C7St_$lAdQ{S)U?^oW>obO}auZ-`Hi7#BD@8jdoXWn~X^lzfi z)$N*>p1SYj9xX%5mzo~a9bez6Z|hf6rs0~A=NqtX+%?@#$#dG^Z_@XaY2DJ7jIZa6 z-Jd9gjJIdWnNQNsmxQmBCElq=(bKPj&+A7lANlcJ*^3Xof!OV@nXMl3W6?$4f$bOH zX48{Q)%T3^EJ&Tw;GT9L>(3VUUEH39{_Un~bBKa^-kOk}j9vFEN9L=Z@mCLwW#av7 zla~$;8P%crb&s}>LGo{$k+PZL5FX1W$M)~$4PVO-(ND{B%_q%EUT)Py-{o(sPhuR4 zXWhvCJm)Fr{tVR*eTWzi)aZG(+tCNAg!S#WuT!q?MuYz47Q-UPj&Fu-5#b3+amK}g zoalRD>6{^3+-KaiTPbOz>~PZQn~)I&m&@A65NGbWehPKo5=Vn@2Hgi!`>45Rsa4Pt zJ@n8ZVv6OOd&?zRLoiLX{I|^cG3x@_mRcd^m5n#+{QzH7mD1*GT22!P#cYNzhDy1t zV_g{;kG-$DTE5E{JnC5w+yO#wKOMym>M$NXZWnIG-%<;m-(1^@M12$F5|Gf3y+24xIs) z+{fvtasZ&H}JAPUA(<6-Vh+g0wFe2m? zdqw8up|uC@d$+EE$BTQy&f%eT;Qm>ILH&(8xX_NBo66;`;KjLuYhcOX7|aH&hi)&_ zK6*!e7-o8?*EM8O=J39TZ4G5^7Q51zF;ihbOt3jc8mm8#BUqoP2O*hraeYd~r?H;_ z*qD&U_40cAU6s_gDBh_!vUTe+gDhcRbTY{Bqi?nc)pii%`Z#31d3i!L7*8#3JGA1m z;*>M&Smp3aCx&*kQbfxpC+u_A>F^`k7*DMWVcGNGp0vE%%Nw)15YG+QzH7vF&pEhu z%`eoY71h4Y)Z?3{&5`8`$bP`12>rLG56StJ%V+#7ICRKXWCgeBOAutilve}bHrIg1 zG1FF#UhgECp%OGeWnQbmnQptxgc(M(Jk# zw3TWIolccw6ay>D_Cz&5Dal`E1DlrQ$(gj}^J{+9_B9ALXm$!O$*hk&kEpTRl^nK5 zlyQQMvA04Om~z+7$)w%C!??__r_Zr(F!pG9i17Ruk$zZ=)%2I)L#;Czm!D19+hDwA zTLE8F_qDsX%EszO7J-4;mXn?FCDTr&geQimJ)OkSK?l9Foa-|!BkdRXeaw5;3Kbk{ zitSOm5i8Gi5&K|uxRIXdeLG$ydN8kymb!(*xq1wEtliqRK_A!@o35n}(t*X6sYkmk z!4Fq*`(KljX>MkQqU$?wo6WJ~$KWo7VMM#TbW+?qL5Ut{k5d8WXLe!)Y}z<|7y`<$ z9n^cA8qCLGr1Y?nkFv&5CvYXU!SXo+n-dktdgyZeZreBduPosU-Sd%PCL`wJ+quBZ zw*wBf;n~rw2S;jxBqoeix@QKqTUx!MtB#;4n*$%@Be3(hA7$%wR859|n|lUpYvC=`1WnK!f(39^{(2y&@0aFB zkhdtS@swm84enrwm>{wA@wZ5;u>)b<>uPMz`LP);|n>pvDT0*bm9K z$gk{wo)*#G1On<|s*FSMXkbP%(J=g(j~&>S{{V?N7Bacu(={DMa3su;J1 zXPN2BlM0JlTpP2bm8MaIIHKd-o;yr(y4u0}#0={?kjpnr*qkrNf z&26m{%s(IaZ#Zh-as%Djct%AI`zQ#1a3!vAck-Dv!qBuKAAZmWR42jGvXI@Th&&DF z_AmAM)!=(G*zP@Rlp-I^av%Pg{SksMxBw3{WO!iU)ugdS4J{zlF{WJ5fsECa7~<*~Dy7-4QmvK|-%1@(RHR zyaIPmg<|{F7Se2J%%#lg;Y&v~>O1t&Wq)$?NTUNbA=4K0sgoL7}D2ZB!;34QWkXoT(Gl5@5ix?IXr5 zDw*|JI0UJS^gO?9D=Zhy>9A%OVs7K>z3G@NI-TI5u8=&^{5tzr0s)W$Yw4AP+rPFG z?)UxsT6NM}iLmWpHB(eQGjvRu$s82iwCdSTh?#?)WCWFjaupri3d&^=BYBu+<(0^UNBCMB=%GQ>e3gfDoU{8TZ{Mu8w|)T&`Q?&~v{ zIxpY-0j}FKZGCsOIcXEo7$QDAOAT|Abg-hVx%gf;g*{k(p=W8$b~Y?|Aai*Dzf04A z0w5NVpby|E$xpaI;W4PUCtYDs7i2CLGSA4u^YvXNtcQTTw$}q4ILHmVY8Vs->vvAEjWh{G(cCYk!(0-300xIv z|L}?NdSK2%h`WL<1sMQQ@_B@7v&8NlA43SvphY#u67!eRWQjxT_`bG9od5-bgdbg% zgLK;A8~JZCurUP+fC=nu*bgn7h^Zgb{}mcfx54D#_m5gp#)0f&thY%Jq6!J-E6r{r zg*&6jgfnGKT?zXD?av_{h$ zWP@3Meo)kbyelf;#jsP8w$`v7Oyy0khw`crdIqo_u$?94chgKB61NOI>ykw$yb=Aa zcQN&8Gv<2Hsgn}im}~)9I{$t8;N^ONlR87b_d)f{W8RVQYZwwuPoON=KBuNSGRO{C z-|`UsEGuW(z^_tKBnbpM3v z^p;#OB({9uUO(EGeTt4L|5Sj1oja7CkNVcwkuHZ&sFa6)(Dm1{61}%WGdtM3`R`wX zJs>Q)X=uN6R^VVSG6OyveY&a2OzoS6J7q@ZL4{-cJUr}lgi_*R@!3wNy;6JrsjD-M zwN5H_;Aq<3i?B%P>At`>;hsy?;b;6L5t&5*q#M%!1nfU9j}6eCLJX2t4O>FvpIZYv z*cvl=^)J}sepi1m=lX#eF;wx4H8Bg(fNnqmr^HLr0??-z6D45n6zPHHnTZ&a1XMbv zO1X}klYOKIskk}?RnPwprLS3w9uoKm;zm4AtG^C7kVKW_9?~(a(M0a*U%>Lt+gH*D z&$z71k8R5^zIJPE-rWvk?_$ZyQtI!ZzY@nVgWYdTaz#^}V7O+;)j3*vBC3_?1M38a zmUq(3YoK|~VKTTf3=7-i$~`%2+^Y%-*pd#=vtARYp-rNOl){2_Sf2owYsKh62gO>f z-RX+JVv`uPKqN&-$yF2lesFS6YI?^sE7tOd(GIN7Esy|CB{2()z=)~=hH5t=oY$^S zSP5>+|4q^7apq2Eb);fX(TNkSUB2W1F+5+xeaS>Lt^VuAGWt!gc`~oh>#e0^)55(x z)+h}!P{n^TuJ6yAv0Hu=h$3uW%?iN;G#d-r-&Q2qcFn7(aym0I``1H60DMl}l!;z% z=oe3KJM7Sd+7d~+9CuLSXx&>XKs6SMu}%J0H;5z0SO;YUz#@bf`(B;Ma6g%24^3I` zJ9;|`Lo!4Wg4W*ixv+(GHw%t?<@;XWPl9RAkBweRQw*yq{gWmVEjdKB7XhT?#MoaS zI^|X|lcrYm+CX><$ea_%5>@uZk(_N8gVy*H#!Ns2;PgN$gpAKu)O*OJ?rn9PqyJX)0T5t>) zmRcw^%8iJGrFZtStrgfYkA|PNkBUu^LHDUSyE!5H5?t!m+*rtOw)X@hCijm>%fl=D z5U)g4NpC6hs+!hS{4bFfr+#D2`IyB&6&GCRnDFmdy(g%wjlf^=J-xhyj8_jl2ock) z2@`G+dP4;dwvo@Vux?Hhq*?q>@a&RVkA!o%f1N?3+E>3Z9~5D%4Kyh433_+fd*`Y$ zDHW6C@!bTZz!zVg4xUngC^jX2$+{~k)&VMdQ9LS#SxLZ-I(3v%6=NneL50~f^)C0N zvhdAUZJ85>$sD%Qsr(982SxjHx-=cx$JDlxAt;chFycJnY~J zkYKY6p&JBe>fS|loQ;D60T6GqFH!R4=Ff!SBCaC3sRL{0gn5XztURzt?mA$VPN~1# zs>hY`9+w2Mlho^GH(~T;P@Cz#7dvh)RWFUk4k-9*{UI43*5+Oa_QR<}3VIOm0p-tm zYY7nE=KPqn9`GrK8!e(CcrSQduO1N5<~)}V%Ag%m09a!Z*y5Xe_oX%GC!+N{eyn8? zK(8)={$J?LrFmPI)Uo^qsM5xM$I?!N4=lPz zk)f`mK&G*or7#Qvl5CEgnyZ)T?fFL5a?S$H*`xBE^2~fpsnbIP(lr=7i!_or8r9~x z1D4#lK=+I?(|1gakH|})>7CvJxDi+CdF_Sy`4tq4$Lh z75M2&n|7{rZGiE6qP&8$MepW=D0vimL~R&rRzeLB;g{&>j^lP!nQ5^PJV9CKv=0;d z??i%Vc^ueAwBt>15f_j&q^U-!|0x>5w|?%L8U+sK90hXz()m*uqW#`}A+Hy{W!?En6w~9;Na8>W5ik9^G*MIHSq~r?Cxs*Vdzo1eao{@~wcFSCl)unv!||N!cm8;weh*biJc~UQET#AFJzsOg_7v zzja-O=ZtV90+#{txX;mPNL0-e+fR?ffD*g$dS~zDWQu!W{=ktK#qvqx&{VR*xjk65 zBO6Bon$z9rr zM6pp+E*r@6TG8hP+h)3KDzhqeI0JY{!zBrb%nfJL{nZuEDGVlJT~^1)$CrOh{GM5( zs2U%czCL29LZvsGXx`nE8vk3KI9n%ZdqSdV8X_DK|Ml%R^?cepyjc2$e(W#OugQEq zu`Lf=ua7=*v@ik56&$#PD4`DEE6bkRCZCROxNvR0Fs0vm+No(h7wcC>4z6%7jEhF0 zX}`GVaTcdAdt62T@|-QD7PSBXVKs?+!A4mV`j7JwH`*e?XzE_F#vFl$c-rM97)C+Aq#dVF6A!;#jl3ZTU+2`2h-<<5bPqy=@)ZWT%8b{Z&TZYPW_2@-BBptGJDcQPB0-x>!z$ECthf|zC8rQf;PLY*A4$^k<3**@N6YGe6n)Os+%K@2)ckGu)yZ_n zTa)e+gLAw}9X){6njs)!56IY^N7ZLh+u<%!p$tkoOcAG(CUh8|qOZ|4MWYLk1BZ^f zKsxkD(j`GGr}FaEvY7>#c5pT#5gBgb3;zXvjmen1*1z)Wx7|LF9xklXUt4+MDZZ{P zk(3zZd9o%3;{6>^1UtWnA_8m{RojgBa@p?r3JEW9Hjhs|!!_1#uU!)~-$i$&5DBf4 z#b4z3c3|y771k|_UE*Nht}R1xH1TTM#!-;jW6HKIv+C_E7q}qMo6cA1HeMi%_o}=% z(cDcu^{zA++MdU>Na8a|^j;k>(-OTlhowl2lsB}om(a=ajB3^`eOZS@wjR15$AsDb z!5Fa!MFdM0XjpUB5G9<<5a2Aa{=e*|tYGynS=ciA#AQmj0L1nD{8|-4r7CVcmSEGuW9~%h52QwA&{pc^yQmLBK~-u5NNw0J>!8ZF9^UrdF`@%%wc+xkqAjpr9UfIXBaLr4;3 z4Po!wTANJG_K`tNgINeGx*ZV?7^>j#h$v*C9Q;~WZC{CZJ9XY^&Fc0EDnVEME#*dq zR=#;Q>nMBv*ks(U!1Sh#eYG}?;W|nI5{a}cePRM!uJu7nYZ8~Cqg=Trxh#x$rz!%x z;`gU6>>}Rg$lC_a=)KkaaRa0GI zlq0jEUam;$WgQU-6Wb$mJ$QVvlX^$4jwcDNlx~D^sm~c#j5FXMMCC;OE29n4wHqT z`~tA`Uk-pgs`U9$s*+$>q<5SmHIUQMnSpn_m!wKb5^Q&lG8TgU^p=gCQ!e=a#ssB= zj`%jhAGqVu*9~Tvo@dGnA&Nx2bGu+CWg1kbr9{D!cM5{7-Ud>;x&aETJ!mqxIrn6{SW-$54CMt&v&=ZJ>qGTXDJj@ zCJ~bw1dN68yVW2&2VHDOTlGMY5YwnNY|wD|(V#x})SMW(=;+qop)ne$!$3Il0|}FO z`n9_+xS4V=k8(>AamMa+Wfjghmt`42L;svz@FUOH_F2(0N{D|J@V{Gz=4yv_TT#JO zBD7Vc$4~Jks}h5n|AF20qFGmlC+G_>iV9!v?ZsQ+=+J8=X{vs?Qn4V``GD9L0q+F9 zyS=u~>1T0lveZ2H>=rzPLWD_r;k{)Az~bqiLIrnBD5v>szG5h_IL3ZLj zA_+QM%nZY}d^M=R8kv1ZX#v2A@2D_5J>&b2*Q~K)%l`+{2vmmU0j@ zx8#gxp&TfVOfrY-Jlx9?Ev*m{E!6BFlM~NzcOL$TIBMW-TG@nz8K!xC)z4v!luBS- z6R4k>;CQZu;|s#P^s??e-#@yPw?a@KfOHo6{-#DxeTOB{5L?d8D_6cb5b_b`;I6kl zv#5j5vqTTTWEw0aae>DfcEW*x`WZz>*f^5vJjw<#=;9s`#FT9#)>)|0XvxA+ z1S+J03eJcm7I$Wnd=}Qq{X=)BND61rdDS*F3-@8oy$Y-$;BlqiQrCS~2|@t#qe0=| z-TpXes@XHAa+{Y_;vW2S1CyNExhcRd?{qGVoL)IOEFi_}2qrJ!k--i+TFCN%OGD{? z+PJ)UYnR0Z?Zm;E<=@+PTO1j|uzQLjJHsc4vt$&^icGX-&EbNdzdo@xXiDf%fK?hIIKkOF4UFQy(b<>;yP2WR!+Lmhdx&721l&%Z>#2D0qH2^?ewmrMw=GUT%9O> z?3Ptemu2=n--7H+T>CUQH})B9fi7F>FR7m_^2oIcAXge0cqv}gcBk@&1Ub+%zz;%a zS8G}JsPflzr;`&$NnOTR*BQJZVv*p>G7oc}BdMw)!|hWRhX;goYoji?m$~R}$WCi( zPi3o0@UP=VPAsiGj71ao@zFH~9v7Tiu+e=ZBiKcPm=9cSRV@6Y)#7sE0RVnFbE|6} z#{A@s!nzBQvsnm+TS}2CGA8{Ub%25R!t??Nyv00pg(^trjs6w_E$b|_#X66uQ&#dn zSh21+d%VN^9k>>@kBfL6rR#DVr+3Da6v;gF)D_-FN6sf%9I#nj!LMK(v1!6t z=r@U*%&T?eYRr7thuRk0UXVZoSo)O?qa%5nu{1D@A*h$dx4i&eb+OF^&GX8x13>a_ zL`*?gGLklvAlVLyYnOm&XVpPxPomR3c%x?W!aro(S;nhIalRrtN@94+Ym1XDZ-*AK76ZPh6 z%(ACErViBiG*ud=r3280>}cqS#Op1>zTzu$Qq4B`p`zD-^W=$JM6d|%WMdq7_bvyh z_lnCQvbzBC0W3fk_MnoE4Rzt$xK*$G+YqRjlQ{I}z3Myu^cX53d?4=OYPW@5Kx)GZZi$;s_y95+Axtc;hu+2PXgET-yk|EGa8Nwe>4Ui6Yne*8_e6E{y zeMTRS)Y)`GLbKe7`rl@LZgs*wT2*9ckExX7RCu&|M${$E8*|KnZ-QmULb>!f=U0rM zC#XhzvsKQTR&y!N==tQ{#!C$o+$;^zsiYV!n5^sDf88Rs2Kee!TI1i>BpKm*3hbej zlL43vxvPvLd!Op`c0Ulb&sT_({(C$nREyLv@Vg;0G81Z2w?W-kdolAG;ovx(B1MZUj{Qwtln}?^~6)1OQcuuN`OrGr%R&^cJm~D|DRvevVNX zp!}_bM1L4JY$@)43AJYUc4gVDfHU`9S;DelAQjG*2OPgGJqGWo$$=_-yW1nu!44Mh*7M3>>QOKlU^i~la2qkvmB@7VT0=l_cN7nTtopTqojYUu94=X7&U6ZF%VX)pV3MwT-)-q2&K&>AeME<=R#S ze|Z~clm5&}d)0=z(HL4XttP%|IPU9J)l|;a@&;-eA0u&Ri=drL-#5&%I{wZ^RC|4W z5X*8XV4a?(CagV2EmMt% i0NeL3!XY%=*P7F4?Hfnur@Cn}UQa5{}>T!>?h$HF- zV9VJZyx<>~Y5a!F7OQX>kerG05;5SH!LvG3ef%T;M0fy{5h7S^mVjf&kWjtF;Ep+M zRpL3%CrVjDKPK0~Sf1c-a>o0(Moci5K5}4u1+TYH;7r0mHIrifp1iQBUWKml*2biI zqt=fypu*<~^gu5+ABk9b4!AWt28fmrFXu8$jZO;H95a)d7bG8Siro&bVjxwIYTR)a zUz43xTWY7hMd4>SP|K-E$h7lo#ArRR(L?Kj>6`H!Hp-43!fSMAsz_Q;P+1?VABZ

-t(wqkj;9n1%-Mf{Eo)RtnaT@f?2BkOjor4#VAW(bbeSW`9S=J2q^Q zd9`$0d?NIQQ#Tz5mf4#dtgOQouhvr$j=$C1qApDxcR)b0NZT_rOh_3VSRl@g| z+7;WJBZP0Z2{F8FqD`53ASyhEg>P-(Ev|1$apj0@Vq_lGu>b5fhStJM$_AIzs)=G* zc@$nCojv^JAR9u0$ zA^V7bps7%nr<%48G$VHvIOXjXBIxM^Tzj&1(X-t64%p_DW}b>K&E|1xNx&(?JQyJg z5PB3#RiuY^M_lmc#ZGn}yY1%rBjEkDYzG;Nw!pL_u1~)pXa%-7&%}sC&1cCC3SOSQ zbJB*Vh6n<`=UiY&mpU*2y4J}d*k=tpkL0%EA{jHC7KP?5uOm9jKH=J24lUC`;`Ub; zCrYIP+wHctW&Ogdzw+x|cFJd6yvQ@FOhI?vuwqB?ANyf1p=(DL&SE1XY;`HLlH)iqws4fqLpSY(_1dj*{F#aw;ux!PI-4^YcAKb>w zn9?!a4VHC-C7;=f+vvW}E-j2~BsTT|0Oj=wRc{}^g*sx_YzZT&u%1H+qk=*&B`&*! zifPLbxbNAS5lpac%f87KKwDZybx7Mm`^)8pi}x=yQBLEuqmg{~exQ zY^?8ZDfh)K6E)hQ^(L!L^vVjn62p19;s7cuK#inITt(b}T^vYi@fmvgz!W2Y;tIT5g8K2TDwqlVp#P6!N!yuH(Zs zezth?+7lfFH9#VG!5wa=G@0K~pBoNun zi!W!(^@tCt_b&o-E#JZj@!?HBUgWLQ*0L2eeg90?FMENtvx@^$I_TI3$mIp;HP;W& zwoIFC_Y!%Qe>orArspR^ax>Vg0I@CCfe><26Bkb03M#?@166GUI@Ui&D=WssemGl4?MbzR-kgQ( z1&b1XB}&j~uc0F@F%OPj-Qtiy?EMVu(j!!_Owi?8Ke2;t?N_8v0h9lx!09)T4JN9S z;>}5_;8~{rs&q~icU&#WWfg^)1MYZqd0(dxnJdrZBPhrXklTk-K+{{~r+f1LJ(tg9 zzb}39Us}e<2~t{MZ(0TDoUd#pjA>W)?i}60Z)F}jdCW3Mv11$y_KYi$ z)=7Qk2|mZFodV*I(^ZB*l}6W0#5AP+0y2FcL7ub%le;B$V;Tikx_dQUSbZ2~E4|R& zF1uf3GJ)I$-c2wj2R7z_|1Ew%9#UpzpXWnbD5`ysgBV(41cQSdWa}Y}=#cR%Mi9?Z z4>qI-3aDV+VfOLdaHp~t9{9+J?o^}e9H^Ju*aT?4W9d;kWpyM?6ylK%S;UkdC$!!2 zAxItEW5)i#-&v2Qq>nblIyMA)>?5|i#5%X%8Pg%pR#S_tnUhaO!!gS3M{XW--v28@ zX)W91U8AW%=(AnEx`f>Us%NQz{rfxw4RISWd+ymY1_4%J0s-Ym%OGVIRt@V%`sZp2 zbiG`b5)1a>=XaQ~Tn&M{#}Q9FSgeCChtA zw%{S0zG1L?&{tl9xU7Kk0Z5n|%R7E<$J_lmY`ZChHY6bFzY_}SvL^R0t9G7Ur$vx1 z1Upuo(xd*-xidW+RZ4V2v<=Y1x|-a~)=dtw}NPpIMA!Dz#c1$B5Bd$LV4FKsxbbkyZNrf5Efly$+swWUOn z*1D~iVd?}ZJE<;q5IRm>ReTU#e3QTt);|w4(qg+coQ#rw5wCwWqZ+9(B%xvm6yFj1 zY*G!(0tqOQj=JDu&KU4OV@l9M4w_}5X(QxKN8B=-Khp|{TwQ{K8LvuuH{)0(fNv`! zat6b)T4**@(q(&g)-gHZ@BniAgzn0V%Ht1`Ivtt>GcGG1353M>8JFvgo{s29n|6#C z1-{(8M6KDTDOYWld-I<27E%vnRs?yM!3F!SR}UIRiO1F)Ftm*YJ1rD4buh!B7`MJcjoZ#~10xSTVjV*db68PTKa5F&Z3*PwXQ@G8 z#~#XkQ_hN}NMEhv_XJ`S@KP(u_(&~tYN&oyMzJedzdThLO+Oi^6f}3!DfE6m5@AC8 zl3(4maL4&z=G2d#Drp&{tukUI=Wr3-Zae|gGrH=)tR|4LGru+SGFD*@Zn%-6UrS7Z zG_c!xxU$u2IxF%(3nDc3*o(KZ871J1EYSwO2?;zj%C~@KnsOPs(^fZOHZXdBh}Ic0 zc?uzN!2*mWI4@js|xkJP4=LDwQEn|c|m#c+nGboFYhD_mnX4?{f|T>0!s zvCMpWh&+&FYKzzDZcP8$*C_62AB9M<%zk5)9oJsl7MgDRn2qZhXQx4FNH)#fEdww1 zY#ADed-r~HN2jIAFDrR$Sy9jNoM_!2aYoXe5^TJLwO>s~IvR7wb(5r1ga)QoA-m|0m3ftkiG1BMO;(I14qp|oSwH1(og7%QGCC|eza7`wkF z$AZe8E3ok$x=v(--suAzZIFFV5)hW(s$rt^`r0u68>jWo?i3JdDsHf}A5pxB~6&fluLn&!j@f zz$iyzq?wnJs3%vpwLX-TfYL7sXQv*n&B&|^ovb*nHx;5PWGq=~4e8q)?@%Rt`45Ge zFAsM|o>UsWDW=Jo2`tnxfE|@#8OmGn-s^zR$DeVnu${2d!G&~k(my#0@wMnMtCHq>AKOuQfo|EVK1j?hHY?>Wh1PC- zV(|;ettUT}Si4fxF$_xIodgeOyttkcAr&M zk}A7ld?$Q37#>BD@p6sX>9WG|);p^*iiGmYaNM9dZM^tcP4e&>&py1adSxnb1PC<7 z7aB#;VNBePlX$u5%d?trDZ&i#OHKbPa6ocr;b|JgEe1}oQ+!3EjYUqRy~dvvAiv~J z+SAy*1=ANWLZ8UeIg%l=2jqT9W-PO)l-se!O0rIvnrsiUuA%7EwVO#<`G)0ShP6ko zFi9PstU0=#9N#8TGnBs6)|{6QcRTz@UCk<~24>G6ScyeDQo1~;A zTWC;?D=*QA7*3tY%d+7xHyvUIW0^j-b2>;ce-GY8LS$FcnqCM5Gm@nfGX3HhgeElo z*Lgio`RX0!m{dZNE_r=UX=Yv27ZAyg5v$@q?_l!vBxXux@n8wlrOuvp+ z!dc`ZIG!B~br@#6X>*n-U(qR`hQxm?v|}HtlB^U+LQTs`EYtJ>_KzV;n3G8!Vg8w1 zeH6^3e!LW2W_sd#r{i3I1p%}dKqUGxbc@GCD9JxL}#nTLE)c)^pPyATLnl&aWl}h8z$hDxD zG7?_4FdbYw#OmhN-~~r7`3+y6kHb0A@f{#(8r9$UG3zEex5y2rgzKE2p3mj`lB z!$#xzgP4qXFyO0bYFYS*F|4?~GF5t31)8HdN^F#Vsh(>}h2ZNH%_pmLAEEyF>3EuO zi_tKt-$Bk4nmhUxR|D8x>Esbx!D?pyd7-c#Om$)y8^A8f>uYCL#FEPRGEBGOy^S~9 z3C09{idw#I(p!ANlsxG%{j?+Jjl&n0x52$w#iryuq{`tL%#Nl7TnwySKnLUoY(O^7 zErdwZqJbz1U^GD^JPsD}bjo}$zeB4U`<5&}g0q7UWMIBkHNj#m`rrRql)c%@K(!H$ zkp!{d3l_kef}Zv)iqYhBrG>vJXTs>AiQGb8y^ZzF8L=jb)#QyGJ^T8zI@zEIJ5CnC z0Cn1nT{iX@Z^#8u5rVFzFjR;cA?oRRf5COv7|Zc+ZP+=qh;$RKzliX!kPS{b z6XLX+akag!MA-kxU=qH|A?{EiYovcxa9mbF8MxmOWI{3c9&%2+M>H01%%pfX+8o>J zfYh2GXi!X;I7jUJ5|z{P7Em{!dRpvBR5k<|QMyUb7}AaV&6FfdWJuy|j~7ZkrOIsZ z{nZ%&5{m4Ej9Y$rG_oamJ7%Em0VX5dJ8s7>scHZS0*10 z+XS5=Wzk*&8d%cO*+Msg@0|Q7e^dy)#t34a;=x{@nN1aRAF)r+>mQuAsQ#!O7B9a7 zpWXSr?wV1B*n64X;dRnSMk&tCl5qqHPZ|l6SXcL+lG{l!slkh=>U!Fl2hWY_O#;XH z7X<0lMkHWVfXFSB=TY1;h3&op!djuPOUqW&`c%k9j!Ce8c^QmF)$L^h|2cCug_EBC zvc&R!9w`|E1eOESkHxNiy?Obs!A=Hii{jD_A|j3_6~L?VW%;DU|)+O>~Is)1_AyRWm$P#}h93M%hIX994 zdo7U$-C-IEzXAlq)CT9vC|-=~zKqJc_HmBnaJ?89q3vjUUYG7nINLiY6yBCop|Q@D z)IS#6D{C6veC#-!`O`253QMJSmc@o*cT88s_PdJ&0jz`IPFICM3|^hn(eE6Njg4Jx zQ6P(Gp(FtbYcv8`bCV%o2@>SmXW2{P9pVs{9=ZY*XAuLet>U~u*35l<(M5)uQKBj5 zY+{K!Bc*0*S6Re(?0yX+;4nOmB9HwGAg3%vwsVQa@?c&pCo^;$FscO6OtY+!t#H?u z>!4g3azK(guWhhp;uw|(k)1>K2No6e-X{JEtdCoHpdI1}=f^#-J!a9o_AtYW)-z>D zMop4xvB7V4eE*Z*ChBf52aghQd0=c7B2bNkS}`<>TVp)y-DgO?Ko3mOmq+jdE3c3}8d1)h3t04Q3tGWmMSyYW84Y_X} zCYrfOzmTpSNJ)hL{hU;9(WbeDEBC*p*F^$~@L)PhRRws{Vl4BGgzuYW!A@Sz0}?)@ z*dgu0BE$(SANfve6>X;NHK-)t2As#aTr3)v4+8n_P4dtt}S> z0ADWPCxk&vB6;cJH0Hx;w$CgnKh8*^P1e_>FJ_A}^L~LR z!9-l1i$=;AL!k!6uwOl5UNzxjyS+4CDWZ{tye#s{1yuLk2@_wHO1)scP!55KpAMtB z=!f=>4v3E+$2@XfW1=3HXJ+nO=f@-Xs@F)upMMbo97HNWUw&A10C98+~(c3ydgnPGGv% zmjOY}8fLn+xa5In55=$s38XCb4hhKE(37NE6b#5LfQsnSCTzh7(9@J_;|r;mLOhL0 zRtU+D@PN5A<|R-!YvGXuHsu1)dySgq7ZY@rOYbm!kz zpUV)BTfL!6iON&l=stsk&gLpVH9iN2)_RNKr$2fGbeFK^$b$3wg9Q%k(oAlORj|Gj zPJ5&KRN(jrIiDs(HHl5Cj{=ahEYg=46kFye61c5b-cV466x3kert|st`uj@9BAszS zyqZ$`fUZ-wmOJ9!A#g#!b5a08e!o{ErZk&f&j=Gwumk*yx3!mB1Xz;0w#)7Du_7ta zqj+$}8G|43bJv8K4<$|G99Rn+Duc;+y+Jfs1NqDnRrtDd8&f!4kK%>%1`8Rbopc z`sKlPPNYz<0xw?TbTdBUi?e?m>|7G;EkM*7USxzZI&lzSnLW%?I9BXS5edvHyhPjn zY8G`yZxB_A(^u}W8=gepUE@&t;0%u2&2t&EaX43ve*v;%lPTTV%1a_?_sekEBacO6 zk1;jFqh>;SC>3Fd3BV$w&77Zmu{bqPIi!Q4<7*6rCe1AKdKVF4wS*U7qtLjfm5Z+{ zIEPPUh8){jkeB3D8V%+IPb`k`vMZD8m7DA2f_$`k^?RlL1`0x^u`y@o$?P&9`Gs_1 z(|7q$LLV6CW+eR5PK5(&g{_kz_{N z2+M8H-7*_IE1tF*NUS+C-AsDL>XW^SLaQ+96s=BYhM1R5k|4DoFnfHBJ}A5CN6&_y z=6NdB(**jFB^~>no7^s4$m?A${Y9QYki^~INGl*OaYa|`K()zsqIXi zF`=_{d<2L|dRIe+2#{Mca~GG~2J<9KHcdNt8nSjN5vW__B+*hk zpxN_cz^9q#=oRg{n-Yo)zeBOi?}l_$D1aM8EBhg=Vs19R{yx@8pl02Pd&%_?fT zRPF`Wf4|{KS(+Yeg6>3&Bl4thDPuM4`UxWn+>j9dT7lVH4y65=ohs^pLe3 zYIWX@oNS!Bzf#`MQSR^))601Du3bhX^k9k&gxzV0bR06=mjo_IknZ?ZBRZclBi(LX zlBZ8NAOK|^;{%%ig%w~l&WdX+daoP;KW1q)N*W+FbQh1A10GAc;=NGTelOOnsx*`< z%r$CwuMP#GRKwYhk48O@4LF6H9=Bj)IpoJTtHQtOP2)vhYenxHKA^Bm-aq6ZZD)#K~yEv~n zLbf!4L7Cg=`NhWkAY|*eAySlhYb%_nWiT(MU-NpHWS+Bh>?reiHqCez^>NocTZ-yN z$H)iC<1E#7rg%S^7hJK%-i4u4Tbo$D6!>M0>K#c>ooj+Z9C$;y3}!D|ZfUNMwM& znCCI)Ed_g~cUEquqNu2S1Yg=AS~u~sN0!!z2NSs{lA}}X#V_zdqA1y(4PQ@*n91B; z>M#218p69`L-k~NF{9;7%)my;a01wH{y$rK}z83;wGY%292^Vzma%0z`j4$jP-oDI5 zcR;8VajkgyhCjgKZ<@e^=wiu+0&>CqFqS5@QB~9?U!VrOeqhiflI(wWwsnRc-zBo3DJ90VVLc0rfMbe zaM^tdCvJlb;Dep$-{OLWZjIWNVTpsk|A2{>8b@}?EKh?}ZRGTp`F$b`YSOF{L+q3> zBIONcf{v$(Gu+lj_k@s4edUgUttG#DG#MIXi7y)j;nHzAw%3l^@^pp#@M=RiKJsMK zMvef~)3PGMSue}nAtET_d*q=ay%|?GeUn`KT$lSzNMF?QUPiF4h-eZKjMgPbM(`}!hK$Yu?`kr= zr9;MRpF;|GF7PeJ>|0=BZR+=*vq3O$orxqe&v@MV&MK;Y-pajCnzMFH=ltL9&+o~c{a7e+8luxa@6*nE)U)ZxRk=i8v3O%fHY z5fL(IK!T)1`6nu4PX4S=#3Y>}JH?lxPmrId^ZuAtI(3UQO+!D_Zij~5wp%(ZJt{?4 z!TI~yDRM2?ZA{C?0W7R^v;)>Fcip3{Vrmq7PK+==5f(y3r6ps!k3bR@GdKVJ=r9^{Typ@Cb7ugg39V&0YL%eF#flPgAaxMq1 zy)WzJ8^CKCu>FiT|I4d~FDR+Ai@+49sp4ts{}bcA7;QZ7rFUlw(IntsQYB~u-fmwZ z%3&nRWbu4}BaaK$NR=xlEL=*y8?K2>*ot{pU$(f=Z-ewb=1V>P8I$s;{Lrr`z6^aU$C zC9;g=Fe^tJM*ef`Cu|JDdERqS$2gfX*$xi2vYFn_De&hqh8mlK)QjHuS(9Ax?7kP` zbY!M|FY1;sghrh0Hn;zvApFDQo6QTWbXgi^MySwQ8hm#QVT0)I%Z`taC8f z-wHdT(C{=dwt4qL$m`5m;(~x_Vm!C$fPS*^hG=IFYCeT_;k)gsIX<~m`<0V+Dt_=hTWHdc_cRizg!Q7No z2JYvBoB;8LWH}r|tq}L9E#vT36W~>O@G8u35-GJcz(UxxeU$Ro_gNWE$ozj69bj~0 zaG>~l1W`oNitL0pBN6H(Gr>+n(I8A?hBtq5ZFG8ZtpdtDj>=gui@r^F6EA;3T3YHd z5ya#IF3R-$6U^#NLJv^N^O+a&oeaEHH|;=4grSfC)z-0Wz)8mCda>HC z`T8=bT$A=d8OD@ofR&}jZdcM9EC|Yt?bwDb=J|SWHcMmb!YB>dH9u#|67DYBpj=wN zu_slbtEED*HXEZMWCBI)Y5|ia7@h^@#J_?u>?X$d%t5794h|Kz1(OA%qdfgMVlFw%)ST_1^89S#(6rT(QKK8?d2 z1H0>f%<&R5GF~x48LB(%I(bz*7d23W+8Or;m}Nyz!OTBL!4#)Pr6*)X)OSQOkM+eo zmb|389A3GxT*;r3+`0k%N-;4)Ob9QwoAv>6n(+U68#vR5?2n!7&-sf~nt{UyS0EiZ6KYvN+p;<2u=>J5U;5`XR# zr^$m{ofyMkFr*JJX%@Af$_|We4DKjLN=^C*$TuZtwufXdxSK>bB6}w9ByPm&f*aEe zT-_U8+u_XlC_sXV`@?Z+tAXJ_ z+7FCq?9v%4_yn35ElC^(01lcVn*Ci6o%PqtRO9pqK+X1j7gDb?VvmQZagU>yG1ni` z+f&PY*rpKnG9_&U;g_82D`#Om( z;DEQ+GzqG3N?av)sG%k26i~_YK1p#u_~A3bf8=^D67vHMi7=E&P{e($*HQd{|A*~c z#{86)mjeK(xck4beKP+KY@dm{k%_(Yuh12}i?f9_y|kT?fwhIFiLt1i<1g3GNzc@g z&fd|^-o(+_!o+FF=fY`2wc*6=8?`NWJ+dp!mBfoI$(^kgii8jnIWZ4%zQvS%B2Zjh zP!I@*$C$hP^Jb&=0Z4#1adZ7GK0zYygXi7(=iMRG?{0XFYpT-uU@1gxrzE#WZu!>F z!9mAQa(t1SI@3F8Q6s@?=Iiw`1pG%@s&-VVmZD2Xp``0q^Mj~%;K?59s)B!#mpPVyniH57qeJE~~s`Yc@URvnFy z?iajKf~1vNS^s$_@52o5x67eFo%FZ&bZ`4dB3G;`mI|_eY8QN9fkPCoo;PU5R?0I{ zj{&S4C|M#axdKLzGegz1H{v`bwmzUc$9_7hFTOTvd%hpf7Ak{>KPo8fx>XlGJYl4` zVuI3GOua2K>=r5lL*CtzQtH~(^g4~~j^7rfZo=%j&b=sUFm5IO+(=~u!Y~gENwc@rYDO+1$cx|ZEb-}>t*l{{r0%ec z$((PYxLITrMqe&Crm3`*qQck*8Mmy_RZ65*40v>%KYhNvIU-4;Q)9T{#0D-=WWMe# zer!vPXMu^Ve>@$s-?UH|Kt|$P8=imN=*js#eD8g|zqjIhaV$)z;Cxf7gW`t?Fhr^$ z{~Vlm{el1L!$8~h!YBjJ>KRf3Q0ljlz@i`V+e(p8_4)u2|M`1-Nb&{uU8Nu1J4b|5 zYpA|-XYR7s6LuG3X4c1(4i~gUi6oX_miae?D30a8lB(`*sTJ1my{ieJApmetv7X?s^3L2I^%&qk zp;H-Pl?E)o0x(AQs`oI~kTe8ybXMvd7;817=9NmnZ9az{=ZYC(___RsSz7=B0e^6P zAjG1e-5;P1sfK7P6FX%s-gF{ecs!%=q&nKoRKC8F^f& z4>xnvIch4Z(ukfhssF+&pZGbGB^-BQX4*L9BVD`Ko1`5Cp=-j)=lG=-KYHS^^YJEv z?=mvOk(;#h-dn|5XJLO$FUY~=X{;k;c-HAlw37YrIrJOF#1A5nO>YQ#7d_~1z$YC2 z;Rr!?;M^KdhF=WegA&FPDc^q3F_2nWK_%y_Bfw9aH06@j8!%|C_vZ$xp(c+;K-B5g zpY#Y$>;y_GBM?fOx;eUMlndQ6e9pK<8>BL62owkGm4Hi&wsdbFDKv2pv$}y=6^_QW zZinEHNrUKAX}QVcNGrD|f^gYbV`k5VmyK+Y{$8!9ezX4=6x_ksIZdEQAgKD=!CHtP z{Q>N$g~)n`dXVq-WzGD3YgpS~tn1gMg^a(J$B$z#+duA4 z$0buP6{_eN7J%7&rZG;9EhJI@(kcf6?lt1?pSITx*`W^d|KMvxrzQz7j8wx82OzOz zJ*epw`(y9&1Z4vIH+E2+37L{qgp$NI1rF)e2YblqvkJxA;oBtO*KS9v-URItW#UgJ z-f546K{{LIgp&%MTQ$%!z|@1jzL9P0%?EXRI>8HRUpn00xiutdAO}kQDSf%k0Jqow zNiL7jlxd~4o!kA(j|Y3bwn;AIn~g|yS^0M!E80=eHs-6!AfDb+xYK`!^IvZnJwgosqW|R7V#JXzxr_BzJM(N-+cQwvO6t!T?Vu=hvT#fJvpzVHiKkdA$2log){ZFjt670!oK~|<`sywLI$Cfq$bj&Xig}^F{}wGM;n8FXs2nIy9DWl%g35+IZew5CoJQXAZ+P+mXL^Obj}YI7Al*O5RW5BEa<5 z0WOx+@pGk3{y#QWf#PidL&Y8i+(BVSy8b4r7l=}Y#!8<&>fqj*jiitK0T? zLuIOJLFSyeZx0ho9FeAFlgkzna}=|9mKp9@-PJ?DJ#-5FOZ>gd2cuB-)c2WVq6`SL zIMADrkDCIl5#MRBBfHUj*AtLsuFt*4bG`V%Mm%%+S!oZH*?%}(`Hv^>%duY#MJ3l{S}q5ae1BAT}DN3S9G-nP?HhkzN!l*JD=>xgd2&Yp%3Iy#1`R-vKtaCMA3nm{x z0u4xKPhJXP<4c`Xqjjq{YX#wERf9OsWu(e9nqi|fXn%;jZBTcGh}nn*k8CxURQ&-+ zmcGhM1?QyzHC{*Xg^MNC{%{&^l|QGg`S?7iugPGkl174IL!K={x`jHxw<&Hzecv6` z@~(9mAHj`?9m9@FA^lkMx}|6$Kar~(+*eS8$hXx99_rA%xXm%yZd04BsS>E98)}Be zlFZpI>=1NebSw!KzGq`aS!fG!$v?&D6yrLLBqKvCFPBua|O7lMd4Q8~@s zCexp1#SlGV2)KQ1Q>JC=9Q%zC7L&>|QPkX))%v_~;^a*9NmqQ^b++D+hTgBHi&UVS z$CL9?qn(TNVi*zZN2*|z*{4Lx`~`bBt_+DFVvus&!sJ($VY2~}MDv*hdC1T7Zt z$qR)dh;+_1C=c1i=}S?+bVzw7Wjtf`pwsVcj{RgLquR()#9|zY!WWD)-n2wl>u(;| zO;w)LAoY8)kLmZ;?oJgwoy_yhhv_pQ_@Ri ze{3Om@IqS)Q+hlj&D)8LhJT3c)7je0?3?n$_GDTqmS(V*2w1f`rl_zD&f#6QN5Wrn zO$fG}_iOlKmyuQJvF^cvM2q&^-EPFzUeNSoMG_tTyDL3RZ!Ep$7t!~&u0*#0AF*3^ zs}lIK!`1oN6)T+f`A2djAsLBu5Lq3pA5)9=U0w8)7pu7LzKYa^mIX#n&m@=#2`rS} zSIli*R%0fL(BLgPD}v`AG3kir|4f5tP-TXXn20w2O4HNG$2I3ONaa~6;KLS;x5Q6hCrLcFdn^=>f?!GK=$EJCWROgvRC%L4kdFO%rJv)7sC(Ux}R0Hq4$Evg^jBpQlGI;VQNvbrFx0c^N0Auzi&OykFJ$n<*zF?ny*AAs{AEwZ-W1P zyaRQcGj%$x4Q2JJ&cg3t;cjMPwd!YY9=AFail+YsBx-6LFT;4TqcUtut zG(81I^^_XgeR)pZ>;^;C`AAh>JS*z%DuRy_13NdCB3qY-`P7JB-0|rt{@}k^9f|5% zZr4hLtXn+wLX}ASi8oQ^D>4K<#`!o}NVCMuf(oDCjv!Cr5?#1X z;);1Qn?-`g?&F(q*jH(i{`no}oTy7R{Tns-o#49Xrn1h2h9W(f)=YR5>W@R3)^9~p zg^>FKe4yZk7R8zN!jmc0c zLTf&a=9dNHrf^X(1m0CuX_Qa!A;!KVRF)9H*``~uiSW_+3)oEurxG?{vahHA?0q%F zo8&~?`SN%1v3q!jBOec;lTh1yR63Z;7&Yas?q>9`&h*0ZIioZ;WNSHFAZ;5R3__a)-4wvJr42aL$cTCx{n4La7QmI9GY*V(zSFb)FsZQ%w2YCqrCB z!4XAzuitRPk~b51vRu;)Bt1`Lyb|lQlO>a#UJx0BY9v}^VSMc{S8A{=z4hq{vs zxiV!LzmQ^j)xfN3F%=uXVU{67J=wCajgJ_CfQoxcn`EacNbaRloPOy={Ssly&iTbU zzK=n;^CgV5;)bajY%|ydR}En;>2BrkJNA zTR=pyL(sZ%zk*hcB2($g^MH$L^;a#MUa?t3q}q-blWmb%FGkP0DKVVA-p;j9gu6$g zPWo7q13SgxWA^2)G?XGCVz~#j)!Ran@Rx@$#8sTSj9DHZ?iDm@><$i-{klj5}3^ zv=au2YU_6~*ih;@4EYW!j-9F4%zv3Z6G=+dGkWt=-C2ny;AKNF6Lj}g5w8$;zl>^9 zQ(1_=l7UKP*xIhHt2~k+VIN&`_Kp0@ae^?@5=*3&+}5?E00bjE@=K37N^!^40zbSK ziKL?o&zNC{?^V^!$5SnP!wF+bou&AuBg|36%vL;432Ur*=JAW{^a;gMZLnU*quWpN zX~-Y?zht`MuK$+BE@N&YCcCqbNheyoWDX4$w}SW;sXWR6zF!-2p2U1!FrjT$c42H_hrh~V4H z-$@_$5;Es(6cWeF+vZf03Bn7qoZ~jT%~Lu~a`t1tI$|Uixud#*I(4I+T?FM)3c3J_ zyHY+;{yRfo-IW{uyOmBl@3+$81xC-P<3>-gcQ)^?$kbGLl;a{ItW2c!SkCW*o zh8M-8$Pwkx9!D-~H)DMIsw*mYDP7a&c56C?>-dh|e15H&V{m}0jPu;9v|S0tm4HZv zkZ01p!>i;KEnpfJ3<>gwaW8Ikzk=U;M`p1;b~78kkqi-@i3|U&cZs{!z0bqk3CfbT zSlYs(>=F#H{XQ}ld%;;21y0F^vqX29WgnMjS6MPRcDi9YDa~V8se4B6cf7wZzAaVR z_a^CpZB#Tk$&&g&=Z;Q;iF6?+!bytu_HH8Zgz@d7ylKWQQ0#Qy=Rs$Im;(r@L&;ud-PcWMUL+l*=)Za zO?>jDH-@o+Sv@Q`jjVWGZ^*rZm0ovGL@2Qf`aDh0YEW>A(NXPybDlPVVs21Pu-?eO4D#Jx^6 z<%QR8?y$Nt;LJIXurB5gkI}ZzVsCgM>M~G19K#z#5)@KR(!g+4EGFUv9%+T?qFK=< z9@Z7hAue8~>|-UWiPIPV{ACTsvMRY!G)g-}i#gXU581ug%z5<=NL?jxQ~#cdZQ$)% zZslk0gU^c-3yoZbc*S->g0X4p`cmj zHedE&|C*T{GxEkmHM#dy<4yAo$sut)wvQIiI=Y(Yf4q;2@n+HR*~itIUL@6>9Yxeq z5+aXv4!;pZJQpl;m3e(1D!86I;erN^0)A_V?z|K|gXT6o*CSH4g<JPq$@7%|+tnmaV52T5m| zo4_UR1KF|S?J0G{T0z&`PjEo@yYN-zIDv9=4$OydA+sO z=A6X-Wujt681)|o+Ltkym;BdzN|I^^!@1k%Bk>n*T|3*k(JS~iweBJMcAUj%B1@C! zWM2%11;G^6b7U*i7}+dEvA9ZXBiSVfitt!o{@aV86|p+K@Irxu3Z8R}y26&u(QF)@ z#90XxEAQ|1O(kW=jgcNu^-ZFNLL__$tZex?qFG2brRwB&&A{%s_hS za95%!ld?{JPQ2eFRNu1f~tTRFF9Ju&8IqGo(b0r^alQtq*v~jaD~m=F1Pjn>AJ`!ZbF+#X3ixqo*X4az61`wUBS&5GP*aiX94ba7>e0mW~_6 zCz0a2XwR6R@^i;e^oLfs?wU@~G-VNMGLxWCQfz9MxG-Ihl)`fQy zBJ=DNGu6bO@np9d7$LVfjYd8m-H^e~7%E}tB)fj6p44+C$mls~y^-2=-J+&7H&%t& z;Hk=02e;G_em}0uwUKp7(ecJv*-q!toiFsG>vVomDz^_C_T|Ir&TRV>J58^6h0pF> z^YmtVOw^LcL;Bjs2e(z*mByC*{QAkxJZ=4GjQ~Tl?ebXeE$#gkbV`f6K|yOmgNmYTK@)mZH z?)y@@xXl{4RNEe3ve#I26Bkelz3Wr4Eu%gMq68=J$XrVVp?xtUnTN$!mH+VY0Wmf{ zOOkzi^rT+WMLBVrPPWaimzn+Ji{-~k7_=qcTeH@GXadOjx>Td`48{=0B+{<2&lp8(&FtZQ` zj=ONnoPoqkY0vN0qNaY7^?}>#EqMibAE$EvKZ2;CY@DP^x7x5?@YyW!*bINe-|my+aN~}^^)6x|*|5#` zR|0GlF>NWJ%@?+_q9xcnDwt=r-wAUdg<&H(o!1Q^H+Yk^72&ocT-A#&me0rj*=h z5rG~XqZF-wF_wH|SdGoKndib z(tM^Z^@izNH|mzAx9Gnd)@*d|RZAveWwDZsyOL3G$)ixK0SvdA2xH%5!~~M+T8F0? zV-IQ+ocxEX`6Cw}%1gIN1=KX|h{&E{K=jkc##?wipa4u+ZQve7g}cADS%{H# z$y*!yklzpPbt_CY*5=3tBAZviE_2jYh@iblwNbD7wEq%AS^mz3YznyinwY6+ML?8` zlWd`bCCPhz4$m>P=J87jk&HD5h^%#D1f`*7JjvVF2q~?LvOOcmZ$wvYVaGbdD-9M@ zW{{5g%v`B|;-BwTKil%!K5?7Li9?$ceZW`kC5v_xOW!k{Jny*Bk5pq%n(Um@Mx4Mi zpPf4z_h}RQQm)LWguEl*9Um9m%Uh}dcb};U#M-=qlF>LtK@c!uUlATpw*H~GVu%h) zY)2#WwP2xgE%2`D326(LZ91g1+-_&(8+P;Zylb(~7|$o%dsHG}rngqMU87aAmN_jF ziC=vt7EQP}7GG|hGV2;EFV}eN<*dxy?#mAtkiIaglbWUn_(%^lVRK9tAQfl+hsscZ{(r00v!loz>pW3iY)vZaTPDu% z^o0hFA&iZQ+ESs(+wiFL;^`Y#O10pr=ZO!nQ5SnM?{gus7qrlIQ17SQVwDdh=Tg6- zmlp3j*?sX>^7(HPz=)?HP7_cX7d zBY%b|=PGZZ4ApaQtw=W9`&ZuiJ5yC`j?)8#N1Qbj=`0rJcX|CVA`@nQ_ zx&Io^JvM@Lo(puPIaqJSsn$MT9@l=K(9;^^$=w{sAg zy64`82R|I$k@t^Q4}yC%G-|sdqo43W$pQ3eHYoYjzLWKdr7iF zdU-=&>l_8LYYnDK>aD~XjgZR5xIzI^Hq?dObQ5emGPD|yK?|uN9Ij2KL;V=XrPS*! z6sD@n=Wlqr%H#HYF^pyFL9E{M=)j9dB6=N}otfa=E5(2{glKt28YYzgl1_DkN?F4# zQsqX4aYS9+?ZHB}as8b1+Y(Qn2{!cdAax<3>od(IJbgJjUcrq@MzcNf8a0a2;^vqU zGH@JBUA5T_LE1$-suDCV%&L6$=4*70#A#Kf1Twm`4|{`&Stw>Gt=C?p#D~e)SPiMVr~VBGBb_wR+!xVC@Kw)4P6i z3v-<8XByca#s6xqe){yjg3tbj}h?-whn-=o+2V; zx+P=vQGq~vF5iw*p@2ZZx1y!3pud8O0UW226IT^xl#-VKK6>f`wqb^RGWF=cO!50) z20oq2^zGBBOg}!I`se#uPIUiwI*i{w!3v>v0fdBv1WMF`W}WLFsM*P4==kvVqk|_~W%6_QF2F3%Y8W%kpyR_`A~-`7lu16xdO-{a ztBpn#fiJ19yiH`SP4zr$gh8N6k`q=ZrYReDo1GF)K0fyBmmtY;cInG5H-~6ywWRM= zFQ2`!4Kr%>d?atqwiVXns*|u`s#K09GJEBQRvL_29lf-OyiszL$-@YkPoEoMuqfqH z`8h6=8(y=K$o2{3Uwx~(G*dG7a&Dc8{}yYMfT|5 zool_KjTr}$5Fmz0B2S#2iiKxG#lY*NR^&~xI{!|cq&`w3n@ls1M7DAaBq?F^tVED3 zD}d3VK#-f*it=uER--GaAbQ)}UT*GQ=;XqxpH~${5GnH=`JgOP=82`7@AYHUkRXwY2`g`) zR`b*M(-$GJw|0}_nCtf*Sn%_rQoeRs?>uIbX7#uOD&{Nv&<+{9FRNpo!{aci&lvUI z(j}EOzl*D7`LOBY;!^##yBnd0HI0~rKKwmQ^#$KN*~!?C=<-{5VGNcAD7;0{2V-C6 z3HQU{XU;8ReB9?H>x~YdFWw@u=>CXq zbYLNRKh*bA)qAe9AFz$KD6k58LNwlXrq8LhCykRHaI6K`mPQX6PlRXuAAuBY9#j`|`-3}=D&iGEQk5@*K6ct-M) z9D|a+V#=9T@8HIOk5}6-F_DNfOsE!NvNwjU^;|;efg3vDkJMie$xyl}T9=N)~GvHa1Z%j&xDB?@Q_r?#qn> zkqDP{>5U9LZK;~Bv95Uee(nknkR8TDl!;3Ahu>}~Q0BgP$%}t-yMz$l$7PmpAtUM@ zmCVhxYyu6Mfm_Y|PtSC~Vhn}dlDyTpsnn<4SS+0PdY;72SLzKX`JCA0Ppq9u=H7T2 z&o!?V)m+x$C;2qa?a0|cK<0gSur%at9s9GXxj1rINivR5N7(w6S+u&Ve%P**v@<1S z9FeW_w?b24`qiw=0zW;|0vSZhZfd#Hs(D-II`YkNaWPQMS;1tQkfPr)w6}gJ6dnBb zCN`}9%zDp-0A`{0UQ(bbRL5oa(gE^ogzoq>hmFi~8xoGqln?^^pg3NF!+qDI%d z9u#d&HN|7Wdp8?8kUfVj%MW?jT^9>8mjVCy$zq}62*y=e3kNY%KE)J%j4TRkiZj#t z_HcwM`Yiv=M!^)t);Z_xTOoas^~MdL->2eq@?BdOHF!(H-zvKqukL0XGwZ{AC; z9cCpC2M64$S+#Osri;BiA1ho3Q_2dAN-@ZM{rv}OUJ+RwC%T)$RQgMk_BU&)W@eN# z9K^m@pMLMshh_pt3NivunksTB<9mut+e?RT~s8D01AOQ|0(F1>z`+7xM z^aPk2aw9z~?;=c0dloJx-$EOSak^RJs4-m3F8(1sq*GN)^&V<-0PRggM#Ek@)(Fo1 zRWy<5?!19;;r_8ccKk*)ezefnS@tp>k6y-hD$rv0W1_<;=I@**P^L8jTZLcL`A|%R zmXp25B1Zh2Gpvyb|FejtU5r`h!nR)+b;)($vEyrO)`?tgvliBuGzR8ExQC+)_Zv84 zvF{_$G~IUFs26&pGDgg+zaLHznsbd04S!jI)~y_I5SCA@hia)C^*upryYMCbm+zuC zOldMf;vkIX2RTo7SZJ&Ao+L^AB1%~YpJLUOWgOuL+Q>1L+eZGXUWEH z*XJ57^}_dE(ykQs_b~BJO*2PgnI)9mf(dV@47git35YVMa;6GSBOo+!M% zJASDd<_>GEm$w`_Y}>^NLVE`qp_Ce=&%O-4v(tnDM4%b!+ohDDIW zt>}iJyM5Nad%kd=0Dt@=efZ#96vjl{Zu@7NP^`Ci^{9zCyqXZ%YQwVT$#?1M3#vvu z&lmBa2W(t)K|?uj#YCy`_%-U<*(yIfZxK>feQfbJtOaqqCUCjPK7{TUcOSoIK;r7* zGGoso;;VNxzffrBy%8;qe%>=;4n97nqR-SgnM}}TDlQ=hDSTyzJ#C5Ei`RgalC)g5 z?xF3(wzn9(q(OZfBDqnQ5JtW&i61W3S#I1_8bdaH2Uy-OVd0tuFuaI{XZ&k@B^z17 zIX^zP!SjP@D<2=5PlV%KMUZE_<#5ovESoQw&UDx1EbzsvwT;x><|)FQ*f?cB$_*#) z9Xsx*Yv%VRgr}MiR0Uw>@IK)@$GrbkVHyUmXveU-MbeC75ZM_?4Rq9`)0GBGlODW1>v~2>n|D}%dM!Z~1pI!5`{vIX84?uM(r z&z!2P86WupqCnTSa8xYz^9xeX&WSw|0tdw)f1YF55m7N`pztVmYm|W__)LN`Yn=RbOqrF%swb$uQan zlj0N}j8yj+jEAV?)3Icqg4O~I!>qu_SR!(68jNZ8ke>U(d@L(%3%+HzUnRrxr8Td_ zIw3u%#fOIHQC?=u7UudZ6Lwkr5VByngl6*0#F)oZ^<5B9IMGY<*troy?$P*aFUd~GbT?q1<@6F1#w@lJB*Ia zuBTpGzuT67?(rur()m~GBe~j@<|vc-HXmklp4oVe$fc!FX=h%|EADecBWb#nn5`T^ zJk!0|u6&i0D?jS`%_lF0Dt%q~bu2o(MVY{lEMlb|M=*zcgecN%DZL3>-(zOlNP<|+&+>~6%AJMpp6KVIc0B4 zUs;SOPFLE1HAgtfbS3)i;DyIX4@GGQ%V6=O2zGkkf!a4dyr?rabLrSH=jj4NgL7e8f{)bdOaal~0y>DZ)Hk6Hcr|PEJ%`UXu%^CO396t!m&+1XJ&;EamO- zY16!@g4U~+jSVD3kG7GDpJ3FyO^Zl(CYs@mG+9!62H%VH7-QB8$F(OGsrAx3gNX#P zB@%-v0~uYWpv*oTmwt4G?YiLtzVNC0+T{o_;|>9`6t2SkE6d#2g~d^~ZnnLnN$obi zJ{q`ZyZ=J|94xOX zdc7lu(5S?pyd7bP5SFNA$TjKEIs$zNO)o1or^2*M)~18f?YvQc-(5j5KH?kA;O3(qrrna z;O+~=bWbauek#H8dD}*d6@iFJD#P*$>Dgyk&36?R%mN{|jO*{A@_J?7O#s#5!7BpLkrhy3b>|lc3Wngbb zum67Xo6^hRG%PVu2h?g@m>#jZCEC=j>x-A6rMY_JLogx zyOc6zdpT+t%Jf&pRpZ;U3a+9ZU)+Uf_k1>P=NO9UT@g2@xk1b*7JMgo%;Id2bmU}p zJ}XQQ_x0ut9jbM?H#WL4gwJ%nbIZo_{s$ZEz3%02G~ z$|sT!l8-*~y!CFuX!NOZu!=Ufj#Kv&)S%g%2|y)VJoj)!`Hgi$_< zQpV-hUvVs!JyWH|)+71~LFS&+m@;yUW6+)9hXxk8&N$0@g_YtmVRJKr(H{ zZ-vf~Ge~P^xDU_Vj*}oO9K#-yC0Nb>;_2aOTdz5~;M_G=an^RV{Hh3b_%@mCg(94q z^bkec8q^I!!oBm?GRofW(PM9io0N?-+FM64Qb}*;3skz1yqJ|-i+fX{fz@ft{9>2w z0}qPx(|%^0>N3$yPtyah9v(r#ow>@%FR^z&cHG#tNkeB#B0MLE9>_8|f<}T9W~{e) z|Bl88ZzPQ$o%}5e&sz$`37aX`#<_MoF;cC|IMNjzu@1soxXN?GI^aqj6)Pr_xzL7U zGE#U6S)=%`VmX(VehvpV`Rr~RdVxJLHa(dXh)0^vUXs*CJvtx!+IRmpn zps>MPy6EY3re1aG?Dkekbw*NfV^b z%%!G`8Xz;I2;aGb7=#ma?ndT?v;*xO=}*Zj7(gt9&%k&H!Dv5>qJ1iGa zu3)Qen3IHj_Dtk46?>F^Cv!1VfL@h)XooD(O0R&2#{i`8>;rl6I6{Q>?O6M`GC@(Q zT7LHDm$Z`E5?E`Udt2gW{oTmX`X4$!S$&Mz(hw8-tg=X@g*&aRC8iLL>Xx>X%lb-X zpIp8aLP=tDT6qnrQF}a70ON`&L4(gG-|)~pZ5dOWtY`0&;@R7!WEynWY<8E^vHgWy z=S4;f;Lu5PkWxG1qzkwivR@L8~^CRY^Lw*8#H^B9T-YD zLJ#Ba*%&3El+L7tTDfv8=9?iaH)FR77{cbZ$j~h4(Cnhh*ry)&-3XRlr^Ks}NN9oW zwsXZUYak^Q$Wg;EpVeKX6qwZJA4kG9FJ9SUPO|a4%;{_Kek;ktZ~P(^#`Tr^p;<}w z9a)5+qEW5v7w7K?nXbL6SBMFYd59YENFZB9!bm}36<%QJsf){&i)$ri)UIi>Y@J1L za7&uwEBsd}lpn1z%d}!{h92;pQ-SgLz>KezQ9;?PzihsXYmjnl{`36QK6T?Df_0oj zB}PC^O@}4t3e(vak~h!TqH9M7hCK>yMK%fWw?9ai5y)t;8bN25$wY%iuP==+t#b43 zs(B&VRzHz#bRWi%wAol8T3&RyV1(vXO3K;gg~iG|%g)(E%X(g}$Md^=@TQ)oCBBU| z&YSNq7M$g>m6M*8f5O_8*0o0lA}0NEX2qgG-6)BU<{~YFD)JtY$@nEMdk6W8!wdUi z3z+D7I4lMO=ng``a>^*UFP)X@c-*a~u3r$==(S$Z#_eM0?BBR=vIw&t`VD_9I>2Nai*EM{`PD38c@M6Tw3Q#tI|UD18qcN#htn z+M@oq&u-(Ij8@NKQ%5P9gslXBiePvPdiCB_rWnqL;WPP$)m^W^d^J<6xM5X4lWw$S zJf8_!$pNr8F8@1sn_zrU>-x&8jTpm$ckl#W*9dj*<`24DUzQy>P8^&tfOBZkY(8 zFC(ut_G{oF8O@45FJ$&Y6f=X#h6Fcg=DxV03D+k*m!-;9o+|%gsy?QG_=pdvG>Q(q1=x zjgF$mSRj`^a+_B0bM!TsE5j|h<5$hkMPXIbv@Y_azjjbbzqLiTdr?L4jec~7iJn;* zTkOO4%jz^wlqQ!$2{}ZI-w()mzTwhJVwZcE`B;-T=E?aoM9@8x+4YjybWMtqcNsGr z-k9)JhDu<66Pw$*Rn+FAz~k%Mj>U2>bI#Dbe@eHrCV*#H+8y_ePb@Fcg&?kvtKFktmyxm7+gvA0}%W{%EusowLUZ5i7Q zKdG~tX<1Flk%}4I7hc*@`&eJ#WWvt}_RG?AMpsANfVb&`O8o>S6XQio8C|&YuRrvt zrFre9cLB#HP$75Pw&{MEj&X-|>q65gqg`G9nz_F9y#Ws{aAYyU-WP?jQD^<`32^H;qIudn8GrTy)`QiX2>ko z!Hu(fFLvc{vEl<9(JrlxK4W~?SYJ76Y>cKJo9LcKj;O>pbXVcg>vs$9#qTsE(lnG* z4XSY~`*_S!@As#=&=;-+NrhLfRk< zSC})OC5_QD7GN9cflduO^_XK{5GBB_g;Eo~t(mdMKK4C#LD-YHJKd zctPnr?lTv@F!qx^1&GzwxJx)y6(bmKo zN*{*_L+hjQbcFw^kBdK){ng2^fcQR6A4XQrj!s|)a~tT;JIpd06jAk)69u~%SUDSf zeG$lUMx=(KpZOR1#^#Pr1~x|EW3>#Klz+P*Ubk=@Ndp@LD|bh8$7AV1tAG~BrhnAy zPkP4YCMIA9u#J=X-&Mf$gWa!ob3YM%a~mhHsl(rCvqRBtIyG%m182wMwF4c6xIn7@ zyLL>RZH)fv8PICcKM`R&TPt@PTWfOztK*rbgHp?r6VZ0GwQ>PF98VWIz(1XcF2s}$ z0ONl*CJ7YRB522`8VHl)b3Syk@cApPuUrBl4HYRPhw?piaccZ4Q3nGX%fBTcS}36r z(f=m&3G><|D6;Z@C2MZ;HJ<;HdZ7I(@~>2lY#kiHC$Ky;-Lb#YH3mBxIhX^lVRAV> zRWd_qf$Hqvl>1-05aU64!||oV{#3*rovp169Ndqk&kDtS{i*0%+gbz3`B?JMj)w^x z*7{>&`xpeHedsXW2r$$T-0&YAhpxM+z@CZ{=y-2 z;vGIQO%rn`r@uurIh6F&n8zp;Xp8Nvz;00DA8s&-p~x8@N6yyx_)vh>Wb)rg+1T1R zIsruzQ90pNsV=k{vZN78UQ*xY?H%EB>TbS*Z#x& zIGRAr8`~b=<3dx*I*yv1gSj>MczH>oczbsoHCrIv9nTuH@+i(7r@XJkjtIbahZeKY zS;FM+Gy%ssg6v_>VS$o6?=)mxz(!8C$7c;5DC#@^K;6Q?$kx!@;P_MrErc?#82@7i z{bsyhx^V>F8u*vg2Q5U(KTro6Xk+ugl>u%jU2XjXj13Tp4(2XUnc{E^LKk>BV3Xx9 zs&ck5cQJ4PRu{)-HA*P%qmHBd>&1=7l`rVNY2ai8|GIRAE(=81$B2Jal{u_U=nAHD z5^`2x14k!EduIcnhC^BEaAZQ4oUG$$8=Kf2OA30SI&~Z=69WS!?Ia@(9d6*~zl!MQnh$z^`$ja97a9KQ@ z*`X=3;2xvRpW-{(nE{~=J_$0;fQw(EA-L!rsHos#@-yJN@e1rOLp|6{89 zsTZ)bk(IeI_%HS1GL&8nPf6Ly%mMtDjXh}16rC2}Z`+-mQ2fIJd&j5I%vZbq=I_TF zSN)V2zZv&1d1fdP9-WB1odNJJU&yNBa6}y@4qdU=PEQzv2#zts z*S5plU8RCUh*>o|yIt z8y9HSYfenw6l? z6#ZWoAtU6OE4(UluprP9Fzc58$shy)SMsC?@?fANaImD32WGgoHd4lrVUmeC*g+K7 z7c&4xKei6PV?(5SFPSeG1z;8eKLIH03F(t!OMnfWoE^YYHbAxg`uhGqV1>3P3MT*< zgTU|CLK!0Gq|8aN)a;CbRjlyW<<0LBLA0s67DO@y82cO?2zZ+3*H!F4EqhXwZ(5{M z0orqjKwm4qqJyoQ`_Yg}AtXqmfB`=OkP^QT0l~NxP7e9afG5F(7!D>Am7fj3Oaz=p z5DIfe>7;8>0vJd;CF%96%au`uVQ~ryHm07wWz4t+SvlT zcXnpxM&b?*whofOYyi#(KTLAJ7kVJqS`130EH*q;VIFS0q44e$q%^jV8 zrjny^gG|~ZoB=aKrU^hk{CO4oSG%4bSIq{J|Bc1IpMj7w0LD3PM+4KHJI@vc2)h6n zUG66=#NfHUrw4|7!v(UwlQ6ddb~34c{Oi%s$q4?Ml>p=c@Pp2rmHwxP26TM_JqIS! z+%N$`DhJTD7?ik+H%^cFL%wg~9xWv(soBIBaA#v+#tm)RhQQM!s#x3FI++2c1>EW{ zt}OTRdVM~SvjUD|z&%>KwQ3C_TnHf0D?q#aP@tsICk6ew)$zSJ0fAy;dNdRa^IpjZAX4}N_fdp` zs!#l9s1sMfLOl!QRRDbv&@i-i8B$J){(G+`0qhmqI=EA@9WAnvF84)aATb02{tF!~ z_tQ=a`t_)rjI9}K7x`%TiP;7RN?coR@Vfcv)Z^50Ug6+97PJKNR1mgst=%0Qwey zuJTiKNG_JoITiZfg#Qx*<(H7e;{f1V;0NtwGta0-G1m(M9>} zRJh-x>-gmnq>X+SoPQhQ-gkd@?`As%htzho1BmR3`7Ag*hHYy#cbZC9NN{cB?f z6bMIi6?0Q-TXSPEu#tiLk03i**`|Yd_j3W!a{$qy*V$Edrw12zvxDR_$ddO2*t8+f zA`}5^TtIMW?CHi+VIQmZqvbZIxH7{4U{3>bivte+<0|%l+I&*%A3GRSiU#Hm-wLIe zt+SyO_-M$bd!=I#FS`doLT3^Awv$5sxl|pIJ0UB7ffpXe*}w`BnFa*}U5Q`ywJTa1t959P?R0NP9 zzn_Ry;?{Of?%)4a1=wE)4p|?uK?Gq#`?`gDAi#zPz{an+AA}9T^%Jx46Zm(fLNEyW zk)?3~3>F~dB%nm4-8?bIpF}+(;vf$DiGrI>8^GiP92VHB{CO4o7k@r6<{?8;DcSRQwwefMD6c4_b}WbSFmqE|tNNr4NF#y&Gwi4=i6M0S|>v zZbS4ZM*$iO2cWC@j`q7ekT~FNE>(5}T!IFuc~VdY`^b1=Bspg*C-YOO5oX}h0i>0A z1wca&L`K+74126#FVxLkivblbLQ)HqU|}4`Bm8{iNBqYbk{=sjN2@UBfSbDF|- zQV!P%kwneFhVG7LV3*^O^xu1_Rsl#$zae$2Vd;_Q0s_N1=>3()|Q@j_XuQs9JGKLCIt>j+Gdj<(Z6 z0QsyDAk%w5CSYv$^D6fLBzQs`Q3D%8u!Doa54@v+FaQz^B!*w7cObg!mpnbl<)gF*Nqg~= zV~!UA7_;ACyk$-g!+8`8#7K_uWuQ2~IKa9TBm`w7RQZ#@{4&kAz4sp~{9ShtwDEl8 zclQC50^kQ7Naqz!f~E?b8UA*{_jsJdRwdnc0LBBr$Dtb-bj6e4i2Zt05vYK_Wc)KK z#ALS=r;8w?G;yH+g?2wPrIVokp#IJMxPMn61O!F3kdzt#sRDc)y1dJ%o*snt2o#8+ z-c*5n8vzAECKe*V@5fc_KcIdRl&|&nyQ$Q_9=`t}+|g1^*Umf}1w7pu*usaF3R&|c zct5CrPe@!xqjZa5rAq+1WBx5aNb8;+h39CH;B4MiJOIS=Hv?_xogRdh{b-bU7Un?| zAbU>(z6Kphj)wn$!uh9-@jK!^_-jBEjr~?B-hoe#^9Q@Y>J|h`002|J3BzZ0dJtCb zqmmsYcD^KEDRu<*A#o`{AdVj{4g6W`zi4@CoTKgXY7Pnc4iRuzLFe%Lw9fG)5QiU< zRsqhnID)T!e=6g5Oh~Z8Y?ZB50Akz#>~tMUtcJV)g83`oLFe@UWW^&-+CX?Y_(1V& z1PJ71VCi^hE8_mY@B$1R&7HtMkbxEJkAH+bMQ-arb@^zO3=}6e?*blW1ngl!vtb_n z|AUPqb`BugFjtHnSp_Vz3s^=I$};cc|AmcTmidnwfC}{^{r#>Ch}(M)PZlQu83_pp zFX(D$l=v@P{P4!(QPUo_6m z7gRCGV@klJ-vtcpeK{LJPJmHCM$*854>)KFc2F?10Lt6%dWZ1RAN&4b53u?!Pt;>Vx1WCudJPzQ*AE?35 zM{w|#|Am_)obag94}rdM&Y}^b2rK{|Iu;p$!v=rc()_vNHU70C`1-K;FLV6I3_vD6 zi5e*Vb2iA3fK?Fg;Ujm&K&y3nUj9-ekB-ZBG_4yp-MjtCGr>I7*AW3!2S5Sp zP$BAe<|L^9eeI1D@T|huVkHX(o~$r-0AGc?t48Yki*bN<>4-iBk~D9Ayjv3kc;q?E z!$}hkVD0Y)_%9FNUXSyG0ZHK0ts?MHjydEd5X#O#tMct2&e2ZU=d;&T2&|j#0Vg7% z_j)NY|BVk314r<&un_TYeGq1U1sGi(=oV$6Odx~vZ?KYJ2Wy~j{VVb%TZ)EhK;XjP zhCC06{|)(v;*W)fWJFa=lsAygZC+qs9r^^&Ct#-iFE&5qY{yzUI>JbC73k3(0i{40 zO68)o|AwyOZvAby@DLkEd)hv3XQMtKJszNVXiqC<{5Sj)!8RfiNIe8RjTBHiaHjm{ zRqP)M9CJUN(*G9hzY7lW^$#9*n`i-#gS-Pw{3kwS4V=z%S`L(Lt%1#E(_i`JXvpLc zxd(oLu91I(6cjuyq>8z`S2^%_O*m%Ep(xka_&dE6^@b>!m*Z0q^ z>wKPDpZjrJ^`1IYDYD2wW}WzU-KOVI>}HsjC+DSFB@~CM3q`48)y}Ik@#v{uH?Z4F zBYus!v^g|c9wEc0%k}-#Q$!|$$W!+oj2VL610HYi>$K(3 zpadeVNSl!2!mUhbv8D8ta`L4aHagfDpA8>j>lZM)gfkM4)UW_NLog_j+?#Sd0O#pSf%esHiV3}RZGuq%h( zBXl?(jS;$he^Sg)RfM+2m^$&|jOu+qnn;S`;P5Ht?88+t{Ioi~5JC3X*eL$LFGxuc zgCjPLP=|;xN!UWOBc`4gqJ#G$^+F(@w*Zh4VptKAaU2sRoV^4E$MhrC6@W&3PZ6bhHxLI&yT zM8%7@>cPog;g_4F8zze6`*VA42}_KybmZcg5(}FATN{=?j{zPJnHTfbVRVK_al}5q zc3oFNTR*^~eV8|oS*8jBZRyO|fNb0RAjFYzEw6;2pDF4<%> zk4C=Vjf0q*P>A_6cHA0OY!VeW21d#fPc9$dHwZ3L9t!69D0YJ?A{^e3C~+ck&XfMX zi|5sXo76%2OXbzV9gUNyM+kCvzHcpTn_7f8VN-9f zE~F2zMCIb1gV6}@%sf;47irma^0coD@%xn`tHlB7=FeC2{DR?wqA}6haRON3Kt{% zswzaF-Y8XC{upd{Af6NdyQYc(lZzYt+Ofe+f<>cn;SE)UV2#89`4Rd0<`wTb+G2J| zh1ZHc0_j{jeC_aiT z_dpfG2iGl1xa|ERA$7#d;={kIVpwK=;`I`})6{C`b2LO$@Bv5tDyKqipDrq4Al+cCD5UIJV#l|$C3*lt74>%h-53$=Dv@w zhzoTJJ(&ujPz1$Etjg)DG}%Z=MOZDyzfi@X94{V`b62!6ra)(JFp}isue`5SA#A0* zIA;IIjOSNjv_cOX@exDy_o^_qk+-aUo|SJnQe1a_9vRfwhn!AasBY^$?usMsrB{bQ zA`nMx4%lF(;toqvPF>f?OzIHu0Ey|n(8_C$&A=#bD}MPglm=OpFdQeBUDsX_Z7XfL z0cmL6kEfe@S(T7%Ur(JAm5}Fb?HNa=K^C0jcXH_g*f1*}nZEK{%qgqQIp|&EU+TwD z=y72TIh0_Wgb|q^p|iMmns!@H!q7PizRmY!E+v$-bqyO&=xCHb@A*IXxC+K7NW}B! zk=#l+p<0bTP^Z;LDFKrD@)oSNpC)}0;0t{IB2Qi=K=!Il+6y;U*RXCCY@?Ov_A=Z% zR)N?aNPL0#WBW--PR4a=@*d)nEwT%?^(RN>Rmuof{)8aQwXTx0-Ru5)(LWES)^+eWzQf{1UH4mLvwK?&t`;-IXvHm0Rv1}f zUHd7p!c&12^v&Jpr&>W`Nzt&p_V|mCd2CVVI>Y$or!vLuUZhUMV(JE}38dWC>Qjkg z`_w3xbo{Am9zSUIU*t~gs5B$sRJKGSAd+0yFXzV3yvGtHx!K;(Pv+{dRHR^qtJ zNw2<}#7l?n9h5L_!llNrNRlR(&A#f&-+w@z>tImcDJ=?9Lg9NmH$%24<;Ze6c5_ zA14Nv6*hQnqxG}k1G$GSr^md^ow?nkEK z^TJmKsUfx3#^BU-f-4njh79aC1Smaxm2VhpH$)A}S%sd#T63(_g|kIg4fMmJjK?uR zeQid=-<0GQ!#)WrF`;lEIe74QupDi=QLveNyTqADKS)%aS9IMF)fC&m>D6 zrG`Z6OiMaaMDmp_L4)-}A=i)jobLmO8KZ`X!X^<1=(SQTlCI9nkGczxif%gKu^uu- z4J%DD9`#aelC$T$UTg2dXL3STzTt1tR5fhd&bRjV!IKn~ByKpW;;?Oy_6_XGsjt3u zhngn26qRJXV$MGNCSpGmwi@#IFE>jKHB=Xc6z($q{Z}>W^AN)A2Fi~)Y+oEDlka{L zQeQ%~hDIo^;l(ahDcMM)HS~cK#>0*Qg3j^CVl_Y?y&kJ8Q9vb97b)x<3HEJDjVnHo zt~hGrPE5Kz%T&Px+a;Ad?vxi1cTh!n?1hGT8DV3Ko|Gb!o8{R#Uxht^>-)s*DXAz5M4N05b%x+UKE?>l?yLF;*@GZwYATCmOu-x zpam^h3x0a7rUk9^m_|10Toyh z6FqnHZsqq?0_Zu@AD;&t3 z)wdy77iltD9{SYc0U^2(149u<8;CW7B5u+d-Nr#EbHY#)bYabiE2X{}sXp&)2fCd; z^$d!zOdw@s8htzOAdIIg<2YLcYem1R>RVxbxdPC%szIV*Qkh`vU;8R`A>+V7cqT}w zqrN@uv;%M~0uNWoWrF6_R|h~|k8j`;flLj)_0?mM{wx_tTJ_`r+IH>t-v=)frfzu; zeyg#1rb<0$nb&giW>ii&Q8@)MfxW%e!`m9Q*0c7m^KHP4ulME7hU&h6^W;%QDQ5WIOo=iIfpzk0A@&z{g?YQuH#>|IFX+|;dysK+|= zXK6YY%hu%HM_(Pu{|{9C1<>)#z2k>}CbWaOJssK>mS~FBL}~-{+BmFEiT7;_Y7J?U zy)X(5gL9#kZlwCw*^+viRvelpYyhd}*BMK8MIhh&hv_I@?M$4jz5x!>t7t>>3)kLt zgo!o^5`k%%`ZkDWAWw;v>+79M6gdKH2UIzonRocCRF8HLU%b!~x51)ntE*AZPFGLx zDZvSNCPaP!rL)%#sO!9JPM~D>(aV48gw28GPob3IyW}*}ODCfK9=|l4gTWlO z7CM!d-dog@(}-|*2P=5umJ_X+ZiExpe0+xahx4HoG)uwjn_k#=t5$yd-b7_1%2g%i ztX&7QcgN6<&rtlmO+DQ8Kto*o*|R(U_&2?qKQdzlD*JW$lL+SJ| z9Pbc@?@><{4|$PY7S#8Dm1k5z^7(P_c|MKM8gCn@wRxJT-1F-Ci>rL-yy&sn(E*=C zzUA~j2i4Pgtf#d_Ozk9l^*pWn8DQ*%ke|EUA1Bn)(|BBVYt)I$-|$%9q+EqOJO=5V zN48f^sc(Ul{4TpaQpB5VNvoS8-R95feDQ=HFBGYD0$VfE6e4AS|E{*Vcpcmt%Dq5(|~QPS^sLyx0ioK$I}^>2w+z5`sg;=1{F$6$a7O?d(j56Y(Vm< zl&>;mQtfbZhL>``i8Ze-#5*b;o@fcT_lnHwTj6-NAkFq-Y^pRztmyYD7F^+QuS!<+ zY;k)_tZmiq+H5`UlkxZ(DZeqZca9uN&^FVi?oX7U7@D;hgM(QfM`2<<4}L3`8x+w; z0mzl^UFmrV*MoZe0uOG)q^XT5Df!&RrI9F%S7yr`iK}ots5s_FkCF?hhcuCzVO(AN ztno0(0C{|wES(E0!8p30lC_Fv&peiA0E^CJ^Essncok1lceohG?4_eJ8;>M;`C>UH z4o~jk#++!}pMs6w7VpP@5|4fThRc8Byq3pexStObGD9)NP@fo+7Pm3@8L_#+HE!LY zGyP@(2Rk`UBk4*i#4-4!Z9f&FPxS!^E6O4;+Jol zn2SdkT#JYE1^rN8c!gU3`sicuoV+1?nWwUv_E;WajsMxP24 z>W?Iv_h;w&qhPSy&>zqAQC}$Kbku1RTtB7v-}p=q>7|O(a6vv%8{(~$!lm(qGp0U{ zhPN%nWt&*FVw=6G&d9Bm!_Q5sNKZyuEM>kuVK_+Xp+(-q)D2WlYUf&s>)Ldmwgod! z88Q9Em&XgYl7mF1J!I$fa-UFj6vw;E9lgC30<}Tc+?|D0{ZJJwi6_bwKEg;1$vk<> zqBZcELnyj=LWvJo(U7#4#VqfiN<64Xz^8+=v@HV3n+sfZd^Z(9Daj=qC|#YZKlT8% zH5{ll(|3`cDyUAjm4B6S+@ic4)N(=FeErWa5B|c!?ukk`N6i@Lv2Dq97ZhmH_D@9lC329I)KvDHe~;dT1OAL6fhU-v z6XiawGo)@+@WO+4hR(4%vq75_-Vqg;Pz(yQ@a16-a51|Fw$D5Dq!H7VvuuSWail8d zKHn@WGz{*2p}cc${&|LS5)mZo9#Y+-{nLK#4@ikp&aW7+MG@=TDru_gD6TI8yl*+` z$T&=c?Zm_bA6^Vys~iww(00}&`524?MCNzNEKPqs`^^rxfL2f^>Qj_s9L*v$KZ*0~ zr+4$`L7d3^&ib10gK|!gxV}h`s77(s?xM2pi%{W-ZS-N~02GFi#z80zanG7IiV7)l zB8fDj%i@e(5&SQZPI*st4STeex`2-!VYc)1PJz`ySCV%hy@5_Scky+8Fh5M%28<0by}E6I@Ul z`1b6CqT7($Xy%1W7Kc03l&aFf*`;zr@1;3kRe;TCx-HeQANb5Z>=8NP3#Loe#lVPH=V`Fb5FmT z9SN!l+ueANzP5xKvK(jK-y@?+Ax~w7PI*u#R#3x99m~2_DFyZ9gDK~5>!b(0-w?o5 znxUo|U>m%bq0#Fdfnq^GRt%foVurW1rqTk zq66M?ACJ-|M4EK*^d6U&?I2K?O^s;_loa@un?;4>Tfl_EUt;EixOWNo`|P^R2U-35E*O2&C`Q%{?2OuG<}Gpi=UY}{4zvs z2p>RkVE;);HuqM8?ySYTI%aKD0Ot7;ExnMCN3quWL&K$Xkz5>s0Am#YPOqJZu{?laPxh-*IV z-Jb1>p!ut)0(i~+bb@Mnur^BaKKaRy7In!FF$ z^ZD*E(^b5>(ZYV~DlQByi z$g)L+<)4lg`VRF#(^CfjDz4N58&oqTFLZ6Zc58zuD77w@M0mkbaI0#Hlu{*zZRg8; z?Mnki?D=)d3@`9b8;@qCzg!GE{|vxtW~ zf<d-^X4j{yc})^>NYiiL!%%Pz@mnDM67FM zdRY|GRe*HdS@s0G0qYp6Gf74uIg7c=oIbRpCo2TxvxNSkZtxtlny0@GPhv}7*X2{a zda2#;(>c&9&u^x1H_$;^BpNf0V~e{E3HwL0QZH#uZz<9ZzYbt=cQwQ?hbd7vX6_0s zN<23fHV(v`3ZJ=aqH(tw{%K1Ft|ksCQg2VpyYw3JP<_J9f6RL399MRw{s*CA2|BF6=^4$jvQPr09`Df7;f_exV+03i zNZT-V+%|o?yy*i$@koo)X}@hFRdB=OqtKt=oMEEgtWzxX7l&rG907O=;9ThGqg23y zjZs=Xmb4>vxM~cX;_U_SNY$$`Id{qh=^r9?A57@HGeK~lA3Ro~*$6>M=Sq^GAbhaW5 z#g0M6+^pM=sDK8k@nuSep(Fl?%!|V8Cv*wk%&hy5tKg=I7phHwKa2G4M5{UB>(g{w zd<*opyp(8hL5`NT;+(qWnXW3t`Z%By75eBhoWvXpY)*I%#5hI3aNJG32*F2DC&^>6@GTJi?q9kYo3}#bOD{OTV zmx@&Q>&9o7Um*T#!CCkgkFWofC)&b~$kuZ%o)VLMEAK5U1ra=c%H_Nh@#bIh9GqnI z*J)ym294gO4k@#=&@0{(a;*HvfRhEU8we_BmRxUX2m;JUpU@I6Hi+2zi*V-Wb`> z;_%iO7I%w*UvHW4Gdln0Sj^({2Q_CYU?@wslp{=WUF$|rb`o?TJ(tRZL@Xq+Iyd@< zTfHtI1Kz=2W`6jm@(Ov5wLg^ATJ;L6zx@bd3ZtjuX`=T!c}S|0TRU8AHnR>ptQjI; zfaGO6lc#z&H^WT-RdlYIE^Ls8+I&x#o5UUCM#h1Acfix}bcfT*^|piZG(jBu#o|F9 zS5ZvSg;&outp_t7n7kUjeOR8^&S+?F>5Kwic7%OXK7vHW>))Ra3}z*q~V z@hnyPzC1@X(1Ze!s;+!n{(2sGUl*v0AG(?RhdfAF6uR<)1Ku+|PeQ0jbp3UhS+e~t z&vKcgXpAtnc!3=$`0U^Kw#q>mmDGH&B(~*NQN|7+knXu{#+jBROO1B z#y_OiHM&MNV=?FVeY?MvN7#l1uKGgFmYsWVqw)Qag80ZSBvUroGS=F4xGKZQD!0GR z6+R2!zl*5h4)$$kc?MFPbs5(xhKu@vScZ*zo^^py_CjMQE$u%k$uqOcv(h9HyM~ay z-~CGQvx6bWa1>pE_OH`c$l$#4-?xh3ufrN3O~M8165=%G$XFLLk)y?b_4?*)FyA0> zcFX?WUl9DNszFh=E$)MA||fWYR>@Lw-UCY0;cDQ_LnT8&^OF#67)UIeAE0ZlDMH zG$IUAUH2;`t{j19Oaq4(VnH<(Fr3HNLP5v{D=nzibPHVX5B%~Z*T0?uhhgjcr#dwoe&n;6rT9cT8$nDC!`nYHV%7j`d7;8g=wx5*b^O!l1 z^Mthc5z0a4?>X=Btbg&zE3k{V?bG<1l6p zA7r;6<_g_#6kRUoqz=d(bSax0NRzil_tf4-a`+CXnRublXreqc&AVL{3JnwThOUAV zKR~zuCfJaf@(e2JwEAeDsJ?W|g~9><^xX>^uPy4~@c=Q!C#+}8mPZOFL&e>GY@xG1 zlgkfWO+z+aBL{GN@-{w7c z2E6U8Tw6k0P(B#*xElS}o+)?kQAF{+Y{?Juw6qGxp*Ir;MU0A? zHWy;iCL=yySmTU5$hH7&O}{dUsmind*K$L98f5sEER1TOlSd(poL7PsQHy?axav62 z4&j%Nc2h3OQ_~iJr0PUUh0C5E-b^=I=0e)#jHQ?484k6Li#3F8S++kbjhG#Px|h$2 zm%Jj+5Dsr8J7bF8jXlCf)4bjdc!oFr+I~`!SKpS0IXIo{gaoNCU*QQ03qXCeY1Q9` z!rzqS+;`<^4(hAx8E%NfgND&MO@!XM15)Vq6wILqetsoB7W($SJW)Z$ASLdPAGhf$ z#M%dc=P|tIfjmSc1xn3XCiVKVdscwxu4`|mzrX&F2Z`435?fZtS{ZjoKK%`pui+b> zjHda^1?&O6@#y3L;I_GC1U!Af4ixglmB5>!wYZz&ATHo3$?qu`uIE?KuzD&9eRg}U442jq?k7+Hu z)|(cW!Wbmp;j$-gd4g983++4xKh{;svn5`6Um^P)JwNlWk+5HH5Pg`0Gn*?VA_lE* z8@LvbaOH;A3%P?SfC(6nb9WgNpcIG0Uvv&ZnS8;Ak_UW`kz^r6eJdv4)iz3jf_q8j zdpZFj7z$&0Gwl0LO0i*@s3^VGa#1!S1g9^M&V_D6TD?736GLxrjRuX6EpPNx zO7qp4HI8z5`o(GuG4!ut8agT@vdx~*4gdIYXcEG)9?CjCfVmUtE?Qj37AGeU90ehL zv4F-^dbpobQaepQO^hZEJA_?DBFW|RL(rtJKszevn|Ab9O0!*Z?3zY#|FKK8H**n% z%b>*|<}S+yDy7-tKJ|ii*H9AiLxk~%ndpAE!D|8;bkhi>(9~E|#3VrziZ)3f4<-&S zcywdTU89sTyXoSi9i{W6e+bpuAK}KS5DFESZo75N9nX5`9$#TqCyKRW^LVB0h}N0u z%%b(AW@-m*&4Z~uH=>s2O07p$@Z^hbu*9KxvPPpSBX`g&TNHvx&ssEK?*F?*p7fj} z))Rz*M>fmz_ITME)Z=1thlhB-g-ToIY%?K=bg(_^!wJ73=uRNSdEt_7rBYIRO+utx z9YIn(t^a#1TovuH06h_Bg`rARR!8`05+h@i9DPw-uB(?T@1Sb%BsAEB*>=xnrK~{L z7!v9Bt~Y-U$2eqFdgsz;?k=SmMUhOlsyKaMkweHFL73&?6ECB7D}@DVaEGjGxd?UK zqvhjYkuX-Fk*|W$0}NBu@c$r#7ev-Wf^|)+9>lGrCj?}1g^y-^Tk|0 zc)KrZhFS1P?j@5iD#dkljUjD@4M{gB54>bLep}jgNwXEbe^rWc)TXjJtV%E6Ok-g~ zIs(JP?f!M8RHb&?SFdZgn{drBf|~Ej1Es9As$FqJME|^e>N?o(E&3HcSg83_DHexC zQ`gqy4H>-QRTv$({TAhI2WH5Yua)vd#+XXA++bUw7ZjCmVNqT_40xv$j|U8}rO9?% zhrGx?#C$dX5z2>xsLHq(9m$weVbTstjEm69jQuE122cNb3tr9i$PO0o_DW}0%4(|} zAk#fi;J?lEILA>$V?P*^lfKELl%y;Q%S@ZDuLha2!DYCMZqKKbWPc7qW;{zeocGg{ zO2r{nGlWHZ=A!KjE9KehT6H;x^!i*My8;tQ9$yu6_Rv3yDW#|70eKA*GsC!u2%2?X z52<-ngjH0^v`Oqtlv>(ZdU(X?E$H(D&{x%CT3%7v1(Obn>$QWt=<)#kmDr$U>3}OX z8;L^2<3kDOZL2$~DF;aHwA!q^=SGB{PJz9$FUPsvKn&|!7@iHrKMXNYYy;- zhC09_xR$OpQh*3G8qEnI(HQWUB_2n5-s-@xF))37n4Tx6;a?~Kq?*AhLtD+@q?Sf~ zl-RJF^tE+%@3~V^4jHRq;|(*p=}YA-VYN!%Zc+Nmv*U257N}UcqIz{u{%wi*a&o8K z$LF=%4J(wx)}%VD@#8uw0Cd3p?|1=6bT)*h<9l`X{q8R8FkO&Nm-lw@dE5fy6>jKf zFb*_e@>7EYIa-s86+t2`TVLtv1_+Q2H14%eG%_UXJ_U{SE`vyIf|%EmF)rpg(GscI z!&t$25ym4@24P8<31)4)#T1q@#>HhCr5;Ur@(NwUBTPYfGouVP%76?s>#vKB_VS6+ z#3jhm$OW?L9tRFXFk)kqQ%7{utd!OgF9K-dTH+0p2K8M@N4(&6yX&k0D+@|O-tnCr ztdwVwE*Ou+nvDiI-pSA(CQLvH`W7+DyMYIzl=A%PAd?}gy-A1Xa2q$MC&yg**SZ-; z;qzs|)qEfSG^ses>JMxd4SNUt#!up;BNFZak8OQG73dIO(VA81U_^kRT&1R)o$M{nOeSQ92(Qzmvau;{r zOxAU`Qm92%3{j#IblS*%E)PSHoD0HA?$3fjiWlbj0+^iPKPyGrZ5f7KO0i*zH{u~I zsoho!=KRq6M@Sjt>8#o_XOtoxQ;j0kW~-DX`8nh}h@Obcnf|&`s0HMki1V&mlVt}E zE=(SP$GAmi{>gJ^r4-S83rm{3oaYf@ZYV|KL}*NmZ=xRem`29p$rY_hF88cHc&IEr z{jmmvY(D6X|5qv1g?2qHFPcS48dtaG@ll++_Q;R!nCJC8A64Nk%2wu3-^We(r#EV` zkAiuHu~~CT*Tz)O*n8%-iFhZ_q>T4fNXB@)+UGF{{U!IM&UuycSl=bzJy&g3AQv4h zErmSK_k6A>tQ1LMD(5{BU(Xr&C%k7m)^mMWI`Ao`lw(z;qNvO_aOXO@GkrTUPzb}# zEvppgr`O;@NK9#mCK_V2Z4%8`kW-Y0is)*+T?=?gxN9p0A5&2&yko3MtHs`{SbAkr z8TQe{m**mYr8WAt4EtR*rC7%RO*5%nY+iUiw(FOmRz{q(VdQVTl#-qNR+-4pY7{Dk zjTIgzDmrKU=8cqs9lS~z^yIj@xyvF-cc8*-$D}>rs}w5YTe5ylslRBiVqZUoz|V>} zr~aNTm9hgc3l|lICsXZion~p_xRm>d{N|CgZpgK-9y5vQoy-?^&X)V3>#bCOQbkTz*BXu)J=ZXb+zwH+)M7U z5ycFTq}k(@GFhTjq3AakcD?M0VN|}F&O0~SO;^emMv@{`PZ{ykl)o^uFsz)jjVmov zigs4DESU6N{mg@A?~%1Gm3QtT#&1*#c6KghIkT$Yxhjc>YzL(@=6wfT?~GZp#m?pN)1(%XNhpie)Rmb?9- z6v^_0E4@;nlzFv2-9W(Bz+L&e(EW!>f!4ah6^ShPpVyG)tD();Wt~^pk33dNvUIKX zk-0^qvcvP=!q&yn^HE`tl24i6f2Wjd3rJTok~Vif{JLgkcxekv0dg;``kzu(+N_l_ zFV*^0&hrt>ESTx$1;pVDxfKrGZ1Pz&sth~ma#)R#=tW0i2FsgyYSZjWv1tJ*r`WCC zdlVf4AwOWe*pktz7gS1foJ&$BW8VvX1Dc>0$%_(&PXv@Ku9WKBi>OfXYmYkdO(66m zsF|zyVs)i>8nG%9c2j891qKWv14}!X2}9~Ar8%ltg`oeeJU*1}imr(nwAReJQB9Si znVuWex6tLh>S6Ag!7Whj@2l**bUfStQ@F|$ez?l5T6CG}FEBBmClx|5D@;J)B zUq2t|aR#V^SgGdq_JJ^^xU_&(VcmRrH$9+H$!n|{?QHM6b!?Sa$u2CjLm<=?mi(= zYDUK%J_AO5WE0M)u~Zo&Eegd9PrXg0KRR8bSNCF2zVM9IdxZ*y)x*S9HFom;0J?bX zd(5=gW-$`6RvE&_#dB;swhpZJExz6hLh!xaRn{x}x?==-xzM z@7W)QBtgnw1t}+2ic*l>yX%U(#k05b8+3;->tQ^eavttb#&AqIA`sg3^v}n}m5u; zZ2Lkj4(CvgN@VTT+iRCz13`X*op_Eoe@uo11*LsoTvZu!6hBG5^b`<$?dG6k1XoYU zd_AqQRan%LX|jDNTJR${TfyUcYjH}37p&14ET*@)pX-eclXGn@LqW6|dgF`Ht53_2 zES6E~36YEbY1I&%{qP1ZQQxyNoCG?ONoUWjKrD2)Og$Cq>zdU9X&XpB%vRaYt0s|S zNbi6l7eC*v_xfi*)kUWBX1LWCl;UXIY(0rUgDYPo^eB0WQ znrpeJU(dI2bZdGscpj$J0+?J^uP7zihmP_S1B7feF87g&$P|;X`HlPHpLdlaxhjRx zOq{{K_bcp%NOTVopNJjsP$|bBFS{oZEY%mq$|Ew^zWH~So`Fo6Fe%FS*Dd@@Da-En zX+9z@*nx+akA=W9Mxd18L3Z^Yr7&l~gd`H{+0Y5?u0w@kP$BPor@vB4a?qYQq(rU@ zIp|PI1$2Y0moYqY_RyBY4rY` z4m=+w;%)4Jk~|7P+nsn?4Ac$MM!D1|dH#(HnUbafM++^yn(3M@k3yWYgLt~yzE9BA z4etE+9b`L)U+$H?Gbn}1i$|7AI&flRQOr8rDe1iA**~LFlFeb{eT8J}GpX#*WGIwQ zq4s3n{rU4J%q#l~n$Q5vsmq#@rJzhx945l3 zaum8M)g&X122DtSm`Uj9__S?{LNebMElNG@r31-nxf4Yk-0Jq1b)Q10C^#)YDq5|m z4A?Fh?&^uw#U$cLfapmIa-Js7wY#ZiIEliWyJ>Q98BAJ@=Txl<1tO=(x_FQGZ=g&; zUgN{^C8cCYB2FXDm@~Zn%HHS(CSzF6M|uw{$uR6nvsI9iQ={Y-t(UbtI2@VsZ-98= zy`_c>$f7J%-#{|aXw2K!^}%l?y+Jf)7z*X?4^?5^k_h^#*3gW015 zJo;OdIeZXwqOJ_U()={n7DbS`@7Jy!TM6yIj9(r&t(wRnM9iHwAMY@F6<6M&5e-J< zL+#NG^%UQc`A1V3u+8+Ai}dKkj_n^3>`^N-^own~x7lb&`~yNN!frPjG7a#Rf!n2a ziY8BY(<2$WMBBxe%c4Ck(H>s0O!Sv&Pg;1p8YdE@=7QD%V-VT>ia0~^196CbCmhvGAKz$u{e%>^kH`!vE?1o z=*0Z@mSsTQ@Ovp|X?ORKX#(_!dr=aNi3uTz=J-VGp&QF1>*6svI|Cgs8WDt zhlG!^oyC<#l0))Tl?BAb>r8Zl#qoX*skD|c-RiG0!#X_?qr7&0bxIy(wGQ28CDaqS z*M&8IS1t;t#?eZraZ|Um@?ZDWnQ;ilq}9aP?Jth0K6TCRhcNnV^x<5HtG~!&I&1a% z`t|EKX%r#+IvM-Y+}DHXx`(Csx(_pUx$E*@4@)vc#+r-<8Ui>uvpDW@(*+NfLzq?q zVSI1N<4Bk~O`6ne6e<4o^aV6;YT@hjyd=+=e)r_RZWX|?3tj9uCYk)i?AymTLt8K4 zPytL^=YNw2&~*=C@i;oCwW6$-@4GNR87N)g%*qEK6JDcox{mSHpYllYaIyLwdA3Db zsYu;t{$b5cq#T+U;2mk*$MWdb{%sVwM1jHuo>m2c9$Br$bUNUvJcV4ML7loHAxg^g zX#DRtC(y^W@Nyodzxzl2+oH-7_q;s^j!f$Z0eTDSd9SQ_Ws{n%w^5`o--?spn_!g} z@IyXy$dp?i6{JbT2|$fO5vsx6*lkl`niq&CK2v))k37l=k=naSS`_p~R>*>$ zhj-RD3&^vAaZRJvV9<6Ph|4&o{5kYy^xQreJ)XySop)@>#pMyL!hC%EtTG9GfRe-Q zq4yhHLt>Z*1g{9aE69J|<^$x=!tawazcqaEPcHaaH~1KzavEGk{`;5&LdEQ46CsEM ziEBQx$23IZ4*YV^)0*-iD?&E6(cVIj4g2a(g~srHlv6r=SW6ycIbDsj^R})>7D-Ax zA6#`oGF-ZppaXh@TW95}4|@kBl5eQiZP~JsCOu+v0)Dv@pKK)mby?$(09WrmZbO^R z-owjyIbElTJVG?3d0GzW%XSBynq--F8%bw9d@zV5>M~!*lfw;>Mw3aa#$M!$+4G;M zegvYf$NC=MhG_PdhgvmClC{Dbx6s>3q1B@1E^P#bl33^_>^~{V^IORiEFMw2ZhaAl zppW}BEYg-P2Bqs_c(V2imj5`eqrvqsVcPzQTHM+qQz-m1^~9l*W|i?17T z3^>j!Oh?z-S;n}y(mWEYhC&UIGxeJD<4>>2g8>R;x<5Tz7Gk-j-NILZhVb+)_5qtv9s^XIW8 zvJ_kOW}Wtrp>!?jA7rbY8x36pq0G0)aJ;gvuv`{~&01QG$*a9?fYFSnfuU6_x`yHo zEOEh(&g?MNA4ba$hv(|Mv{ET6lsaxu5@L1nLJCO~cl+Gjc~IX=NX2vZ@HI*)?Tmq1 zO@a%K&#;X|UN~aPWS}CQ;mS^P^Wy*$cT+ z(3f+^&u~I1$ErklKb}Is21&T3NRpx`o4ho~&HZrt{pbSySYoVsS{=-q3bE`Jm}rpL zeok7PGq!r^W3b$DxC!rXdtFcpv>D6~9an@VvY$|oBwEzk`-``u+q#F9E>4O?6jt+LO5FUbQWBn!Yp0E|tQ)48O&k|;rAL*MnB?qV+_^Fuc0(yH z)e)s0Jth79*`UX%9gyk{q~iX*`JqybW1bS5X&~*LUJy~MH@x97l7=_a-r2upIkrTv zs9Pc0lnKkKR)xb)hXT7Z+QO%@G+eorn(PNy`cCWf5E#mv%$C)?)Q2LhBj3~}iKQ@7 z?-y|aU$uaH(v9#PSVKZyy4et=c+$hd$@`CWhhC^_N`GnqRcYwhzRR9x(B>{5pLlLW9{fx@e|r% znM-V^9f&ciOat!Z%hUFIgmxstt_^EIBQNz0uq>C`vc7GNP}~>ZU<(t99TE0W3O)kYYTOEWx(iq>VY=lR0TVEUYFyVbdS)CwdiJhvSy5Eq`nyzyj<21 zOShDF3igkxyAdYXhv4Ud|8Fz(P3fq?75@@}-{#l5{mz0!&j7|Sq4Tv+L82#LP+mLg z+~#bwV2_g$sjDW~DrOxpNv-3P_*q6bN-h9P&?7~iS)&GcyV)p#CG62BW&?7EuIazc zHVFC;M2XjzH6pja`bNZ6(9*F>pe{O2o5a*Ly3_x+J)W(i=voGI zk`k*{y)*hDO;VVV0-{(mPj&e}H&f!^+^+b^kLVqxGEf}fBpTISeTxKx9$UZ(twzbG z{)N-mt^yp7Zh-f@eR`^gJ7z?CfD6GCUEiJa3ZnUqHYhj^%nn;Lp9Ypl#choPwWe^| z)M-h{QW=@rcD=?~|2wcqS@?*KwQWY!|D|opnsuxCW6zps(kx8VbYacP8S{CX)n04B zf8W$Y<5&2EcH%!+}ps?dzw$6+uRgUi<s7<{x!;sj#oN^&RU$vn zGx5-AOk6J?>}-R}2i&JSB?NK72l#F|xfh|g2xCS*VNoV~e&y2yspA$~9(1xnpw4X2 zCM4LpPw|%A$~~g`2PA@8hzH&WMd$f!E%7%dVm7)JX2J)Fx8fh4^gGj|6}0V*PnrFh z|FgBCy)hoc5(>^R>|PXa$cQFqyhfvR+9ilfb0PN|Vw*^EnG!DMH0Gweej36OJQxzo zx{nqFLtUZZR0U-A**Nbdw0{LjiRZ+n71Yx$xlnr0Dr^GvhTSIh+Cf)>Szc*o*`Qbz z^-Z8*Y8V#HB4efE|Kot{V}>9IOCbn(sobEt8$5?eLhG8KMevO9TMcOM3I4?)5 z)>aR8tkG?;?lfy*DV1fbnF&mb_5MG$A_qNMSeNfBB>Kl;eb>g(ki?s_+g3=Ru z=JUf{zEDqd6jQ?VB4bpFwM^N{hAf8E^qvk+``@?tf3!nf8*Mghn0y!7m;`O~X1YJ; z_y1@GPLoI<0=#RUn7j{-po68ptTEmJvW>B2_*7@J^fIY?52Vsh%PSQppF!#=hHXK7 z++_@u&?VObL@9g#5&(1`4=qb;6e z|JYpq0a$%7&f}&1o-j46v_1s8=u?HYiz%hlC-+Nb*aE-Khb1pRX2jB+)xbrN;x0U_ zf0ZnK;W2L@G4DitdbkO+Z1|B~<(_h+#N2*JnwZ>o+Gpt5OAR=6YBErV>P)0eCyNd~ z;$43*tXT%5c0O2n8?6TA(xT$(O)Pyq_gQogCxLIv?D@o?25l{a(yVG3pSawwlebr` zwX}$F6^3oe$W0Q|kkgoalb5)>RnHCISseaL7u@jOqrDPksa7GaOT(@Oq>3-5T~J-x z+%gh50jrhvpOoZ#NwO$8S!fg2UzL{?IgHQNh8Fp@yZT?r0<0yJ>upse#m8nnvS9q? zF%`cJ>@raI-4l~ck~;^DmIYVGY)!jG#cfje=&MY0qgziXi|?{)I$Rc!dQv(l5hF3- z=ShOYy5!&-_;ftX?#m>|pDg=%yhWo;ONzL=uoY6XpX8<$>iX9YebW4Ih(m|bYcSrV zk+Qs0f>09r^89v*`3ggl^N@s(U@qV)c^O-{>Op1YB0Yxxd$405d^rY%9Pi^|#>&!3 zkB-%pU8h1xiB)J+gDR82dWjh%e(s7q;K3?4QUd@%|!3l^UE=h|4)edcfGrz|# zKQz!B?{Lbv9+yO-V!oL3=rnTf3j*hEw@{WKUt{x=0tB zQ;D``L9RKALEDPd;LB(OwkV>tOT@EgrdA0ZjYi9!c^Tf8jTuTd2X6*EgIBwwwkhI~ zbglGy>ti3X^Wr-7nvP)Rft*#gB?e79G-v2y^}cCX?7fV(J|G|77^F z5jg3<;gwyp1By9#qyd|jU5P}>JNNINk^cd84OZf%>y1OoPh(URm_#Z(T!=>MG#>Ri zb_G6C1S5K1Cfd2*6tNuoXp~lFxghA?D!ukLWV;C2{28yTM>~Y3^ybs#>e9UdfY6CEj^a-li`Ns`{HsExZ?!X)|e*>xr(p) zCrgg2`!41@Gb%csZUG@lDjxek9?@l*R*1#*TY-19JX{ZZ?r+lgd$_0<~SbV$rr^Yi!F= z;f8^hqcqr^W>4|rP5klEg8*N~lHsjFY~H zlys9m5AQzlYO(ga6FcFJxhM@zVvE~()uQY3>6PExu(OtFctn4-Ofd~xToG+Z)Z+3| z+W{BbdbN0y_G)MN{tfNl5g5I3;^$~mJ#p-Zq_<`7LId=67+-FhKS(WBoxmjv4V!Zi zWG|3;5%oGrEm<_yMBJSG?MD3z>rGJfBDgtUzpOJvE!Q9O1zPJlJ=e*Fz-Pj4&%OYG zPe5QEUnPgB1v@&O%*=X;qxX8e1vWcmMvrFyNlA_#{#me|mIfqBTscrFU5AfvO5?g9 z%%1VZ@mnL*<5e6AB$e;n+NHoS$h`r!=DQBVmwZMzE|s>>iVu=|3aY}vU&E#1-eY(0u(*Gum@DDQr^Wmx#v6O<+S zQI_WmBv`2 zCDZep?P_6SA`3+%>)tLfeRh3Vm(l}24^VBtTB>76*oscMQnN$t0ed2#;#mmEPE6{X z2h{S#q~@ijxDJjkOq{eF^3!eA+`|taQQHPb9Y~(OA>Zn9XHCKx2>vrxzqp5AKdKfg zFSyjRmI0aP znY5MT*)dj&lT=uH)#xo1waj^ju0yi+patLT0wJ5?>T}6?a@$zGrN$IT^VY6}Y}2Ia zjB!9T1A^zOhJPzSs1j0apCc){NZ*b3P9tAehO+r`fZr1ZZLk&TArT35Z+DbsZ-BT- z%YJ`hT_c!tFSe=j0m6`H3P?7EI-1lzF175667wZXjI;}nDGc#)B2M_O!|Lx9fNk#T z3M{5wLf0Ap>n$Jj!S}JZGLX6Po{uWfsUECM+y&*{<~y9~xO^?Cf7XKXjw@u$gT&*6mJ`ZEHtABC5`qPXp3jyUj)`sRP8+}u7FPgqa7tm+k%`hT*z@~q)c#s*#o;EZ zQeMIL+Z**s24kEK8?w?;sgOjOq~)-8Wwt|I{UHtC|1hqK0+L8J6LLtRfN~Sh3_&;t zAg=h)-__L>a2({2?h>Tp*-&s=G@UFe1~#A8S>*M(*g~mEyVJ5xs7Q}tJ%b&&b`RH8 zK(+;dgY-gj*857h*0msSdoimn{Ugw=0GUP6F3Q?T;hEvT|P#vVh z`Dv2|TdlMvmwiKHkF&qkfLd{hx070{1iA+nS8IpHrDk@9<3uAAc`n)0Rskn145jJ` zvR$?**}Z8E^JZ@6eHep66hN%I`y6yAE=owJi?ip!LkxoWiwRdiarnNA_>-8_F8;J= zb{bjr5L8TGbydI?$ua8MKw3Vv{gmM>`tkr&O^sQfzM_YVHbh0od!=pR_m7TuJ#YQ= z`TR#KQ7v68;^9%1QLgorq2Sw?jSx59?WpTTPhlEp6~0-GefDy!{AX!JO!!?&PnY%> z3a>(H>Ri#oqdNQUyJ7O*wQRo>ewef!+Np4-Ua+_xoiP9K+sX1Dh91OH4z+m9l(A#q zN->vz`l9q z7nyI$2_a>jZJVxE?g3;ZbXSETzrQAfgcwp^eY~VomcFPWmlk&3mC);ki?2rG(k06t zUSC~IVCw(2E_Q+JXiJAVQ~l6k zQ*pqHyetou05Q3Stui*OlxRen*R8=AtlfL0NAlzSSjsacBs)Wg8#biO)G^)ELFb^q zVGxOj=FiWSKpf3P9HG+4O2aRf8@C4pEyiYiGWNfhN+?#PIkGIf5ri<(TZhIE^VCF# znFj?9-#k+JKP51`-Xs_#(1A6{7iPgO-O)L7x7(Sykc)wzn0H&uBlmjru`b_ima1cePE0Uq&q`F6Fm-{;SR!!zx1zNZO zB*beYF4iSMXJTZtcRBE`Fk+FH6f3+3&yKs23Y7~li;Mcv725$`v$pm35pP2 z?L3^|4hK?_bmEFUQfuD7OX1n{ZZwDeIz=4}&;1P6yO!+W=yJz*L4(w*a@e1 zQu#1n3|Zm^$oh6atV?UKq>uihnp+jSE&EUn5rm&=8|bAwB!Opx5DOFGUv?^%grn0vYC z?L5gDwbc!vMNslvnjDP5^BJNKXHdbDdF0aY*@*jFMV)uZy*la!*gEhr>$C}e*mRpH zxrV!_`h%9X*Xb%rA@_k#tuvHzqbhyLykD=|V!jpQh~A9fmf7-6^< zR^v;DU;ga|t&5(V&g;@-an{|6|8sBqD(x z^29?jbjZoaT(`Z>^3*qaEOC1d@Xp$L2%P6Arp~$ZTzT$BQ>@NY$6p8|75ks6Jp2O; zdJ%PeJ0|!3mu|ppa)%{G(Eqd^I27BSO$q39i5xF>gDLD&n!Iy^Z4*?iPa#n&UOU}u zCvdr8W^X2H?uQc1X!?XO@KB$hZ$~(Cos=btALO=l-DzCh5oeJ74Cj{Fp^*|bu2*xr)i4^&dffB7^w%qw%59M zt^wS22f7blo<1(_1`*N;B_r!aMTJg%0qY%ubYaX_CX{i5W4B&ABZRb!!DOaTfBiP( z>?9kHX4OF1ujWw zZ6%-9CPv~2ix!Xam}5;^^c?Vy_Iiy$qzos;#bsS*qKBmnP@Xqa+=fQ(;j}U0my8gt z`@%-OPJ=`nwRRebi9rg6iGR`%%|2(&tbTh0ts=>7i_m^REc=JqW@qAXeg|aLF z*klwk$!+>9TXu6M669K_HH4|O^BK380k#BP&)-w7_PXR9@aG@s(vllH*Iv4FZoysj z1hZxpXc~l!7z|zz6Ljw#w^+7R=8zC((bA*f1{es>G%pk1LoDK6U#O5D*3 z#OFv#2u=G>O7gc4-6GoD$1;tKONWdGad3m7CkhrTjuBX*v-5^Oatmy6UYnA|nI|95 z?fNrv0V+JF&2D$I6j4x53yTTLz^-0fr;r&}?B4HtpxDv~8=i&AB7`9mu@5ZHARQYrxni@aSLlH z>}k@=p^Fo@?d!L}d#*ymIwYnpOycV0-9r1}wM2~}0B=1J*8sF#8nkS=q$4~7=M5V6$jp*dD7_apNJNj>mnm| zs?fYkL)0S0kXze8H`n#$`nhw0yVo z9lA{ALwqkZaX- zUc(+U*$tj}P9}A3J$0u=Fs%6$*5rwC)azcamr(AY=9^qeoe1UOHg_h3NY_junGzpfSw!#^H+yc4)g$V_})()W@ZSWB%W(X}@8 z2swWW9+U^O@xag*Ns*H9Acsi3SFK< z{;uYq;UiI5+(TyK={DnUZb0pojMR#6y8Dj?(8Ubvk>dIC^6Nj`;Mr6w3{a{?(>)D& zNs%I~Me99s1Lh!{SiM9x%yjXKj^mLIekt!PUeCvF5Uu$~N|$3!HVdJ`w<@+n@IdMK z#toPPZ>cn~M>blRyaWq&V)@|xe{K*R6{>h`a%+}Kby{N;WMD(*ol53(MO95x34&GV zMP$>eabxEefSPj)#ur}s-2mEb>S}!P?$>Tl#m8^kinxJv)U&Jc8%g_S#(cvswjkkO%k;oDq_)=&*& zI`zaMN?awc#TDohcZbw#IY^%Yf)0X?+p~~OUt2XhRllB{GzMKlEG+DoXl|)7L}3G^jatN?lz#1Eff8Cgd)U1l;Tc=Cof^vL4dY|e`>`Rl1>aV@vQlh_Gc4lQE)3>-*0cCn#l#W^s5Qh zHY^@Zvt;8ta9MzB7aCf31{Lp8fwy&m0hyh||i^6E>~ zK$J*wp?lw4eiq&Ca|i=rJ~3L?S2d68*d9b3jks(`Q zdK5-1S#-`{*YjsYv?igq<3&ZjAoV~x5{%hrmpg$Eu352W7F1jjDh^;iG^VX;qHUJP zs%j}O+Px&}K2?@S7Is&LOD%CndQ|tZFFt-7ZGF2QS^}R2ZmjFc4MgbR0**|Fi$3B-hugCZ~F> zP_g8$2`_V1%7%iwZaL??TWGj?QmVVkES6M^U3??}dMyDi<~8g;Daq5vxy_`Ly^`nHEcN z+GMb0^OIDpz8tmxx4)ocEoA2<#O>*-p#gXZDvB;C5DG{-zJ1%LeSHWw3p(agD~)ET zW?6~`(PIdNdVa2k*B*#e2^|?1>+)>XC|g}7aZ$*)`?2ZoqcC|{+4)e(fAdtcY#CO8 zzbtzZ+?)224@cH(V-FKrCh4|PHJ2{f$G}3H;N{b)EmirRVg0lNg?6N@@XYjG@3x4} zLO93C!R@~L3}CXXIJjuy@);B%bKpcgH5AzT8Nd?rSDEe(&3gd$?TJ+yF0OvtCr~ZJ zCv8;6#CWj{(WK}1<9_Kxj~~}VvB0a|Rr@{xoN8d9iYaiuNk6c`C^%I!*caD5+kaA$ z8y!*2wDxL35D9m-K-aPw2)7lJ4L)`Zd2hv|szHvmtq@0YwY^!P4qX@D6NU_6xR<9? z<7`2iS_Vnvgaw-9hJ;d zB?wt>XHb@i%gC*Hu&t7-^Xw(nQ0Kl%C?_HR`uHjjop^5mIeF<^?1pM2ueU@3pL`}^ z#GSpAZu)@uzt*kk`p;{hBz6-EUp$U z?KPEZDJ`lsD|Jm*sg`Q1l=vxCrL9(R4e=W)+;^RGa&p%BzVGb)rGK6$PlxBpe)pQ! zUVDFQaU#?3d7EZ$1NSEotXSivGa9}8r|kGOH3L?04Cx*JHsPb6bVG6?qfJ>^cra$o zFlq^wXkM_seo+CG_MReezJ5XX2FkTbgTE_=fAUxku;{5Hm#FQcZY-BAQX6yahkrK$ zlIlGVbDV?>gr@}wmwh1GXz;QtkqUJUtft8jn(cCllQmAv?RpQ|GZ5O7$jtxdHCZgj z#|e%OvMC0WUFv-`naZlEL8r)67K5?F7__-m7P?$r@=bIN>DjN|Sz@i2i!K;mu&eIU z6Tf0JDd0mm+sxkoliiGy=Z=$^%0)AAJ1}xjy;SJZB1kukp*(s=7RA|)ROx+a{p9n0 z%W7eL>ITUTbI+f$>pP|CcqgV$rnG_Fb}i1F!3KuGFnKZ%e_wV3ps*Jo8!X-&orLGIR0N9BG{~O;{e%3&7MVm;)cFDhuqM?OTY)llVNr zskQ=TP4&+Y8w1c4sFv`;^{drofz5b0X0W3=@BI1&m0XoxXC%^Jw%=SslSIfv@WOR& zEuCOVwpa{wGSPzpo7wR)Qt(u>e(UzDbAU~6*dm#|Y^|*mo36MGb{~u-RT?$8tP0Ue zSqk@tbL!~C8(}p^1gXU4rkA?3yp31aUD5a?f{}XSF`dv(KU9=PF40h+^b|zt zPaz-PdJ6{g4(dXE8C=g+I^oLgRmfo?vuua?!C~O8L*~wLQ=Zj{>%tpOZ(1?IRJ(g5 z;Rf&f^oQRNXbN$$9>wTg_*|uM;hpmE(%Ymq9-A2aZqFIF+k?n;csbRJ0bc8>6VN43 zXP-l*IElOfW79WxLUF4>ak=))iqwhb=@HcGF+|+XnkUjrK@?5HM|KGo5sq*Wt!~JlTc68a*atefJ}@j$G0eu;AUpBfAD8uu@BsA&dou$vOcelOqTBi*VziFEA#R=fxD| znlTL^Q{a(*9#+~Z{26@yj3=2~@-6!7+(%SmL`Y&SQGb?(M<2O36@0B+d_kO4T1!Iv%MR<(5NiH-dZR`H7Pp{Y7I z##JIX)ilClQ0K2eS1TsS(hG-fE=&;r!ncr=|kM<=3#3(*cIiOVE|*(dIfFK1fQ!1tc!#8^|BybGlFa-j*2!h_54%Get6HcUhuy3tpZT)yh?cNgT&zYjk`!x?z;{pg*)1|MxJKq?%EY+R%F&Kn!*wkm^g zX}}JDAT#aWUxQAu<>I?Is`b$2o;u+_Zalw$d|80PmsNS76J5fWIXt`2sdvA;q9#oY z>xbJD{+V9Be-p_=wJYV)ihY83SFKgh!%JY`{ZYK-20pX4&K;CTUY|Z~M9lJy6CwY5 z(0;CdiyG*}^KvL2sfJPkD0|{zQF- z&fWS4!8-RLRzxK$XbVRYCv`as_e!6L@`fKJt^eP*5bP_hnbPf8#s_dmtr1_j!|&Nv z=S~z3U*#@_i2vK`iI=N@aGIdXv)#e%Wg)dIq5^xn*68Cs2LT+7n9l9(M5ruymTPV| zA9|uL>4AG|R9ON%3;4_N0y^r&D<9^fH4DUHWG~-~dI)&)VdHTufCqKai>EpgN}bH_ z`UIrK!=>y|+?6a2*9*(pDml<)>#XO`_`|3pVAR~AOc8oF;5n)!*_^3!fZW!#A3Z$) zZY~P>F|SUS#^~J%m$)P=-fEEciWw?U0(L|*6*!ozcLQFsP`NxJi~e?A@4Gvo;L9L= zUa4KxUoWBu^VL-?=-}zi)1cin_x?pj-r>Q20W8>;q_uL_&Yd%}SAoq1wY|UIJfHqo z_M%he8s!ez(gG|wqd2GpWa!<7m&CotDQR)y_y-NY+YhCqnPyz+wr1(w0)0H?96sjD z(=E4^1e<_(9Q;Q$+5NM*_^L@3vA4}&PQ#OSbxkw;u%KWd0@X<%@H>GWW?6&+tI2ij z3#Fu`ViJ%bPPGi4@#$W8krWhGd0c+oS{ZCyHs=cnre{2g{PVmDqtZ1+CbJ<7(IEwQ6zWYW1nU|2Mc#o{WxLScwf( zK=bDUO6nmnT&%Wj5T zoacs|@^D@>2y}7A%?9BQ0lo=55En$*5?OdpXwC~C;3SCgPi*`x7ixG2YRJuh@={rF zC#_DV`_?-`+_m88`oZAzC5XN|b9BR3$RdhVj8d~DMPv6-hC*-cA{fqk^ zI;y~6r`F%rLTc}<@)Z=pWxjU(ToF7?T~6;V9lk8}caDrz0rN*{jlheP>0WRc>mc+_k#JLYmK{UK>jqf=X&e*=^p z7zJ;JGJTgUinb4s)+6h{P9H{L8v`KU7$)1(yJffGEn9&D3ft+|ow^)61OD=w)SNxC zklf>W@dIr0$ZNx;BPFmCq)6~PfJ^OEG^ll@; zSZK5k$5&N}20Mk7%nG$o7s8p+KWcpooum%-kxVxq{HYf_1urCQ7~e^^62eLL#{y&L1o@P@L;6cT(epG2NJ?!vt8VEhWCP`wz;g+{V4YA;)r zL{Yen2%L1_A)uW`&4y?EZ#0ud^Nw>WK~^n$A^4|Kzi7N4JRPct_JKjN@Z5!Y#ypjc zsB_``pojl;02#6wrpB|z;Voph;mrLVoYy>Ul6>Q`@1Csm z%+nSwmt1W44%Ewn44rQwxV7vSyoIirxGFhLt@d6i>Hh6XaA6a;fN0|W*<2jeL3Rsi z2E3V8nXo{LWnS{j;83i+4^rjj=(sQ+>(gg%^v9o(c)#p;(%A~2e(9bvZ{#^eR7+?CPlH3#mi`YBeWz}Je?9= z@oQU)$gJJ)17G7T6U9Ilhl@axbB$KCP)M^mUmx@_yhvv zZ=QYALj)L$vncT`%3xOM=0_SH`22Ls9`LInNaAOek|f#HgYi(1$fC!^N+l+y9S;aC zOMrr{gY)Fk`Cf_$g(+ErvB;ER8(}x(W}7l-vKBrT*6dz8WQ27*U0*fCL=fI~=jim6r8<_I^!B+LA)nJExYme-{D}YTk0K~q+QX9s!|>Gx{1Qc1 zla{`60u-eym=<(S2!mMeIGQ9lCS7V(uV$azHl4oAPl4>aFu4ppFM^0RW*IOP-KSva z3^%lH_|2}*`1|cU=kLX>(qBaw<;t4?>qE8Jc>+?GfArZg>2xC)0-$W^{ECjw87pWmK(qpX8sJja%< z6C_&NlOUCIH|@M(>K`?>W7z=kkL$#>7NX_Vqp?N`=AZL$EHx(S3_4;N9f83jAhi^X z4z31A_MfQQx`zVK?1kH#G=mO4hV#)g4D&*W2$Omrs0+JFd`Ry=2>P=py~EkywxU%d zFj6PmVnl;}4Uv;f_U{av)*r0ujjczrZ6E3`0`NR`;e#t0e2P-I(?e*bmX8EZexx_> zs9!d(z5Mfe5uQgPlR{YrPGd^0kshCz*7wB=P_iR%J`s$l9=${$z6@1G-3V^y_2s!s z0Y~?^y%^k_ND-VTP0)h!&rKYWPe~j}Y)8u@W2lL8UxjB~8ZAPLLeh`mAa-{SN7G=z zfsdih4RM&^VWKQn2;{2x+3co_JRj=u(MIgok*70mAu)hey9g1Rb@uiZjkySo0 zhNk}qBC!C2=bD#NMeBPUjnyS_cvzje6hp@&=`10@K7z4W;_m`74p)A-QY}fs1nc4Mx={YFV8o~HxdmRRXwtgKIZq6 zsas1NV0c)WHB1EK8CF!xkEqD0KP&ca@Q5-1uBTfJqUGIGMA-jf2{tJL3x&CBj@tNtS5+3OOtHPW(xE_~)dZh#?b@ z>+^)6-)zy^?#iHYX>t*DhsVvo0+xJ;q?iZV>}8^*8CzJrRy%?a=Bk6s=kElI9)~#i z`<#O-M40X@f>nvsa##||2jTDESP1)WiIXtD^0>NEgybWPC|OBhZ~IRP`w3)?0a<;R z2HadD26Gp5bR?6c8wZotZtsH|tL<<4`8~@}6V{1P%WX$V4~gmPZ?0O_W5rwesi&+!)ZA<~IFP5tM$e=VNJl z7Jy_c598~~KipJj&5BNc4*D7vLt_Yd4m7F0%=$^rJ5jqWFVBW|gX$n(wCT3}EZ)hR|l591KV2D?%_72%i=OL=HapzkvNCqY<+itVi@@y8Pb`m@#?LzD+Bq9e; z7v}L}XbTw(XT>nys8S>(5?-r5xzsz@I_AK#dVu6fSfFNUw+#-w~GvjgPa(%AvX{GM{#qb zPRhLZ-i_=Ep(g}*3+8M$85AlQiEKT6{LMoppyEDa2&ZIRgbW7WzGvYLO_XnA-*Tk= zdWyr#QBvi`{z-2c6t{(x>zX>lI&OPp)D>vhZ5Sgbrgnl1Oe7uw*vE+M<=mM;m$m^V z8Yn#M4(lg_5<`7{X)c{eKBUeIKhGb!7hqfPFpbwFUVcFa4Ab!JRs&t8xD{K;JF?JG zy?6H93}tJhP__+2Wq_i_WSETtHF&%J{)pWOES(ToxO@&|$Y8iS_6kt?PJ4D5wMJcB z-y7xfNEsAzGmuV%c?3>}s8Fc$YhlL5J|*xo^AvujwOt0qO@x-8A?X+GyS=*r0PEpv zc>bD^Cj$~^Ei{--nf;Bqc*PGLaMY0nZIBji7&2-p2>TJg+*T6`WH3|nZH}H(I6*q! zTPpcSq)nN1ygq%qI}e9b{sJqtPzJ{Rsu!jtve+@l_C0+FKkyk*~TlnR*g9j62pj@3xl;R3*VGuP+HBfT}WJxu))L7OPBu!N)!rwPZ z!9{1tC_?(Tzjrv95J$k&WvA$hq+9Lm&4(PQLi17$)9ewiv9j4ovm+{l7o3 zf=a?2;W2mw?Dw5`eHR&M50_Wqd<5i!l$X!exxN;<@c_TvlB<=7q2w^^J&GEYV*MGg zW`6p9{J0pyw>Zvap_tS7UP4N;pWjE8c<`t`jjK&Bz+5K3#<|{+vQ46bRF&QG)pKo@_C*%6rzq1$ q;3n66J$4jWF%G}n3qP7wIS^0TRfo^T%;)N3t8c{>^&eQ#&+os&$J==T literal 0 HcmV?d00001 diff --git a/deps/gral-core-0.11.jar b/deps/gral-core-0.11.jar new file mode 100644 index 0000000000000000000000000000000000000000..108ac12d8755573571d2bad7ee3bb9aee0fc3ef9 GIT binary patch literal 280268 zcmb5VbC6}-v#wjVZQHhO+jgz8ZQJg$ZQHiH%eJe!s`~b~fBWux{yE<{cSX#Ixnjj! z5p#^p98cz(sU!;uh6V%$1qB4iwUq+;Up{Dm@8!kSgz2RfBpBs|6{ID^Rn-{eB_8Ex zrsZVm85ZGX>1pO>=9^WRR#^9r4~{{Alw={HngT#>aQ{Av{r6J(-~Kt<-(Stl8O@!o zO|4watu4%*T^TK%jqMoCj9rZxg-u*sosCUh#r}R#b#QYwH77G>FtsywaY<9tS40&? z<8R(=YN1<5{{SYz5U0{D0f{Cg$5M$wgCWC^-;26-r;E7;H1CT0#~@NX%!E+*k|j@c z3r<2l&$R)Q^xQF7p8Vu>Imw;e{dztfR|HD&tlUcqb^=$0$*1zHGSV4rMk0HHiiGVz zh8UIyZU@^zP_5&H!){~>20kzko*Uk%41_8ov9p7glFTfM(}*>?EwV58rYYOUL;AF@6gOzi$njE!^l&yr;@uEharS{Bo6dzb3w<3pM?mBY=7z}M z0>fTB#}9V=HPBZt$<+4#d!0!J3+#6sFo|!_H->SM_=bP*-Ul;Dxur@rq-_$FbpP_! zSJ)MVm49(9X8gi4Ha?}&nbs4Vc>A(dIWmvPxU)?jh?mRZf+BR5A+jv=co9l6=j6*q zJ8RnT5tb*o^qjI2fwC8Hh%>?R0}0Cmit_`@NhO2clgNiG0ojN3Ldf@MYGTP-7l@}2 zl|S=PngrK@A#-erAmtz6e|&?Y--@UU1PG`N?B9HY<^QK|{Kqp&HMKoa)zQAow-;Px zWOR|J%`ulsP%vIKTF?@$sAaU_I^K}L3S%QqdTNc4 zvJj-*XU1Zh_mCZ$W7ki3s*l;S7-Zas$8wrqr8O#!>9YJxzgM`AX9e9S4A>^56(_Dk zDN#M=O;=Bs;AXb{t$oH%z9d84kNZBqb$`2|zir5axhsl15Tbj10c+P#x6o&>!TF zq}~WJ0Dmn~9rR;D-$~F#<0G0-5GKH^awo0Z)2>mz!vm<^foRZfB&fsu#MD6$O;I|l zhLzU3ss@k$yXj0d0x8pYf-&UE1fL`rs)!wawFs)j| z*4ypVj@jV8;@Dn^Q)r@uZ$xb)fDN~sRlDw(3<>i>#9?)18}If}Q?*a9j{7Eum&L)` zxWw;TY;31i)1C83jO<*2D z7ITYDw0f*V>$7=zjEw&xeMGqiCZFa5**3Y6k=ACA*G?udPjcU4+`z z#rRS(lrPFp7=j)i~V%vqecLv~sPe{Kyr1HjcaoWS*RC zX^8H>&;;3w_=RFKM?co}i0Y^zSI!OyydT8e2D>Pb2+ zo<>sL9L2KQ?@-I-nzX9b(IWHFqj(?`1}WA}{5Gq_R8O~; zC@HKi!4!I|<6&>moa}wBE!z?M-eL#sE7h1aU z@k{pQqW-n8bmW4xJOT|C{%8y5p&B7zGpbya@;xLtsf`)scA%8^{io9!?%&+M@cwuL zcrOJI{P93kePVp({Pi@Q8IHiD^XGO|wy2I?(f$CPyn}w}tq_jG{UNFv2EBVNexXt% ze@aw1$c42#oYQ~CwIMX#-kC+M$MF;m+CWV${F0aV4C*&KT>l8YE&Zi-*TSQ8|$Debk zj)yQTOgPNL7L>A~0tmNhuxBFZi`-e@ZCy9!amPEQ{Uv!AdCRXkG9%D{Cz1r%>m+F< z4drz2$L|B&_ZJUjw>bO#R+9Ta=18c+Lwi6V`|6YpN<&p2s8BMV*eRV_MEhtmL$&@O zRg5D+{Q&~m58^Crl9^PJ%$S6x0s?~~crLyw;lYARvY_&|hYh2*xi?oq>=ZT_+zq5g7rVtiA zN)!uM(=gk?+cSyE&0_Kkn-HBOW!zZIWpYWT6w+^_ULc+GN8r8G*72rPzEIBzS~|U2 zC)D+&7b_239#r2H3W;`-!&B+P4Ye}*n=C(1D7JL+1rp%vCOI?}?Psf%Z1BW?E9rSk z)!1OPs(FKsGruZL4W}u@&OIbtaeLnL@_$Dh>Vt!yDt%LuVTYj{dUL5iWps!eUL%6( z#eRw5acw4K7Y`T8j8bLDD2bDwGu*MQokG~;qE>8b|IFy&3qWk|O2_O-r+o{J*>gG;Zn5O7P$B^dC4|}9gbDdjSP{0SwT#fL zd-ZLd?+x@*d909qgX(3$kJaHFs8d4}n1sJc8KOan-Xm z<>dQaK_l69hBju zeCHW%`V2O_edtZQ9hO{j8vW;j5g~Te*h(=yZa1(;{_Tejm{OyO*H0yck+5qem6KuP z2eI(4r!^DSFDF^5Dp^}T!SE%ro43O9j4;()yG&B_8%-yzOdTi=rf?9whNK^WE>&fQ=Ewj zZ!{PbzDW=AGZMb=n^5aXF^%nGEWWlmVg z-?q~61xBEFDAPToKh6&Do!s~A0>dSVSxH7>b9{x7Dd?1X$zKR<-O0rS%Nm0f=xA$V z<}F#hmUB#sXD!wgF2zFVh97-#YJxM5)N!OIlZlSMqvutf3`l`V?aF@`l8c;I5|*jib;RX|&7U9C?0T4}4i zzR0{ED`)~a^VI8X=c(XpuFt%4`}p86;uWaU937tEen-S%IUb?&XT)JYUIf?o_&xJD zmgQco6NM9ni^U0D6l)l3-5xV|zv`V2c!1JfO|T%%TS~AXt*64EAzDx69zD1Nt*7Lm zAlj$uU^mQ9)w{l6M6^%Y!TywV0njf->+@;olQ=LJs=3@~uwm4h8nEKAEZD=TNu@=~ zNJXT6qCvBx0aIZNl3=^0M7v(1-r!t^!F#Ut;LQ%9#CmAwDDX~4-NXoBVTM*C0){rD zzQFe)Q(z7qr9cAVp5RchO^ZR1j@pSa2;rh&IG85wM0$;x(J&3P13qDfrUThKn5J16 z$PaL6C=?8{YIt6!G$PK8J1Y0hJ1ziC)*Tq2d7r4ycsS*)5x##2(f+Nq!BfVS zkACm5V8Tu#q#`>Saq3@v`zti!koW)Thpm_8PZc zhy-4hQAa%yyg1J<^EhNhsTeR(^)B@Y1x;2n?u)pw=fN|c{s>pIWYzXfWkW^^oii&s zn~VEYFA)O|!;M4zTWIkqZ_(`j8p#+db2s6D7C|A4cgb~ISU?qu3&-49gWLlGvt{wm zbgp<775*d&2d)EXPZ4#I?z83={XwgV>qWQi1Z9s|%Zkz^9)wANoVrRbGym6 z`V~rCTeXCik3VdvT;&*l#iGwHYV9JfSr zVpZ6nnVRvyX`@%uVgRxZ9~nYRY#at~D+|f>F|Y2KN>;!@_aiYPU9G;UjQe_e?aiyJ z7sWgI+DfIi_g%z>6St1wJx$nksWIS1Kb}67IN*WT!$r0*_-(?=vW`{_t!7uxe#-p> zg^TH5(1KHO=_EoA&J~N$a=F${Jw6HF!kF@Q5%nuJlADba!~SB?XsNSusM6ou*jn0E z-j?WfgNI9J-L~D<;NW0)EwBPRmJnifTz?2xr-x^#N}gQ(Dffs(pTLg(7y6{i%evjP zJ^T)v%y-?c%h}hG{Iiv%OxIHAhN)blqHv_LuO40?TBO*-$eTu@duM1b(hj1n0EEXB z27&_ng11&gl$SO+STch1OC`BhXfbQcqU6Ljd}5Uj_+LA&-(6n>aSf~ZCC^9jp&34H zN{E|eG0L_+-h3mv;J;4J5fS2xUx151&SRwNwi}$oR(5^2? ztHVY)U?fNCoa34$AKc5}CmM_-^!++vDYv4a3Dv8$W1dD^EfA#Eoxw#@oshdLg8JkS zB;}GVP1R7>$_x|~ih2*bW&gr|R!wX)zl;;)JM+vt=P=D=cPn1b&-TY$T0j*^ z%9RdpOaUZQxtq$Nj4EJkMX}-m(2hf&;OKWGc^UU7N+8vSlI~@L+b&9)V@+PfMU#v+ zXq$f3+m{s={VE0ryF)R5N&)r0V1Wn*B~foNJAt<$uE#*4U1lSaF~W&VhA5|jAo&O~ zl5RMTfj7F(fZsE_kcPMY0`*TY=HtHN*Hk09dbERCm@94^Ui2qUc*z*gj@A+#&tj>- z^ycU9SNHZ?rVS)m=H7@SL<)f9e|0>EB0m#Y7rU$7(m(og0Lg`lm%5F=Cd0(06hivHo!e>wT&p*j1@3P#Y5I|H6%S$ zX0cOd(Ih{MmeV{@=BaEw)U4$mZS540i&>P&Ue?a~WI92N z>&;K;A$;Ver60Dsan_M+u!CxLMoa5BF6Po5s?s-wbWT;SF<0w)!Q&7R<&__$uH4HiDo2iy zGi0Kzd-dnMs!*<+PpaPqEQ5FwaB#}jPwCW_SA5%9SUN1>Ki)kx)3mSY!6EN}};EU<}HS!0>Pa*G^8B($3n<&!t4X~-*LSd}?~ zDQsxG<8WAxDRV$dl_+1Mu2HJBEmbLUNv*JcwbLP%qw*tQq{ns2jY88wqCYTI9rK^1 zO8%JiS)>(=^nWK7JNDb4xg9Tk0Jh5@9L0Yy#Y!U_SA9VB47)NgZ@#B+80YN)y?s!B z3oHmj^rA$#UwzB0A2j|siY1sc*^_g8@1jNQ(X8@wSmB_zCfY|E^Vfjy&V1ee*Oi9A zfcqU%cTB`4Ki^QeSL*d?$Q9AAnf!g-jpk3i7ZAaO-pP5(+k4oO&QFobWJ9{uhguc> zUlg5hrAs{iSuIJ14EiJWiEWRxrQ7f7OS_*o=feJRPh|ZX-cb%2KTp@Q$ozY$!?xi3 zLn;%0SJN(=dw?RNsIQFKN0ya{)~;ehwDS{ z=YDvm1l^?>E%j0IxP7BHMfO0V4a=e@`T9jr{7qeQOZN2(uh^geoO1#Goy&dXc|EyJ zdk3C8PyTm$rp?LGjTm4u_d%wUD$gtsBI)CSmIdj?t9n zy?d1?5H_@db#nHnIc>Bb_s~Tj<@H+4X)?Yj$JqVz=S~#d;B36Ux3?zX(>vB}^$4en zqK7LVVA;Sx*4&&lxmFaI7s66zOzm>{vn0w~`A0wSh?_?w92UXiEaAK0Ka`He!~-k} z3j{=r`EQi|@2bWBLg`X}Y2D$ko?-tVNKaF{R6rHR;$OzV*s29b>x6=GZfu!wM(%M` zRuN)?Cliv64ajwe)N0x#?^Z1mWM725lV($nmGA=!_`nhfz0WC4FH4HC{$P zr<m8ew%zOf$#k zBal9lO=^Sx(kd*Mr4F4fxQVi=C{td>T_8qBp z0s19aOdk5$A|aV#0&5MLV)X--B%Zp(mYZu=W za;0)TK(lZaauP*)zA&RG7{`1Y<(!o5&vdP^%052)iw>M!lJef9JLmJP!URFOWW!i13OG|goHYK`2Ocy(-3?-%#^0}||8O_AdLGBkT~|I)GBy{X2}$Mz!hcx^534;{ zQAtLG!(`%=6^jqUfwAR=yTg|kmm=YGfrWzEVIW~F=ts(kf!R@yP&OD0Sc192M8ZU3 znv^YAkd&En)*(AK2QtEJlpYfJ%8!eJ^pWo|?^GQ+?NlB@U#;Gk1eTj^1N*9u3-1(} zN|nv;!{AGXzVO{F-P`XJ9#R329J}Lh4_tT*gzDpO4`uKfixkIYS-yztmhMUI*6&&B z*6tD9FFX+oR__G>%lDMV@2qvGj=h07XdAoD89EE)1K0VxSWLYZbVs+*IfV+W>30yO z5*xToDB&K|!m@1Gk2x`Dxh^7WoXxcSyZjO}XHYqA>M@w~Cm0z%)-TNI5-ECQe(BpDB$RAo!;^qUlar`-4axcjy9aaH zdvO$tg;?z^KkmFe*WbP0O!@4tB8;!6kF< z1$x0!SUQTyuV^eHBX#d@qaR{`^>M~_{s>FO(a@I!BipkgBbQALnwF#d6NO7yaaQYt zm?tt+`lw86S6w)U*TyWeR%d?%Z-hBLYc2^g^{`CJqACH%uT+ttx)!F0*ca3S+TqfH z!#Nvdx=|+X+RUSu!0kL!Vn|y0>1tSUk*HA^Jov@H${!WPIL5;Jyi!Bi<$7Asi6iO;yww8`KqF)>do#$Bx}xsNAZY-!3gXS%_? zZ#)^;onsyAnm;8v-)PC`$4hYbtw;U{PFG?wAxmbyx9Ortk2snU?@|BEp{6z!{oXRK z*7buwFxBPtQ`yR|Hq1D&b2aa*O08q}Ou`BRI+WKUL`Yc~tS`u0C*+93a$>-cVXiwT zX5;349C_Bcea*S|Ox3k4a5biVJDPlg0e4Zj;4v6vo=OA!3@vZlx5FrTMXUcj#LlMW zMwf%h%#&cr)w0J4a_x-@s68{6k=7Eb(+rUGO$fkOriI-J5$`&lEmL?ZMBclqAJMEoRu4Z<&we%ox-iMX>Zs zW;zbpWYf~kS1K*=~p(p-ySnMBsPtkt-?UcudDsh77=x;XDlbEQ8sM04RgXI1V z3|m!&xSvZi53HuiA98LVp%eg=uiO%Tb}p7dFp#Uf^1Fj??#^v!`3DL^Fshp`y8giH zs!3l|`VSmT6M>7#R$N0FT6LW_HCmF_FZI=YQLgq2A`Cc_&S0K-)Xd*N(MzG|WF^es z!L@E1r@Z=e(Y;WqyfRk=8IMGBh7~C7rT6f#uw_+)EHf|j8`%0zp! zj@g+Vxhar2SXgF#B@Biv4@+Y;VEL>@y|hG8*PY$)*NWlsLwBvl+3|imVgrch@jG&z zwjv>^&DnFQ0qzwG=;)&`cfiqVXw=lvG69i7zQE@EfyhnNM~Tumm2?*pptH_LS?J3vAI+p>#R`nlCzjfDuDw!k z6?zTp@P)Z8Asfw%ll=NlmTW5Q7}w!?xaQvL1i7j=j@Gz6*-lYJ zKPNBhd}*hV)Cwie5oIbWa4y+^^1<6VcMG0But@<2O`kgBgSCT){e zkW~tbo&w(17d`bumZ95=f!3S+u7to-Tp{Wt=>Y@c8D_EgG>ib#FDYj75L zp^dqVME}$M!!NKovpbF2Jx0z#vueWhgeSB6PYTb3BJ<7r;aa3jljje@ZlTtiv;fn| z2rANSlQ=xfZhJ9G793Tr#BWPf|3LdJk?cX`qyTy8IzEo2s|UIR)zDvqm@G8{6g4Y5 zbdw?$iYc=)-DBsE*;VDNS8;Up&gq!4)m`RlYEiA$P@|slZ^&|^k9yowP#biOt9Yft z88RCYqda9k*gN;9UewEng7cfQXS2DssMJM8Tlv)aH6H`1`yY-C0-5YFmw#&=8Ln zMNPEWEwF6m0wGSC7}TS&wz*-xM~a+dk@vjN$(*Yc2^GK*g`>80=K?X2{;QSJA* z|5%mM!vfCxU%l=9Uxi1Cf3+%62Rk==z<=lOs=EJl9e$UU(%H8MQjuVyqg?`oH5q7@ zWR}pFZKKK1a?Z9F5X@aS$-8yg`+hsfi4ihA4{FBsPa@6R1tEchF#gKr&bZaHn7i%0 z6$FwyY=n><=7(3sDPx}@o6 z*`1L^?Zi4b%!-R-O-#6~79c2l`xgI0AE(VcJjeRFK~ zAkV3xG1ELB=7$D6vPwi~n=a-p_7Yj0_pOYYv7xx7I{+a$S3a%R?WPdKpj){9NiCg7p?$7_9B)}e2BZM`&v+3TdnZR z{tv-NgW+Q7#b(&|djTMQA+Ee6Ykc+Vj_w@Yx*bMSnf__)Teee#3mcvH{lBziUJaTQbNVKQ{0)6vIh7hSuE42E8B>T9( znZ^0&etLRa{|lIJs4ChVotCDG=BBcvKpccsMSo?$QM#%poXiy-#uc9&&5drqE55s< zvN+ZYAHu?oPb`R7yRHSxVmj>w;n#85@NQ7&>Nc{5nrY^5Tms29(>4<1y9rnur_~rO z2iDZ7+LTdwhoi^9S3F^_Rp)L-IpmEsCbSn?WU&*Xz4*;jWX^&_on|`Z@KEaeCAaO? zVu+BXr;p%{n(p+&ur}Teq{W3xR;Fxqht4{vYy?D6WEQ#Ipu4R$T8{DJe5m|MVC=QI zCV>dYFFkL!Vr5$-n>JHKJ%TvUp=F+*Tn!_ty210VB!J$Zd*3D4hh+TW$LA0fHp}D; zwM(jSVk18gygH~~CZ;!1HnE+{saa}15&1oa8*hDt$v$-Z=omT(Mv*9YXTQ z<9td$nIGJvGEuf1z-m>4+v17EIfyY4CdiNG7T0LV$n^@BtB>f%umdgB5DRg}7X+3G zhv}EBn+60PDvSWhe=?iQTa0{#v&HyDUO-i*gdYNnqEOv#og!Ret}va!jElH}v@(Uv z`h?F34u=v{;RR0~JOigwu5{!;GC8~KZ8Wb{e%T)%6E8_lxNaAGqhp#_{Fb6}P*(f7 zIPx2<6N9xZXB>VqnGc$xfBU`%))jP#;XhqGX_TtUJb$fnLkEme_M&jrL32c}Oa(Q?AcF?t4R+c@@2xH`! z(I@CwXz0jUguf7Im{i4wILaaAA>$q5+oss)=^UWZu3bcK%jGuL=ce3(wfG)^=Q1=|Kr?p^KNN%v{r$9p@JS`VE# zNw9@oobwv>CJF}^q$zOq;&D-3>4sg%rpG@8CL+hC*#whB-D58Y_Z zQmh5$P*t9}{m^)0xC>9*FCK=yA7~M-Js|}6n2nm_-5a&TBLeuv8^xrIg7s4S#fpO$ z2o57IG601qch9`^Jj~@@{C8Lwktj0>VUi@gnV1&G+MN!{8s`0v^I%(yWv^wq!q-iLX z`Q|#Kw4||W6j%j5W^d`E&zqxn8b9#*qe1egr{?}}|B~=a9lD+@t-$9WDXh?Ie_q@8 znN@KA9HDrF`=oD>SZkYTW;K2gOt<;2-5T{@X5WtHHFj9)qu<+Z^Ik8FR5)r+0Y}}A zKgQo3v>lF9$_a83^slu}h@g#zHuyQ@fVd4z!h*|##$UgeT_a|VqV%I1fb*Mf55ZsP zc&g#6H$02qN<98Bk2xG{EH_7inPY%xt!d14O=p-ba$^UwHrAioCL(^D-(G0SR0U6} zQE!m%KYBQ`;;tD^k1eLY%;}sSpP7`=bF*xMS)-HAGPt((9g}zHnXwL0 z_mX>~S{2ErQ|C8)3|D8O+Gq((F;PaFG3nQ(n#AE@%R^1+JKliNpz~Imm^EQRr>n0E zwNyL46juOAV=Vi6VivK$7}n}S8bMX4LtnlpRzuXylB;`jv(fV;oT^ZK=w zO81CrdLi*bf$vr!Nh+chA&m!F0L?MXLnj$y$C=wc5kK6RWGi`xbFA!tT_PW8>T)5l zr8>snQeyJD@WHMQqX4nJG9Wj~@Y1tuXXDesf+KbQBd>UfIkzh&oma7a6>`cz#=Qxr ztd>>1EJ97ZO>nMRc(3=k&gPfMZAASi;0b5Y$3vPcQ_MU%baD{H|1qZEBR|WIJ zHepv{%c@|s3e<)MYsmh>RBU@l&_vv-Ox_-L-b8e7PeSVbVUqDe&ao=?)GZhy*E~mX zJa(S-5V?gV{P}9}`f5%$GkNf5PYBhOcs%pzVuVw$4f9yclky0*x6}`ThfrQo9JO!e zNx?#@0OOEwi0`kUG0IQ=Afn+<)kGewu#sZv1MZlPkqd8jEln!^t7quXHNF~qgPpHTgocjoHBu>>J5>AI=z=X zVF(MtK0bSzzJTBpoG?n;-w2p{f^ayzv1)B8H zDBQJ{#5BX^Zq@xRVKFnZ-@sl-Jw@MpKo2O-2-XSAvzjFI*)49|xWZm}1vU(+CV@+&I6 z;P{IlVU;Pu!HW<~5v8ULFcA8xXe69#jh=pzw_onmZh|}5=KS_8uEYAB@HlI6Ic;iTNOI=E9Q zx4~+daJfMjYYITe*d=_|Wr7UtoVT?XyP=s;4BVk*#lV6=YMmCq&K@d2y>%{;W;%O% zIJ|x$N1s9Jcw*s`mNEV9#eZ*O5_C$Fh6IYQ!1#zQ#SDu}z;4uM)TrP-iAk$GAB=xH z8wz_13f7>v@ff2gTsB;Tg$wXkr5Ic|HLS&c_N!3ohRe2QlTlA9B>j=Hz8*@5^v5*9 ze=1$54;ib-+_WYC3CIbNBG1${hFF?+a-|A6KG{6;;K0>p^ZuJr$}d`_DU=7i`dVR$ zWa-5y@P=k^Q}Jx>hUClaoEOE;vM7P!gMh{9N=zM1n9`od$`rMwfqE%X0%3h}3FZaX zI<9D}cw<^Dpg@h|S+7*}d=34JU<*qCPfA82A2O6xIXAkXghs|nleI6;;KZ_phP#_d z;Cp#iw8c1x?g`O(!JqD-MBV!r0guU_Ra#^PF&WD5|C%vlOk$}I`AZy+|2jwWf6+Jm zcmB-W<-bi^L*E5e9m}6Xy4k)9Z42e7+Bcv?S|&9iT4^B}1HPoPtp&a6jAApqbP}+! zixy3|2j{_Kz~=&Q)Z1*w&0%6f9hB8n)~WE z?{e~#@W($3(h;lOOfS_*T0%!cLP8^)qL^qn(Rhk#s)J%U*?8K~EHyhE;!n@(SJccf z1{*Qm4@w}$E>OHMFg)Z1+C6pPaqu1tAyx$NAA6aBDZnlJMzo)iFrL~2v>*tuTwBr4 zkx-G)T!ltZ<=|vsxvET2$l$m8^x(IqLWAadN=)Qb+)uDv#d|OxXlI`KgX*~|O!Q@5 zz^q*LdtHIJAOa#PgX2T@)ISsV;N2+6?BLue>#JC8=<0DgH!4ieC2mSC@jUWU*nfH& zwA%A7i0bXQk`XCT4V-l)EkLzjzGD;|o&@N5wIKO@6f&^;B2gNw## zKD?fX-{hw6#pGzq4|R1|Z^YYh9oqDbcp2SENYL`|)S{HQpdj!WileMix{1oB!C23B z5rGjK51T-cOU{pvbf&cQ&#kNrWs6AC7kkes8swkJMnYtZHr~QJyK9uj?1I=S|OcO8-6J z&tLFOex+Mn|788L)iTv~t!*zuf1HObKg%GKx_ZiHg3Amzkp(9Oq{pI%!#0aIhRKP_ z&^xAS#7oRvqMI}uq=}y{!Arwwf|D3ev);nz70@_ z0)K{t2s@5{AYSOV)0#jWIRAD7x0GCDUVsbB7EvnoL>-*Koz5f!mk5s+6k7}sGhr5y zVJ^zb@7|Am_9dmqw<{9cQx;{|7@(iB4Q_M|oTn@3q_8}wlIk`1%u*|YypWMDg{0NbMUED=|BD_e$UcpWckkG{b&6gPo;pgG2LPkYM(0iCcK==6!L_7xJ zr{~-r`g`LF;;jnUOi=5Mmjx|;&iK-_T|-$MCU3;QWe<+>s035Zun0gHT02$pbcqN4gQ~E0j@tTGM{We$lMq7lFlP`|atC zoXDC(m8~Dm_!L)mKKXf(CnOQ5bGca0BOqKMoO;YcS3P-V4pYiYVeVK zbG*d6hAQCx%Pa~7&LfZ1Mi2I1Wd;I92^nt$?G*i7Ss544ZZUox@_k#G{iXSTxZe#E z{}`KopLlAd#FD+z|0#j7k91PvRGj_XvC9_)oYpgnIUYatM~Ru=5#+I zUVVwi2b2ItLJV-%3EusZ$x+|1kz=dZeP!#+O&poUnlcR>eMr#miDH+c*A#y#@aQq}@*adW_#!{mLhj<9kG=fjjlqTU9)|7dnEcTO!9Qta z2NndU+ZRcK%`C@lK-3=It&d$+g0=P?#uv-~>tnRI@k{r>GY1GKt!%di+u6RJFwzqX z#jKAXE4)tc73DL^oo?qe$HZah_6E8>sL+!QG@5B}AYer$qI&!d3vN9=sa2?>HKoCv z>eH(l&N87(W2XdpS@=_0fwEZqFq7B^NA(;*iP(@huilrW(qHHW-z!w|(hR3l5=;Kb zvHy-KYuag-Hri<^Zfc2`MLoH8HvW-dGu}l>Gp)^0K}# z=i^&8t{2}={Y8~Sy4=gmx^_^>!Bn`muV&z<`uw*_oBXeJ1M2@fYx?h^fhMeD zt~&ZR;N_k&$3CZJw=D;<#9B6G7v5SHx&b~Yv5g}W%qltEzVcY{fpW896TUk~KuD~i zA`%fyj2=p5Aoxccl(ek%pvIIa0SU-K1=lbf)j{kTR|o=1zl%qA4(F=b$xgsL|Lf1k zyvJRaTfgta@dO~Ppmk>_O@eEpa<{ zV+M|{y+I!2IEER~>PUD7x&id}iD3-n0^~+^!pBA8B1S?3J%%DyLh%kUv7E@nNCIR( zz)m!+_!W{!CMtx0vr_9O0e?=gZVaK_q~%?|jVPcQHHrp!qo-jAC=yg!DN41k-S2aW7@LNatbbb{-+r!xWYMbvlP_e2^-dJ0>- zmwMhszdg`mzt8|&57#%!jH)Z_)G}3-H&-kHtkt9zE#+OrCKM>uXeaTD1}lq}ZWNXI z9wPjiaFSKHDH=O+V+Ykwdblk+CF6j6v#E#Zv8ghK>aFMqULRDAj_qj5YM%p(lCEjF z?A1%tZR;cSVr5g)FHnn}t4J;HduG4C17WMClLz^Y_}C8DE6deI(PNdA^m$FqYntQV z=2r#2SE;H?dC+&G3CF04rcb<3tSv}MqnHqmPvMm@_*ZG9;%tHPU}O=GG*3P>n& zy)G$dcgo~B6-`&OvXfS1&XD1=etCyIoNFKvK-ZsY$jJ>+NY9Ct$t|=~9PV2s7+mH` zKjlznnG~fZdaYPkM~aiQz>ODe^|Dgl=Hw&AWg~4m$?uCfuV#9UjZ}7-bP-(+yg1|A z&T`OZuaE{W$G?TPc+yY+exuz|o(U$sikptdnrIbYZBFupGe!?y8Lzw$;i9$}N}g)xb**Px7Q!hHGV%G8GeJ$dk=lIfr0lA31oKve}Hf zb<~6gcPSZbsB+n~!o7HCIrT=N!B7;z#Hy|;;L|yg*0b-RvZsVN&7H{Df3zBBc}v(X zUG)@g;z=>8cQO;iyrjB~k%W9LHXY3Y+Zu0X|H`#)i^EaApu1?o;>lbpH zBane5oinn~A|crCf7rW44Ts%)_`@<5tlj2y72D<0VDOrm z^x-*gB&gbCAz98&bgWzGI0PPcnZStG<7TdI-+RCDvI6ti`Zsh|=hTV~T{W(i4YN>o zmtP(_xmZTqf*-bE{~FJushLfwv=;C=u#ZP3&=txosfa(Uv7*Di`AO|ncYDz^@iA0m z(Ys2x&7rU^Fc2FvhrQlg!&I3-q1s(QBtA0%L7V@B^E$3N>pQe0z`{f?8lFaH#$Ulm zF|>Y3o{oY0Cq?T+5r8hVhenGnX;}AN_Kl;zfAm!jA=>ND=~qtw?LxoDW1M52-t@a4 zF8j3cA*RyVBjO?2FJe!TVXjN&)SGgZecn`7YY@9|(2RTgMsohe^$j0dft>sk-!_xh z0ZZQ4tYIy!8HyD&uD~Djf?$7jOs`zXv;E)Y84l@8{|{;J7^G>ttciAYb=kIU<1O2^ ztIM`++qP}nwrv|-=+ddR*4}3(&WZVEBIf7wJ2UdhymW6}9B3YdKUS`ss`H9cG(6eK zq&3Z-@P=v(MSKZtw2{0Y*VTdH=JXumPfzU?h`RZhg4NUot`rlZ@T)CpJ{| zI(x>f14c3QN-aUPK<|-n2?iW-c1Uz(3)Dwd{Nqm^@OlA)YLB+VUSyiPe;Ye?cIkLb z6b2TtJb8{3zGU59dFToS)$G~O=ly3du}AbKVb_G5ewZ`{Us52w^7y9fRk|`3u}7-s zB@>0jZAdLF_&e_uki&rBh+478U}l!g4i@V$D($NGyWgSFAkOF+ew}>d1^dwaTyJ2o1)z zoJ3!A#~FDdtO<+y64(6=jxzLA9fA?~#}(^_{>RNO_g1mOT%RZ@dO1dG+F>V%vZX5H zZ>Pdj^UY`|v!?9Ob@6F*U=Nn-L0VFCw(DVS%bO8y*U(pQ%;)r%aVIq0RJL-N1d)<;#IR=z1&d18~6qEBxWDt+?aKo4y$l4co5P(8E=vw zfXFarHejc}N2$K2GQrC$J%g@6l)QNu&m2Ix5zMU18rhJsreadBlsKj^i+j7S=(ovv z?~DSRx}lU5y+a6*jblPE3K77r+ETWgC6L1xydnPi^S&tFW*f!xK08d19ZuGCw?YqZ zuVdT$XUoX%%CK{#DghO}lOEs9I8d_{{2{)FH;_xQ0FMx<*4nctKzv`UH|SkJe9_;2L&X>$Os=aH{{hjHLH zKbfsLA$F#l*2UMKpsyF=WM45obWc{WDm8obK6eba{?a&nkS_1Kw4(QnkiG+H-X#y~ z5Urw_Uk*czNB3JJomN9XW+tYIbU**HKbpV$@poY~Wf9^X)1z!;JHzj??uH*`B6dW* z9Zd2AmrU4h03*hC@>RT2)%co{#9-v<#jew1h{2`Rls z_o%jLyMnebI$c9_aWn~-6-k$-((E1-NS3JA5XqzxxhXGf%Zd(5U{Z%X52&P_a>cZz z9mHGOT<*YyRFWszo*T}H{BA=6CYJ_wmEf)0)my6?t-3o9TKf+RCr)#=indw`IQu28 zNreaba@1T2H@9LmgDgt^2Ff8)r*e^Ypy(L+aSa*_%($PXr|x`Fep(+iM{9iT`W=iY z8-R7WN=T<5RN>;#ou6$Yk0sBZ08PM*cG_e#=h>2i4z$jYwAouIEGr#&I>JEpKx7< zf83s>ogDvliT(d9^l}q2-wx|811J>FJz$hbtb_c~{NX_utJU99>AOS%o2{7Zb;;0G zX)<3vZ9^&JSAG-dC@bsQm#A>!x=2QU9}oTFkO6x zNaUI>#kbYztktkLCZ46W?vN~UcWLW*@VJq64hj zXzbys#C5!X74a`t^``On3G|(v^$+H7j(;qofsK`|p1q!0sBqW!VCfBMQah_I(%P0imJipF~^>$kt*kL_iw`Vk=2x&jUJ==Yn(g zXNRrc1l7M>f>w^es-V_bhvzT)Wz&VMofSb7oc-Y2xR}2>C3<5B{#;5Z z-fh*MFc^MzPz)^Yka;nEZDyzP6I)8)kneDoD<4!mP8gu)(aBJS7)`=63JYTL`#&-J zna-HvBOxy+0TA%SIAYKp?%`^$OZ8KW*u}Seoz9zqurdN^^*wVnizms+GCkB<1jkH& zUCT|hjZy|!CN|{!tHQ8W=_u~s6{h{i3jeeH|9`G9zk`91wV|1{$$yIb-^vZF5eD%r z*2LtWc|oWWTg36gL4ySH1nfUSifqNkf)<9={UZ!ipVEH@rY9t&Pv@q&Q$jgi^k-N#(O#@!to#BPd5l#r zH^_)9FIv{Dh1L21W6IVv1J>%z-~Knsx(%hd(DVY>DMy#ElSV~jSQm#!AFceN$dSee znOeXn6Z+YaAmpK+bp4W)*2lj|y>294?T7EKlKw~NW|8rLf8U26TYQlO!4xXDW z+F+lSzzVKtHZj4%^Rvo-i>U25~;hfq^z!`?W8ecMq*oPf-XhRGXyx zhj#$nkK^=G{WvkPC$8yCCMMN%n;x0&AFIQ`!OAdf%#~)XW!-=8-VfhGa^5%~Qy21j zV~xFGg_WSG3(R*hY0+DwA3&GudUF?B+M$QsT`YQQwQg|kT{iFCb~R>#L;A%v>N^1- zIn$k*KCiNUup^>e``?-n<6Z>^pWx!H)iiP`myB!`_cX z`=>;`yb}<8UK}`KNBkz}qwW(>E^(spKi;V#(XN+c0!2BtCs(+<>F}z?)Kj?tH_{C0 z{D9cKZ80^%`%JdFTb&57aESIn@dj$!F*2wfbnZ2zvz7fhhN+aKY9h0xOY7-HJr6 zkQ!s!_8HZ=McKl1$pWuK?Z=>9ba`Mn( zj}nYlHpmmK_yw^ZT={VD=B+zg!$p|~imf;ruaL(5gvoo#O5xkY@N&x^QP<4M+9fZC z#-Lb33E9e-({=l#{>IqRa(ak`an(vRCr4QL{F`1&+%7o(``ukK|JYss8(_}K%F69u zzoY-mDKEuu2c$gwr_7CZv#&6pDbzm5dQd&2@FFX5VU)P^0Zb*sCx;cB)0lJ0rSJk7 zLw5i#bDgQwBakPU?ht!PGb!?U43kNB+N<$5#QXXFaRuf}b171XJ0yavDQ_t%56-*h z^>v|5As+yP-@onCy;NZSvg2nJt>w=l|Q&7n5r^X z+mG8Z13!`D@zb-`T7dd8WB2~uNOS!POCkqrxnmX%7Cbr3o&}mkIv^r>+Ru<)qpgPx zF|x1$%k~HLxwU)8mOF&43(~L0G5F$OfXcgMA*pV0Cr&T@kz%9YAT;hWCPGi4y!p(f zvi?f*Fav*p>Fw%=bkt;up1WhTV8RVXarX^-Csl!#J0jafza7kmyH1rHiHq75;H)su5eUMtIQfZe^Yi%fR(OW3e z`x3FvSq1LFCP%pNgyiJmTjQnP4CgZRbR(%n_=)VononCsS zjF^8D4>fqd{QyBS+hV4+G z^%vyeJ&Hw~fIU(=D$P1yS*)D&geVCg$onp78y`NNt3yBl6UUO>@SKTPY+CfPd<9Nc zABLZP$;)woPt;6wbGF044-xd=jIUQ~4LuG|ncN;O&oLuC*1)Gi8pENHD~3|zsqqXn z2Tm9e810d3^C7@}yf&OZ9h$J5(+sZYov?|!>R`l;^e^Zf=+jKUu!R5jpEx+dSPYN0)G;pH@$@IJ- z1@{)dtP##GAL^nb`$A{8{x|9VHBZ0o(=Z{}KSw-{wW3!=b~z^Wd0>u27&$X%W9nP< zzz)I5ki^W2P=OGj2>`{JQ;`-IfnE<}&h#lPyRCiPGq(^dSf;mShPAlSzBJrQqnU$| zM=q~lG|aNofBcNN4K%!!XSxBR`cUqhm(kd{;q-uAK-pVaf_i4)q~_TdRwP-|Gcl8R zgK978IH{xGxEyN&Q&S`$ujqaeP4BNRnknaYJfso~DbrtD9-M_JhU!p0H)cS}++-(z zeL-(W@}b{&Y1t53NMjLB{+A&IM3nIYV%UdAvhf16pk|m!ib^O#flsF6WgcDJEYeRD z>X`Gh%X@1Z&#+jJ&w-Mgh$AV%hzyUm`4+oNQ?rlg=P8IrT$3yiu8;*##@9w`TMAZ4NUrVp-A>4l6m;$TFUtwKcU@-yzoZeKv-Rx)kwzGhFo{H^{OG~I3@b^}%#4XIZJD}madDxyPEpb%cKQ{Yi zFqyP6`&R9_F!gOttOz&jQk(ZLkUBDga0w=qEy|K zw2n}|yl(pf_J9(=41p&N>o7oLsc8|!EYW+RF?xU1$F_1C>x>c)Od1|bqc*LpR7h88 zE}EVrN-vp8C#~{H>@RB=WHj6DJeywOaXSM_N}f!qx}LirFp@JlPCTEzcRrds-mkN6 za6bOdF8ny&n*q=})N+Es9q#gj@G9O0`sZsg?`>UdK z7VkQN*pRy__Gv#6Cfw^KEo1_ESzY zj#CJuj;b%e!naU9Vg4F-kyeVjn{!OMlFuuW(ccBK*HLISY>E*N7>DT151JjwG-4KS zmu9$UIbBLbRM)}kW;nOARgxh#7LIPkdYcWfF5sJmbuehJqf0x7sOwx>%cQV{6mU=x zZgq!)X0WVRt{L-WG}R(>KW24@nmwZ1T~O|{s#pxzH%CJ=4uf+Fc2Q?Ci=@*3*;bRN zfz5~mD{l89s=gQTFmTsup`qeEGVC&mJ1R+jH2WsB?bA1sgYsFfwy+|7*Rq)n#1kUv zAGbN2y~8-IQo4$xlggZ9Sllb|Fyr%VXYCg<6>Cf?=t8jys}U~g$K<<21}m|g{)EvK z&Ue}!^6Y#8CJ%T3H&G&lhN9${WmsRq<2LQCFg3K!E|ImKUd+}3=22I@b+txr&R*n* zjA(NlHq55rhYP~U&!KG!aAanert6sW`kpodeDLrfdA81y1_3K5g_pJ@`D3oVVy!>j zi4j?}w}Pqk1_j;O9n%oF1aoKc!qKh9wylY_$H?(7qeAB6?O;eUhG$m&qe*=dS{9D% zSmE?!2bw2GGUlVa!@O02v!R7fRNPIDaRBwA_kIJbq=Do z^F?oGg$5^(R!uA$Fc2XUyRkL-@~PlsOWy(!S3qL27<&Hp>Ibi4+BcS#)q-28%`iuG zA)9Q)rEkk$bqAkh|8t-G+r>9!zRk0&j-o7N?5n(P2|N~eB3{H3YpSZ?Z6#=H57p5+B1*0IAh0Xt0@y9eL#2vvqs(TBOd+7XTkITl zTFb99J0WNumnOzqTziz027VoEy{?(f!H&Q}fxBW-&Ql;P_>jXskiVLmLmtlaYTyTP zmZ*xF|4OMZM5~DSdcHB!8Ily|5TKnfhMmmlGLS*|J0GU`b$X7)Y*3uyAgka`rsxS7 zB%JZ$a57ws5F=s^L8O-3c+g3OXDU43jxji&D}Pb3j>n0Gus24!`Vq(A6Ov*kn2a;| zbs-VpR)wQsHOP+g+hkIOKsulwUEM~bZB_h?pEJw(Rn2S=$?+Z%?*rkO1blH|lw2&b z-zpjdXL#9|R^uuW)lGAsV4*g^|Ll=*qBx{Lpr$g$j_%iWzC7r7-W^fsU(6nFY7A~) zYMB|lhy|$8eXuG!*sCHix^6^~=d)7b>8Zu_IQ0bkv#R3^6&klTpHY=-%abKcpsLFtZl z&=cRFV%+P*(YQotx%G^ucmyi);D;Xt=*N4iC60>@n%&DY2wo$VOpFKxd1@(*edtGf z3QVR1>|?(ss*&5E=)6X<+X8z zPwnKw5F|9i+NkW-!lDagqp%_06A|6L(N$rOC^=yrmnJ3a#S*g+ECdptGHmeW2~;6 z!#bCIRCn14{b*KX=5LIeSOhU`;+ITnO6YfbVNO&U&Lcy`AUlaSd@hqI)0iQEk{i>F ze{8^QUI!FW7Z;1w2PtF+K|m79&N_-#C*B=c=!u~^u3D?z9gcI)vPq;nB6tsTnPRga z>j^b8(PAgn9nf;r!A`p~aB}bUF6r%Ca}**FhZiRBT9-;41C{a~X!}-{O2v!x08dth zxG$Be4-}8eb0K&74mYhppJuD^LtITiQ5rOu`VoHDR0tL2ZsyDpHV)!Zb5hP@v^*b4(m2CsivtdyH zY(cB!1bb*hHipw5$4#q0Or?*tm>yN3*B}2T2l$3I=S#mgzd(e4+W!6-hWS?RD>~^r z82y(kI!R?i5lb2SQwC8DT(S+tvTZRL6&ixMX6|)`_8>X#(iS?%C$mi?TiDZ0sX!ana*TEYT1l=E6 zFPI711ViVK-~a{hyK4}^z9p=)-Y>InH?4BCs- zqd96)$4P?X1L@A{1CC&)&L9dLn+J1jG$-o&QNBbyxe>&_j+?yz917@Dv4=%Nwc*g{ z4Cog0>)I8TBBuG|yTtHc zZys+Hh1~ELnBwKN^-+WRDi{yr&izo$Qb7sxaeHM#ea191Dy|1#Ld3Dgs8>0hK@ZbC5SBPk|RmnV`LO^ z9c%p43<`QY^!Deg#^GH2iqyX25C(mTGSkP&tdh`JnGNp!abZ{~Mx?reV(SS~wlj~$ zqlWRA1k_95fFY3YzY>X=)>sxCaY8s(g)3L}{Ib0sYZAes`t$V$Zm0>4CTZsWlX$=z z4{pAr&pIl59o{)e^i5f3m=;$>skyeo)P&YJhALwl1r4F4pDHZ8NR<+;l}J@)+Yo(Q zygYHBJ)<1uzNtg(a|JzQyO}HX<*FJ#|IZMYBu<O3vkV6p}pHKwQ9lp-{DP$kxXhc>U0RZ?kUv9Z2kaZbrHR;Q@a zE`xkFIW4@-ZHJ-VSj_Quz6PU(LFRzUvC2&@%DtQ1^qof+*0AS%z2r;+!7;5Am6t?}SbW zrLE6=LT$2D_0uY|sEJrICnJd3Y8%IFn0zYf{S$zr9r9YduKhF`Q@~~`w3{Jd+1AlN zS(J0C+u;|T^|=CZRy@_xLG#s+U)Uo3<=S2I;0kxMtKTgXORd9Zjq|7PnuQq^f_Jw% z^|9@D9wJ6~#0~EAOKzv_nfL2&$VLs!`y>_t?{7I zA-h>!4a?#6Q)+Jt_GxvUls1LWJda5I!0{DOH*f!1YsHYY`%=bvt_h49s4Xo=mw@@gaJ`3w6i~l^W@(f_2 zSpGhhW&cr{%=C|^va#8B2GKW*DrjTv{O$gCG_(0H|9{mtK!~M`{H0xQ_)sU53xf!6 zX;ncGSlpbB>Yo(Phn4P|3%;h%NJ0!(;kXC7Lb`#@_9Wge;yFE{d~XORrB3dhNuw_l?W9Nl|+xV)#|@MlmX4% zHT|LUC@Ch!j^G=v2=sC*@&o7*BzI351|xIn7M7H`GomqAlD$9=lL!;_=sY~|Id1+I zC?2y~Uu}RTbGf&uojA|8g&Fxs;kBb_QTgx*(PQ&d-+1thWe?gFFLm@->=2tOP&oi z&uC5epi?A+i~dGMMjM+&BV{_W;^gWG|16f3@~1{Ci0*TCMKPj+=GO zV%K_j{$NG0m-uZyrv@`-(O(R%iSPW&erEYv^Wq8R1?P@rsg`&G3)G?E#3H&2(vs!( z#y^Eq_*D;{19zns?Q6MLBH~vHuf+-38iZ3A{S;IOtRwLARA$!5<)B$JSy5y+g3jh9 zau|ePFUj=S=B+7*__E1Yc9d$C;5J_Fo1gVZ({xjnOTEe#LF~uF*xYy$3>ihLGTJWb zbbIt$UyxqR>9aw~hJEzcrUZ=>9@)!~Joy%1R`ro_$;4f0h8~sQeCg(ZWZjEP;o_`a zh%*MQL`DLG_)heKX&*+TUM%$^LFvgU!I&89NVo7C8>gO*i9?|O8Rvd`eGY{<)s?kk zP(b#cHR4u_UCLktT;374iO2p%%bi(eN$_+b;!Rjk(sd!*8W(TjB77R2f)AgI5CmID z7mMQ*+-r~M1b^f9NFI$AEX-dba~L`@FTEVCM{mEmTDHrMWM~coelp@#Bzq%zN4yZ5 zz7>ph0aY@P5HFTT$6#yZ@044f=07j|C0{(zQa0|URU`W>*sF$(lUsJ=NhZ_;0_-9t z*ks`|1;A*tl8tyo<+9{NVw5Mb3L*@}g$z}ZdNLRz_4c^M_CQz?s2StGcvNWjkw{`@ z#-558gKEg1EXEzs0GkD!a17#Ky(YI`pmc9IR+Q)-kpwSFuBl3e#JBllEUyTz>w{df zktOi!1K^kJ*qc$#-oBUUr;u9=uEg%%L0-*84C|9)1O);Kv09>)R8OHl5eQ}lW_}o^P)2Wk5ZhRKa)2=|sg_(%TtKED z_)wZ_5C*BDb%@^DsNCZ^&*IH`w)tYiBOj%TVX$h_BDgcjO>+yO8N6$`Bl^}^7=7(( z_Rkd#oBfscOpMTK9a~an1{L7FX~t8k_KnvfiM9&)0!-44cPX#L)Cg(Ml9yH zK@fS$dNdu=SDjtq3uukJnp=e;d3R+RR&+#?dlPypetZGtrc?S=;1gNZF22swYnuq$ ziLECJ!@C?6DBxkOl2VPTdDBIsG!|v!e4Pr*Ip>1+dM#p-BiF0msCI%ZjA?#0O9)5; zn4Lr{r{JSLULpsKc$zQ#T=L~F4kl{Y#1Os1o0NfEymoKZMVB(pA}3aR=3R<*iuK__ zY-3-;YPyuaj2kHr3ehrS6l5{KUb*|A(XSCRNGMX~1pgw5$mV+C568yUEvfrms@lD^ zcu8Gh8hGw8(dPK(w8V^Uh>%~Iz?Xo{qSY^qpuf3JuaZXYkv2Jm+%k`OP%2bEsoox| zad}5diqfNqlOkit6UQkTs>P)ikH!*8sSfV$gbsPoXBp>*Ae5wC>aCiYb3+59yF?xA z0v~hoi%Y40;|#3ge_&ki0X|S!O z|1UVc|Nf8vr*HqOWz{T{lvYqaVI54a*|qrkM<^c;Tb|sbJ=slJMmnse&G)G zn2CuJg-B!b^yfKYA}`vNp3L^@0f)eK;1?`|kS%wF-tfSFn`YS?9ag9Hz(T-7WY8Gl zoe7|xJ7S|sp#U$jP)u`2{#eqqll{Q7lYJ^^_ILcSK(JVVMq4@U)QBnUX4~0?JprZ= zR#<*m0$3dEW{MZ=cEIJ{EqI8mgR55GiJefND!XUY00Zm?cDLUEq)eV_AJj{tzs)p|ugxQD1%f?ESR9 zbEDOYe=teQ*t?}(>IF=sK}DFea~Z?ZX8vw)L{c}UhRdvb@1ra}{oJtO+~4bIRy~!v zXVmOUm=PFhG9BxqV@*3vZ@d<-c?{AL`zg)h(pT1iHOkBlF5#o9mfsa?BFPpO9?VwdF)EwleMWtCB@wO2@0#8@5>K?!IeomE@V(%c%Y zZ53Hc!OU(oc6DDAYdMCv$hO{ktVg~7RS+UG|7y5yA3krk0lY zI}%R)CJKVuzlq|oR;<-Dr31{Q_h7YI+6~?xi(d`Vq#4tpSy~HZuIek}nk%g=e~TTs zC2*^+Or{O`BcH2D>QgrTZlalHK+YdPB6T6$H!b+l805s#+##-L&}StCslW(E#7y)S zFju_=b0tK4X0}Za@KWqn1b!X65EV9 zxB+Br)*Z$t3pJ(!XPtw}9gyIdB##0?iL;0c;Sy{{5%Jfo)$2K3=x$0(Zdigoj8!GH zT1`PkI!2LiagR-{eGT3L)YQ#4ZP=Y{%?c+2gYC77A?$~{sBj)PxdNLpx@esvZUu! zJR2lZc!4V}2yHY&Cw0+tL9Ryt>RXhY0Z-jA0QF;1GA!I)w!`g#C z`s9bF$sj`vqIDk8&*wRZV{dmeE?+lS_=wzmWPWN<&T9cM6@4sLLMf_^xiE0&`IZ#Z zx7nbWxl4Ne$MV&%li$0UE4!=<@iCWQMG0qsZ7>O}hhkff2!o#Ie3F3Vb z3U_k(ll1DM(2TfxHs@MNaRG_{)&etaJ}mSfwpAJ(|*duh+M%yjkA){!m)C_ozmE zex?r2B_TTr{7B6e`sxZTdCNY2s~+Buq$VAPo=c{Mlr2P+RSy$FPAbbkvT*n{aOg*r zSSl)hkCBgyv_0eh&|}+hmIerlR{zSApnved14L{)BO;)EhDS&u!{ypLluu%;UsT4r^~VE*m~=Rkh6Yk%wM{B0t;?jV{r&Y@ zx;%pl3UgEzCJ3STA3^K1aY6xwtV19SrG z;KpiYqNXNX6(YMBQ=A?2f0w>r{(`K%(<=ON43k?}bWUC$Pc$?&ipRG!QHz#Hwx3L6 zs6(b$J-b(UFI3& zwb|J?CW_O)rr#m9J25fSlmeSyYWBmZ?P-A`+C72QEuz^ygYg1~y4dB}-rad+zTyqg z;P09oEB{C+v z5#aeOtLFzpoiVu6I`?!zYW+pG{<&^-8zV=?8^ROO6B)T@Ox~Tm4ut$h-jz&ZuNIhC zL^Q>N23w4uWfc3kJ5@NLP;`QCrGY7a691?bkK3Bo$gAwmFrU~H|A-i`BaygLmX$tF zRk@y_2UyQ0!_I7>9vY}blxc>fZFXNApq+nMPtBH)l$8n3Ca9EILdKWA5LdLSFUH#^ zkWAQ_FAT-z`Ptz(o-9YuIg=h#igUSRD~|Z(5XXLt@^>h8brY?a*=1S86(9&Zr@R{wFt&*^+A#30KPca@PKd2Rzja-1F*c|(|zcdxE6rmX)-yl&t@;{;K|12W= z?*&uR$llt>@;?h^m9nN~f)Tp+CvM)`3e2+os)o$|a#Mf?EO4L|Hfgox_YTM zmkM`?%@wW~8%m9PASiZ&O4xh>;m&@regmQ9r$eMDUZ!%t;g&{Fm;=u_JS{G3;vMrX$fc%5BdVWkwdnKN_7F=ao-m)%P zv9#1Ez4|^B%wVb|T}QGBxeljW)0Tq-lH^R` zq>1qD7H_FaGf!?i^RApLJn>V(TcTM{3i? zQ?9y0C9zN4+*e{WLT-2|@dWM%M>!EU%+_yP1gV;DF#v417P-|MbxNb3O}!$|-0}D` znYa@NSR=+oeO+r8*uiR!2uGFc_X~%@Wg{}Ri*LE=YF-?Z{w$JAn@H?}?*V`|Cx0ka-AN(Uc@mI3oTc+1{f$SrHu^D^!^K!{|<E>%+~N+j{F z4bPVlSf!!qxlH-k4XOI5*L(x}Hew!Khu;CV1f|4gPnD(|zJne%9j>`&+PrRdyx$*I zeq0ZVqX?rIp&(JhmZd7$sSPop_$Yio4RS!KqkNYhzM|ZT@JajmINMT#%?)oB@)g1L z+(lQ(hwcKki6so5QIL3z*ed$FqL7G?e|Bd0Z%D#LXa>@6CO zs_jZ1I56bFeVhj}7vzb7Wc~~}E}Cis%jA2SfyX-9Y#sV+%IK(z=<5zw;_W21_+W!$ z5y@b6dTchp{;3LMO^17ZKrBsiR_0u~%$L7*Ut{a7f_=-%_NMkER#kw`rJqszm-e(r z%9-b_>ZC$}R79Ocf9;maorl-vOtO0AA){4H%2wqC`rlL&_=p)vlVUDbOZF-r*$6ZE zkMtL==#ELmCLDo}q;<#jgNJ4+ux2{ao~nI)+q>9G`ueR#>6R##Sp9C~#lmpsu_db( z*_QE3Q5WgsNV}Cn6~F#ejrC?2GNZGic!F{n5ULKTja!!%+47+2c5V}@`s2{54kJujMjja98UHC^jiHhhB$A!ks2?Y!l_zAV33$hXvPS=4@0Fm^Bu@t{&TT?;q z5nIw)y_O4>n_>%!rPlmnL9M2Xs0RgoO~r! zmYv3jAwhMAa0@xnKMKRCiMPfSMVf8(Lo^{9C(^o3Mt#(BuS>3g#*|H*=mNZC!TjCyAv}fa-+S`<2pikeDgX{PuHld4 zhT!ip=5$<#Xct+x9~ej%r?PcUw5FwJlRjcCe0I{goQQf%t8}l(PT=^2Y)eGff?qR^ zzr3fND)+k64;k55>pq z==Nbj5RZ^dVfJ=~H)-Px2xu)Ni4h_~b70&U(C_stl2(;r_WqW)t&jGK>jq z^?ydBSunjtWpbOA>>$1ow#4V@edHQ-5lNqkz*0=(NA+3_ zA$Zh}{6MsVJ@|nK`oSIzl-Y~V(?`S}A<7Ui(w0T=j>6Gx^yUJ6uv7TVIe&+@{)qTL!9vM=BxMnjbNsvEhV7WgnQ|Hhr7pLd7^0WbwCS$Pe zzT{wcDyJuctXt*_?vtuif+OPZ4o17I%vGUVs$a!+TQg+M%Mtgm7#=D25azmSj51qE zb}|UE)Ho&A<#s#3m zqTXhIggk&_0t_uL$^La?u;Po3rF_3@t_%Hte`6>ZIheWsH}9fqA*Zy0^M&(d=aK>y zKK(P|w>G%N0x`G4hjME1Lw)R?upN5jKhrg>(0(LP%RR# z{B64b3Q8mud&Mp%Bq?&H;_WwNi_%%M8~^=ivzE$jo_`GTJ6|6Ph$;@-Mm5?sk9W}^ z3>xO9twBs6DjcM3FEH3S3A1FV7&~F!0x(%Smt3u8KR*Nl#9{j!d7gOx0ip&;qqwVt zfKWdH1P)@Ue5e;L@J3 zZkzzz+W;KHN`{1yXhPEZynUx(pAVD#v))V~yM^fCA7>P<|<6{>PCTj`-01FweZ( z6J+!gHQ^G+VA;vr@O{xN*#&4ygXcn2_MZWd9+VX~iiKHUg;>np1GA+QhPieY15Bvb zW8p1CbLj0*BaOS)x1(e7d}D@^_=w1c;hkmXXcDh8$1R!SC36Eg(^2-f#GURT{yur|Ny?wZu1 zGBh}!wt+QUDhz%bomx zQ<7=v5W;olsew@bhWr)#E4ddX{c?fv=9pXqaUQJEs{dr6DNWgx0mG#FNODpJ#blg4 z&UKhRPHe1q4b*wOJ^aZ*fs4~t+Sr&2O8i7@1Z-biT4QIN%RQfY463?od2Kgl)!^u& z%V?m13(c7p$^_w1ZhS@dtj--&mDWc1l~XjrYP+;R{pA60!} zV>>Yit$Pt;SVt1uFs;qeRn3QnkwGOQo&kjoE3xhZy;p<>7P;HXs;qZpln;MM8DQyF zxR;je*z!O%yD+j7;T|bbi@R^xKig2a_K2jjdE4D)H(&42lnh42JEUF@_LJNJq<&DL z+t_c@%YWf+X!Zv!=B^-8+xyY+1+yJ8wq!sL{~wgrfR@^u_AFi2&3KcDKSZ^um(6^_ zlrot%P{|%wo69ok#-@plip?uiij7Dm*@1T#*USPx%}vvY$d`z`TO*nrcFF^C4O8{< zSR@ir+a?KkNyc(^+Q+diZ0uTtVOULCv=rhb05sLhk*3oFwhQ2O zMVI&?KY#n7F$SQS`9y9MWXowLZkGi`@=0%DyeUZ=#k>e+wV=1;KVoYraz%@F`xTn5 zQ$KrPo-5d3E~cCWX-OBI;xr#oNSY#oSyu3j6oQz^Svk}El9Z4#2wi5DzeKNja?^e^ z{hfZ=pz5y8Q@o*ABV%~S)O;-G?6pB$^ZWhV|YS1SDXIR&y8XndO@c1=T;u~~DzCKju0fJB+7`;k)j0JV-WbrG+4I{5IAzEl_z8>xYtAoRX;e4o2LDB7U<+;qd75kPlv!7sV$ zUY>yx2MRk!$o$^EwJ*3%$e`9pZAL03(VVeneb#9@Se8fwMAPfma+wt8dDOuT|hlXroM84xIeV zj@wTQZ?wo2p?fRvfdadu2zmipX%;c^#;im5h3#!JX8P_3Rg(5yG(g4K-OJf(fPWc?~?aw|*LpR2yBk`{^Y zyI%6U2vS3pu6cQcB4tVT;~$yD0ZBE^46ttr8r;Q`o&H`35rMtqL_?=Kml3OS*hI4VZ*vT`3&Fp-j$z1 z9vJXpGFD)c103+e|9toNj&^0$3#A%Rj7(WImrUEWSR z|5ld&JMcIOMXPl|LiKNbnp_bsC6tXTj0&w>P4r$$49DmNOb!6Z&%?_ z&p%^+qTaUfaVvMeB^JN)T7)BnRiOoG#R*r_I3);kdk_`Ww%1oLT-WMHMjAd~j_40Q z^pF!IK6;QaBz$H2^Rhko$Fl`rgVND#dGo0!=4B|>CmdRS)H9o-Q8)~o2n!=PZvYSA zL|7Od(htw@7PtW%atlLK1_hs2OL#%G_}n?JR?DkkEs`X?D{FWMS1qlS z4IG^u^bMVa9Q0lP zn(y<^1a-8c_FpDO+=AvU)WIp^tO0pmjl$#vcm!m+FaUx{VF6s|+G_}?6E&-w5!ZXN zh)BUg1-!kiU!l`HnA292X(0u0j+fb-#~Yrwl-Qz04p7Vo^b=A=i)_DNp2PFhuy|1I!}w;8Y34_C5ZI`2oI?^>M1BNm4TETL9D_;q?KluRDh9}_Sor(0v;AnE)F4*Yz{kk8EZyW<$|uehv7gtdgrEM+=J znOWVW;iYCu_`)6oNek#)>HW_JIT-kU zWt@_MV&L$*igQm+DmUIF*cq}vATW!zGTEt>;2E15hTT{~JTyqW(o`rv=*gpc`c^=? z-C*nq5xaP^d&aZrgyT?~{(={!tUDWDJsUK?Pgz0ADs6W)wD8k*Tyzv}JB@*7$I{Lc z1j=zdpp}zd|FJ1KuPBjdkP(L&PqCJ3b<<)d8kYNKKqp?cOgJZ=o<)7>9Ks9R^Fm*} z0oERMS>haF>3Y5yxiV>3zWtc}VXFY+?OtIErXp=VmdNq>gp%`wyR2{fud~v>1mQdW ztrJT7TPvi0YdZ6vXXXDsBf)VUG6Q_@!dE0RS!`VW4S|TOixG`~dIgZp&H&z0> z;tdNQLhyN_1K@TF;SEO+VFIX+Ha64SI5VbyJ;D7T#O^?EWrH_+<0rG*14|6{kXNX# zmMT*lm!l=8b&ikizp;JMjHnt%6lyEzfbJL_ASJGuWeOl2$nOIx_qq)kpMBa}`yx^e=l zf!{r7^^*!{Z_>zLI&nx=yDchVF1<$ZLzM%O9up?_Lw?wivq15A&nEFWYyNHHILlGj z=Pz+#FXoccWVu-7DA_1^>#rSuKt@=MWndy;Ei}4v{(hL~P6!wYyb`C4p{N-4$ulvi zQE)W@nGpt?Q#Jks{kc(#exnD=qoTpeRQcVY=Ozv3Tn<_RA0rHK9Qd)>u3|Mboa`zcHo>PWu#Yv<9{hv>bM z_+Y~{Dp#<3GB!+9lHEaxN$oxwn@ zDEkzxf$y&0#P=V7tQ6wKC;yHD!GEh3WdC=n|9=NaC4C3e|7e-YR=oO4>&k7by>Ie-TJh< z;knIu_5Brl#mnOhWQSMD0m%`8nZlgJl*C+RlyC5@ZVj3MMLvMJbpT}$Y&F;eHIYW9 zvn?RorAd)iOJkAmV-7K|T;Mtw*?4rHY0}IV+#Oa19iq6P=mOSWUK@& z?BY{iG{}1EM*R7OS9*C^VGIAFYTp?M_eoHJIZKDvX^2s_WE5Kb;M{6)y;>C-Zlp_e z7(;3K3WP}W1rH+Rfu4ck;FAXj^djxedv>kV29b76tB^D&pEuuXYCIGsj#`3~nKYNR zx+s2#d(v;0L>S8GkPdXzC&(W3FH+V5!8n#7{SI04byS+5PWUT@SAP%s)ZItolTu(T zx74>ZZgHG4STPN6Djp47u@w@>F=&8jU8xAWQaA7NDBU4Kl5{2kKUoG)`$Hn0!SCq2 z1Z*Z7$>_`MI3dY0t(T*G4S6$xc)mhnT+)eXpvtv2ZDr^mv)r7>M2^6|(I)=4Xk+;Q zh_?R-d+UGsm2xLCvA9TS3eZB#IG6*Bh}S9AAfgmVgH((LOD>2OMR!PRgMh8V2AleT zQxr&WT?2R_8!QzGQ|#vZT&JgJJGz(-XXN&DfBmS1R1K{ztQwfLANirL(FXzo0)!!j zF={Y(aNQXWp@u4vrYP5F2N8){W7yX(t<_*B>E2Q&=4O<7#yOXqe{~@|x1Fqi?jks= zc1gK?r#)>>B^V z>Z&yBTxk=|$nm;{aG?3*zO`WWOG?ACS%-D$4A}dgqR(p{FDS?Bh%)=}SOyT{ljGez z=v2LeU_)}Ad)Fpn3&MSPAGQrGMuvuojjcqQbpIqg@2r{QZ7$NC`uXW5#8_T#y-$aq zTFk&*bmb^bzMpH~IL6Av^joNL2!9N#kKOk^PQOc0n0~+#CrT}kB3i-Bqxx%-O>~qq z`KN=7Gx%?H41ur8oc$I*w8^RgKA=RiJpzraYCRXHc|c7CW%lj3HwS{ngaPYe3dzr6 zi_&si3{^VDkc!-rONSfP1b-tpsi4DB;zw}S6`C7&P|2QugfQw}2Jye9;Fta_sHp!( zQ2lk8>YLjbJNy$*$=^;*>vYK6AvMKO0Q;7PSo@ZIP;fbJ)R}{!B+3;`jo;ugQBaH$ z2(SVJ=Cy`<19&HEv?N7d60>}b!`9t)oa&mAzP)~agY(l~piryQD-KW&nbqhTtJSV- z;Yg6I4uB$D{B9q0Z35rCcohH%VI?H2Ugfr+yY@ej+ZYNzq=qX}BN!@fMbO$nR327+ zPlc`uYtO%rVU&FttcYt#vM=b`INI{77uDE^Xpm#+W_|CI$r6{BR-r1Yd7f^NJdKrd ziI|WLG00``qMV#^RVmZ3HH!IghJV{mXBY2UVr|@46JB~b3|*ud$FT^>ebd(MW~mw4 ze=l^en{QO${FQH^vR;7&k!dzYw-tkgGm1x1q^IP>0d2^St)5RXQ2XG!Jdi}j?Cw&` z9hO)oSRt;VIIbowE{TQIc(cHtauxi>f>K&2wfraOq;L!`Nx%Keoi1rWN^a?vqWh=9 zB3H})61VH!xemjrP721!hEw#6uVIA{P#>kA9grd}Z{FSwlnFOY;kiA`J}xW$#SIP# zL)QH>t}PeME_K^<;v2XL*=JClj#lwAp^oR4N6EIp*s;PeHYyj*JIG&Tt5^Jusrwrk zYkv!jf7`+FpLd(M&3F5+BZCl;kgfCoc?>FRe~-LE_mRP8CknZhCQlZiOgboHMy2v8 zNag zb{d0LtSg%?G){CXib4P=1I|XiW6o=l2eQNe%TE#TyWt*{4n9v(j8CnX9N+^`1}d&$ z8bmJI6zH0OV&~|K#2f ze$B2FykkIDcpv@|h^HizQBBcuTLW0fH_++&ff(_vI2q4=Bwwx#%7K>8TuepWz* zoSV{KT0n^$TX)&7li94CX(3UEcIy#jrmH%Vtbp|CL8H;efYTYX=YjxKmyRrvY6Aw- zL5cZ$1;N612vmq6w5T$9Iz{z$x_Obla1%%mnO=t_snyxKPHQ%oZ8IsimLL~uj(9C5 z1sN(Yn@6*lhBx3V)$psRbk^*KNtZzlI^=~IHTU(|yQ#(;N{1>r zeBE*)kiI&vEiy4{=uAhdZW^1T=$k!-IWno!x$>LYdt_ilmAW_vnza5xmfe%`v(yJ; z)_%t19Rm){1nQyYyq)KL@#39>eRh}B$THnHqqzvpm&w{cweYz&F7ne53C)m_?S;L$ z^jZ4urpOC%6B+I)MfO|eh*-<1QFHew_NC}D9Ol&XDT^0Y;xp|Ll0(20SL3*fe`+7o zBtn&0E)Y{lGKJf78U%gv5<)eiNXg|SbBFhyS&xV>(58VLj0kURV1 z!F*V{`NoiJc>g>q*2B%EUZp%Uh>o7E_hLdmLxbWTtI24gT0WYVsxo$gc$u5r z*(P5g>K0$&($OYg;!=rC-b;Q)HM}p_He%0yd{sWKtC{9;RXD$Eox4xB@TcH*VX=I9 z8`QQ`a&vf&G`8fV5>$E1Y<60_gv1e&fOrWc4)FT$4JV3dYu`juFuErQBf2xIXRI)! zdI%xs^+rI81+xQO4%^ciBBHkol>RND0L3lrE$mMWcOduDxR?#iE{&#FzHUOQAJ5@# zsTJ@2A6L6{E;Et3v$5MnK|F5nUj}~aCzIt#k`XHL=2GX~(WN!nNScXE`w)t$g|O@u z&Z5~4N~9vJ9A_O{T{pWH!E?UX{a@lfc$?3WzB|5*Lz1`bWVg{eMgd3+H{t*6#T~&} zdsqLCT8H1s(0~6-{GZ?E{}H+Vd80+kOWPvRBV*4?H;bc*<$Iw?2#~E4G%DDF5Bdx7 z$q5l_IJh?3>{(c=uNoAR#0GtJ;zGVWuE8ayxNt4Al1uw9mq^ zA%@NK@J{2F3~(oxD;z79-gi?}S}Bb856mhZ(_o>OQnW1k?kzr)uAQ8w^DQ)ZM&NoZ zwMt}I5Jh4vKXhkDLnRpLMNxPLJISyE++@&%u9dMi4AfD$8pAWYo>xsSLS3MpnKt~q zKC$Y*#G{N3ugF=is1LoD{2Wht{jMjXzQbw3E&34Gian~xmJ~V9X?qgY3NaXfWqV$X z`+LzcS~uXhqz3ck@D`vnLz$DTK0fmucIF)h1Qg3?-r4ZY!(?P|My_G2465mE3<8Dp zGEco?TbRW;`VCfY+(`6kt-l8pBO&^04w4k>=?5_(`ZWJ=d}I2ReH1fY)jGk|Q-ict z?{mk988!4izs-5Jdq74wHHDj@&{Q>jWU8Vtj zLeu(J;^3P-|9eFI+hOJZd6!w~yW2WD(MtW}=U+r8Zd&3yWi#AUO|SVSdh-(z8P(%r zR*n`R*l%T@1!tam-D#}7_9tENe`Z(xd*@%$-MzncXw_XlWe0$T!GA{!c; zSc4Y6#ND~LUJ|OJ!htli&w!JO{fGP;sz?}2b z32koxjC*8yPT*H;&lBH&%m6MmRH=LTriI~un~eFN-@gA^)Bi{s|JSvRmXo9fl1JxO z#Vb_SxMHP_REdW`WFbI+`6;kBTieOlWnnZqI;mt}c%{0s9u_1<_5OobA`3%_02Oun zCFieMaJE;pzkVFa&(M|Wiw&3=TpfB$^mMgJ^5f$OXkyYAF^uMO2l_af()ro=tC?3I z>MP^xR0Pq;R|xU6S+T3s_P=ImDgs_u*6f4LK~&7y(4i4UQ2U=ZAC_egx8-*NnXjA| zJ#B`VRyb2i1r=ccLNOOpPBX}Q8)uWz&Ya~m3bwK}N$Iv6Ca;6vD-XbNnS-v&Q_y|T zEsP=_)vRR0X0Jbr@le3>JJZSGrrDIRLBqg~hyLTUQgl4{n9kHh8&f0hORt}j_ z5B`kG54A_T+6Z8aCXL$jA0=Ix_$hgA)XXOmz@zCSV%hc_WaNGdu?8dw*fmHa@x$E! zfLtmMDDfPc@Q#>HLLXr~1uwqSb}m7_P7Is$(9tQN!$6;Q?XH198bUARD$UsVK-T=C z85^fiUpOs{sf6t&J#j>LZ`6l*={#kag@|!uhj)jTcC>(qFSI2^vMv)%2%wI7uFqo z=jy<*b4P(59@I<~ClT}^aR>#04)s080(%lK=}hFWFoLJ(vBU5vE)!SedM)@;bxd&x z(fV-1h4@3uZ#(1kM?S5v_^`0}&#@^Ml#%6uv%EjQXZ3~6DQ#IJ=kyGoc-}99GdZ?e z7$lg0jG`KSp9mY2a{fuA`%v3KvO%2sv)Yn;>57^|SH?fp0vB>{9YqU&s`5V}{@SK0 z#?wc(?`I!-ZH7s|~S;x03OQwfO7`;fGK6=KSn&eOG= z1-qAzN9DIJKyL*az&O&eJ%;iF5rM@9^9G~QKYHPx3}}j&i&)HQLI_WB_k=Bvpg^z~ z3XT^^9*UrQ`t1Fn?%PaiigBxUAd%{Eb#$k&Bn${eNa3BG=8w^>w(mc>faoVm6kVMW zCg|55mY-0SRK%r-P!KL^dXN{QwCntG)d89bvt-EmtFd=G?nW9zc8rZ?Uz0&*^tn0e zYLtz1zcUJofo9xIc$ipp-&QhaA#3YC1qwuMWTt;+d}g>dM;}O#QxI%Gg!NqQECdOT z!Ak$c)GbY)bbxdtu5K6xZK7?yHvH${%-Hv&q=}hhk)JG#W;SFSitr{Y!`JWwE})p% z!ThXTYKq_xc%~=cPA_?A{r))6@dC*Detl#?Xq(U-$X=NCA+i+D(6E$jgV(|#wDj2e z&kO_dA;0Lnl6S?^px@AWigzrbWes}*t_;Nb#Lwlgp&u#SQpS$aW$3d^o^cBxbB?#3 zFsA4_d#`~)(CRe%;M!bMc159iP23Mq^#Rpx;;Wr8j1EwP@}QNN;o@uZfjuFVO=c62!d6TPf5_-mNU zFBU-!MCK_RN-t?P^0}>Y#JNnp){vkNs&lv-$4|>$N|?RBm;&4@mXvvuo+`-dvwqLI zEocd6r!?1eH{$|$N*c_-rwMx|7tpb^nAOP_WLJmFD-_%`H+6XfN{D7X))AK!D~L$& zSs|yH^E#MP$RQUfo?znO(j|Cj7%$B(Zq6^$>@=@s{}E>xTw)=??%K?xhN%24Q54=7 zRLP1NZh2%jx8px(rog%+y82wDqd5O0w_;4vPScaj-8OM;AVG}}?a7#&B-P{)z zzgQ~_Er7P$9%N1u((p0+j2~PU`l=#F`o~YoV03ULFZ%x2W4BSD10fnZK3{!9mZ%Wy zS<3KF-91SWv%oM7$M$Y8D0_!K-7=DQFM#Bv6N$*g*Nut*1Pa8?tUnG@>OY7b+T_HIP<1 zcBEhyC?Q-+cjcNX@+b|D-Ke?Tg*JI7soPHouY)&ql5_A@ji8l#Q!gNzEHO>k83Enp-=oSm4G+{<)m3H;DL$r37KPX(f~G1Zo%c==cqakT zCwJpAY&}*9Hc@c%V>5Iks@D6JcdSS#{b6=ttQ5jIZFtG1BHk(^Tz<(VQ9mfbDL=$M z&aY%1@FL1+cD9LyWwK62Ev2!91u0NVUL+Vx56zZH>mUyru8FrhZm@WRISRRgh5j2 z+mAydvb>_Ze6oJc-YY5xA$Vbn79Mt!Z&!JAm!1kD8C9oW)RI;|znfdFhN4}g3Ji^& zk#ABMVG#*}#-u)e6f!}*!oyj4F)(>jOJouRVG#{Nr844lHqd9W^7URXTcaxFqz_bC zd4izNxY(viOIreQYoe?|6|G!S{Y6KCCbsM|Yz@9nMB?Jq0P(H}0t_L!B9s_Q%)wr$ zIDfwenK43-)P6IgF_rDmTyEy9Q(wl1IsEbm!;Kv|UYwbL$ zQ-;|oA=tFOBJg)TB936L^Kl|){6VdXeryS$3-EH(L21*?O4HurX7SNZ<-^$;Fm4U0 zyhDBTN7t%_SsSo7N1B|&Q@g2I^~%gf1JuE^qYvhZ^}&PHNn-O0VT&qd4cgprJ%%-e zg+ql!o{5EHp`-K^K0d9`euf0@<+2fx*vTc>sZsRHo8!iaD=)m>1T_N6id)(XoR&0$ z$x7;HCAsWijP*7sU{8ySXC=VyG&+S1!_Fgp*=rn%w~}1*bTVvwH|xf%fAop)_F}I0 z(2t}HK}_avb0IUfBc;U}B)D$z>x39gl*{G2A(T6{#Z4&yw1ujneN9h*Cq)Qiqrpiojl2ljpBJ7Yz=cL z1vn<}ppkRYE;{!Ju0KOGUPd=wMj5ZEBzmE+*}>fEvrN+FMQFHgSBuJxKzU9F-#r!> zfT0g!6^8DCC-D)+c(A--+d?e8#<~IAY9`>8iI*Y&Ga<}T&zpGTZfP}rxH3!~(56Ns z0x@#Sw9j%jS17w%^qX}*u~z-ANhdhe<*qx<7n|RIs@4>2I_HgR!ImJxCx6EsPZ#)>AWSy8CqpK;{o3F=M1~-s z?X3K#$=>BrO~=3n9z3%@fkyx`6xMHUf6U#^%?&TEHwMRFB~S1@VP2nDwYi1IF{g5e z_DpSb?&Qy-ykQ0_Lt1QuT$893#%rK`B)qoaVk%r-F;T1Le(NJtK(QZaf6+q_ZOhRL z@E<=e5&w=1{m&Kjf3bL3=kI}K|D6$Kt6JJ&eKVpO9ZE^8RryUP2VF62??Vyu`?p+pT+P3mXM9W85sipx8NWW`#*)*b60* zp*w^eLw6+9$SZKw5qjImEq+&1Z2Xx;aa;d;I%NkmEn}9b#4xrZ8hZE0wRZ>}U#dNV zImWNOvM9V=AO@X*P~&&>5s=BPqddRqb!^P}cMT5Q>`}8Dd+O>pLv!XnI%b4ellQK% zs1nn)KpeoPA}=-Wiq}QMqT*tbkG|)kl*vKGF|0{A3wdqnVZ;o2UF|g4xJh0*k2DkU z&Jz5brF{tBUp2+b+{u@83LB<7J^+!dqfv`k&<AZpyZr46;@Z)qO->`f za}DOHIT>y*6-!5-$G+BE9YF@3$l&RqDc2&O$gfC-$L8L%+H*Qhnf798&xpY ze!ucC(@S?!r)7{3W?XHd;v&X*CN{=sLog@KG5{K+_DY<|SC#V_hgHn*am5KK1N5LHi9Hj5sm{jfhcZGz|qcS;2$rKV`#}X@hb5!35S#aPix(u$qRMggp z#LhHNfHfT4XHMu)cvab$X3d88`T10P1Iwil^`{GQk9@gPSQu$2H1H@EGs60cyO?b zye$Yf)-}v45oZGEkM*LCY@Cks*9Q}Q$LSTw8H~fITSc;2B zt`N_KA{&EDo}i5Iz^73-B5rB8`wXEW%oz^qSZ5^!TU-L1C3IdW8Y9Y1WC=Yoau0FK zlyCCdv|nTyd)$K!n1hvbwLGc)5M0nihJ)u#;i;?5QQ)~S3EV{scxly0lYZ?PH6MpMoBXdYGo-LDgVa<>+cyCAkBly=7!p zcIz5}Dt}h#D0^5(SMS5Bjz6=(BU?X0WGMl5oyYku$TOgWj*Wg>@*#`hWxGUA^bjgy z3vk7)0cWKo$U};srhVHK4_xRKfyQ*-9;6cGtwSGXaRt5^BXGo?4o#W)*q%>22b=i@ z5j=#p{~bfoDAy&Vdlp(<{vpAVXfiXsa16*&GLb(=$rW)sPl=K!(8Ht+(c@HE!C+E_ zT3$X81QWxi%zcNUgf!F616z`_L?8jBGL)H(;wiG=3wMzm8lw?zq=GDD4Ynb1iM)N? z6nD`)ykUNHkj|VPBVjz;l`;=>es+Kxd03wk{CwHygjXYlbElGgar`o&M*Xj0Yc6{t z6@}^WwV2w?th!(BP~H5$!Dpm3?Z7rx!a44DZ0_emHiW-i41s?}6~b}6-k?9~p$0nb z!|bD>_Y*wsT0=u2i40nYg@IzjSG&ns_43=}!G=@I4dF&b1cpTb4-bl)8G!B^pdtm( ztnU#Q4RS@N#v!Pl7`#(*5%@^%U)d?VW0VfAvr&Hv?{lWnv)?5Bamk`zoKp)mm4acj zY)6~U2uNeTAoc;C-fg%i68&~e>M4*25DX9xco6y0FTtx_e79A~NZm(VDp<4A>j(#e zsAvCT)H%6xWBY3F5d-^?O9%$_%l40V`xJ@w?|>REttPX4i&?+qqU?~ypBiLZO!(R% z#06?7=D255Xp(BOBS>YjbqZMfB|EsM8W!c|ZIK+wuog;>a(!;*8}O1uOlY~2Z2o1O z1iV>~^G*_VRBjkF3F7K10=dfvCff5ij5Xqm!3{3Iy zkt95Zt?s~#8|{axtm4&FrK@|VHy13nHBDW958Z1npa?c#SFDIVfrhje!I46L# z zm=(|9(AZ3rSo02X=s1B25$TW{b};VX!b8Y?&~hxV($`BO;gXX$ahZxnn0g4(|CFP+ zv2xl%dJTJWfUIhyMJ_cVL!(`oC&8=n5D5`y4GuW`&tN9JT&4~ ztNV>xb-u%~26XIhD}A)AuH+`7W<~_{^cjB$wYm`c)uNxWHG0BHH(xkKuCHJnW)p4G zqjU3q=}&5yys-fsd9#EI@n?X?1}0%xA-&1o!!3G~?0qj8eXRt9|955wj(KAQ8&~cb zx9htzSGEGCKFW&tGiqmmsPQzLd>3X?wx~GV>1aRco_zO_x46mNJQa6&Y$=?5m4bQs z_O8X}AKH^alKjWP@3h?f-zF>B{(qt7pGYZIwU*OT#qfdcnAoHxBaWjnH=W2{p{qqlu_Pm%hT20#QIzG&2`LuY)^ zoSoVL0t}pmo7jLn%m@=#)h+~#tc9Dz04o#M#mhck%vD*rTSJA@gs%SAi(Et*UnHE4 z)%`#)jE`HbuwEvgRNguq4BpfHV2FypC-52w2MEuf(gs;@E5sG5+5tFT4q%UW@G#`w zF2Hq=GN=OCJl-F{9UyDK&5-BNz0oxO+5ky~s(Scg^j;!*O86LqY$O3`-`3~|{$K%a zz=8Z;Dm#vVBlO6F5JUmbolZUY*TVjyb(~=%LazzEsUY0}-27QWT6}POl?87Zy~`lD zBi{U3h-}faVD_kV_v;uA?I-t6@^nHqTJso;=pPrirO=z2NFJx^(U$$8UHh zwtkA1x1ICTozdDzb34;*9}(MrGa4%0)#xGc)o$GEqvwsg>*SB*%9f{Q$^AgOcxBu6 z9MW5KeA;H^;eA$eF%YGwiYv{ag%8ar`9@O`gv>WP4883aVYJrBMA^7VM-a@PJSr%y z=I3S}^U=d))o?W;amR-Iyy)`I7VP2%vZfE#GtJPnmHpF}#ZS0c46m-hvHkH0caee~ z+hgkBwK58O0z33MX~d#$#aOIpGJUZ`dK#4e^B~_$*}Qk zb5pRRc1x?5)=cenGnJT|4nDF58cImBKKoP9p%nF?p#H~PU|H?U$G4PS8dF7cT&l!9 zZ7C=7)gA=z?a7FWl2Ip)be=FvRptdJhKb^Gk@Rs=;$>_dhLPQbz231ZMtBmv3A=n< z>MA{XFXqfO%Mt{IvmW#*m09HVH(`RG(gS;pBsr`R3HGLq;~-{X13mY$A@-hG@8pA~ zIwAdVVo7+qZxV{d)&mYTX6Dm#;^v0nO7(;W3TsakWb#lC;6eKM$Ru+O9wJj4v+J6P zdb}b0!$Mv>3Stn+ zqC*N>uaAs){0v)@Dcw1n!-diB`mB&`%P=W@XV(MBOQjQi$5esH4s*y|%qL`l@Ul>c zz)?y>`Dlm1B~lQ}1bIB>hsUz&Hfju*R+d(*lIuQ6H5XjkAR~_=dr0T8+X*u(H;6?= zwT@hywuMlXcC24Jh5cvX!Lj68p&g}b-u=~6KhbYzron>xP^w5P>qAOLnN)@~$4jsC z8Oh*43X*?PYd8Z`T8x*}(jd1+k;n%F=8qe}R9m#kDJza5RUiho%N?S44Ti>zT+ZGE zr|+ZT)F>a{c!@Qu%GR76*`uJX5wu#|H%Q2wXt%zKO)^e2(HuCodI)rLEjPg~Q_THp zY}vP4v`UW&uFRG~Ty-oXlwm-D&4UJ$j~=%-UIpzw3r?% zIr3%n3!^H#bZLhM`W>v28RO>nj?0FIRUd!(fp&9jGQrg71v$EdiC@U0*+ABs4qH#v z6G>^a2XnxXMQ9i_nxcJ(Z9#ve^IUgzr_L#;AX47t_EdC)>)n(SeUpk1cMZ(i`3E{h ztVi}igz)WH6S;y|4XSUGi@<){>%gP%NyQE4*dg5VGqHb1+8FW@y?Wsm6ytKbw9c3X zkx3$lPA8w{4d9fr;j4#9D!BUvv(@s8@j29;MVh5ka9c8_dhUhwf^IM+F06Y=9oN?0 zN1s)Oi9OiO8&_52`+eJ>>UF5pVrnfUtszWFEyVmv#6%c9hU+fH0=>yg?hEL4)9-7p;?jH3!rf;9^wX4Nv`1WeKEA$pdQ2wgE z;UpJLYCTXBX!i>TM4{$=<-uyRvy9IzV;#K1hz;mO#KtBcb*bd*WbQi)cgiTK#^=!1 z?;NfHN-X!w-^5`fTYkK^m|mtY=Xc@Z!Zib|u13iM;I_BFKaoU(&mK0c0PZ>n_2 zSx@?s?1|kni>D2~RenZ~f;KHtwn--BouPRL7dXn;sUfXWN^874+%N=EfN&baLTNv; zgodN;Xu6!gIpw90343aaZ2PnhdfJWO$BL=hd&>dADaJz%f>p?#$HA=8PpUbp>Zi`b z&ny?=?8~f@J4-U*Wsm_HVe<31mQd?kjK?~ZJN|xA2s~1+1iDC`@G5@!Y$Xi)x@Ljq z$C$|h$Tdn9oxN1y`gQwlfR9Ufkf<_K|GhFE;j+942QKj!tiOnQPk76y);Hz)`L~qo z-#Rz{_iE^W*};DjuJ7cZlhWdMIkfYV%LbP#AUz0JXpjp$UtV4yf{y?bGk_QYTxJaqXx)SZq6E1_F+&4?*&VX>c@{boE$nRp&H%nde2&S*nHe111jO+<2un&#vGQN^ zImlPWKN96ZeW3@P0N(S78fpO{0AQ<=*unLe@vr&8RSR4IaA08mV_%3KSKpr*069-u zubQtV9B+~QN!3Xv> z>kU-A54qhB*)%q?HP%_fy*RN@kQng$pXLR+MF2%ooy2qU{w*L|2yUu7+*V9CmR5B3 zh;SLt+)L@tKt6hVvTiGbBVuXKz;NJP27A+Lzjml7ZD&@>BE$&5Oj*GbE@oX(x6Av0pomjn` zG_rlYCnrB=uwe3Pz(=hCpgkSQKmVFHmZU%k4{lPWJkzkW6#a;6Us_^!Jf5UB?E7-~ zLz8H0GSrHDElZYK6AvyJUg4m` z{F8=#_Q#?HDRIA&G<0t^r$)^I^a73ifY}}(vq^zAhR)Q$r*84L__GGVZd&rGxZIg- z_!E)9V}DrMQDafnj0UE0#?~|Q0H6AM(;eDgXvn!(l3_@r?)ehiAK2hC8b)N4aatR8 z0%Bwno#u;$s>D+50`YzgTkRNq7gNQucCLY43@u-Eo}BF*DdH+Qii;yjpVJr0LOI97 z$a46Tnfb|KQeWJ+Zd}T7J*CPQD93&1_47?pEqK}DJ#F@urCd;beI(C-avaEYMyKRgbHI6aIxTuhdB3YnZA^j>&J_H-z z&0sAy;H#Ss6y#CtSEF*H+ym6j2adzBE(PRK++R$Fh`Gs^PO?l5?^86EK-!4&F?KFc z$+<>cYO}^J0^RRZB0f2^?k0b<#4jujv#CB2YnnwR#kFACYyn`AcVkx|gYo{X0qZ2X zh38wv?W2S~Gg(f!x!%=M)sRs-J?LxP*c@OB`>d-ihGK13lJP|K2et>Ig&~gQYy7Ad~XEHz5 zs&|HLs>!qb0fp?M7b*4-(LyF$-4Vo%EglQgAIKj;Qc+nS*jbRm*<$#GK~J!j?U7ilzUDwRZ}SeC^hLJGSkP zZM$RJwr$(CZQHhO+nsdmbdsGp=lia2Vb8g)eeLg{4(gyzs-F7&#~9B&?)&)B;88De zRu(R6kFvpY)(M!=DI!cyD=|=raf2}2d@B%g1tZACHIRFh_P%gv``NqI9dMo*TZF4>#UxwQ-Rm}b_jS!p z$tpxvGj+s?~I#wc7q2ft^z<;WvM|_C!lNvDOYV~gNphae@KH2ckqoR=?mHS)gsV3jjTc3 z2YPM!lI!|cNDmzC3x~)d%4mz5@&f2LoFvyNdZZf8pS2TpzO)cxRo;i0!T|sw40Ino zt2}{W*K{+fM6e(B(15|IJUpi2ADOv!x}o!GL<@|&*!=WDQ^rvYOOflk{S;fG1MtOT z)q18*?dWj7;qJP9Jwj#b9U`~ZwuvTuL_W_loi_*5G=Fc$NgaL(&;@8=0?e_=R+!vTll+0=Z zDk3bA2>=uuhcD^DbF-wEwog$qXb8FCIG?ocNC$xALF7jKCYgNWi4FR~lG(4K$Gj83 zoO!I-86(67iiJm4%6pjXk!c0?g8m+gO8N}X6*lv%`Wr1LEaxui8HGoVM7oUMvpoDJ zjbcd0F|-SO#!PZff^v^35aXJ@zjby1+r{w6aU9TQsCCZCePP+J_*b$11<32DYM9(E z0Z?00nk90Kaddpq_0Qh)qJYvfvQ4X`dX6DX3I6s}^m0eD>7?WPY1E$shd?LTTs|c> zpM1wEo5=I;DYc0Q6VxVSSOdqnQXe5x&UPlYrVCB+v{Vw5uIfs#1hVwtE=PXhKq$}y zZm<`Iq+k>?7d%DrMVqvplh{Z)1ZX93HP5!Pu#$>2UC=6hM@I5q3ls%cK<*90SF`*~($uY69oqynE}wb-sKlmH-rq^SJSk!S@hbLzufzn+tcjDz7~}#eJ~*yl}y?@UU2Sg`L+J*Rt2Cb-w5^0qU1Yc9UtBX_w>43*JwjPn=$^ z=3sc%>oPw|&}HaDm`%D`Yu$lflf9l#w$H>J9|Jz_`pFQnS|BN&*-k&oqp3H6_%_{gOzGk z+>OxEnvMFrr1AxGaT(pxVy+$uKfUsm_cbW=#T6q3C!p?GmjH9E_J_;0tb42!xKRQ2 zsQ^V0P#TCd=;;sN3eEdVPTEw2-alnH~_sC@G?cMWz_rmr;aN*gA%nY9qirw2vW za<&mtUpym{o; z5Jr(_Kd1wtk*J@0+jw-JiET;j!09A*l>k*vk18$zW@5vt(WO7a<3?!l5q8?d(>R%! zSkT+~+!|t}Yeh_s$@Rwu6(XVM*9?16&ydfkb(_I74_1UqB;Nh!=n-CEhMnow`pRIX zk(&kDuW_YOo4uOVHwMmfzz}!*!*C{TQ7&GxwD)UPyRt;9)O|KLp8UHb>-f zus`<@VyXh@eUjhx#+9oS0$6YM7OV$`O zlr>!KJ!BDQrH`{op1)-kg(MUx?C|`ycJY1I(hdfVU{-r1T$j82X>pGqLGx^g`tfIP z%x(2DVfp2pa{Z5v5dXXV&VTwp|J71O$pm!0cd9ZP<0!D?4p*V>#pPxtmVKxFNS!Nf>&Om$4w z>%-kHqb2S=;9~7Mzi;smEA(Q(D1#y;Z-U(+V`;$ix;dH@4jCh5Ivb+mRAXp$gQ~IN zG{@*nUp6Gu97-v)A$##hdF6aveMrs%1*LdfX#_Q94K{gJ!@JYv@k+}lC}sz_{N%zc z2KPj8>~{^$XKvF^X`WG0p8Dj;+ZwHwR|S&v+Oo;Tg&DVu>U{Dwc~@rXP98RJnwW|Z zt;QECJ73CDMnog|%@x=A8a7#8&!EqK-(Rg@R3O2Y@C@svB>o7bV-;EB<#&HBcVP0; zCu4uLw8{TJ1-}2b;`ncytWByGs@O{y-X>`1t2p0dV-ZCO@Pny3VwEhbP!I)r6%qOK z$;j)>gSQ|g>nG#W);7znehFzbp?OHup?SzHs56V9fa^1-kks9{y*B)c+0Onrjrncy zspwUH&)v|_aZw*vi4 zkey)1KRjb7Ii4DCCp_F3sbVxa>MAu{W7tV^0E1y-lu6lr_A_Vw!|t|RK3LyVGgh0= z8N7Z146YfxUISh!79S6-9b}DS6vuy)c+~g12XNa87zP5Kcu+N-7Y|wMR*3!mo2(xV z9>oy9QoQ9;9;n9e>wR3l$7i`fPLRDu=p6XN1aGRo-0x2>a#2>^R6|?-o3x`q-c$lH z-#J0n2uHQ~@*%qeTfY~7hl98c^|vDeeo6N)v6YOaC40ujRl4@_)b4}3b^_rYY(eIV znt|+J!rQ}w^p2Jxch!#70pEst&h$si``VZaM(K=1;G+Vm(Ut52h9zU8W#NU>=mWV> zxwi0>>l4azmP2oi4Djcw+?C=g-GyX=*#6-V6R4Zp##$c4tPm5an%*tL`0Kj1Y#0~= zYmQL4b)=SQ!~EPj1zua0tr$0o^uo60E_ay1{6Yn;Oz(kCsOj0XRReDcS|SE3dg$fc z#SB4%IoKe*p_{4+myov8!IW2JOgmej)RG(ZvW{7y>3{@{dfN_HteKJ`HeZQM9 zDB{GjgR&ZnrDf88kS$jTr}4J;Y5mirLTGT;2U2H*|FWd$&e)>V_Q6j`j4^`+m5O_Z zv2G(O==6NJ7ChE@kY;kgaRPpxm5L~9i!o5#VHZ;^mbB>=DoIOm@VweADYa%=D|4eE z@Kef#p z9-V0pMS)tPfk)sH9X+a> z0`tgv76f%(+)DO@h9XJw!}&n4IjN-k)p-o*WN5Pznh5z-%hD)7`vtC){7bN&U?_{3 z2^C3RVn9{9*_tNKzD^(&Yc!x|xb?HH3`Ypnh9aT!I3dJ2)WyMMT0iVqO?W@>NvgG) zVc|Esm4yXq74|b@`^;G-DCu2=|AP>3f1^9 zE^*44`+pykuKkwb@WwoTBlu3Vrj_Fque4(cz`itUvkM)vgdhe_IDlGq0h@5FwHL2S zkr@n>?II~DE@{Q&9XcUFMG}aKH7j|e<}3quL*BpufO6pISt;omPBjc{;hJ;f%kok= zKUinMK!= z_F%L&F~kfu9k9w-RN4Kvct*R9F?Gfn@hA~3|r%KH$-dz{%Hp;#U?rVHC=MYSF+D3v19tB zjmXtwVV@APGME@aEM1F7#2qA~AW2q92+yC#g`UobLfEngy_`8N=e9bPGh^$FSWx|w z1TB1tu@oKoO{zelA6XsLBcUPYhAS_!3KA@2#C6X*GnZ#?ohcOiYM^?mg^ZA(0Awc5 zG&7Ak>Ps?7I>!a;BN4loDVRFR(w!e*U1|ek%*nKj)Ixho=F4fBv3r`V%cfa^mda_#rGCB`2u?y(V%jD=_m5H1-NvRA^6 z4I^V{c^mYkI)&_J?|{Eu85Y8 zW@RG0KDE7C@bh1(DTadS!9*3DHgam`Wc5#^b@sX`FN5@Z#9eFi1JQ8GD)-*OCVve= zDU!vAZgQYqDwI4SnZnJSg=hqOh~K5!sX?@AJf%m*go)hJcjm%&7>9knKY6ylTRA_J zm)gJUUJ*a@OBQ8tkN!gPDSp){{ZIkCWgWTG7rnA42=i%ZE!#NdxR4C*VS@%$r-)Pr$Q?kJ$gI7`+B^-ukHp} zaYx=W;_jJqpk}XQ%qv0R(w0FZ!*_%x>lHXQq0(2bu;wb}sURjqmJlvSJXR*GBotS} z78SpP3jK(5f81K&`uoqu&nrbiRO(BEEB=oOFy#NM>OoRZ|KH&+Nh%PYibEKmGW8iL zmfHN_pe&jG*b~;@ebMl>W8qPd1Q7uNs=6(;<3(6H>|B8Oxz%IB)lts<`hczqicqT5 zew;4>sh2<2maH!;Zn`@9Kee^uBWE>h5^^o+u&rGu3ZS72EuwRcU%mAw9cD}Sq z4>(|EuUz{F+n7Hm2lJY_stkBwZm(RM!1&BvtHAgyT)V*Fxpv)cuPVPzM~2)lFbmX|a6#U021@fX04?}O44hl*WQb=bscm=6r6!SW zQ*RRwvVPW&elQ%J>pbvtkal4GKR+caLaz)}iLy#y8wFP&Xc`8TLm3G73owfVcc=;w z?&mXu^Vw8LzjR`UjvjM>ZtISEKei(#`)=?u1#A~rUvO4pEC^TQrh zJ2NauqErG0}=EL&=!+ zq8Q+_fYyV$#jdWJ-KQ>Hy5iwu5;#frPJLfA187-Yv+lnZQXBXlKMp9+@8x{%US5;z zii?Dv795wPlx&4kgqss|sb5_&rGJ~+yH2GDSB9MK5|7dpUqZJc@e^$&Q^;Maa!Qd* z-y9KIy?!n9-o8>5+dQqm)ZM+Kv!!Dxk`<#0VLB0dygE!s|HfSH@T*2Sj3&b{Q!s0$ zcwioOKhSHKMl=$N5+mGP(!DQCq7+ubpwcg3?$f69(Tnb%r3de24I@4LZ5-YYeo!g=j7nQbbCEK( z8_+ao`ZQft^mO4sMjS=B@}Sf(fwW5H6j2n3nGw}kW{%m4^{Qjx8dG*sbTSDiFY%f7 z@C2Xyaii>P5R)u#bXP@Hvmq(aW}e)Y6H4XlxbiOW2K3}w)* z%zJfYDwcgXELpuv`66Dy3C~S%T;`VKO1r3ZZETci0|uH<#dKj~eqhDdRR2|?^(QU8 zs?SSUAAz`GI2k?FFKl*Vf-Xk@B4K3TZ1m(`@~|R@B&>RJx_k`H^QH~0im(0sL>Z~$ zSX!{O`5eOsgq~4PAz9c*x=cQuN^4%*WfzZUjuUT*TbB|sZYlK}Kxgzz8!Ust7NEtn9gK|iY*~vz z1>VV^aD(XI(a)I<{LSH{e}?d?ZpPg1BC)mO9b}b3^lf@eVlToM!tP>&>JryfNOkI0 z_p>n>Kq?z>EPoF~rRr7B40SquhP||>l2y5`))1dg@h7L^VrTo37D)_vyW-ZYMkGN_ zh*fj7jCX)7d4a!n4Q;&IM(%Xj!C@X3%1-RebF0qRk1E9V?=x6WncIu z3vGL$D_!dOIJc$XD%H7QtIeF2-qv|=b(lCSo?T2=QjkoSQ{24$p65(fC~#9m=29gJ?bSt`=#-!vo7pqAJ=Bcfh{lUK7itZc4l};Epp74>+=m{ zx5{#DPqc_sf_ovnB?}C?!a`{b>j@^`p$?YsR+R^{^XY4nJPz5UliBgAFK^7 zsk2;DL@ZAWz{4)Ozk1SmrlCZe@Rl#xI5t7FRQo551FcuWv)J(>gnYB>v4eCbvNSrE zNcb7^HBG<^uEd>}@L|>D4eI!6;h;r7GV1}D;qTb8&(KKE>mm%55)|=k)aJ~^5dE-u z9#?Ko2N&_m`7Oyo@iAB)=&r{0Zy|Px^3H{&hu_8F_~=cf2cP{VDZ^}y;#A2|6qUXg zDJY?5GH+ZxSaclC-lADePBXj2=_dGKpNAIc7UF6^Iaf3D_NB2qgmn)I`t&dzvT-cqy^lIPoFcBKU zune}a{5JS{Ye|7wmLEo;9QO)o{bldu+Jbh12zLvQ1s;1Kl((GUYyNG=lgZg#hra) zB>!WYn=_tuoDG)T!I)NP&1a!{rd z{#kKt=L}EDNdsrjImKbFp3fe4=ht!HuLZ_V_I0#M-V2F-$B}d4Q*dDnf67(eiimB8 zBQ1ZEE5Pl2`N`*47Gm4vj?P*kV%y@r$b&UJpkkXUq8xqfDIv>LP}*twIzkpd`m}NT z_6haJWrt=-AAZ(X>Y*vhKk38&cS{~g8-xFBOs=?LKQD`{MV?Z~1X#41QRQNhOR-HG zq)jI4(U%YNla7atJSr6y1{RpNPv)9c(Y&glV8NuPSEOgq?kYji;+McwY}535N`uUF z_EbwwPB&m{c*q}C&=jK-sY3h%vYQYZB z2GA!MOu@hc@p_qi{NVVS&~rZx!6~HaH0ABUSTU^2QhO7_#e%5@s05<%XJmC#4ODei z`Gtkz_Ha>^s1E8OaaM?*8wIubH6@T&qEdv*tyh~A&78I>In4GviS#rjxX7#1$Q#U* za#|$M)7Bj2n~LR3TyHkZo8^aumuxG8rPu+eb51I;*0XUOoC=o2ujo&u7wRp}x|E=t zJpyhS*ZK59Xm)&lyaMK!Tz?PoP$X8U(r7-C6azPQMr-T0Z>uHf`|94(5Q*A}eef$% zh)qLyr3y{gj_o}RmMoK_mN5SntF! z8EnRR_r~Nz{QF5rELI2ep;^sccnYCnc@iZZHfdNg3uE8zTWACBj62tvUEe|HhyyOI zYo>v4B&m>X96QJ49Y2R?foAbdN-T*}dTNd=*Z`ibC0JfdA(3Q+=wp;@XEavNK}R4n z^0}Dz;0@0GZ>*gm1*y>+*1dqq64B@wO9Q5~)qY)jy4s*Tm!3QQYb0q|?{sVY0PWZL z4#Ts4X7wGB@e1yrORz*c2G>*F^=^<}wz{XYAG5?{tx=TLrO2d1Gfy+8WrIXI*dnJb zQE^g&fnz76IHkC)sYZuD3KQ=fVu3~%z>(S|bGSv(#nAt(4radPX!TWT4P40&u?91yqjmlGbJqdh0D+=iEoiG0OM#9X7_TQ#FVlu*Ce(pB*|MEzVQaRI5T*3Itm}jSR5E2v;Wy+^d zWG)m-7bF@kf}hi?g*A^YoHA&7d(xAPO{P-6;0R z;gQKHd6}Pihq}$9e(!PtP1PF)z3D#5bm6>mKhA9Vd>hvIW<8=Kaq}YIS!m0*=N5#9 zOheI`e_h^h0a-(-DW9sGD%V;`S8*NOpV|K<#e=jV*OY55zh(@|q5RFimjc-%-&%Za z5ww$-haM6D+{FhxizW!s4vY=SpT`+0?@1> zyekTy#IWHD2Udp=z-QS%_r2VfF4SCaI~|l8FcO~SfDfP!-uyb&*AL$M2U{Q(0s=hB zb*(QxzyQ8w9|XWV{$^kdIQrZTa{QNd;B%qxh?6J8%-J&oiKC}bsZP?`%I?qS_Q`HP zF`S)20}ky$H5}SKIh>vT)My*R>H|*nl^ZQj^^qst^VI$kr{A)+v;zw_gaEw5gdEkDZx_@Fne+bjdSMgRa(vj zM?%~yOv5e~tF>R->5sPOeywqmh#CnoFr34=XYtMSA#* z8Xa5<%v>UiipTK%%JPYgC-@r!0mc<)>UD92W-w{hD;yV?b~`cIK*Ig#wfo5?X=7U+ zWZgU>T;}28pu4SbGUls_JF_~Yqd&Y-=#*B_pyOkI{=D;|K@XM+LT`KE2Dz?KY^(4! z{iHD3IKO+hQneCg-jtW+>d{VD9$494+&C{OyX0<7sr=+Me}{HiEwdvho2YYm^>dWTa!cS38t^F(tew`D5ObZ(iRRLHM3BusxC z69Z%Z`Pju=m$l}zSA2#xO|)i9#&}FTx-D%x0lEo{3l_x1jpPWk8MtvLbFs*E`#~o} zCXamQ(eR9>=7S|zc5;u}s>iqu66QpqD!q+sc^Vg3;jBa~Mowya1FJJvX69!p{J^i4X>H#K8pP5w)GG^j&uBp^- zcZ%bo3eqs_)`RFJam1NXScNEXP$L}uo7CbUg!But-E2~L$H*l8F4d6-;86DdKE3XRt5sTcnHA0=XMvEZsIkONiD8g}+p!Q_-#L(!7I? z`UJ;nH^cQZoCb#KHebfX$xI3%NiS8q*%Br8GxB*x1}QVF z5-r@2f(OI31p-V=Kk%1^YDa!6G_2UBl~Xk>t#Hn#8sr#eXrI>==w&y5%o`Al z#Ytig7@HKsvr@6%@vJbD9GZC2!%)Up9eZQ=%!)?W;<>So_R!b5I?#ez?q&)Qn&?!! z7*7{RO{`Ax?YRgg+qO3hPdY|`>{r6UHtXc$V=y#L+y&e|$`=u%JJ0Y6y03jeJJFxV z#*3X}qm4UwUIA^m?NNitpm-*WuXdYp4vU8jH)rvh?;4tK_@Ln)y_~y z_X?`c{s9fq{z74VL*hTkHL*liv)8KyJ-XGoado`afx~G>>#Rrncyk5+Sbzpbw&fQx zD~1C`?@wdS5xRg)IyY4-=<0WwcU-XO6}euJTC&J2{tg4Tdv!X%Ym2CJD4hUKBkNYD z?~bekthy_E@wt<(wlki2le3>wT?8o@dU!`6-;nKLvP61e8|R0ZlC77>_KD zvP0>LhH^E3WHO4D8;$7g2@Nj};y8!Cwx2mzZHD@ULf=`mHI*bZbVrso{Ps#Pm6;@S z@UCK)fDClExRp7!uzW0;4d@kTW@$p8L8~h@F;o`hBVFeh+VLf^V_=c0Yh`0$cwu0X z%u^iRXpFdT!`1_}&f;tUM~YgSx4Je%6yJ#DbzV>~}YXRq{eySG!oD3*a0$8`6ep zi`%S29}5>H>5J9J5>d4-|6yxKKDarM6zTOLwq4dA@&U#Q$PQ7xOP z=g7H}+KJr%%vH_{cfQihwMED(CBXMW&CKuH5uwlmYn>@s=pr^ak*l+$qAW-VepWW^ zMmf5N_jIj3>TsaMnY~8xq$s#Jj;xn0E`3D45o#kNdjRVe1bPNI$bwbT63*o+fuyaD zbz?Vp5ovRedl8%1?oAp+HKTl?HG1adQ{bIYi(RF*yep9yXGkQq+s2#uEAw1)L;9TR zYvLXCkK3W7e>d^|Dn$N!0TMIyWx9wQG;>eeto#P$Fh-dhB-1rC5eD^x$f#DsG| zO%IU}wp-D53iK?y&*Voz;@^26GivwauO4Qff+)}VHa7nyGaQF5K){eZ6 z`f9n)^6wDtr(pL5`E3Ls&2ZeC4#vmXoQ#|eIXYK(-<)f4hvm^N5anM2Wx#Dp(7ycA?;I5MA5>NJU)7-U|Tkfw;YPLc=W+h!&RWu_-}@1oZ0w-1spL}kKx1UjiZ8$@JQz0Ot-MMh~kty4UhRO@Mt zRG6~e71<=UlU&BqU#xPCw<3x|oYsH%vJ~PM1Nx4K)bP`C}JwIF6DBK!Z7^9ezsEuSC3N-5Zr@&}{BLC$N2gc=p z{DuG4ko$l9!U|sny`IUx(wU0nrDQgKz_#?sP216t7J;(1%&iNGaaIy2iMYoEZw7pq%#e~|5Wjui# zul!I^^{`yeg!2f4w3~pc{HzPJ-7#9A2UN+k?;3 z#>EuvUM1|g31QyI0zX$$B&=aG=uM}w*!>-j;FSoBdnI%`TJkldpL5ML2ot4DB)zXngg#9n)69GRB`qsT8+}YuK^NA}@>Gfx zznLty*clu*kW#sz!4V@T_)uM|9-eSY+E~Mw*j+$3)%r_*Q}UhVFCW&$%y#kSuVW$p zkEvaM>u>mVEDZG=_5P#P6a0E3Z=`4VZzKOGg3zv3A=RTMn^`5RB-%|-of+xNALi^n zKiZFOt?nAC4J9*clFON(wT7q@sD)s?HfKHq(6pcIcyIaGIq^eA zakt$s4g3=YU&b!P={@I7=X(TR*tLi)qrGSK_3z(fp2*gDKZe67M;JFrP16*r=kGw% zQOk+P&ei3rJ-1eA#B08Xqqw){)8KoZTAC`=sR%`7pDkp!RXDQEbP8%GY2{(zmc_rA z4>%mg-?}NdQD@EsLY~tB?-1yW{K!ynYLc~nPukpz6`xPewr4q)w-S}vFp^QURBF`RHtMQozAVyK-fW~- za@-R8lOqsUFZe*1i~FFTg~RhtSUgW530QIr!rE z;vwXfs)0EGwBE+Z(h}v)=mpd&#V%@*mPYRlX8$I7?4AE|z_b3Si(66EHpflWO+Vbr zJ$^3uZFnvaqEN3Oreh;UEL-~a0{%f-7NyO8CvKHn+zR3=lUSiuNS)U)NT=~Hn|J^^g3WLg^Z-B}V15-~ z{ovVlQ-&ee2MEe$;NJW3k%^(}A^+Z~*oQ;>BnQcq@UKVOoam>e%NOjJ|4~u-x6u^; zKH2}{M9WFZ^#4H43=#*Cllutp6=uCLg+Sv)M2aVAzS%c3%Wu+*=C;W~8cZcV^G$ZLWqG}z zc1bx|=QbUQn6L;f$e9U)GKp{zgR=4%*0#T=F~KdccFV;ouZGd>m?8$Vc$p8!HRwi3 zmZM6$ZQ?W{%ctCjsbrjyo=JeM)`|x*+f|6lIcb0tpWbK|ZS!)2C&Fy2SA?m#Q#K0V z!w=H5dPV`yTF>PyX$(geY2Olc*gZc*$zUspHQ&l3a6e~u&z?wxuif_?-+>*(hBmS( zW&l45)QX>-2jH+2rgZkHHM%hskj~hCK#Qqr`&z>zwi22rp#*3b*?ckw8uI{qD{4V>Tx+x<%XOt4xZ@-z?1A?&FIL1 zuYPSUt&Q51*dY4N=4{4EHDu!dqRZi*bP@cbOG9?s z`JZ&*`xjk;{!JH<|DX%v|Dj9N=20w5AvO1rNfJ zn&T3Z5y4u@kPSHXg-TKTV_*TAS*4q}#1~zRhR^;*mwabKyOuAyRDA!7E;(OxN%(^< zs9$t3`A>9F_CzSPDvTL|TZeQYP;69MpSc;=q@M#h)|B6_}Y0zgD zSkG^GL94O|N=#t(w$8>TE*CGq-9NwCh6BNE;5u_(kZVdCJIo(i{#K0jA{ybaBUy47 z5Y`z(I4+79%b}i(m}6Pt8=Ht1a5l_-Kg;T$GhC98N;ciIN`78orf^l2o$T&!G0Dh^ASob=pCbKSj_71S*X$W;G|Vsw;^%D?Gj4Sxidu58v82%5OpP>@4RN@l zN=T>+WFs=JlV$rI^^>L43R&3aid11}UGb@DeMv#qwBU6eC&j}9X7gX_5hX1REG2mF z6iYU}4o@cHRDIry5UcNnltOjrm>~1Ymh+1JB7{~CvD^?)Vk}!*jZ08D?ngpC{yZ@c z;TjJFM|I)aZ#hiUVy04N;k^U4k6G+jlWA!V$2C6QTL88Q+FyqV6;Kso*ZQ0DHyVLt zy|_J8f#^NPV5Q&M^}5RM$YRZrQHV9jQH5F>lo0d6gyah7{dKqJ)wPiQH<9@R62V4T zcWLa}M;6Lsw^Vz>#1luN5d!9vOX(>O*nJZ>Uj3%53bALMK26m1ZHO*oYA2@^KBqj3UjfHfz4S2V!Z^0e0l@eeA z>fD+Co;I3XKns4F;cev=9cM=_Pt zLAcc_RQI%}@|u<@=9DBT+`sOPY>M5SR%Tlm1m>KorYXR?G1<@B%;JIKf5FJWwqEE4 z^yhap`-EJ$bGX!Y6!yAi=_S}1Pd#8~KM~#e?-tu43qJ1P6M9*@w-=aAHHZtVx6;s# zgTtmxk?N+Um?OKo_-(E=K8eb?deG7s`Ohu~d>$GQo zkGPRWl|X4xu3C>KolI6SUu|x5+z9fgB!f)ql$9~Rk3$C0rbHONoKQD{T&!J;XA@#P zg+Gje3&*A>s##D0q-a0=yf(cjkB$Oe`moBZJ~%X;-C0q8msAH~6$KqbZ3X5no{fRC zMYi)4ASC6>94xYRT<`?)j7UsGdZ1z;vOpF&CVk&`H1$*q(z_P8Jc5qD?b>_ zVUr(8BjId#|x8%%nWhb`=}`LPD~%8vP2~h41wJ+E#vxpRM`8 z$6r^JJ92o1-pPMgB*AXMde<+$pwUeR;e()9Y`@ppFfo0f<>zyG{tOQLu`iuy{MA^zIs`+Ly+)8OS#&@KQpIC)u~8ACD{VJz_oCX%~Y&MlJLFNy3seba{Z zAqU<9Jb8EFRfvdGChZB2=;p^v_LIr9xt-6C8#G^wXQcrr7)s3UrP|`XZqVW{ql~&> zZWvzkXR(19idzav6c7~6q2lm(NRgn5{L1~f@Nh^O5l&$z$M1OsNGimhBzqD#S9=aP zTj+7uVS(fj3mp2Q;;FNCusPzXmO@z7V(1n^wB50E*1K3#qN?$+^w&U_=&rt4pt$%+BiJY+z_eS96P1 zPgTPw9no^wh*wyz_fO-LsMK^pP)*u%uI1k|bRi2(UCe$c6)67YE-#@+*?LbyE#C2J z?N$2SEqT_3J>e;ki)8+xD_m&gh`Rb6L-8~CnqMK$M>wVRq%L2RcM?x2O-k4!E+WxF zMM8SKio+jLL@*hO&#B0N6s%_$a*_I&`i?u^RQbJ<^3)u=$nkiodM;@0!k7HiMwqq# z(%fE*i3_K}x=gaO$1kfy!*_jusv?wQ{st)8Ra5$beCt3z+NQo-iWboSh#Zfvys&4+ zt6S{C)C-a}@^U=*x=@t@kl$U=i=jcx>sFP-_s+4(Wp*V%Qx}IFQ{}7-gaXiTfm^MQiyeFA} z@w1;W^rvLZm@gf3N1yNbV(m3gjsbl!%;H^pH0*0)QY|o-!(2nDcj|tPy1?D*o zva1N{Hv`>Q>?dB^ZyhI{?{81M0Fk?9=uZQ#x%$FGmEr6t5fsUag-V8sR28m;`*q0dTik>)q?3=Ujy(X9{D@0)u@w2)4G6Lv8m;~~eagaZV#$m1Y*2ucl2#Oak7t%hzFfw}a9*xv4^Cw* z$|XPlISgmkWe#bld59hrckS{N{ObUt_`MQEDkG z6Xbf=<${FyOX&#JxyL}!cW2LdiWDI+S{bb1Qe`i36&e0ac`FIkYPiFegQ3Ip_QdD! zD$)2DoEnTQ3;kP-5j=wDZ-f)pxOi2Irj8QN*IV5^66nk$jx91R&evDur!PA?Vtk)s zZsYFOSlSfqTY6DmurzL_DxHoAX33JYVJ`#I%m?J?dZjb?*VoQK95=+}U zvmc;ZZ)_<$14BA<+9C`4Jn6S#+?w7(d(kE9;m-4*Gp=YVx=i?zx4(Ia6sk5caP7)**DEfwfAlbh@&D5A##MC^9Q#AQuFAuDnG-c znKDOkE_RJP5G|`FkyeWOE#G-Uti1e2DSd%q?kN)X8@&phzd;tt23OQ`f4~wr#EAk^ ztwXIb_1wxpQ)If0xL$Y;ddY(87AVPtgIjz})!XK{xHJN#BK=Neu~p~5goa;p0x?c9 zhK2q!airwqPxsGnQ-dEw|92?#SLO8IC}j0TA>=vyEo3pms)#|e)d;XeVgX`!Sda|)vA{R$VJ;@PlVaG|ryaRe+ zC(kf^oEbY65!e98V1up*kU02iBWuOLCK^pzImamZetSfa0Y*edq8ZHzq{~b__vjAp z;_vY1T1s>X8lGmI42Z-7G$ah!7HdOwe?SQ94+u%6M2ZKsW_&^DNC$F(@Ou6a2wf%K zH6?($%X~p-@!XhI(_~^aCD6v1sM(od-5sl1m3Gcrf4z<}TO(A;1--hgS)#2cXxN!!kysm?k>UIy>NGT zC%6-W4Ci!zGu;>G^vwF|s@AHzcfIvIf7yHga3F1cpH9izoEMB!9=djwzVY!(rbrc7 zB$dc0t5Ca0Ez1dQ7`Z5~=;4=b#SkW%1C*4Y+dL5@dD6?<;!(Fkl*@!0I|b^`k8Wli zlf^hh@w+Q7uTagBO*i;A*ZO)&^ZxqzkwN-U97_I8Hh%eKf|$xy?c}g3?zPvHDp6-5 zrZ|D`T0M)YJzQl;Ki_d2Ynft9>X6Cd_;Z<;LQ}6y2Xgkiz1AE=b z5rcWUt>D)raJ~1lb^K?882j!*lVtXY3G#4bB>;#x&r3nX-gxd$gwM*|hrqc0@`Q+| zi#I~fSJgz+9_q42Za0>Q zbP0Y+!Wy?Z?=2@Q;-t&vuhu76I_tv6neX^RIAU3&xley6x0y#NG*Cy)^Z)RQQvZPy z78qF+!#d@4i>1>186(<=wj9n1^w9F|x1+rynwqzQa{J|#dj?xsPd%*}&s%l;j9Pv3 zXI%M?#>!VVnm2y?o9PZD94|^)@9h~!#0U=#a;?#%@9cAXZm#<52t&X8KGu;N(K8ah zBfq!8xN?Zc-`Wm!?AolKag{EAr)G76UUP=2GQZm!lqK@#zC!f-{ zM1k;0vmSB?-gOFL!0t{_NK#0+E(j_Q(u8$FJtE6WxsC~PBkQEtEeLud^Zve@5QI$T zO=`?TaJ&Z#;F)1Cra&592?psP0D&q)5ZEboxG3~cZJflQP-Es-m~nR)2%d>or>+`r;oA;z+Rq&r9jVB30YNVlETzU zgXYS^05K-)XhaJ#I?Dru`579b%ln_puA{R;zpREP>#GliAAYQ50a$Of)R03e0FK3_ zh2CO<#*@pk?4+D=^VH}?9_*Hr3jrvoH%3iadj#fcr*#Z7WmHGfTAC!pFRyR;?~CGR zx9slu3SvaKRwf)NSxd@C)CgzP-F&hL;k(e8Cs#-VbmD5wouy{=9tJHfqjqt=>i*>A%$<`iQKVIY0mLA|u9!T? zvo2*%q!N3Qsj|~{f{oy$oAw@Q_c}{Xv+FBSn`APicd$sU&(`(r?#vS9Nc{~{oQYMx zlkDlV0Fl(Bisr_p@vU9!G`m5MXtVwB8C#yEXc9$XBlVcH_U54FD z7hj88c2<(TJF2ME1oB*~&F?I~L+vR99%gHN=GL84lWAOQ>>x+}L`#c78KSba-{>*r zbgHC8b$$d={6Q+1){764xFOj2DNC(> zP2|V1ls@m;L~*RL&95rlrWOIs#x}S6fG^A0(X}$BZoABjRYtbSgQvTWnmn@I8#-+E z=A$I*lX509<_HBzCL!`RntRb!EI-f^ri{pyXTvQ*MS~>($~+IyTm&&b+(ih6P9IY&$|`e}d>-B68G13q!;y@SrhT z<~$JflePNo?u*hQ%ayNqUa?6?UD>Cefj1$KlI|QQ|f7YovxW(J66KkywiatDB;8 z&Z=a=t>)O|8Y!4XL-S=R?n=A@3&k%Vg9cg;1F#*btw_cXqr-sp-1s4I)4w7Qy?ZAQ|ql2t|beVHI`ym|lNO6QYpF zb48|ZeEj1~52`dvaQ|Eydw)7k{&j!*e|M(;x1pTcnH%mP#)mDbhj@jHO-h)Er4HU* zm{B4n7!P#Z%YDs4iZ=AQsFk^RNUfjW|wc9JZ_i9uKXWIn@?amG1J&~=Beq zW`Ikx*3ezOkiP%|1NXFDrVxD=UeL982o|=U$tMK}8#Io95ds$?E6iUEohV7jR0EMXTnwEEZ44V!oXmKYnQ(1% zXTzF+sxX>of@&<2T%posNJ&Tsq9MpO!8nmGC>xb~?C4*)NJr#Vcq0fa-0{dTe^7=a-2)h~gYqDc_3nkfcbcZbm3FZU)y-WgT#b}Y z&xIs{S1d{&UdG1%yLk5y%swsS1DZFn@_MYd-u8f)sr<_(dsVUAV&1_*3DoP*C2}rq z8?kx)%@7~rglskX6WOuZx-wUx!3s~=NV7Uc&U-wcN-Km}hO`0{awSFA{x-d*5@2=j$45azdA(CBJFl_wZ+m(Q|~3wI>&5- z{%paOd$81cf&q(PX!aL@jlN}##jGuk+^Q*dKn!aA0wlWSYqD;ueTwHL<~BRK5rWMe zr02A;qzo-~Z?qWW)*s$qKI*$BDqngwo{JEtd|({$d*NuDTD^a8y9DhQZ;x(=WLV`_ zXBoZ3B7!;PW=6ixy1^s!(QU7QL0lf@S z#%(`DE437sxM?#9>#e!)%1b1)eIFz(1jg~$_74{p3}TKw`l@+E9d0)DY>mcjA$+Ue zdFKIvI58Gtv^vyt=Pq}G@CDsj@f;&8_Wm2iM$9bf36vzUi4?hH8QEIN?gfbDIf|0h z0U#DnE^z|^x{YV4IOK>Iyu!^+J1w87E!X?VUq0qdJUntruumw9Fz_2Ngs2vMvM`1Tq`3tWm?J6o0Fx~7un%XtpL)+1W1NuyWbTHdCRGmKMn<)SLE10%R0uz*mSuu^>5mU6K5amw;#@ky8e_m&85M(Itx%{+X-m@v?Ut zNO9qUeBp}K-Anr(+;L-%Ls)=sY{4B(K*`K)qC-hSD@hO=btQ#*&GtH{9`=saJ)a~1 z<`3}=L-5-UYa1CXd%SHUfO7Tz4>U;Luys(#phsD#Ci{n%P$H{5T~PexLvGz!TboQbaNU) zN#Ft^MA37BZ`{1WD0qc8sygy11f;kX*E=7d7bY~!n*~Jb;iqft72*Ha1^T(u`j3|A zf2X@E+se-?p!;6xtyMe!45LI7MJa};>!h)xryZA(fC9PvL}V&jr*9~7mTb8Zezf1Kqd@Av-l0?`Z33`andrgW{+R~f(sxMR*4cPApj z2n^5$7yG(_$w>X3Xr~$u)=lL$M0H@wPzFRw&YB==rGZ{cY5;g*t%R{x?UkOeme>aa z)#lLRtqnKtuIX)3sv&taB^$wI0SgP#nm>o-rg8Hx=p0X*&i~^|MGIJxKM^$v}t^!_PYr4 zj(2>wO*cH!f*!H)q`p_7GG4TGCmpatkgqQ3%hP8AoWfl|guMGb1q<>wZ?ZGYQBYlH zSUa)qF}>Xd|u zTPq*mn}v!$I@E7ZxKGHbvcnx+5Sr7}+} z%ygo69`T^+2h<=AT(CTF|EtxHg7}~JkfeBsVVH4Y=yC2p((vMZ4|(bwLXUbQoM+6n zW|3Iu6S%`NQ#J&9JOccCM9Io%4RC?y3HF9?UX7Voam7NQ8PRR@Uq6QWwFHf#0Q5xba`WF}&m@jr&))Jr6lmGqsA8Wz?^C}ztXV86;_2;XM zJ^T@>yO!(-j5z7s{jn0FAR>x#u!jyt@tuS;=y}hEZ$ijcd>NJX1$f`(1twNV*c-bO z%EVt9XW_sQB0YUI>hw2veT}fE+Z&oOq98&LgF_YJ7q%Kue=sTn3oeH`O}#eHK(UVn zavFn{Ebd3FNR3GD0Ajc=B2Kk*5g8OIGmaKeG%%(Db(yu1s5Bp66MvtP^ipDDkttFV zKbEnagyBY`U7qxa6b^M9JF&IY7_!Bs(kO_iy34vS)V~-|(52cUMV>g7fHi8e3}|Qm zV`G?k1q2<*4N|`39IB9;D85s^sXMkc(v7_bMLn6n+gg>e%;eS99k?qeBbF3z{ekMr zg#1*QG>p|)^{=7k*sJi`;riRJs`UHRVXRnR#yC{A^q*-X+Mq~9o4z;1BhCZmwPFtC zXKxO5l^IXqV@NtXC#~5OjYrtjnsq=2{2aG~52}5#sE5vu_>ki$(tT$M*GulB$ls)}xq3EGxJCI~8_2NMYqPJYt1It@R3i+EAgwpF#UH$Ed^qOxcgO z(OF}Rpyl&i3Pu@GS9`aB@?^0`A&h%U+@muQI6?vvsf!!JbuuKO(++(yMV9SX_K6bS!yfYqb{>;4at!8%Dc zV+PT8P>!k4cZno_B_r?zoX>#Hld!688G_M7&AkcSuT;&{5ldQC&P*%qd1-6qtu8`Q zP`|aRR4W##?ObX;f6-db$hkACmp5ATJ^XvS?KREywBa=UczHd8<>m}Qi6w2?IPR`9 zl*pWua6@|^;NfXsh5|2C_L>A8g8%tUuQSbv*nT$ymRb0ZT zowPF{jVL@lA&o42H6e{8yp1a@!WLoMlrwdgm*TcA*{}nRzy@dpC+Al1#hfu~^jbJ1 zmxl=v3PeB=(@Rg$DZ#8W@(`}Y56gyh@~52o!5%LmT{(3`ii zV;w#-fi89M!tGhICLO?paX}bu8d3NN+s4o70RlT>A=&^Xgueja@oSzCag5Gj9zc%j zwK|@OyGY;qiNZCradpm=Tm}OV7A*0|XJizJd^&2z7Qn@@!PJbgrF8d#HaF1E zNmWC(`0w$SfulfMl1rfKu2D?$!{=7Am)Pe|N)#^b9 zG|P*fAgHPZV8UXBmZ)nv761KwNdO zHdNbO>HcT#&{&}Avx#>HU$c~?lj4o>v@}fdibA~{)jW`#3@|ilc2tpdf)5R4w&rea zfSpShH_wk%JWQa~=7<7beedu>yX-+Zmp+?gf+a{?0LhwdP7r8r(Ozru^&L9Pt3Ols7=C8Mqn>Sj>L=?A;4hzQnf zAc&+tj5(*DFoH>^Wq=QUD6^x*a`-H=DpkSuR?3ZJGkROgHCPSH6pgcSMc#W-pGRJv}Qh*!sb7(@VDIW~(h*_-3z%G7fZj3KGSu=HPA%=DD&# zAJ6tlyIcW@LV``a^`f_FoXrhGtKY|=sF@W_B9zrF^@J~{L*Lq+4pZXHrqIBp5KFU9 ziK0^mNggd5QsXO@tf2o_#N8GP>P(!Zj|gD9Q6U3r zIPQgf?ODQ+d&;KQ(@5F0wWubv65X^tFy*6=D|x#eZB2#W))Fh!)T=Q@U{59$7bS*9 z+0ENwYvxvGfMCLiwpxYFW(Y0p4yY@*lmrJvRYaI~Vhblr9}QiTh}fww##H?(QW$u^{vXkH#Mn7 zqDr$SlnUQ7jiX2Np)W0Ps%leWvZ-Xx)3&&IW;G|XDwWT%uW?)7Uzw3}I}Ja&f1|`@ z^P<5;gX#&@aN>>@SLEZ|hJ+i|!ZyYtYnhy&wrXxsB2d5lR{gX=Vbjqp1r7 zBI-U9N=#3Yc7CVeIUy?u;i_H;rzE11nZ(IYjB78*7q#5Y8c_ zA>$wJS->2>Ggor2fe|YzAthfK)rga%Q=j9Z1TXX3YjyGIq0@ii{Yj6(<+>rg-dAFA zCX;5JMxmEyM^-ksz>H1D(w6}$i^r)|qLT|i)PwYG4EK>8D{V`@A`&toKc%q&`aFa4 zK9P#CIJc1;~D_UeW3SO~w=gX{599B$1G`cWDAw9 zRtH1@i}qgWRlc6~Mptj3YXuawx242L=HGrdTXZqhs$~t{=T^X|Bnd1JY$D4Jn|;gV zMycER-r3iVZe=%^&~@!P8&RZwN2sV%08#N_dq@iJA4Pl-Z{ZUr$`d@Z&H>h1OoTV5r0BfJ&k%#BmTYnnuN1o?%#cESFv zpIE8vk7ja{kRxo5OtWG}LwNg-%vOK$Qn+~uzZlEISuduo#2f+_{1UhPBo&+M5i0M* z(c!tY{+3rqFL^hyiR~WaQ5T~w?OPZ9Xh_{OEayYcOCjLQZ`YO2VNjEQ-Xxu=nX5iW z>|d1My|B>UcE2{RXdgIvfH)nM6Q7A65fthx6K~!x;r{3gfoc2dYe0gwa?+FfRats_ zx%{n#t`WBGGu8GYv7c2L|_)CRm2ik23a& zCghLX9P$zz-8l}Q57UBZ7!lPAVAS&wmcJcq;e~do2wzzAAzBQ|sv!QYg>NZ9Y>B_W zXw9+sOZmYAguWERx&&pbc)9HwI`6yS_5MZAm*C2OHc4 zI|Hx=|GJMd6EJ9PxGyr}*JzsUAxcwiHPZHJr{HwjS{5k|ccjc;=M45jr`SHvIFj?% zXGP1?9`CU3Wi>KP5RI5h%n z(`flalRx>(d2Pw@3jDh)_rv&(Q13R6?L0dNAKgWO2L?q%=uxoLNUhWw&fxuZg`L~B z4He~vKs9wHjD?IfR~!B9n5uzl`07(VyQWGYb>5aF*uJrEw{H2e zR|azuSL*tJtVP z#4jp|%*E9O514jUJ|_f4r(exrN@2aXw8Q7*jqlZ84NIvLxZn`}QO!qnlSOjgq4`_a zj~=Isgz3OF2cD>5K)mRiyFh0qcJmO+NYWf2#}jfyLs>tZU~Q!!yI)sEB8`ON2e)aA z<5RPhzp8?>t;H0aV8N|N)}hCI;dA;=;|4O{9r``|moFgff7dWGezwjgrVOTzmc|xN zrj}-=j?N69a5x)=PjR4wjlHuIgOH`Ot)atzU7r-I!@A*qb`(P?yoEO_K=L27s1(6M z)Y5VyN>bYEuo{t*qzU+>tG^`r@THAC@HCZJ3s>wwbCB(dlrxwJ&R}ao(rc)RD{49^ z;F~Aisnz%T_xJa#UG`$P)W@x*+~V6_PAzWR9Z%hd(H}bQu)Scf!o5D=1mCXneujSK zrTrw`@-yt9fXTzTtMvlF;KB7Uulc}g;M`?<&%nDGc3QxFDR!Q~-@os~f^VT;n}his z15<`+W3k+`_JKLWc(EP?0y{Ut1Oj_E#sv1)&#e!llrTaJlRIG`X`nU$&-~gKg$D&|HY6xaw^fvMa~%-HL>bl!*B(|8k5vcF z1Vuu;b_0f@XF>c({3%p5B6LKMV>g1HLl6U)0AyGTAodaDSo@Jx`%8fleb9i7!JR}@ zg27bM2}bv*zI}x52nOkAoWL3u_mDo0YYf=!fo#+qkU5z*yfSL{by9$lS#HDSpjC6h z2|&E;wH8X-nH&g0vqA>$@DaT*IR=U=qA$UE5?fBzU_30O<)0R6#f#CGYeJitS$xP>{#zTRV%KK_CrXr3~AHpYe}nv&fd5uGuUH46zIxG zJk>Z{CTokd`Pi^>>yRo91{-y>jNv^Ra#*6RV=U%%&r)-!E^c**O=Nb;F~DDfGG?ip zn;QGOY18fG5%)1I$CmQju$QF%&=sp%5AWV;{T9ZZp~8K1UpkhaM8CD6)nI<8)Msic zusVvg_9=@qN zUz`e2>d@M+#bIi&Jt9I>1o%~8H(F_6azCpYb)h=sE;zoRMs>j4q)NUVLrm3{rG{Xp z3Yr;VSl%t%<^R~#JJKDGcW`Vi70ACANy=%R+ZMMTmFTL=F%SZrT!o8(!qZTroL0t8 zr2L5Sc(}iv8ptF4+m@z?mp9a7 z>VX69-6}GcUEC~N=p2g+;bmH72;|5QB2b|51{|{-JxjFZ$#J90+Vl!?4m^c`!244C zsiU=dyl&IDDDnjKTVu5Yu4MAcl6e~I>@t!A>OubjrHq`z9U0R*D6ZwKf_kPVs~hDN zoBsB(0-@E7lA-*4zttx8`VKqLUagx`0I*!pF(=TCr-PlnY{<|xLQex*z04ge zev&PRtPtX|sQ{uY@Y^U*B^9TZ5oN4~K!b&5TTlJ`Vd?CAicrRFH0WaaQP5c9qNW7S zfMu$}Hf#Z}sa>oZh)KnyHlaSJqSxaxZ`bgW_3PX)`Lr@$-N|tJXo@^y{kcr;&kxQq zejAfMmldJ{WFhe>IIAuUs?@qH+Dd!eB26W~#rnh?e6eFvr^xE0j??ndUE8w2iAyKv z_>@)K7%d7sXZ+W%KmlQW`-GstwIDZwO}%Xo9SZx0Ng{8B6wNzq_hA-?1wyU2)lK$5 zTORYBTkdJ&56zmu-55aF7UnE*qeLZ9hs!gu;TO6f3X39Ioe@Ey97;$VkmPNnM2mi) zT{Btxd2T;qng~aU;E`;SHlv%;yTY2|Gv7)8ER0koH6LHxxpApz~QpZ7Wt&szC69h zmwd@%eq;BW-pG88ZnCgJ`F3h|2K*% zK%CQ={jUX7m3Ku&R2V#ei^|Y0cWdUxLC~HPM=DB{usFb(IO{_Ht?TKqfweC520f*a z1&(7k(c-%mP1PN}Cr0CZ;f|*#+J=OD04PZ?kTa0T6K+F{!5@L|D}pCB1C%?}3aM1)x_QGxKH#?bQe$%llo)_phEx{Z#I z72tyMky72wisN;(CBZ$He~Mw)H3pW6c9fHZQYcY$Qu0|MEu_b?bb5Yf9+(|RUX!04 z4!O?}N#A%l)9vJuDNyjF^U5&xnb5UF*oE8A^i+(yQNL z_->SR2)iME0U@!6f;Zf-z#nP|cZF4Xe&m42Cz9*XO36xlBLDVJzf%RkL#F?e0j%?H z8Nkf{V}0=d;dcI8g%H;#2hQ{@)x!UO;$zi$c4Ox?m_Ip zk-?WpYJXo&d?&;|vO%+s-oo6T@JpSisWAy}z9dN#Uk5+!hgD+HsXGzlACAKjuG~&5 z$G#-d!B`JXFIi<{$(>2Yh?#Lov&d9jWhtI_-s{-fWF0LIJ=-8sA#j}2MqT#QTK01@cHH>W`=GJYx-PFQd}Le@8+9H&dZWB#YkO+LT(hjIHacKaUK$e=V;reY(l&ozYy z2K=W2nwh$uI;TuSrLKs$l(@!7b1)*J6eSCUhzRCg@G0Jt)JgC~q<&!yVk#pdZbG55 zOkkCo3p&HeC|-yFLp&~C2+3630M(MVko{qekc<*#3guDc6(WvcV8j_TjuN>+a4V!V z(CF)O-xg9N4Kl{TRW+=JAC^tR>&jxh5Gl6lSR9Bdv_G{ry;)$=-JLiMvF2Gfh6BIp z#(-453C4Pn=2Kj%QX)R)E>Xqd!6nYG&V_UAWYb-$P+i+}kJWX(2xip5(c_(r+u9N^ z^?M-wu`Njhnf>1I2XXk(=-S|FKwaMbY}jGIGrcw3a=pA=PSz~$C&&I(+Y4pZOsi$O zosyu#8a*83+BuD|icX@#rw*EJJ<+-|`a#MRxq{udxu4YI;RM=Md_2H1T*lT(meb>x z`nS<^GHEyK7=-WU%Xq>Q=}NOnPA>cFje1Ja`(RQ?V&8HdT{_W}~ z213rDkJ>FnLGkb)=#9?4hg;{sg+xJg5Mik>%J4r;hufmLkXoU49 zb6OCkx<|+bTVjA~4b6!-wU>$)`Je0(f$jkLv-&o8@t!XCKhg%l%n%8`^~p6yj=Rrm{QkE3-LQ8 zA^AT344@-qEtFQKHtz-}EaM-oxb=}uuVK_|h-6UBOMliCj?pPA-1M^2!7Uwn^GB<; z;4RP7NDkj>YYrJwmA)a~>dU+U)R#vv9GiOnX~(#h8J1+D{@DRD``qmobinzw@Rv*X7hIr9T$t%P?%RlTG4?9Rch=sX* z9A4f@^K!SaB_g+)|6#|FSw=Scv}3%aRd`r2hY?32@fspwT2h3i8MCEul|w43r`?*n z|L_P9W(-#~6aDrkJvCMnM(hq+7MZOR@kkfd5JZ_)EO3QTP3n4$CcaJC0W+%{l*S45 zyCcDfekFco^)>W84z!=8`U_&Q(lu$e$5(q|#!tcjme6*&!u2~cPW_JPH~9$eiPhZx z=zlCqR~|0YsXv#bj{nva_CNQ1YNr24iv4e=y1Iuu`XS&$mOazn)vZ;HDV#M!ELfJ^ z1OuHh9A(6xit8t0(YnUk=p`v&rJ|z&R-CUc^syUxeNBz7xgg;Smq<`f#G~D>t}6MD z%k2w7A1l9Y8C3Ssel&+%^R27(r`PVM3=jRk+mQ?q8liq=&#e)|D&9ha6sq2ugUc$s z`Fm6t@)ho4gHNijKL)8V_NmELI*ax~so#tCYN+4IukroOA!A^9DXu$v;lYO?#UO{i z%E7#9>`;IUU_7Vy(ty{%WnsC??zs5p!oLdbq=NULJ~#E+fAyug=JDT#*ZKAw*o#Y$ zWEcy5=w1Vj5hgK1(bq+=5unE)RW}}aHoHGaeSV*C%@6zN1%xot>%;{zl-H^U_`(+G zMO@q&A@=KitzD1gMsNqxATZd0pgZpe|eVz#^JE zh=9i3e}K5WH9)Zr5+K5xun>X$ypWz9Vbmy#XP!BnEfKYVPz;r?uTSR?1e_5CRH%^k!x=$2bf1JkQvGWd9UzD{1OwLJkQGf6RAMai=^I zv!JLb0R9-x(a-q&_$Y$Z?|dd=4f!ci`~}if;<4#)F2|M5Qw3zg@~oU%THAG);?uT~ zvmki((u5RXuT>m#pY+I#n3r2a&eGq>&vR95>4+b-^<>g^Uh8z2hS}?GDoZXIx<;W~ zd>R2~D%~DNhrA@g(B(UW&F0%*3A-}AFs0gGU-pSbuV}xowMeXLgTp7%=hksmn>Qfd zT`K;xXV+K9G%6zDhTFjkJf*3$a{_bmfuG9u>;DXhJvw^CA=iA9EG&&1w%WX;#l7T3F7X)RP`4Un{V8ma$X#escTGEYRp`;! z)?_>y$PA@pFH7rAGclh;TpO8pVpz~St=*V2rAw6o<6){u3Pq0JlO<2od=7WDuSm9Y zmX2~Rb>SjjnyD3>x1?eRZ@qpE6wL!!%Exy?(!NH$;>l23bM=)5`0^`4x-b>e3plud zLS(knN2($hnZOuc+?l|gXOdxO?EipQU_GrVDR_}dmhL=ONZMh3s1`jI)7S01l^R^^ zVS}6j*3U|*a_4J;l9L8E=VuF*0t4}L+X@=F*Bj@Ph@so4>$U1n1ux30R$RFR3 zI3q{342E1!VRPySMs@2~x30h0$sQ&!MU*-E%_NkkIA$)h;PaRMqPZUJN@w&$DnSh0 zQz54rO}d~RFvH}H3!6_%$CJCDm}i4*??+gAJh8z&_c=6gH{Jx=^rPR%$P;H7MV@Z?79`!!spf@l|t&8eEwk|Dw zC^B8!%&SePR^i0LcN9{1hMJO=?kn$%u@rHd$O{aHG%HX8u0E0V0I=rPKj8^(T&Bt9 zdFM*{5O7kq36(?XmA093Ll{_@?|h!FVO?pXtjD6gjnX(IF@*)U57usqSZG01X8%m$mMs0B}%CtD<<7jXR|ex*8VyoW$y~8pVvUU ziQHp>5!30rCS9YL@pMgEgE5a-=$0cs-^gRl_7j$t1sbbfYuaDIqg^hUQ4N~)+_wB$W&mz$zCB7n z)_JS!j??tWJ@!2EfIwl|mLuNOrPpiazmGC{K zW^g<@CwvimdOh}POBZgEnoTS5566;ae^A#dMZ$YDq$(YFP?sgFmyg1$(lBu^@J&5D z>oBUE{cvfc9Qb;_)ZMfttOah30vRa{7#jrBobNt{QJmp z$)2iv@B!Gd$oua1kA|s2`s`fjvo`tpZ+Y1q|EghfakjK!Pnu{t(f9{UK7A2o{ywigQEqj3KH(5fFcCD3QT=X%dhK zt9lj~+kGN`(^sW6Gq?5z_D(rI4^coqt3-ITvCda|)#c;)G8Gzo^$zWT*C45ZQ*G5+ zVkic(MRa5RBucpz!gpXGP_L94NKoJ@I4JZHL58{v#4VwSi;07Gpd*~k)ar{XAttUA z8q|Q#_vVh^v<5Xm-EtNiZ1fi4=nVz=({S4FaLeIR8Z7i8;xRd(kwBFsxk-D>W3woz zfV?=V858U#ID{x*DCUx9iB8ptao@X0DdwVQ^Bp&liwWfrN^wERknIyPf(DuC>7M7b zJet!t6|0idmaLB8Z`%`7w7e;YwYFmuxPt@j&Qgp9W4Lu<{G`c7S%@kk|k2Kl|T3x>D-lmi~k9A7)enf3rNQaV_rlN$E5lb*3Ar--hVy|u12dFyKp;F~zw zeP(C+*bsH9uS`$Kqu|G3f#-S#ZsCTQd}+c0m&QNApl`mAAB~RfA9!Xc)0(4QxMElY zO;fv0X*xTbJ)=6(RDg{!Dj0H(YChIKeDkt|w9O)F*SDpW6iH;;n~YKEN^X}iaXSC8 z`Pv@*5;d~bE{CsGN?uj=?yvUfWCRT4lh#~3cb6jl5H46Stt#-t@NuOQt2w4qa;1{9 zw>}^{c~~QhHj8}2T-R@rxD6P7Oz6qS>XIb53eTnDm;X(g`Wi&)ks}+Uc3c+uE^5~C z%|{4}|DRGzCgWT?zRwg=u+Qnxzm{75OQQY1_=hUF*!*WkZL*4_GMXUzdj_ctGlKTY zS1?gUa#*JCb|d6sDHa-}Ntj#Y`LGZm1Ud4Q!|m&#z6va?N>qi)PZ;uVc_n>hFu?+{ zuD&S#i4{ zO+Yax*-qn6b};j=jqscddBPz#Ua55#l7Te#+z6_E z%{q8a16!4n+3@DCY`o2Ie79CxLpixM2uJ5er-x*@vVGchm@ zaS2wb>Dzo_xIVJqJ6c-Y&eWC+IYN5jTrb27Ee7r6fJkb1!j_w~VGhe%E~&}ub6W)< zfzG@u{s3fh-d1(VBAcmisAvRH$mC+8xeMaa3<=n1hz~q&h}ta$l}x8^*>`UrQ*J%; zSH8fj`OGgbK*fQ1;*hUdn0c_ABnE0f^m@6#Ai+ezLVhOvyaU&B>krXG^5Q&ChJhkm zK{>b%`U)+C=jsF_{cQ$hnEMq7$Vu8c;0+J72E356-s!Rs<2^dLM+h%K0%D!89r9s) z@Lo(i!yuT^5uC7h;H$jB}izUQK|z79)ix)?Ogw<^xuBXC9A zOvJb0?nn|?jnr$>2AVoc}Aci?lYt4s3- ztr`M8kvpkVJvw&jodx>Lvz6E!( zK%@T*f){%RC1?xriH)o>hlWaXY$`($Q7W~T8l`b>WVMrNc&7dlf1x&o=V!jl;b1iN zAb|RvTQ4irLffb5L6dEgfm5}KIXw$bxhq3}U9kzelq9w)BNcYtG6-TjuEu_M$nB&T z|9s#{q?AeP0YA?jQ|oYt!XXs%CJi!?hJaN05pD85ca&Onx%?1JttW1=rd4GB$zpL# z{`gZOa$=az%xg{OTl#yGjc%v{lh4GkxG8+EF~k$AZoHj;M*p7gh6A|O2QQMCZWxI_o=u68YPqSN_Qmb+d4zQLK@|jakFShH zTHRuz)b226c)RARi2db#)#*u0wHNh;RH~WQ8!AlXr?NV>V;8p}h@5WwDQoJi6B4O( zo|9D*l~K8FaaA$)Iyl5f0w+|(|-B3a?YgJ4gNrthEI$((=TFUhRU4=uPY-) zXe|`PW*pQ8OlUI5XfjIixFN6}{%ga+Z@}+8!0iz2V&w0#%hHUP+kpQZ;j)i(w=dp| z))RlByA&v(5jRRZz+SiM9=-Se`*lx zs@y!xL$?=nAKF}2Ho5;u&|;9KrzH85+gE)GW&U-k^Dl`O|15PB{ugQA6r9=CwcANL zwr$&H$F^pxH+SH4o&8S~Xs^JUir^~I6 z!yNo$pvGN502V_pqr%aU1UsL-QKVRU$kaY?OpJ$j-#$@{6c63qbK)>c3^h;nZOhO; zR}6M_mJht|)pPa3I8@8*5#em_01%n(Q%?Xc9>mJ&57IUs^-<3X`;`Eyj-wx}g3=de z`3YeGcAc>SaxvBFJBz(iEh&Th#UJy*Nq=k(Zn~W#HiyOM216Il(QtvORsZvE*ZUk^i_FDaQcktypVr#yb@@Dkcb zMpaOZ!oNsvV$;8CprfReZ%K>RRH!a&(HOyttP!pv8+z>a9UARNk^FD;0cMy&L=>fT z%Ixh{=X3$5;nS#DDNuDKqAZlBP?g6_VMNK*%1SbbmcsKnW9@O-_;^+j3AhX-$58X= z7|iDfswnVr?X;K{y{14}YpgV0f8wTal9o*%f6Ge&~c4~T7|Y0?-mYg-D^(ClEcJAzQPhml*m?njfZ+Ww2<;5 z3yngm1+Ea*8jg>M$geaUN;6%IjN3rWvjkWn$x$)uDd-{9wMqm?_auWj29op0MojD^%}{m(VKUBUDgiXReO%tb91q)OYQ$&q@Sutg((FJ(=#k^* z-j=;9Kh)54L|Kxn9D?ckq@2ZI75?y^Kf1`nU$af?J2??B@JA$*@A&nsiCyrC{yLC6 zx7`9IcSSDe1(aY+&iRPMzpM(-irIMFJ*ji^>u77)T5wCu(VAVg&h|lGPXO|M?;`Ev zc?IxcZ4UhGG^h60XV_TE*S{y_i8-vq=UGKl#VbOvLlv5sgK0Q1pEA$OvFRa+%5vqrAKJ(D8V_%hj&*;{lheY$c3& zW;iC~OE7<$?`%pCg)#zG*uu<{W27}M)4bST>O4`KX(*9_+Hqj}7wAipz*2O04jyE^YTa#norE=UkTIM29pyl`3KTHYQ`*RN`* z+FX>E8{KeibsCd!|6`u28{b@G?i^z8D--eomwp`;Q~+i&eF~oRxYz3>e8$Y=pua%n z^s24&6Ms&Nq82&PeTnQ3=wHphe>Uq+vaiNp@?Vdh|0-zw`{)rjuy(eyRWfmKF|jrJ zXS%jgoR(VjuIYs)f=C$}Gp4hT zbXKBWa=<*SXW%N(mRQ6}o#!y+_$*kPb-cwy43Cs7D^^XAY<1LP#<=cDn2Lz?oNQz2 zbIG{M1DU-IT!@+z=eFp2H5*Job7P(W=}W*AE%4`^CL#1_Q{Yi z2pjQj;&ixw6UoZF??dWA#yP~ZBq3gL=RvNiMGfc3m((o^EwC22UeQ`ceb0gwB*zv# z6y-9n*;HUnSn-PKjg;5>y&*HsYd3eMYM?xIe~qx7EnVT)ia*9bcZ<$)5%L>>5+*PD z0EU$^LUlqR?{1+I^h7(6dQ?`OFj zxc=^j2^`k?%WfQoI4lapcVHfjz3JYnSpm@%uoIM00|uZ1&!=k08q+QrVDNUal2~gi zGwIY!8_+d-rJVy^NNS7QI*=hka~e#V>bRxVoXff};0*0bXipkn2=jU)F_^ zG3alWQ3E4K$VGhg1#L6VMxoQwez6WX4^@5y)q zdVG0ben%&AesM7kh2tr@vO;vAQOJTJtCfCbF02)l1mk>_lV5@WzTrPnKrlU)KP70S zmVPD9am^8rp)A?lM50XmX?_bX*f2a=6N>kTe(gA9skGI_viPK5NWXj3;QQm;!r%8B z8_Y>*@n1kE|5u>@S3=m|bzRKF&c?*q(c^EhlgJx5n=6@^*_hZm|1)GLegXe$fm*!j zdRi|a1r4DhEV5D^8+C#^l%YC_r6^7%1EV(YN+SelFm^33qbH~_GAv*m0>1|J#@=5Y z#EvARn=l`Ms9paZVTMoVn;a{|86*i6L8*+Z zp6Vvw^D6>%L3?AcKEkVI-w^to4zI8_fHk;d`Gkq*u`hu6Ga39n3o@7p4^*s9*|es~ zPv*5SDfwmV@G7*zzjlNh!5U=O*h&|^%Wb>Ck<)oO@}Q9F$;W(cJrwih-D zsSWdn1QD`Gmx%^PoOEqpLGDDY10B)f5K9K8L2M(_b-kvv>@~eC2plmmpc=%4nfBN&jqF+@u`q3Pn-TMk14J$kqPrP0zJ+Af#1<9Mw)C@CP+LscYcQQl1IdW9*h40)W; zHM(n^#GW{zPAn@Iq$`itDH1uGt;Ser>QjV zw=*&NOi=kERW8*@Am@&XeO}zFbMZ5%HpRBvGt2bq;&aR3YSS~z3dw(^-pK^+yYlt0hKIUT;26Fc&UjSY`x z_}+Jy>`xt6+BfvIpPAIZk?1%aQhJU-yQr>R*jcUD%@ptmj&Q;74>_0t^p{Dexm@fzr}x5v(84%&UW=g&?%7$3^B-g|?8%r&il3QUqeI!sbnGwk6G zjb#5_u;X4v@EmA;;VF{+{#)?akRBElctG&jpi}S|aw1SRj&G7X2r>2#hNt@aL%>a##a+MLN0C^-8J0++u&z<&8O{Z{E zd88~N(C9{=qla9I-bbaSc8t65!Gn`x{Q>CGzFS@uLt(OE}@94Z?xiVC)0 ziCl64HDY8gjwSbNv$i;)u%1#GM6tWppW0FPSy8n7esTgp}^Yb;;NAOQDy?(-bP&aoZi{l zOIM8_DH;I2PQ(kYVRs%rAk7$K+$cgc>pG=8GxRMyqw2=IaNfE(`e#ZSEl%{~ZuACV z%RCVqdn-q_m(R&5@N4{b{uVU;=bKvIyq>o*^Mj&O`?`?hrH$#iZoP5vX#6}1)d33k zgnO1vw~IDOY&;>bMibAw3mxMcLTfF-l0x?k z-dzAyJ7#SLPz7exMG27CuR655pP2+!8Tm(D@`Wk$*o_O3Lnp_1;;HSBgJ;ABH+%Bd zGH!C2$LXk8fJ*xnCslBxJhnGw59

NH0lfMJi@~w#|9Dp%R@SkAfhp*556da6#On zcPbol{C85uL^mCI6tp-wA>!Mrmj#jTrxO|*>6E}cL;-$ac83litWt7DVOdhW%W zcYxfEPpNgsPWxgaw!5Gf7r4u~16ECj#@ryN1L?AYYrkIP zg=+%~I3sWF!|s}?o+&?_9SySeEhyIXk|~{oI}US9!PK#XvWk_7zvb~NspnBVja;%A zfAn~VtemP!(|Co4&POSfa=UJ@!ler=f%NU=gkspixf@rg+1NY}T`o5W_%2a_M++jJ zH&{^%X2pmqh%ISAvjO$`viw$Xdu1oPkd$HZ#iqfBoEpqel8`o0ap!}2Dqg1qn5w$5 z^vOPF*{5ieiEVZ3_nBz;2b|W_38sEAcw>8a;L1vh5_p%|`uL5 zy*3SvQ#luQi5T%JeciA^8phc`xe_}t{F4p{g+=n%wyM7$k^4S%uH8;a~9 zqY1?rqi=EyS2)Ai?(rMh`fOg|V%MA8h+~?DFgM7OogYcfWv%As~ZF!3T_YVC7m@-ZzGF7H6=elC9`PQ;rk#M;^?ZD z!kwTQyYVApe!c{=n1F^uE3B=?^bpz{DU0DJH-^^dU=pYH`q0_XOpz7^s}XxFLbg;& zPL5knx_(a z#l^UBz*pU~UG&J9dR9?Tm4f37!>KzwK5}bWBXE~>&qV@?1bEyZvmBlvp23CWV6y6j z8!c5snQlzAyqztx^fnT@rzMNli+yur06k87-`bVAr*O z9U>y5E0&hkHI@-v9qiQ+&BBh|B2mgYqL|XB|7%L^jzMN}Slb12Oc^q{RIyTtkEMc1 zd;DOt`aQHfs6|9&&(?+WQX#@#oObAgM|jtUIa8w8)R8%D%JzfVXBug!I09Q5AS7U{ zij~1af}>jGK6XHIG=ofop2nKFt4rDswmELv0?PSL^{tET10ws86^@9XAn~?nHsqmR z!*_|Ley9B$;?l54t6JYI_r)WzDUm-0RE)7~;^-MA9ck2wi1^9Ez=-H29%A%8F>!|M z4@x@nXrOc42WCOrg%L*(Y}kQLeoqZ>*5yj9_$58}>A9Fl`m3A-k$gqk{`t;AbzmOt zp_wo%RU;P7TymbMR`i1=Et>_keG~wx7yt#{$hA?vxE~6DlQTbe5M2LBZxQ95?!;5D zq%KyAp&>DWKxcL~0&cg*q@zAXk?9KLL`T3a0dgQX+02_E%j=c8?`LTLCmg+X(&1+g zxFgIqrtpvS&E&d^Y>dgv)%hv3^YVurUbvX;eF8)iJh8*Pipur7-z+cCAJIW2*JZ-> ze&1gJ*X6>uqlgC)Gc~mL+^dV};#<7G-knqQ^iHPp`-+9@jlRENBahmc7*zu;!j?c0 z%ZbRBd&-wR=8KA)o_U>~IasT9LX`Ww`>w|LoPD!Z1$U@vLlj$(ahKivg}zY5QDHmW zyoif-480qlsP8lt`YJBzm|aGfYksS~2OWI+$*AK=*_F}OC|9ig%7bfSV02VJ%eQ&a zPyuo>TH6u>^+aFymEdYu*PMB%o-E!q>Q(!R>OS@{EmSSmzTydG^}#kTGPmFC^{zUd z{-reOo_yvxr76%t#!WIpT_%lpd$svQ*9=cDI;nhb`QZ|FAlmJ6%?YE99;J~b!EGh# zEx9?B8}iCy_dqY87V`Y!Mqga|mKt#>*6R7Q_2kDwc}S`ye1R-)Bwmk7J2v zX6q>i`~~Ek0}S}0!$xuTfX~@?JOdAH-obAYJE#vZUDLOjuS{F=dcAUs4bQEwR9lLA z!}Li$B`K2MCPj*)Imf;v)r=V>8Y~6Iv!K%PLXCW#x3vA+M6Z=vQvLKV3!`R|UJ2-e zK;tO3=dKzJ0^T`Tv-49S!WinDb8mu^_C{fc92C zO!|{EG11AKAcfQyXe{_kK!BXtAEPHRaQHifzq$Lx&z)~n3C8g-n5KIZf!F0b$f#A- zIwJDs6-_Ia9+nXLy=&Di;X3ElF(O)$ZWT+eT5Vb`E{pe>US_vMz;AEAcQUUs?|lB; zWnFn6XST9;-7e1Ve@Yx z)l`b2Xwf8DMHQr?S)eFfR4QphwOObrUDP58c?b%AALF>!pm(+Y(Cg)=BKy9Y!fUv` zmP188#iEkEabP-`v3!PqIA8_ce5{!=tytV?u-5z*P}GlVcQTqY*o@~&wWSr2+~M%2 zxEbZD(=8jb&PuO(?_;a9A*YM?_m9E1kK-+`(en}2j_DRY-n-v>*>qOO!% z0af=)(d-)Y57mB)C)8K+9rSc-dJbp$&3n8}2FGRG(Jv@=mTp(va?v$YEA_%RUyjAz z*{U5^zUp^Ctcv;|xAzUG;GAM>Z%F8mJ0 zHG8~nu9v#Q!42V02~lRgpB7V^gKvvU%|5N>6HG;8EE0bxRF(>RskB^YTQ>3is+CQO zSjs|Gq9hrO6s2$0A5U%MI;xagmC_+8kH%1#y`xr$o(1~;@k`p?&MIyb=A@agrWXA^_rpj)UGeqVqUt5BLM$Wk=pzjraM3-bF_I))}Q?IIi~7R+l30xDW;UG!~o zS!UuWbWk8fkdz?%U#ZZ^4QH1Kti+xc*}w~|B+b}ZgNS-b>jX%)P@<}KS%Z$NZa}e- z{KcI(IO@`mam!v9&Lz>8YK}Bi(MuM>cG`qbCxnU6%I)O7W1BU9H}nq{W>6j979hgf zZ|YaFT1U>ax5$Cyn^DZ7BTv;?98^Q5sXnv(Vm(HpyXfjolA++ar1qX1S(2!usmVkI zUNWi4{J!OTOwW%KK1Fivq^spy%bt;0T!IojjN@eE8d_}kb!C~rLx)!m%>i*~3aCtX z-YWNZd>|+t^pSTm@&_c#3uRsvPKz{uU;Cv5ZrTr8trWfZ{Kxj8Vqyu0O*r33z`0POwjYCpIuiMd= zU^ZSmsTT;c3U(?yC|&E>aMe#p0XMWMJk=s}Trey-Z5M#XXR2yMGn0pIQ)6^%vv+O@ z74(v*!E~=@UI$?;F);Zh%~U%C}o`O3o(1-GP=Gq&;-5#&6J%8;y7KRJ-AjE;>9z) zpH`cy_9dONv5jThKu_io7X8E5^Te9Fd0VqCa<T;&tZs9{%)zf5J$n0c-?TW7fy@y#OuU>=#^WRS4| zzWpcD1-6%s7;#8P@s2q06Th97(2qfQtoPzB$N%}JTx~R^4>z9<<*N0*P!k2pEzuM* zm=s47IX)A*xh4z4s#?zRe93O-v5~AcdY(C7ua$T1INsU7KuL*bRx*IWZ$m($3k@~nz zb{!|15;>)%n0#%jlIifR?Yp#4te;|77ZcU?$ zp;`4>5WcL!lXK3f%IdcC;~{qv6(dPl6Q_;DMN}W=ilo<#dP&x<%u|!9F~?#DOdMWk z4RQ>=Q1Z5gTY1)s4~Crfeq(mvq>jZVNXGow@LLznW$a=MHuTGvJ!;lwSl({~e)*&di~yDA$|F}1KcJ6gtlAc;}nl<3>Vf;?Z> zO+U7KWXlJPNa!C!;yyu{%CJf0l{u8nEyxsKs!;Um_;E6qIH-iR%R(5P|0?2q!bE7@wZEF~Vcg+%H$W7tSic3dj+n=CZ(hO85Lmrw3- zwofd7JQ+liFI%7@18xxRNT8+Al3_Ni zvbXXxMohpmO`3hj5xsI6PC>dt;a?EChuz5LaLyg9!uQd!5@Kms^*@~DWiVUdk|!{w zn&6d>fWtjTlol4#@|-=#{M}Q2qza@)ftN7uUkBIHW`8UTGpTetF_~|%6!pe~7E?B{ zm~Li!4GTj-`F__&DeekW;2cQ?i`@FXWL93dg@oIjBRkK#Lz4I!4fPDDO0aFxWW1wt z?4C4}Oo?4=g@%yT!A7l)qh2hL!fF0TOdkmp@|CNZT=7SE!K8roSy;1$r@z*8(yxFO z^`2Hk91Zm;)aE#9B8TdhC~b)ZZG+5%6=OM|;ZfSrQ_7tQV+C7sweLB6YLgzTV-{=H z-{c;`M!y$2Nt4-2ORkPfU`Qq~CJm=;7+G0Rq0O^Y=3|Q2cKAap?J@pBmS!r;V5WrS z4O3ybaFS)qct52|)2w(dodc0Ox2V_Tha~^$8=TbSc%CdR8;E_-QEeWy>MyF%U)i_+ z!#Q<4A5~SirxGt7ZZn!MPs>o&T7>!nhIIj5z3@SpCnhS{{uehd*_3r$c_czm2B%~C zFiE*EwHXgNK?#zXVs>YmiIk-3ElZpi2&a_a)()6t#EXO}B$PR2b*@RK_BdmfYHqfw zA@ydc4Nekx%ZaNz$fE*+&O&5L8R*rFC2tEUgP%X}RC&u587F}3#a{3H$b3zSYJYsT ztChU&K!Q@nPcffvFeb|-W;TW3ruXYyxZmTm5ui+32z8tEt<&lJ8C0HggJToiGr&;89y%uT#Q-BVJfGg zWCu#lKmg*0G}UdT1i!vHD*Jbkvm?u7@)_%=AJ&fgy69{XF*++u2+cVTTR$AOI|wc* z@bf4h2Bbh4KFLQ~jl`c4R=qLcar-n6Jr<`&+eVJr&0gO#L!iAwW*i`!93al=@;KlO ze3BqJoFD2FUEsWe2b#-%l3y) zo)x%!%c8sIdgK_dQ?Q>&Be&gi$*Epm?`D!PenFuaa9Or~Eqy}p1&^GXS|7ef3qy{m z{m_&%R`pl*zvk_zJOCc*m+wz4_P@>B6#q)bkuh;{`pU}thl>-Xs3Z49N#LEY-h@Y| zK>dyw1lntZsybU5HUJ(v1WpykiiKa&zR%TSo$+jS< zIkBnQs|1-~(=A!E)Rp$RU^mwq@3U2}wuFF!9WhL_Om>2N#(5#e2-PHzGQr_9D{mfI z1&g>nUHq1%D-a<0uIVpcm@yU zpU(A-vVxNK@u58+XFMdmVl5IXuotbmxta4G>7d9A*hzM&uTV}bN|be)5Lk($1IlW( zpMR$;9@FYs?thUHetxNz{yQ1rznY8uO-4}qGMhB8w(vACv^M$SXkzd`e1xRGIV~8x z^W8;Od52;MC@2amwgK1=ih_a+WT~R`Z8 z%&-_=;k*$aM;UjMoOeFl$IChR{6IVbSNfy9#NaWwG~DW=f3{w|>pv)6BM?ekV36sU zDApM+iOd>!h9px58)2DAc?P^8RixJ#2Jdv6d*(9hf_m=%=!*@8^ad-$ z2bDz#QWVHu16*>~Aa^U(Y@nn)`z6t`ZmQ$!lls!5o$Kjh*CXAMdQMDn9*{6eWiX33 zB9?(G9&}JC3fA9vi=Gnmg5wNg$+%#!224u%$5cz{xagN%3bzVFXic^>w0HUsgKG-X zPB_-s>ep3Ff0qL-d1%z-amPt3_FHX;W~Ku?i+*PbLOm~AZG=NE*fJFLBxF2Hi*@mQ z`_1&O2k`)QU;Je@v2E9RKwLD-Xi_U~clcs*TFL3&GW<@*oAv_;c}aPqVZhWO#38!9 zq){*Uyk&d1)Gv5KwhI1%2dFQ@h8q`9rQoIe^r=K@{!u{FQ91rD^UJx zH2MDx6lV)NTeYwCp1q0V|A56tt{n>a2TbO3%N-<|Zy+0;dbzqLB$}Ikr`wQ|No#_O zT(4ZiHOM;!qd8%zNa_Sh8p+e}1DJlKZK!FeYA9PCKL*{?7dvUuqgZt`TZx}^0lc3B zEpvKr)XwLVx)W8YG&E~=N!!^_113Fg)bY2}aGRkF|v^C(OV=NO; zem~?((?NOLG#>)O-Fm+bCV2IRA}D`kmIeh8SS~EmRg9GvkX|dV4(bx-hL(HNH-!Ax z*TD@-r0e*qt^{9S=)eC){}18cfBZ&D<_7lv(0{X(wEil@pT)E^iJ+DWt>P-VlJsMa zH^B% zY9iBao8J$JA*>y22u2-j2v!=S#bBq{Ukl8(xg+i5l*`?dVKbT{-v1;_XvdmhYS1D( zrU2GVx^TvB534%0CAwoY5rnLm!Q2q56L?e_P)n*ODRpUH(L!lu87$%ZE83ZQsbDUd z%BpWx+EqrMWB$wKrrK(~4hn$Z@`&SRcp_fB>huwKR@DHoI_LCX@pch{be>Yv(UVfE zktmUEH<>Myq}8Wuuf9FPJ$)NPM|c8lg9cRKEj3GxX~mI-Oi>SGQ(99cK$S<9pu}bAAYd}Tmtez_&%TpD zyb#8)9=;sZwN0Q@xwwURGYn{0?#mCBg4=`lYwPVlQvldLf=EUm_#5zVmTC&BTrS1>K;DUf>$e@}}bVp%5oZBm)mok|Ru<6AZJ86{5!p z-8&G%2*V?KBUZcb_ENB07NrTxXSC`ptpv5kR6qTYPHkh|$dK4D64oOo0!7THZH+mx zb;UKM79uPWPjyH6U}$kmo5W|$5@lOh{hQdEIY%I3^TkbT_*cH;|HIGWKd>xl;ACN> zc7=#MGvf^Qg>X=k@v9;&N)gVZ|;lsmML*n?$(eIZC7e_m*&wB94pcO7h93i{EnO z#j!lFK(R#pPyJ>{r~N`9q(5@hkoKajAu&h~i;A>#U2$Gs-JV-$bjBc*S}f6(9My6I zjy3>IU69|DVt$W>x)9Fzc1*ObUEMB+EeBT`WHNsBrdM%t zkux7Qd58iKA1!h<0zHMx2m;ie&+&5|Ay;M7&@!?t%cp&>9S6fd*0{qU`zXU%79kL( zhu|I9_Y9#%vtwamoEx%?=-j9tiltx$wW@ocUjS=KpMc{+10g{UaMp zQv9E)9qihETCW`lr3gip56~Ki(#;bvER|t!4^wG;WuZ0F(RLlxCAryj)BQkCg^&sS zt7tQ2r=j7aAo*|{XD~Y*W!g=7^ZWXKfa$|YaoL`+f;VWuzwA!U4jxFxVZm+C&a8 zkX{6X3~2P!*AK2*C*6qJN#AMT!miwBwTmWVIr*Ggm+SG_*+iJBDk9EdG`kc}^_!>| zGx&?5d8BE%vXN<-Nz~q9duN*WybK09&9mAW2P0DpseCu=DQC*7r-{Lw7Vm^>_ihJ}3Y5Apxc=$>8 zySJCt_lS~f-QtpBE7|dV1sr+uf}`OdO3JvafEu)$qxKN*cBz0)qJ3l7dNQF?e2$qx zTl(O%Kl{=F)?p_m;Ae$#$T>Z++zx)P?sNO(_-@Di&&S3V)XK(7A_z!n#}&8hhIS$1 zyF?buB1=N~6Zw(ARV5NTyfcg>MdIg#WuieO;(gx_rOPr>DB9#4;CBNThcGMLe|Gs4 zl0IJb*M@J$ZHQf&N$S^*#Kd0vV_KRCS@H@EIw_}0c(_UNsU-gV^#IzL!{8lioRw_B zR1oFgDP&Hym4w}H19M3^RPW7S2ZR>tgIS=SFB*Pzvcp@>KU+nwu(VtWlIqo6=8`U} z=&ReQIz{47EslKny&6eZ$tRqGlIG*@PHe&V>{aaxx3K?;+yCnG`oBA||F~d{QW;hK zYBoAWfRmiLq#^fyVu7JAR%3`B` zMs)AosE}I%-((u!l%H*>)#z?|e%$Ua4^MxaG9V13#woyI=dg8*bcl44w%<5v>1P~t zNHIz`3N}hMiZ;sL#~b#E2FKF0R~GsP3Ht+QekPn4i_2b7h& z{!+v|o8ek9`xru|y(&o+c@|UFkUbf#v{W?-54i%uIn#}_x=EV7D)QENzVv+xQc?N= z7^dcYGBFRB&lsTSygQMG(Rm^jkV%c6T=XXY?B5ir*==0E1W<#i*1I{^O6w)_)Foqn!kyDGZ-yxdogey#>4RD#= z{W&{|Z@5Gt1H^van6u!OSOf#BR`cniR))kMV4viYc(}fTz%g25W%x0ll1=`kIlceR zg?8#^I2wcXEh285b-O626ru=2G;yecCHfgi)EDHhlgF#Oi_h?DjvDz_n-HphKY8pN zolT6TEu8+5khpw#3S+CF_}YeQh@(NElroA33BvA@D%wPJG_in21=n(~-B-)#5$cv{E*X1j+C zn`8AX*iQ`W0SgMNXSp&bzi^!tYy-=!gWygtZ69S2Y4FQ{DiT4oZ$^DK=mvs|ag+i1 z2gVgM32~@?;x1P|Z1DGfmj1|SuT-O!s(qzG7i0SngKUEz!)EGBaf2Z+_@^s9GPoHq z@HhU^HF0xw<7+xgd_$E2Vunn_46&&be2m#xW$6YgN*P7u^%rzdFj*1U)f!SJ+7{Th zo4U%Cv_ag!b;89-nbr6>SOA4`iF#~r6}Mdu;afp}wjXQO4!INOrj?bI9y@BxL zcVI75Mf57tZMqe4eU(~NQ>=cQb0{XQ`7~sjwDraNbgyFYq@jJg$th6K&|RzalqJ-( zpQ=*PR@f#fA8btr=A(_$Zb6=j)oO(Tc1w-M)eiFUuKt}6!t2cWYwNOYnn9}@DXiByY$d_pqd^{)QT4 zBDn?$Hg{6lk#n{tDbdRJUj;u!-DEaC+|7^ z@a~1Cbc65EZ$3G#qsnMCYOH6Q*kJCUwx1gsN0>W29poy0v=2DScyzFpNPJpIR{u7* z6XyAhss>2$6F#oRuB2%&PQABtBXD<|EoW?-_s4m@?UZ!0gNYGOF0q74?L%X&EnO=n zM0i8@IR??ob9UWUf33AUZKo|dHpiNr>wakYpfbu=m?Izj_9u}?uncr@t%8RBSc^;s zbThVawSZY!B}~+#iz{Rap+n9>Ozj1GPXzlWKPdhNJrrQZ@dKdYx30^t^&0B|D9E-^ zi@}7RAe9Tj&NzJ{`0pzIq?pS^1)Z_DEU_}uYZ?a%6#e1{`1gRJGV<%#{7f( z=JUZ7?LZgRJHSZXgJh(?Ti-SbiY|!+ky0BcfUZwtcY$uSw^By0?Rm`B=2J@LLj9E* zLI^Nd6jdjmWguy@P~um9Td|n`{3Vl7?6VRAX>sR!{2aBfU5>hYoOzdd{GNTx(|mW- z@aOXk^5^dsQ~d>jv7T`-N3dHkD6nv_Da%dz30NGpqe4h= z#t|gkJTtW_@n)o9p1DR1Bzg(P86?vZbCeP(B)oVn2aq7xy!KLilnKXHyTW3$P1Y#~ z=kd-`_45&k7q@)_?4+EhgBZH^ME(Z!@s6%wA)Oo%sp$KTX+ysBWHaX?VC|hFW2=QE zH6xqL3_F9^CwF^DkM0hb;GHc*?A3dqKxXbnHTfXncuMyzKhZ9eupL+Q@J1H;JHyZS z)LA*{$Uin7I~CO4sjSuV_%~o+LYhfJo-@^3*!}trCCQqq@~{ zFq$5=6^(t2Uw6Zp?JF)3kvc8SOps;h(GXGg`*%TXzbG}ib$&i?*{D9T<13-x`FEG@Tr zl@z+eZ}eCAl{T4)t~X@9aq%|yy;B7u#gN%0Ecd+2Q6dW8HviHHMI}ZGC`6MAKsG%i zxK%K+N>njIdZXNwd>>;H^@+jCuY?3GS_PW@{oo1F_lEu7n0OLIg{(=)C5-d%s~)-6 zhk2<;H&KOjMpt_=hDUqGzt75(-763X(aKamPc4{)#rMt1iK;qGp^Sl-h%5e*Cx>N^ zs+Z0yRn5dsq@LD|22b>*=4Xf;f*}^^8?}jyKg=7l7|)S`zR10D8nJ0fqzBgR3XyFy z)2g(BO%K$8p&>ImW=YP~_N)eS|qW(M?qo)m9 zC^;l8Xsp{syXXg;tb?{&68P(m&pO-+ZcoVKhL5d(sox^ZC3H?K_Vv5eVwnfM-GM#b z48#3Wo_)mDw!#{M*ccYngqb^_N|L?!5I;w%4dLvsN3cTh3$w@XmH;mFob+F4!$URK zLzE|7sZBOcNV(U+!^UJVTu)9q#JPGFZ|w*P@O_dwx8O3#PzyD`N?b{&0QN8lrgRvk z?!I>_w8H55GWG{pRU`YI2Zvlu+>4e`!#QT*WGNjct2OD6s)6P9xa)@BGkI8 zB8Q4#WFpeJ{gNTUrF##Ti}}4SwNB}!$ja~|e!m#8#^jwbe0Y>E-ISW`i!b&DpSd2K z%mF&(mrSgIUvk?($nt@<0qi2sVGuHqtjlPzTu|aJuzR-I1uhz-D@gm7S41yPJ%zu?Rx~aIzf@&XjTk4Hte{MpH&<%)oFS-|O zyk>;7`<4{iD$^nSk7Exqvgyu7I$ z@W%T1?MvcaaOjP9mwha|Xmlj%Xh-v;_w?vgFvT19lYIIs66=-S z_M0}^l%uc1+9V&k z){DWcVyT6}Xm%v@%2~7)cB~a^xBM^L*s5U(o9+8!2^H{_UVK8vx|StJAIKm2+^aHm z8-KfjwzBZjxnsN1$Tv-ckx>x^2sujy=+{T~3bsha;%z}qf|KQjfvGGY`9e=vDPi>y z=>dfO)-diNm>ta3;Xt59KK{;`SrW+Ks zz|oyTs{_j?;O!BsnZ^~hrWW%jn7mNd6=#i=b<7I{Uu|jT;K0gO@f+B0-wr_p18p)4Xh9EJC4R@uCXt(tLgwK*Ue+vys8*N z!4_x2uJOMZ16IvEqBq}45EKw1-EE(OwHUTr*HBwnQ>X~~t)2K8F5;a+w44v^@87q5yCgbw2bH*B(%yoA3=(3%Cez|o;gD99iU{vg#I_jL7~o_| zp>`@V0oh0Ju(`vxg(uorR^-hlnZLS1!yzP`P^d1%Unk^^0>Lv8@ zW1}scIpD>X|5i_&PIv?dFY$zg=9XRhgoC<2Rry*nA>=I7k^cPWQG?UDqXpqd*tg|} z$o=n&8viyCY^CdDYOMQ@QV%t+p1p&euD*lRzdo}5uc}X`vboJaeCMhtOf60I_0^p~ zb;Ra;4iTf$V*W@*!0!v|)f^%O$E5JJB`rS@J%JY_>SJhG@?-O0H$1?SH1P0?6$4E| zGQqPMz5sEvJs7{&XMUM}H_?C2F2{HoH;U9zz_Vw~I$yK8UpY^49&bEuZhL-Qx&Lz7 zNk+q3yh#ZfX5`4-6@{8MfAI~%HhYN;!VZ4U)_fW7W!5+Dd;bQzruNuz(UtoXxc=J- z;sW-iqle3v%9kB4Kof8ikQ2}u`~mC%0up?K(5AU3hDS_?!0*=+1V#u>L?^7t3M?Sr6nopV+!}Vv9{6D3f6ds30C(p zhs%g~3B+PgrzNp*gKWOzHD#l^hHh8J_YU)E0%&84Vadl?DxvoHqm0xH+RV~}krz?7 zg0@HaMq{oMHP!6ocb2o=6h4|QVm|i{YpAM$I&;b-&Cog@xz|-&^7iU=buagivN&RK z=PF~+k*U_CejbCvCdTRs1f-3+ zF+W788f&Pa^5t&At~x~sPZpx+e$6KR_RR!$dibQipsgRmqvSBB+0+3kIabe6*OzaW zdvH_+3OXt(7wycvyTJigpm~yMuzOUc3{=sJUi(=7I*kFlk}kfm#F8*WVLhYSsO!0Q zm14LM2Da|Wu`5LRg5&LWw%@n=RPa5dC{icG6})*>Jd2mQZ`&*6eDw8 z-w}Bekv*I4ahQ9wl*{pD{8QX^0pC7>`F1;pHdG$^xPehP8sngzq^eb~4DWHr3PYf9 z;N2|LaaMGKV_Io3fdoYuH@c1y;a3PXbo#xapCpsz+C*W6YY;}QeX!&(>BBEzT2j!) zrtdi8YvnH4q*Cxd(eD(F7r6AylU0f)YOmb>wm-};Ea_ng!i+{Edi#T}CYn;Et~L$T zAiHroghG|Iuq1LLLgm;*4Ob;QL)FkXK40999@A(A$J`F7EVr1Y#=uY&6FSUMd!^%P zw~Za6EnS8$zm7l)zev-mVi$989iYRXYxdq{l3Tn8Cxl;}QY19~^_<*hS}wm?2?e~=)9Z3tCfDt|woo{$YJ zC153TtAK7&OJFnA4ofSt>LXfylFyY0tQW{2Aht)F(`jF|(qTCmk44`%v1~SV~XtsZsv&ATWie|%)8>lP9 zxEz7zH;mav8PeM?3TYCIX~m{5kfvFb`L0!FpX%i2-yFAxXOGsE71QDl_jHUMcF3hb zf@ej|WF^|fUy#FL3yfM7y7`%!TB4ssrQ3N&?24u7x!lN zi3`{;+NDyMg1-pbB zeam8m*66O*0_AO`1M6q^TqBtriU*A>Vs(3R`{FMdeK(cKGo>$?ZL#r|;Me&_E@6w; zpgVns-AYCTQA~@zm18{ZVlGo@uq_kdOE;ECGb(@|5X=b82nXzjpH-1%Ro40EnGT)d zRnFR@kNy)!{aY8i-~UYSwWa_(%>ShJ7GeI=zDfP>(tH1xee-|cFJ=E(IPK&YPxito z$tigO22__-DhC^agWn4pC_suM;(D-b!(75$SFNXCNAXUB{`%#ea65HjpbjC4G+%I> zF~#|u<^KLYJ+1v~#;^JBhNDiuFC`#h^C>)wLwY9ey-J^db=<9e5(%}0$pIMK5w0Q! zk`{9@m$XWbXnM~ShjE$9LFS-FNmaDtb@&42r8Ct@iW@9q?y{sXP*MYTgX9SHQM+`` z#hcnitCw$U+g*vs;bMH_XXd+h^6XOoxeB`m8Iete6BdHgP^zwT)b1SP8Zh`VcK*c^ z=Dn^EYJN843@`3Hk%NY$d4Fw~>H3 zNwkss??3pt7sIz9J#~h}3?pnRpQ&Eia2TA7RMRCe4mr+(x!82IY^*D%JAD&Wp7|!L zA}b_V_2o@!5-A331sMSvyjS)1X+mYiC4Ey+uhJK6W1=9!N8%%?ga;3Bc4nb%h^oP3 z&;`R|andhc39z5(`KP93^lDBOWWSMee*fnFm2Lc@~aurif?ttz68|+SR6zh ziL)gCnW+sq$M=n~;^>X&jG6u|^m4o5^O~Q~+gav%YQcK?gp=KQc#l8bdi%)T;!(UD zTlKT=%&|rHCUx*njmb=)p}(`v;0|Xbi|eF>);q*MQpdJeeum#aBonJ2jnjXBCS&=Z zW9#R5_Kzg8q1As=aWW%or2u&m1h4rGfEjM-X^`S!*g>I8D45E@LO(C=G_X*O;&hE5 zxF`FdZ}KDRgF*s<-?Z$dZLeLwT|9wkhFpWZf&g}n5~@{dlg&EyU5&66E*oW)nB~rK zrpor%x0o#Y56(h$zBSUnv_g0z+#K}yYg2w?IX6uV8!8oHn+e}XDLlzLzJqUQnrvzr zI#N+sI_#Se5Q%}8>5^cIsEYLmYI{>K2W>(A7#{|ryde`MLwlr;wC;gJh@rs3F}E1Q3rGkU`E6!#22PTC&ZVZrN;n&T2bg| z=xAtpe&GYr#~A48fc&7~4``OICxz9|LwWqX{yi!f|9_!E(CPn_r%L?cg6{DkaPq6G z)Og|6oxOc3gjvArd&u;K&l3BOig{q`ROp+Dn(2Ng5yeS*-28dTk0=(20E8BwYkl5G zx1Y+Cx;kIKhw$;dFsg~|l|lmKj*F4xqY6f#W4cSJuMP5x)FxR|5thx_OPE?8laIC9 z+#vU?%v-s~M|H`)Fx4JvgLiv`UI~o?20z#y%X$DrecKYeS8CL2qAXr8p+T2A72AoX z4?J$!bRnkYOc_c@-c26KFxxlTs9`!Ko>Rm;Ya!Cfa#$0~;aD7>$Uc`@Y$Gd6Ik2jcA7jYaN$jHY=sitcmOe0w0|}Fa>k@X3e^3DDF!+>I&oL05%G#HkeU# ze0&ynglzyu5~2>myb=u~H?R?J!4r5j5MTKe&FCXLf3$8C%^2pmg=1GVif`Td;$NeD z)@^b3OtC72K9BYEH5|gD7@|vcAIbA${U};PccY4F3`HFpu=Q7^QNMzZ2$l|i$Z;KM zfpTa0AYa5NTnf6XuV^9?tB@UCEhb2R{|Q`B`tFgm*dG&=?gkRpMM`?}>VmP}EcMvl``LK}Y+ z)ZcY*<8Y7maQAbMpYe5a@!~5es3@o@C_Fx~fw8`kzNiCwIskDJkQDy}wrV9UD7%DIIU0e5hw; z&%ZjeaaWTkS3znTo{-5atG1yPlv`*Xo|x5C**PW_m*cjfm6hwZjV&+QXhzN~ifAI9 zoDpbdR+RH;M$RpoXhzO1s%S=vcRJoS#yfARx)$jJsD2m9GjS3goH~r<8wY;yj+FCl zA>4Jvbc4Nu1~}rL^3?@E!o}emgv5B@;s-<^*u}-f2TF(($Db@qi5(;0#%Cso2J^bq z#Mhm4OQ8u!`_wFpvd)ba@=H;?M#OA`x=M{)2XIgyJo9P6-POe?2Xs&!{4}N^-8tj_ zkg0=Xyun|SW2OT>)JMDnJg5#*VyFWjd}zRQasT3?@_|5%BE}ILG{n^Mg=H`(2tXM& z#|PEQj}QhmMnnIWC$&0F|B(s3yU#*2ng4B$cw?}i}JIn4Tp5Y3K#~z z1toQq1?fD_>;17Q&kMg(Z8c%xBtBrobz#pC21CUkxXhEAa+p<+f~VUMES|9r?7;c? z(i-#?B>)OHm2U_l^&;=Ik1q3z>;N8S3P}#fAS33KDvej$$EGaYC~PK`PQM5=lQhrh z&c&a4R}Gguzyi*$t2g-$3PgKooBjov?+PiY{WTb5yWf$I36zz8WI12~V%6%V)1$4| zJ>ZoqwoX~i{Z+~TS=1c+dt^t-)bTczk0xJz2y3Sv%FDM~_a^-A>1WV?_zB$;^^jjc z%qSmaG0Ux^JIn?{=^FYs>T^FK8RLtzM{cjR_%o&!bwU4*vukMY^{tfuci*@1%{$-M z5F&^-&H;ZF!wbHa!Od{T(2lfARIm4OA;`D?IMf$0HPeeW$M(*2%fycNy@r4EO(}@? z6a?fKwKdZVM3&_ZE!Xl677cly#^4MOsg@B*WHr4)Sc9BvVJ^npTwuYyX^`FBGZbT1 zw|NQPN^aPz8^5H_>=@+${=hghT3LWHs##u)T-T^fyg}~hogVl#-GaiFZi%T!aIRD@ zR_W=TQ_w^vsR2^cAA|guzqspAjOah&OghmE8eMZTh8=@4h#O`lVy2XQpe2KRNjQHO z=>DRa0e|Ev-8DlthOI+2rX@qD8kaEMRH=>Q@>lL#N~qlifX7qOnIgs)yYM;scQ0&X zm26`?{9$@s=P!)B>>|RoOb2@Gox58~ilLs_v(D~USfF-pw9fAa%eeYtRX_L4wgGD8EG#C{2rrqp@{3( zWghUF#|D$&XiN+_C3!UrqCKLl22fYlnBTc&O_jK5en-{~D$r5McnVU~u@|PIPp-z! z#1tAWN7J?B=0o1tlE=5lSnMLZmlZ)?b*8T`8MqS}Wn?=Suzx>DLWNZprdVD^7*GNO zefa1FyNV%gyVzr34O5T9B^%OlgYb+mxN)6~PqG33w%@eOfveTxKE>lIEgeD4dPBSu z$_Qk@)rsA7H#yU*-8#9g$7*-wb4a9O)8QG?BO};u-7d|i*m4Y&!v0z%jWyy?LiFom z+xA05R6ubzYXRHYS|yQm&{HC`Ur|@nOG9bBPu<4KG> z#ve$!mNFJnwPBq*Bkgo=DGnR#KbeAN{ofj9d~q>`AjrewF|!+c1rx-G&-o51xHD$L zT8iT8!k};;T}JV{2QEQ|n7LaRS0uw^7ZKH@Hd&6p;{fzzZ6{1Dh3|!Ql=eg_RKG~;cB(k4YhH1SwAW@s1j&ieboEl^a~!%ay+%D+s-WF8FB zkkDosc|E3akQxyY3npoThvaP|oN}Ye^`2^?=mBmzhkuTKu z$Hks^5X(v8Cql#2$dL{3^&I~Kx~OP!Q_}OQ|~fWoE#cV6AzrLN=Yo~S99Y0B#Aw$9dt55Y^pYvBffT7Em2MmnIRWM?Zzy4rfW=Uo@edy5qv+8Hu%W?2rL`LgQx>5z0 zKvb)-y-C%q$r)E5CL)1!0cfXBOM=B^;5Gy#MXn)5T- zn4n--V)Id8v~HF-C_D)&MR!Ii;c+cXznT8(oCEgO*;v6r>sNb7K4MDhFwZJN|0Yjg z=eyxk!ZBIZ5f9+=)hWnCs_C{4T%nAaZx;*b>ogNMSRmMD)QN1tqn!vww_mIi0hmhI zJ}$%_t-F5b(n!AmjFLc^yf%{6UJnc5ff=M=CFwfpg(5vFUm(&6uP&|Vtj$MFN2I4_ z-+f=Iah{;%jn?Yx7xt9#7=?WbWNmP>cQ4QU4ob_9D-$#S=*_8yz0tv(*)Y(~+V4xV zU_n`0z|h`bVC-VkU?R3wE zG+Lnp_yFwApFMu@$MR$vatKJ51_0Dw7AGOFB6Lpe!dxBObWt?})&)Xnmy$i@_o!c} z2onh%5-*T34bp~R?M_nAmKdoNWz|SR0!|K8ADdd5IyzuFAl!!12n(B9Q?q!*$ReoZTY-Mk<4_}K8lk+9ES6y$9x+s|23pn8t#imLI9|kL9>yyW-CKL%G;@A;vUTKx zchncxmu$he{6o9`TXW90ki<9fNjKvBH|?AC@PoGy>)r8+mS<#jeACA(;xxu9M8zug z(fMR?vh~0{->ZK4YPQ8w;z#46htxj%#4+gy=RIq3^?*H>W>50XpvtKoURRid*x*U` zCbW#yrq^0c_EHWj@Fcdw93TU6zN;s3qF_2i{^XrWJ>FVH1QT*DE7T-9n`u{Z)myIX zS}8ETb*_eVZ^A0+)kgvq+c{pO^Rvgnk(3%)!I~#_sl&>=sA3Fjb$n90y{Qy& zrHy%J!^EZ_`*TXy7r+S;+Fv)=))P2^enW;ZDq?C)UiuR?kO!+g%?JLrR4<99B5N!&oJif*-H<0 zr7^-qe?fVNv3XHrA~ru0gV$T1MtT+M#f?9LjcKV zm0kV@&#pVi!bd;#C)5dNsaQ1Uortj(l~MPcA>%#}juj_QD%w0m%N^0;*+bWb95O>S zeT@F58KMW8ZARjo9z5oN9i_$72J+0DJArC>mK2NC=3kk=50vMcCH-r^qgmsMXQ3Au zWDHQ?ymI!Zyl`IdTY29X-W$Vw#0C`i4gKNsSGkt}>I1Fb5j>ixH#5{+$UM#~=a%U> zwzWGc{JH{2vje%sXpQ^60~_GD^r7{dJsFOW1KJs<#3`Kc_KN;g5FNBh1JzU|#d=}wqB5tTTx~?3D4FCKc!`H&N z&JV?u)F|Ur3;CQX5MrpgZrA)1pV&%Ghe^}9Uwm5h3@6QYqhK z+R|_?5dFT%*xiESutfK-fbLWCHia2wjvC=J<58h8n=CkU_53ppO-t%?lFeiVf22h% zB^|+xTwp}DZXzh^mG!1i@-S^pM#^W^f!LSjsH%(ks`76;e2MN*87LhwCnYqc!{wM~ z#JJ*@?o^8=t;9wzc}-MOE(1?d1vnWNuxdVHaF0g=NnYu*lLt@_b&U-M*!AJvvis+k zG631Tj$Vn- z>+tRjKc2iHz)tbT_#$Z%s0(8~P$PTA;AK%K_sS)dSwx^X!xnl!2>l3T4+n3_wEskZ zpwlLfs3A_f{roEK2AryNxbY_{hU_3f`lBMdj}z!QE*gGc;i@FJoB^X(uaSTI>0iiR z+G5oXIa!hVCAV3@T(ne5Sm%18Ps_~)YNBo^sAFd3%0IME_M?{GQEj$u0RZ1{RvqxO zj>w2Nn+gNZamX%oiP!z4YvPF=(MkCmrbAePF5H&FuO`P`c~}D_1l_wvckF;Z(y`d1 zt4>yaiGFPG^oG>R7&+lisl$eWnlPH3j-d$Lf+SvLlH_ft#9*cY*h1GhJjbwTQ_=eV z**&jZ2G&&Gy!`op8s=vjTNT0N6Y=O*kMn0woWvcDY1NWPQgURfhNMiNB@ zl!wE;VDrXX2~$tbTxP3z9?DT(aY~mMZ}YYTP69_8t3r`K{|a=6$4UeEhUS^?3wA@# zCUy)OIj-kr;;m5_=kL)Q62Ibye5cI4!e5MT#(H)waIJ*X_a#~Zh@D>e62$X(Jm^P(}m~~Z! zYfs)>UAIaETr%Sk?hqHw*@&_)6)RQ{nZB*KTFJ2NUaYU;Q zxoA*iXWbP15xJ*Ep=GZW(p{WQs2b9Fz&b!P-$Gf(*u3lwJTbqmvWw?;odDCWCw8#} zMLB39i>4x)9-(5R_c~%2lPgZ4Kfg#-Ucq4%CK5~aY8C=+pV(3L+2S=c63E`^AX{ zM;J3n$TNJ`eii~zp<^4W#Z&QPotDIIir;q1HCk5nQp1Y*PETGZQqO6e z_Gjs11~Lv<<=l4sq^1|8b<=~`&4Db9TqwGQUhh$KCOaY9p%E37)wN&$<8}`(a8S$w2h_&rhNU&c1Uj9i|(5p;y z*QK{*tYe*fuai0NSYXvH5IwyOcB(y8h)vC;BR_E?%86|dwm?ic1WDfmY-_nJUD8vw z4;!DqnBl6|bYW6%oKUlTu%N;j|59wigE*E5V+$+5k0_9gCz?uz@uEJ`6F}cC_bkQ_ z?#O_HXV8(=j9c@)<{5V!pjob#wWN?sB#Uhlje}=fRWW(bQzYxpiF=(O--5&Nc&D=!Q;zS#WkS)FkFX3yNjre>^Be{Ta@qR{LnCt5ig39C zab~W}q<)2@qrAwb^|g_i)G2a}=?3hDR@g^Bz0Kp)&U8n>Df8mGp`>H|Mbm@pBa>Ea>&sN}-`YD%`DQl{c zi?)pPDyp9`XY1VmUSx?=Sz;ZU-J7N~`3RXA&a&YmPq^cQaxX?T^x9RmnRbIMhEE7- zAm&gOIaq=nnkd55P*eC&3ygrha9vlGdnwrDr~e&6Hjf?@*vzt7m@MH}e2!_D^JUR& za8sU659tV=v_>VsBNy-cGyXeQaJCAc`w^z_kp1tx=qo9!k6q46GjON9+(nZd=nvDLq>ieWYz?NhNzy0MGk8N{B=Dim9tCvuS;IGmdCiY^LaW`Ui>%_oOWP?4)dD zJUbC}5N_(?+cogCg35x_H8i!7%6!B%H#YV1e9ASDwW3TZWOL&=s!NJCarX49We*3H zbrEUP$0IKaykS~2i@fgz{f4EEuwv|Z2nE=$YXGW~UGX=C^D8X_zd!;gRx?)_!D2W$ zGq&bc9Gg~8vm;zi4P4f}F@J`uUz#2?g{jJ3X__CUTY?{&xxToD${Fthc`TjrH)K^oe}@R3V^ z97K^dJ^RK~Z@p*}+7s#;$VbXGMdcgIP1>9s6-qz$Nd}kGf}>4AB#+H8PCe2|-SW|(waV@7{R!ejxWb^j z6#xv6B4Ed!WMEiaE9u zgU_yNNS=Fh;j!bo5vs4nvQL6ui*>JgDg0t(RQM$)M-5&`ttl0=dbFCTGI9Y(wazQZ zmcgMX>}0aZh+~M@5Yx0YO(LBS1awsS_@v;BKYdB6ErJX*-BA9{sj9?jfGmQ$USt=a z-thW?dNk^~w3e^bzhY`PVV1!@8KoZDJO5C(ND!q|KP}Z-XJ5>xtE)t9`GNS2PSq+v z3_qE1Au|o<;qGgC{$W^Y9&1WX8t%4MPpOd|h&T#$68Y9l#DT!3Qfkoit31HhE@ik8 z2#5_cn%AFetbxX5Q$xJG27ZH>VVxYl^fcvVZ|lH z%N5P`?xTidN^Ql6WsM!`y8#b2_~J6kc*q{*5*4?7trKk)` zIY6wrq9W3ZNOJ>}B87T`QuGVv-X_}y@d|d0#z$?w#1R-own^^`Y=e-Z2dEFy0p2J# z{D$xWW~y%yrFxi!m*vkgD0VN4E>+Sz4POgnd5pZ5X!2#911RuYd!L)gaciAFzAz!9t z3FyE7S%iEU7)E*gX}C@N;llp=>iWNJ*ZbEz(sePkr{;Ar{V#c?M5Xl~TUnHEODhOn z-(P%!WshOBy+V~uiZBg1h~hnHy?#wkF%&gubt#)TjmVYMTus)P*>0&#T`ck`VPfq2 z4n_1&Pb=OznNQg!*k<0w&S1DhsF|W&_EXMX*Uy^MtncUE+naxC{wynW6z*k&H7iP# zkCf6VPL#Bi;8pj@>6Vj}q(EUwYeFwPHa;ov^D4xp5ZH>c^%1NSt`d$~i9U(caYJ%H z1;GwX(UjTXM3`}43!z-b5%iVtx=p_W5;b}$lN?KbVO8Zm8Bvwfv^=5OG_s11r@q7HVL(+my#mq-p0E#o_9r6a zYA+j(BG7M03}7)?fvIrZ?78B|fm5@sJya%>j>x``>Yz}Yv_3}qTo~$<*K!Q$6hf4C z-?e~-OR&aYfQVmNM7*|zdCEJ@`^w4_j@d;ldq^Evoh*#KmN<};aRQ7No$f7w#NaZ% zZKS18Rwmw-ZA08!q+10>j)9?cU6l4%G6Dmbl~q?Qs3OvjtV*g5a6z^>fU#s6R-C?~ zA9%fC4zHYkfvx`xan%8r+=5xUOm{Y_x00-%-4i@5NxjXxM8zGrGTPDs>-w-0fuCs0 z5ZQBIO#Q(q&=4x^Nwz*_JRwJD4El*IX zo<2Ug^(-?kVK?}m5E1n7(bQgvsfk@xb2a4fH*4N8Wf0BAw0iZ@+~picaK)jTs#axL zMdI1S*w|l59r$V&*U4a)-s*mLls%47<-uS!jre88<>Cy-FmJ83sgDZgyR##d-H2v( z!apr*)6adwwX9Ca=la|EMh{e3>H-8yO(8|VRwOLEYazc(iA|BuY+=l2CNaAZuqKTB zNHF+odo(LlXCc^kJRP1x@VzJEx5c}(+2HTxxsbF4_$%~bBM*_{7cdCMU@EhArcm5C z14v*AnvmKfMLfXNJyOe>E`@*(8Pb-PHg>{60N zs&`6=*RBrfF~Wzha$f%~CG~6X#(N}YNC>_R*}a?>U@Q0#yNP!Ieh3GAr(kpq45k46 zl^bw8Q7s+Sy-TMP&yLZeR5}qh3p8LVcmcAwyRdBWMGC$D^=Nlu!{Qs52tKrj=|4IP zP~;4zj)(!;0FqQA+6&b%x@rW>-NWpLgL1vn8W0Jv;qh|pH=j8di{k%_iyxkASjofJ z@+GdLI;LlN1sP??M(6i2VDamzEj)h0#;@E5b#G|PdqHJ2Q1A(PLtodIB&y9JH3~MPPZ@(TNQ^R>-Xe8F z*G}m-uTfun_8O_MCeN_4JyHA1CD!9TW3P_SzUkU+40m3VZ=2j5zFECuW7|rLQFoKh zUbh+YC)f%{-=2ARQg{{3lXXWW|dst~-)dQJ}n`rv1NeJ`3jY;%kH_nmNmp`|q z))-!0HZn9VR*&d@p=s(iiM5=1SWhi}9~$*wYHHWtHM1Uutsvg-A^+fkBm~gBVBqLu%bH1!+)*}iytf}kc9B?vM19qT!8KbV( z$CoLe0XjdszO)=RCcxVR~&n4FWR z_ou4(77Ec@CS=>U+-TGJCapJGXKE+<-bR@xnL!7}cWx2#wA9n@GiG(8Bk&ghQ2Lbvdvv*@w zO3v6C5bIkEIwI~k^(&T?=a}w?Me6el9|9kU9f&?;um_MJ6-DKr$K8$yBBa!xpm5_q za_;`EF4F&HnzLk$wFpW$ebwivJf>{>j-v?DH~5i!~&Q5FkQ*>G>ihu z7P<1wrRrK}9a8L3PtJSxs=*2M;7uo+9tCRqnAgJyi%vzpe41G^`x+|RjpJm6Gg@xx ztJTDDEMq-^u~prD$&JcFUwTDh{qo(30g|M93kwn`nA2+Y?Jz$BD@NCvgkUl4nMKCDzQLjDu57;|RK6peeB!i9+4#Yt^{Tx~w7_GrA2!fq8u z-kMW9zR9Kh#7C_7FzJ0tU?^l~Kbxp{3$+y=B(NyLN#RiND6Fu`J@G##9e{V83i?l| zCHEh-js7R0)<0nPUt~`OaqFMF#aGjh`8H#NscWimuB4A%iPBzQu415qJV{xZSX7I3 z9HFX>rFm!3O+AZ>2nLJILGcYfOns4H2;YKG;$iCQBS%+iY_~P{PuO^aQciW%qT*CL z*MneGc~jA%Gbl)Yl%`|irZV6c%v9xavQre?-g2~yW#!TmT@IPy*BS1H~#$Fi8>hm-YmMk7HIdHmoQOe<^ia`0 zkWoa_I|F&d`f7%8XF$9`@#|YAg+Us%5*a-q>=+Ff)zV7iaR8f}c<$g_nW02w?t8&v z@cJ=E4-|S?9#pfWeGD3Nmp+_t0YW!50}?e#c~~!vaE(3AVlBSf)Vm%Pe%0|BWqf=K zw~+NKMF!KQ3lL)6{)inMelvN`bgD_MMWbDx3&kSuhNu4oP={htC_@fAy^XBWC~a;~$*>0qws)m8lBhf}!mAH7&BXiW#Yuq?8tGIp~C;oo@G62zlEUsM)^?dbq%FOjl;PdFfS7?_=rl6K1 zS16|V<26*KR4PQsPbgogmWWi=AX3;#_E^#&UHD0cDRY`5Mw|Gz)Ip_?U7=0Buw8*I zZ*G%Jl?+pnRI7oj<-W_9%dM8`CQy0j3z(_%1U@~MSZd=M4!6XmxyPMPf}8M$(6<}* zB^idHLvsfc@OpvAB|HdlqdFJHJ0};^8vX^-mmB`2pa&n&oBYNZ5c&5PFaNJ=xR;n7 zY_JIM45Sx*UvAi!ke*>+F5H`#o@|JZz@FmYUvfLuzqu%HP<@4gvEW}adR%>{AwC*= z;?b~gnt`)mModBX0DS*2axGn(kqo7PU|uiF_;D}FgatDu?Dhj1|K=jUc?Oh*_{i^3 zW>DDc1jL?~38Xd$4Y%!cDGxGJEm1=%>%E5XklBF-##+`12??z>D;ebe;iNp9ssz{r zerrU4d*q;m|1{Z#50>;_gJrd)q#Gt}{luOCx zS`9(4ZQ_M*li8sQ8o+l|%^RIs!LE?akj)U$H|-L$Sq|5;UBYZh`8xS(x`-C9-`Hoe z1)L$Az?~qiP};QjV0DzpQx@Z-1k#JzNWDurJ~whmcMM(L?8O%qfh*HA<@*ztxpIX z^aswixV4|njM$n;q2_@0JYdlxbAriQy0~tlJauAycUon82p@td`l1Q0>ILCw3&4EE z$mkHkh$$Wm;c9Ml!;77Bp`);xI=0T8PHF5^+&DFe{g3_7%N2w5 z0A@O?b2R3(TIpB8Wt8&aaQy$l**gW<5^deOg;lF;+qP}nwr#ss*|u%lwr$&5WuDrK zdrsW=_dRhVG9pL5&4-bF%-*xL_Dxz|W1w?bn3~jf#NZr=Gp>4t3YF)qExA95vBX)~ z%&enRW}q-zy?@f+5FjnLgmLz7O3lwDs_}EUUk-nl;U7EiuJ(=hI6G9awK&=EiVU>o3E}8GB89dR3N~WiG7|ZOHj+eW=c< z37t=kzDJILNmss>6dqTLX4Wz0BFgdv*}^z}RLAW}?K%#1QpGreqvi5^o6y=brEz`x zL5#%4R(3QpzDu2wXVo0~9mD_iN18(Qg>^)MJ+rFv6#ssy!-@xHNt09OK5)dCQhN?T z?sMisP?^wX;F zg`GL&!s0l?bIq2L@-THONz-M(g&6Ls&HHAqwK{Q4kSKYuTpv~oxjG_BC9g4S+khE? z-cl^8&=swweV|h@HJ=ucz)3Gl(?cl`>dAQ}^bKGM#&G4?!6n;FTv$A4%x>bWQQ}1q zw~ufHe-^oFCCM9=Cc}9JmJ+o2md*QjUHMK-J zL4SQ^={jt(V7v+w=BX}@+;FeIkdA{PQ$oU0N1AmMXf1mbBbRy7)@~%clSu47zhiCQ z&FfxLpLsc2$@zi@6JkcayfZJGJV+-D>$#p+R67=V_dLb{q* zUer5YsyoYKm3pX{{K~vLa3-coAD{}1X@k##Ndkz`8ine0+5!QeqFWLWe=>e<%Wvg@ z12eRNVMwyaGE&)sTlqXrOvhII6?0lNiNO7gO?V_z$*$K#Msy*a$=cZ z8z@3H3hk|g2eN!*_-9&a(IOUf5n-wS%_g#%?DQ_bI2A0&Io zY_=Oy2u;PWz zCphMSnae-tVBrO1_?DxaoR@hYy3^lYtB?Rf!H-e1h@#knTxdmszKSGk*>PKUh7hwf zl4TxfT_kBySie04$^$X&fhQTKD99-oWzIA$rGVp&V8$o9x*)|2q)USGY(=RCNj@N7 zu|Pq*BFVT>q^!hQf^e&}vIwOp$wq<0ETBGwU|c_(0%a>7t3Wd;p;5dohJ_Nhka|2| zvD_g<5+d&po>-*diPDjnf@^6EMVT+ z{2=JxC(BhLxe%0D^PnPivtXH61EEIh8hUO};MLv0+S1p7YKiV6#=9@Mdc#3|ZiQ@G zOyP3K$=Uq+Y4TiXT zznAJ{$cq^2cDjTWt~=eLv%8<4)W#$h#)exaKOBi6sj*{Q| ziwXy6JyBQ;?m*9yig0CzU_oU-4%43xtAmJ#{mn)wd8v{cx6V*nR}1mAY&n7S(l0=I z@#~ugxBCO@&@uovOsLV7=uGnPmn;;$JuheIF(=KoVT|J)H>?hftqzR_JUPinCk?_F8TEzMxffdABgnJs`GjX?C z;J)~K?g-hmdmsor)O)tXULyUb#9lJ}C&V9Ffjud=AmF-*x5VJzczd|SUh4g-L|)4M zD?}d&fi;pZ!GX3CFUf(nk}syn#)8@5rURPa_0L2|G)a zCl_KAV69n0*iX)YWenS~l+a~s*Lm^Z=CU@u& zJ@qgCLn%~W!}~W>-THU3DBlKm+!459c=d2pRAqR5+GVjYt{edR6#>CqllcilJSeiY zY@_?;C^Pjh*b%5|oum82D871kqA0WtZYe{aRA2r3qM&Me8Nijdm?*M!ZqY-3skUAH zu$wvYK)&|yI<5@vOi^-bUlsvjTBiWbZ?PkEKu0Uf5Zl#1wgJ;_HBn}2-I9hZsdP;5 zf`RLIRX~jf2&r`R??^!pd#PbgLAj~AU3%$jLw?OOeC}bRe7o@RTsrpx=$PSQx%AfE zrUFL?kYdw;bvyU!U8D6Ipjk-=v2#DL{MBs_N zLz*;>n=!zPz^CG(G8tD3YhqB@OJkVsFJhQJKE|p{sY8)XvB#lFse?hCX!YX+a!Zc< z@nA((tr8f*nU1ao`=HMpGYf3y?JA)Uun7;lT(`oJj=8}<>rCz=aPbdI&QTl~w@M99 z*e6D+?xHj3gdrMrLSz_!5N8t|ETs}3FsI@lJf_kdaGHA1r~3`dbow1y3t*w_r) zGi*OWAy9*Wpj2X4Oi~6TgoHR@dXwS$WmO$HDZ)6iIHmoG4D^p0jYi&(YX0F?|i7Mf5nUZs42{tmIzhj|7+c-aA_x($a zFwEsC!l^mr^G|$vE$tyRsNkKZGG}?0bzqj!AjwFXJiL`I&aHH~pjpJ%aRn}Mf=~sWNl}vF>v3>wpGFW?IQKf_n?!aG7kPS+G!Og&z$%2O0gU(1{!Eh@sQxmHgF#b{xhDfDeE z-SSvxWvmN@^jDbjhN0d%nGKx-YN#(u^ncB2rt*9OcwYmyl{YP+Qoy<)4~=Lyzy;&( z{cSz$nS2JLnf6-8L3LB!VlW`B;6jtj$*(RPKw%}j-;WL;xVe%_SaC^K&mU*-Wa)_K z^4*u`@lm|^kgnRc^9*f1DTQnf!SG`I>|A+huWiW-Dt+iG5uy?_DH$Y8j$epA`&(^? z>1mLIIV%ZkX=_Nhl$?N_{I1!R$L!2wTbk!?f`HjAm+MG^5pE41O_vT?ovzvNZ>9GDuNCdkWv#& zf6><&;IzPWXC_T?w5Z$8Y^rQg?v0@pCt}aUdvQ0%8|Sgfk(>40mG%TAYkvFGQch9A zq`)?)g&QvW<}ZuI3Skx&wkFbjh&Mc4(cDZ~$)Dpw=5kQN_&~N}?}}1>{Gx1yewA4S z%0)rZD3b6E65ORsq9(TmVEQP(@@23ZN$a^1SanF zjGPK(fBfSdoLt2A`4tIB)8PY)-}&0ZhK^oU(t9SrrAMg1rHP;$X$(od7~A+~CIxSs za~|v>8_S!y`!UuAJjSpF<9p>eK1Y2?)_p3<+&FofG~5bHO->@~@X!T(LYyjv(>=>0 zq*D3qC=KWy)YD+~FlUqI9tjOK#c39yLWr<*0cWYdfv@zp80N0i+ItX7k3k1?rl8K? z)po>e1UQG+bVrmUFgde4Otmvw{xH}_G8;r8bxHRb7o8hSkw-Y6P~jBxJ!&-Qgj|4& zD2Q7;Q7}8{%1y{xz9u=?=H_wlLR+SBZPX0*>*eX*Rg_NEEV@~emAoS_(IS7vqI5fB zZ#T2x7A^I8#GueL;q$f$GE2DQt5F3)p%N?U)G_7&0;|rETND z)Em3WmqZJLiu(k~ROYlRe7xxfn&p_r_2i? z);4VmTc6&f%<0DeR`lxPF!TTrHPCRDf@B}KZ$nmSZA?~fh%)co_pE^|9I8maNlQa~ zCL(XZ8XoUda7f|3i5oulnU}hS8@~2)+r(uD*Lz5;_lc|E6YqrBjB{}aMn^b%8$&8U zvw>0l6#VZm#EfF|JqO8XkmYKL5;gAv*E)MskgSZEybS*xD&SFx$30?S-{1C=z3k+(-BglEH`l2huaeU=(3Gmq8Vy7F~Hm&Oimwzfa^utHy!H=@L zVwG>4+B3K8_(`Q6-Ee}-v};!luL2X?dzmosR$K)|NfX_10ztCqvfe42;?cQGibs~f zO9p?dcsT67$dume!B$=es;_shaoI+ffL31wT4c))@KuehfjgRC>!o{olSZ1_;Y7S* zOr)aSs6nHb++~Sji(!|z^ovWe>a$wI*@I(3|Bl-PP+0|IunLxHO^c;QB5CO*YegRJ zWl06v$OEzop=bp@?#rr$bLmxRg;eR?sztc|F->NxjgVg znN1LJ?em_MuEJS`_1qH)XuUdHs%s1V{fpd#kT>9Kn$t=AGQ z8zwa&edZrD)Un8Bur!Vr(5MAU?nc;pOENkL9UFqF4`vfgunBZocS!e*=!eoV&=>xkr_8EMpEfRF z{F~g{1hulQIG$ocwE0qs3DrfALO2Ea=KCy7GTsy?H!Wsivct#Yxc)G0W_HrFO67}& z)8oDvUJbSbx{## z9{v`%b`Kw-5LO?_=a=D~A=$u8?r+`@;TI65{ghcD_XO^JAbYe;1gI+znY>)v6QlKM zYqe6$V@xr?Fv3|yEwKp=Ds8)UAe+34CIB;=8$_gclD2ybiJi1|S{LVsvmyu}|HA zq82d1q*?q505+pdHi3o_W3q2+miY{Dh0tugqTsAy%t9% z$wQ)-S8rno(x}AQfLVeIHOwj9lZ5u^AqwJ2LIv>~upxy5p;1EUr{D6Wp@B5z|2hsw z)cb=5twWE3L=QuQOxpiw;BV2er}vHX`!RmtDn32tMW}Y@^aPZzpRQ&yUlja^@hb;{ zTf)MeOqXWlei>E(1NEI;mfh7s+FBh`^d_?W!pMRiTFZdLDBQvMl?iSq;G(u2Zq6o} zjjwf-yzLOI+479vuI!1Z1DSVpoqmKdBS?3lW@pg)IpNl z?nos2JlUbQ!3VLB!#yw}gH&$eI-j5AB$ztZAWcgDqPcC^_IF8pWm8c2 ze{XOu8PUSYFM$hvjio-vQ>F4h7&JhmIL}kddIM$~UraO#CNpx&gI{&ThO)vBol&@mKLE2{NNHauca*&f`BfJXV# z39#^4fCW^T_En2hUj_U=4rrI|p};XE?{{pp1%F~cs8j^GMG42kyvLb@%p5)Uyn-@- zp&ynyF<^{{9?W-2>{sWW@60}zGo^c{eRzo(AM7vAyv2gIWBD>f5_9DX1{LvHdN>x>$YrFJRD>WyVOUG6kb{1TpH z5ly=DBNz*(0b=JAyzA2~6v-9FF#x>kJVH-uwjt-l_399K1MEn6)_x&-L@5N!QD02* zt}UrEYe*_o&9hOP5Z%y?QQa0roh^WtQ0#J9qgpT6gwxAi*InW-TKh&HY-&QthA2|G z`u0V^{d(Zt>pxGxv3)b_z;folhKF^OGTHgLeyPlf-z^Kby9|iugPthnWG#;t2vP{) zM9-;K&#B_@C#ImrMU8vtDWhujEsd)=SE?{q|0Szx$hjXdoYlqh+uOHy#vW(wg^bFDZRw&Mt+;&ZjhbMw(k-ZO-**h%g<4pMkGW5+G0WD35ys zvA~WN!bLh;G?(H|ifUyWt|9J73HwI23snX8hI&t{w7>TbX5I!UBvlZOe|vqPV=e!N znd^}p^-(-G7deM5U9yzno)Y^6m-m$zrB1aF;NCJzqb+>|M#(_;ZjXDj%>N3GwN5n= z&^9UjN`?YbGZ6X5>QAXJkx@<=|2XvTy4$3`1#Lg8#Rt1ubp9mYQU%Kap&VOU7il8rdqUj)v7QC6 z{(rneE*48JndCe}*Z;W7TSUA)G<%B7i;59CgUjdejmj*5l`&x$VaZP%!z-8<(h#4A z1#a4uJ15CodfYVA5e_j>1X=D*gFA`u?vfOg~8{M#Qn}5+2{@!u{i(whf>skJS^Y70}tSh4wm+0`f zV$}$G({=tb?^F|xY2miyVhn;q!5KgATJRbAqvHB#6NeW$UmrH`D!~dgi`M0`7McWQh8R?6~HzSAG#R6Ef5Uf#P9>rf6$XwFg`o;VV zHeR8SpjNv1j76W-hDA<9bWxs@BH#cxU>V-jOMe(O(4OL@w*a>D<+7lL=cW9B?6E^! zb0S7TYQb@a{kh}W=Q*>1-Sc_-*%hF%FPWa?02!UssFUKLFjA4hfq}#rjiLAl-QA;O zbtfyW%XV`i@_2CZL`A_IF&->jR960Lm!AQERwK|1T0p=Nj;0a3ju4Dh2hN}b4jkVF zWKU2lbc=t~47NYUn*aK*7Z|@4G`{$wnzvN zv?o#|WE_8qf936&72pbh}QRTfGKj|o@wDK`$0kArE^@fN^eIX`d`_-Uhvq~r`WU^wo<$?$K zHluYShk{`Ymu1let_~-OjPKvO3DHQYZt>8#zrtOHK}Lp@>&=3JrsxfOcjVj$PJ_cl zSQ@t}*adL7bQ04NvNF_~Da+V832mwFb}iFMcNcFtB`!RfchwY#x+VG;GN=;;E92(~ zDvuf_V{=lbN|cG_l-|W<8(kn(O7oHkg+AbSq*8H#!=g2%wVYPy#f*sr=VgEcixoq3 z`Edl64z(q|FQI7f!GmaGnCyy<<18os<`q_^51+vR)e@Wo!u%>sGYgD!= zb5TH_=o3y%1BcQA=$b27+5qOnIGD?K@rIV@qJht$HYU!REgNdJ(v)K%fmbmBVI7uF zh*wmllB;h*V|p}S+{gjxjP8lyp)$=1#E`iH`$9?`p$G9na4!Fe{C=sbeBf)7sHPh+@rj1yT z?NkZC}z6|rBz>Xpi$c=2}Eg1^%flvQFG~mgpotmgIcM=Gt!mT&%#{L>UGZcC|?<+w$IEf?;1;^SS(n!&)$%apo=Yw z?>2@JkR!>{$Fh>KL%a^BV*bhsIsA%qp`V(v4az>se`^1?f)jWma;X~cQAJ{`ypxk zzskAlmg5g+i1)kyoDa!*mlktcU20^d^w&E=F9XGR_chH9_*iNV4IC{S)+dAU0rO+r( z_ck48xKFOxdmN{)=X$z7H+TWC`YGYLsPl>Z!%|V?QRoQ;Q1?RZgcpS-!&-?9c${2L z*RGF%bG~`GR-tcDg~2}M1M5-}yb&~F_lRim{X*E>)db+)+1V$>qZ4u*9fbTtsYtyM z2+(3r>v6ylVC?57#%PHKZ}p%UUZ=F@>DmXe5a+Y(_Xxs0Rra#%5vs9x}dILX%N;Smf z`n_i?VrO>}T1=&X&$`4PxVc+8;wZC{9?+_&>n2Q_qytBgzOl^6$Y>i0x6m@SiR;)| zZ&7*Lai?u(&XI6qbWc_HYC+`KbhN)V7bkoyWUqe@q~qLjgFjysU&Da8`C}FrSEj2w zC^RsSNK4l#t(l}xTqbfBq>)d^)S+6W$2n9jN=`N_ED+IG)|*^hPgd$k-JRg(s$kSh zNbz078go>ev?Hd=7j$tMq)*~7FpcO(1MIc>U26Y$owi(?Z}+{%=cS(q>CA^jofBS< zSgPe~7kdmvV{*8LR^kx7qEH^{%i5STrVIU*8zL_4vnZQUw5rt57s{On#18fj>qKZF ztCaG=BBWSPE6viXi!+dOC+(m~fQHwt3z?W*I zoEn7aEkuHwa1wEI3y>q6uu3ARpT~0 zfSf^iCqTo_4yD|1OXA*>Yqg_F`-U#S$XP=nX|)6kO+h$qO8JfVve zFD3iCiLz6c!0O7Cj(;O7lT5eoz4|O;ni%D?^BB$6+Wp#y9qBq1hVT|E$l1ik%Mv|( zkdM>@o6$p?i5JH0w{#*4Hv<0!1jwgTAV<*c7va~}i?NQ!ECh`|^o7|zDY{FUZmePM zY$J-d$j2x3D`hrGh3ugeLqqtyfC)BWKc<{uryQSmQw|s){vDwXkgpQh+MKyqWCGd7 zvTSajqP^{o1A=`fNb%70PpiGa9+Qinf4%!}PcsV+F+s)XeV*WxP*0pl5z+va=t21C zL7YJML_k`BAYlAAPd)4qGeLzEcmO8xI8dx$P_rXq0(&%%r|tgc7#3t$!VB~MocE7k zcfy&s)|%V-1QKx$q6GIW`FCDU=nTRhxS(_rlTVIqqaAXKW&{YGc1s!}Vo}FOk@dBK zavyAY3F<@BodQrH_NLv`1@R8X$l9+iG>KKpo8Klh<;|w!P6VnST}Y!tO2j*5F6GvV zIl>x85%4*-IvL$<*#{G=;){iVof3-mQ80_KgIG@sNbhjabs=SBpry<)d&uSf zI|?o}v%Bw}^Il0--+nuL%$;GZwPFw4AMiH^)SH7jwf?*Zj8wZjZkXTrGhY#wFIYFb zl3J)5x503I75&^V5vr8mf|r(q-FfjP;itFh!huxxU+{Aja_U&nUV@I?SupvA3*?_b zt7N&%9*EW*0pYW9;BFG`rLGDH@Y`~KksPNsQP$Tf#|%F?xWzf&O5|-Hft0CzS+B3} zHnj2-LZ4r;KzIqN3@D zB#g$5$bybWf`1qs7}!y}_6tSs?k63OgF z(ePMEc4B;5BjS-~sc>}Qf+I-7&T3-ksVKJ5bS@y7Be~I#Yy}6_SWEWs^w=rCIwN$j zZ}MbE-q~^wINqGSf&!y!=qnFMWXM7TIe#mdEIL&lCR%DB79R+cVh^CiX4S{rFlD<) z&ulGhROvBCl|=m&SxkM*|4eHXwUH)vt)&y!U{#97Vx%(PRud=TB6XZ5+Rz!3Nl!~V zwP!p-KNH_bRFEFB&(Lx*^GYu$ObOx?LHY^Ud@a^x>KKSwldUnF)HoYMOR?3tZ6C^< z9+@H^;!|S{^yY^%BEUim3h$CZS8v$BjTODrC@ubST>|x|-DC>>gz&e90L7@GomDBe zgS&HLIhpHaGAZo)-P0#Gt!V*Iu1SREJkU&oalmpE0MllsHRkebMs*g;NGgW;y|VG> zN>$EVFPGFMa1CLiPzt0;3OJ?jP6Uc`#7EkeM3fjrV<)IE?U4$Ga`xb?@odm)z**WQ zX#gUd%@C;)<0p+x&&FiaDHxhuM;FG5%FqCkgzN46mmw>*V=UiG(vB1AK{x*gJ`8^b`= zkl`AFSxysUHYT^orG7N|DvnvwU#bozVbWE5+-6#H^>M1WUm$;%$Q}Df*S75!#Eu#w zasq%{=j*r{#FmTD;()m##7Pq*8TZqP7-Yts+#2%ewmTycZ9RRz42-2T&mllJ*pO*^6zB+|y$TQpV}L0q!cZYxn4=2v_7W3 zXyodksO*>6m$sp;X{pF11*-32yoXFjsWZmW@0mxY&_24fluShG49FJ1T3-uCtSS~8 zsG5Jk5Z}i03I5}McI>~9E=CI5eJPP}*|PcVYUG9r6>IY#=_}j$ClBvTq~`%P@hc9B zHU)5A+UG1MRCiY`)+s^PBYPgwhz6v(eT~*TN_=8|WWKKt}U&g@5!#;ZXmrc>j-Ni+>ewD`V3i z-@YTQ)Iab4D&a|S+O`XHNWr=>)##X8qMAIvt-P$P$ZOF(HYnAYY)GKX5HL2|!ct5m z55}ii`eYCMf2{igSe*J4>Scq%ABUYDF`qc^Cp9;`08Vp{x4i@HAt5+Abes2_fCJe( z?BPTy9N-}$Bqa(bT+0Ma6K<)2!MGPfCT*jLNsnmDqrN0GAgHSByh`da8jcF@WC*0q zBtt&cOKn8Xh6+(d70D3tM{K6=7uk7#JC zeaBZsHM$PhT2U4emcc5OlO2pV$!#J9h)U>JFYJKQ)3lRp7qAt6J2T0d^S+93S6mw? z#tnVA*^vlZJT-DH%|n@EQj4C)Ye6f9*-*?$6Su!owwH;pvgT)8oF2u1yH32}BxAWs*z`Mk1u2g}Q?YdqrXMJ7x@-zA+^L`K(01hpSvRYYqg6%6xfA`zA!ZjHn|wYV<8(rN5rCs7KJ(peG_#h9@88*u56CEzbO@LU{j zK(o_QQRH@_HoUPT4<@|AJ&a%?^d&ps1Pl}SghOp;M>oj<>CT!x!_ET!5oPEIv_-tz z;9z1XGqH)SdM3SHY3Q8MENW;r1W!~|BtCxSQcD4T$x_Ph{F4VW5!Qt{^c9xL2R--= zGRs$91;kuSgNW0IElG=C+0J1>YnmYD4aQVL)jNW-+;IrKpfUv z*jUA%)e={KDfS?oyNsq(O1&=FE$WPQ#3PRa&ph}aaE(>B%dK>sg2P*XN~FOYb&Xqo z=Kcp@Piu`48?#`rdFy~xbZQa;1cpKKS!?^*^jR9!41}k0Tk)>iCY^Bioz3VvnHkMW zsWYR<`r=llbPykp;6d=BO{)Fl(2}@!m!FCgOLexy9D}+2ihOb*ep*bNl7w7=&UML9 zdeR2(RCU6*qN#CJWo|*d1qB$6Iu;1(#P|wh@`Vs10rg}eBDOe3bro&9{Y_e2T0I8MPR2p&my$bPC;k2iq|J;`wWi!SR+ooQhIrq{d|5o+m70Z9+ujn5yu^ zO7sF+6UktU2x3jP38|Q?M<7kQ9(Ju$k`UBcM#p{^sEN!hv?A&fCT1CN3kz*Z+>URm z6Jh2YbKDRCPAw^W+>^okyg1wt|CSTH-E#TiKm2bvvikS0{e*Da!(nzyhD_Z4Ubi&~ zEb|z%GxpBl&aIQoVesdYn6JNh*Q^;;=K7Zvpy9Z%GOIteIe6IyOEy z*+h48RLL0elBGFs>@mc*)p!T5*A?$Y|^e5#I0&P(pRLV;g^5{pkGZWzN z`0hZn^IFJd^*im-Ko3WAg9kL-?ko-;P;|tkxP_$~>cwR=4SK(kq~o{lku7|OC4s+K zzHesNKe#o)Z1|2GIN*7~>JnCd8#JWQ#fqsBc5&?aH#waA#MhhV{lMEc=aKJ-D+;)3ZTmf zxkLAN=ic;;Q{rVqad_!&3PBaKkX?%FfZ`r)p$B`occV+TF+@*h2N}~TfD!N-6*joMjG*;ZO`SIp+Z?G|oXFc>+Q5VXQ zO+^h8@%{OYU#=z}kq&R%^aKH48fail&Pb8foCc6w$0UIz*uD<(i+qOXiCpACD2 zOok#=o{sZ3G%1o4W~-m$@B2}-R{z951k-4Xdegninap<5br%#akSFK_X_d$ZN%{;4 zRoq7#n}?i#)E_r2Vtv8wiIHAUVCWv0!5a%-<(lh$A6grx8L=@SSz}LT_ zuOGxQFRCd&!Uu|w;{R+Jj^gH#4!BLZ42krtAbkOEJCz!BUO#>&m#$0D$&|d9a{E_R zZ^a+~QJgs89Do=SL}MGp!1zIq9cBjg@X9~Uo|w#X63F!=;)_^GuV&HQf$u+i^N)3# ztz2o-Z>m%Z8OF(RS+Q(#ioC^b!L&C%j^xr!ez=O2Mi8ZJnuF;I<5Vk(r3}!lb4{@n zVAA=kZwjTq6v>^XDllR>h!Aqiw(?PkdIT=JU2}84x`uY)3-9>Ti8uNA+3@4iTPY?E zf0^Qxgv)D0w6%nK_x>6H7_Ml_OE+50^)QT4Z7c$eKa=hk@^JLKL%({gxp!0oS}kIk zp^xG&tc?-w#LIXm+a+GpP#QkH0=tVy=Qm0E-25k>I-PrDqAbuW%w#emC7QD+~T0rMqQ=4 z%hWaA+{+z3eIl!C_PfV`Z8pra_u$=yKw&f0+B$G}C$dweT6TzFXL%;Q zfS~3IAfZzalEAh?eEQzM7V(cCe6So>krZ1tgcXU7;54sTn`NgNsFo;+61gbK>X&U< zPZ6hPD@}OPi+0n#wa-LW?4qo(e{2P0;D@?`Z(j-y?YM+_2BSjciq*x8pk>62;@SPn z4z&CXVF>j|yy%#CF=)sYg+^$@Iu)U3)BOVmv~>!6r^}!Z~z3z6pz-ja~B5~6fkrCkXn>D6HMbEaUZ_WOG{Zm-w(iy0l` z2W*o8kDn48m=~7W>8$xsSndNS==d^1#W?7-p0GjK|F=wh06m}eUEpa$WepuQx|7Y6 zdpvip9bxmZB1*Ytmj9Whpo2G%xz&&79(JMp&o+qlc`-?k^wz?kqKb5@RJN{F!PML( z%l0egdc$F;b(N6fx?>&N)tAWG)AHMR^vcX(ivmvw>fxvB7_|*Q@60(}g{>bBbxGCfvP!T0{TEdOpf{enQMO|nLeHGHAowDP&vCpv&yaJp! z1HFis1B&w>kx0CvFtm0cwDQB0;gg1*%C8>v<@a>Nw(fr^t&6a2!5vrGVVj(3oWt$V zIFIv&j}>@_G0Mu`FUCAlrgy>AAJ3!YW@6^U3Ih_v{}rpbZ3t_o{PXH=fd01@?|;P0 z|DP@1|M~jx0bg#0~`f0&5$Ckidv$nSRaBCk|GJz2~sn zqHsr9r!DW4d~bVhxBd9UuGffozqePif79vmSdK0QPcj;H<3mEJn~f3(qF~k!#uf!r zF&eeuBL`Q~9byRnd|nxkT?($GH>$!<3RXg&Hy0a>EydRk?wpBD#kUtk2zJ7(pNahp z#-cmS#b?F5_Yt(AKLif;qWg||E3xc(I6T&bQ0W4C*X^??Bq1IX#}Bvj#Sh-Y50WM4 zs=O`jM@9Nl*s~Af2}*z{LCThQQ`y6XpohU#bn69$jeg%9(&jj59*PB(F`I*&Q^Hg4631c zAoJ4RGY_&Q_tM;R4?;!iuDKNq!hNL!dM4vK9We9K*{ktF3-DEW34=AXZ-G6yGY`_i zCD~8y2M_YS*Jt1NAAkebi6i_Tsqys~L$JiDoi#U6JbZ(Egx8c zByr0ebP`U7=v#9u9kc+kBma^@FxgLvj3fUN-0vz)K8y)rOYtGIM;-L7!X^o~kf_fv zmzc(|ov6-{5#{)+Z5)aBEB98^A1PgdL^V}`rl@#QKF=`;C04w+GJ!yGnbJByfO(t# zNFzuZf|<=$qDqRTNTxWo9{nb*Ubsa&Bt^PR)vUKhYOQ!SR8@K{S~sH}_*-8BQHS1` zREP1%<6}M%GtnJ&o8?I4qd#%$rH!2RYz6OYDbeI(GEv32?xB(UrHb6zqsnE8qHv-M z0^4mXu{M(FNF`|F_NI7~Mp2r*@D~4LI1x5tCXv(WNq);y4ch)67Zk|$htJ1$BIqrt zB94-q7+0~E*3}1iknFy;B2Uma{gHkq{ZZ)pm;4y((ZUO>A`c-*F&By8FZZH`3M(yI zGV1?D+dBtW)^**Z9d$ak)v;~cwrx8(ad&Lnwr$%^I<{@+=6Rp@tNZ&^eJ|=(-BbJ2 z-hZC6=UQ`(HRf1jW@yh@fR(Ei7jWAIJgC(OWmBUqZtr8 zH3Vtw{GON#FZ8!AeVi{`<4I1>36!!_O1 zt8gHVCtzbV zcAgyHN)3A6ANt51+k5P8^Cd!?V4-jPPsG+F%-YEw*Cg#t!K-bWUmRG7*6(69U%)$T z{&@YSe$UdEcH}~UY9xxCk{2jCD{ofvErDRs)aO**17rlwriTzydewusl|#Blwut4* zl~jCQDuC}Xa+@fXX!Ixv zFc=yjSC|AV^$o;w$$xfj zpFe>@4I$JYkrM2yZk91lC-rV=xu|4g&|4MWsNric=#f4dZ3Z3K)`Gft;ah6P8bNqf z!8vW?v#j=CgZtF|MLV~5m)9fm%immn#X)dEgG!9>NLqeU& zNBxzh@Aw7b)dLjn+#!gr0cr|ObUYGXx~VZv?q4m@e_5e=oC z4@;wFrm9Q=Nn7lF33`VXWeYZv$@+JuaJ=Ub0ezLS)>0|{8wrj*+PC(9NaB?^l zp`2foNyJa*yjC@njk75~e1vM=Cb9}q_l!la!f5>?&u5y7aMlthdv78RE_QQ_uqs#) z;({5-E8;4TuyQn zUGP;^n_{NwVAi|xW;AivcOZe=u(YRiBi#l|fz!d++cyNw=0!oG?S;7~A!YEZ0o+Nh zCo7NHVhkbphfNCNp+y2ZFviWGUVDcM-iEMYj?Bo}<7%UxR^V`EAO!V<&RSK;QBz}= zBsfk*A4js*bd*2qgUA`$FKi(&EA3HWs4wK#R#Cr1nmMdHq7N^3bc~B6JO~y#q!7 z$|hHmxMpTmAJj`Rx}w&%Y>~UljZ6!fgLaVRJGnXOBvy`+-XPCU)R5OCo=-SlN7CT~ znvHv&!x%K}FQf*d53q>x8WeB5Xom*g9)$2v&qb4%8EO?@BPG)~_f-Q_Fb{-NzER)Bbd4&5Pa#ifp(~a{%0LGM+ zJZL_~1WGeaEZbDOJUd8~avIWVRlNb7`?Qj%izLt!Wmo zR|x#pEspnmZYL+w&K+vn4^Pia2^p?jd-%*C>pSLuycP9`stC$XecU0fML?Qw+71Ds*JR1J&H7H#aOx27(& z@)JrRN#5MOGv{k-y2!(@D1dY|fkQD^jOS1JPTCHWK*wl=Cvt=*O(fH5Rtr`3Ig|`h zn2V_!4zq_B=$Mu)nZ0lR5UujhTOv4_E)G32D=nB3d9nKmx1a9(u>I3?D*Ne&NMe?N zeVhaH{k91l!>E)YcyrphS>fa1_#|kypnm~K{2I$&z_aJGlr?DI}9Zm!LsKcSQW^JKo zZILTrss(-z)!9Q`A6ww&z#wyv(YzB6{oo*v05As~4cN?t>+po{A$BZNzp#h$NJ}Wn z_)*!1d1sb^&wVGCG`(av=YK+FZNb|T9{uDoyd_p>+OHp1c*IyiU;EN~Nv@xK#_#Bo z7_+|q`kkB9BK+xF7Nl+xSMDuZFDp!Yy17f#;1jXq6Cv;nQ?j(Ze}|BHhcK4qgp+ga zj`kW5|1iR(x|KDcGG6hniCnec!Bcbu*>u#@(#qNN*8?N6S7LkyfI3KDr5WZHR~0T~ zNZ;Dzr{%?uVto~|PxJ9OG8MO*=*#QgyFJ73qHm7e zf(#WCTAA~)iVc=prEXG{xZ-7tQ#h6O>nn`Dq_z8cin-}J4<&ue>Bt6bLpeHeb@*0V zkPT?_@)A}Nl7G7k1NI;&l3~An>m&Ggn_uq#j%fXxv-+D?{U7b;-&gpFux-V#~6RsG90YrCJ%sq2t#fYHr}39x?|ATob|`oVDMtV1E_o zu6h-LbHD!T*4Ou6D|MLvyO*K(rIIyv{QH&s{SpfPNit)R+Mg6ki_@-Qn)MY-f{pJ( z5SQ{%iP>`$<;;=)COQn+z#(*A)Kns zZ5tpg*|h{?s)RO2D1TqAY{|3}q5}VN+1w0OWA`2h8QKlyY(s9Hp~DSE?SpK~M}2R3r2jpqxAh9p0NRJyttv4G1pm_C#AW4#_zflV!s2-U+`c=!WQ5 zQocu*=}TE!T3v+9V|{<*3LI7PgLa)-`$QL_um|1_o0d!$eHR+=%wDTEu`}6nD&Z&c z!APW?-<2~D&fyCfdnNdJTaWEgSi<#A#w140q{Lu%v~d}5IO@MOAg%@?36U}Aml=$N z5m3d^<`f({2$#9;&mRYi`7GHSP!?Y$m+)JhZSGd4MnEipAuqiwitdw`*h+4^NH5`I z1a%Tgx``)$G`ro~ckSZ`l&oy`1J>XVN1M89lrW5T8{BtAGDTLsJie}yaE?D_dW;Qr zzg?_KhrY9rS>^={(w7?|N6EM~3)ZCGl=}Qb6lV9@k@w?^Gd}&dobi7!7#7lZ(wDO} zw{iL>&!oUD3(ODi1wv{EaR2GuAOf}5Cs|+pYg(-QN2=Z#n%WfcAvOEMn=Wd9e=puv z6vJdD3Cmz{O^TZv=j(=)iH=TICJ?q^Q*Z@Aqc(gfOZ@0?&Q_1#sXo#vuFDqE&3&I` zZ!u5uC?AQ1LtFHT2nop#Bm}Tqu{2@2C5i(lb46YBndeqEW(s#&%m+>t<~Q4g3q6tx zVfYX>=obzg(b~DObVzL!$~i(dQ+Eo8b6pIi2Om0w?Yk%(#JAs}`*a;xV|x;G;&!4G z;Q``EgZnWuaUoo)4?QUklKy_S->aofz5Pdv)&~G2q*4h7?m6MJ^bde@cAh}&QkUKE zQkUa#8zZX#glqogF*U;jf5*(aO+ddyUW-uYj7G1UUg#6$Q(9lmNDUa8bt2bGw8nm@ zMxez%%JQz12ve+IWqIGPko@bJPyg>{zTID;aHRc5ME(lRKWDvywj>rmGIv~ghPd_xFm+!)vEnV}S%eHIHhdBHFkFSBBXP+YkkQpy1o8~Sz@ zD@o8+Svhy#V)Sz>1)izdt;HRQG=Q#2L?4@8_khqFKV03QTMAG731pz1lWb4=>-SZS zHJ#5m9U_~FMcCFCfdrp3UraRu;$f{<@{FhF{VsqJT%Pz(g&GY5ce(;CIer|;98V{* zwo3XFaV>OmsJK|V{49_5Q8cm#2Rqde2=iA^`>E9$a0n3>ajaFHSt!LDHqIlw8R~x$ zKSW0B(M5leKpTD9cg^zMZTxjwbdi$7%g7rhxr%I(P|!Xup0{Vfw6sCkeKr4OU&Jw0 zhXzJQ(g*0T#bA({vAF(gNQC^`8TuamMF%O|M;VZ};!u z-{$ojz8yksanNa1FxzXp>UC zL;~j|oQCj;?RPc+rgDQN;~1?SV3$=7Y6;IPL*%e3(ia;a)%zpVj*%LWb;~*8ic@{+ zo@>Xfz~{7H;Em)LUcrGdLI;<6{L3?gXImKZ4H1usO*Ii{Qtm{P)%C3=-BiC^AO zlDL5=%BRi|r+9`8vU(o1)qIWkCFRT_8`**Hv$lhKuDr*=>k1rOk<$zAX}h`_o&fDc!KQr ztV4C>Jfn74kyXjP#jkNrEJI#2ayu>L_&R+VZg}pW<6qjPym)eXXyvtvo(LAS^IOA| z9wDD^l091>i(+K;P~C6}qnGqB-R5T5I87JvlV4%}8qgM?>KHa(`K{wii~O&19N&MH z0vEd|;ZVP%F{?Hv9vr^wYJ?La>uQPOf%19=1%a zr*wV1@5+A5yJEYrUpoYJU&9PFVZ*U^?mlG-+QqX|V6%u4GF_c6UxI8$CS|bs@e@~) zAzTWP^2qH75(maV5djCz`~U{<`oe|_b;ro> z?Zqt0_16aqkDIG0M zI}+~yf%O`6P?mmQPzv};@go(jtn`JL%3K_ zCR>hmf#Cg6p%Ja3%;En#^sR`H!1fQ5RUbh@(pav!yJKmSp)_As_bltk96Kzwy0s4H z$iYxE8_-d%m4t)^y*HUM?B2GrkIZ!C7iVU^bPs0m!+s#%sB{M}{E}c=s!m5G`{J<& zzEfWv$cE#pOC-WoN zzWvW_2*H=TKSt;_lvv1*@%kf+HE1Z4&@=D9Ix#KW150EvDtieP>eFO|HyGl@U1yLI zM3v@OX_9}YBdeNAoEen)W=nlSqOf?uqSN4nf%Pryj?l}yaEmInF`pF2ovcF>sXK?pR$QqrH6ZGK^fRfTQ1Qmtei&il#m-Yr>s zkhygo+dEccAo$@AK!-(S??OmYf)09ka(?p)}aVE0FK~@;wkoVA5st zS>UCiZGR>L0$H=B+4`VI=*)kHp_ig>Hojq<7z4e<0zz-+h;n7GMeLw1!LERNQWp89 zCi%#4tRn6T1S>=?)zs8&b}Br~H}F>a0}h+(1DZg@ZudxD%o!G^{y1t$S#N6xZo(H0 zazY!X-x&v{jdC5+Lfr>?JP&MtY>|A=d@@y%kJ`l^S^bgoi>H?)vJD*{dX_1TSSmER zXlM)=Hx_kXqd+xW(Cl4I>^&Tu38dEeQ?AHwjVzj-hrslgJ7-B>*=Bp!_S-*tWZ{!A z^ih4Oeaa#Jf6Gh^e}l0MrBj)|L==Iji;2|8!oot=zK|W&3btau`|DHZkq!9LhP#ek z%tVvcOA&qV_cLO>^g)R|({Hky9;Dw+c&4Poab7k8?a|rl zjq*))GlML_tkK!kz3z@a>^@fUT%+f*m2M{o_Mo@gQ@{rPW+PzR2*XXEr!(5&l1WSM z_lJNoM^dG?F~BsHUK?abVnk<&8431jaF$Y(fIXs=MK;u#kIi#qfbPHnMCw;?cdTOmr#A+wM`K+w8AE+R<<<|YOk$>1S z&0r+w41kNW6R4kQ*fcsq4SZTE)1@zTKN!_{#X%FHoU zX;qkD6oS%`rXv!oDc(>9E#mz`(MC;w|VU1$u-R#UPm0gL)J7F`q}4iqeKxduw9dbI@Gb{10^8 ztEF2JCRx^MX$84pVO-Y;otK)i*g{`oKVGQ_obk~d$(xk14hn2v zOsknsWoM)2Rr+G8Bo@Pu-B4(wV&neDVo`>l78gqXcw$ptN))s4A+vPA+jIwZDQ{uO z&OKr-$LgTb1@_1qsbbq0W=atX2Vgf0$f6^#g|nJR(#DPOlEzK&vK{;eeh(N5{@nOO zrqElclV>U`Oc2h-Bn=@OV7|*F;{)TGL>M{-!Rg+C>|V(v!KR`*dA5XmOE^I#q*np% zp2EPJ_Q1Twx3aCru(eLJFb@&FKL&e;gvquM-P~_16#P|}CK$T@u?HNRJvIvYT9607 z^yUA0LH-XtLjH*`|Mvy???K<7`jft2mYzGGFFQ02izF&IC`aE6fe47i12MFy1A$kyd6V=G>$cMZmMu~IL zT>JL}h4>-LN^lWh*Y`6b`b0nF^=A=%P+g;ibV-0% zxOUZ98&7RCZLAmaWvA#<_n8DzqU`B`^-%)*0zJk7j!84{umkf<62;S!&2m`6)slg8&rI!)694)5Ae~1Aj|^hd}E&t?UWc z#Ne5t58fveXiL8~QLQP=YNL8h)mgj)e<63xb)kH1c&2cTw^YnvIxZ7n>{JJa_h?d&h@>brPZS4(6Q`#PM zQ3lvy^(}!qfW)0zrJEXdbjNq^1qS2JN0PvS#~0ZqgW~9vFC-k(n;?nFN1~G)qL)N?(>!oU(NK$XY6{;#H}z z#Bye2^DvypHpui=3A+afv64}@-!euv-6l7Z&*+0;oejFQnEglsO2d!?r&NKqH{mQd zqiQBYh|q+3CbQx>fIPPn#b3~@k4!f9D8LJWou%WlPU3*P_{DX#JApa5zz z()UXm`Z1hN_C#- zeO(F~nksYTJ;|^Uqd(m2V7~k39X)!BiF9=A%}b_Z?sc&XbPuz6(4qtN zBEMmjU?H%D7gr@#1N{V(vmzfAJo*gZ)Txz8i3t|DBqEN8S{B+qe-EN0R8<}&dBOMs z0YWQwr1&@Bp6vwCTc`mMR!|BV|7cJW?8BXf)O&O=7r;_oces9xgkn$umLp+BYadPg z<2L-5+!PDw1cXxNw1;oE`VenNU7GaRbnl-tLc0gi0_xuJhv&15g0M2OtR?QdR%bn8@#}jxdD!<1^5y#lb@l>Pv(yrVz-r z!w(Y5`9%ZX$2pGkrAY1&heRAZ2yuoQe1sl6oE;ducUB#SX^Ys8cZ^VbGsT$%4Kwod ztH|(+I05fulkqOB%mquhY4V5Y)%p@KQ|m`28IJ`DT}cQyWlBUMg>7|)GmC&U+$I`q zDRc+a#()x2N{Oh`++*ufa|B(O$+^NnnPGSBmr3g?Gy7hN5Xi4zjtb@49~^Eqh{^9O zRGvpILp0=8=sK@sl9`t>W5hUQVG5~`gXJ-fMeOLNIrTP%6oo6r zML)4t;McLD@a?6GZcerD7uq@%W6(*R&}2d!u>(y~J=v~yrcNQaPZX(UTyNPx;%T6G zikiw4iuH+#iMdfk3B}EX)4QU&Jg+i#Y^w}x`~2xxg@p-9?pQuBu_$HChE3;yh6H!W zzB^5LA!>M$tr1xE)Sbf{R>u6tFA;X4N4YE>6NoO^*qZs-!=G!49M{+Dje=-7L#UHP zo?x3YDKdd+JQu%xZHjZq6)8EcL*)7@buxL4b=gzP_?D!ghISj6XAFnM9jh8xELpf$@g3a=~M_qMGsw zjOy^^iI8ydin2ZWiQ*gMTeHwKDFwN!Qu7JH5jK)|>lBY7ia zP5?^$Qk+0eJ*Gc?v_xEL!+I!*uqHDXvRoK_!>oKvID{GiD2{pa!PKJ z3$+=*YKHj|O_pt4xuJb&~C_S;s7j1+4=@^l@K?KlM*et`~1h4&aC>X=8FO3-ZpYprEwZbrUtAgGeEk0 z>>46L-pmP-P_e-X5cTpQ=tqS&tCC=iQ4%NeRz(jkXG7Y6aIObKINTwAuHU2(QSi6} ziU7DNNLE+~uqg=MOtjrA-yd7T@*#Z&-y?%>uVRy{}Gt}U)0OrI4?of5`e9Y;aw!{l6tYlSMm1>h#`qk^rF@Y~NF+V?FN3WJsx^Vq0pRq1~2do_J${Wl!I~SNjS;9CD z6FGOM04!8Yxg8mSc0b7HE{G@U<>@K&&!35lKjI}Lldlu)w;7LGotK;*4|hJMxM0(P zNlKnN1KJc9D%W5rx=PoXV@EhfSp?e)FFcQx}$fo6_v9QVJ@es$XSbT7=oM-MBzYkm&GqWO`M< zPC=m|mPxnVf%2DZgW3X2g>duVeS|!^xCB#EC)`&g}ZUT*ep0{75{}e5@8izf=#K9EpbK z93KBGgr0JH@ay31wz`XZn(xFdyKKJIR0Qc+{CV@WjJ^v75>jCw%e|H3bn{3sR-8`z zkc`J3W@t+fy3H-BH`!ifk{rZx{2*`6ezSDaL?17>I2_K-Q-~xN^3VxWF?oo23H-y+`2X&+sAJ>UlRF}?AAG%w#=A^ zz;LC&DM%#lSz}W+7O1i5}LgW}2DiAU1<>SW)m5Og4P#KBH! zY&sz|biEt>pe;u4NOSd0!QM!%NIJ1>@$9*W!~h=syT4LoQX@wauaj)a8aKuv~c(qUB4uA;ba${r0_bHO-w;tFNO%KF{%Qt{@@*q(oQg!HtEH+#? zBhNvnq=lzauAPF;-5%K5$O|4+Z(I6KCtwNC*hbIjjB%aC|4m(iu z4v0Thf(ft>2TNRXF9Aahihmf8$SdT=MMGH}%+*B@shYS19h2CE zr5g+s)1JARb=yQqWj%Q8+*l8wCZ@$~B&Ss4`SecD@~uxe0N=Sx`aoT<_270P$)Gx^ zmD#XpX$=At0OZvW>}%ZUH{<)-n{(xh$d*pEx`y!Q?1i209A3iKTFzVw&RqKHR$)eL zR7bzAixn<;F{l}Pp3U`YPg=qt$M^WXHp;^`&CE+1^UgMh&bIyMi^P2o>r4u%pRwYy z4y${v@{?4V>8tz{D%VzjhIdWCPRx^b51-)SnlE?xU4c>o*Pch4x4}o6nTTFvez~@8 zYuGfj%WGhol8^kl&}xaeOVLijF6_%2JjGa=qGA6|JWCZp>)h6Zn`t~-7y zjO0}I8c+zP`8>VRPUEeXSp_~2fqqUC26lU!Cb9d zmZD%Nm)^ahTEX4nL-CAXo(lMGvlY7;j6ydZ4$49hLQQAS4x5dW*9>X63L4+pV@ z8o90g#%zy_d5-u&1?YMz5e)b~4?neQ{rjSjuPHK?Q}Zrp#s#q|OW-x#00s%7y-ZKf z5~JRL7;K0Qj@Jx;Qt?BBSXc#zmMQ9KFQb2ROKhu^c&=+9c$ z-oY0)KFNOrI{-3h(0Q2fMi%Uii2AY}_`Y zuMhEAOtb|*NTiwERkD8`<_Y`~+cfpIJ;W<9cJ!5hpa}Ntw7)1blVOv8y~u?hBCMs^ zfDR0YyGD*dR%Fq2e&nH@&d@DDWXL%DxY@TH7Ua+gnZ7uWXj2OMs5x|wgTziMh&U%a zj>8IjX?x2*64Kqd{U^AVkrM!YR(^mSXDR<&S!?T(oxxk^vjQ}vi~2Sc3Q3s)N`FXoZe(#MkS-9&L@Q|i->x<(d=QQ!lpGI;~5vbXSB<~pE_GbiQkFB zlu2moLy%E@+Yk4hn2{f6G%3+HjV&u5W?*+D=O$JBNxh9!FN_kvvZJ(~e#BTHYt_%{ zfCM5^FqnhxIrzMXTt3p$dxZwcx95lCKsOcYx%GjJ{dP$)9PBIK@Rp4p7?6QhY1f9~ z=k$~+j*&@az_<1?S(TRHqkd9z-jNGnf)!EwWl0(UMEt>vdKWLBX7yofiqFn>6L zteVLT4b*BE`s@&Ly#nvC(s?^6+@e6mQcbC`=I>G0lmd23-3aB*EL4-4y{YF1aIo0j zUd)D^Qd|0C$1zaT65{*}_h^!^XN@cK!e`%4ULBJLy#^n@0U;acf03e zO8%ZvyX%_#TwB7xxdh?5SwjhEOQq(_d{jzFl zX32x4{ZuY8dDJ=M24hSrq$@QBnCFhUyP`76b}`K%(%;#JKNk8f9Dh*8h>*e>GDhl= zMmnIbidx4+#5=?c_G_27GRn>%qwmYu{gVYFYB9!EupNh?wC|unow-|gwO4i z@x<}EoxguenAesPOnxCLv7IpxR&ez%u|={KQT)1Z;@`K`Kd~vMeUhrH$R)hl&_ewCI0_i!$~}xWryz;#+2GPTS?&n|J1(7~!tSn5eUY_`M>bwTUG8 z5l#aJl2H-YW_mR&WEyVp+E3LO0W6-wR>Gt?Ot$%*F6roOP}(9||8Xs0Ph;nkT||3zG}PJ$0) zpHtSS_ySleYX6=>b%5mGhM6v1sqUv=H7l@xdqVxc+tVqUyBq5pSQ-CsSyf5f5lI={ z8&`2rpy>ldcnGVi zqnJ?+od&(?o%-WjRr%B(lV1!O3?z(~Ze5#)?U$L4RX%v!-|51zzSCenO?UhL76y_0 zPJ_{Gu!RKDaFrsco%hSsVWkfw;Gu`Hp zfq?!KP};5ECig1fO^oA4>Vlb8TXcY=sQA-Z6*3DkQoDp}w=T!G(y?UD-m3vsg7*Ye zKM7y-{G@v%?jukUwv`)WbTv~ZDYv40S1c+kNc4>0#|+v=4bxjfa~vU0hhvh7(QhcK+=K*>LkFsIpGJcv4r$u> ztp=M}Sa&g2Lc!9B2WT8Lk*IKN2IGA6QSBq+jvDOSMaa&xZTPexcU4U=M!}Mj{@(YG z35vt$h|CQVl$s#6$t15}$zQZMs@FVO?`@PA&&bZ6d--+oq4Q9gCf7hZG=-Oh zkKn|U;ZE^kpnx<4*rZW)i#8vu& zF7cIY39Yl6^$CuGSq4%ez@Mx*7z-jqaECUhU7a*0t#1G^@h#2Gc4NHV@j?6bu#WPZ z`_*rMN5lgnbi@PVWJD?m3XwijD_GI0JUy; zATI`se)%s)ANepdVxl!o2(U*=wlIC5BIJBJ5pWFz_#Js?wLDuO~i z2vQU-KYXw$1GyeYwwx_DY{e_!NJ;<#66EAA0vIjC#u%^;!d2<7CA!=#ZLWeXuW*L= zAk947LG;$X3PFfU2hFG=oJ!J`^HOq6#`$plmPpJd=rNahAbM!a6zC=ojEC7w#}(f~ zi?B)#Gs~2ETvzwpdI!nv(c;218hXEgar>pl12+3dGzZ1CRMpp5@%25VMiUP4u}spG zL23p=t_us3(X9<p%cLP4X$9+ASUI6#rLMUFXBy%LSTg|sGb9J4w5lgse)#$lH1HFd$Rkb z;#NTd57^f9^++*N8(p1!dvhbz!<;-+OaAmtt1H}z&*4)HwZ9{!7I~bTs4@=ksw_s{ z?zXB`VY)UvVRs-|-bm$rQoZjgjR{j5u&HsiyqMrDE$&>n$I?5+D~v&d+gwy-#4pd3 zAP3H}Fu5wCOSs!$tVjl93XV0-s;jcHNSMU_7-iJ;t-mD!#mKBtUff4ESE=K2)S(K79W;i3TkXE89x9pbVpNFU{nzhj(6ZuddmE|@p zrZ8*0rp}(%AcdLOpK}{wbnlgp!)M}7!!yg#aOGNfh4#aiRRwEuV-!0Zbf+;YPgzsD zJMD*GxmMR-Zratjec_aA+J_R>X%r@&=RoG0NZx78(>yQ=pNvE8r*xnQp|MaIExy0b z0lM54w@||+E`@e(FwPD6W|q&>i&c_vwa6DS$R<8HUG8Uw7tyx5k|e*mSQDrG|@u5A97_UOEN@Vo}dy!w#5gdw`aC!582FBva|ymml7JA!Wk zvRAAXK+5c@YFSwW}NXI+?vpeTe1 zZsq5$zqoCM0;iy@FB~-eZ*kE7haCD(#ZHCN-?k^P*6LHu*s1n)3{MSAbl_EO_?!rVdO=Q799;@=e$V@PCxS4T zg3bg@##UvBEXYwvm;1B85ECP#kJQ=d%iV{H<|w(ZI?_!FUSJpL`CAxJCy`VXZ9)OQ z_E@?5tUI;#W^r?FVYW_#)RdatK%%j#L*)6GtG9}qx7m(j6?>;C7wQEhr6HASfp%i0 zQ(eWrnmZv&0DhyVVFkrWZHTM-Q?HtHW38LA;ydp`y-(ML8cP@oF)G^>FL6nHf}vt2 z_6~A>u!6J+#Cct!_4BR&a?JN1+v$pl{%p4g&%F;}xrUUBHzw~$^wo9~2_3mAJ@=&;SQc8VBs|vIxsEVU=r$m_uGZ9Ca+f3+N1x8!^Hukk2 zT@~F>PT?eVQrg>&JK<1rl&PrEzx}-r_L{q|4wQtyq@UzJlp<6?rak3whV~4GD}jKk zxmCg(432L4PI0+19b={l0;M;?NEyx52#f_N*4{}oEH7}wGx?JwbuJ)V=!zh1;({RQ zEwaRtb*pP+rOJLp?rw*N2FE2mS#f^!5Gcm%sMc3gFY@7e#25~4Sqp%C35C5QHC z1NNpY*bf^?iO)X~p$O$}&JlW!LZKek?|f~6mWJ2glHXB3z0Y~k-OoX=8JM~0v1{b# z(cV9ro{WzTf<}JHc3%H2YWNQpe*X(<_c>;cuPi8lN;fU&n?iRLC>QBhgSAYw zE3BcnMpKte=L*k-mJ_#RADVH2ASf3nhvngI5;P$v`{i!^=>UQHFg*YixU@e^lO3Q; zY*dqNZ8Rs!kEZuG3xW(RO?{}HA)mj01p!xcgrI;B#3dO&YYDw`D=Jsh_UGM{tak5DX>X7yh0wVv$`#EYRmMA%&< zMBF}7Voy}tq_66ZNbe!LCs0=6m9VEoFTxt>HZ-0~VjnvZu_xGN?3MD_fgNj*2a#ul zYx)okgzjO3?Y1>y=3YY)n`c_z(v+erS z?7wMP0F_|P&L>v%_p$%GS5cMP$|UL|Gi$W7cZPrP@}#}Jqq)rdM2K;tIh~tY z6T567eR^_m4}DR7M5JN9*hk?P6idKQW$r{7L)0*U6)0#CehBd8w+Ing05}SX6De8L zvd&4+#!x}e9l!^!9AERxm!T@p0ky@@rse?7l2h-4Cy(m@JNxpnhl$nm<5xBdh*}df z8#4{|IMiN#nc+e64VaHxfAq+5&aEZJZ-$XuDdKfjz&NK!739eB7*+WUJ@=l6^Y49T z8KuneHePxkqxITq`>NE#_cNF+!O%8k6s)oPQRdfK!VV;CF#G3HYf<{^QejFu?T-X7 zPX>zn6~2i{`7A8YhsnlCIcvp4gh66-slG6diSNd|;sEA&2cvX-z=j}7+Gn2x!cXC<4JiGL^aFV5h=67K|gTvCTR$)m4K%!22R4!DBl!bUMFHjT| z1+SN0d;^bQiPRsVTL%Cy zj`knTs>2BYElxz{P>m_pbGn>CQsbOz&YtZkS;%#yrKTmBDih=y21pM}&J!S>#2)A- zocP($mPVL_S^65akp&ZzDGhszR9&4D0%J~^zICKO{EoNI21qqKM#!5P3wFKx>unvV zfNzSvs%Ga>obSiYJG5I@9KL5C*0DYRW~p~n80dG(kWSNK;S$~QA&;1B>8?5y@C za=eB7nFoHJQC%>==bF)cII5r5IE8Z!!F9mPU!v;p)z)~R$a}N?LS!&{K+l^K;CR2~ z?(<(T$A6`wpzI`_-FeLH;lHL=EZljnLn2{LRNNztl|k~Cu}*w4ja8l>12Os0CA4%+%$Z(c2~S2@p#?= zisKmV(@a3r?%^K4Vi>okPu0A<#}#>msFKo~Oc~^N9|V4m9qfEC-C&(U>}RF7r0$3l z7cTV2VrSskFoS|a>VV;w-YTm*NqA5%DC;K26h{ zA0BzwCwhhDHa%UA38VLwz(Cf8h5e{x@mvmb@!PR7*>>kdiNZbv-lnOSby?K z*>Ic0HE&+LbeP)ZC;Z!HO(Y%GTzhujTq5`D#|HQBMDSf*5l^Dh-@$I=70?ix8D=e} ztI!HJRxmBlA~h^KG|jY0psQS1_s!4Izf4J0s2d`XtGL101CM-2B?uE#@=G>q1)U?E zR)^cfOUmhNWJ)y&lB0H{eCxiEdAe1aL>{KFtRQ2Dt@f#E<#d_HkLqILh3|0uHF!ar zOZ9s{0{Z%G$4~@(%N__iHGU%ds^IWeYHGFo#aA3dv48x8%ceG?MsfpQuTrQczP+{1}p&5Im7`gQ%Ue;+4v9dVRBtXF9-B3-wnR{L3Hf7RtJ} zd?jj`Y*~94Ct_Ed1==GO29Du3t`RJ@iFAe$DBHBAYus3Isb^BCYgFqka3ZbTD=o<` z^O2sk@<7<>HmC9!YRzgzk~nSRa!qSR>S#s0J4-!OQN4JQ?)_?JMcAc2vn5+qJa?z7=MJa(oB|k6j_wbfJr3J!2HY5@(~Ly~T&%Xwz-PSdRv6!?LW)B*7A!WHZdr zOALc}Y%jm{?cjjVHm!M9dDYfurQggdx1R!!zW*uqKWOgkDzZM3Z&%ISKQ^`4{<*33 z|Et6PrQ-Y-b@9LSn@kloSB*u4FOl`y>gr5*OT@sW7+t?TP-1Dc7&AlzQ1ctay&csV z;N`nUPk*Y`XKhkvg(mo?M&exfr8*Gt<%Uqheg4y=xrS=56AhlOYOiYvyf;}62V(Zy zBGtuyZYc%1%7-2yO=@bY2=6)gnMCXcxnltv@w~6Sj^bf2dQu5>7iJoyc7j3 zq9dZC)G$@_TEiq0kkeJ<;x~e!`lz0KAxQcAGGr8I}AwJOy^HFe?VN zffR=KYd~S4Bq29wZ*qF%d__QT7jL~HAU#EP+BvlQ3^=rho*h5ngPlBm1UUW#csPBa zZ_nK#<^Bnah|0#V+&}KiLVOAAp#_!R$Hy_Dt0D{*!*S!xF;HJh>1}rM45^4xn|)90 z5wUg57=-5F9z?+L?(656(&Hb_-bMU~rM81>hlm|Xy3%7bUsJYUpsz%jcg`nY7ZnMH zSq>S(c&kTpp0gyaFk1XM#7Ah3ZJ*D&KJ-$O=(x7WS$EqPn~;hV?i>-Jis6uLWtb6L z!8OFOE5zYZr#$p{(cNNdS)J+_DM?}FzJGD%6YK(yNpPEIpN5imdoduZ-T^JVXE!VV zK`jdtTLsPh9t3++P~oO!X!M%~Q>I0kW6g?Pf31Oko<^;^JmYTbBKOINAe$nH1+zI) zKv>UZJt@^9t13~<$(XT<{j_QP&3}9)qPV^asdKjGnQm6~!#SOtk+CB~;$Ctk6Z|W> zbX=`~3x!l&`O$O3)nPg5QMcDqzox#Tx8)#DK~#)=_z4=Z&U*npnen9BGN>@I)ABCC zeLqX56v{+vM;Vme(abQGzPg*-K6VbJ(1HLBS^j!pCC2RgbsJ)AVyL%BwKtAerNWUc zbfxM3R(=eFEa4u?53{LjMCAgWTV*g}XGM7WBohf^G#{|$rX~jAXdEns>Tt-mVZQ-H z$kppvGNTGn?raiwTG8LQXwa6g)-==3fH8k1i4|qQ0n!#&vrCXp(4eGE7f`MoBXFU| znyrE_{0^8lshkP2t_vu=bcsCZdUL>fgD+;rF`t1yyCk*?93v5yPs`>ttguQf=ue~@rFvFr8IU^Luz zKR2N`cFUh71J{@9rw;`#&TH~j69}r5cyS|Q(Wc#K*7j$Jdg6$tdj4XL@JxBH)N@IY zrPg%zW9<{_aV#EfHHJf75LZFvM{&^VI3UtNOSzyY0Y5GgjICqvcTmjJm7f5r6dYsM zl-C#c*g3V3V5lBP?VwOJjHLlnFmbP%zUxZCq4FGn9AD*PxstZq*4~>FD#_k%Bo+|# ze3joDl4rC~y#pIct~avL30Q=t)gX>_p}=XflDy42KWf&6U14LDS{^f2-P|Q)p8JW7 zePnaJCsvMKkBqaKiWX?Da?-GS7sEj|*Y+r(L<=s}~RUi4<6GktedcHYW`fA3-rRXEA%Yu@e~@m320*|448ezyV2GQ#Q!skLC3O z;#B+VF~HxXmIm80lP?&q7G7a@2H^bK8!H#Oq*f6Jisky}X}|oUwt|2LGF5~rx=6L; zkgAFGcxD9)HghPE-7*qX-C+fFe^m8x99U;m&qLxK;QTU!341i-Joa0Ty%=d_g47;e z$q{d9{<9?xR}dP9505M2(-GNap0MUb?#~wXATn1_@u?klKIshwS7`hLvNU~WzR3+a zS9tfV!%KvA56=num(cJno_j3+1ESLGxS|B9DRn1*`iaw;w9O2xd%XJzbz9_C5s-WE zRj!L!fOMS1^{k$IHf|o=P2RKpleaX!H0hvNnQXai^~-6iK-j#|kMWr&b-@-y<& zzS_`_Xe`&LQYl=Vp7<@o)*Frf)K|bg$MFFY5YBLC2=?E9>lS_!U6y0tv%fWP|6~IB zpDT6$-}mxA%0=dXDRo87R^z~l;RI;k>O{K|s_gzx!F(%Gb4=#E$c_}r_1ucpE0%T* zh@pY({c=~aNTROu^uIlSciL|!nzVal!{Z+^*iF6-rt^$kpC6z7B0nfwigx1s#-UJA z(4mr$D+F!4Jiad8#$|N$S-S~TAp_`1CS4H$gkpkpX@bbbaUr`6VQP}1jO3FMP&oG# z_NuaWC?*(8)EZ@w0xiZ)>qtjQwqE&H_TwdX*;t?qSkmK_VM;+YNz{xH7J-(hyQRZ6j5I_VWRAE zCtMH3T!>brGw5b;qXaodmsJWI$Rru3yt{}66~=dA_m7E@ry2zfa&P@Uxu2#8ZM$K8 z!bBO?7sbiM7I!Ncs;sl+ny)tt)RVVIl+w^jam2CO`ivA+ z9j~FgKZc_d!ZpQ*#ebyI=&2u>3TYeckll&-WLy!Lj7V52dP6_blI^iYhte>KsI>~i z^|0i}(i3eFE)MNr0WR?Hl~3AIb71h_)bY(#{l5NkP+~Puy#KpfH^d`+t@*9HN&lnn zM)p6d_x|7hoS7}M5b~GyQ;H!Ydq@BXJVJyaBP3NG0lw=12%Y#3e_>!($+~{yK4X@P z34K|)+rFRISl384Qi*CIQ0j$&Ng|1^if$I)ImG23ySKyn1JBMZ;OX!JC>o7AF5PaQ zZ;#75(;Y5!dG3zdK00lY&3BTa4B7G!83L2sGuyNa}u<_Ya{rZ)v9%2gX0d@*&{@}3mTIoURkg^t~9cMRN z@THO#Bx;JQK5-P6eNL2Thz&|xJmqp%kT%}(FpT&=-*Iz`T(5`zw^ z<$G=^6xuznATl+1+<`Cwce;adH3$rQ#v1KbDHf3}NMQqyrX`e^4i_`_Lu)O$%kV?> zCc#~Na6(R$i0VsgdJXKBSu-}$Y{pCrJLq*`u4>GFh#I z4d11LP+0baJB%Os-tfv4^NNgCB=d|Ss1p%Bh!ZP=en1wPFU}!K9PQ^Hm!No-V zzEtF*xs!04!dzrD7i6QlW?g*x&VO5)6EvZuW#1sk8tmPzLv@?NGuPQ2kfM}lJky$O zPrX~So;QY>Mz_0z(5J;6tyQDp6CYB)`7vRfmBRLpmXdUuAvhwTaD2x%a%jhMi`_

r|o%%L7N=mId@vl`tU9Dv*-RIvy zft1g`(nc7LlbGuXe8R<%484a24>?sbt6vL~oF%N2zM|tXM<;s0-OLcV{v9h7O}642 zW@@jIkC0qr(3A-Mb_x&$9+B?PF}`NCE3Q2gS;i@`&ZI`8PSnRKdc~WO_)xZ&pO&rp zMJs_$wE=^Ql$ULt3nxce=4*|gi2MFZk{)^{$@Q@@Hf!TfQ*A7mhbI{dO{rh@2vCgG z#g=RHtO=~VSoDz=fAVILc!{KQZ%irFh|y9Pf*V5e1bB`y%Z~Sm4rj*I^y7*A%8LI zNDufDasG8M8@Os0!SOk6Y#B`_HxEvSPR4h-O;$E>%gIm8f3X# zDf~8sqSrZoTm4k-c%(DnDI$1zK~H&s-24ID!r)$h=w4woZ-8$;SW8$}59%9Y^UQKf zd{=M&19evJ^$n+2wDucN`-#X!VYV$owMuYC9FN=!ttzxOC@2*0-(NbtEnb@Z@8Fid z0?Q3Q0x`P0RDT_l2)lCP-o(Z%jF^2hkknjTVa(#oi!OLy%WuX{@j3;|%N{QL(gx(z zQS4}0Lr<+~Nka+2mFPodFdi6@-vX6xDJl0@6K1bF-g#F1CC(rC6;kN;mWn$gAZcMG zpTlFnj5ng7=c?vgm!3x$D>Dk&TNHUgG7f!d$H$Y_g#lV|2pkedp7sYb#HqRA><=JK zmi=x&bIpD^o;qOU7Bg@|Tl{iVKJ$BR9QBN35Kyr-jr72hPq@WRd3^K~`rH_5ojgKn zOIeR3H?#VH`&auEu`~3_`@1L``^Rv||Hek9s`hUOimKZ8(1@9do}-zKwV;{3k-@)i z{_~|P{8w!z2mb}zc`;WdJ0{dxN@h;GGp1!KBo1UHuQAUOFgD*rnUTs)dVjyXjQ4}&R#Z@Spe4i%K@NeEKv}2) zG6e-55gzr1w?_a-;?g!hI~<4xtQCDve+3jlMaxjjj<3&%rb-NAhXu`r2n1gO{a8OO z{5>U}E?Nx|x`hVcPc8^Io2M&Z5m`+o!Y^auvc!#YK==N28KaN;ud$~@qLRWm4{hmM zlexNmucG5?pmu}!o$wR+>1?DWf2k?x;9S^Hn6W$v1DPnT3lC&gljJ1X%vZ$qg0-TG zc;SrO+G&Gwf`*DZ5?W0sCiyeqwSb2r9J0rJ%4{pU~kem5;fCX3i!3~Thu*ads4 z_^^UHz>}$+gpnSw$gLHQ_m@`7{*(jpi1%DTPO% za57ELcIQ5uLsg_+5~g?1ZAL%Qn8Lvo>Sr!gW=@`aaYs6P`;5cjI<++TOA)!Vf~5I$ zcahrOKq;u{j0nTS@Is14YGxsZmlb$eo+lgO$LVPhtUU~EHoA|A4;+m8?~u+2tOI6Y z%Bt7nvfg)$&0zTL`LJDFF%uldP`utsgFhNx%ZEdV#_wQq1}x9SZUsLVP}p?pL;IJ=4wtVKWUbgHyF{W}$1yto7HO2$EvqX2^Y4m~ zITlfO?z3$E&Ylq+}2mgW+ksM4%o3+HSaD(9Dl4rx!(b(gz6&i7ji38;qjKtJ*7sEpLlq z1r;=ttBZ~Rs*=m_vS`~^FBTMU?y4JSvBARNf^EHV)KqR{wYfm$H8pZp67Xl~Jbs#*`j8c)E=^FY(yk%*gNN_H_j{Qw|7SJ$#>a~9Q) z6O`2m?Y8sgdWdR{PDiD!$XKS346m~`qTZI?Y(`z|;P$(p7JV;=`|>RHl+UZlk=}7K zt;zm=scTf{HEJebk%%BGFKSM0%J^iBcbvY&!chZ*Z#+#Y_i0o25S?QQsg*|PFtcBl z_4HGH*pX3&xoX$tzD>;LV%k2gJSLLXmb7p>BzRkLJ%GNSI+!St;B1_}7+s#^_sg-W zuIVQXu~fW?6Qi}seL^o+cg$|R_aI8U5sKo42G}V18KJrfN+lEN0?ekd?lZdQGsi5y ze!25_PbO9wWQX4|L|a< zX?!=UZ{Tkkg?0~w*EXO{>NtS8`TXSrON7Yxmwt2WF@GR=pmz?I#<>j{xu21=B#bI*j`?OYZRa!adTzjX_zoTx{RwO0<8BRrzmh693!gD`pPJ4wg8a0XSJ+$4W{qKi~5>9D-p`;TYb_0`n( zZz4T)Q;E&~VwUuWE@l_iq=wrAirLm|e)Y-?F&1vDU1Ee1LsgPpWJK{;i}H{;hJ~Rf z>ApLLOnj}faB~Ef;Rf0MDZ`iOkQ9S;((N#VyJ3gIP`hD=#*i|`b?mJ+#&!Jd9}K*h zTRseL;(Y-I+?ZQE47jnEkcePIPAY@+h|46E3JVt$ORw4?SSZe(n?Rho9qS+uj4Okd z?A*xQ%-nuhwTWcV?KOO?E5jBEAj*x2nNlAZZN(l~5p-?i7wZ0N6h!ZEVAz#vA1F9_ z&b}MA{&;{4eMjF7X1@jikG$a!C@2^MmI2$?HEkCo==hs$yI|m}y!X{L@4PqrF$5vdHN9HihzAV6he5VT8!`WvEfP}35rWU zJ<4-Wx6;NqW=3evp4!Im^j%WGaZQJV+LjyDHSmPeEq_)^h#p>E7}`EM3N4@5phW65 z19suwA)EYQcHIG`Yd+;JI7)TjzG6pO@+V-DLc4#w>TuV|RN?k`;~ljB5x|<0rw<*a zV#iZPu@yq7*b!>hZP=2!iyEYXVQtWoxeJ@1bn$&O&s442%V&$y^9$2bE!*4w$j$2K zN69u>Y@?SNM0>&N41oo4m>m%Jl>ng;AfriZsoT;xf_Xh_3heBv+>$M*z(2TUWU{(n z3>;4a?b{M{RX1YiN2RxUzIaG*a~2v)0{MxMcSt;!gc%Ov;=DJ387))uOrUIY&*T>B z%1=<+i)Bfr(c)B2yHg422E1F@D@%B5>gBowB37_s=9t~uxYZUyIDw9l5#jxDkGZ7%ln{OyA zsf$ZBGB@ZXe!zQf$TJF+p!AEB%8C)uxw_y|S=?wD#5$9R#`=Ze)wwlORUa$O zjP#~9e*h=kXViGbyZ|-yrJ2L%?(ETT1nu(PSE^a#79#QfCmROqO$;AjThI(eWOwxE z)y#mWUS_73au$J1Sum*{gnI2fW)L~ESY_`SxVH>pmqVC4stU+wf<=e7m)sa|T!)N3 zHO8-fq$FYfUYu`U;NDTtkznP8fD~-xf!$#cvd$5ye`xCOnCR8&zTU(8_bQ3F-#m@L z`(a?EIhK~%c;EC#LgO-pDMjm(;)AD1U*z&u>&HrU%~DMvuW?Zxy@ZTE5aD0@gBG2> z?lz)|ij`!&)5u|eNo9({T?=)N?5vUCA=k+Li&A{Dobmt=+|tAyNr1$rn|e;!54<}oPA?Hu72T?52Y zy{_q#l%SKVwZ|{(D6B6RyMla3=dcN!g?O%$URVIK@!ZJ*uS+`0y$MS`dKm`?H;c*2a`x3W(Vaq zN$i)8e>glHW$`C^FdJ?)vkd-8ZrGb^Q zTNAjzg@Ro&(J)k+tSnm77+Oi>^TrT?PR=p`)@%ev{y>|htFmQGj(~cEG1)Hseob^W z>|4lL*)C*~MNRGFVppd&>bT)lPt8?%nr^(c`bS<-J-XZw!LkD9+u4f3#pPpHO>~~D z4E+)3qzc}u@U7^kdMCcXp;eY`V#%O$RE2B`tdsgRw2JG8)8rp@sxx;mgn{M!`KbPE z)VIEHtaJhoQF5IW?gMpL5Svc)p-ruIkCUZf`tGGC+_pg3x?q9rBSzfS0?F&-AMDM` zw9tIo5Do|XhYTYgouY4pL`S%Cd8k4BSzK>M_>7^LQD&)*voOOSGv~$8DR>bcI=aEl+Gy!p z?;N6bsPMB!7GWaYg{ADWBEDq79lzOkM3dF%^JlF znrlhOz5a6>HDO!55%)c@kbr_fB8O{B939dxyERJQoECm*{nidH?ZagI!v`j+f7llF z*Hlg{B#8ja-$|pw>1%rHdTgaDp6JF56JgUiDXE`yV!Rm=Y(N(QHvS;jve#Uq z!O!^M+&;iBILN)hbdZ1G?so|Hs`@0hq@AlR{c+00!`6GG zyjdIgd`fELb~A)z){0scjYO z9s3F)tdln&muKeXm#ESjk!Tow$LB!zH_|r1Cfm_nt{C3ru>?VKb8)70Q!{OURyNok zs|TR240fKwXZcaZc|d4_=YCk{t_~%g*f3`@JX;GapCA-XnE8V>k1yePMJ#ZQ8eQ+! zAuXHHc!U~T_`?gNTrO3l;ne;-6DMipGq89d*yGS*^;UpZ51d3?w+wYkK0opTBY z8}L_@^b4#5`SU$J4s%~D8>YyvDkl)>K3j%AsA_0n3-0hfNd_WKV`<`X3?*Wj>Y7FMjC3we1)WVhoad-Yc_| ze*4T6QkXu6`f>=$jlIq^KhD|2e~EUUvD|3U2j{tPqCv8PkMwztM{!i4bE+Bw%-w2y zz+jkEr~RRD8~Ux2IZLsI9D7xt3!EY3mF-pHOSi$K(k6+M?LXehyPR973LzIoWd*Mq z`4Y2G>qySc@H+>%Vo^~MS0RrP>ECMA=G&V^w&yL6q}jFw7gP$_9@QpEFcx4@CqQ)z z$7$M}@0q4-h44i6cV>{KuTKus1RBsDY-wCdxiZGJo@mINn)}(SnC>SWO*pPyaW5fe zX=>V-(-}K)j#{-a6xoh>KuOye8Udpx#%AWM2c~63rm2Xho}r-XdWvYK*5mthy;joK zKAnr!VoaAiPDU2aN6i+n)D~nP?CQ>}M$Xc#Oiy%XntjdOphzJKp)_3yiq?(3#YiUxbh36g8lV&$8 z4l*|!YQ+Ss_07K;`co^Crn0IJu`UKTkS?HbU|Z8Z;U!N4%1fmw)w7CDSQ>nV$w-D`y@%-Az+b5j%SlN|d%NlYV^Nz|M9Rg*`TjLs+wYvKFb zs00GB>q3<}{3^%s^8x4fjTkaTVjyY9`AUcIV$$0GHi4wtCmmN$r#v>Vd^- zrec_HI;GQjh9yqv0QV=kMlx12%@_0UUH5=bS9{B6-2SQvtfCmbU|k9fBM=R&i`4yy zV65mn@%zkIw}cBwKMyQMM(c=qsU<_wmAvScoN`qO;vyp#@@25aZT45 z;gZJP(=NHayJ?KolvaO>TaR?jEHm^zp>X@>p3}3Z109bk+Yc^v)3v7q5|1T25Pb4G zN$TFnb;Oevm&HXt{Z-47^)KY_iEM-7R|!u=`C5swp5cPnmlj1I8BwGgF*8(d>dJnT zg2f`; zwC5%R=5`HLA1k%R4fVLO=lYz_wQAFTdlHG~G~y5()$dz@akZD&L(UI>BRscYYXtcp zL&AF1b{y*i7@WdK%Rr61tfb@g=y<>DCGu?142kT9NR7Jq496y7@Hq+{AMn1Twp7Jd zLK_)O<=R3H0R~*Og^i9tGb*fb4$ov-Kjy(z`DP{eB-AD`7`QwGLWyI3zaaW+6rG1s zWw8-c8P)-$(-8EFc)z@fg2W15MA7Ll4tu_EMg$;zn z;ga@#dj6y>`le&uOP0^86I>xS_b(ulcItTRAwGk(y5`OI*$kCF7*j>cM4b9iQ_?i( zTRe!~`o37yq)-n`?#+>Z3qbsn1_2bLBAzVm}Z?Ipx#8RLZRr$uB6QMm}!9DzbE4Ac_wkDUs4xK3F_05OYT6CSz?us6NaPx8%gpH z6^66SOztd=Cu*a4tg$DPf~(1M`1SEPbG-S*3cn4V>rNO&9YgXAi*^#omJ}-r1YEE) zd`RVf<3b6g!>Fm&^7aQ36rq0o8xF^~5(Yhl_~QpT)j!#C82;JT@V|7j|J}e^sA}Q( zFY@oy=tRcBQ5*>K*p581pR_h?E}Y>Wr7^s}SP#g2M8lbseLO(gc&?Q-rlBd3+q6;U zEvHNNR?MQZuuqa7B(aGsXDMs}JZur~vbw5j5$|&`aPxgil0l3_pf0WPZqw`O^@;oa zqJFydd7_pP92Q75R0cUqc_sgbGEj$-GyeuF&;;dA`AtUOHS!b1hxT_yuNTxi3L=zP zpj==xiZsQC(k@P*3(A&)tIlqMhu0p`W43`ej~WPTmu3Ke1LH;>-yTWOI>yz)PM;N~ zoH~;$ygnUzA11Q3vFZGXWjq*6C8i^j85v)F5JSbXEi4P&g9RJfPXMZaWiIwPQ${qI zfMh@D3qgM}dK-p2x@3?xOgLRZZ+PS&8LtR^*vzP{1$`I-tuXnO?g_;Z{{y`x&5*vQ zub%8M?G1B~6=2)AC3yE8z+?PE-aqZg>8lrX&2TYyOZ2B||2yK?0I=?a-NWh>VGtaJ zc0-K=ev5CaGj3Q6S$XShguHkF)^ETe*9-)1t?RXSfb*it!Z%%vdTTK#==?XqBGCq7E-YMo@W;xr5<{5q-` zEK+h{vf8^%zl&Yh*ElyB_0-{L{L_|{rblg@)N9Wg?sh{>?-iYB z`pC?Md8jx6FsFMNH<&c(eh&)|k92q*?F(av9ZpMRN}^02hjkdp+z*2-A2FjJ+||n~ zjYz0uEBRl34*e?b^!kHqAD;;IwQ7zAI1Um3R}HB~lh^n(m!wV`Bdf9mzZI;cm7>b8u9&jTnwKhE2GOyiHmnOj zXHpO8w$;-y{s6U_L52yh7l@?s4Qs_ta{M^XEbcLKpahH!drpn4_DL8;?>pG@+cejc zq-p~kbV649Cd8^rkV+;6SoezbUa=t7L#&1-UBApQ`blPk`<1`QNKE6kRWc%{j0^@C z!6;9m^Q~cros5qS?Hx8dtSE|Xx;$UQWMfKYNllcwqWe{QctoBG{%$_xd4v+@HEE{u5A&L$Nq zBe7#k!wjy9!X#!UKgd>y!wqhr8nig@LlqXvqqsRL3857m)fiJvfNJEVt|*=z z^&8w#ggrL!9y%v9Ikn*L520ZJ26l5Yhj{SG)Q+fbB&Jv-Y_Og{c)H}5NNYh4}g58WczBXz3D z5H^+uk`xSV4q%1i^kJx`K<`%heQRW9( zC@3Bm<=P$1yj2uW3gaSwLMD>2M(q@|GL)%`D6UAMA$<%WRT-M^Q=HeRaYQfbmfAq*f?LHRM|DFAh08a zI`mSdx*jIJ<69UFu2H|r3+0JOKOj8$ zhl3qAvE}Cu_Z~a86~00VKe*46ze0;-AZHo?!e~kp*vZuwEydm2h~6)2iA< znLP4rSm>$qc1Z5l_`zG1h&RUKrXF-4a_9U?kDJe~e&b2e#7B-y(SjVnpW3G%NC3)u zL!LBw;y-_{L#0BNISW^CnH0~fUL&oir@jut20rvNU<0k!pNQJY5Dpjo?@0U`<*-{z z_8PIOPbLjcd#2IqC(pl{YD5v?^ON5VHM{SE;r|SBqx-)q7XH&vOH}yJoV~Hfs`DnW zz8sK^=74iJ&CVfc9-Nh=Ii`)S0ABH>?2@I+=oRXP|E-+Y!{!UtfCOFKNPBmm4nfu` zDlxiwrr}g7<9+7+Bs=Nx`*ij852_vIgTb$_uCQ{7s!}?oiP97mJFcc?)@Fv$?XK|c zS6^FVguxKxVrDY7Lj0hHAhsap61IE;;C%TA2|GR!SVj(GJE38z2zomF%4XPMbXANyBDh5G@Rfc}iq8Mtf!}N`Y)_FQ;>vHq)Ccv) z;9lhVPaS#>y-WDLbgo?QxuUg+hh7|DBnjqq`-&YF0nbv8kfY5uUC~3WVYn8ggw{<0 z4O)(&_guU*C(55akx?Bchw72Q$$fluXniVl=jbg)XK-74b90lwOhjQJ}04cw1P z<9ceIUbA^fhx`+0nJ^DeCi??Dr$GwbHTlrDBhppfrms%EdRETV6Aq zan`7>yqIo;2=5;LYxt~d^1uRR*eFe`Bo68Y!1drz&63sRsg0p8(rkWELSf*MKCay%KFzBIZ zmrjvXt{+IDT&AB$VXh=s9JW}dnjhw_v{4n-SY|3a$f3kkmM4aCu2jp1f~7QD5r(RC zp&}Gb;jV-rI|!tNttcdm;#CGwN>CB@M`@!nEQBJjETmMQ7bW=OF?f-5TeD*^z25ow z=T5iS$Z#-*ry*k4Ej?KG^bV1~4C4zS>D^7UwB(=xfO~2O4nxyE55oJ3C@z}eg$qoE z&NZ%=94uS^rWn9Iyu;+rV{oGa$kL-5*dg%mHon33mjHD2?UVz$hIVYwJu`caz*I8G zdh?|vO=QP(NpOvC#K4X-$d1iG{aal#dhveK!+H1agiBNPK$4=~IpSv--++EkmWNKW z?e^i(y?~Q$yu={kavlnz)R*-UO1s{wfq7pKAacfqkFt&LjJJ{v+_#eT>oB}<`ZEH) zqIy~Fw?^ z(^W;fMw=P%w~T|MyA^mzB#GK51%w>lBoc0!UPnG*Bi^htCRG7$bSxm$NgHP&Y#9o3CrHBkr7S zdrY~qBACI&4ROS9YEN}HGIAa;OMu%rSXx}ZFO~j^a9=IA5-wQ}nHfE^NvzQQWhiTl zh)sOHQyH^}2OGd<_)0Inwr5!wTQ6-W_M7kLb?UFr_Cj&YcO8{PriY5LD;K`RhAX|J z=uL{FWiB&eCuO7ZsT9k@PH=1M>w)=4Wk`wiYAPyM=l~;8Rn%q<2|Ew@GDi<8M2N?f z^aR&thOP97E6u`WRZ5Re&mfVwchsPXuS~3xm6Fa-m!0n2 zO77$PE4*x5U=0Cp;Q9wj0@o5LUYf-*O>Sh;A}#A3p~JiNhOKQ3QUyi`hHZ;_3&!1E z6||sBn-52^6_^I`35sgzVBY=?R-qsfvJ)4?Qm9U9_2?cfTbr)+?IKE-t%>_*w=d4( zrA$~1D&N6f_*w$8@~xy^G)EP%0l>BHKsEwG=Digwcu|TcC}J!qTJB`XQA&=OD7n76 zHR`%z0)r)a$%9E5K~YIhoj3~x>i%gUW7)i~7AbZm1dl}{ezkMxS1ceT3gi*;&A98O z;NYfN2F%02Q;#BT5r3YX5=bUB*3_MC%r>`n@>MdD;FWxaa&RLt8%S8>3^;v95LBJ_ zDLA&>3%Y6#YHO)^ESIHFpohWX9M$i{@1aTGz@2Z0jpMdM<8ZFBS>Ku)(K|f3(NF($nFoz zQN9LyyM$~HV{DS7t~RQU>rA`W5-2IsWecsaq)~kVbH3HA)5qEjMx@X~6*{P z9q7?U4b>b@lGLf>!EBgi$h@(-QxghDY`6re<{W4lNrG1@u!E#a4EYuVQ=M8IX`-q< zp}n*>SKLZZQ|lJ{a5BJL#YU5MZ}oQ>poZ)kL_(@4N5boO4#S*Ps0HJLbvYyI$R!I_ zpzC^$qXMeJYtAlFel?GC!llG!fZekXE>ZRfu7A-hh=P_lG-m#YWu-eF8tGz29oqeV z{*bMXH=E$7WFcLYI0a8A-Fe^7hcvy&^hjPAn~b`^Gclqx2vcyqy+VKXVoXjNXNO-4 z^bB_zX@wvbG*a=U>OJ*}0>b;qyQV#eBl1nc00y&x6KgnZMk*X<&^Cikq9T>(rnEz8 z7{SpXpfP2UUtftuykh6>h9bS!=7^km@zvnvR zAr*<T#u?i zrOG83Cj5mO$=Av3=8gbYC|mv^Voj72NKopk?3k;uD@N+LsMW&1H_ zPQ-nav#UgyCIhA$sSbJ4Xb7lJYeG%API+=g3Wr;?UEyZuqMFIIAo^`*z1??zl9l?* zCQl~^tJNFJ$D85+!w%l70|5__Ba*<6a025B@c{8OP;XU+x5HFp!mk=b4BS9`Cq*1J zvt|DMAPYm;Kp4ohI}CG&j}cW!1_<&IF9A9vg^fwwoR8APrm&gWBvbfyEulGF=tD95 zpw^Afbf%5VgfH-5Bf*^#Z%;4R{EgrfSaj0DjsJ5)6eS)=Q2=WR%5#MDPas=ReZ?=0 z9alZ9o^8h>+23>da%!{2Et{-Ct>D$^1Ef41jtJcAKAZWhH62z9$`lUC^K(=cN+t-{ zcyT*-SCcw{=Gl{CFIG8|p7dKlK!09=ErQ}H^1B0pCwps`_c4Q_Deh)_`T2}8bAz_H z_GYil?3Q%JtIyF>EImPVSG9_2-;uDbJHdD{lGij8YIqY9%Xal@IdlfK(t!K4L=0sFN0D!O3`f)Bnf5fSaa(dw^-2ya24P zE+$2ev_Q1)?h0~Nxi3yGz}mQ>Ts5zK~VoFBz?PCAgIijLW|J zH_Ciah&8?iM+Dh&I<6bjaAc3V7pcTih4nI@Vh5lEjr#BqlvkW^dP9HTk%SV#J6TL2 z{acGMeOL%}dP4XV5Xb)WX1`Y}i4q+cDcobCMBbrzRf;6tnhm6}q)`RRinYTwyl-N^LVd1Js043jBiD-!qjmq8;JER7VWG2`6N5WTtpVQb$8%^T5jf zCw<-h)F~p%ux+MzP4ir~syj^!l)r;H>qjh#f~9!uz3N?Vmo-ZhR_KX4=lDV=;_VWs z+QN_y@T9VoG##bgfi7!%FIxj@ex;l?@AIRq``!K9hv;Z}u;dM!~>a(&?t_fV%%etiG9pc*pQa=`BU7CyJIa=JHqKB^2Y1N znkkJK&bk76Y5q~J&TvjtQj{m6HIC}=072@as%Yxf1<;Y49NP*_fR7(TCb>l%IS{W_ z-~;@8ZlY}cW{3gv0}#$h^>ggD-ByI}k9+~I9-Y~?aIW!>!&j1Fj{sv{$r?Gb3D-mv z#J5hE9TzPe`j~jx4m{~sV@{_U#eFl%q|EU2eKV)Pj4n(2`VP@J6_1MtZU5PQw7{la z*wx&VxEfnXM*ew}Q3TbG@#K?z2hZyEGfJ8plvT^OdQNqQXQH(ap;d&752k#zDACuL z-!@g3O=~z?t|aoRAdybbJSfjB88sT>8#mUlE4Gh_d~(b?AC`Bh3X_vF!n3ss&jYVcDZnW{@2g4vvd9 zkpfbq3f3q@=@!3b%Lnx_(e!|jk#g>esDsPmWAy3KSQ9AaNv^J&l1sMOL#gY*!OIAm z6<+UsXCpaqcUtp227?`iux}kb#}qQU`L=IGWkQClk0zDClt5Wqtxzlw$rPRN2j4Z3 zW|)#_nXV0Eaf@PJj;`ZWhnd$z*xb(jXypFMBwGmG#z5|s;BDl0MD-}vIEIMUOugeafi+b&mCcw!iDCr}skKcnk_jiPF!fYk8OaFuwUBls zxKhAt$1w_}Wd%WW+O?9+z++}FmKbTT9W=H~^KXvIeiaj)9Nt}5WPIJ|T1#9gt4D+d z#K0G2iY!N~W@u>KLUndM|y8@kiME7Oce9Hj(WQ*xix z0npl-z_ZTyr;R|pK}Q0VPMwnBknD6fovON1k`C|#idV^JJQd3J0+-;d#{kNzRG^&ACXVznU(f%x|NUE>$XAq=?-4-w9V`VThBdf@y$2E-bIi^fX5u(`?lb+ed5f=tD_yH z3pJy)>aYjVzwNLQYL2&)IlGc2OBvURGTQl)NoHpfFv<6YinGVJqiyT zIn5kKxlhhKPYV|{T0`8691Q|N49IN)F7T^@SjR6K2-H2L&!GyY~va9?;kFe2p3Wdo}bw4A1?&e*Yb- z^}nywXoP0rwmx5N;l;a zh5SGr)ljiVS63<1*X=L4^CTGO(p9bwlSK7wD(UHKrJ~U`f+UTrg$)cdb_wzAnf2O~ zrFUF+D#QS!b+=h+wFXSNeP?ZIPMkn>5mDqqo-8r@n#~LQ@r)!lHf%zHn3r_qhMcx} zV8WOP3w%>y1{`BH`BY`|{5YAuA1)0SaOnUgQg9J>6`OkIWa@tvp^5~{i#h6~ZPQY^Ry4((TheFaqlsdo zUZ@Az)H{_tFI%m$Obz*(*%p=ENvJTuMB`ZkR-)>VC5vn1UTTQmpFwBgaYILcL3dLl zKUx$XF{_+aDDkdHvahYkt9>&f%%6Zkmn@QYLvO<^w29J?zERU0ONX6wn)e-gK~f$a zXYoK(9ne8E7FQL_D>4jzQOOU)j_$UF4T=!beE5C?IKd6TV#msavAvUvpIr z(QpxtwbV?iEzec*-P-n=Nf_O_q?xIxMR+M(HCupU+f8Q}^WvyKP2JWKGYv?uyh8x$ zC|dC}>sh;f3YPrO>I!V`vGn{ti%JAny=?zlW4>!si_;~0I3k~XZB=q6f(lk(?otm9 z1`~@5_f!b|Ue@gc%V}HU!0*PHs$5l4y|f5pvm;vZ*@S7XY~F6nb9j*j@MYu-o<6?? z&rm^Hr%=LkGgy4059DUXH6m^)JnU>5KN?&ek{z7LYZKUMuL&e9;9qg8WE+IkoR!lngz))M z3?;Fc+<+GpdYs(&0GmDyQg4YoY>^Sl^Y5^^e(6C{19(Hxzk(_MJgWX_{6it1U#G`- zg+d->*V4Uox^IYNlxqCZ6dX1zAM)qkLNh-PQPM$yAMd^kdReFKyfx}IS*%_~`ic?W zTZGa}YzS+{`6P<#ek&U2WODe#tyT{AW+(C|dQp_%34PcLwa~^Owsj8P3!%V!${8Fg z55_%)vv|ylWzGj6=22qCtaw*Yu!FQUa`YTD45GM`_~a7m$Cakp_P;tc!E;sIj9M=8FY7C5I6k(L% z`iuan%fj_+T;?%0X60)GFDPWe-C%azlqVuS|Hgq@>hIvw6zOMUUvcK#{F`H`^k4Id zpjDx(m?+FCqge@poPi@T9}n&y&gZ9vI7%3iA&l^_g*>oZbs>U#ys!pqgJ3c*P5u`6 zwM_>`c*=ahC|+wlLD66tW+^li^SW2bJX@`F8mw)rv9zsCHGMIk&ik0jE3x)f9EI(g5Yl>rl%)gS{hxVO z(74dVu=x%tqV2t{MAvHccD|LbE`xvP;8>3_Umc^S=Ed8AeFr2stWN7?|85H z(1)_5p(S^`#rayM5~{fh3=s&}Nj=Tr>bx`J_$Nu>G}Cp2+T_rfZ>;6P#Z)%sRj^jS zw=X0mi9f6NEo=)Z$8I@D0oA$l3~u*DW|}*(5sR3GUpeKUk68FD<;-pSFZE0+ABSuV zYn(r1`v!*nW?^7!2ZiDTFE;mSXC-8zU$RSOxQM8B)1fE|Kr3Nfj!Ujv_V`g>H{8e z$P#cnd>2)XTLjKROrbmQX;8b&!_pw8HX)^tn$pwrI0@y%+rLiKq}H)-QeQ2aq%Y+D zd(`s$PZ-hv6Se#l|Doh^n>~Tn*02vvaWTyQ; z0se5ZzcIe{<6Qli{Hi!i7ArK3MOMaYM!YjH44&`RSZY!`$=pC0d+qG~H>cSIr{hFw zDzoqV`=0AJWR1P1vDke(&W`=29{b-$NxR^KvQdU7sGjj&A20j#<@y|^*-#<0Bry#! zeTQgDPcuTy9SjWmThuT(e}0&EBZ7Ean~Qe(ce815{M>~V`yPSKVX(^$yPCpg_g$Fn z2HcdvG}jLi+tJQy3|phi9(!{)AQFiT1L>GBd0XFu!dHC_J<2WXw<=}@XKgn65fpo` zoxbM;dUuJV_i+V{CDNnKFUytN-x*0#M+zo}(J+j3OnEaEmQ5;L$;@|}T%9zy#cd9x zaU0<(b!kW)%J;&!oE_*xL-zaOMbBLFW3reu(xj;U*K}=$qADf>Zm05>aTh3U%Hh3Z zp0PH0EbY=3jfVh#WEE=N)Eu=Pe~lY#uJpIcJe_P&?XxkJ+@ZP5-`*nN@_#E6YCiR)a_u%rk8SiNt$Rl;Kc+S!NvTHW?gW9L;W=5^qyanEHCs z;scShlKP`^aG^z%$Z|ssWfS*)X5@2G+L1?7k@^abE8iP4j@#})7YoW6sRY*y7Qn10 zcMh!CqbY}7K=x&zXl`1$)bDaiQV^ZV*!aGuoXDc+o$>-;B(2Wwy0E^r6(Z7_;?N=j zU!qgAN*{~ksLQ4|A@zv;ZLuBy^YKfIB}R-Emqsu^lncrTaVJ zgkai}|#=te%haOlVrA%1m*2T)2Rax+fED{U8IA1IWt4Mz&Yrxm$DRzn9cpOfG#Y zHkVl%R(yF3DKwM%tC0ST=^~gl;LIqMTsQSTvd1_YVv@Jq(^M4h(t;9ZLZvMyr6y1V z!^=ozg+tIBPX>gZo=it?3cnHg_!^+PAfJK}?0 z{Hdlm*o_zpbN4?+t{(p3S~0~&J?2%?4aKa(Ep@uLqd>eZO)yKM9_C~W3a)Xs1v*pK zPl##489K+xq$axkFv8TR75<96mb$w(!TzITKokBY#B=8X)a?LH)@rMwy^p)1hGpD? zeo{Dp8N^t6AH-M+KgM&A%zu^Vf!u}~qZ?P72bk8r3PXjWUHk!IW95txTw@}kUmOl9L3SJwJU=b??E(Wav%5S$5r0AU4PnNnL7I))%!2=G_QT2iQA53+7T zxX6Fp5SU+p;C?ya*ezmyhu9mps0XWOK1pYe+KsT~dvWDZg1nTl>o4iIFT*X1>pmTtXVhI`Fwi~n8KCt8Df#bK^0r^ixRnsL$Y{FL7QlWD2!oAEN$F!mMrtRc+b)8V?yl2JQH<%8 zM6Ts9Ac}4Za|eUru-Sp0NNWmLm(>>L7dFY`ov0$8$xKOLJl0I5l-EqoI~}a47@|x` zuVK=qIo6zc2)5;XKm;%h%l~pmM1~=u_`SS@Iau@lZm(&nsWS@2jg37qS&*;QBUeyp zGC=NfOT~Su)x6|Kud~f9mC43dVIM$<5>}}i#r^Cg7bio26ir>+9y_?yt|ajm(xW|b z-L5fFlaKyOOLri#LuSfKWF>wkk&g4J>vEcsk-WZHCl={K4B(K%LSvce{0%ATFj*Oo z29fH0FeHTFA{>&ac++Hr2U71Mo0X~sFXV`vOEtT~4b`7Zx>VfjuCbA>G) z1RxyE1Lkcp=_)#)=L^l2`{Uz{!HGZHbd?YAJ34}2_&jgIyBZ0rX6Evi$+*9!R+hq~3g+m2Ho`ji{Tkj3Dg}PRM zYeYrIclG?M!i0kdhqH$Hk?)D^dYC8d8-b@9!6!uM(w8a#+EaKcTx8Ts#*ok-X1d6# zE(W)bQD&$+N|%aVqBhzsc;l0BQ)pOiOpNy=A;eV zxDhj2X?Z`u8m7cA(+iHna${$)c>RKUSxyPRiy1jOrFK+KyFtiKlg;`5(s4y-5v7LR z4T?0z=a6s<&7A9n%uZLU!60cJk;{AfJkSAEnw~JRk|wp;SY(rcJ}R^aJ-pNXn&A)j z4`6GRnrxPQIxkh2NaxE0u^)-V?xtQeZo=0~&7%rGp$1 z#v(8N#K@i4L+@CDP?GcvHVA0+iAu>ru6)ewp3+nTU#gde@6q(|0+g# zg<;UlYq>Upu;{JQ@-IQi{oQ@jA7zaelw=m?a`fTgW2z1PdjxHMtZvE5K! zw;fp|V}>j-zzSPt$liK~+2W@@mf|BrOXgC)xDbbw?5dS$7 z8n(EO(u)3wf#bA;-bu&aD9At`8}?CbE+Pt^SSzr-VQNxX3^p~spCK>3TflRt8uqIg zZ5*$9dql#oi=1Dp?N!30`gBCcxQJ3gvS38AsUC^pN5%Bs-`-y)3}K0O4W*H+r%nv7 zh&U3_WF%?rSpY#b2S_r7Z~#Ev4WxuHrFvAQ&51#L&AcO5Xym-1PKMln?phkt$FKv! z#x$0azKzeND#Ff{qni(!)ZFY1nrG4_!pBgl!o|?Ei@(qYW7te_AmY9vFgFF?if5@x zp#?bPyGr2pEYsi{#+?}ldw0z-vWb6!XZe$`#rB}puuSey8dNIq@a*DL#G!sD?L0lx zh@vF>{HqvM>7x$*s~C;@M;^faKVh%`FVOzY0{YcYzXCQ2dXynx?j%#06G{(WTI~0MB!_TpM z1R;jo`3(Ow>~XOU3K^eQZ%JHimWg@r{wR!qB)1YM#=2}E2<7*d)g z$Uc+g7wL}zL5W?+nK*5VVbQpix>?2`YNsWQaw7~&r#;eT|9Y;0yb6M04koT}jY6ZsyBe6}qov4F=QW~! zt?ArdHti7x;%bUseG)ViSB-eJm6hW{aVs+(@BDcB7ilJH3{5I;uu_h=3+hPt6`M$p z-7Pro!}yl^9J=Rcp_ai$ol)03-gfiSoK*}{awc;436A{k09m$d5i;WPoVk(cJx}Ci zLT>BU=d~iU!w~CaV5f2+kDRS1-If^o72Ou!HT$<|n(OqlotX0#I#C}(q4(T{pmrfH zt(cEAcf`O1Kv)&Z|$sN^+ogJ zP_bcOlB2Ylwq+seUfsa*Nau*zzzr>HG-~Oo=)s4j*{1>ccH*<)hTeEr>ux_m=DswOWAGm`0E+F_5ln9XT+d4*vdFQn_ z@;na{xt-%%FYq~xeHy9Nlw$C)nKOcbIWkJK4;j4_Gorw$H%{EJspFv2dX!v9Cqb+y zL`maVA^~ZFG&<Kt>1|DwO-?5LXG626V&t)BP*G{RV9~*_C&N|<2YiUfGeU3_1K}1EPKAl-u`93En4$n1UWxHQr3OOqI@m4O@%LBAcb?Ij- z-msPjMOBJ;7AGe)gZW*F0krZohY?C-O2U&Z&VUye2lkP%wE(uwfEt(HYvP;;Jg!4u zh@`kU!L%%ib1ZLe1EV_z?eIZ#)s=9DPbdoPB7${}&6XioXz~nHOGF*<5wW_1c|cu_ zIzKR9%o$I_lfXm!E-@?W0N2mT9yZjT#5v~h@7?Auc)w@3j^W7)r?`S^J);C*aR#*G znVI{>7?{DBiNz5}_ko!;4eI6wB^Zp0IYYK7%ZLuN0h3+eV@t`iomkcI43^LUOvWZe zrXBzTk=Wc6623tLBAYOPp;xRArBdEk%`%4N31z}fUX=Q<3Ts@Xae92mBLjfVh`wqM zN0Y}Ginj+DW>ABj|Jn`L0w2-+^(N7QcZshZQWFeXk(EJ98m66>Bg;+bhtnPe&B)$CnX zPEl#Jruc;o9Vh0F^o1$j&|TfSUA~e@2s^?~{Lv>6hG)LA?bqpX{DJ+qZw*(07zfe% z5&YrnZ(qZ%(YxP#f$6Wvulanj@NdnoIDOIdt`DzheenjLemw>;fwxbXDqo8EA?g}Mil&ZlbTl&Bv|6mCE=d<+YrsQ1}L9tpJAbOg+Y z-^nv%RL{-2EADs+A3^N3LTz&&uWmLGp`p_)>P3(HYueSaea`>ox9-4V?x*%8yd1;+ zla~4)y2}P%o@b8qe>tE1|GLXD<8nO$D8Z8g`F?(oA2vGmFw9|Ekzujsh7u$(P5SH! z)vy*Trd)}xj@uwl3InUvv7liv=Y|u!jfbtx%$N9;w%_RNP7Eje35DlxAz*nY@#*@1 zZ5f(8Nfa$zM#*x0D_g;3>QaIyUeRhh{M!OtF#;LnhztA|EQ zRhd-6#`}qgD&C?XH~^tp)Vu&EncAG7Q?t z;LF}9EuLi2zfBo2^;S;}K{GsJbBZ(RTKi`)=9)rUPVW>Ibt{ta?=x#8(u86~cY3Ap zq6nvqJ&{SwmItiZP~i^_t&uK-#PZ^@ycIpsuz3s&DvFMl-l}M>XSQbOw7phyuUDNL zZxx^!qq#CX{lOC`O*K!uGQ4h5K(^8F1o>Z_Sjdo-n*XbNT>3>Z{=L@yALzw@t&gFj zlY@bg)Bn9r!Ad%|NMDS&m%T~f`c&O=en;HEQU|OQK1EEZzM5@eDygsIJHrm!sZDLG z`A%;12O4sDY|7IX{MGWGZCi#+9STqu#`tE}i)Pm^ahsdp$M+R3E64#!S`sC$DYj1v ziGBBSRDCH*`zVCRNFuC^AfvM z-Z=q3Gj{R7K^PC(yg*#fwT0#<%-#S!F#|Smfzg?Qq~^hDce(IVoXg;n4PH@_{16N^ z*2ulg;D+Z|h_pMgpe;elIX!rIwI~~J6r^~B5ga%jQtIKKFoN#ki4aRR{<|}N?>N>s z+&agIg(ox6cg%Nc7T!f+spyB81^!(T_*7z3P&zPoDj<`SH9@S>p=~<3UA$VZ0tjuG zImo7+7xX+nxJELeDk0BwmiHMRlUzYLy_`J>GGXW~p#Bn(BuaZ3TEN^fJn|g8g)|3y zUQ`eXly@e2YTgFPJu;E#*jpgitwn%G`UBd;hiE&`1BdsCj?yLKa7gs;&wrVkZh45H z(|tj*^B*rY{D;Qj-?03z7R>*SN+yy2)i|`2|GQT6u2K*H>TeA29?^^l0yR?7V*KhG zLT?tHTXUN(k=80-+onQd@jWf4Jh8uF{#~d2)imT~cD&dea*d`EW_lQK9UMg$fB{0Uemd=;>!MY>F9RAj8$}FAHohWM4@xU~}= z_?lv`Fi_WJMW^RWyD6c5q4k&=>&ZJ0o%FL5Sh@3}En%d#4P$iQ6?CN8BVC)RWFAJs zc}SztG7l~!^l~9$Ok3T zb4@qa4W@*W$*2$`SigEL5VfRQLyy}m=-Sz|EMoz&G#-WfiAwQ4X^o)4rzcxB@Em$; z;(wMpcO(pdG06s!#Jh3e^rI|lhO32jE@}=*!in;RCdRn*#BvidqK5OTtIRJ@qFtCw zp`)=~cUSF~qisN|LzLDt+Ug?acLQTX3M*MZvx^Dy?`ze`&wZ>7H4#QUX3+g0dC>VF zBry0fK7-Q0u5LJCYZdxPk9Nl?bz|K^Gcwz}N+EV^zd|rfxPKtwGrIKPM$4(j^dZaS z4jh5+#&8FxTLpKHEM8jFXpPUKNVr0fuRiaTfNG+lD zQSo2~1!y4noW&u)=YaDH&KZUTtqX!q({5WpO-dhqCn9OISR&p|B{-?l>G>e&S;7|e#cv?5u9R}7vFwKG!}=V8_#G1wxgm3cOXv?0 zo4b)CaS}VtVwk;_9eEOpa+`h=uLvv@GqIIH{2$jf{E3@32?^$?O0Sg+J40T_mUxYy z+fQz5GOEyt!sAWFu_Q>b+00tZlqPo7N{Y1pQT8}jChG$A$=fEowFN^wy42%drh{6||3u{VzW2DEVXf2bm{;lL*E+xYJoOR~R;0h>-Gt-)OJS zlv?a(H+RE8ne>;c#s-M#$`-272}dh+2An$xuC*j_gtr(g7vxK@+!yYo9%Q(SU+({| z0S1SGI-~#{_=alh)e*Y&4m;TCSH#v`$wS{EF4Ff+M?QgVej#M0?EB2bZiErHd<{C8 z&AKeBqM#YulF6H~Rv;Bokq0y@trQzhd!QZItL7UK_F_A8r4OdrW4!I73Y+OTp}FZ9 z1~JW=HOVl}VtLnx{hJF509N}OYeBT@{9xu<9J!4~)Vf-;yzFQPg38&v-i>J4OuN2D z`<<#jBz*_j9WaK6Tyh1rQ$Cy)%kYod4G~6O*Pl0yyf$_eA8Q!dr-FB}d`zOh6SMI$ zgs8pl5(0G}@1KAxr#J-XsCY!Y$n>;(?02m4VyBNTIij66J->S6T}EP1Fc{g^N>0r6 zV0>7C$ypK3B9po99a28%GnsL@BI7#}7Wl7$YU;?JVuzw4m>q&Tg_lHJ>f2avRvkQ@ zz%Fo+hf{e8lAi+eBP%0P1gNxz-iY#jsA+XWk_2mIED&`1!fk+awU&yUYU&kjN1$kG zC$YZh^%2sbfeE8qfnP$Jxwo|8N`1ZR3hI4E_Ov+g@zy%9?<{r9UXh@(Tq$$BNn9bU zqElZTH`ChQIaQ*(4h+G))D8YppJy5zWv6P$MBt z6$!!ona|nvY@OP(zb+eLdcos&iA+89LR@7>xT>e6g^RTgPpok>A8t5KPORH*c6xzT z0h~d=Ktw@EK}2t0E$88Aola#KFWQZhNQB!n_>@d^a}#^YrW&jYdbZ&e^bX>@ zm_8$k?B#u4#NeN36Zt$IP6_W*m!VrjE9eaeK7+`h-*YcAM9(c3iOHlsGhgvb4y@&4 z8ww!!)-b0hDnuG; zadwrYc@7|-`mJ*3iCI3N&O1c)m$WsN@#w-#=rF5@S*cu1njp@{CS3NBWjxRJX|?$` zP&4@>P)hmoLta^=08*@Y#Uo=5S!*Z%iW-{NaXQzvK z^R93l-6S`@-w2=4*nEk)LP$@~Wg>HGe~Y@U#!WtdafX0@R|*+CUVxpci# z#Xr?#1v6-Nvpb&I*X(#Y!oL>0=8msRAV~^$y8i9`z-ji!`&rKP^XAcY6J#lrUR9=q zqry zO)yeT3W*9Y;ie#r$@X*3+5F0&7Mve1sY*u}3~wGmq%}yK#e6AGa1akl2TSNi1Jy<9 zXig!r9La-)rguRKv?>=V(X9xHHB|DbLWH(Ka*5QSF$(mB6erG3V~|3@SH+E}B z5*IUtODlb#@sdZ!?BxckL6P7E=$yr8?HCk#E`ccX`4R?*My`S@~g8~5V@0A z1Q6~Yi6@lk(I|Vlz^{CradDi(M}Wgv8(lI%5;VPywG`(fvm{G57Uu# zjNKJ$M@z|AtjIePG5~C=M7yi`nnaUIWs0(yHZ$h2!*{Kwq_xRY2p$|21@tId9-LYx zVaa0vKhCdV9iS-2<8t~ot%=hf9a3+KsY&i?@-=2F5!h9k2u=W};S%f!+OPzdMYEj9 z62Oj#*L374t8P=`J9dKs^8#2HCbC7Yj;^{yo#~exv+> zt4`C=hEVXBi{gBqtD_ljJa55n64$CuUGY;-Tolrbk!ep@pOwA#o|KBQ)vDoh7?iqO zY=bTReyaEAz=t@fzqRRzQ)9gL?}e&tf;o$P9QC|4px7}xyrF4D|BXZ`OcygHj;L)4 zg%;F0+5)f&X$~(A|#0%@aUh*hpZ3 zrV8OrI^fje`&k7?r8ppaa**%E36k*;UfiZ%FoXvE{KswOhAiqh4J|n!V}D5iPk}E1 zd#8?{EQ8NTYQvbTm2Bn$3JlfsgFLfS@it?f5{H@5EVspP1cv>9k2ONOrMe)Y#r}eI zA@Pmx`Ui@SxQ)WTF6s~6H(4bG=iR`aM{*0f6dVvqrXxR5gPycIP`!~~twg+k3QXXn zN#a1fL^ANta;OClJr3q1f26h(Ym6r4MwH89s_i;PR5LTSEjxUeQ41`~<9dSbFqmO4 z{ieXNOf#!)d1k6>;``;iX}Hg>Ld79gmLo|p5~;NuRHyuklv%*(?uA?LpxO$n*VgQe z)+j&u2gVKHO1RI-(6>Cwk;Yx9z4i0^y>Fd%&pY%gKtcMMRAl4|`EA5Ww*%S)+?l!P zali0mBOp=Lk=nmwf#zZ;hw~(NiXd1(wY`$h4$)PNx+F()HQLlnmdx?rD2; zr=qlIf(R%7G5d+;;v%2jtA!V51%-_zopP;kXm!V%StGW8#Z3?GQAF7K#~OCIO*#Dh ztyeBiJD^#(lrE|Q)kVe*GO*PL6R?r!Z%;TXFUa#gwmpR zF%uIxkq`V+r^x;>3riK3G?+WZVj6L|^wJdl{w1J;u$eB!h1pG>z{FrtKGC)=hD099 z5gs`3G%Xu~xC4vH7=JU$NTrJXqtRAG!%yy>q@^3W#t)#sv^47ajV{|S_K^$oPg>f4 z=r8{t0W2i{E6YgI#?4P|SREjK!Chc2cjX97Tc1PIG?l+2yVJc3 z0E9aoT~?H@ch7dI{o`6K<4$$O=+v3!JaUA8^X)IVuqXfrh;w)v6z#YW#EX1o@Ok5w zTxSw5!$7i{IV)TaIr1hHNAoy4f>_rFmsd$mQ*k5D2)LXeE$B{`7m9qzMPZd#7(ny%f0GI#I~CMlA@JyN!2dUl7I}@w2Xd(AM39=E^{` zLemwWF78^pTUp--J1MM_FL-ca0>AcSrgeBQVHxLW{+SkLnksBUm(pzNPCSYVDd+3& z5%{TV=bGw1{_0=S$SX9wikW>@FIL5K$z6tMRmmu{k4@;WHK)2X2Pbuu6Am(G@s%%B z9VCqB9OQ1rIPgF{)>9{5I)aYAk zG3_VVUm&w;(zty25^OjAQ5mEAXX@~Ofb4Hn{r&;vg))!%*?Gn|Z0vx5w5E!HAe1C4 z1d2LN<^V3i040GS!*LcP6X!o}v$PJH*8nDZUBpgxT~;pCPNm`))`(WFX$en@SFTxJ zAEFsuLQ(VHk!nyYorJXYIO@Ccdf;ul@%S0_xN+0tFOCPnAetxTCe{Okq?>RR7qlti z_M^v^w2f%n70HKw8yV^|_Nq8&lEjN{8wTn#@hU&4lEmvg;{z_jcLMVO*}^W%-vF#v z3X@WUrWfF7d_reXWTw$SH8eF=mDW9ppbyC`g29Esg*jo?ZG42_p-qM>uIy33opl8yhx9&{)OBj=SvX z+jE_n8<@+AQ?W5<57@bL0Ss_^qh}a#MlmLgo`8BukB9bc=vV-e&>nUmz1Fae%vNS! z36`~QJ3sEIpHT5ssvzL0-Qc1r-SApb-_kZefYd3Thx4HkpZrlA0tx zPYCQ(PY^9AZ}D26hEMFh;;{I;Twt$uwE?zY!J6+);@v=JN(lXIqJ9fBpciT)(5}{Z z_6CD;q8xVdL>W!Wh)6zE`nNJ=3{_J48D@sg@oG82cLNJm1?-mD5|Yvq_sMmyfw6YO zLOo3WZ@rNxp+_Ha!GgR9#pPM{9oZ4o^kur`E+wQstW!!#tJ4iqFp09n``Su)cRLE# z0jj0-V!AV-frdsWC820a#DaK#;;(Wv;ct(i0)zJL;}=AQJhJ*VK&xx|y1@N;@R9CDAx8yHBhpOWR$> z5tqy>&b#Y8OnPitu=7uwkTI4n?=UmPB82+Hb|6H5@Nw*|caYhSo2PMkw^$6JYZ!?P zf(ks2(R)9y*D?1l{4tpXsJ!`OS|HXLL?Z6J7Jcy|#q`ozMNDVJdi(FR-AoQ{ zJh|1@vPFHxD|0Nfmxp30)}+T&FP12FEHA9ABn;0I=`&-h+Y%DiI2x@2!-^Naz`4-^ zu!)`7O5$1*j5RV9_)-=K6kKW0LS_}c^4>*TXWv$ih znv*J1-n?-#B1&A%;XzI0VDeF{fbNErzJ(mbXr%42`wRxtU+2R$njq40#9^F-<9L?z zkjJzh0{7`P(CxA?L1EmMoS4^4mOk-nj{N=E%d9;zwX7h) zn&+7g!ksmAeyaA?uXtenE)Fp({TP7j#9|E8Tj+(E7w9^}DGWK)oOdY?7-EDrTIZ^7 z|GgZ0$FQ8ujtR|ESsYWMMJ`K)8gifzFjPhbMZ|mz9}X)&0UJDb8ZM zTb|J4)P?JHmapvK6$xE7oi=thE<>ZUmk<;uVsXB>>J+yM0*O`Gg2=XkVISkwJI9IKCg~-Vs!;dK$ z#kFF~Q#6QVaABVuZf{(Ebcp1bDZZqNEJ~;K`su`&i=T5N+tOH|nRzbIc!hlHi-zyw z$GQ|x1>)zraT&5{Y#s-mo{TfC*qrz6DYKEtMX9pm;Wjvzv}b@-t+~J)9TtTx#Gc(_ zF&J&}#>vxTwU)#ec0-m11D=*L_;r8TyVO5ZZXaWyr_42tRYmZ%9`-w3+BF7UlSgP? z==Dbn7AK+c$4u$MwjS-g9L4xBpd~P`_DNatR)u1$=?RLxFr$@~>&WkZ09lHY!8Vk+ z*E7$Y${+8|ltuQdzrsBk`ZuDVT@tv)FN|wj+gRrJttb;E9i)nP;&h~{SY~k)XF@QO z$wnOA|=SaI^vQ+s?$B4Vpi*55o^uAMc$;oun zWklJG5&ap@SG+xTXL~-zxl!Qdog~I*i}&~831-L~=ywAgc_-EV=@s6a#%uB8m#r-z zHsLph>V25rbLn8ziipl3*Kymv;)8vhz*v?Oeu5@kFD=h@jVEe#6g17Z){LKv~QZegy`L&KbN!>$OzoFXQWSmuUjbJ z?(fwWM${HO>~v3G`04|u^LRMDayXl_RHU7UBajqHx7(X@Wq)*)^Oa>)PU8{g z!z!aT3!?Bm^kV(HR=X=vKkztzE_yBv+H9@2>WHuVLH zlvoFGBMqGW&U9BnnmP;Nx0wv{q;e^I1-*oZhM^8H$WUQ|VA6=G>;i^*Z6ib6vHs8c z>}G;hMt&FHG#gAqao8xtjmCx!YltR+ZCM)g6CR2v@aMicnTAN-s8?aB=qRlCGqqC> zFRm4>g~PU+h10Ybp^$}3?4usW>dkvdH~YVH)PomWHN^wyu(GHriSd`*D7uG<-E4T1 zu^Eu!Fai}BurT#uZU2v+MD$kC6fch$2s>5UA6uHS99a1~DS`Xd)74 zHwvJd&(iWMuJ)}^a?X-0?cmkoZSH#9hr$NYk@}sk+vKlU3#Rc^jIyDB2M%n-HF+ze zE78R>v_oSMtFFl$_arfqq)|AjM^AU%vtKFVbUhN^m?#>yG>%I)*py7K-QaFjbmF?r zpiKq&GI22svu#cgdhIbL6M8hj*~FPW;B80z-LP)&l71J#AlM;hsD>R#@zXHhvuiBuzU?-4=8TRb`jk7M0l+HZj?}R#-Dwx)v2Z z6x%j+C8%5o-3pOyPuiC160I52!A&oG4s9IKjER4iytl^zPBxgNQM@+O+ao%2Rz4zL zm6R*vhm9PR?LPPZF~L(!O|rD7@hYA{CZoLAQ2_4*ufsivGMoiTC5Xd5L*rCK*S>M3 z7bD6>j?7YlF2!?=%eGC5Kp4U%iUH3EYNsOhO9h2@=p?gIbK{eT`53b`VJ02&RN2t8 zJU1W7p;&w7=dkZY)1CLv0l2~LoNitNVy&8x0y6rzD6O}{($Bw1@@ODPk>S^4plqyv zBFXIk%wG(wEv)VA=>-1zNa@+w7}*g^SsNPti^(Wh%FN56cwH_vYEjTh3-URH^|TS9 zp@rf%AtV_MkYF=mr%`*I4jCmSI03l4lA{D8g!@gr6K*!5j#0X5*7rG%?s*?Mjy96B zySqNV#fWGNsSmb=eI4WVlLDnfNf8@qAtE5zuJUn(MY;rhiC|=fYjXA&k{k z?~$$vl2C6DD4}YV4pteoJGG1xpjYEGYFZ|3Es0Bkl}esr-j|(y)s{?f7&HZbZBa*YLx+_p7`M&SBlLGyU<~9YNle?32B(a-ew~(WCr~_y0Bbo-OCO8F zv7*3C4J33e`j`P$wBGB0Jk&aUQvpfOATP)hA|aS*hyzor$R`b#r(pc>4>JmmN6`A@ znCd%&-Bd&lkO!r)H|*5_iTS~4;CEi(;Ht=kldQ+t`~5V&G<7i_svGZ6%Yfz2Bf^7WNN zi7X!2{vy&@A}e7;Uo&{;f1JVpo0n<-dm#Q-3?@qVnti=Y%P5|eQqXYwb4iFd<_AvK ziUJ(yr`}7ay2m8EWU-=k(fwxz{yM(^o5$s$H(f8twSz;)>+_rBHRUyN3`7S)(TPiw z-e?o0Q&c&P2AxECgGIxQG@3B>nc?p_O%~Yo*$oSJqKLUw?aYLQGTMV(7uEX7AvTG3 zmsUlk3jvF3rLU7vl^F&iA#3LRb&Mh!*CvJjF5bsK^=@5s_?r!75P+;-F0?<~JCFJv zAqfMWI1zU+c?hn*eK|1T(?fq4nWtCHqT zuG&e?UR9uBhN%;DRpf>eA~_~jT71$X!%G-8oHib+t^?wFp=tK*bCIlbT#jM;*=My8 zf@|lrshDtiaiAJELY;;DbN5?#g1DySRxs^{0arK48_=%I*LX#*p1D|`{w=|TL4e^$ z?7_1+{S}?ZD?B(0JRiJ2kAgAGL-9Z7hzzPFi1EgjJMfJ+ODe`iNu|K@h0qIRPM;g)6d@txXIMugI))M$W6VLZasAO32t*xG5lvUt0vLF>rXPIYy6GV^(bQO=Z^RW|| zFaOL{_Xa;BBHfCc4uO}PS2SV(Q>G7051>U>rau}rp0IldA>De*Q?#>*B!@E=$(3j& z=PcLxr14}Cxr#k5(%VLgLgvjL=i&RBTOu+C?PquEU}t6w@LQpK0sj?WUn*{;$FJDJ z{Ks_sH^bBanT}Qt04qmpNBjRh!v4Ae&xi5>wnnR!^g1XnRH1kg*k)HO8?(j_j7GA7 z6iFwcHg;Mk@!)rpESlF9_oVFkYuBIQW>QCQ_Y+~-qI~D!8!^|>gok_Amr{2$Bip;n z3xwXM!iNy3A6WQ%1QZ5x3?ltWwiRr%_gm~ct{@F(%Lz*F3~gVq`G$inGTP3tBO*{h zODiG&FVQ~Sd(oC~UPwkZ{}vj;NGr&_77{&RHWEofN%N!=WPH3GFc9+Jpd+9v3&C5#WyBX~h*~m_a#9nCn5QfYG_C*+{ zcJ>mji~LTZy~+6j^vwH`{Z1(TY6=d?OLG}|CCbt&78;G1E8P8i&|gatE3PDYhbSX% zd*yeOO`~HoM{`QkAa%rsycum`-Ckq_)ikw?(JK1y$&GQj>{UWJEf#Ica+!-Ry8U(e zC_1xFO8POZOIwO7{VH)oF>MJDLB8YR#u%Ltqc+U_ELyJvww*_eS|alYpo6RGg^;Mt zUj0-Ojkk>?i+Ttn%F@=nT3yJpg(xsyTI)+8%NFylVO>S)O~zQ|_V>bpT3t8uQaS-y zy!nT{2txwIBg3Xj{+y>^5#3&Oj}RxM(|d2BbTPcH0Vu0J;KCjek09{4BG!pWxzY*( zyeXo1ITzm|4-^{sIMcDjS>Dhq{q`kLHs?h4F1Q-5UBiZcgFnR|3;?BNMZWUpd*Q>5 zb}bO5brZ>6{t(;<&L~5Y0Q@`(e0vCQm}z;$(-(z!4hIktUvCWxG$g65#;4xC6bU-P z5Sm%&nE`l4W&%lPWin}`#6}hDsR+W2xcltYOH)YTN(f*2M2-stAtByg&3uW(^>Eom z`A~oD*B^41Mk+53iB(2>Nc<2(dND09#mU)mh;u>P+jkv5eD3(U83_J+Gu}bq^7ZrY z49k|vK!5ydc;Eg}2hZ>yAuka-Jy&}JJ&S)qu0%yOc@#bb&p~QfDJFvOx{$HFdPo|g zaCV>L27_M{IY534w|Xc7AT&~Jv(RA8*XsfpPapwUI6crVKr-7vGZk5gY%m2xoaLuN zU1P~=iGNO>-VuFZZjpqEBg8S{ZAAK70@{&^h&RGL5~I_*afEn9iX|X;F$oPiTtcEP2+H>|S5dV@C-{LMtK<+? zZ4~m=zRCE7rVnIU|>~wt~id)QHfvuLj0Cj4*=;5(buI-Hyk~Rbt~FP&uKRbh$5i z+157RV~mLf9aN~|gpkqFv)zTyX^J%R=qa(IIxC(71)eD#;sF!y9yq6dK?lE!}|?&Qia;}0r-83kJ_ zv46Tm+a6X^BfCH|pPgg1JP$xb(5oW|@3ftsg;0RZP8NWZqXc^jVUjmF@|(CIU0B$F z*wJUm8E6M>)%4p#Oy)10#XmHH)4+7{H=YAfr4Hu^=-4M)A_Ap0A%|=sHJ!=}#gDU1 z9C%S)3F5gA*B%r&>2yN+cV9n)!Y4?a%gx2OQP(c+|4ABqy8o@x-B+6MhY%27Zhk>0 zs{e5wcN;?hd#3<$i`4ti2#$ztOkn^hvyUfHFqWI5nZM+5Vu{%mNrUiyqBwreiAk27 zkMvAAvsiuaH$7$pjI_%fdVcXkuD|gPITY>mSGK(WV?Pr3kFrJKuS_u%u>QYxr9?$3 z8DzOH$>`6aBwuBepRxm2Ub>ZeK4H3zsJ$o*eu9zd09P8KJ(wv;wG!K0>`&j&pFOCd zX%JZG!h3xKItAE!uJfV#`EuzKuFjY3U++1Ox|XN6es_I!CP-8P${?i-SzCD_zQI+9 zwC*m^r(O}0`}yQpjJ_38J$D>Ji_rNsO1A21fu(LkDfCh*V+d%R@$*|a6JmgJ;MJSTNk97%1K9Z5Ll>yHt%PL_za z?N@J}IP%RWYUG_p8d{NuWU*5BV;gwHj-ooCSdRa37*C&{1lvMQDwk4EvI#4?Z0jow zFAJ^H3zdjmN8On?MIrvWdNOQs9;AS}7j*A9;o{~PI|$AYHdUNQ@Tg-+h4J(`U7-7< zBbsEQ3fsQ(@q_Kf`A|}cZSW2MY1GvlqTXq>>GTLDdW)L!lG!0XNF80fz6+!BM12x9 z%MZ5UJ%JhB!8w;B-0)1*+mKg%@DH?56& zm|F|_Y6l4Z#w=jQ|HrMYO^CH+$juJq;{~60q zT)$B!-Wk9qOumWcVG*6Xe|k27N1(c*Q3k5B_v`pbDZc@e;@<3J-(J`LrF%4fRRgmZ zI<`%;{v(AuJG+4$iU{=jvkYxG<`djsc?s%(*iQDf`&{{2wEy3E2;F~_m!d{`4qxMg ze^EBYaXV}w6rRfA2yQH~B$9q&TY^y7S%3Ngc1YyaT4YEPy8`Y4Rf6^OQ07{2DPh`4 zauh06*+f(&3%$`GQ0%*q3*b0--Tp8VQ2ZYFns4^*#MC4Olm+DuFTdwEovWrUx_-XD zzY~3{SB2mI`CYJsCXZNOZ9oap2oV*L>c?p>II{Qq%jOFid_bYCi-4;92McGn`w)g- zN-Tu-j*YmV&mN9;GPy-kzc~^=d#_$vzZe_^8~_e8l)qz)FOeZy4bFrkBiKr1Vcy9eCLX+^a2?w$cfQ>ca{#)OKetB!qEx?jWIBA~y28HHZd^99YIVZ_<}Pa1 zaWS&Ws#HUH*m1#l_|yTHWx6=5tI^28gfcTJc8@Gs;q!gzQ!guRci*(eytBPI(u%fo z3?a>0y~wf+o&5RP7jZ-Z3MSTL*hzEK>8x#$NQZW{X?9YhZ4UzuM8h~FQEL5Iq`h!H z_}F5Qi)xXx(`uePEhBtEvvakmn{8!JgQ#@ZT)?xlTSkmAQ!hfXhWA*6Un!S37ePFBljvmDeC5?CZT@?NoX5nA3Pzn?kNraMe<3c1ML@yhO_qAwFP(G~G!Nn@>pm z$J#?uKyTcF4iakUgc(PfP@Xz<*`K+uHT z)Ih>hOzN(rrWi~rQHGeuxq;55^{0=lK&W6m#+Lu>$@luil@erpMsEXwF-VnrO6L!xs#=plmRm(z&tY<2yy6(<=YE>>PGp?ITGi zbUK(bT2~8y+F8m!4;#HKv!i?YC~l&h&#kIEHZJJFW|6(^Xg6ZMT<0Z!`$P3)3phcz&8m9#{#(7_D_QWRaQyb|;vYdV=YLdA#HnZ_@*b&YFzWdN2J*YyM=O_G!IyC zd}GiND8GeN7e?iKM83)|U?3ocYbJKTT;_fo`UHxRyb7vkSOMiFqfM0Xwt_IDMnf$9 zu7V^70ZBDls>Ja+ypbfR+ZI?IV^jDdfz;x;Bx3PtDO+uM=J?-^ID$%IRAGS0gz!3P zxA>D} zNwxB2Ek*1<%`eg;m3r&y1qfpJZ>xw^{C|1EaDCqq;;B`Be z+`!N;{?SWs<2L7@_z7Ov==a7?`&O@_BcM8{sK`K-iY>vMTkeQr6z@yc-mO+|ca7M9 z+s*;DHG37-TS}P@wRnx$kX}GL-j#BCQyq#UgNGV-wVoAdHoSaj1oD-2O2zh{wkDo0R5vc(sE@jYj zVwO4>lY2;@&u1a#Y=bBv9%b&&k?lA4fdL?4iEXltF2F8Yi9Ix;LX?LFJ3oyGV8C=? zo5zjVixTmNHARCzRwvJ5AeYlP;{AHp=il?y%4;FE+b;lp^^c93<^OeN+5dOD)=-$2 zMfi}`zzT^?_XF0>QIrbD0_{LUB+pw!ll?AqzcYhpMqeZu=jMKg{#4}+Y?2T@#oooS z2Y+4tRCFmuC0d%#?a=;u;W=&G{qb}S`HK#ZT$G}vYCFiU!7sv31F8sRLz%u(SGYGb zO=Zj9I&Z5Br$PV%T*uQ(#g&`e4*1f|>@4J0k0%7vv|iNG*}_8RD5Vh(CC!MJ>^ zslApUIT*7RKQCAV_WT`6Hx|u)4%j_}dD^34fc{mDrI$df2` zKM0{iP7?%O*yXg@lL2g(QE5Tir)FYUE#*#k zShJf)N^IRXMn0*9$oGya(i!hqAH(2oP8D;H4F^*w_Aaw-T^eWX*?^_W!TTz-&_GLk*MTGW~EK# zmsix-T)(<#S^6q5cUlY?GO>(gHFpxhu5U3W*bYK14D^At9Dw{C zgg{J(wP1X9^5_7jNsp2HdOBT_PIM>dnWX!`glwY{FN3?~rXk*f7w44fzw>!N;QsKO zt>E|Ij^gPEoN=y+x=9SdB!@K3b%ILE^~{^*+-*kj9v_okuuCWOuNxxgd@|icv7E!s z$p~wRfU_hL0YIhdPgt0{g<&-w?5lLAIoCj*BChLnY9$vX#eQjmJ0j)c_aj4Te92?AudX=$k6n@VKg!*|1PXd~UjrjUfRUBM zzmiu;%pO?;_m*}dcAa|-|6VQ%+~9!Nsp@r4l&8rx@(1B32q&xP3p{B}TsqFFTi z073OwR(owhkTB*g{^3}>gP^e4dV&Iwn6O}WSVgndxf8mK6O0=I+WyfMK~PhsEzyLq zI@=jR!Q8J9ps+gnqI|!uro<+wR`Q+EjR!qr%bto7DO0kt zq}{MyEBg7%&4}VBl#>bW`d#2fG-Nry0gd%~PA;p}pKJXc|HfEASG(q%eK8mMvdScoowN=DeDct)_3 zCY?R^kGE9p1;R+DM8n0!?=T6lYpq!}Gilkm-^&(o;}j52#Xhwcw>!SDeqn6eGK{#L z|A|qcQiWKU_SncYA^W?uiH-_UON|*$b0U_9d?I|95oPs zrN=QH+1hM%8e2n1_b+bK4+Y0O=M6cz7l=BLMOZ*hntUzIIr3VuOOM;UfDhk9w_$Fo zquSfW1!&w^H!(dt>7i^py~bV`Y+3878EUfD-#eWTwBzh!b~H!c;pgt-DxB791l0WfDu68f4>JfHOp+SwMD&gfn)w zOuTM@^b9%rjAHNt?`HE^`1tU1V-Q-Bk`E#c)D@w|MhE^I{^U`K%eDv<6qgwt^%YMM$ZH#zAmu zWEb#rAQwac$01>j}5 zAM~?ak5Zj~KW3UZZEbygoN)M1m6-2seOrr6_wnTbxdTIkNr0ioY_ZNU+xGP}0)Zz= ze*MIG+I#KJau(=!g+wRTOt2B_<09?DU>+4u4cX2JaF#k2O-FHC5oALml{AzTWWWdv zB!m=$Os4S&phB`kGrq13%%~kRseVHT8C=ER&1FsVrlP>p=1^mesc0`BsoXj0Z%QO z&XnY;$(&$z2A-w~AGX|CDzxbYT}QRQ_>*>hWjiO&NZD;icME&l>K22^#b3~m6+K^j zS-0unI`cqLqV}-nrL}LFnp=!>{c?m-8qYwCA8Culg5?-wx@iyMmbg^$6qf>)XtSTl zibH2=bjoNDE)EDO&da@3IEUR~ig^31l}~RzZ{M(VIXg8CC%kEUVbFZCUj6~Ej6Ry< zBS~4a>*8^h+9!obKLDXL1@&lIwJQ{wMk_;}v=ixHc1gA%B0&iE2@T^}-7$r?+{$O3 zxSy-SeqC}O%JI-9MaZJUT}aU}n{=b$z;&q@uvN$7Y-=no7hKMoHDW$ly^X^XPTxp~ zTYQaa<+lS?$$!kJ=>$}_SBF^Q+Qg(lM$oM>W*r8`0$RtiTjGxpHGisM#uIV)T8fJ! z@g5Zs? zas274&m@VERk#GEng0ek5YvZQFxnP{xL+fP%3!9n%&GJ)tt4dn@p4ZqjV}N52k#pU z2%(3_vkvuC&^1*XtHL_FHce1HfJOqlbDh04Qo+2@gELO*EH3Oqj)TV1a9%6!Y<)*v)Bp%CT>N5*dfZz$~V9(fP=Zl zhb5s#`oX}gOJ_FFYQ9vv#{2l!h>x+XLb99e&&v%5ALCN*0HjCjE))rseF6Tc+Nd+v zG7{oP`F`*K7F4Q|CRF{~vctFTzlNH}fN7MaFTB+04sfK=l`{EBr2@S zBl98f2#6{tOZ@^$Bp*|<15(}vWj2!|O+=!U8~;^yZHWY?is`JtRWHl?g8hR01e^fx z<%3`NU?tltK?uLjV_(!hotkw)r}NVjO!n7oPlGQeNIjSZNHfd^iw#}Zt)89Xy55!K zzzlxcIBAh`~S~&K%koR0`z6XrzzUgMPH_?*oBh z8em)%H^hc{Pqk}$NxQO1zcPCTb=K4}#CQu8zqDF2qB9jo+({HaQ1uv%&ysoaC~Bj% z*x{4Y+monE^$4}!?>k0`PhHP-^ag=%ANLOliESA zuf{-v$6cO{#%z-q7>}WLt(x0dgrx;p(~zj5dW+i^haBul!gMQ-qT(b`W>+fSP){&l z>g=%&4MWx+Z9A;AY@3&xaBa)iHJg>*sde=IB>ZeD0Sk{+RV73R(2^7+Fcp7J9-qzADMRFey8Gp{u~cKWdBVOC-CKq0tgMq-P1 zqVbgQ%W22N{n_)rGLhyCq0=4FK$TVsly5$@hZ&4s;Jki-TZ9v8WL6C692-cBc}%## z_wY}MW5i6AtQ@Vk&putCalll35vaP9FhoA8fUzyaY6#~m?q6X{n<`9d_(l0m{&8o< z{2$SV|3mvzvi!@W(#xuD)sk&pUR(kjajYF64oLv)2_BY9Q7FqF4)k@mX5C@kfz5)| zlTSzyg5Xr}DToU;1~{0aI68OONC-dbUe-?$;3*L})EIxCU6_*Jp_A2 zKCmaJEB=BW#NMfpi$c#0y#o#`Q3MfiRG?g-6A&&i5^x+C?QVjvZ3>u00jy*XBYkLv zFV1hqm|+eO6`MYvU_ua3!e>!Tawq^+G3L#uLUnnALWNZ#o9UHD(a3 zM^rpaucoiGd(lytkBlfp!=p~l*_uKDd4@Vuwa^J z-nkPF(?)RD6^vxf!`H54R`3U5+@gfu>~zMBkl;x@ZJK6p*4JJynIev=T%414+D@-Z z@Kq=(b2izWwmtI2E=W69`B;rxFT6pCVyl6a!lN|8hh5A#F8IXtFyr9xNEE-&JDkv>HA-e! znY}l3GkeGOa&^hYcimv)ZclA`V(^Y*nQnkaPTKc$;#w^$c2F*g`w_$Gvw2;Ab*{Xp zrm{kyl;-1!9?}qX!Y-SSh?}xqQy?yaUf-?hL{(4;!Es}6BR4Z;nVzr`2%6Q%9gET z%siI1cZe-g8Y;&evImHCgP-}F?+`TbHKBt311lgF5sM|=B`3Nrvng5T%H!^hr#Zk70Le7@{pxINUJ-RSTEE^vc%ul(>5(G5%Q}o zc|D_2`e{ANx)Kds@My`JdQ$yGwT@Pyb`J|3imH0cN+>xE5SQNxbYvm&=EwFZ>f zVP=Mf&X18Zh6O?f?u9XeW$$Cwr54(@i~Bo;51qqBZaRM%yWU&}%l8-z4sVGg$|L}m z3MOiBw=K|zR;&zHwN=jvNL9g$R%}}^^3NH_r^#)9`RC1w;7uR9SI|;QBFm=){eisv zAR12Mohl4n6O~~YB3#p$e?N*Z5Wj`)ld;V;T$8KFl=p8>|I1 zvZi9>KyfMhrijTuP$&@lVs24KfZSF|C3f}C^|^coU=>TfeLucQbNGDc;|K0dM1BML z05YKssWn$Zh{*}g{4+7t;dF$hx?f$yeosw_jKCuNkra$pb$-UNm!wq#&I8u zhL%i$vY@V`ZjtZ)gIy67$&J-?*|3R}6Cwn2z~@ojG#fDnzn) zpzSR2Rng#cV?^Ft7E!89I3J|)g+a9g`~)1Xb{(_~R-zR~{C9MZNdU7K`B%h)MJEY* zK^=^P1`S{So(&DlqMgLih;Z~+KTsiS1DK5%afTHY*#z8WlgZ(0&IX;tzQIw)6hePU zP(mx{5VB;ni8^_uPg)F+atsJU<}100v4qWlgxy+;Jf}S%&XFSBbUgsc^OzRQV(IQ< zG7iWtn(~P7pANs~;sBW@fq~He3gX+-%CkLVM?wlO>?RVSIR*$vQpQ$1>uvxEFDFw0 zoqs!#tZM&oXswGK-^aJ+K7kK)j*O{}M}j>~g$9Q-G+@_EtD2OeTlFQ)76V*3xM%cwuKU6@oD9Ygh$Du zbv6?)C2@K1-Rnd1mAm(=$5x_u*Be+5SV!S*NLW5)9p#YX3Z)&Tw){<9m=)QSuP&KGa6z`nyBvl9V2 zqIhwwAv!`gp@3(T3j9PH3b`yvC5Oc$52efp95w`p80tcAET$&OUP5rA01Z^C^)bf1 zjdh`28Ak1$VyBi`5x<*U9uW=tL=9oN;*V(}VAG{vov`SNYsu)NX2&KXpTV%d4td~R z+lcacGOscY3oxo+Or; zY5lrus|wM7{eg019j?kIgnk?jft?3_L`T#xSx4i{g*}%lkq(9Oz<*U|Ie#*N_1uxF zQsc%DNU7RbQor@~DbrQ7UMJ<b5(C9U*G9&XCW2!wWHVxb2pb|S@cds&0c}sJ+ zOz6!H8sIv4&ag4-N$lb?*=*73SJv?84}-A^oQ^z_GSLyY0$8g$dAgULAB%|75prV% zmvZ_jc{X#8Xi(B!ftq`*Y~UK(`Qh551BP0n8D!VWu%%prxA&A0X+#B~@hnZ0PH70c z{F82S>=CnxryfztTjA%`ian>*+iSJKvwuMjw|S%*H6^_jy+y0RVd1?`aN_eS*g}kS z8j&#JnO&Ub{MXz_X;OzuEHeh}5|58*3oOuD0YT!xj7*8NnahSU1%1T)~`@d3aa3kXJ;0@H1g|rv1Sy zA<;9T(R%XrSia>Yuh<@xAilyyL(S1u#J$9>a|tDaRJY~A> z#h!(=FeR@cS-@%|2k!P_&O(LpSNaYSgwyCdn%6MwE7UIiNHY!|xcY2{dB$~r<(dBk zl6wpJ(=w6u8G!dT@!fj|MmshBlH&Hg)Raofj(y0Z{FqZ&VF0)Oqdx(pd+yWv{*$ZK z#Mpu@(c(;Beh;Ng-)mB$C}-<<2j1-odHfokiTxZmb@v^lALpVWS>;9Nud>SU2#j+5 zRZ_425iI&1DsrADuiTF|>NniKt`Ky*-cFo+xlhzUcq={m_2~tIqjr_p2<{LDR`6%{ z^+UZwMU!(^U;FjZp?Vcw=k-;iN>jcG?=(YoD?D}f;fJw(_1AHUY8QH3)f?`PZUSJ_ zCD_=Yy5dnrKNKLY9EFgs*v=xeNvvUI48l`P@-!o8csu{u=k{PNR4c%z4 zz;fnH-++pxR_M@ja8k)^oB^tiIUHiXr|`w)BuRSft@cqr0t0l~_gF zX$TOR!0q4VfnWKr^}>512?J^b2q4``#7sWogBDIeSBFwRnTtp)jmsn;uoYbHN$4gN7@!Q^}b% zwC>=6YrS+6(PQgty$!3B{&K{^SXSJ30hQ)^9k&jsg4i1W!46K~NT$?B5MH6m`Y4OuUK z>hkf98GJfKW320Brt-qr3hriv}|* z`^NF9!`MOXX|93!t#H;uL2lfVRsHa8ubKcjva*|sgON&dX5AX2@z{yDiBoM91HXy= znsjT{JSLGLjdHMg5t7(=yb9XB7+$#5T98aPuDiP%z4gz&EFLF>MwqAHaTqz}GM$U&11ry91jD0KPx8EHp#TSVZ7?V!K zjNy`DXcXi^goKTaHYn*I)ukN{wAXh?s$a4rgBN533|$VQw}-25Nmqx3Vl9c_H^@yW zYc`};FAqEzvF0+-2qyv$Yy>x)m{!L3*XKN%P zo=zRrNF6uN#J5V4MZxIp42atY3z<#1kh*r(<}p|753RjnB#NbY<%|kg)pC4Ww=syt9=y>1}z8tHyxs+bC$r@cS+W~0f z#?E!B*i?i;v4RTQO$DDxjd-F$iR2~+RXv}|alwgt%3!kFU^Wu3WPkQGMVABqbxWy- z)KNLpycb?Oyff49X-%4OkGBQ0*P0fm4}lb~6plU<3<)*#^TH6ia=xzeIL+2OCzbt+ zqNS;6{j6V=J#TA7DO1y{{@P_v{okLk_qLv)_wdR4e?EtOGP--_ZBKpzPb&?LN7S4| zJOxo}ch<6os|*$w9-#gqZpGiK^o`v zO&}G)!!k5(V;JKJxq9&7Ck-2r@MDFYP}4Gr>z7T*s!{KS(ng{#j}q^4g}ZrChkzPt zsA-}^mlo5XkdqElF+_TMw*0VmZABc>Uz8?PfoQcWUU5^7^|CmG77CS{i;fI3SUsPNHzN7b5~^*?!77=2+??^<;_ZB3l z=fF6{(vMNTP8iH6b$x4m5(jiv$E|rRE?lPbX?WBF%BzE_29I2lafX1-1w#3M^;RP& zlPh^dJ@q8}$td3dsFleTQYvH_e6YR;0}cZ!v_WCESuyd1s(Nh8gUYujmXx zXaBk`ZH)L&YuA5ghxISYr(gjv_?Mz7FlJJ`|8JAEVg?3Qsdudwq+aIq9IHX8aDost z%1g4*MrkoJqqrAs+OX}uFL&1gY}+gSDGsJP+h8W0E&S}S!xH;?%l%owAoyraoHrmV z*Zctx{O9@jy9k~@T$ntNEu)5Wu2-0majiq|mBfI@)n6sqN=72#!=ZCHEK`G%i_b^Yb_WgJB^kNDQC#5AkT z{4ChiIvu+%Zr@Hz01>l?+#PSlp0=j{%1wx4WpbZtJ<77b zd~RbqDsRu$0QQA0C34>hz{*_j37FtmV0jxTHqUe3X&rbQ-=ytfc-R=*N)=&V;mWXF9u{5r#_*0{SrGn(P{ucl5~j2R4;J>*aSgSK}J z&MfS^d^@(y?%1}SJGO1xcJA1=ZQJVDHakhjNe3NG9!$-gntGpiPMtcR_WrzU?`vQG zb*;62Te7JGl?$JbOJH_GTqhg*9YAML_0CqF0ZA$KDD$q^lE=q7rd|eT(*lhh~%q z9U%0OJ2f7sRkqZliPq-sD#b1?t1oQwhNa;V7}=niqJU?FXMyyMImRBKQI+kS*uva- zEp$eu+;09a+8)l+Ns=y-jUD?bQ`SLLJ(yzyZ~viY|a@E zKS82zn!`0ktx6mm7bRV$uF!BMryr>`1gpAMNRF!)(&}BSq#TKoBX6M1pv)PsmJkeEuKbqhhEdCeM z@h>9X1E1Cz`Nk>K<6m+m7r1Q~ysT4zO<7)jmftAKUkI=Vn!5+QnT2c0`R|+n|G~08 zhro|fvA&(z25nA+)Vv{~=6w9Yp8N+=sWY0m6EOfod}_`=+*nW38C!phEoq&Ec#iUdaHXpG z%XafexMIUQu{{5?pWH#^Ab9m_lK%VurJwx2TtAurEm5jz+kXX_KFo}~(ag~j*+D2s z(KiGMC}vuzAW)w$FH$?#3WjSon+0(;mA$j3Yg@h|EZ_XV?YnQWh}lYS0*290<-@VS z!?T8E1D+vD9L#c*%F)NhrCxI~oKLpQ-5wXazWae2V5S1e5Fik~xH?M;OAeAlrU;X` zwHED_1(=VQv%Q|zIdRwGas_`LeguKRlB4ski$t$eVjsYk7VUWuMHJ?-SW;s zX6ivKabW%)>sF%-6aJQ!<+hX0ET???o>T&?3>H}TAablZ^Mo$ZPDY-MH$|z6A31C) z&ajIITow4AOwGsWXqpw7u1q%@{hbG8>RJx>@bNi<`K&h=WVQdv7mzw3Nh(I zBlhle0&WL|tYYzZjEJtnkQEb4cw1fwhLz`YLg~atz%n z@(Py@D`NzY>Z~F8e@^(_T-3+pLL(rm&EWbPpqHjReB;pULCtbm_2{@B{ zxLfcVo&0&$X%W#dRAs!ir1YJBLE?_Uf#FvVkDOc2xlW^jY$`6vK-)b6l>=z+&M!M~)T z<4S{crH2_S=i^%(OLr7D!Xp#Dx^$_yaD#kvtVI$1KY8cmQAhJ*qYz1 zZrW}0Q0rW~6n&S&LIS`2ulee{uR6XWPRFY|-utWpxRV2Ll}gC&cs+-D~eJ0?osC&h9q`m51S_b5Po=qPO6@ z5Y7#NdxCzefa6B&RG?Id9)sX#xG9DsYo8DGd~Sxjcl;R&>!b1Ga1eA}_eZB4d}lrK zY*#(>cQg;-y^wxqP!W3C(Y*G0@F9AYeMBt!!FLGCeq9L4AzN<0SbMm)j{YZbJ*;P% zz&@;J072hq-|uIJz|Rr?(`SLVrdW3fzbO6FXM*0M!>4B+0)GQsj01?A$QzLyDHBel z&wOR79pvW>InzNptn|3LGZms9i04!};KP=OVwo6c(V`I!{Xn>!^etFU<&A3&J*pO4 zZ=G_?Ln_?T0a=ck#B6YyYvmA!>)k=K+#lh4nCf9`Q2XC5OnUQ{XuVa+S^Z{i*>BGr zIUBc?a_Z1F`+^Ekexx^T+_oe7r!FOe6n=$^awr{AK;6PkI=HRSyz^#lp!W?zPVHzG zcv#tty_}irXEw4gFkJ89NUG-Rx&(P;(#b^f()BYs+o3vpFpxnj%T&A z@18+E5o5ZYh5YcMj5coqCL-Bi+_!{Y1>TVl)|U)@{)sqOAQR0hEZSTGmEIx|sF0gb z&Ggn$uIvn(m1M8dWC%^cb?}23K~m|ON0~hH%wML9p&G7%=28U>)EN#|yl74<^tfo# z8%<~@v!tV@MQ+5tW4*sc23#hi#jFzpX;n|$?ZSsi&L-QXY~&t*(4pB96)rz=chJHS zZqnOvIo~5dVlk20-+mL^dQf(7VM>$;Q<2+}(elZY-{vqqS?8PCRVZ)aM1)-kUchS1 z9NX>Aw^+j!m{|2PR(X%v86Io7(AT)VSjC0w8M<>LN8jB}ZxnpVbRHSERr%{1HpX8Sg-+((2M0EWHZvpHDT!VazGaO~!#(h{){a@c?qQQ-) z0@cN5{y&+|=+iB&vzWu<3^0QeaFw>d5S7(FDgya z4-Pqm&yRbE<>$rE=Fk;LJby#GZ{Hn2{BA^}mR2RAp3lMj!&wuYilUKXaEB>AcZzTq zp2?&JsO;37HQk7cLm|>#PHL`qZ;oE!;;h&^rbeb$r9C88 zUqv&eu_8@HL0F3mti|j>iZaKq?v}-MMV(DQG|4k<%qZa_xy4o5Y(IKhm49(EE$?xW zu%{@h#lq>4Yf!mvR+9AfBwMuc`lsSTNEv@$v$@}ibLImCB8<3+^r3L{ZNo#@;CTF2 zN^G$X6d9G=f}o8&B^A;7_5cloOy~ld{7x~`_f8+eHZsVA9vjlQ*Yzg#neEA>anZyv zFyGr&QSO{QXFhvoPxT-cHRDWQ`0NTBRIHLxlPYBLUleGgNX7L4dH$^9<6@JX4l16S zJ0-B!YTVJQQZyrCWGwf^h0V~(kcdn1j+dPltfMBkEt7~Nb(;9(LRXqUYs)sXk`$ksQ0O2+CLoU&qB4k(3 zNZH&e9d{^s;PPxeuFyx+VQ5sBJ8{^RF#mQiaVM6k%XfIMZ6zotBkn zNwl55W{a}QvVHxf0F7Q7@x`jL%n$M?yR7wx^NLb^^F{l5A2Pq}6#daxsyhghIj`_`uPkE;-s3Ax%F#~=)CYQN9)S&=(u7eMo@_=>PJ@!{Qif-SRxep%;)RMkE@e~5 z=tEB9*sNQpVi0hdWlW>KSewo5EWSi4tY@@{YYtZL&ETG4w;t0>NewYl4<6r$O^dPD z98#X($Y5%%={SLk@m9tw&gmGbAd)ytL!Ufh-$T|2xUpuAkc}2@5k0uY<`SI9RqoVNur+8Uvg3)lVVgr zJ;baUdu#>LJt0_B8B&2+s7W_SZr4^ha;hfnP@@%zR6!lG%v`L3fLL|hE?LuGGZDPm z(WAY*?{_>BJP{VQEajuewnw!bZrFlrzJ%Ldv9dpA#phR=2~(MJr;3MBG0m#~QX$@= z+|wDfQc1T|SX->NEXlLPzERYw+;?7xr^>Ni{kZ4vfgn$GtxM~TRD4^oC}`dQMYhi0 zM6mK{LhuGMW7Ipc5Fck*E!`m4OwM%CJMBKehvr}Hj=5T}mfHqu{5@-toSL04Eb=zZ zO_-Cwra6gY57Pb0hk`=5DXFcks!Y=xg3RvMq=pZ==a2-OwcX_=rHi#4rc|zAZZn6* zAdkk{bjmFL=$~1Vnz?FC&&6zWve+XLcW3@X_NEZWF3pMdNm}!*uLq4i>IzV_P{9sW zY&rnX7BdS?5dz|~G&RmJJ}<4}q$u*QVVI@xd}`{vfz!}3R|c8=fw4i68bZrPl8&x) zm}fK+wl(@ltk)!w92l!V`8h;M38>N3GEs{#n4>%{(k7c?{3X*;oI*P&w}dOXlx^;l zn7{_pv_gS1P7tR^hkJY@F3Zq$A)C%WWV{5NjzY*|n;$7cOF?IFIZP{3ZXts;?FvEywGPa}{xJhbPCSe&h^ z*|6TLDAvNa?8DRFS2(o#@ zjXp`i!4KCGt65&_53c94n3O`ttqGp8#ADrTmtY0NtmJ<+Ag?{JSc)uJpee19x4^A# z5raEd&EDW$j$#^HL)IvPvh%WNfs|tsY#|WqUjh8Sh);Ak=VJRRxM$HxNG)G6~MCS zFRg9`KY(Z1c&Uc4tlldK^;{BHMZb9HT-qh;FY|UmZlUox%|p6ZX0FQYLeqJbi#Q*^ zzEb%ibz)9_3Av|6FW-F$`d!I4#;>NgRw74D>|Crxp{F>tA}s}wqe!z%Q>p3;aII2T zjq{S#E$gi+Jom2D@1ai-zZ9O=R1s>T4nH71m@7V4v630K56uYPl9VxI;ES?LmYdhC zgt5#W#XZD0dQymO(ufE(9#mpAOLdF3oEC_ZN=VO&)J>=^Q~_4rTdf}$kH{=dIL?E! zW$TYGY(Ur5glf75NV0H^rmPyVnW+*m{A_}^!3(|!I%c)+2VE<5Vw@afg7cixdS|t6 z@|!V^(wCSV%~f$-r%>I8zPq4UZsE&0jHCWdR@xf}`ll+9*N>}@?eS+(17N4J!oEJZ z`k{{3>YyR%@{__|TWZp`ToE^dpl`jI1^`!?(IpJ}u+(VYDzgm2$m z3I5Zu$bZwa`@acI|8T^~n3|i~nfx!6-c}hMfb0k4($Gl7fQlAf09im(K~zFiBV?tq7(XAsY+&h8X(&C^3e5Ry&S7p; zrvK^N3xjZ~T&xc@#72M*#x2}lSwz^wO_$E?BI?3g1OUMCtD0yeq{phkQ{QC}bD(!r z6n$yp%_JMq+&Y%PKq9cF_M)H3#CdogA(CRL2tJ`WVEV=*{oGf$9zmOsHqkh1{ox=` zi;y}p*lWY(f!D|!d;6&%`ZbV|N9ZpgPY7?}j*x_B5iFv_d@PohQnON~zLqtT42&$f z_0!GJAvhF`rzhRX(M;LI%dWR7=|(h+*Pcc!)+KKRoHaTg-ee@(2+lsX(@sZ;6!`wr zf7m5{UGQ+jF=Iee7*7Vp{gvSTa#-Y}Fi1uGyp30dHdu56+ud@Z3tQ_pf?JT3miKyS zIkW1;+NzO~V=1YhZl`D!T~PDHsowh?PaXxb@PZ>X&ZOBI&Y+AqedI>bg8O- z6fUglKrSWK(cd_YGl^t$9bH9XsO8y#?Ww}rRPl2fYTT9jNn_Sf9v*=t)fmDUzUEL; z;6{{MV{2WalU>AOP*xg93xXwmh%*k-kCAu~m2MV1A7F_xqU zM*F$<0cXt@cn>fz#jfnpJKbbSZtd6-SMriB3@AMgfDP8;%}r7>bYw!VplC8`DxLx# zA@WH9#U(xSDvwOuU$|{eC(@eKEDqx2b^``#p@~Y?EEjvn7j#7?tflsH_1eCq2=f-J z^Do8V=fl8r~4m1M9O2Wm;^9!NrO{+M` zEMLT(ZBeI;03n#Y5iy8gzTOVNMUse|;}q@gX}ji&rZS7B(^N_ncL@`uwY8~RH zU%-X(7fdUtX$0$(yrF@VTHOcfJHjep=+FL~w9Y~L<>cYeumfdWT$p97j&6P%O`P+5 zZ(6%Xm;Q754Ee<4B!x#%{kc zKm53H{R_0)Go|0Y@pH=VVA@d?#svZ-8#b;Mo7FBSrUkp``>rc(;*x5-h=!Ol5#G5a zNfm=d^&$@zb3Ek_={LB4`g`-E7ahLj^MwB>pZ~uzqWx=C`uU8 zc{4750J!nsOzE@I&BX))S1U^)sG&0m^FTh2A*?)@2Kn+#Gm$qY9lSgv=3N5nq?0P}Fm%zNHd(^W@K9}`A zM2hD9`zRVaZPVjE4|I}j+r-izoomJ+9iAX%w7{HemU$>P6`kJoZg6)Gx4PM1ps}lgcO#ih; zkO8-LDi`gwVyj)%Qj6XBE+AfZRAGT8+g3cpryee4wy{$XG|bgdg`Vbm)oy_@b2d?! zLQdWpJiz_j5@XK4y9@^DUh5~!Q{A+r9Mg;)VF}@#4H#t0PCP1Uc3~dcN{zVl_i}rh zhG~hUOMM!ePPUM)n$K)6Tp17Ae(NnfG>B|u(PMMwt{l)Jk1q@!;A)`I)P?L9IaEV{T(jDz3d@{zo%k|17CX>}F>@7a@VXn}h4Md#2>-ox`PXONq6z1dwCeh)@1N&ld)8zEk3B^LiAO7qNKQ`L zPyjv#No<4{gdij+%s-iDOV)UFngo9|&#v258dq)I#!e=?TC)9RN5$0WA9Yn;C?>OA zTy5mPx9TiD>%5q^-CnV=?RKu^mlR(cK6=7i`+Vj8wdFj^7f17wW$$-8`7KkdQN^N! zn0~~E3R9v%A(EO3Q?fxL(uyioqCq9nREajtC=@+SLXl)dib_pVk!FNVsablSXhe;w zRkA@h(z*m%x(7jm77$9bmZ@nH9E04^d6-PN7ohp#^V`vImGtaH`w#M z*YmWTnN*u7=HvrApf@&u|34sM!#6O%*9nDKfk(liA$T-GiSDfZC+wZs8x*AZp0xcZ z9RA@OL!f|3d)~e>e4d#{{C*RBp7FCZu+PXN`Kt{D1~`T-$DDl^pLzYzKeT7ch&|yL z2F1TMbMp({m{8@W9@YPHz~?O#3eJIHD9=M7l!s3vr0>>%sflg?z^4%_iKMotOQ;j{ z#OO00jO#NMobucb)zUs0%)NCL3Wvn#GYTj0k!+Z~-;7mtYYw0HWQ4FYb|VQ4!zMIK zzbPdAZo)Zw0|5lUcgNN-`y}n-0IwO}()Zbb{;VNzeM}*E<_JW$x zIgj+=D1E%ay-+8;8>Z*mZX)U%ePDXncih6nf>e7HJ-BbA?BIJwUx^6#5uBKomK;99^K!WWYR`#{QP7n$xkmq^Rgm891!To(Si zUmn4c?WuL|8h#!~fzW`Z&oqqSF@lVO*_Vgp9FWqD(#JR~`wS(L?lFVx>oJe4`1TX| z{W*e&_N^Z|*kc`8#A5)N>1_eItr2p_CJnroJ|6;?8yyHikHG5ks4c5TjY-g0vlfsd z#eq;d<)J)?AA^v2rolYFlygb0j0Zs-@qy{QWW$V9mgNPULWv@;Dw9Xl8s9I~9oHb< z-V(BgbFy}1VOnc$y2hl*EIq5-av>*(;s{+-tMmYCnZs$y$aLARa_9>nJT>_9^(Sh! z-0T;mHT+XL6~Y%UgMhX>$eXayLy~b8)ig*O4BiP!P?@r1=3NE0uX!Z^4dc z-oAvE{XP3nJ9f_5sMm=EPu5wJ)ODn0SGn>kTAbJm;?u0+xfothT$_39AW}Dk<|}eX zSc~hDRB_6dtaGZiLv5}Lbt<;X#h<47JYym;oOVVsL+uG>jI#~6#L*fd=IHIE3aycP zYK3f2v!5{cvlPTDWPzHf5Dc{rn8uP6`GXM&GMTaV8AFi zfr+HmFxlT*SRn5PGoUT2s?5^!ihi#2!>4%>EoK2|yDBavrpQmMci8Wnzv*)(AvaEZ zWwm~lVmr6>>0UV#%OREPV8eH-O2|qJU&%Iz()MWf?|v1kIG4B8c)zY(?Ko&tL|Dr| zYJ(nMj)&y1qn-7b@roD=Q7z@rfq~}M018*2(>S&Jp(#++D*5a-TE#>fL=1*>77`Za z>JmQWs6{l(ezPshMVZmXrTp5Ag+Qk^NaGS_5&1P^^VeU>H_MXd_0rbWZaO#Ax>TlD z^HS?d#!1cUiZZ&%5|CfGHnUDeMqJh_s3~v5XjsZZ)z~3jGf!vEwuN~ZMR_fmHLrc9 zF*CyYggA16t5!ws>oQy^NqzvZzL@$c!JN`+J%yV^|K%UQv9z`!GpBojJO(jb@E*Qs z!g-bKb7D!7+fZb&YauZF%;1l05co51uhNevOTJ)6Yp8EdfRT<>a#&h}Xx%?Gyr?-t zCgvQsT>fgQjln^omxKL}g~ za%ufF{>be6+>8mPddVz$X0YiKNa_ZgvM-deGT>=0pt&w5r*TpSiA&}FZ&P6NCi81k zNxF!LYJiSxzP{{s>1HRLF>?}j{;p6aVRN_+su{wGyVoK!;&ijJ#L=r9BNGw;6a({I zc22HID_nP(!4g(m<{fDdXK9I zsVqzttr-uh}KM#@V|OU06SOc5vmbZk6UqsBUpKg}%!$)cu> zm6J1XdsqvNuVEICC3(IpK6;{Ql)wJY{`pHS5xt^60-r413jqHR+k@t zL1gPfw<|4|O{89OCmheZ!tL1o0+VSoZo79}oJy5gT$eE69!Hh+lbTSJqve6BM=go} z0apMoJuLJF_2&~p5C*h-RA9gF{t#8=u1%daSLu-BhVY}3THxb5uJ^6=x%yq23h&si zWJT+MWw3CW8_{idtU1hQhB#WYKTOMz(4}Mh=sa%r@WD?|)`eM4JO0o=LZ4JRgbz7` zz!(^+~0Etw>?b(1jZy!!5yc zFOyuquz%-Q7^}z(0;n%9;nh;-R#q|G?oc53Ml8zspIa!w{kMNPd?Iq|f*4Sj4!kO2 z!p9gd!YKXSkXQvjoro0@m@k+8p&CT7cQCFEaaA^MaERUd-DckRsRHG;4ZuA+D3XKc zL4L#&(>uaFfc==G;68G0GsLT8j%>Pt?4uQ}5@{UB9(}A86zzbA+l-#cmKDtyiFwJ` zY5|xl-449m$XTn|4kf(QZP)Z}+Y_+|ZhmS%ldi}Zg0Oz|dZnP!$J-|lr4R(q3WUOb zxMk{&ieX(VCz(j-@5FNq6rE&JC<+0iUE~TQw}{I9R{rsv&tci*4BEko8Ucmin#%5& zGCd(N6+Lk>?|!t4R|RnIKY}*G95dV)GIS5RX7nrzjpMc?+;+GF;k7$_P-%!$jPU1K z21;Tk#~K__A-$FD&Fd3d*D-9CzK>0Wt7$H<0I!0C)aN|&ebIrBOe&V&DMb9f$U(1j z<-Vvj8%(B@2!)ZX7Nfh|xYddYVlybb5v~O=_$Qk=?!5k}94&K%q=aw+4j#A?@Y>}% zxAA1L7VQNN9!PLYy@Fo6!ZvC9lZe`Q1SuhgObu)T2m)deX|v1Du+zM*y#9&RW&Ds8 zIm14-v}G?oonuu#?h(q*8IruEuF+QUM<$} z`^N2U8)B=j(lA=vN#!vrU1M|1u?1?HHE7B$Ra$292iCVY8>++Q@;}Di8?(HV_w)K2 zC8~bIEH!uf(0y2~TH0yBlgl5?-T;{qEKKe*PZg6VlnxUD!T+NZ-hf7i*4oG zv808(&}uJi+av2lOPz7VBZ3Zbo>=f3(aPla0@)Ajt|RBugjo_Q{r++v6u_}`yY>hA z(@*sqlox7#693q+V{1-&|G=?k^BasyZ4dERcE3Vjs9Eb>5ghCve)|((;PG%j2YkW zWEA-leVvpPNn+hzRBv85JCpuej_r6kj4VM!)S}mW!<|LxP55@(fGt02yVo1k%h7Ci zu57wtBe^<7>PZF9D|oJ0T>_`Kjb#iQ7pp}PvVC5xT0*zfZ2mU@5?i< z&sKDbFjDA_dPe6t|CE@Ptmuu9bY<{@SI!+>5PUbPS$(V`C|@8^^-8P8zJ!zubgdW5 z9gRtlo8f}e-cAnNs%%BSGN9{jp5<4v7U2CWG_`0in&OA1b{eKowHuvpXOy!8a7Pu( z;?KVdeY-=LXcx8_T{UC;#E3)BAr>m;I7~x4`*Ar12@9Tf7fj*(EwY-dp!%<_`My1G z%zFp7#+)mLsp)B$vg0iJ5 zLGoz6M)_Dz@eyN}vpLJk_)LHK_4)b2cAtfWNC;UE3gEihUmIvhGR7LSi}mK}9lxcE zedX+(z9oo#H4NBC@c<=X^L*t0}rFi?9(pVPY#lYTCWL=Zed1m z9;X}_GfjqzacYJQhnq8*8chLZhd#x;k;K6WhdE7Aj3|!gYL^jD$yeR4{1$l|@eOAS zM-XQP0$DUHXtq#);Ma{RM4NF}Kodx(|WA+6{tE-JbWU^3Ate z<$9>nZ_)uIKj`*YVEqEVKrjtr10rjcdtt(d08l^LJwqR@0r@XzcAl_$z4{y>N>3il z8ij#CD-~xD9>yEKI?Z!v{=3pc?r^}jtOCYv+H)hgp}U*Ll@QE%TD~1~Yp*&pu7u)} zQerTw#Rd{b7E>*^Vog>iR|CN&T%1Y?^QcbQnDSt`BW7uW)5XKbNJ__(xL>4fO#%xA zBLvG5rL1Z4*0tvGgNlazHddp>o2uIm62(r*nZ!L3OEOQztc9jdpjfHoow$`BU?nv_&vlA?BFHnSJGsbS@|94a15*;R;N8um<9MECxw z_=e0T8mqP3k6@gc^v=X%YDp{vi=ili#uFxR)GG#^M@DHFSgvEQx?HJ_Py^N{*d$yr zcER=y89W$jHF!VV4!j0FIXlld=Z;c}SBWrXfl@p?aqn&TktJu@8}!WzKh93exrD+5 zYq;sGD-Paqnm-|nfU>AgJSP{XQ$mb|v55pbZx!wXqifdV;YC@2H&5zo4<`4+Lzs?3 zj)rIUKaWaeID928Z0U`hNdO9cD(s2aE~=vy7fUA9iw+m3ikb1~6(ZOeGQ_^w*eW}= zCd*ALE4~!;I}3FmDP)}!SjvxbbZ~n?{Jk!d(l0j=FhN( zC@uL_MmW83Lh?;FRjhw?Q&uj0LFt-y2@Tpfp&1q|{+cfV%m*2-8;~K0x)i1@5 zyJ?kSZap<~IVKZPR7~qD`S&c3fn>GW*dxNdod)@!W#nOVKN9A#UKG*?G)c;T=J)op zj>Y~mwy$JBN=-a~Xgc_VQBW9zll{dc=Vcov% zBjm^A&M?n~ZTI9((WAcyQro=UWB(`rh4DefxZ<$l&;7%_tFpCsMsAETM*VK_&~)CC zbQ%u#MEpsL5zHhcE;C0J$7Dw@)LcK+jr1WXH_Y z)U?atpRp;R&hhQs<8nVV%oWKLDP_v@+UwrEveO zb~5AMcHIa;DcW?j%^pEIQpWQvWXiB4t|Ve0=V33YW%fqTc$xH)J3^#hv6IDL4wInG z0aD(2ecQXA_9i3^i|BExjNUKH zLkWsKEBcj$FvM0S-@Jn0;XD?dE~x5NO>;b$?dkV*WuRwY^dx=~$6<629|%}@q6Ta~ z8HyESL(ilSvQ#&=O!T8q;{K8}_L4&LI%D|93qZQ%#hvz*SA_dIQ~0leLH`ZmnVJlij4QieR@xf?HJek01?j+4Hvz(!V$u5lmplPRuUE}mTzzxS69w0?BEzmDs1k^-e~?FVDcZPu?( zWgOZszl7T7NcKVk^gt-cf|OCWPE+@U(!d$Ghp>hF0)#-!hp+*p(bCum#=-%_2AIC^ zR}!q_a|98kxs_R!g?3+X%TBEWM{nzx0W?Y2d(OlO$51>ix9y`1G&>Ec9R)b43Wa7F zQ!zF=JK9B`Vs71iuUNdTa6p!Hk&|b)6EWJr#5wu2ptg zXm!5!nUt6lc-%RxT!hOE3*J$3NnT2D)?17%g&#jUMAu7MHmhgZpPC#4bIBQcEc70X z35^Y~3sT_tU81nYa~F$DHX|}sZSV@$zNmfprOUQ=T|XbkyH4YcF~CjSA%xbI14+GU zpnXeafs}><31G9QWVAoR5t>B+NRgZ|sA4)4+9mj;lcLsl>fi!bWv@2B;07V!mxRNt zmVNKOVenCst?#5gxYzwevzMUbs?bNHXD?07UfL9WPvvz+s1T7mcMsvfRSwHux{mk@ z=2@F4zWi)>*FG}-8Nfp~HtIg#dPsQ_>Hzucx0mC3kB`V2%7jkH>SM=Pc*p3aWD@Z5 zY-wg6sDT$$-NqugdLR?*kHD$zDItkv+p&$@ViF>GcmAt(J>56Y=wHF=jeW$DfAH_r z{^Kzm&HwGR^Y8CO14ct-72~6>soT&a00%-ykirfgj2kirlZgqM9$Sz^oPcf8_yh#$ zJIi4=2c%6_F?)<|vusjx47=nadyTG4l`Xzewe}*p?MCTq@3r^hyL4Y&4d1UGoYZl_ zdY_v|1#-h9vLPy$bTScGre!Tu81sW-_XEU3Au4r+sC zq}fRhdV>%!SY$ehHNvo(n?0OFlP*`2!{)S@++{Ctf8Vt^X_wH^+zb!=G>~5~l+Q$S^22acl%}wSr zJ+Pd@lMm%%iM6js8C@8xjW|?ck*&=-gkdcv7+~KGhS4*a88L`N?+0L&NO&ra!eJ<2 z>m82R*gSn5SVdYcpVEhf@B=}BzM<`~;zTDuX5wjwb-J}ijX8&J%z&@hJJUDNLq*JT z2PDjL`*iRC>>ZLrG}>Fq6K~Y-sgAf~raq8$DYu&4%A-vlY0;BfCs}5ZuR~x#jx;IVPUThuUr+ar%b&nEj%lOy3aglWx6v ze;gutXpDZx(Hqt_eZ#qqzs1^OIIOGwu=hv`AW_(~GR*346twkLL8y?VTQD!zipyjb z>5&ve62nl2!6`Me0#=AcE3E#km&`XKt_UIIh?&D2JSnb3{>7H$EPmj{YZ;>TJYPVH zYL#eGDOsw&UKf(g6RsJ96r$Av!e(Z1t06*Dquy=fE3Ffiv9d9Bky$(JC6d+kx*RTf z)JV%^YUNcvt&$XpW3Jun2zS{$L{7uHNw-C&fNMce)xef}zM^{I2%)8&QAIz;F8NIx zrt_e}MAUX;WGg4If=NC#naKvUMOjs16iGh8y)lH0a{)+jQ)5M2Nls8IyuLt9er&7>zgQ8cCNG{Vlfh%Op~LX}c7yx)4*s%l9$(_`4PS2Sv9KZ_eSejSe% zNL_Fh$hyT#jUYQxk>;(0MQ<54UP3TFaTAlD-?F_H7qp8SSt>TwU;`f}51hkr?@n~1 zE8Q61E!D81p|}iaBERq-al15MB;IQYZqYNY5nCD|@gBDsl^Sa0pT21__H(8z_FvS&5l5tn$7@av}Rkb$%SY#EE!SRx~oFgVjhu!zEbH z$N0)urARqFZZFlyKv4_t%jszDogIb&9vw%4p8yqi-UXiFw-{N+8Chlb+)C9I7F7MdW zc+cjkF*si+*)`&Fh7((4P*u+}k`%4PMd`C(YJIE{mh8<{h?AJa4Hw-@)rS)k`$!+= zRRr;+5XszmYuAfOxmCJXD<}A&hpo1K&cyfD{Mptt|0zYcQGZH>4JgjOSP;2t7BeyD zP9cbr)6Hd4!1)O~tYjcl=AN*z4W_ik%IF8q!(&Si3GCCkji-s|#v#gx8D*hn*ur;t zI|-}#9IpF%TUu>+b(GjDeR_~W+mf6_*9f5Q1_&+}!f&F>UyVCkBD%?~WIzWt-Q>tK z%#-4->AD*s={#U9I5YXV8gpDesGwNqc;GxX zZ&c$A<4VpbF)k)hS_-J>kITk-i}DU!ga%)1e_E+v6Qc zwqDTKJw2LNBJ8kL1t>POZ%Nvvb^Tt{z$;M1wT?A5ToJ^fTaNRA|X(XQ3 z)|OUR4u^amW}ZT&QJ_*YD$o$yv@X1?8I@`Pwt9fsp--=ouN3Mx_aoP|t5=T^HGqVP z;h92dK*e3}-bkjupqA>Ns7S|?sh|lNp{1SOU5`Q!>>DVN?M{7ytyO;(-cbtThOs0l zO9qhM%FMwknyyg*=iT;cc@3YqreJw|Fmw$mf};$uTP_D!PLZMApR+BOY%8A>2Y)}Z zc3OGkk&U@FuSx3X)xxgg*r0I2<^VWgbVOgM-7)Ce;7HZbRWcqG^!IZjAYw)^uB6Mk zBNt$w#8g7n6Ib@YvAM>5JrrktVZl;F}x{f+V;F0X|zUcH5lvwDwN?7cJL9M=K3_B#g!CKWHNd2MoI-XO5y-)nYN1Z6@$V zK^xb?m=lCsu!nuDz$QmPCJmuPaWvmx_3|3DW#!$bF?>*?M*92nysGj%SJP(L7_e$DHNY-l^R2*_-FCz`;z>Ezu2 z>)7~C@y523YnYQZe}%ZB7(Ais3rc?r9>Z_o$gLz{`@Cg&{b8_?)O(YjSkv>8a@6SroFJe$3NxbudBL+rL(oE)BhnEYry!RA7gy_ z@7lOEW)XoW_R|vsqU(azA;=Z-r@_g?38kM4)eKcDhxe)F3%BK`<^ z6`t~KU#e`StB!CC<&KhVQZ)MV$L?@7<&LuLlJLdreeIS)*XOP?!3$16-}}u1Cn}#? zZP*qV5YC&T=Lud5v+7c~NB_|5v4G&)!BcL|R18l)7M-aC!z}{|mJCoAD2+)2L={fo zQUt~@X-{4<^1mKl3JcH2z#QJ@Bb~t$7`8-ysF_yZK9oR!K2dlzCa;wk!-gk?fJ%69 zcmm_4!Al1q;89_eOeu%iYcQs?Wi;j!+Y54#uAi4zfnVLUiXV{^hCa3-c2^)hlXkTM z|M|TAC%svFBrF7e!xlJCmbEBumbE}Ti$}Doh0E_|%t-~~q&6IO zb^;qk^r@b-E9`!OJbbx2)@D81w`b<_#Aapit2D}o5-h%+R_o3*v?@uaCh5>P47vxggM6?ZzJ>J zEHasP;n70GxN90{SlFf&0^+KKDd}ON+;P>l@v$>@a78b8nX@B{r;5yMtU2Wo*i!L; zJzuD*P|t`u1p&7+OD8-yU?>^!GeK#2*H(!j^9JiU+GWgT zPiAb7^_D4viqAY+`bGqbv0d|bX&UC(r8)^Mu{>7P?T$v2i!JUj@$Td2I|nCX zdtR?1n!0$Cnr_WkXm$O|P>!&aeJ(P6{Rb|NVh^1*67-&g%C=nRq@$ac6-mI0`k>7-pY$BUMTeGapgU6mAXMR2$6_8?& zaZowa1soWTx9&7+R%9V@Sa<6@-RJGkK0pe$Fyz^j5s8W%^ZO0YsjCbYOx*rv@4xCQ z)>VGY&0Wg-wTaxLIdcBT&2AWAl$6d@54Lxw>l1`2o*Mh1F3U4HCaK%_1*I!}Q-$aO zE?Sh&dMjI?cV_tdwrzS!`0>3I{+p?(2 zSBc7_ey}z;$u>OqL%vHg9|_l=7c&yu1wk5`ra4y+6BELjqD^k4UaA%?wz*D=QLU&IC2vFZe=ei|J^YiIOiA5D5& zqHut=lvdqzfGEf7Ev*vu=}$;67AykEMETaOe z2b;6-Jh3d#j8gkGi74|EGnD{N**QhO2&+;DDV5b4w_L{wsnEv%$RDd#fPx`pS7g*Z zyi6Q+Ut@SmprE*%gh(TVk1!GK&yUtNdb$^%$9~~0iUd9?-eb=#K97i!3fl3GPOZD0o zmJ%(9X1sbl$1y1(_Q?i$qw`WPW<+p<@DV&1izdv?PVoET#CK&SjN7DzGZ57MjyB8z z*6?@S(jTc1aULP1Q8dn}5(T{maxpAiGO`7wbySCyb#qOKX0s~?BFV@LqRDEIDW>vz zSk}Y(7Nms-r=vMTgIrqLQ`=Npv1a*}M){T2h9(Rf$u!MRCL|js?B6UAw!e}<{{)d- z@r?Gvap-h}nrxF+AXn>mx}jwZC^SSYB4JeLt9AJMT#?bC4B4aI<>D!Bno>GsDA#Ct z*bD4$<%|y*9D$5xV~FcMRZGaa?R`<8is*;`@P{@IQ>T#@&B`Q7-&L-SKh(_2FcIiC zmREO7Z&8-RSlu1jmdaB@>6Dv9VjoE}B%jd=`%P&U=Iz+j5^?A)LXc>(ZQvg6mUxIF z@-umFTf@D~E$&dkz3g_FvrZnktIP?QOhUVc=hUl;hchnMrf41(osBJ)l+LE3Pl(t< z6KNj9cE{5=OKfB!o{C2t_HY+rqjay+NF!UMVBXU-snRYEGAUOiUZge~Ly$^XD`^;I z+w*FbWZX3+rJPcG-b3GWboZ~*(Jjy>cHYy><2F`qRdAu;HYs*2kECoKquZ0iQoA3s z-NR3lKTqKuHAqv&k1x6oJypR^NudBpN^=s;jn>xz+$C)buRq0K;tu#5^~=g{spOW( zp8>kwkS7W3Wo!dCnkbYN3i6iTpi{2mkfk=qOju?N%+Vm4SF1~TyfFE{SB>xUwoJSa zW#6bt&3XMC97wgE>vTyv^TzoLu$J%hQXl(pbg@DG|7U9a-;_nKoRT0audo(=qEIdo zG&EcvnD(V#P^!Ek5iMD&RH(V6cB;%q`#l1WX?hyvEu41iH9*}$`|-0Em~S7@O)n`* zj77%rV2zve1Gb*%?0CAz>w!cElYw$W)hFw*-g?__uU;gm_7H`JPhtQX!o)CA#cJtV zz*f++8^Vs1Q8*Ov#oigLjFRruZJ>IR@hBe_S!ni^XEC@$vV^#1w;i@Rw-eKo>ib`!ZQxiy0E1;e{n_%{^uRS!A( zguyO`bCK_7W}jkjv9D-V*O4H%9*y8I&S<7Z_g8Ht@2B~H`TGRIp+f!qpe_*qk-Fgi zXAJf~?+<@tvT8O?sK2m$OmAvyG@$jt2$8@(6E5dy<)K^AB$5y)(Or_ zb@Qt~zP~q^E9@;@;ZpGz+lZQF(i;8%rqjqA+@Fy-V9jFkVHrfwJAMLsU!?8pduWkG zYPB}2pp&v=kmO+wfh*vmJi?yGY`63Tf+522ka-hexCx~L zV7*XOQ8)SoQ0@AnwpUXlw`pZWubS4flG~Z%9aYmWByM!P=)$qQIKzJ$v4m4&Mr>m+ zuqLuLJGn3A8;Jjqz6eETw`OMC$J{pnx$NXOeaw~#$tV3NsZNFZ^c5 zu2j@6Ei5X2kv+++aR~<(Y_ehzg^8W)tVucaOX=J%d%UL7p;Po;jx@5t>KX=yuG1Vq zWwMkdx$Xd;dv6iyd)lbJZdDZdmKJ6J;-j$3F%UJF?3};%rA@Hk6sl=U<-qQisnz?quxMwpK9NR}i;<$YoGr(>UY zve9V49xKVZFHM(unfWL8LwZT~L$!~sQ`CPXrgElpP*3Izn!WxBVlJ24l;~$&hf|}1 zx`z51?v0l0l>Za20B8kq9h`OE_whc3J?~T-n+?5*)()_2*Sdb~908mkbSHIJ5KU+r z5VgZdT7(_?2&uOgKduQ`RZUV-l$VniZu#hNHkzg|5xn#V6?8$1_n;)Z$4DRGxhFfUGE~7KVvBTG|ECoxj zwI6Z2KV5y-Vi2FN2>JQ8hRENB=YC?i-`^0$_(sNz!c1FrpEUzs&X|4PHGcXI?Nk>- zWlM*lSikw7vkV&5a`qdVXw3JI)|W)77}s*CrVXU4b40W)#nUVdTGmiSJTI9j!%ygs z;cC{YV`TL1(<~%tGofaI5HwhJOAthrjjB!t*AirZCzzO+{Agi}D7wMb5e6JV(rc4r*zcA;%!|IY5lj=iR{)8LALstKqMg~fR80l1G-#&Tbz7RzP{kmw<$Kc0VbZuv)e@F+Split~{ylQSORi611-|5p1 zzzY{CW;Hpl6l-p=MK!geVJp+e;rwTv%bf5SacFdkrPvibn9~-)3P1jZaT^f$*OOi0 z*_4TXJKOzey2I&>Q?xCMBVuYwI_0Wc!fppWN6J;PEn=LR19Q`3y@6<5diQ4moOZJ# zzd|9Rf=AC7;PHu8`*VEv_-d$TE5d|f`O2BDNaM>ePlWL2=!Np=!O)9|82N4UPAZ$Z zxYL~}0|tRM!6ZJpj-E5hzkc~d&c-CT6Hnhksyu6KPX*}M$rl0?pH-NO!F1TmX6=wS z5M94=UX9{Tzg zT}cF9Aun%T&kX*+c{+maYPTEt3#ZcD={a?5u3qj88Qz4w6Otzst?0FGCVu>2T#V>< zg1;uda{|OR-w&QO^B-}-|HiH1|G4M>uWk)VN>f%Sf*+os^&>?iY&JGKF$I;H`DCRv ztoTZ0Yzmb3v;oXB9OKiR_x&Ix{iu$xc+;6uaz=l)ds^w_n86%4QR3#J%K zsNuK>wi4Ooc4Qb4879$_P!wTSHM%PPHJ&Y}wo66Xsufq>cw#< zTn;fSp*rr&lUzgkN22mI%`&$Xwbc9SwY0iw*n=_D@nX1DGoaSme&2$}GzU;o2JXWD z5T9+I&$UC)GEskIr*u8kk@|xZ-!4PYM10splI6NSgw{+hiNn7}p5`?=o&~)0T1|Se zQh_ug_j+iQrI|iuNGC+VLX9PTDws9oK$k-rLFPe#3g;o0&?1fzb1UTdgFIsBMKE(W zjJo|(e_`=1G2rl%p%E-R1VOBuxB>i}6ImbXij_zsduoqpBw~UYv47Z3XvzE(YKPHuV3pMc(<=MC&W@twl-#H>e|i=>c$WfKB@M&J## z#1v{Km$Seev_MF4PzIsl&f235v5?q{fH;J(i|kVganI#UgXnOHvwj3SsBtJxajnfW zYdiAF87|OqSTOcai&Z^5f>&j%jUFqNdJ@r&tm(306c`-CP~y_rgy_x(w_h-1!r0Ni zUkJtnPekRE11FcHg)`*IYg3tLtMFYPzX8(lpWbB+RUWZbUFMq#)RTqRf511h_0ps_ zIo%<9x~G%n&ZeSj7?`l-D}N^Big_n?Vhz%8a=0t2>b@4sIH?@f7v@2f=eJe|@=Vpd zDUK$61&l3+JSEyNv8Y@co0EF;nYF<6r4a_&2Z1(m8kqyUD0{1RlQVZr{coRJbaGG( z&GGAJi_T_|WuVjQDI=3>XtpBL*PMgLdIquD-fJ0w>SykSjR`SG_vp^EhpnV%so5nqI4{I_r&hL`0%NC=! zm=0jP))n7_*&CQ4o|<_Dqm{%Ctgaz`2CHmNC|??gjjS>x2N|)<6l58^AFV8!4eWL1 zoQYtJLOmwMm@DxSmU)R)UqhJjQpqn&OGZ=aNIgcYuFS*Ky&QHEkXxV=HpEnPUfMR^ z>G2+M9ewsNynTf6St~ZEY1!Wd{B;-$ha9}gKMo@IKdN&68wZU4+neI=Wl(9t_9MFS zec{RBeI+6tm#qG};E1$hTqQO5Wg+fHxi zgO@1|)B@5>x$i+rFhRMbNWIFi^{Ia;bDmJE^!b8GX&8bWpCE-<)lQ&=TTDGcDElZ| z&ti*v$unDg?C0F8cBNnbPQah z^Y~GP=IH?fyi|R#+B`-DCxQqi@?$&3NN%Q%F;;*lW?S{Ob8M3cPhI_(%0}7`J7ygC znZ{nzZTV67t-3j6V><4pgCDDQ_T}OpWtOXb2qi&7J+{m=QNyi5@~$4XS}vsAy1~Vk zMYQMlY+8NZ-(N;zmx|Td3;Q^{X@S9i5*RCRo7Lb8cYwy#KS@gZ<#BhKp-11z8{O0% z?=UiGhw`WpSd#_0Ym_r}^YBYO!qD+GzIfJk;Ti}5a1(cz2aww87 z4Y*SA23#2foPC_LPS*+&WVd`|cYWd{t`bJ-B$*^^6ne<2U4&Jqad%Wqfi0qKvV)|q z$hOBGxiMj`zTo*Jxv$fPPIqa7J-Cu}M0vgfj!SpWu?M$3&RG?XXs*bXmNQeKY{C|e zzu~1rB|@d-N&BInB|60o%|dSw_FTgnusni=lHo$bJOXVLS?c3;@%!bx{lfO*Xrlar{{hTz?=b@>rk(M05XZLTXs~+CZ8b`- z{VE&B7wsxC)Gq9?Db!3f^V=03@&?)!FY*RP96BS>_7IUS+7${iKiU;DGC#&udZ=FL zV`1oGmK`PihWGgrKYiOEUGy?P1`~g896?8zG@Y(3vi( zA$tg-!_t`GevbX&7Se&fgMIHN*HBe#)Zrnca|O>XMKOzjwbn{+&e zSfk&<{VK^36GGB4Y(l?v^UbHHG{r%r50O)Q^Aa|MV2cmNZZrSe@7+uEuhMQ%Ka(!C zyu|u0E-7KUhw{I@_iV*H76iFoal-g+Q~B*LPo49I52>QlE+Y z9MX-C*XSu7f<5K&EYl3VQ3OM>nG8qUbk<7mr*9LBuPFhtJ?R!W9YnG!b2?H!1X)Gr z$|iEhWrO7tA!p$Wm6(Y=>x-QM?Mm!Au4G>(7U^0?SH_bOoRVkp7^ZHnTX_^|Dx{UH@vcEy-!>@}%T6wES<%~QqLo` zfTFWS#qa`!3)Nw-{HnMnQ|FN|)GNh^B1+&{fgvms8{B1cS$ce_Dft7yj~!)QmdXs4 zn}%~?k&L`PVT^mE{X4*B8e4`+P)8abazdG@6ek&r1d$>I#w37!cGCR3OIr@1XV(_C zQC?1?4J!df>g|&&*-tf20%B+B+@Q-yIB4CIL6jPEE)|p-d&@@a0=O#g?GlznRZW)M ze(K`p-Eg{8{(&|bpQBqnC9|2m!c-n36uD@>^b<~fFrr0w{#k$dbD0sC70F0yRa1a( za$5oFcga9o4G-Ty>s`xpLW5{J>|&g|L{pOrleQsoWjg!Mq?uz6J>w%XzZ9Km&1zze z@pg)7ca(~=$5(YvlO|laQs;NeG=84wQ`MKGPrON5#quc2a_R99fUQ~H;|Vm8tzqBB zrk-{o$@5%M3UsDDRA=W%>&VUHIIIZQr$ZS^#fJ!d*11{)V6~B0B~eh*#ycuuBv3$7Y7|A_a=0%(y>ynetjOj&)W(xq944m2S*Pbxx*MawHx_ zM;YC5s|o#Bsk>C22O3o1i?K?NDCsC(mOAGYwWm@aD`Io)v)-~S-|nht%UNyNHd8wI zJWlsZ`Aj4^RgEnm!+4caH=T|sp8il`l#$yhq!gc|)y;3CSj+Pewh%K|aJ-n^ozeGk zPV1T7Eq<^XNzKpQ9?2U_9Hv_)o;;L3r%>8VV^@Iv6J!0-X zd(<}!Rw9zEjnJ50$@{R{1Ze_}<=L`CitI8RiW_RN8Olw@?7D079Q`j72YvNc`;q!e zEn*Tz&Mo`!uQSL}e>4({YWL?`rs^rS^fL%+X(^1(QbA1ygzae5OD?Mzkhzg;1$HIl zO%Mv20#(pxpV^bVZyXZ8@L=`fRpIwWbzt#f+O&VNlf_0D+Ts{^i)e~5Z1*EHWIkC) z$t#=G2oH8PJfq+`OxiEKj5NeqCkh80(}_*`sVID4qM z5pjtqSaz8e((R2|wN>kCNgtV&&Ko3PgMFgLX?=?T0`zlbtk;aHomX5=+Aq<@)4tO> zPddg0bwx5Lon@T#Z!rd2yGzv?V=7Xjr$p>cy6I&V7p-ZWhbali_Mqf5Mh!~0dLzM6 z`0E&(L7CQ3?73hFS+kcd;W=U6>$9##u+ji!Wdu=91mPlxCp~hR&=70i+*0ohLP_ld zEar(NkK<5*%b$5b=R)ZS+wLw%^tGOs*zFkAbB}D?K@Up?uUUh>H81vY>+~E;;6j|- zhKupfM*H3JuY4sLu%gQ0(63OUMElVSW37^8u|YhhMBYwD@DZCMuvsLv14Q1%Mpu{+ zsTtq4h6+pT7=`R66Js-wT3WGJ*qXr)c>9eqyMyCq$WNnf#b>@vv_ks6R*TF-#?>kx#1-`lZOzfh)IEWp4fz_+L zcUpd0-Wm~OoZ$U6{|BQVTc(;l;U@%P*x!hKAwLAK`IM2=V&&~Aq50{cX8dQqgSi0& zWqLycV$evq2`~Kv3?K+7TS|xn%VGKE;sz?B=^2ZSV3@g*YfE;hWe(K`(C}QZ!U6!! zYagbadejtKz-Xo_YD}fe)_@Eyw%7%OZ8*FP37CE(P;0!*Xq(1bO`*HqLY8r>tupGz zurJD;R*Dl7DI^*VcdOt&_c$qm9g}H1SRpmWW`zzBXa_r5r)nc9&Yajh0KB2Af-$d! z_YGe#)Oeq#L*};qCiODw&>&l$S)~!}b=t!AR;wDIl#Q>Xl-DIJQnk5@6CkSL1Ydq? z!q5gVOiGPV>9Wy`_Vy9u!?J^=o(D`~uvr{oXGP&DNx%>F%lXJ z&RJ62S;MkUs3@xrcdjHANGlEYd2TYJX_@D)H%2PwrKb?}kaPFzP4>Gu#uv!w!x)Tv zhgsEN2{}(Fcss0liN!K4R%y)&nf{_Ig^{tgQ7h6hKLahU7ewK~2~7~y^2FO~@|FC$ z$O_jB(M>+Nw91zQ4jgdYRvQk4uvJ|5W{D>x5oK9U*D1jvRsjvjoqkD0l--w>?9hu% zW1cH)j}DuR#6PS;^dlI<$S>1!9iuazQTL0;gP0!L1h{G0#e!7j6u#O)kAAn6B+ z(Ho5}ludd1I;jPsTSqwG7(h+NnoTzvMXHH+OK1l}M};FQPPl#2tKeb1DR z<{F5yi%N)>#nZ>Dsv$=9P>uEQ_drgMwV^RiXP7E&eg%#`gQR^oaN`Y zj&-nvVT`j_+hE;}!sl4GpS)IOU)@=cLlIBgQ3X?8f|hyqY)AK?J3v)3FW{&C$8)dU ze?bDZm2T4*AEubFA3f(kuUt(3i6s6%`i+{S#fLY6n1%Jn_rKdtl(NoWQBu4p)t&bq zS=9@)g^aP&=tEzZfTxI&WeFHFp+>WI21*nRI z@~S0Xk>5W7lB7J$7LjG!5oe^#&c{0+)_z=^Pj38qyMph5Ur2cT9#+n^@1(uxAUq_C z*X*q9Tyd;EryxxjT@T69k-w<}ae*bFzvfp(gNFjC_|Yf20)D_wQn%>$2uuoK+hwGR z&h+!}u{ppolc75-_cQUa)CL5E0Z_fdrOEg}iDBHSY*(DuWL7= z8ta?r42Oa~O)`(CT2lK7%n0u{ zp`n)o|wC?xU4xroLJR_@<|sE#pIdcffTtKr38k#;1^=BB9gN?&gx^ zG)9+mIX5{Up&+=MgvUdp>H+V=1+=)2;q@7Z*U?GBn~Njf3xLn&Kw%=}eoy0@vRxsY zXKmA3HPz|&Zck=0bZ=5v-}_*hF<%ejwrLgJezTpsP?L~uK0c>9;v3>vhqEZ@c2s^_ zFt#wB+9ujUTR~$GK-5R|8A=nnVo&XcoLPj1LMF~Ef{&j+4q4xqbQheFuehx!>PLZ!3(xB9^>`82?!N{)LV(O@eP|8DrY1VCi!lV-`>}ma7L^ z!}u_iv2C^vszH>J+f<8G5PR^ST3 zsfk6EdOEjfuHxj7^yDi=#Gy@013^sD`Q@)uY$|juYx)7~p+f%CDgLLaLDbFO&e2KO z+|KUD|31D-T7bV;pCX+$`Q-9OqD=@i^_9MDS~4LCiMWD-9`Jy;<|7x1z!O_$?xgpx zzi($Svc3KN!e-R|1oMM1PL`801X1w!$6Y5gpC;Lv&AR?@y@PEcXQ!qz#4*RQGn(`< zGOjl@o88_u5co^cGT?7vdGrd@2u3`r3WQ)j3uzZD#Oi?^cRmnPlW5`Z^8hLXT!p) zCZc(1-7AWfS~4rXMFdffPIQ(;9LeaWYK!wOjs3fXewu34h?!oZhgV~GBQ>QF`A0KD zVJ^7v3$cpoM3OeB-q~eZt!X@&M?;aNZ1`Mbkznw*OraXT?iB^Q zqy}L&p4#*gqdrNjXBN1Vxk6L3-+nHtMI?6jo9sjOz#M%dc4F)pV(_;GR_l+oPDymo z;pXjpI(l1(0We;H*9AI^Nake<5#a7JMw#7WWG4hUXu8AZ2h)+rQd!I*8h+74<%c7I zu0iKA)c=O)6F)lB(t|h4i=JQmFD3~6gQ}MP0QY+TkqKh`hnwc#H7a6ZU~OkcqViFv zf<{gjcDDb8J?s2ct-Nz*F3l&3HAJvYdGZcgu?Ql5*>4Ji+*-scZZ+ee)`!VV&WFkIECT*+FQ}Sm6*LGmQ3z?+QCKS2f|6q}66PME0+wE^7lb7HN|##!n`R_@;QbKKi5 z$|kXq*Z3f%{MRDq9$9>j`_)+P5T4L+AN^L-)6|KFi`VZSTk2IC^k+bxlGV5!&xWTo zMxtf=N`{JP8K?Z7tLI-c4YKrnMc%SIR4b29W>wS6=m!c`O($-04I{CoZ!U??lau9> zx(P+tcP{zMh7#TisTG2zRR}L{y)s@-Oc~QR6IyhR+2~PDo z#TOb1xUqQ)cRM}%^mv5TI!IUx)i-YAhOst_4-%EP{Hs{wjP(q=?_FO!f>Fkz+z(=P z39tGpS&w(%S-ToosoOBVYoWSW%H1+l7Q_vpjQefziNYBVOhXR)1h{-X0vClxgkc_8 zfxJ?)e?a6<8n<+By~aX0h^4<#+P*=8edqC}3#(Anpvx5e;}+H-k=kcdl1hwAW}y^k zSm6`g@zZP;%QjO;GC-LNM)?UxboP^!D?hK_3a{wB5O+#}S2T>Wq;p`Ny8=_?Xu)e} zm2s-`=feJEpMOEgkv>ela39r1_c7c2=edUFe_Cyfe@`?@tA7z3yf{KxEk&{|$y(B@ z@|ma%v}&c$B#xA#TSN+X-bVBzkV81jCuCme-@f#NZ>Plwjgz6NP$OwrM4OqKO^u&M z`@TPas2$1hHCs%!nt~DFGSJU8TT;X!&8!(R+3XiS$nXOM?S{Ak2pn>S8pc2fDC!o& z&GbMfbc71d5=@)*9$9dFI?k5Bv9I`>R3MmUZDPabwbN_w^I#rJ&uT55t&_^Def+?^ z1#>K$Asfg(l-gVFu-FTcicXhtVfrLp?PCKdn%%Gc;J-h=;OF=K zY@UOz&)T#8>DMQ#&*v!$J=R#FA87;(I}_TW7TS?De&OtDMB1PU=#Pkv3@zmI+&=k= z$_s{y#TDL>LY1o?$wqRU(HB(`uL`#lb7SkaQW3-F7+zO)a(0aJ=Sj(SDrgo0umYmw z%sj1%2N-^_@QyI7&N>)o&VJ};@KW)GZxyX9GQ#ZTxPamZw&4b}8!Z%`S{6?pJf~7G z3(X*;E=D7qF$^m3;xc#{Bt7FC;rH^zD4j;u5Kn+K=KVk=6v#<)qIFF*Bi zE48UC@*1+2UqlZ1HjdB7I0l4Qwk$N)C~H~+^b}TZ!PenYi|0;uE5F^78@%A=e79AORby&1_7!K%uFs$UfNhiEKYrqaWwatnf{N9a#-GCa$;n)g z|L67Y4a$$U0jvU29c~)F26@vI4{dxwVW1TWp85B9aO&VPG@QBH55hiD?Wmf7o8Q_I zHPMj5jg3$72K7m|Bq^$e;N-vj8#pht;;w49vlfYsZtzH%=DH7BtEC*JYt!j78&)l< zBI)`Gn&O2WNLn~1-K~Md`Gu2zh(%3V4(bx>0wLO>X$F@h&hTSG)^V z-u*J&JlW4l;FW5RB!SD(a?Cr4=ln@eJ-3*7gOKy2AIb&-1$MP zd7X=Z^i;y>_%-_#XO?H}{%Rtpm+=w99~Bbyj}=1oKfJ;I9+K2vv~WMv+JL$-ngsuz zbhy+{wcnO>zFXxqu`OZt0fW9sU_%=-%Hp~}rM9%!Pfj{2WSHC7`1my6Fdp>z>hU4wVEwt> zjKKFA2^`{itb@|K+APQCIq&^}?=|sZ?>{V&n#@4Fl^K*mIxh8C6tqaH9eYU(!=HSK z0>htl$qd7vatQ}xC-GPq#7_Du)mKgWI{0?+E-q#Hn~qcYL(yc4X&A~Ng2e*dGECeO zOY;c96vKiCYGDpyk{KuF=!sE+q=1fVG@uAREVWGr5HeP|TMIUnaYe5J5K}mluved{ zz_`Lh7s574VWd+ka;)W>0Wib30^}EYhiNR2MFW(?Qjsa$Hb9$YD$5-!=@kTmKKwD_ znbdmumQ36J>7*KNT(!*9dFY4iI4)9$$47XiL&Oj9ChgK#lBe6UceS}J`vglGl=QY?S92n_eDCv?YDy=BQ z>BxxZi$uxkm|+$ZxeKScZ(!x#gdynprTW7XhyyI?NnV7{2Eeh!k*M910)lhr=i~y@ z^3Dqp2G**%$#!md<|@r(^s_m#imy5mqDPp26d&?_K&1?OFUsvsfOl!r4%0AeedI@>36)CR)BR&&Zr*J zj=mhH+Ayqy(&(TQUn`WuwkX$H~yQ*EMC z`)!q$$XodyAsWG!N<0g>h!(pVPbe!}5b*NhRy~OFcdU+MBi0O=Ty3-H>5JEuj#^u*B+J^_g>W8*O_Hj{j*7Q}zPX4J zARU1v|6GZi*A4wPv(i?G2J634_;{lDLhEv}U-&H}Mami(x@#;{@rkmdZ`P>SmNqGm zX<%7sFv7rp8+l^Iwg5#TK1uOsHIYh%w`BnI9tkv7oKq&rj{+5vF;yYhS1+B$hvhvI z)`v50x!xk5Do1>5#HFW`ymP^J7$u9eDbAPK6_X^zKigD-DHgdDLy=dU#{o{orQ!z# zNhva>{s<|VhQ+j6f-z}{HTIj2p^jTx2>0{c&L$~f? zDO?2unV^GUm#EtOB!C&#OgWtL0NzyrtA%IU+RuV92~)*LiCUitnHeAy*9hkTr5r+r zO1fqyc4>qXD8W%NkgvU@eT?Bwi_^5WDU~li)a=F>Le`j;Fp%<)hlz*^r&cdQfxGAq z3k;3qqR0aeFk}I;J`TD?UU&TJAVuYxm3M|;uSL0fjyI@sJJ1!ai}}r4{?Au{(B=(` zrkEqW@1E()t%7uAO1D-0S>jyRcEdq^rHmE9Aa792Y@VE({Fl%Ke;}4qdr>X%rVd|V zGJJr)Mg;<32S}-n#}QGEGnK3MJ+RV0W%B~Ym0dR11)X(E!!7LYw?(WqI!>QS-5Yn* z8CE-nkH2JC-cz* z=e-&}hM_uIby2d;pNSV1*4OA}HFoG~z|OHy{wSAw5lXFE&OmvTR{aYB7fl+O>fNLL zCksabqa4COSu+X|FaQc)3}l}!YJN<>B7nZ&^A~%h#TMOxMobZC_V`_-H+(Tv@f_g+ zM))m~C^bU?sskJBjkFVugsgiCE)`b& zR{PP{=vM4yPWv5ZgfEf>*Jy3~U>GA4h@w6FNzO5buKZfyiu+-BB*H}P=(sEGQOCCS zp{{7k`Vi)p@Xq6zmgXeTb-9tuM{}43c62^hYafm3n;H4-Aq45b-7m)N_3Q)zrit$) zJ;M1!FGh=x;vV5Acq7DkLMAw5PcLHE?^`FF5Rx70xLa|~>x`Nkw+5cPr6t*?nWu#@ ziX!PEB6u8&>wSQ7J4y)TBgX_DiFJK)r2Kc~SwW@tb2)1x5wKy9Rm?nP4{9yc!*z&` zT?c76y}o}I3UEu}UF zR^bFzVG6xq0V7Wit>76}L9b{1E9>SLwXZBr!4E9*ZyFNl+$9tC?s7_>I1#dktLziV z(RjKmzfl|fN#wE#o2weY_VQoIoE+S|{kK7df6?bysSn;@^dGrOhJTn)ByB&)0)r0} z$K~I2C5ge`bFA{J9I7A^FRwNvP(%N-f`9_uv2Krod`AUi97FqF6>o z1H;+=#4rmKGucdLMx$-7u?$aov#yR&Z@Z7|Aau-U8kXEeA?D{s4)a_SE!?_k;AfnC z4r}5l16sKij$lEYuR!a}g%vDZBXcQ|AMm_k#_xR9KSJy%%z9I@M@6bgfg>VaG`Psa zvz8RQ;n0anFfAwZ1qnBa&~B0=ZR(rZ_RQG)e+VA4GSRlwno$4~CXVT59JM=W&Rdkl zn~Oq>)xXBOKYy6nxj?OHp!KciT6EIzmR2#an7!5MhnjfPE3YX@uT{p`9Pj|XXrzSX zLSrpC1LxnVjSokq0c#~HDWdin^zHrTXm6VG-xdql3`GZ|tsuI7+cQnZF46PynsiS) zY)7dCjkeV_B;Q$O8=4byA9D(`mns<9K7~^sdBQtj?GJ>9d$4IKNo^pUElii2bjgii zLf&UW$(~%~>timX#HQqa%a)tQFetb{Ej2wKg<9psnP1G1Ya#3mSDJTJkW`~8g)&uR zRZwoCnByqxc8BxP*>DO$UXF(rD)VGy7hg4)HpDUymUKi)u@7jn$y}Hd;P$v>iu*0% zn$IER7+Hb(1kY7DPu{P1gm~yCjy@4@Om5)MRe1) zeX($8gm?i2gfuM2P`nutwfN;D1Z2!8`ET8#d*~YZ<#B8MCXzE#)4eIoz|j`#{{^7w zL3tMB5yi;PMVu-P#Zdk<4DyLJ*lei^`i6O1SPDKu!SnR5T`jpH!#Mn7oiF@HEb0GI zo&Sv|B`NCIeft0{!BKI3CvXo|5;hi1 zQJ|{w(*#ZW%sbdmxzH&t6Nwg+zMy(0_O$9w?ow};A9Gs7nE^(jJKrD2tabZ2rtSGF zGAWs*d*t`MN;pq`fyo_?ryzUdi;kC|(7kr{xX&|27GbpftzWOn3^(^z9oc47{B~WiBOgMdh0iPaJenO(ohN?3 zTTzP30ON+oKwzO=)cwrsd$`Qxv7C2!+>4zjlQMMSRo6jVo)% zeS2qquc;-3d+^h_=N3x-2j{yQRtwlk*F{!l2vQmwlEjV# zdBF)|rDrid-tErLKAb+`Tc+NE{zd}_9QtX8^Np^tO%U`5*A~OUx|pl#Y*WDIQcso5 z3#A_Q2=mZ*NcFxCQG4dU_!84V>$Q1?HieoqGlDsJ#y4#;VhMFb@WQDV=)OG(@1lt4 zUif7{%b<%}>r66pw} zS2T?8nx~8;UN0jkl6q=u>dhJ$ca5Sico6=pp)9pswFi#cuo77 z?RKGS?na}5_NaTr9NTqmXiw7P;%W?P1AM-;OLsOmaU6uXO*IF66fil(|6iDM{=L|u zz6efT;q6~RASjk`)zl`->G9^IDje$6ws?j`!UY>#O>F{heaZWl%75Q`XfU7awUD!$nr)VkJj(@s7W>Khd==MlX*7*ksFeX<_Y z-^U1zsLZiUr>8B6>G8^Mx)e*`U}c>qDVX=-X3rCNvqGo{ZD;h20@uWi(iR&1N>AI- z2pJsj@7e?Bui>h7s6y(WkMpZVnQ)Z74+>9suZw%pM|wcy(c&EqWFB?Jgqu)*i!(V>XpTzO4xO>VXa$&Hn*`( zUJu0GDzXYQuhEN%^m%5^6=is(|4AUD9)A6uD}_=Wn~g6KJadLS`Mb}35@MXtgyuD4 zTxlYaP(Z~Y8pwHK?LumU3|`H{<~%Gt&F)C_Qk#!Ms?0-Vi>2-g=U|zbOfOw~UTINw ze=TPqTbZ?9G*gaCL5GX~)9LccZF!;?m(fyQ!JbgMgn&=Z12n~VN<-d~YOpFLKFu0z zm2vLI>~icKa;hgwka-MsVop;gnQe3MclUiQV3u`0zXfV-(zIB4>!X2NViX?ljokYL zZrYMoPLuobZcZC=6zHfN-HR!9f<@op-;|qTp^wyka5~cf|6bhO3#%i95SyM)a_(dJ zhwFn|@Z`xJX9bh#C;Lrb2oAdwSACIF!474SzbiMTj~zNHo}}n3NzB`+B$0ggtOp@a zCFZx$F-OK^9yjvfhsg@>Ni?6V(~CCOB|fKtF9f^-h#?v5@Amh zh(F%kV!*$V{nUS&)UA2=t?+Ql2P8K;^0V6)&fM|7bS>S#kB~Q%#SZ%xBxnb6=f2d{ zn$Oz=1>2Z1+lh%hLLD-*64?{96@E!;{CD3FZ{yoc@KlI?D&Ho3$f-hm$MflyLSd64 z^7mT1i(lB;v=rW4&n=|cP?3Ckztci|o_0w_qs*>OX6N0HgQZgTND6_VfW*r$n+8a?-LJL!11C=?!`X&Q`AY zC-qbU;ObcR+GL zC!TU_@g-KnH#JXurCQAG-ir_sS}{%K6YvoeYZlm@eaKzRYBR-6U^)DzqDHK0l_{JB zLHetC1c`FuP)MV|Wqg4v)E-y(t=fa1=uv;mpHR_ixO&lR*{$v7`G`l>OJ6c*&aOB6 zF31c-ge*14OSlRzbr({7;k1lIB-=yox){!KKUyU;?s-&qe)N9KJ-2$)Vm=yl25p7& zXkR~5c41Z2JS0DNK>!kgkjCh>=#O2#MQ`mdcgCFsMe@@&dmtSSUC1rQ0=3F}m}LzZ z%Kl|`@alp~3^8QxgN?n0^Hqc3{z?@|%y6k0E@g>l{4~thOW?oSMc8{yiSVqTO^d${ zE_eH$swS_yU>aM~*=RwkoW!e?W(Z}K>>C;SeMZ9K6@K}=w={&M& zV9z9R?26q4UR+=7Hw(@Cb3H1u7#9-WUQTDbkW*?eb@7(V7URmkeml?XZV3Kvz0;;q z_)hENCxbo^TRFyTV$@a!i=E(w!W|t2`B&eO4`x^2ZR9%_KbT&gmP2fT%)0VAeu>6;A+ zDM@?>#z>q2ic!mD6UBVLH#xFe1yKYWP$Cv8+ltfeavU|DkB*H- z&lhxm^0R3>Ux|NlaPb|r3`-QaZL(-gK$fs5ld?h(xeBMX?t89`ni>M5jh!2#^u@Jq zfr=I`1+0FHS^l=JZ6wo=TImY1R8qp*^^u+TLc_Qv<3n%r#qA)_m-;sP>8p^KW?l>+ zNN&9Jg-|F`)=GF_rm40`7eOm{yFhL|>HI#u7*t@_Sv4nV^Zm4h&ZOHsn4D0mu1ZoDVh=~-`#u~Qz<6o?t5mFsBQ^^ zre9}A2%&6z-|HjGb?;jutF)JKL=v7ptZ$@-_H74AgWS(3Q@AcVnRu5GcJ|FNjc34ndiG^g!k^ zQ#m$)8odH-d4q9(i*;)o^WAezU%UtdBdNS6LAg_n>|rcMr`%iTm~?H=DJl2clTUlQ zUq&S0JW7%$p8G*CD2c!`>piyWb$l2XF|;rY*~Idc0$Qal10aaE86XQNhWBwsq%Hff z-@1_!_0F5ta+9(xbv!dvA@Rwv^XV|u7jld0H_=Cl#_`7>sbfCdVAoiKihhAN*vE@Q zl1P#gIu5@{RFY9^-)}XJvxA{4E<|BQ!;WYs)z_w=mg*r_mZ;`z4L|+K<^+=b=_j2Ux>K%xe)&^DgSex>-#s=JRLyTeGS;^|QGJ-+y6j2oxTARY_spV_SL&wf+-( zX9(rU#G?##XjIrvE>T2qjHGF6e+YWNuJW2su~4pZdz6Ls&5*&Su_vF!zKg4?-W``( z)q5zFCKa(egBsvB0N#MRR#!LDJ7}76x4sINEn@ z$RK-TiEjhEGgz@i`tn2lI=(loK-ns*WAI1uIO5c?Te3AHeQ!7nNA247qigtxcIawh zU%QyYEY0QmooKA<%6Dr+EG+uqIqeIi<`t_9&;1_ex>jwIO=1`N&zvcKR6%Z#Lp!Fg z#?IxxjjrQE$)s}ut?WL^$c>=oXQWeCS?-rmY`!RQdf}SgMio);pgl#f=w3131qOxB z%88h>2yPGP1Zx@Gf|%WEOWXEazW6qnMLPKwTu3?}hiad{Mqq(D(9NXXZ*Hu1!61c; zRU2&&d;fVbnx+H!S`T(FR>wE84*?&M>uGA2KDNk-MW%3UAu)1PzIgrd9EJW6+m!Rn zgMAi#*1GhLj~C-V^2N_1_IAi@bTDpwK*#K~2TjX$?ez!v&?_6bp2O2=4hko>dZOq zlS{>9HE?~`BrqI!+tY!}wppzVg#JgKR`Ep-_VxT=e{9aKY2%RR2~ zgsvW3*SC)Cg$7?uvC8H(M!0S0C4{}L;w6L&ZdOY|yQ4LpC2v`8C=XT?P$JJ+;?ULQ z@+&bbdTj~3x_HahfRP#Pj?_4#yy`>*yaGx+qA}u2UZvnIzE@|H@V7<1+EK60i(!11 z9A`;boy^27+UD{ab4->`@011e^wei&ym3CSYMkvdwDPsc8V+X8aZz}M@;qb~Q=>X(gzq=UzrnMh?LMrj zKDVnlE&<6N(unu8Y)7r%FPZ^p&3-VDUC?hJgPt_+N^jtsr= zj2bpCOs^>yr4;!)GAY)(!Qz6N9T|iyX5F;II*8V|AJgvyBdzKM%PV?`-(PoBuJNz# zqVulqp`-DC^3EyPSS-aM`Gf0+kJgZ3N?Vqy^bZ~`aw*O@oNk0#oMpGh1zq$~kXKcL z$s*_7*Uko$J;KMD5-zZ7=Bx;iET1`}kk>iX}7K3Vl}_UhWDVF=rJ09#>N$M1bPI;EoeIfzoVa z_?6@PMbFB8610Vh_dAs73dkZm*Xzjx6EP)dw9*WGTda0WTgZv97BF(=cV9?e!pmC0 z?WSy~qikW3UB6$ER^>d6o@>1Rj>?sv0HxPCuf#RY8yfWTy6W?R!23v;xOmPMSuLt$ zxC-3P{^&Qiw5^yr-*CyKzZfGl{-pV(D4yT$g_TxS$V!!^y8}{Is1ly9^w>+p+@PM*vHVd z0DhEj$^`Qq{4$RI=_ziHucm!7zvW`?mZ^g!M;ymJ#V=*!_P|36vyh`e)>-q>d-nIF zan$}aj)En!d7XQn)6UqLQiRfUNi&bLFQq2%zO`B$zS#bHxVpZm z#8x`IxYQr2^~{}jugT|$1MB&7^_Z_TWn5%wv!^D{&pZsk*ty?zwcQLu;qw}5Tk+?V zoyZEtCP8_L2O}BOA4A2R5~I^4hMD(vRe5n1W2etUkgKuXFP)G0#Pc$Y?a94Lb41Ey zi7);7*M%hLZoa9YB}rUDv9mRqwjH4AuoL+dA0ZJ{&Bka)Z?IU-8|IcqE3wgdZ!GWT zTBcdilHW`oZ=Ig=w{)sOYt>z8^>*&I@2ieRs)VjppT5U>ZZO%Hl11=dZfxI+@a(QI z%ks1g3Tr4~qF?i+mTGo5|IO;rE2f#ecGk*UN$bR|B-O?~LMg-f!AM^_5WdklQ-8l# z5wRUCV57^XgHxNo5>nKoUR7@ypVCvWfofTsc+16sTKulOvHBvxKCV_&1k!3tLg;=f}}Z{R=QoHCr8-z zTFe59WVAT!o{GJZeZXAI`2^}>o>=oPlot1Fb!cp|{C0|<_>#&!TJf@%=5>u2A27-}+6pc*N-reNdk{btGb=KU z5?JI|Bp&K9$3*q;bJj+;s9C-;Ys|B23O0L@qo?fTFo+vc^w1*BQteTb!k!whnTfH} zMjBJ2%*yje-biNpmvOig-0PGdI#S`Rja`{}XyZBa8k+>Uxtw0b-1P-Fxb$$3Tdh&G zvNYfL<;YSdMI9f00f)9tkT{~r>oC?=@=~4!6v+yHCL4urdhsH1ECbZ^6@{5O;w47J zxhg?b4^tRZ_mz`V?y~8SkzXCh!dwWav$>OeU#}HgPny1TcerVHwPfHEUtHb=appv( z8-sqP(v~burb-<3xFYOwsE7j)dYmW+Wy4Y@xlQlPfgK2OVBVQw-5OuH4a}yqN|jPt91Mpy&<*Tl})EtM*^#HaAjK96!&v}C{) zp5@ym7)K0sCLm2@M9~vZnM2zRpuB_FFv&YO6DRSk{oU?V%!ihWS@>rB3a*gPE&Yp+ z-)=xjjMm@4&t2u-xr%ts!NiU|!~v;?E7Txu_JZoIM+>nMs47-SPP|fTb4pFB>>00V zUu?Qs8f5l79i>nmf|AU>*4VzFWIz zgRoN2$-RgP^9adBaj%8oZgaLxa+HuK87@1oY3&MJ3)NUdzx#k?Qo@C7AC=f?q5<_W z1!fkcfR6m-ybNz0@<6+B$v5_RpGT}WNI2|7S&@ zsTFb_W6PaqCH#Dj5%k6giNZx4kM|Yw&+?n;Rof!zh~FEOsPYl(^j79h;woAyxa1mS z1&8X_4DzZ5x$K6+!?IaRi@-DPp|LeaH1<`@uoj)$`xckU<7xqF=9+rTgRnAMn) zYq#M++OvV-^6|0hQ$o9YRldeq48|7glhO z6%QZhB}3+Qh6TbrOzuRh83pR<&bF(>73W8m^oA>-;W-7yH&?A4GfL z6wBDNyk5Lz!RP|NF%otqOqRZ1;%s=y)RLbhcqW>?|H_Q5 zX7Q!ITC*|bfOE~aRdq7^nFRWoxGV{<9=~li9`G%Q-r;nxY|_U}-`#8KUNe)IS0__& zP4vBe=4)bBM}A(yN;cLmi<$>ODAH0+6W^ zjnakup-R7s#bos}0)ihb8mp1Ap7jeEuMSWuFmGuU5+~=zC!gW?=5}@TIbw0D_ET2K znOl7%qjH)rwWyc;jJZ>Zm{XB_1Cgnlm@SnSv~-a3ZXu@t0o2>iHkot5d*#=8J!!Tb;)Qld zMrYtnb{eUbSmJ9UUDL1L^3mfCbW4Qv+1V~LdlLrhR$`@u=%t58WsB0feK2W5#&|0b zY=`oC3a<-SJPtDAGp87@__Q!tlCMQ$6#VPWo{BL9?)P{>B3jw$wYNK*v5_n_-vCL) zl87AYNJD?B#}|?!O~@bD*IaRJcBH8Sw}n{MjkSJbDDH0Hyfd4J>O2p+2jLQ$xYIbw zCUag-zgh2#{?ugk1w?;QHE%6i*(}v?ZHI-%#_{!JqLeoUYn7@KN$k21!!*X>HV=6b z$A<$SGRRg|XL_!($3eJRHqTDpXEYjU!Az;)=e59JlbNoj#9J$68g{{7yY@JUghnWJ zR?{Hl?QF>hk}RdS=6o65s~C4AG(L`|2vO*jo_E3ls)ZT&F z*51YzYVT+Ub%;`KwjN?VUopo>&`5p8l3wnEXcy-_^ZtNyeQZXhUP>EzI2t%;@pzKb znfp~Tj5oq$h;MCZE~A^=-rQXxSuQYg#Z9!Lbi$C)(kw*I2=dMCpSp3|^>&*TVS!9+ z+@?Ns#HFOFY=^h9%5Ce+ta>ztrKGx%;PANx&!_uR&lcVpP<^znMIS5id4AJvs~v-~ zhDe~On`lwb$kM~Pg3IRleQ5^xyRRGRR7mk98m3n9Lieh=@HHrv#yNEs{maLM~4W8=ju!utMnoz~Qdl$zTLJ)?EIC-}YtJOWd z{OPlF8!U}|?{4j)hV4l9$40ku%GPfpy}-jmNJz<4p+H>rP3QD<8J-QxzP%c0q?O;~ zoK(`st^9)%D@A4aPO#Nwa(mlht*TGw#;X*6-7>CGc?yE6FHYe~F54%9K&`ioLb@gghP zi&T>W&Az-3yZO+xhMNey(mf%JhHO5rYD0hyETFrATHL7+sHJHV13AiG!yN45of>fc~YI_<%rgu~$ z2FKaR!5WR;SC6MR7vkSp&%S2uYtgidg?8K>Y4M~At>%ztcsO387?hFBp@H`ehdjT^ zo1K5N(D|ih{49EzuQxqwqpy?rbPgpvvg}%zB`GK2%ynCaqQI0h8kD@8$cyuP?OkqY zjD^u|3K<=&sE@g0lAnH~SJXlfcf0epw~=DYlI-<{NT&uxUbk5LlMZuux(u7AqK5P2 zqx*vMQ8w^{+d9T=Sv*gPvC666pOu`IZ*-WV^(67($LTGj;NZdzue>RV$|qv+$}&~K z%NRmv(#|r3p8SREw$dZ9Ma%sFW4)Xg4@pC0Cp#pC>!;tc&LBNnGSsE|Y$76dYf|mW zCn+ALDa%Sp70oKD^KWRR^IfX+ZlGEgzn`VnL%9CTUFl=${+4;Op}3>|{NU=|6UPBIA!@y)y{SmO%{ z9tqDj$I^(2Nn(D6sw@Sq5Pi6? zXJ{f8jpdDsPUS*eS*iDx84&L3yrENB#+UeZd;46%qw{a#I=8%6iEgL)>Y83+dj6T} zb&d%mFei!@sZUKeYvpR^N9?E5*M$A2x5=;V^3B)qz>7{q`(iDi24UnmL|2@p z-bGt4S|jvCl&qx94u*1Y;l8T8$$+Ti(+e5M41;g4{mkU?ZL=6>j78Py*Aqa*k@fV3Q+~^qUF&1~rhp(^Rts5rZ zA@1f~v47M{UdJlwtoLPEBP9gxJJP|t%-vE?E)KjA?%2H@a5p!c71Y52Vgmg&69%iv zISg^1uUynv3SwCc66KrUP~>rx2&aw8g(aBH9(S(&~vGw=ogWc5;V~Atdi;UgSN;_A*xR%uJ43uB$&zhh{S1andqoV2J z?y=Xk_`1*Lu21-^*%_H>K6A7ccFVgan+lHQ#;-3LxwzjTyPJB&Z}P#Ft$U=xjC@)4qJyu9#Abr~OdbgAkIb>9PhRcoEJHKgK9zeuT$SUW?mTYb?a zn)>XEDw?THE>+b0Rz2*Z7{%A~GGwNP%ikJp!l`ijS>i@!#NE45NpLlF_cmKyce z-)vk$x*NoDmbtP{L=8_?IE1bu8tsgQ&!GNIG!4YsS_bK5@L&|Wu|ghE{hEIC)je5F z9lCsj`vM9T*$A`^cn^&`t)=oAr|8H=aSd0m#f!hko%gegY!Pp!4w_>_*JpbWVYXymoLQZOmqfyT5Ue%kb7xNt)+k{l;=E^utwCEeC&^ zo?$}9pp>=P^{>4A{VH9ru++5J`Mq~yOTD>dyG=3mhY)EkJuri%i-l`nHZS0nPqM4z zcx??wXS<18x!etmHx<{o%5`39fwt_S{gk$9Ov^Qu@0qp^O<(ga$muUFk2y<5E!h${ z`VPd?aTMlsCXL&!ay%34%2iTq)mKz%Nd5kHA2vG=gh#Xwaq3 z$03vXyEp8d8FFMIH;43PyHJhe*eBLPW3?BW4VgY)+G7Y~=ie z-wHR6%fnxkMg>n#Cex_R>0+DE?X3?iv!gGhO7Jf%FMTW3FI$BlQN&!?%d)_U9kP`U zT`pEri_OR^A6Rc8P(^p!yi=-WKJRxWR_s*_=Z@^zhV0nrja(GmG8;dJn6lw-^sPSP z(N<>!nYTq>?)o~N)ml~HgvX;JGRm2~dwGA|W^UV@#9-DM8{v)fn*=7;cYGC{x`Vb8 zi7aJZrXAPpE$jL{ghi9)GH#RaT|=9@R~^MbdGWhA3sDox&|J~T8Pmzl?>}x3sGi=7 zi2++g{>NUHd{E^4jO$xQ&|m89V6`FZA@TDbTN>!&F&FaaX>X7(_%WM4d=!`Q==ytt zpkgc;dr9lcVd~p42Gf_4)Hfp5(c)5#77b{xj6dXcXq$*ji0fJVz=l4h?>O=qN2LNxw~IFuAJwkl8PFB?o1fLhE$lQQvPjKYi)3alf88cyeQ6Hf>w902Cc_Ge zyWXIOeVi_(w^FH9+&eVQ7f8x9!iMjHd#;)>p&kUdl2#N5@XP$ZL~+lMbS`UlN7=0} zLwKuvv57=WDWtn)YYL?h6z1ef&lrM-;B>QldoP>y%4=^Hx_AT12oi=G*Z27x!HYUHd5ctI@Aa z)n?07rKb_G)3MVH;JhfMU#A{04C~bWzS0(shZ{&U(o>#DeUA?L#S%TZ(5b4hxa#AV z!QwCH21+1H0bG3>%n5NR*9w^8U9RYCes~`5+`2wx%KG$k1zOVji-BfORkgQm=L(5Z zp9ko6EKT9|E*s7}k*No-5CIW?VS_!s`J7msK*; z@V$k=0h6XNE`stWSY5U#XJ2~=UFxw9l0()N2jLl1cebr+^*?RUedIP<8R_KXffd`98ga>Fb4 zSjRHsww&vp2|{S4oCLn68TiNs)Me!Z)n9j3gbK~v>Agz7Na$XR-78Tm5|YC7)lMAf ztnPF)`Osb3ThQJ4QZ7#H)f&Ow$zvC9(I1NAjj!Nc5ZZ&dchUbyRt~* zu^o~jet$E>a1pt)V=LCTK|JE?hSy|hu37Qp2s>J_N;gy&)y%->p8jRF(i``8@JW#$ zbM{V%B9o*&i z&&L%=^(PE}ZFB#Qzp+)*|k{AWbbz_D*aIJkp5hyM9kVH}6-;0SR9z-ERHEGqx| z_3*(*N$m7h0JFA%!VuQ1xWHGAR?06Fl7Pwv7~JY`hA&<04>rNO{&4Z(;0|u>|L4O- z@}~@JVuy1mu6Gc91?v9_Ov~~Q0r>49&2bzDrWG}XSerm^+=f~^9u6*`j6pQ~*?`!#-RSEaB|A_ra(?gB(El&yc}ypE!;~Rrk9UXo<*+dr?+j2b8w~7QspDYfoE#5E zds2qNw2H@f1MtiMo*xE2Q06#zLmMkwh&{y7#@>PDN2vVo?}v*~g)5}@8SuyfwZrBs zOS#kX2s;=;t&PmAO%A7s98Fo+0Tl9p0ydk}Dx8)=40=2VwWS}SFi;g5aC2BAUs67f zL(Iv_%Jo1`hYvmPeLqqZfJ_I;5H{vZRF8wbVeMoE9zb@48Xb*&{q1mP2Eg?JPdS66 z^vmak)^XUf5% zUq0QY$H5x^xVF`SMbyUnHps32T&wqc_$$91;nM&HtNbz%*ffPzC+Ggzri`}Z2| z;U;~5-|7o782$(Fg`JV>BTr)Zc~kn~$XQ}Sm*~OReSxRLW_G^l(;$O93!=#p>f%VH z5c`Kbst|jVqcX#l8g{9Jc{?4@z_tLqkN=G3 za4~A6zHwFo{6T(9o*FdurnY8U~^7d(n-)#)*x3pu!~WN z**Jme{P3}Bqkm*BIdCFi23RN3e|}nm!;#Ys)n9!9+6VyXu+@is+DXWk5LX)~M;6&1 zKMsf2yyWun0f6=e1BdmUcj>2u{~2b-(PVQhZ1Mt{G(aN^W80z^e@OFJ%77XjM@J&{ z3?mEBhyY4hsdT}AKD2cGUrPF0X{Vt<)U#;J1lN}=;r-KY!Xq5yKivXnKPlI2Iw@t2K`>O5Lw z_V#E%Nq`9)0k-hH^Zw6S4wppG>T9zlm||DKObE+?)O8Yvn3)yS+5t?mC!{eVA+~4| zpsj-&3}C17-rhgpI9vda7!^r55G~T6E`x1A6#7pD|9c8QAG95QCp@JNdl`xz%%7jToq&2UKUU+5Pk4iLf??$CNj^L-LDEKqtW9YgZhg9)P-fWqoR?dx%% zq7Yk%ff*=bj$9Y$eo`h~43MRPreP;(o^Pi`Rsq@o8>ELj;0MWlOJ^`_E)YSm4k*8O zG=UN58ULs8gLX{$$HAz>DXi|PHqiqa>;MgH4MPWa=J1IJ*z*U)Nzgh4Q2*P9jz0U$ z3D7@h=mUzsUb1oc=(!4rI}pL>m%tZx^u7ouP@DuE#jrOM3@R|{e>F}sfbq~7`KMxp zos7(Ej#K(tJX-QWb*Bgd3Dzas&YgfQs-k|JLf~5Kzf=8<4BLHpfxtR;)c=_C*ceqE z#{T>H+21D% zEWyus8)$HFbr*j3Mn%TcVjmu!Sr=VpYeB`NivR7SDf-4qH0scU+4MLe*bI}b1;PAu2AF{d#su8*N1%hHFv}l1Jy2sOOH~^Ss5Mwg zv8Vd++u?R@)SN3p1SA3=vS2H{ex*MnQFc12VP%nHrlSPjp94GQJP4?101fN(1SZG9N3+jWcVQAu+5Gg|$@HlY}Rhs|I}VW))`fjF2MsyNz%WOld= z-FFvu4%YZF010d zIt}pCL7r!TaZS^>WAVW&u)q=s*mOT!F@nw&C3s+VDgnU?n`WLT9EU3hGQcszEsZ_1 z(FIh|1KLPfqhh5U0c#DpZD#VLGyPw4BmdWbvN^&r?Uucv`@rq3!L$L}t4idYOmYJF zkYUHGA)x4kMO4^znv~pAg9Do$e`X^Q;=yDMSnhx?Y&xFK`x6#1GkZ`f0J_7ioZad~ z2HX(N9C#3HqgnduPiT%g_W*gYbJGV%Q3}4W#&}h5T8blAv+s-Gx=(`gl~myOod2ls z2=KqE%%6>>BB(hJSIu^P!-X#(Gem(Ppax_A=hNPLEcDTkd}BM7dcY^gK!XDttAt=r z=g?g6*JvRwPzM%a7qcVg?j-MN`Uzmceo(`}=9re=)8Q(E&2p&yQHj1Hh=w2z$Uh9e zu=p55r^7$q+0S_9YZ3!hEB`AABMqO7uWDv!L3Qwls_RixNrhT)GP;b{qLJV*m9#k{n;KnbXy77~7fBN8oVSgF`EPEbt9*6Q`rs`L)AgK)|^Q*rw z!NG|y|5vWVrHUVmZ!`vOss-E>wyJ+|7XCyxl?9ty5c_}RIh>==qm*SG%mXih_CW0Z z@^L^t1&56Z1UzYFYGr145)p@4rt*O>fuQk+oyXeFA4_x)#z$9IqO>=s56-B#1CN5u zY7YsHg|&p5fLL>2k^S-WaOFUHXCAx-z}JBRU`w|laKYR$dEzIyI>gcmdK^P!joKz3 zh`1S$HN<~WJ{%l8*{K+Q`tDyOR6qZ!;%a4J^Y@#$e_w7GHN-Mi1AIfEQh{~g+)Mw3 zQ_2x~#92X?X;g+-P`A`w{=LYsruq*|hZ||NRs}v8sBRp51z}WZ!Eq{*zf|{^#(sM7 z;Z(NYDpOE^wHE(1OS^EMit4XJZpS%!~idn~T)L4WPQ@&o#S<8XL$1g(qKV91pqmB7|7zTjNsF_H2s{PD`C zpkc3L0>PLK)`PFZ*jZihG!$Y`V~CTb;}1c8G98`en>*)?0)Rm8K+1w;TLovyP8R40 zw!d#<|2-s&quGQ!fLwK87YcU%niKo)Y=@i5$LGF30jQ-0z#Ik}FCFry;rf|kU=(>c z)$Qtdw?$yGgR@nzThU6O*E?B>KQ`D-!BfSYUwzQLF9T!2iu7FfG(0L`eeIx$KLwR? zs-yon5UJx|bF!)au~Z@u`-7Q`3jF-(eMeOoEzR!`LV)jm1LDBW``OSx<~YLRl3vo) z9_&AN0xy7_+7eCwl;d#Yd$&|sHi2}I2bO|h`!gE*(=r@r?C+WFh-&PekoXF)F`WFr zbfxb4=PZXyf>Rl=>xUz0 zYW>|HgQoI??ov6CMUWT72O*g8VViwAztd42FrLtlbMyzIy#q_=^k72`)}!8nM0y%| z4oD6vy`z?JsDd7LwE_|B01IsU^XbXy7>@U)*6WcsZUKvM0$+k%2P8`U6a2&N&58Fa z<|?BxUbqcD#XIxmOqf+dp z5000hKxeBU_+V>bw>STl>u?2DPpy?n0jc7FR6;OjmwI~|CNl>^d#EGybYc-ugbRHH zL{Gr%1Z%DRhW|`?i_PFpxOg6 z!M6QM2&bWvu!p!h7($LZ6M*Q5T}}&}w;#lcD9q&MiF_J(l>=y_gCm-!l*dcJxE(O-^T@J+gpF1DUBTp{- z@t|F82139tmek<l+mm-w!*<}y43ku7_)f*4Vrh2Np&eV*$@_gkO*^1gfvq4S`A>xn)bs=XXPtLcgFzcU zhCd5}g9z9ImZ)3kzY!g=kTWlqFi`*&CY(rrH$0`-eaqoj3kQmWo#O?S zPfK&)XUBKov>(a9+i>CFlt7mco3?N@{+#7-N$6>cFh#+p1P=M{t2x`+r{OppHH5b0 zlPnl@99ZpwErP?%jzv|5fGZ>ZS{nT8*ONSpYS@iG280Hf?|x&Fu=|fpN4VDD1ZL_% z@t_Xmf}IZ~9sV2B;kt8D)3RO!Nktd;_s9D^Z=aIqaA3vSJDSZP0Ik3xCv1IP=Xor! zh>gpSqzHa$n3_3QKu=t=y^n^6oCK@_3WeXOzJe{6Vkl6|!ENdW8KCkvfCF~m z%Q;8m-*B-7C*nj+ZEPHlItCMTm;DVI0A>bSfvpH1<(&j922O0+m{6$!aN%RlV-@q+ ztsbTl)v0?FOP2|aYkSId_h3rvuO5`J4d};O3!$yD{{4eCEuTP20 zakwSD($0iQ1NUnJj?M6^F5qfQPltRs?yoO7hh1O&Uv_1 ze|`TVEIM|_AE5vJrqAEE%71;W9W1(k=O3W|{YJ;%(SLnM7c6>6&mW*4@u1JI*QvvH zHsk}RM?YNazuu2c028B~a{wEh+yE`tZ`ZT`F8!~U9K&MhE&PSy{I7epf5-UsYFeIZ{s#c|{!B#~L@*hG SXWGF(rV3zJc?;xHxc>w4y=$8Q literal 0 HcmV?d00001 diff --git a/deps/json-20190722.jar b/deps/json-20190722.jar new file mode 100644 index 0000000000000000000000000000000000000000..6db21f623413dc643a66ffd6f9eb511a21baef31 GIT binary patch literal 65003 zcmb5U1CS@tvf$meZQHi({ncQ?M>?^T>aL{(Vbe%1p1c)4G0WKUR+g}URptdQC?U1LgZ*cxYK>7z}AA|58-8ss@UOZM|6om2kMm#G)0{q|fgR%+ern+~ax2 zBky)f1gk}yFwx+=yU`rPH@8*iS*<=4ibfVgT^%P0Q)wTpdh1@pLB8vcp(zWd06^0Y zU8WLuC+2PF-jIvH7aJf_(ky5G5KBU>_p0Iq1?0c$; zZB5a%@{9=}0JChF5_Rr>xeUTE*NDUqVnLBD4lhul4gy-S4}?B%%yvdOBaeXi9Xwl(rQxo{_r- zck@IbYHo8)ypTcBCEAxuHb&*PLXShDGhMx20ADxcBFcnN$Aa#|d}Q#^sY{DFp(1g| zEM4uTE{;!U^38UUkP=JhTCL>TE+kcWnN<-x;hF~^C@w-vilkSr=Yw|H@uUX*yrkwg zIm0%LWWX$ebbw7h)Ko+w9qy!}L6zj9su_SJAVe~gDN{yBvg&Dd zvZxrpMU(6%kN;Um;gM6Ns8QC`#Wi+$@pc)rcE-837ShzJo-}cR$$Z@My!1td|M%kP zxMcqc36O<^;%|{mtONl9asdMZ0{m}#$M~=I4*l2m|I^+<|9%Jw^^e`~SMHz3|Fa-aJ%gZ&P-sGQE?7LnA!aH$2B_CCk8o+u_01PwU?Ss||WM&)Pc#L#&`Ss3EzcFe$PUhX_ zp~BAST=nPoQq4`Om_<^RH!}89Iz`6U*2QM}Ov!E8hp;KZ-kl{qUrOD_#LMdU1n=Xl zLeA+)QEJPRd)J>fRp=Yb-8EHzj1}T9EUC=(8GM=x%YxrdK4jK-lZSbESb!w~kw9ph@_Q#2m5C-O+}yh*=;fo6?Duw6Dzt@_;PpxrEy^4JsIw4TW$% z2j*RLh36p1Fl7^hm4Zv;DdPw7bd!~ixVOinT#21aQ)i7Yav*d^^5n&OPjP3OWyGgF zQu$^ATrx4Rx$9G;2dQFBa>pJBgDT+sL&k1cNKpffXxipyo*Kd*T`os69*0Ief ziY$m&*aoc7UsCaHF%Ju=P&2@#VQbSB74BS1EvakjDVFQngxb`QOax9Cqocc>QDyBT zs=k*sIj>yAuL9^i4>yYpSCZ)&)Y8r2+a@0%5N)cIrA=vMX~B$&@}aR>b{c(j;2@KA z7rzHP+o&-jmu;H=&=ewBqiojH`z}bT%#%o0)92?K@bo>?>3xTkz=N+PA2hbM*`yHs z2yvv3<_p#`S{sHrXj1=m0)$eoV6C4q&;5lSea3IB*&vK7`5|oZvmZQR&@lAs zG4xQYu^{0hMwF+k3O%9#QimJ!f!rmcbNE0`(tuO)TDDBB6wx%1SQ@ovRRHi6L zMD!0*V6K!!(I-0}ou3-n!F!7hkY=Du+?O};N@gV(*V&XS$i9ke`N62~cd6HBOA zPM=90evZ-t1ui&poe(ogar8K8$X1*FsR$q!JC8f5x7R1WLo;u<$N3BHG;_$^ce58M zca$u}TMALWX%hT%)vA_~G?;TqywAH{g5QwGIC+h7wpmyVIf)>OD8J^n!|@4!0D442*7imfQ^uI+~u(=yOfa!oTuO3E(f|aek~FgBLC!alzxU%XZK>>l-i- z6}Oq`uP?PN2QzsV4;An`ac;@@DD(fJVgGK|Kbw4I-YS6&ZDlHK{F)N1+T85=Qy1qi z*J66=FF&IXo%a%uxefU}66@%&?|iGjjifpO(U$pfLf>(>`vX(4?bxzkPeoYaD`?o| z$a!>rWV$`W`9rVUy;}e1@pVlgS`rz3#&%Qo^5dsd8ZM}L2{j52&0*xqGb+)cp)2_T zj8Qb#eJjt9At9q<`pz=kM)B0Qqa7i^z7{<(1LPTl?l%9$*J5!5yyqf`I9RDq zy;+?gkJvq${I!=9uy}`UTG||Ec*dB_C^19PAF`wmeueeyvSOLa@8`!JR>RAGa^asA zEbsZWr^0j0)B?&{57FG*wt&%>3(8NymO~Q zgPU-(2wrBQXW;}alnqiAIG%)`DaC2$E*0&IR%ijEf4U*;olXW7%8`C`FBa zB4Lct@WCYB%3+l7KH|Um$(0qS?qcBPqRut+&imJno#evmrj9s=BUB)AS?{`oOkDVo z=h$d9gK?j!*R>OUnL`twJV{o$or@_`H*tSqA4awDZ{Xr@V#<%4aJN}b;l-7qt2a}s ze8PiXm=+e4wDd?1Y!FUeM5ygF?Q97n2%+pAg)|!d)P`++&_b z!&vW4N$mE)wR2?%_Og4s?&Bwb~PaiVa!4~a9${wXY+cx zEQnUKl-4om$b2Lr%+xHQiX@F)Z**Wr-U6z*VFrRGVZ(&s@2pMi;YLtCGlsH@U1abk zvMXTmXY*g(Fre?kf~?sLNXzC+@DyO92nrHbL{utzK?jy23dZp-q8nluqH`* zVawj4d1+`klda%xVW*k8HKt#RkBfocFyGsCkGnGJ!cpiC^24A{1t@Ou9$v6vg7k<^ zxY9Ygl4V4KTg!LHXqdhr=vCKnIw9?`-_!I`+SF0^4?o}Y4Ec6}QsCTUqsH$yN3wbb zzjpI)VxIHk$%}ilHmK&OCM)AYMHM!w_9jf~%v&Eqa#C;fO$EQe|JS-fgA9AKkX$dfWHEaFwJFqLsx z{jLn@&fC6b^f8T7#y{NAmwpm4mfv(x4tDb-Ybp+LIjNTeRs-J>m{4MEihv%P`l)vC z)bYsTTKFpUrmyBmhJ zD(lI<6PjvBfq)v;sxoU3H5QxZSKHi7r{ovgv-%X;Cu!ST z8}{y5D>OCvp%eO3Q=C(_ZNa)nMHBJo8xOD1NaFj>ItrK4FQAqe&tSg+kc6BUsZi`@|Vw-N7PH%=jaI zA0-nHLiQU;YJq5ZF=JYU1K?S@WiKRoz7d-9`)TvoJH>mVy+-i+iXf>yu_Wa-Krx)A zjZ9_snvsiP7KEA+Z&V1WOF?-7P2i7fn(mOIW`0+2GyEW97gGrI1FM(We%Z3Ax%~D` zRP1m)`OsJ0g_$yFE{X;98KA-n?S3~6@9iU|%DH}m+)2^ysBv}J;gpRD>pFh|8{gIA z>-VIlvWI$(qL3q_yDbcRkkb()eBMD*DW;d9WNG9~wgRjIgRy$ZG3ayXue{+VPZ?3H zLIZo#`e37afT(gXS%2(FfQ#}Qu}CJkJ$jV=pjE#&tPOlKwVB7;^4k>?2JzU_PjQ6L z?&#LVJ9Jeyr0PQ`y^7or`I)ouXc0rjmLqXHRiduYjJx{T8)Z8f!SZ^MEaQdJ^!n{# znasu&!(KYR++S2W0hboZZVxkZ2*>VM7}9=w;JURukQ$mOD=YZM=6fqzoWW@s6E+0( zYMWRSE?inxNzZ{zP%fv7O)c3Sf2s=?%~z7pe>ASDum-l)mr0;mgU7nt6b+r-Z7}Ay zE}psoN*C_1bNjujk7G;DVBX=730=x3Hulb*6r8o5Fx}#{+PBeDlk|3`nOz7Pg5lU4 zGkckD$H7jxqOG%scv>H|<$lJ^vidR_5@!7n+%*;H9wBRwC}WO1yW`Lw;=TUDe0`Fv zuJm~QX5KBUMZ8D-NKA3AtJS77^W`Ciiy?`bV-3Yyb`jkBWyE&r7zN#u)Lu74yFMk; z!jh`O=N2D#9ut>ZJkL&H*WedP;%1?{0@(%7aoin<|HU9 zkR=|gO2=lUFFph8e9=kU?rja7qpu@WR>}bzooM{6%dRq8SQ4cn9UtWj^(U9rYUM&+QwOs~gn)bZs|a0ik>*awfO0o<(ugOh!Wl^)LL*U= zUyoR9VH5FiW`!N%oFOPHFV!?4r)psw-PZI?5-S6c3RH&SIAR?H<1_7q!BD7E_~KMf zSFZBJ=aIb6VAm+#wr`8TQ?JCEJR?kL>A0i3yN_u*JH2=M!{G|$#f|h=J%>g(dt^0i zQkhLClX*RhvQ?3(rVil+K~tmWH&ViEdYdokTmX%D15L0_%1{|iy+q9*gj!_1cC5UQ zA3*KQdkcakZ{60U1=39o+O_7@vH3J&Lz1y%&umBu#Jk})dn~nPCQpZVf*~2kO`?(*aC1!r>K%;LLMS#_HAPYH*PoC_~)nF2=cQKZ9zFh0FQ& zV(>83xPp#gYETbd^~ZIQbQHyf#g&j`X&5R!RYnq{{yxBN>d@3i6ltLAs@&N?7wB&_ zM1P`y;D^si{e;}nk`<91b+2AnJd8Ps&0^(N9>nIfIh{?#MR7ONb*Qx| z*yqs;uJzt+U0k+7Z#2(kQS>myn2t8rm~}nv9F5BTHC=+}Kq>vR@dM&@<0Gu1VBckU zCAQehfy#p0WyA|wJ`@|;Zfh7q#@&APf$DQub74A{komFq0A@EeA9E+kq)b9_hE8*% zFk}dRrutP4v!r!joK>Td16SQ-GOj~Pe<_HT_yG%iF)?IyrrYVc`{bq7T2xkx)}UFh zEPo##+Ij)MibR+cm)aJpOxu}5glOjBs5-WToY5wyUi{i!Rm4pUZ^a2rkEixX5C5~B z*yz?IA1&zi;sxHX>d4n8e_s@z^FAR?shifw1N4aO+UmFr@Vg;S@vb6n@8Fro{s7VV zr6^ADU@oMNk-mM0N1;gPI4FhQD>ZKJt|Q0{-+#ak`X0FpkneOa>KlI8iaPg3F!ESB zhJ;3c8xhBNR}#l7GN(9vC!h``o(DFfJ-L;uHs27{g_60n!mm}J<+0F=Pm*3+EtT|G zI^G1(p7!Ori4>LjF;rQ1$8KXTi!8;|S~^CtC;`ynJWzq{EoYe1C-cLHKbrbsmN1S# zRA?)@;kCr8UVW`4O3a$qh8O1RKeqq0^rv%O&jMaKID_2U^&|TVzwONS64o8=9fmY^ zQdIX^Q+C8D;WCy1#r#xOHOb!5$NQeIcGuJ?^3D#BE;7bF8C`4fn$=Xep-Yv~F^Iv+ z*{p1+k;Aj!$vuU37uUzaEC$80<=O2ld61~WmKMf0M^04ny@O}%baZgaUDb}fGy7fj zxk8GP&e`_X;1uO&Y2T~qlJB*e*_JAHOuG(u1Y{7X5Yb0OrnH0??@Vbf4M2S+{!EFc z_((SyrzF^?g%E)51vag*sx?2&9F@>nnW);*`y!x1Zt7l zXf_CzNYvbclCin+*gR&*>?=VB-g~gHWNe3VE?GF`Z|0H6LR`EA{y?L==QG&J8xY6A zoah>CrRcscqlCPtAty}6BfXq33p3dWQV=E zcNe_CeqDwnyz^aGi2)O@-dvoRBXY9&wx{Bj3~A_y7aRp0;soI&R~UTmW)ek}T|!uQ zfaa7tc$GeYThAN|JC5>8>(C2<(5N@;jr$UB5IU|b;ue;VQE9e(F+v#KKP7%D8jC{2 z=t1$YgyxbFcG;VAe);7B*bl)!E_x42d%&-}*@ma1#`IZtJbE^W zl2&mdvu2rC=ji$38`u&cpAF~yrl`#Bq4wM)xD#rY65TrbL(Dgu8Vjhf3M$7NVsg2q z^Pps1!O)A9R{%0k+?s@WyXz=0coPAX%-$9HJt(#klEytukV3{{4&lXkjJ*^hfiVRp zf{&bf!nS)fe@L=B^5`#wB=^wOIu_sC#*bTO@jjz0O$lfl0X)XVtRq_##`o9*wxC~wdX3F6sjaD&R;7om&|z;EfdF}d0Hg7}p*!3`56h&tuOrS)=05QF?|(+Z zLU6qEF^IpB5bj?i;lI~xvH#CVC}-v3`ah$gnw|!#2HFm%919a%C{ZD`c8#4C3dntM zC3p}<6gpfaM?$h6qEU$Spqv~9nm^1ZXs=s~Z-jPdr_WP|f2p4AuU=6i_?W60?T)kQ zjx&>6m$@9T`^z>#Al*??c#8yO<|<;M6L@$S`^gj3j=zP}u`*?yp9pQmPZ?2LIIhLT zW(}CK?MuiM)d zI>><295TVsYddHkv7JBC5iK^k;0=;*Y81#7}KHyu?MW z-N7y(ls^5?aIg2N$OacLID6+W7<&~j`r(1>_~O-9O!q?8raqVO`L4Eu%1Vn$65?a2 z(<&kKOpa_q;lY)0;pxjtqI%)cVR3d^QzMABLNa6I*B`jPS$dMapdv%~Aqa}mHBUac zwQAA~o#r!+IXD)B4vWXG4&3ZZxNh#8rdho9`U(Ko-DkG<_<$o#HrpnBwn|k=-|!8} zXp$*F{Wzbj2Ch%~6SRN;i$f=F$ebK;oXV_eqhqt$nhl7&b1yF(m_7cJdHc|3zD0}@ zXY7yBAs)2YSA=>Mx9=>^cNmMCvZY}w0b8t;w**n{e5$#Da&>ucz5SRyZaiJ6jPjMY z`|p)EcSFh?b)el5>|VH&I#`ii^4hc43gwD?ILJN5eKBYV`{~Y@SGLWrcUa80mwcPR7H`& z`bv}benf{@q&G}WWK0U(s02y`jn4)o-as z^4)*nK0z|>EwGT*#ZzT8_qid;l0C(&4u@6mG~mR8_i|J9X9sj340mlM&_P|-m9LV(6* z#HtP22au|TghaSm(rfFKAj~sKfuN1)@5_J?Ve#0J%JQ|j64gy@ z*%a`2JyrP@_7CoC-s=dQH`J_Re7|m*YkS@};`Zl%|K$Oc#r#Vc$xfmBNH|h=h+utz zK{^~a=lsDCAE9%eek}r43Hr*ZU@cSt`iDlMA0|SFqh_Nd8TaKdGa}6b#lRT3m!dtp zG(FHilv8$$3X}m;S)(%JLWqx$wWCSG&Mm|8^z8s+=cmKsFT%EF)B5%x2%U} zUH}fk0!4FaNGhIvRCu9F@MNx5(^$(WJ=!!3&rKp-*wJO=n^N$cvBj~bOM#Zn(QQ0xMn@t|h07A|qxsZS4UHZ)n23o!=YRwdskfl^2?YyJLT6T_&Yt|QR; z$B|eW%lW;G40?{TikvdtK@_$qn%c+afo3BlNjRlJa1_~GC59*}FuP-r)7fCuFGyut zKoj9V{-|ae(Y!zr!g^*vvL+#%$mp)t*fir^MwK)-*Y3m3(!7A3rN6oF#9)i6p06sJ z|8B;6aX(cabc`47-IVTu{aJl_Fo2!v=|<{HKMwk+cdFzFzn1f&I{?3}dM7^H!3gdHo1=1<;(Bhg zt$YXHTjJhiFkml-W_YGtt6dm_t;p80NIt{H1xOirOItcrxJ)u|CmEQ&|f;oCR|gYuZ|Sb`;1O6Z1dz=q-Nd00K`Gt2vlb*0x17Fvs63n6_cf{5n?&e~Da~ai(Aa2XcR!T83 z3irtv+i{PosW!dwY62O~Rk(B&)q$f8T_z=v4h|xKb?>92ir#;=8OozDx^8q*P*3|{ z<%)asdWVn4LZ6@yXzSn^A9nj4G88)ZdQH80NZ$JeWI)J9GVDg`L9Pjk>(xtFTnAVj zR&%6>-wuCS39_Yd(;U>cC026=vK`^5weOBvizsYdABwL^Zq#9=y68jH@q~Et!=bTr zm>yg}?u4|!U|7iswZI9?zl1j{_zk|o;+1VOg=?opm%wM%+uNmyt4eEbbjdf(JLas% z6Wb|az`Bz8YqhhQQPaf0@a%POz~DS%CaM&k<^s5VJ_;s8Db&4sOt`cJcMEx7D?<54 z#BZj!BPfad12PDvP~l!b(RLVoPN$%`k@}Q`nwTFjE6ecApfQAXNua+BBw5{=4A9#H zay)~*DhosP_*xF+Nqp-0Mb{%yD6bW&b#?;Us9ID^$XUB^y`3}YsVQ?a(6=lA6VvLU zpw?O#Q)Lab`Kdb7t%gE>%$0J)&_wWO!!lhe%K zt<2I?z6NKLIV@zgX>tUod|p<*Yko=s^hnJD={^wa)$@Dqfvv$ynI%rm0tFjtN&7o% z9a?ql03Nt{)>?5Jb*X3Rdg>Pwwkj)lOP+|h*4J9gd*&t~bRNqPHVrW+V5>78d3)(6 zL0Vv^HiCgG#TJ@bO_~GohWxWmM6*rdjP(qdTFRTJ z1-v4PuGu!AtE*Nhudy1Sy&K~Hr0podkEv|nrzkqkf1(LcJ_!cir}H!Kkq7zGl{Nn{ z_(wiP`6n_&CpZvLJj}nk{(sM>;QYJmS9P#4vo~}8j|kwVBCm+5gvMV7m*Z|(;-fh% zOs`fzpZpdGL!Dm$oTAFs8kE`YDM!f!Fu$BOyer$6I1H=Cx92B zlHbkQb(!tTW9>ue{RDD^O~T<}DkrHR4yeLm(_M1J7bS*+r6k{PX2M1%rIEl6Qc1OY zWraIa8FBlHJFDE*pGomqYt(qWAcrW~SCtE!Ei}uD*2$tR)j6eA6X}eO8>o`qZVA}~ zL-(I~z&aEk)0?UBj?3{@We}w0#Vxh#^pZK77(aZfu!S?)+I}iYFW^kECpU7qKs(2R z19k{4_)fNVpQ=@8y!W}w^1*fvBNc=X~Wx6Ng(e#w(SVxc7SGauU=$EW(|TW zg!8o+#{8`b#=Q-2Vig(clNax+_g&g)w!O(p88)gb#vaRox*;JL;FtSZx#Ac%1Y1%T zE$R3H=Cceesv~nFIW5P-mXiD3g0b2@1#ci0p}G5zd6K0ci)$=dA@as98veZd^!k*2 z#Z!!J*Yah2wam8h^ENp%3+_RCrkNHF6zzH1%n<2t2dxh%J)LgD<#^^NVZH?uYa`;5 z_(P5Ym@uhd0cf$#pG{a;9Nk}@%WyYxi=OLyPD+w?!W?EbTqDx;#PAnfdH}JUL57srKZ%_PugO3R3<*UJ`M_Ow!lufznFsTxpU7a<^P)t3bn!Ga80+Cs+xE=&$`kF>W9`bb7LvCcFi?-C zJCl^dBhk%-r}$`?e5>cfJr}&=6MrA)iGZ^{^po?veIYoj8>xSWuVWx*R=qX z;%M#FIUx@7@e~X7H#|P${XQr5iTbX41tg=%1H;*fgV!BQuffGY71q`Y!3T$+fB1lp z#@Mab-8+x|(E#DyFe3j8Da5@A;#WvT{Nt+4EC0Z>jQ-YW+Akjcv)*%9B!509egpgY zdx<}VlG7RZJ{uEhS?QU2JiFJSYVA5>IPUeK%+Ss;r9!%Wq{Q_}jQ`r^ z>+0fd@8HIZCPm|{L$rsAyNwLz9o1QKgW`@J{FPwXUB(;2v}!fy>e5JxWkuNMIP(Uu z>9(inIm;!83prv%)=e>)69HTm*?|@0bK^m`{C2H{c4I`Sy~xKlaA{^=cT%tCot|@6 zj;(_oLxSLt?AjWuix($7I%CvcCjp?GFHSDMjx4x{CICF}j|SwS$Y-aZa-}R)y8ZO( zvz}H+kLjZzb>{Stt`jwT9ywaVIu8#lLmV+RHea;SZV@Cm!9hIeHkWp2pyo6&i^;`R z34fgvIU(^SHCtZFDr<(ct!$1D^MWAhZh*IR&=OZGk8zf2%v3MkYvKC`18(Hd9gGH* zHB(ffgNAxLgVO%VF60b1Cb~1=nS89NY{eNx!L4|#&dp%TjG^HjAz$BU zRh{J1>{v`M_QOqb1P(f;buLnZS40>kUB-c)l((d#V}W4F$I_Z1L0SbKf5C7&+lq-Z zV>K;sCY!<*t1(-cPE$hIhNnl6ad9bM ze9FXSQf9_eU4Lp>yd%c4*9^3z!%ElhZ0y0cy0|2aqP!+KWNK8DBNDh2&D{Xd0PuuG zXF~`_)->QPw|Xcjwin4mMHG@Y+(fxIXf3U<*wi#yVQ;l8U})oBUqs}gU!N0CiE+4X zrZKr~a-`YepOr#jPG!4n4J*8MhU=#=2s?1pD-wNruRUaMAC>ZpFgA-)Nt8h^T~cyu z`gVTucm`IvJn}hXZ;7Ce#ofp3$!Pjq>PWJhX=o^B`#Nf25H54nH=MtChX}Q1pM9LZ6p@jhaYCrg&U7yR zbTjiyO;K|HNd9OtqLaAVdn&(9Sx3SpN-;lDfWax1#;jl7J1AnTaQKEGB|0 zk7Bir^XnQ;SuvRo&B|tJ5bZNP%grZu^uBz<_*GfPc*EeLAP!I#P~{PBoP2JAk@I9n zx>Sk>YlZ(kE|DEaF1t_@Zt}>}b(kfNEE1-i)iIOX&=FK7LITTlOR|8$9@0TI(ROW) z=fJW5?g$^M7=F4C;4tI?=L7sLMmPJUbNhOA)y zlmJiMnBlpcN7wn0LYGO3rZXDHiUybmpm|20kHfi}>T?_>w#rp=4Rf*tH1C}9897nY ztRT}KCstS;Iujm&i!PwG0pIp_LHr*2q<&zn@&?@vM}%9Rmj@(97y5DTlfIMz=M7rW z)%#;d)q0NKE7KZ_PAGMwk;UtIkizl*Sh33wVgPmfUB7f~Jl^5M>`ESg``W48|16@d z4uKVg_|)kA0$(D9oqiLH(jG{;FC|KC&WIaJicAxi`2<&O3QI5*=S%ZS^#QI=fhPmK z!PzaxmAx2R0H+Lr%LQ+7cj6{WtriA|<7FLeh@lrdhS1q(=4Zotjus8q{*Hv0RiC7q zApE9hB8P^A)8`JGcwW?<`Um%7N&U=(m1cpO z7*1+dGpBsUAG7W%&YrDeQgJ3B5}NiRBD;fH-(fHxPDRm7#ny$4V4JP3E6WO=OI>Gn zAekkmlVbe`!;bc>tvyA+Kr2V2NNY_+N~oH5dBYus7nv)@Nw?d8CTx!=D)M7%1Mhl@ z`m5GRAt;xCN@638jBq;FN{@6F8j`FfmC%FuPWg+ zOlugobiC90xsU!Sg1cKNiQP68o?=@XUksH850W&44SZ7;=1kKYQCAAn>bw_!vcP!l zjIfF~+2rpr5iJCjiems~p3~o@#&;QM34GxgIzF^4T;f+(vS;s9L%_|#x7EnDd%#{S zbhOZrEDwdzTmTX4$bZbRh>0$8f6h1|di!oXsN)U`EScI=2tTPCD?Lh=#3YESSTu6x zDNJzZrr4OHEJ&{jQmZDMqOE@D`57aCafAp?wik9|N!eu*=2AcE)&!~*&BX08w17^J zm=yKOM#QhS$~*}1-aVe^MvXj^Xd+#iLs?=nm3MkCi%dvbtkCGp5{EQ<$U%c0HXYFewqcCRa$olcM)bm)g9PN zzwuw7CKCiyGSlp!iq4){Ct_T97D{v7AI(MZNy{%j^mD&(T zg&3!cN1X+(DZTb=CLBuljoN;iMvMEyPQ0lXdc~Vn@wwo}Y8D0$xP@q8p!DRB^GJpB zA`Aj9NIhWepJnX*#p^S+epoF8zZu?flvmt@FJe!NcoD)m%~VtEfs?DPpnn1=G-(VP zS3%lbk{JV7S+rHwzSu@s*t?%?FemtFQb zgH~uZwS+_V#3c?3cZQ_NJYY*!bmZ2OBHU#$WQG2+QF+iv)z7~LI5=fzWi%PRPE#ik z{)V4?(~5*I-t?kQ(XV@3*}J6o8HI1uGfJX#2e#zv)e%B!T7=p4M0aE{hNpxf2d4O> zKBVu4X!J2pu?50}s*O@0J*jd&BGYxqvun~k4oGwUEgjPRhpa%p!@O!TOqp=DZLX+@ z07f10>C!tX{DR_N+|oL@OC0XPhJvbpg#WlxLG!@`+A$H`L4o_@g4aD zLCDqf52|}UKm^IQv-!MP;s{OL1&9=5!y4yF=bu7&&|1m{3p7k8|LAPG6= z|As;6-@w@7rLv)XFiCBJ;m3R(ob!+>ZwJM@7?RwItS7oIK-So)xDfqF&KQIv^1WF> zgd&dtMFa9X_5^X@gz7^`a6;Itnh0tVUJuBgsu6yj;(uIaf2-IQatd*S37~vZ^BmN> z{DyTlN!vdsjxMr>fpMc}R~!s+MVQP8zF^CjVksgtUmW*vUUannQA4E(g5$&l>zWPU z!G$Pc1iEZoB<@Qy6R(0K9Q^~_6^2+5K;#sOWoaGe!7tu5-BM;X)x~;4{$HL^ujdsY*1h27?Ue)w> zps{Gt4CiCLg7MK}kAw5UElIKSfXjB7=LYYYm-*g&OLE z>QgNEM7;CCILm6|oOxvsus?ez?IsG;r!G1Gn|j5OJF_`=Lz|#RXpkSa`9PRB=sGsu zBgO0*#h9YdOqQ!RMUskN>;3KdNlC-dsI+dWynZfcq@oVvffCAz9NHBzxbw{#$~Y*i zg~s|_%QkW?Xg~5dF3(Q7_nY$WPd`;?ZTO|H`-QCgC9nHk`m8n95G(eEg2)%QLAj(Exy*va8*$|q2Edv)&+v?(n%<~RwZYutd!sqMV9f^8H@{cmapFl7-aO8rf{mRLD#MxRk*%eCRs%;IK z$!sop-0EM!$#@0JL6Q~0d}cgoRICMJ87A17Nd%t1|5pE@?g7$|U_MgGX-M7v^VzAc zGaw3kP=rcu=85cj))Ojfr#h>UQ%g~-W(Bdr@u4dw%rD3vDk7aRM9g;N6v5fVEeRe; zI`Wy72+Fq#NA~0wR_MnxRgpvNfa2;FCk^8R>V|e&;u`^s66wJGxOXhfl~F>}JPZ#n z3XeQxL&wGemqj}!cR1V+G=Zdm!^Zf>jda>Q9a7XvdS{w6B$GX|(N+|bw2j5ixuDyo z^ao@W^PUvi3>k|PmrBGLO^?=?Uj&tiks;{P9_(HXc`)nfDdoTT8e3)ETL`ok$gf)F zDh8MojTJCkm^F%2U2*|alr*;GE6e@Mzttaq@@%AR5!I>sf~l`qmt=CwraWKnYPU#y zz(R=^FB8EPr;k0;q*LAS38Jq?c=bN=?af@e;Z1-hZ%HM#1uJ%dLeO{*)ByikLhEh-VFsXGQTBisMykZZ}VI6+$skT{@E#M?lY1pfXLA?Y?v>5+BVXiVD=&?}i zqf9iP3ZvN@}YYs!wZk>?()p(M7)jMo&7mKJ*U1>#vF_$>2{i_uBiTUFFV<$n z-IYLfC_>$xgStKYR_u-q(I|jnK-O6nvz@pIUTuDxDZ%4!y(`m&wk(3n9-+<{@W*^l zqJp(M7-0wEV<0^4h|2F*vt80?2rXP+)L`xouN;T+Vj(R)0bVXIn2ku56Wb(?vl(V? zUzn!{{!Dyg;zX4Y@)CXaXnw-F)t&3)v zW=Gzxl?I$=!U?QN11>XRMD^U5CfPx)bybch2_!mCirc)5&81p1kHBliMSsR9ERFV<&m|5*sN8=QXc_Xp00xJO!Q>eWu zXxUiOerniT{zB{i5Zt$0;}dQF9GJO=bw>}OlvEd#j+!*}hzTfG$z__mm5nk7X!sXT z_bKpAYlGJS~f{O=LqfY(bT%dkl6d%q9G}w2vaiCv2e{U=& zN0?tp!2a6}2hpxsF#hGsep$&Mw^{ALP{2*y*y)K74w6tmPRya3g&Hr zA_t}!987Za`)Pc=wB8Z5jaTuXPU6|f*Fl8=t}~57gsvz(#(tEc890sIdI9aD!+APcaUTKSc-hQ*y|AeSs$N_q$_m)uNxdeAN_D@+D z?2ExPXoJ(bGPwj9@n;on9k(&?IOF=2KxWU25?68%7^ce9qpKG%v}zg&W|=3n1A11S zq^JFK3zhv#cR@Ql_Y&*57zUWJvHu5O?;M;-^lpvDwr$(CZQHhO+vXcgoHx$Ib|$tp z@x+|q&hI;?>VD@`-CNaN{m1U=>Zi8Xv)0-}<-EQ!Xyg%@tCNd*Ta#+Bt$6{yH5khE zgOaLcLI_ZviQ&uArYwoco?Q|Wh73~5E zp>8>nYa#9Knx4n)?kP-gSs^YOW!vY(lHLh?ADv4zJ_$3bgF_B39xR@MBWy3=S>!*_ zmus2D%HGj*Kc`)y-r?%hj3Z0l`65=hO~T))9Mty03jVv-iuJy6kIR-xU}Mt zyzvU+K=EuX{uJJmGs}*l{a(=_zc&{OFf0qnTFzm^sNJTdG#2|K z3Kq$OG(HV~13U(>UEARPPBUW(h z#42pvZ~oVSKVxoanR(zx5G?pgI3V|x@4Y}5RmFjS~N)Z|a)ggs#y?lM#^a}Lp3)j{*`3Z+AK8VvSbeEQeuFW9_ zs^gzjH@AuY&`h>1s^m)A86y$W=OIW8=>ERe6KqXTq1dh%xzD`u*OcQXwak8TED>B) zgvT3f@BD5X^uaR4Ffd29410Bl1(yiQWK}{B5#{R^kT_k`t zoxTeH7AgsRenJ5FhCpVK^ zg=%Uv!~Hyn8T+<=_(u#k8;RsFZNL{z+6vlLI zrMAxKB1D-H;hz+`Qj2EDFh6=RIE% zUP4TuR7s7bhcl-T+{71OSm~t}-KtTRV{Qsrv z|Gn@(Q=5`L=9VrVw$4ufov=@xR2pVMi3;|Hk7({-u%vgPg$1B#qd;@PYKQ>lyJ@vp z>#VbH?{KEJvs9?Y?wDLW zX~&T#JT z)VB>2U>6y}Piv512;2e;e8Jq7+JXKhwK4s^*`pMhlV!MO)xRApPVcVsSbrB2?uU=_ z{?M9%ND|6n)krd!#hQ`@(nL*lOxf0vZD0xtkE=7J^ic!K=JIJ)w7!%S^LUSE$u(6% zB<+a{+0LZ1o-L9ONi5rGvP;|cJC#k4E3IMxj?I*28LSH3vB`7^Cd&drpyoK#QC68~ ztDsFSt$In_?-4W3I+=M`h;{F(&yX!>IlGyO8DmOR>y9<6pY2CNWS5mGgm}}}O}4?Q zj>Ah_KNRL3`Ts-62m-lo&jAGifdK!%YxsZDdjE&OxqG|f&oYYqA0*a3ItLVtHT)xQD=SU`1(z~hI+stw3hss zG~)t2D1Ly-mP&o2eosZ)rdEBc(5BJoJAlQz-u>6iF)QjrAg}*T+nP~h?^oNifcwXf zWN@BB4rZ()J?0D7!lX;fkEDRU%R$7~qM3HPS7zPqs)N6HK_v%N%m@axM^?BUlc!jO z9aHPqk;q$-Z(M{O(>~EMo$BLAxHoBY$e!DbbT_G^$vrf~N`!*VG8diNzqWrI1rZ{j zy*5QbM;_=Q3f}?5Je>aN(XoxT%gVIJ#ohKz3BRvT?oc&ukK1dR%kd-;e~?$ilC z$*hx;0*795qQ)f;yhw#eGpJ8mj169M=Znxlg=^Ov(*EQV=k-TkFrVAXxcv}Mj^e}dYF)TvatPp$eE}cthQ%V>0gbO_UyJLNl zL)sI(?g>b$RHy7&-Dm*ss?1zPMpQd{I7bue`#kj0)u(u|LNAT~lRoB0zg~c;eWC>5 z=EGoOk`p$}IQH^8Iib_J7wEE1m0qYi*<(D{Y+seR;AhcmLAY&c^2$+!7Y|1xJkTg5 zj2S(=1^l|bjJ0VY+>DDeDAM{ZC$~1HB8_d_U>@kxQcn0Iv74O0R=(~;b{Q!)t^);( zJgInPWw$9$aq(8zYTa!kQ@y%_cN5bdan3or^LO7r^^k+1hobDyQ0+VDw|~Mrji8#)+FNSZBTn$fcv{H# z&7-@vQl%_2vbKmj%YDSV!#SUHaAS4$tpU@6Z+NC-cv~L-KWRUqzT!F%dKjB`2fGcX z+1fMm5$JXA_9)=cCHr)=gt~huTBFQW)Qp5B5#GA1wB0+Sep@=q$dpc`&u{WD)1Hd4 zu<5Vg60FgVeT3I)Ug{yKrt7A`Ga-x*HzlH#dwiPjd{cKlELP_7TK!`_JMYK9>}$Dl z3bDAbX0d*l^hQ`dfyq)z*lCN`Hl#i6OT&gN+#0S&l=3Jk}*5GqG`E zBO+mNaDU6mfXq@Dnx%X^W`I)b+?$j8m!nWLDbd9hg0xot3RSdg8EFvCca_fEJ#w3{ zIxL)f^+`}87Lfc`%Wp2mebFl}@u?lH3;|cMiqY?}nctL)b@W% zM2>(}LViGDEb2X5W%tivj_6!d13pZJGnQEHhbWZw>SqK16@sZUxgvrAejK-M^#YZ( zK%LNa#^A#Yrx~0u2e$YZLP{&n7uQ2gmNb);3*<`((P8Wm+E=^2cVzvOZR zk;74M?2=(*!$)4X3I%*Fj_7x}5JXxvS7kwlg5lU-`kNtK+upCqK$?s8H{Y@nKN3yj z+1f*)f*yukKE|_e?uDa*2G%BtBm$HZb%v8eJOO#s$3Ql`zbmK1V}LRvcUh15+JiCzx({!|cgZteX1*m?wKyQPOqk(pegb`Lx zLHKn+ zKy6KxTKvono4rkAJl(%*dc^~w?;)t?BUGquY*jED0?m#qX z!PZn^)|U7Jq7Pr03`6nHE?ZbMgIcB zgOa+>K)eEzc z-sM~jpx2-)*FZei(%)uup()oo@8fzB7HMwX7IY!b)fW1Q3Pu~(V!NvJhGj3Cen|Bu zieKEk*83qd*CO9iKd~CQqZoNBjNvDl^;oTT(DT0Qzn%Vtt2?H9!TL2oNuZf{-CIE3 z9cNFV&6DIPQ$szcH&2I|YF*1aHC0e=ng@A6-Q{DJ>N^y6>SCdfuqnUQ!}%>=F7cz&mYwmpISM8QDZ_qW0UPYPTQ(DLz%Z zNcAXF%YbFFc8ow09GTwt)Zk0`t|D+1*RlbNe5&Kh!id;dm-6)Ko!%I@L)o8@0}MyFzX~tGa8|V+3Ph z65|dwf#wx$_{jSr?ynXDvu=kb<5qA|Gk56_cxf&$+oteH$73`uISs=0nYaVC(_)eu z{3hGhDn5r7=?R0opJiRB`O=-jHPwXF9^X@_+8i~B+QEP55BHq2bfTlB8*$9Id-$|d z_RLx;NdJryycJBkYX=1q|7L>koPp|Om{9zxnGarvvM9caZ5(C#R7k-DY-r-dJ|W z=ov&W8|GhaTvL{13@xhd*r&Sq<_@UMX5?x+8!{D%O=MZ^6#IwK;?7;YN7Pk^>&}tU zPGUkk31XX3WKL-n9`rS~{J-|Cc+;K68M?p`w>h+z1kXx{@0|Y>Zb$fczES-=*p0_O z7i!6+ItRT1KsV)knIa2@1#auSs1p}e3i`wnjnXeCb9XKfRgT{x2_}(0Lhzo;ve^h@ zF3s8C2}&-VV{>E&$v&Lh+5xO>Xg}kaDy(f0xp^lWISZHxZ3eX8E)Uwhh=f_RTp#jA ztJ17wda#GrekRhg4_4fP`UAIiccP69X4#?rxx_)k76`iWzJYqNgY%l)l zgv6ue5be0=@#q}2IyoKcgZ!ZRd8JNctAWQ3vf(H~*O}F@8(t;Jl?kQVb}yUWQ!xzU zmWY_5hEHT=smI9ta%o5KN><3*|F(nsDhfj~Iat68sHR_kUQIZ1PIUev& zknSvP@1-;_e5mjaHn<2qtfUP^#~ozpg{+nl{&014pyrb)9+|w}XsSWT^#(kAINtI44b+uzqRDIK^9$P@r6hWL4hhLGJR^=j={r4~|Y z<(>pO^?mnb=7R{+K{!zSsLKVSfgX6Ktl>DsL>=?_`AGr`53LY zZlqbFB*xyzO)1FL%BaiPPF5-ijvpMGJlrNowJS)=HK<5PtT&F796Z_D$jC0$UCGSV z)sB@s9ApCKvtXphBQOR}3d)p$4-x|h2R8?YBm@@*H$(snN{eK6XaI_WHzWtXDhjn+ zB;>zrQ@4)kp>zKI{>Z=k|26dd-vJW+e*~!H>EQ6+xQD8u^O6Wk;AJw8;u2MPMe#hA z9*Hby_HK=aW`&%LBq=Y%(}3fVUTk+qsuzFC#k^@5UHKHJR6{(5QgzY!ABrkQy{aK|Ao0kH7_ ze$7qDp+HFiTU08s=O#D6VMY6^EUX4iSktWjjlS%IqjWhV?EuM6Zi7;zOlLz#+O_+Q zFzXIH>MNZj5HOQnJ|iZlX?bj$G*$vhArL4hoMFyj!pg6u=ImD2_|u%xRF}4xw!&zs zC8nvYZg2`5dab65c^ zrT{hqA2uzdz%2%05+sxY-QA^{B<>~F`!G>jKt*&LHrk*oEWYEi>7r}*vTgTI!!+P+ zulCRRqXN}XkZ|6gi<%4V#$ErXhMJ@nVGxi+F|rJ5HYq#C%PR_!7l^0AD)rfnfry|=jXxqzS09^!BXJj@7`pFMdd zQ#mU4Pu*OPRQ)cUO$E>Fs>OH#OT>Y+pfiP)z>4tk?8a6xwR~9)verjblER|ov z-eO$@hSTlH2s#0x^EJ=0xG@$2;>-0l&$$%smdmNQ6UgWD%eT(mqN#RdU%Fw&cJe%s zcWx@CwYs){$iAT0L35moc5&M;ibq@zKi%gIoW@YK%?D=Vi!C~JU8z>|YCN=3U6ao|tDk@>^2xl2FW(~=7XAA?;DK1v zi_i3yVBr!-MM$bAq&yp}R#C=Rmu2K~bRwzgCmZd#IPKKa1CVR%ItVxqq3it}g-Er% zrg=Wc@v!rF8%5W99yPm2K3`lh%`P$O&3P{9hZ68kUwYR^_c@EG zUyiJCE?)B?lPTmyjw)0dt!#TccXscs`EHQeS8|x`!JEuvj0!MT9}iYJ7g!rJ7WpWv zaX!1R@3|{^dnGjN`!S8|@ur#{1o%4_F)Vz3&)oH~HQSdSWbKg}<2YAUV9uGX+2CVB>|Jf3`Loi^@W|-`sCYz_iT@~;HkE$9I|(lB z6F0_X%73GP-8iOxUi91QT)@!!Ng$l4d){0d?50efyUT*CSs28-pgShKa(^r@~fI|(b_#vQ%pyV#pshXQu zB3qqPNayH>Z9vRev|T{XSTy=8Dju=yEaZf;kxW`!B8;B=O|qELgDM?y{T-Q@9fIN5 zq9p-aTr#y2VaYUUrtnDUQ}gop{A;l9)I%dr`53+HD3)jji>&0P)4i3nZg1OaKf{WnF=!(0aof@wKegg0n8FStb zkO8In%!gGU?YEXbfggoRr#>6%C zOcn#RVVnqjynY!F_CTXz&88kcojnzNGZv0^&x|)6+&Uv67p*`?$)|fU>Dk8$dU4CA zNXf{ExdPiI9G|TYHkZVjs)j0NF$lN6bE6IDLnov|WdJ^nO_eqd4SxR4RyGOd=;^Rb z_wY8%M+eQRCwe-UzVoG_wrS{wI(Tj50zP}cYDE5&e4weRe~+z=R%q}jLV2bsl$<9p zP9`_6ggv}m_i3!@2**+*uOXyfaCghNRcQbvgsA8&_OC1-L#anhAX!y6cDgm?0S zj;wyWfBJ)+BS z)d_H0(O=nIG%>7NmgrRjY0|xfNT`>`ubHlH%P;e^niz5Ju_@DxXb!ErIXq*p?kc6z zz^5oBaaG<)T-`LJE1{xb7GyXN3S1_GdYPcQ3Tcjh%6@v8R+e+?5Yq}$?YNu z(P*Rk3F{=Zft6GmhDm(Y0^1^D*j%D0-c--Z6n_x-TVh8jYss-WuJdDZV;|$Y>h(bV)--~m>U|TM~$Wj_E<}6RP>+MuHkHUAgtV05f4ouk)&WfC{ns#{% z!Dh89`i?fblzsdzY@BGM^x`Yim)ccVr0L=d zCqZOL8^d>)q6FfNRZO*rxpZrqs@CtExIaG$^BOvf9u0CjFO=6)RK7`hG=8+mT=9?h zL~5?DQ};E1ljy}Ll!K^m4$`}>J{|{9l}ftF?k~r6$!c^J>rI+K! z$8oZbRBzQIbfpsPr`Txi)hXVYwfvFn!l>aG?rNq{230D~ekj4ox*btfgwg=d$YK_8 z0pgmJmmm?4Bf~Xp-i4DzVDlPhDT>z1nyUaaEd0WDVbOa$lpTR9^C;H@1YaLEh1OZ8 zs8SzXN@LCRBBN24wQs5ZT>yBtAGzVzg~e*>Re)9SI4K61xv4f(R_v7W382J4>ar8} z>?}v|)9ma4!whD`4XIK2jC1*UT|ajAjkXXK!dLdY!GQ*O)~>3FOuanjjVg-`eFN#z zFf*|1-Y!ff`l^bCyH-({4^eRvx772Ir+s0W!HipQ=X z&hIGuGUY!eo}QgXopUh`bwh=!_+zvy@DvQ)LcbQeAH7{{fAAJgv?1~W5s8pUG)q=9 z#c+hI_n_%r#!^Pg7nYLR>F*%2x5^?1@pz={rE{^nFcC||cNcsv@D_Y-@X_y4w5fWU)Ml>F zRS~W&U3ja>{&yi2KY56?H%|?Ti7wT+qF@UJ5Re${r*EX_kG*RrLvU_I@y9-|k6rP0 z2mRUg0#brP!L`rsV$h9Wss;v`q3F*Q?Mi)F9;nk>yXligrsGE_K|N;R@If$EAAGd!~94 zrkqI}4(5eyK!fZG-%_;;6-8B)!T!67VJ|S3EcmDzncpD8CztIg3MnkMb!266iX=|6 zm(Z;IgsQdS{O2g_Wn$cg8^y=532u}n4`(`mEI1Z_X$DAAPi0n5I{H(Gc8md5Whd*T zhq5)qv=(G`^i@XXnY||3shMADs`lGY8c2H?6x_!dL0DU_*k3%79W*+1_^W?bo+q%d zsX?qGy^byb8E&}|6i_2CSU-DquWQi?EXa_>n_^{A9cblqZ=4w%>f0j(DQbS2diF$qmp$IcxT}tARY-=JLrA`N! zG~2ogSAyOe&J{@aL<(Qa6AdCPn;2B%3D1(yk=v%p>2mby>Zu0j^2#X#B4cCKFI{!j zezG5XzMlw2bND!q7bWghUE3Fapk9WvQn&$##`ZF0uJ^6qOH=b-{dtLd! z3pbu_WPg2%c*7E7rYusb0%9Suydr)`g?}dQguBa|WFtP)Y+1<+Z;-*6Y}pEmy;HS% zvoa>p`frjjN`w^`s;g#)3z4F2Lxs|8&p5Nb)_-7aPK%(Cu5Ca<^(S(ZwLsza#2PvR zqf===yn>*$5LqaQx1!)496;@LJ4?F=Wc^YcrHUIIW9%?$qG}3mn+x7OIZFw`_h=KP z>;N(k-LE@P{n8iF@xHpiW+sbUe^-RQ%ss_!tG4ogKDwQH8;Ar)n$LLQ+b!->Lx`Ct z08d*O;u>x9iEuX!;$OD#v+n<(J`SK{=glu+Pj&kJ{>E=-iborH^FQ!d?(@zgPIP)^Gi zhx!Ij9w8CMWi`mBP!m)x2xnhMeGZrzVMt~5fnRu~OWPOgi)ZRKpD%7BGtehyzkl_7 zBE9Gs-}ir8iUHrVmH~$yDBi$_`kQln$oSkoxNCW{a6}FDHzaTZ1mT(X@67&RSx|y~ zXvClxra2&1rm+33@ck)5P!5yy>jTs``gvs8hgoL7$t^Z+Uigh|4Dot0t42o#NN{XF zK_OAz1Z?I(7mDiUeq#!%tl~Z#`-H7>M{~1^VPTnkNnnhwK`);Hm4TT1_xwVB^Q)G| zZmyTKnC00nz(>zB7xn>VbjXyOf=afEkWWDq=W6c?J6ur`bI_R5(4|{LVlt91ynoD? z`?dHDA1XMVRDAEy8UKU%@f9g~-~Pie++W7HUpl)V&2{fISllCs8b6eD9M%nWsnr_$YYv5Q7jrIkCqTC3j7ctXy((@ zidr+N<_pH_J zavPiiM?(RhhjAo`^MU`xs1!*DU9u(j(iZdTZSe!{?FDLUx`=Dt)*)spnB_J3gF5ru z;Wikp(;b-1p-4A4QK5Ja>%Dny9E$>mXu;@92+148VVGws(^A0;^^N__-O&HR`qLZ^ zs<8id`6JbuneOFf{D&ksRwnej`sdJmc?&kw{TvZF9l{s)f^Qu7@X?68@eKEN&jl?t3hsV8k;RtoI=~r+9 zRR=g(ArhwoO9!uy(>Ltd&T@Ti19C&5hQ56IB>!Dj1-mKREHTW;GsHGuM zRFT(Ba%V2xzYnUc1>S1X7JMKl2#=eEcB+bf%e*eKF0B>l%`Fi1+vRcx_a@HBO)Gv9 zi0aXnsl zPJ6HzFo`8!(EV3AkLx8%{9=2SOQ|x(+GOlQ6>N)HhQ<8+svf*-qeSxRzjL~(WwPIa zff8n>U=e7`xoF%Qe1<8RTfz%OsvfCTtG>_}5D2Un;g~C)W}faEqCSXO{9chte#NX` zk?4O)-wUkw3S#{zl;tFMI=lGz1Y#k|W^39V65YYUEhlyC?$^jl8p&Hv^A@R{)X%M! z$FEwwX0KhWgaS&-+K;Q2a5dpPcB?45)Uyk7ke`K$*PhkIPoCvH9b;=+8R>*&oSf_$dn)>h zjUyvO?!%ZTts1}QawryUYKLoq!xQKQk{^PfjTx$SAsV%{$g8XR@_U+5LQ9=~?s68= z^eJ8TVr{E(vxOoL8P-b0Li**lgpPskTbC;%{B4+??sj&7#tJ~|hQBKNzeTbbBa$qM z3w6^GjR)HGR#q;Pe3~yEoksURdjW!ZM^M=ShY~@5v<-g!h{Gh1&D`78?a5z$sL8#XkPx+K?t}Qr7<;sXvslWrK*k^zQ;7MXU_v+`F zJpILwSaMazjg2IuW|ZWo>9U~wxCAcDTKzi2X;1m&Tt$7ZEtVG$0Q>m`0iRZ(w=H^i zPRl{7BXJ!wx<1K|(FydpR|XF8(u-!5ghXy*W>#Z51(2T5K0{9#@SW>U>x}H7tPxP`#>hSL2<@B;KcO@xdOrU5~W_B9otVg?He9z zcJ-n5Ib!rt4h#DReSA5+b_R{awmiMwgWLG(xf%rhh!3F$yXdh}fjgcp;Oq!$1{b9i z=Q<97GC=TwtMU;C_mzx$Ped;q+KGu^JS0)Q9!+?e7(c@_n#yN zctqyPT8Ju4{m=qum@P{1zYIfy1;KVHF51EWQXU!qfGN+&yD7(jp((89{bs>Xo znm6z_%s(YQLe~9qnGm!wnPgEuY;1ZUdd)i}?nWH#195SmyzUKWFet9%3#n`$9tYld z2;&t?Zl6B~a&H*ym6{T2H1XZq!TP7!y{- zhVyIGH(^2Dq}jtgzgLCl`O+XKp^s`nR|$(%mUWRQOnOU*FA>vqiF1Cv4+Uhwi>?x9 zu?jnw_yS`Qfs%qTIl0IA2;}PwT++8+WcexBO+U@*=Z4*&(iW~fvsUbx@{=8@L^HK6 zL?A4M$ZWEvun3}s=#B}(cgIr#D!X)OCVo!nEvKVWz;@?jMGDV@eI6}?>qjotKon}i zX0Xrfa``!VagohI%#2bgWT5NTJ)l+sL`0vm?@ish6y5>KMqL7(B6oi?0*cW>LE3*y zk{F*Mu36zejdhoEv#EYSFE(T4JVFv4IDueq!4P?ombWOTOfp3Yc)=oAh{T9(W~s$rbj92w!dl$_-=X3R9ZB zIAvZ0OraAJgqNh4feEnexi(`a;>ve;4j~2QwWXDMmgQ5qHE8V4z`Qxa&@iy%Id=%Q zXED+S9>QYa<|*m*$peN>zUT3-YMpyUZTJJ^F-!tr_4jK0rq(oA0WR?G-8rbmSvb!g z^!%VKNRC};G9J*CJYG@7@|qCWhgVO>p;0$&4OwL z)Ld5%{{q5cYKG3Ub!;s6Cu*WSNmj>ck~^#IyJ1;zcFM51P!>(wxk{-Xu-ab$qav(P zJ8c~EhS&`(pXlsWHtf)fMfa0xIVE8wVRpbYhQX^4;etVXG1bsRQV8xzmaLlEfbtBc zmk#>h3hJa|jW^i0ZP=-x%)Ai|ErQp-92nE0S6}$rchNX8MVI{kc`|ZsCd035<^@Ce zy@UHkmsFwh-9(aMB(rwbjdO(;P(y%#y#bokzeH&OSalZ{$U26qQsZiro=?sliW?xu zc)&T7!TvJ98$sFzcFbA!#8zVobJoMg8cW0{_*k>EDqmlRCmp~_*`$btPa#8QPL2kh z((ElCzB}a6ig-E@hbg9ijZJ=7Kem|_aXZM(cgala&{y?-pccy)Yc%CYyx_)}M1JXf zxon;=N=2ORo;`CyKCvh9SlJp1$%|>&xlrrC2sjenlSC|}EU2zqDE^&N7RMRw`Mj~4 zc&NnySao_hQ@leLL-Tp_MCG&swBhzZvbb`AP4=H8-;1jNuTV-;>87N*`Lw=n6E*bC zJFcIo2D?ig=C*ROMpGd$7<-UM4{BmMo#0ZxD-_ToMSXXxQF+QxdwdC~1r?c+MP&bt zo@>6lYN~say2Wc;+QMd#YE-{i;rZlktSgF8Qv3$1)tn3LiD|Ol2Nh_svE)IcS(r`n z=N;ykG`vWEZFt}#s-#gq@}=Y(F1kqNuS;Tm|7rfs$w#ss<~qbEl7~($f1f0>=e4~7 zxfCnPzKL@z(uH4xn<7OLE=6`2nL?Eq*05+plQ9NE;XX6yFqY7clO7e9vTh2f4bKQ5 zxKANwRr6-W6J`PmS;+3-7(}7+q)Ry22mpMs0PKpXd6t4%?FWVZJ6cP)ZItyW-Rj zWwpoZ7ENXH4A!o%VCfrmtTz|nuy#}2$mXDj{!~l})wAZYD->X}cp!7pA|IpL0{RC1 z{S9f=(o;{4#pFOPxecce%2W;3T%kEHUlSpuhMABy#9~wv8mm?xo;vLaVCcX(7u#!0 zOeIQ57H2***Q%rKk218MZQU@lOyyK>^^cchZB@DN@Q!%d7}(Jlj$yJ^s99ax04i~wioffWB zJ>8FSN;-i0{2+Q?J_PfE)QFElixr_8%Pwb`KW8{ir&xLTL zQ_-nN8{8nAOsd}=adU;~U4=UfpcQoOqpBC->6OccS4{9{oLPTx?9^)}$~9D@$#_Xa zDg0u$7ll)Z_DBT#B>e(zbl$`rEuuDCh|h9*|M?^PAO>-F{}88uSEPXFmvFO;mida3 zX%|BqdT=}cPCV{)u!p|VebQm@_c=|sNdEO_7-!&-;@8lwg+TKsYL&$2OuKn0+;`2( z;O!1d7K=usZA;aV^NDWBy~Dh(xAZ2RzD114Oa%DSC=Ies*+&9-w+-AE`6|knEl;ew z{QWbwCAX?37m_x~gQ;9sS}*2epj%g3b^}6^$aUQ;+!&Yf-(#-7G+{wW@*&UzqYs0_ z&?0ceFx3Gl9tS_dl8d2s-cTk^#7$v#;a^?&g|1-@C27P+$81Cc)fB@w!iVB2OU$=s zh{OQpVa0+B_a-|B7^u}#Nv|32%xy#8OeEbw;$uy0nSx>ePDa2v#L;5s<6bX~K;))$ z@QFs#T1$<%i{-hLr7=xc9jg53r@UfqeW1!8(?R=Px-4(Py)2LN1MHO{I>GnqKw#A+ zL6FE$9mlU5LalLQS3gadM7jjD_v(}9dnGX?6lqCR=aZr?c0h0GyN_6ZRZ@Rd5cZPX zrD(&Avb|sr<{WVH0b@YI%opK}bz$I}eN0ai^mGcCg0SFfa^JEYOYwI4!YsbBO&m{~f*6B}`$8%l(3|oZ zLy8)~()(c6ovr|5qYtEvz!g6X*2gaQF?aX(_wBi4jaztM!*D5Jki5XIdCEzl1N$0Y z8?6z@i-EYjSfQxV3DgI0qCt=2hrGV2;ptI=b*Aq32JJg(JEV^Y8C7B{B#XXVM<#}s zDiB&>Q*IRAB<0i_zr0dZ2E2wduSq#QVPN-4z$ar#E!(0WWujBaVwQ&MMgf`x#^~gb!QyC(pk>g$ zZca^kWa=`a-RYwCs^{j+T$uN=yA@8ca#}s94of`}JRT@OsQG_CLZAVlhaAh(p*H(x zb;u)>Xs=sUwclYmeermg&Q)c?Ap&2d2)~I%NxyL_@0Crlz7c*M81qE1O*}V!iuLCW zlE?GiO%BD6ud_BmgYIC%(PEm2UgIJ+C(!b^2z(e zf|Pxn>36|d7%aCsvv#C@yn|q-`mS+{r6~)+=+kuDtOD@;hM&QBjXz*vs%dJu)qLpx z1o0?tR|i4hN!9$|Us*DAGA}7Wswn_9`Uzh?DKwGVQc_%i81$1LA=TX^XB%8c|}TAR}AZVRp;ZEMt>T>)9H~X2Y$dQu;&kY*^-uynU0Qb-D5a z`4(myqa*G_6v&p9n`E0HRKHy{ zTE7ExLU#*A0{JX{DLx8>>@{;dM4kwq_MV603*vSXy);??GS(R3^Q8J&NhMhH7nSI* zkVL%!B@W0GfnYSVWoh6Lg$5dB-UP8sQF)sCKvFX{K@ce@dmV!wkyM%^p4Rd7NegP* zXp#=F7qfKH9S3xAfXUq?;}Ls9e${IfhCZPy^(sTQbik|s7KB51GnlTdc;1$|EVa>D+t|VOh5hY&vn)0W>q_fD;g-BgIO{sXKZhJH;juDrn0q*vX-t!eS`y8Mhz2)KkL+QTl)1=MH^zkY zOOrSQWc8DOB4HzV#CyMW2Ir8=lSH6o-#pbS&!ZSECsnCTUIBS&mud=(MC^o>U5Um# zVlwwRPgmzS2`~E_Lb^6{i#Ffy6@ZVCVRFx=8(L47P?C0I^BTiH>&~7o_9X3EMWg!m z*WaXllKTxhLMIf*>P&7E7n`W*X^c?UVcoP2GPHw}JLa+yL~e0Ld+@c@0gd~45SJ;| ziZTF38;N{}Kbd5NqJ4xvy`kN1n2vXMCVKr-{qLgaOJsN9JEoPl=$$#r^$WH`j3zF{Y)Ycz6=S2ULe9R zpODGJw8Eo=Lfb^c4L5I7PgrFnYIM;lum4t{2s!pvdFzkY@JCKNc_B6YnkW(+0!m-l z!K-N(oJ+AvSr>c;NeB=g^u~J1=@X>YiNW0Y#_!mfa!xJw*=Y14OO^04DU%0Z<`geg zNu9o6`EP}J#8w0?jegJ&*FFXjaJsy~{EYwb***>$&Ah{plcdLi18)TIP-QzIr#mS# z5mLWkH_7qEPP!sY@%Teu9=A{8{yyHd^rqloL>|q>8ubTTx@YpA1Jg(jvBCBG1bq}B z!b%sfHM6uQPz5Z4YgADCWEiECKe{pmHX`oXD^JCz=h5)|W~E-?%A|0o3%2yu#i<(! zI$pQX2`!vB>!dAPN}#ZDkBm4}Rf5cBTR%XuTraa;M^%FJ7v@rx9P_V>yW=Zsyyqk6 zm?!99S?I*Mq&HXM`I8oLgmoB046Nt6Jf^vPgb_f?_EfDb4DloeA~TBE*Qv9dQ(e}1 zW^kfuWRZhK|^y@O;-yH z+X$EuY67`##mW`l9iQAPa;_AApe4+6t`LVm7GSIXQF3vKe|boQpQ4FRD)|#ddrxv- zoheE^W4ff#jrW*Nd%c!*?cng$apr>y^+P7&)6DQ$>G;q`i5v6chl4&?;DZfB`)K;% zD*9Qz@`g2+xgz*gJb7f^8Uh_Ei4hO+0Iu+vNzEM8P0Q)g@Y@W^gRJKj;-(p2s1m=- zV|86@ghtYm><|(0Vrep30tOL(f*pP~6!TQ2CtBz@Dt?ckXqdF>(3dHbkb|@>U|*373eAzOM-%1FxuZN^ zM|~okDa0)x6v7G2?pMaE?QbLu8eB5)v3Fn>g`XaPNq7h)ctg)t*{@rRNrnWJJ z*Oj>}ETLhf(d{nHZibek_csOHb7au{HEC!j{-ugE;C4c?OnVkUGdEy$qPq?dfcB<~ zHm!Ao@S(l&}Jo65gUyXWf(ds)jA9>(_x*7pV96CS#|0`AyhJ)x0WZuxG_`EHh{fk@=E(q5{y_kwt6PCTPcGl^h zVEfz@40I-tm1$X1lMiGB2QP$8a34DayZ~Y8{UVq zUGZBv0n;B`_i=!CbOZ%4py*$O?~%WL((r7)cy)5j#kF+%6^rKjx5KLS1arVwZnxo5 zxQl+SG?f%M4fA>d6K~na*a(iHpUY0Xf~+c%gkgP(w;-dXt#=^LL2pnQuq^kG^t7G> zGiXsc=ZGW7TensOgSkIq2Tdnf;Kkr}tbF;&*2RWy1o1+#@k-$fBl3QC5vK*l(StE# zk^JrjK2b{7lIdaAVoEbDgQrwonv%m-Iwkwu2gK>wo|cf+qP}nwrwXB z+jeqdqhjB@{qMegZ};dPW3Ny9%N}#han7F4UeE7IdTN7E@Ip`jgXzCgwgR6^9m!M6 z#$S^xKe$p?GkAfVPt3;CV`hSCF5O}t-hM*w|Ca#sCU(}(H){S3(umSG)ap?3q|^({ zFu4}sbf`%#-xEkO{!}ON0>nzr+mA9nW0(9FuT7Z)JbK(dX;&8jdB~QutMWWMWOaI9 z5cW=-ut8-flpupa+bk(&mC2R+lcP9#|4&11aO5mpj>(tNSHEj*Kw}k~#4hUHZ0hcw z-mGu1)No8Z&{=JNyso^Ld_#lg*ja>K7V%{mJZscI;yi?ZX3y{Dzc|-&2mW@fukwLl zlQl~!&}dmvbx7D_d^&`{f62MAN~ru$mrEb*xw zVFJLrY8_!h9%>eLy;k7cdRZ1t)G06lU-(o?S}s{QhF?STgz}s*#SD9kHt?#yaDwwy zV9~)F_qF9v>!85tQlmyK`!Y?Lk!+Y&T_9 z$@MDCdz6eyR=!E$lwFD7?hs4Eog;iA%?wbva_L=`Cfar%ou`^ciCYRkMwaV8hsisO ztx-Es+%prG=35@CaJLvL;ouhLn>&Bd{Y|i*ibEcGHeF}JRUX&QGcj~E*DQa=3zz>1 z1;94q*qVqx)Nezq={v66wXiQeKCjQoscjV&SjAOkh!|8t4o5@|R}gcY0?oBVJ!mr# zlwDDmJJI-|s12oGVu=tjXn-8*fE-E!?*x{=*^De)08Lq^yV?wFp@mY1aE;cf(q~*l z**1<6VyVSqSADM4wyg}Msr8-lV==oYCG5J5oSfcP!@66sgl`5l#i(iaOW%)#8BOzp zUCT0Z1~v3~(=2i(I_3FU&pYcmZC2{GPY1EpQ+UXfo7h|`7A1E-E>?Emu;`GT5>5eS z6P1cU1{Ns6Up(TVp`kw0-l?B)32#&Y=azWV7Ce=`aGr&h;k;uI0ikK)DPmq}JQ33A zj=w*R-s38&Ia?}m{p>=}oQ=zIE-cd`8%86FH5y!!btdnyxpxV2wqwa(r6KyCi!qbZ zoZ-cwVlJBuo@Tsl=ma;CQL!p3dIN8C3+!5*h$~BLMKC5lTQstes52fP%TR_B(Q6>Y zRsk3Av<>Df{loW3y!T6z>skB~V0szwgw)IHfp|mK5}3Q0!^6?JYYVyi#})C0*8<{? zBH5`9gN95nGddqMjv1vI2v&FSxhsfqsMn*gI z5CWS(VR&cuM`9C=dt#FiL!uO!4d<<^UNvH;MX7s_##yxK5Pl0+t<2xpX)#RliTGgH}DW*B317r-Fu6%}CW*m}!<=cNrk^3;5L&+IdD4?Juws2kYvhG6fU9bF{2i z20PRlA!DL)P~k!>sXEA2!(X(I$Npn-L)}^bB)a2N?tM|wU8<J(Hs~%c0s|=^PGXgvZO44J_O94l3bn!nZLq<5P)>@reo_ylqw==(^3y`L zC7DSSCY!PsHVQo@ok=9dn&fYzuTDfDfy;+?W^%0J!TZcmr^plTzrsIQ^giB0hd$qP zL~cO4bVYaZ{4cwHQkB3sf+={2>|!k#_sf0ltQCHoqEB^cCDHJB1duYcy{HN&4g6Uu z+PJYToaIPj1drEV1wKNPH{IRgd(VVB$k}tmH%5R(937Tq(#lL`Ji|3AZnW|4eWNK@ zf<6ZC+6nKE@O$!=@4=?J?C^|F@j z*{gDbb@Lgd-RRmk1Ln~CCR-E1Ud0Xkg_xQ9QwWI&%2bxge0Mdq2gn`V0;z+bRnYVS zR!sTY-|2zpU=d_i&>Nmbi>ZSYt`Gh}zfEonJhdXWPx)-$uDS!qM!}UYu>!DUnbTPR#4ah{iK{?QX|s95czUhoG-!w zW{188ycC*fU*c>0oDwG95+(3I5<=I|iOG3Z0(UKJythlS3DkIm58}G-yQT8s2EGi@ zt1_2_Rh$u&zgi(V6vQ2DAJhS@OgTpOU4C;knmGT9*)doQgc_VF7UbXgl z@A>d@6JMER)ggBfCeNy>{sGti0B=~d1t33o-c$Pejh)5HReXZpE#>Nmzsiy;e!);J z>gpAHKwB(*^^2h7SN`ck83kzC-ENnN*D3GY{VCyVJPHV9LBXA4)~q5OFhD4tK$n_M zb{KMHy#qj(^QMqbm&d*DVYP|QCjJz24=~-Z%CS!TOTlIANl@^Ixp!PL2COwFL`ZHe zK!usXg1NhiPq^FEcL1m+DoQ0vu5An24!X#`XlW46OFf`@oHIG?8Vy3B=na2_PNqnY zVt_8DNN?=sGh+V6%COTZkseut(rIoUUslpND<(hiCsWk|1MTj|vl{rG>Os}wfY1a+ z`-Ch;j(j>r;1$?!CgXz-r>Q>>DQ`oM`{qSziV4>cf>xLdF$}ElBK{VZNQWBYv>WSx z2T@5-uZM7>ik<$zajV767H`o~4yU1Dd&`|o9+d4Tj?2lH?wg&KPa3!LNLh2ikv|qS z=j_gV@T*qCIjuMlsGh@>S^%M!9QFxaDv{601fH&A*rl+-1ZY4inJwh2WCEQxr`z?g zZpaA2f#7Z6XGawALU~9A4yn*9^cSHkoU@)XFS3+4j{`^TcS)U6CY)z7$DiGn*Kr=I zZOAK<7M5coE}>Fe%{`)C7m{uuf4N)(|9Ph68_Kipbj|soH|>0KdILmU;@A}q9*C3# zK7!BngtHQ4^j+@^H6ijYpBQx6tQr&Xw9~bhi_dP*p!@wkM0DC?2cITrLrA@2guXcS zq0u6{BCSR%e1NFNcA^2rtp=WNN*245ILTN3&f9|qX~IOWst!h2=S-`x_G4;}rdRER zA8(eflj=l2?ZK#Mmek93q0p+(24AsI?R~(EDbj{vGhbQrN`s<6#jD6KWmdu@eYT4% z{t)dofWTwyyFm}J$MzN{QRIZ}R$kR3wPE?|7t$!4a_5oj+ne zb>4*1aqu#?-H2?zZhygji}QZ$ZV!k;X(;e)8Fk9zJf6~So`~JA* zmg7<{*!1E&5DQjVw3G#38}JdXh7i6$&(Jvr6%j9_v1Z-jX`3Rdx_dN-T~UdgQ>)$M z^np>jblxzlSS~@cbhO5SttJhjXgFCk^Um3ta4<6$_Tu<+kKwCB8gnk3%9@+C<^`CP zI2klii23#9Ft}C!Qugs9!sh}N3w3>IEu@uo7^sKuy=LxR9b`TA@07!3#0&nix3|q7V z@ai>4rEaTvN{}gQ;GTCAFl-JgC~U{axEvw`Zx`A3JAA05Wez z>=oHi-3N+Cgm0)f3~H;Y#KFFkO6+5Wy*#M+JP!OU4%>D7GIaMRU=$UQliH=7ak z|D9|90i04{tH<#w!m742`0F7u7@vAzHZ3NT4U83C2xqLO7rdeyL#b^X9E2Rt>@KID3q+u_t5S#29bPyfE%<6eIAl#&L zMCerw`6J}61yS6|_nZve5WK=B4_$dX@$Al`V(04|b03JKexPA}y_IAi^aTw#Wfex! z=-BD;&0pE?6dcInl4c6NR!qoN=hx)G1~L)UWE7 z_Ui_{?Hq*@2B%U;kUqbb=R{A2ywarbh+!0gDUJy+Pb0kG7FX@{n4b%!@wwg=L3oys z&-f&OdJ>({jET$;fzE>C^;I5em*Ik|UHy;5m`fV8*3*=wRWo6ks@P|tEjUt_60O&pNHpF7K4CJ)Z*QZX@_)gyVG^5T4k?=GhRO zkb)lSJ2+Z)8!~5UeDRHg5d!!lZLw*17AZzk5u@JG_6=UaA9zj$^$O!wA*zO&Q69)n z;6PUJfV6#)IZtB&gr3+A4`g~_JvbugTzUbY#91}hL5PF;`8`;u=QMSoWR3DWAgQOG z0E-WEH>n*6*|RtOR3G@9Ww?B2H&nDWJOIoGhn7*OeLRl;%)>DN>jSI_mQJwplhE*0 zvTasJzx!TQUH60KXhqjF@Sbf|?t@0l&9-swRd*GA>pL)lhEqy1?x5*{dC)y4OiP;{ zbQ(S#ESaHl3C6b9NxpQzuukKCVb{Vf zvT!{IC39UTsQ{{(-6sE+6g{a+x}m-}QUecEf@b{v9y55cmYMlcSobwXo5xom&tYxc z@L=q)o-^#QijUQAqzwljAYopSKYj%nWNTAV(Z3)JvZmJNv8e*I&2bnln|v}&HQs{8 zhSP$?@i-{}#Y~a~)E7z9qqx$HmOfQP3YZ z;V%onv4HJ!Z%=azYj45s=l%$szG4=ifs>qRmM#7f+}Vd{6Z(Q&dYrMV{FLQN zWk4;r`E;3Cb20DM?f~UfFXn-7X}}aij7-I}iZ}3G6TMG33U`E9WbL1qU(1_ko0ue1 z3*;XAmSqD}0Kd0ZKT95te{+L3ATcO*7v zg9LWUQ??R>fdS77xKPTyrZw_|5(pcD%*NtIv2aX|m~`HMf&Ak&J}%hwA>sb<Xmm z{Og_bq-B06*>H$z)=rHT(V0VpZX!cN=X`{!8tt{_Tx5ZqB0m3zIN2!`qd)zERM2Rt zCef{pI9cs(TQ#_`uM$-_fuwV|TKY=tH(UUMtEd9Wa0J;m?h<{nK%rl~*{zbqOuxd2 zEBf7LLggj(@S%C7MXAQlB*4kxy7G)*K!|jMNf~W4Q#zmAl)$kiaJ#|=MD;p__A4rd zK*z=1`WnR+{8Gv^;tOoJZT|*NSQ!lhx=PHy;gW;pR?9-5K$5u@N1B+SpWeX>Rkm3N zFD#q@nknj$ak0U($#+D!);$G=W#t_6`BLOppD}(wq8Uv-JMIe8_*S^#9)8|MJpDt3kOTFQI&rtr@Xq5)gxggRUC6 z9o1v0Aj=`bn29-A|4g|t1I0_+5@)PSS2r;Qsi*N?HPEzPT1GRV(m=^&(U9&{3T#o}ug2>9UDivBu;MN^_KKzt$F|aWduiYW!FHop8=AB|3T5N4-$~uR7OlD2 zwiNAcvw1XpX|vf^Nq2NKZ6IWi#^xINoD=5B{ZmhDu)FGz2Vuu`-vjVgwdo)lUffxQZ4q~cpG&=N!V|a?+1{V+=8}Xcv#k+S)YlFKF;&air{~Z3~ z_Pz}l(lX@-g&BIr5~92z0}W~K*7{t7iE`aOG?2p^sxu#qkWwMrthr{#+y=3pM5Otk z)lwZ>S$rF5-srr?a=Io<;A09Y>!9^-M6(q`RvNmqMNgQe7|kZ9&!SVsn8h6_&A}_k zg{1WkmxVJJtMGJ@-KuF89MjAWeaq$dqT8m`C4&(0heemISH+lR{w4$K?|cmi_n()&f)*Q0 zFV=P$9kkU89+*p>><|@Vk;985jf8xB7B(8puynb*Yx>_i}(;io5l^$idVg zn20d}oE@9DkXVvsBA-=aT1%GBDQ0V8_?&_B8pSdBHch3pR-KRj1m3#)viMM0rp}@D*;p=a7 zlj*;6^M9W)hVH{_^~97xy)6jR-6Nqy8A%8LHYu6X!D6%O)|HfQF#bbW2n>8wq6$WY zP^}uBW%9u3H7R$fiqayMe#5kEI!vS=ERk(Ywc*?;TMoHMUQ)a`3AHGvP~te54@Q;| zq`S|Cs549jjK8N0`DaM+;^~_BWVIi)Tg2}|iyGkkp5r-^=+9N&=uYc=3GaeI?lu@J#i+rTU%4j(JruK-xCsIVv^Q z_)4yZ(-3|V0pJ(3WE#oE;^nLpp(kq(_o&b6mp{vXpG3_7?srgCiR#6l)`XUd!4A!} zX-Ma|lc@8BF)Q_b=G~E&$nGK@*|B4-iDP^Rt;N?P4Q{X05v4AeL*b zb&KU&7`KDYy zBpYx@>oG}fRBq0+OqETxbIpm7Le({x3qnTImD5q1@5@!lhD4bJG!{h19C44974>UJ zBc?!co?VDPUCp>g9Z~_@4cBptmnpU)m$84w6eplOvCn>~sw&E`%1a56owJ*vtZ7M5>f3s-y#1^wj#e#{pUR_W#a@V%d_~R9j_f== zeJylk&h%)s)Ql;iqQc3Vm=K4UI@O2mj-o5BP34{(v~ZeTnZPtv`jt*6gIVi5oK0Tv z$5~A_0fty!Z1`)l5WYhsj!noL2&q~bI-60J9^_CZcLR+C;tS#novGI_)g7BMZw`P?)mYY<2kl} zs1}aePq)*zFQ6pv3F!@?^Xqkw=*2iKazZ|oN-mb_6zY_6-5%z$J;p^lQh8N6epRqd zJNE8WP=~#dry}i9@HVG&*HfAJ-UNS0~ljA47b$IiD4241fbYw zJ)$BBMHx2do;A2SD1ARqPR!Og>c)k17HAO)`4)I5&eqxB0%>;6?uQR*ZK+Hk-zyqR z$9pV(9oE7J1VUM@6T*3jJ$F10-`}B5d4+3J03`8k%-$fayLg|V+IsT!^@W3S2j`RF z+D{qG4K|-lUvjX0LS)4^o0sUcW4GnBQ;e~vLi7GV64UF7A(&8Z0P>7- z(5g69*nMWiT%IV@>1Aa@oR|z&RRx$!Ydwbi2GD4;{&FWTBKHl6563K1QXN~lo9&`) z%_Iq1LxOF7kl(4Z=Xyxn#ogC)F;5g*Ja#vniJKhBC-vb8ZGNB2NC{c&LrP{4Kbg>` zlxA&11y8Lhm|Ho}f63U+igQj;biRbv2Q`@4V|{}FJxCHP%^BM@nD|hhgBirHyNj|5 zmnPFjw-K`DatJppd=speJ|P>NpCv#B*c)^7AQ9cLo}&LqICqdtW&H~6-M@+RX9@5# z7Qjt`dWjh^BCi8LeC!0z|@Yiml0(YY|z#+Ng5 zs!BU^D4MM`5sT@rufoW={8NztvN(-2NxuYtKyts3?BH18ggaA+>?Ci0Iy#0CBOAOY zVOpa1E&@cBOIMnwCnKwu#ZdSRwTuvxFHP8QinO2tj;a=QWY!r0-fN)Osad^0cOe2a? z#~`1x8SkYmoPm4#=_E9|6xEVHtFPF^#rRRjcyOeH%lk83yI5I`1bO9Lbx%cUUEnQQ z1fBfy+KL&nJfl4>$V=PYeY4$WY*(sjott7YdPE@LuHz)99><6MF!4NFhDH+VeMSV%g>nj#r8*#dQm*!!Y;KJ-WU0nBj%=P+&jQ= zn1(knXD=Ij#EM({aDyevLHW#vAeI5YW>{WNWH95T9#)-cY|VZmb4Khvq}@v?MqhHP znP>8}ufPIvXw`tCC+8LTpPj?mf6g@jrh^%Nk2U`@O^)Ed?VN+How0+HySS;1t%LEu zCY#_mX~_XT_>i6Imbq8u?yxYW-}h#{ma+mwDprc~CqoOYu=;`>nyi@upBWIoe!LP{ zZgmhKu#*sXJWSAcFAtwUyQpNiG2Hju*icT#B~6f9m06%Nc*g)Ilc|WR%HeX>6dT6& z6kt>N@@$RyNXkXRQm*RgL>Ub2pIX0{qH-m(U;nD!h>}vI7U6WmfYD~AhhZaWG0f{s zbR7_Zf8{YHRu=66(Rt(y?|<7M=eQ9iGZPH|cBsQSRKP`5qA)C`gWd|VBeJuxJ~RgS z|G9=gu~rF=j6x)vwcYG_nd9Tj8|n#O*I4}ww{~KGYCpH%*7r`G9m0J)|BDh}=Qm*c zPd%v|<-~!$>)G-7U~+|8a~nAx7eQP!cy)8uG+%p^RS7918|{Q@yhUC6CFu`HB##^YR5HOzy5^}l6mGvkjLir ztKiKi)=ps?v7B0;?7+Q!N7CKB-i*P}|LjA@3C-m&npN^$oVIs|06wEK&yE|gil9-v zRyo!L85B{)@`6x-SWy;Uk@wl{sg}Bq=qhL-*hXoHq`9gyjs|ZC(W(1SeY=~~Cy~Bu zJNLiV_rKBX6rCK*ZA|~wr~e6el=(NfBdiE`PJ-7r(ecl2LcwI0lL$BhjCAflSjT_I zGnTOsfvDQ~n9DmNk_Zjb*)r~KFB|A#VW9X}xh%zzy71+0J$ z(Z2uT16db0Sd1RXV6P9ZrbkZ;k*0@WGRl5--sV^t9xsH1*Bi>1lcMgI{~c&4^X2v7 z`Fi*E0<-%Q0-FN{IuesmEh4~BJp=`&Qf*)DcvbIb?oUm(Qs_Rf{4sb=S58#HP52gN zPxL10r*W%?@&v}LmNnaqnz(jdX!q8=99nwpR?V|5E|=2=`C1lk)m7~Y8YUrb(<}y~ zzhH%?JQ>A3=B|?aloSRqGgdpwQ~3f8R*Ysa$9>kCXaYL%S;V*!Kk|`9*?A7vQF0E? z!UPiaB}Z6YoGuJv4Ru9<#X~NnLZMH~U(*KTo^6x#Id}n|R_sj|G0a*j(pY6B^^O+D ziLs+oDYEtF)j8j!6`E4G1R}ma!nJwqvTF8?PvDC{$&0)6-dd}(%9xdw(wg8@={t#|H>Vcx|%cs4&XPy-i+(d&hO(*$DX@xUDuqK1vXqTJA%&>QK+lG z`<5BOuoHH%(7FkL3C2yT0ac^t3TP1Uo+DBCro^@LyL$zN4SMDf(6e#=!35kza^sGoH5rXmlR83I4g5Zt8t2 z^#f9wIOZmQ< zlBi|c=xj&Q`A%T$WJ@~@>f*}0x`+Wam)1&_u&v!n7bmgQTwkuzNnJN4VUg@>samVA zT)J4g0oRddr;}~rSldXoo=_;lmF^^r-^u$y0%*I&KVePWux!s1vsr0X7D@BkK}feE zgHy6^=6lI}bW!VG6QUHqktOQn+-liRh8l9FsP4KFk`?fLm{c&K9E#v|rP%-3(06e~v^9Pv@XT__RUK0$H^JVJ zZ0bVd5nRQa$g?r5vXnZ0+rnc#)`;+U@xg-eyl z(2BJ37ZDB0W%*L9^f7GZi^FOgHj#g0t&Z+kqVNilI1`h>q+a0fFDuE1Vy>!W$na4) z{vXpwyFXYBJb%;%)G*i&YGS>1bW}AhnM3sWY2ol;ErZQQECE%e0w}9s^k7uLZU`_~ zN9{;d=1?RCjdACi4;(>zO&ENK`7+cr(0(mht5>$B?lM5GsJX~erT}C}Q$`09%B`pu zRyHyvOsl7VAQH~b)P-_X2|ZItY33py4mFgcH<}JhT(^Wtu0}EFAp#R`zH|Gn+<5#j z<=dhi-HAuWnz*Vn*o&;!!i;t+=G73|d3*0M_@mx(dw zq>g3IjfdzDZG+U-pog73S0FFs^dC0EBVtXXCoaTLyk7%R+D=W}*{m2){_T=2+e)3r z>ql5;DKc=ozPFw!3ClvHL=IOe7x29s&mc%9las?jnb$W8R*u^$ldudFd0J)Fiw5Pd zN=3w(6eY2H8Dbs3O*~XL!tTT$k2?k4Yh!%I&i52LuG&gg# zv^#)i8`M@F(znv(oj1mg6l4NhkZL43%)jVRVzdatR9dq%)wFs)D}${o&}hZ=wAzW= zPu-*Me2STvmh53A!56R3aoS*By?~R5#bPp_AE7t7foP+1{UT;C0xI!_vw)Pcgw{$p z$aZ;PWxFoe$BpTYZic-_0FiI819X+Y)WKp9g)w-l-cEju913mpDidJ=P{Q)Ut@kA+ zdk@3*e=RDc1tXg>2&;>fu-<*w3dX8Wg|9ZqJJ?!l#?LY>Oba{%=5Zq8jy`JB(?<7i zGm&Z{kt)3pB0qxBBxKa@?=!SouMYrDG5b+PxT7)%{etW=P-9WZBm#bp8qjfTA@?Z` zIhX!<@^m#fQu10N2@~GQ7`#CHA3!oZJC_g$+~GGRH_u3A+`^qwVVyWzsmBl8V29YQ z3N)QI2mr zs}8|9MP~j&x2Duv3~VqnM(2@eod8_hj#m3=Gm|iX;YOt+YP=h}wO?UpA!^jHshmYe z8V@XDX?qwN9_LxwA@k-EPW>5Tf5)k~F_#)JWq@nl3w-th;zi5X6pbI4X_E`vsFH`} zom!9MBN?K*9zoym3Gw`K)xh2E0OM#1v_4MApbeM+m5wm8_GRC1Q)}Ek4;}eE8a(nl zC>-QHWKPB&7svK5#TssZQeYJStBCtrUN^#+zc5RhXI$1ZxdjO+1MqQS%pI^+fobLl z3HrdT4&@P5&^x9+9{#qDnq#|O9uLK!bNIBe>BQdR_t3{(i+BTDyv&Tm+AbsCAir)tN3>4mWVJ% z*}OBQB0i9Kq%_Rfi&W?#s=z@l@lq~cvQxqk{2ObDSN7^#P}$sr7p5S$2nFsbwHF>< z&s<~hH=xD^$4MDp160oHVl6StXrde&qj0ti&7rbJo^dJ>O~5Eu=F2qCR>|d64f5Db zf9bpM+=$A=ZOOtORMrNO>%ImTu(XICF*0`)CD)l0+1Y!7y*KAQsxUF7Y0ThhkRvc> zzBy`eNpuA=q2)~8pOmWL2 zu=@lc2aU;Vy~Y!#ljmZ!nT99mE>(mmbQZBYQ~a9PAX8>H;HHT{Di#_50>ID`GG<7O zB$&h$cqo4ooSMcHx$83_8{AP$wq@FR_ZR3EB-l1)@uE8}Ga?vq%8apdL8yv(YjZGv zR9Buh$d8EmJ9~~J9)l3B*@VX7_t)-S>>x8|xxrXDo=*R4lQQ1scPPh))A)@R;2O!; zLhsp>OrGe9^I9xsja@yc!cP-SudKdIjsR2{U7rOvQJKWR0@$Qnyi7ik<<36SBIZTd zNS#^7pF^scEuj(+QSn=ONz5zHPPpMhF}t zWM|SI6LtIyOel{gDd~AwOEKw^xFf zg4etk&otS@$lk)p@p497Ds8L1-f9)(%f-@gM%<20^YS;oqN1J@xk)wBa&H*^C{!R; zug}NR@(9tD`@L^WY9C5=N$9eh-n9ut6m~#U(3WQ}>-`jm@{Bp~nuU~b1C;A@LoO1a z?Cg}_p;bUTP+S2-r9=c!O~N>yi4JX;#0P~*Q61v zy0qjbZQYB}j9^=C?WU<6$V;jC^|UXqJznc_kg$b8+M<)9&G7k*(7J!NzrM+@Tmy4W zD2wt8%5&PbWfkQfOH<*$O22evqFb_BHI#<3J=DzeQq5wQzoU6Y^*2&B`WehJQgWkb z`ZiL9fqwrSepvOv&`NpK_h%2~Sma-uoBM)xP84cR#@6xW3rCKXY!Q{b$G8#igJ%yZ zMK-;X4g~uL1g$cg5?tOCs2Y3_apDAQ`BbPz&PPbX+SDz7u~UbL^f&6Rq;qP+C3=x? zhe)Dv!x-|32rVzzYOh;ubi86_c^YXYNhIf@a{D5T+eB0O#m=%B#f%N|DW6HXR>PK# zK#IM{Hn9h^qHtr5&(!*n_#CFuzn80# zQiYpJhL^;qcgh?WdvDI?ZE?sIlr7n1(At!aHz$aTj(7qNU!*z{oUzU-Cv~6ndoTwH zAMjJkLTAfj_8cDQYm{R5ES!IBEE%52?+E02V6#<_*)@6~ww9IJWqM$`R$QZ$J>?bZ zz;SVLy>0cwo-`^oMdm6?gPmo=UaKQMfC693k0@C#@=m%4jewz4KWG&lYKlsftQTRi z=~a3mGK>BGvpT?FSAQ>@tgBo%OcM`L8y z%q+t)&mIn}&Q0>Qawq73IJH<{s%c4M1aanWaS8T)Dl`4zn?UryIIUW%*WnROaL;M6 zgu%H@Cs*ndUVH|_T&9~Z+#Rm+U|FT|r%&Vom9=umVye10)x9ip=GL+{O8H!Yb)(Wr zwi(@bCb^H+Drdi-GCM~?z}|8?xpj}V`aBw4{C5EW3V@q3PKO!1A$dt@6$P(&X5vZ&34R_!8l(~7vLB2I`Z{zQ)?aD?-m=_A3r$$zg&#} zDop)1;Y8KJ{QG3izYBb-kl%5ND4*BV?uq)Nj7B7RL~=io@PU;n@(>Y086d^z!@~Zi zb;S`Rx(`rOH>;d4t5`N)^--!-s##0cCFHfusWiDLTWVLRRJ$}bS5^yCeq4Lok}{1= z9zT&>Z*e?rHhvv%K3$B&a>MGy*m=}Lub>SC*N%(!MOnB>*Kp~M z_95wV1_|hTV)4wL^FvAx;=3_nC1Xkt19@|9_lV!ccpk?uO}n2NdrUmt0SQZ5kSO@BpMvlfPbPl7II@ksz9=3E53 z(8(U2Z0KXiw%1A8zzLItG4wN(GL03BVKx>UnY6j#LmaAgRjW;_padw;EO91Mxh5K1 z8BF`X%{I%eXVD11JId=RP?-v}Ux&l^dkTU9X6)`6eAeDRDW};=n^nlEEg^*>o)xx* z2)Z;+pzqZtVzEwVw{`E{fD-A5;h!)5jWy-3*Kub(5FU5uj=A@xY&^XP+ z@*{p*vF5ZJj6K2!qOlgvM+b3I(O{Cq#$U$GSu7Z~1aD8uub(dO+k1!dIeQZf$rxLF zW9S_D7ha$7=5Kx_N*s|&8Ze})2#^=9#37rINS9N`wG%RV6O$^QRM@IegcT!JC1$*K zl@f;n z378PakTcfJNP~aT@Y@)x+XOK3s2(oQ#i(_p3?H7UqeJJ2Jg#?rr=50Zyx#pXF)!S- zp=g^Tjzk@6=)#BkjXWWmWKCN2GULWIsl;uRg^==@1Zz8$farBHSjp3rzZHt2CLVhC z6GOZi`PGh9yL>)%O?HIH6M{mjyj|un$-Ns;0v5|qdwL67;kcYpEulvZt1{$`YhA!oY_ELQoDxsZChn#Ll2mZkthwayg{L(oD0)=nNSTqVM4k zxYA=DGgDEc)m+F zYS&o>A> zaY=>H(kWb4zj)qdIZq{qNh-FsJc#wpo>xN+soAw6ELjNBAOJV|TrLOC$ya{HL`)M` z3Ur$4#y#b;>8x&pK?>RK9{DdW1}$YrxWBjcQ*QzSL@gR(tFFQ`Hy8tF*9ysgrH#CB zGhNeD$@M55h?~4R343qXTtpS4m+IlR6J=_ZBzLqHO%^c}+@UdxOk;rujbQ;)I?Cs0 zbX~$tNCo^c4415Yq)9H1n`m?z&ia$3D^=;#mvS~n_J>IgJ@+MkkKvLW3p@MM09DJ% zhIkl(q`ircO>u6U;Ea>C)6mSMWXU;;&3rr%4QEyPufM(%$y~X!VvHSy<>Up~b6_Y7 zozdd(7fjpr51Va2Pt4&hy+vU+HKkD~KWCf~QFR=yrC2$m4g_G&wq!7>Cp)x7kHg69 z7CT|sW(lLmGSy=Po8G2^RKFkF?X8m>BklNbxGdt5#TGa|-)N6BWvdMwx4)z8_XJ*3 z^bv&RIr3unHQe~H2Ohc|F|<7uiXk@Z4fwb{QkYx5aKmEeavIwlgz|+kcFI8o-rGnG zlV*)*F1h#V%VPp+2_>pTLJVWV^!gmGjQqntj6`{P@ z*4ymv3rRmZlb~eRqCx?VdeK^J+)?#fSADCj6eh#)64n%*^4Qep$++!Bjvx|}>5Bpn zK-9)o5@vz-7CfqqgtS%w%DydRnL!n5BSWo-nM6m3LT`qBH%RaHBp=;jc{dK$eThSR zKZj`pZdQ86`6r{{C*pnNf*#r$?^%iQ^L6GVvQ+`P?T@aQd5=RQ4&hDC2CaJkh4bKiF2BK3F6CvQ#Uybyds9i zOTP(5i*eAdaB=l=ElUA9RoFufqRkQV)$%?PwJ=<_XV)kz)**9wW}&P~BOix`h19WW zEiNu<>TatKcnfgGUUCJjSd-wE)fNg(CFb0+?S{y^FwS?#f=TFT+K{7-|4eq6a;MaQ6k23Mp&*(ZQ#0NMW4_~cQ4$RzWz;U?Qe*kqg3yEzR7ML z(b^Zzf4lkr>=0A#5Wa2?qjYiTM7xq7YHLkIZqsym6-yd0p0kKRbG0!=4R59It!4)g zbGAvw803SyUNT4p2L|`v3r0!!awj%sUS>6`?JB{DxN{*EAO(C<{K|#^n1u0?+-86+ zmUHlB4~|2`$gPN4m3|o(exX0GhqNoP#5Qy2vNuZPlR(wkuuD!@I>1k8c35A8x+ptM zEbi!|4KsJr&p+HSH7hN# zI4jejYtsULF`$fuo2OBn*+-=1uzVdEbEk(|SBY1iS?pGw)J3;QO#dD~GjPXgtuiTX zXn5ASp&tev!Y_F$9L2-_i7Oz;iwc?x3b70AznlfMYKMLm;%^l-)4*UekU4_&X3rhV zhT9un4QIg0b_{J`^M{)pK*QqYL3aKKzsUtSJTLNb3kYOazsj1A{e{a@tc>b50DlCt z$CSXcQ!qpJK`gFI9~KP4?R17OV~7{8q{Akox+ti&7>npYhbfdeF9!HKg|AePP1^X@ zsnoll*6Y{WOO`@^Eh$fuLWI9gubvf5QIOncJ7QHI5XOOZSrDkZeyrF1?S8VSCEW9} zLO|Q4tOr^Ni*Dl&va3Al-zva*ij-cZ^01S$8dfYon+fOXqAqwRjwlzR-8U9ZG1g*< zrl=_PN(oOFkJ4y*DC-rraHg90bnGJhDMN`@3!O^d)HCA$3D!f`IMKh?!9Cy{tc^;R zH+Zb4J;@zm;6m_(5XBo2u7%@Y*{`gvt)8=xKzrCdP+_svGn5Q=o`(Bnz!8zT<^j&Q zR8bP%MqbG{!I-QbQt9T{Bvlq-=&qt4AtgGg{4T6{TmA@E!_I#BLj%0tXz(3T)x?~7 z+KhTQ^~N|1L7*0w?;G>Y?ihu6ew2QrMSC$OYuT*cb67-D{XOicXxMpcXxMp*DoA-AKLSr z^Gy;Ge$17bo!#tx@6KMMD~-D~vAT{?q)p)kQ&S|au}A|yx*)}1PFbGTQf;#^C5?cQ zP;Jt$iZFuIYy0aY>|6>u0F7D|P4yCPcZr4VYXgUxMW2D`q79Ahk(yT{AfJL>!(!n} z)tt@20q(T1$n<<46h@MDeuaYCd`@2(S%@e~-j*)Y{8@ntxn>i^U|sU` zbzZC;iRzhJf6+-bqH*fA7BpyT9ud7INVr4uMWK-5 zQ|U^r7zq zC$%l1_;CCEjDNI}Jh z4K96WDcJKTtd&kt7A(PS@?(qHF4*X>WXC{^@5Rovl%xj;w&1N)>EIu z8)Z=CJ>?XhO5dMfj!_bH;?d7WzTf7;WIj_#?~JJhxp^Xn;kVrx_Mq?y~Z+9=QzL}JCX zh~EK{%vWZJ4si>;r}5KHE0dAuL~;zE64BL^26<&71DpQE*q`jF_PeMpM{I z#K!0KAI}*-(wt``Z)piDFz3oK$cjY=!Y(;7ZWS#NKddnFUhHQ0NS-h90^kF4jK^Gp zJw(8c*O{l^jT(mFAL@BOu~G`k#jz2+YwXGh3JHo;L)mDz49dC*Ifkpp^3X*AQ2>Non)nkuA?iV>#~$1Mr& z{k}NOz1`2Ab3Xk?=9F2el1de@GT$%A*F*o$+j6wmLthCXPR#J{N|mOvsJ`0~LMav56!f(X>-wPtL>B37?&*8Jhw+dD@wzh4V;BrST0 z!NiJQ9n2oPY;$d!JU!jtVz;0`GgPcsd9inSM*5~gB4d#WU$?M5;OCzkCbPt~+%}b|jpjONUL_b1fx^|vmz8goB2Q_?#wZz0~U z!JsB~0A?tV5oHJ`&KRn~&_EJafS({;NnN~DY304%ZltY%iF3em_Gp5yoF?ON1bw%dmEM5dq2S9(mj|I zZs!$KktS;msM3N8mCiF%Tgf3gU#P$xUfUGhQcMU7%8r>F4dlgr#25|zlpVyuEgL#M z>bbqfpX5lL5*jMW zFpK;NA0|`m4%Ww)%Q?Y7#curcX4_erm>$IlbpleVe3yk0!WI9{QnRRZk@S}IGFxEb zAmSkvUlG!FA3`53*NXuuBMy2)_y?aVm%x0oZdcvjpln{cZB_@4$(iR7!hvkxyR87I6;tf0VAqzV4NMiDSM z@vjN=AEW4>v!|_$`pZc(9{y-Ed*#%hE7fTzv!B->E(<--(?rA5NGBmaWcTaE8YGGu zWIxcl;1kE)fIUceam{y8XPT8+A182J5Aj?N9e@1j`oB_jE*k}2#{n4}FgebMF)PS{KS+zcL_86Wcx)sV1D zrM$?nR6MyI-lx^6^vSpM=(LFvj=U>Eb&n_)2elc_@jRwwdU8gQ2}u_!kT%l%D%v%Z zUfN7%l1Esov1E%B5(z1EOr3`_Qdy6+8SP&})%68Q#kYM3xlkY0Er?}Q1^bNhj(?15 zYX$=-m&C|Y`B0m!xRD+uGHYpbP|4bo_L)A+BdW~!BH#yd1n%`;WvwwQ3-f1alVdEHWw9Z~LRzF7H&m7MG5FCAO64(6Tb){1^PTT?%pOXsnU(i)GRZTVX3k&UjNLeg# zEMEf{q4;hZH`wfXfNPtJ*3Z|@hvDd&p!Bgx_PUTu_G@5lC{H^b$qO;=@QWqu!)9`8 zbh$V0K4h;!J;?htbDY|<$(+K&J)^|^FutkwdY-fpYFAEu4)(JCY@uQBF_dr!yftv& z$E0O=P3-|ftz&rp(@GTC5V5t0sCIbUkq{9_LPT2Vc%bD?I`x#t^gUKBvsJ%K9!zA0 z7!@G>jSPH5Te@`J$;lVP5EwG!670>0)KLUXOv+CBK$kM78kAU>fDxmNiF9Txnl*z` z>7M*ijKHq1%tNB;k} zA0q(SMmCWHYBX!&lRH?UR&oA{>iN>C6XPtDVXc^0sP)FAgJEd`ezRr`e3>$z{Pt^F zKF;*XZDnwj8P-}PQ3-n5Y;){7&6dmfQ3mEEGA{=P>hye3!SDPWsv}J~xuPpwIR)@H z_6?7!8x`uWL5Q6Qm4#a_N4$JLZ=eNRzih;georXGfgI3 zs}VB_$;_8LGz3Pkn> zZss(+(hzq$d9GLtKiQe3*;6$=2i{idscT?b(-g_miw!`RAB%5;BVo`esbfKlLpC;D zTOq~E9z+^`JRF*v5S;lCuiHo-CZNs50*>9uZrkPR!4MtcNrOL*=niI%2s5RK&5gq_ zTYXJXa%DNDVi$|4TZy=jqee+tryrr4FmO>Pl8;&$Xc~#=t0Fm85a6?C)zj7rL3Y}J z=YL@Yh#5H^dc-F0PJ#nH+(` z(BV>}YZpujzk70(YtA7*zax11VP4!x$f6LoyXokkvg{HP=2K?;SWq*NQ1(z3rQxOW zcv58w&01ox?;fdeC$;bH(b`BOH8zH1qN~$Q%5-Fk{W-z2BCQT$AJ1Z1Kt*-$vvph8 z3d_=uG?UEr{Tm3wJH6H}O^WnkWG@Y3raku0`!QZ^oL5@K;Zyq+zp!k+W{@TlcI>h| zy6F{;3+c?_&bD@K?Q&KkbSLuEw~D~eUJ4l*nwtd11Zr6mbECr3QC;7GJ0i> zP7dYP$_7;hiP4w@U(Tb|MT=^b>oux_i`Y(1yDwDk(aaFKw)-*q>ioo5eQO6XBvZA~ z@OERw{gJ39VNM|jWkKdS8K~TI@VwgCmm^qmNlnr%F!vlToJUBjV@P)xmO10!9YUFO ztsE?;7I5Iu&ji;q5;+$o>unz1((SQ(Dq>>pU$7*M?C$F%RCEHoYQBlXS)!_!i@e``2WCvwa-xTM}Gl)7ehVpox7N(SJ5^JRX=yC$oI#5Ab#HN~GL zb?_W>lHH1mvSX>pXn*gm4<4cJqa|+0&vbn>v`y2fB3*LDxF)+*Mwx(l&O z%OuOgmoA7ENT%xx4YdWCf@u`TV=a02uwoNFKJuwbC6Xm-C`cDIgWdLRSyEyJoKPs! zLU|mu7j>%!!h~?C`0>(gKb`EWH7)3*X@fbY`brYD41MucGh)Spje)FXSt4RN%;Y)C z8udn&nA?ecFsu>#t`eg9fLKfh)W-J>zM3390Rq%~HWcIwfewo}Q7(6wZ0}ay3+KB} zdYncpnG)zIf=y2mZ05unb{H35CtTX;b`NOENoz=}w`GkK(^08fSOX5zfF&tivEb_v z-uGiyF%ZIcp$M_E5LC%K6&JMepXuzgv^YvWZ?#gO`I!}duZF%f6es_0}*xw^ad zf-9$UiF;oTVey!|2Jn&CfmpPYam1hN@Z^FE;7oR zAU+yHh${Z?7}OFvD{Z_{U^iKO=k(XNNsO5(5C(eNr|aEXnn%YT>*O+&kLngpAc0bm z*Pv>jYl5-O+NeYhJv6w_M0+%Q5Z+_-H+w$xv%W=M{e^v_*wKvnK((dm*b+bG`$mkb zgnR|ps0zq!hgU9-bCMNbm=CH^JbM;=(3WBs0P6tR|LJEvrcgUmBQk$X3o6E}Z>kvA z8XGt#gE*`f6Ku&l_u7TNzGXk|1uyv;+{>Au%Y&uB8ZZXCAvC+g?b*cYaw_|h`y+$t z#qOi8hWv-R-aJD=oNbNhGgr@@Q|P(|4A0!}J%uelH6g9l=qun3r-KET@_pFWAYIsI z=zyw6mQ3IWuic>Ar^Ydyy)ygNANBmP|NE)L?g{P9TqwiB`keo-cAld~3%KiyL;fKP z$tkwlL)@kh>E6yvfmc3{7|aV?V@APq@Y#)EcJr-fi-7HqksA*({2CZ#wIOR_06^v7 z8cvIVFGfsVfDW zpAjb!LpBEKB-2K_fZf=G&Qoz-u`q7*jXi$5nG^NsTviUzlahHcsxE%?vO#XMyY>yO z(E3}*2~l3sYzr2RPHGqU^Apamr{AgdW2%roenv3Y#vNx{&GzcDRt{7?c+8%qqi84t z87?_`za{^R-ysU@JBV<*Hl8d-2Z2+^nO?Ta6>Jjb_6vYM;sy>`k`l2(#vd6lR#UM*YG6P;e9CKP# zKXkYgU}jh#0aX=Z{1)V}UA#UuGwt#^&yW84r=ZR!9Vo=B$CR`N7&y>bscBvNDOU>YzCZ4Qi^Lc zJbKb5@6&@qmP9){3bAh-^Jm#)gzjB$+3Tbo;=`lZqy%J}hZr#^IFa3|CDxSTazJoM z2CQ{$e9j*3RhV~w^Xp-oUXW9fM*sa%J{QBK{=FO|vO3XylH2@oBB?uJdnM$`+?LkP z$4^e4kRfG*h{G1#C_nn`q=d3QAQ=0>8fSc52bqeo+DL4B_oMBpGqEiNnQ8WlbiYAj zU~Z5ANYbqB$9+0-z?;z)Xzwc5LCK=G85p!)XNO776x-;=;d%Dv5u-15cA*VrUas0` z?F+^^`&NZ+z39$CsfA#51w^lzHix8AnQxJKH@SJ_jISxjjMALvo?Xp>>>_SYuf=hf zlBVBqZ^rq2D6saik}W!#kE3#0&<)M!4R!LzAcu7Q^fJ9dSQ5sC!;`lzbK2C5BB3PP zbq4SdXDQ73;@efdeHEm*xp-|kEkB)MYs&O3EP1_SJ8TkS^5+KKz$8+_^rzLy~; z6z5@1F6W09a}T;9GC=A0a8iz^;))(s(S6J+FmLK(VChKfjLvHeKOn8OClz*M906s7UYz8E!HC5WN^DLV zqS9v~OQOIwEUdtHfvrMV!GjTjG!g!V%x~sy9_QOUMvWy}B z2yVkevsUI6b@Kd0#e6 zsKh0Ion|ATeu7KwIjX6MH^c4{eNI=e!BnI@FkzHz0y1#UzyMM&?H-GAcV)Lu3wxu~g5&?IcjCrQgHXRKVCckZ{2 zi~&Jfusq&WKIZbAe!UlrS))`j!pnjo5*Bt`z5pBO`5pNolj7C)PPq1?*P{|2R|>8m zlCnOmAtZJoI>8KwLQOxIbOTQ4OPm9BA85Nci}MH=1*#6mR0Gd2t-O$V zi9Dp01-QY?xt=}Ap7OeP6i>1XrvZ_%g$+DYFv&AWKwCBHyJjtC3Y2(Af8d5b;pvOs zKR$Enz$AeOlLr9+KG)SDwNK~;$jDlF)LP@RM}Jn-EL5PM;49vs+SToUg0M z6b>RNdvgZctS_(x?GfD%)69y+C`1@gH%jZ7^&Wh#2tJ&2Bi_$Y)`*BQPFxCDZo*h^ z@syC?r)`^=po%@EJLzwtv-*h18+fUYwSP(Y!`mGGLi=)gs^7wkB)$K`PV!`-=oyKU z=ss81HiY&im24hL>xps08Uf4?`TOAXhQupK2_2)RY!N)&+c%CSo6dfj>p#FZJ>P%$ zxUHhOat_<7yF~_)7aDa6_fxxYm;m1_7ksc022-|;4CIz6ab_XtP4`IE!ZxR$YRu<; zrWCa8%t*J(xj6>m5)IYV#qQ!(8rj9F++56D%p-5a9+5>b`=)N1w3`FW+{7D`)THBa zuG3mt7mbaDsJ`R$aUh*V(?Jx*VT-o^Wt4x3#^m5oHnxW#)Fm8q+(`0u8h2FGuo@<4u~sx z?2lxRQ29kWW{w?At_*a|&+1Rafr(YQDqc~mE*KmIrKDK(4(lxxMoWbW&tQvg->7ef z2OIUyNL`ce0sd$FPbflU2=|3-=w*v=JPS0y5-K- z-MSDslHU@6)H1}o+mdC+n`@;wfw)h&V-(?ij+%4FX@WYRbRAF()`{i(87~JpmD7zN z9lVZqiBgrHZ5izZQ9nVzorCcvkH|rW$GbfbxqCvop-A9+KbtT$UiI?5^1YU0`mI(_8xC1+&L@%ZH)oJv;()nu@d`yE4NPBq41 zl7ZemYx_1FB@V?iMK&~ zk8M_a+k(ET-T=upUo@A-)lY{OezcrZy~Eoj6#l;72+Q@G*7U8M+cKsDYqA-WOr`sh zfn?0X(CJd!u;2$mt&{N`FbV6nVbSB%k+tq#l2ErA{VaTA(K5M%UiB_A)c80bpU^L| zumcV6mA6CIJ$Qzy-Md2i-)eJfwU&_mJU@xIpe71B9SQeMFe>k%Zs~G%8pa<7?MJs_ z>cv3l##~Sfo8+KgnNr>{T&W@MXE5}Tfa3wXUm@6D(ekpaD#{-wEntS48a@~tj6;;@ z+hJtv6cjZfg_2CS3v7`spW^fUZU%Z0N~9_T8`$BhF4yK|nw$UoRN{ zx#dps$AYmGkU~-4ir?JKz}V2%O54WR-0WW)@L{IrV^S#H&(U`2C3SFm;vGCIE?SEb zdgcLj7>L`S^%fa>7EU~CCxTGxry|OZE2%vMkU#zep4vXje1nYr-8$*0w)wdh{^O7D z_iwZyC7Bl_iF^Z@ZMa3GFQj6G+qfmtsHgNCWd*!^s={UrM&1YS-`keYX_2!$q^Ry* zelNCi8ew1KTYmqw$^OU&@(n!hvU6`r^YT2`-GmA5^xz|D`vUs>(;O^V_x=^8Qan~c zHTMS163cDoV2J6(4Qg@C!oEV+_qP;EP4@bbsk=3kA%2N`M%6CXD|N8t^+DSn#TXH1 zTTt#Q=O2*`Qdb?SIBE`N`26kFpsr|+l1^F>9p&WOVZ67b`b|sib04Z}a<=;qZ#*|^ zz7AHl>PbGTx_1F(AcZi9f+|3D8z2>)^fq(2*9A=+mftS6%utE~ zRK_bzzwe#zw=YOF{Hy>xhxc%F@1Vm%18b;GL1hB)<=u#hGce#C`9tD7Ho5~51q5`y zkXl|7F6_U{#_UtTIs7?f^29ez$_z-d6<75&!rhbZ*$zNNNoV)?Y68!oOU^$a(d$^p zw*p3yJSJ|~@eO%5T~7JKadOT^TC5=P1(J+8%a}EVqV9!)&c#q}xtJ5WfSu1oxKo$I z^T!JTVh!0;9EAW;(#URKV4pa^EUz>>nfo`U<5x zUx25J0l)Fg{kbXpTdp>6JL~rY#)^(Fx!TW*%FE(-dW;BY$oSM=2uSJgq(xi25J=(> zKD(KuHHmxmdgvL%#3HnyW=^TM`hlCmRmIg!cqxJU*%qthMX5y7+LRYQ-bp?i-(TjZ zjW0W%GeT*b#JgNC+yl3~7Rr;kx|iX z559oEBJ_sMc!uOHn==D;wL=NE=A{mV8S29H+XYg&>i#2K(4z^9Xsx5DMrV%;4Y=!G z7x$k$8V8+^piM_zU~aS91gq{E3Et*4rJ717ePC9j{GfPfCxAE0NGCpCyzuYWq~VsQ zPH^FZp@R1p9n{z_zTFf_@eq8F{Oa(9H)-mG2X5HtrpX1a#YV5LflKdg@9}VAXlpf|mtxO<8t54Td?(T%FG;n*f;5 zG^!9c^)lL6=)pTOlr!wKQz=11Labb+Y2entB2qv|qMIMpP1n-rvoNO3$a?wDMI5^R zd%|w>;g$X0RKB5*Mh)}}rGes9;%EmsfvctgwD&M0`kmU;jS0Fci33~Eu!dziRjYXr z0!Z3NMcM)lQLP5J(nE=Pn69R>s)n@iMM*UX^2*hsHD%%>dvtBO-A+9ajk7P2voN67 zoe5h7T71C0CD9F;zOVvJe__aHba1E=jxLF80qct>jtF#gX^pL<7DiD3;4P_2NpMv4 ziF1-^FgJMtS*#W|G9x=%gTDCoYU-^bblK${j)#FNChh#6%eJ5;#(`n5~=%CTf(2%n3?I7JP zW|Ve2B><{EDp1nc0}F#ow~mTiyvD+&F?~u@vF`u|;9Np+#kR~WaT4neK8*_k5(0kK z)@2V}85Fe6-$L^w5{#%KPjvV9_w&3n#Z_F#!aZIo0kvuHPp-54+&z4f^fQ^Mtotj$ zT63{31?|-78(uv>eM=~QwW6bx{dxbo-RQK8*6#A=T z|A8ms9gIz8`vB1_-vd0|c>rw}U&rs5nss)2&hq#42DM<~ShJ;Gjy z1QAsu<0EDnrz_d#2fQCzN!X?2aJQxJ^k76AY!KP2t^~q4pN#xsGePN18E5)c;uH)< z!X@|(k%DpR(`D8$Bw+cyJ@Rf_8|*Mkm82MRPA;giQNQ-04`N@nb%2;yVE0H>R)QZaR##OZLOOIi(6B1-7fLE873`g$IP zTnRb*L85O?iJj)W@@08VBMPrJ0$27hqX;as(3sYIwHgJMGN_}c{Xdo|xU4ObVDIk( z>}U98O#Gg`r5RZ!?I_^(OpJ4km0N@B4ECA}3^p@6Sc-GM8S?pM?!YKsyAlQ zj_U{?i>^#C7ZCyGHo4AthM*B`xUP@gpYPQW z^&P4hf;p~1Aw!Ui0+(_+( zpS2Mk$Z7L1nU{RcH5k*L!Y>FY{9*3u_3c2#0PE2MtN>?q3cv?50a=7qwI}$Z6^_8<7>2t76-0khx~Wxo(U- zWP4KKjk~n+D*{eSH}9vkJq6D)$Afg%-Z*648py6Px^DW*JjO5$Do#Qw ze$0wixp)%gj}f;Pr>9{&%6yuj(n*Ni6lT!Z3RphQkh32bz8=}WPQ$oPg>{ztb)P#3 z7I5-CzzY&UgDz8US@CO!^sdTatr|66{5uPigupWCICP-G+nZHR@IX%gJC3>R7!&Nw zTGGL#z7!N|KEmAU3pj_|%ZW#e+hHv7O8C@I7aDSVA(L0U83@HM$PGZq3t17(Ic~I6kY%v`h?j&1O2L+;-8aeC`Agi^|$uWUp8H#X|9==>m|hwMoNTD z2X{LZ6b(*yR;lq0s|u!cl?%JeR4f97+oL97`@gD+J#MaL%RF-!cNpL{^KJXDgx`AI??@F*)Njv|cZXPP$1JS4J7 zaF-0tjHrCdr;9@QK(#^zDn@W?Hd_(zQFRl7-7Jx3L(s2%JA+jOK1D)SWNVv7>*x`Xby! zwERe(m8IJEhW$NY@(g!;>cB4NX@cyw=u5V)s8?Qs^N{EHdFBo;=wMUE2g5_VJQu^J zd;A8*N=44W@MF{?vi$Lwx}J&5GxZDr4~49AX8y;?XiLci9tCl2#rT|M`5t*bart-# zbx(RRTdk_S4(>HdIoR#|LZu8Ri_$qSp~?Q_)cI1CQkeX2mYH?$-yC^P4(=#ak2F>j zq?!pA*MZGXez!TsJCJd8E<28+5rUF|`rz3`;L5C+0S+J>`FAgb@UAJP*XE+_-7R2H0=tBFP zZ;1z2_ft-^2f1eZ<4f96Iib!E9bn?N<3D)s-hiTjpn$x4_YUOcQk|z#I4lo%5pNB= zh(`ed{`pM+f^vK`q7p)M06qy(AwgL=T7b|~-^;z|D-<+H$rmLc$Ug+?U+@2XJ9)W5 z_&3V`QiK0ZjRKe<^?z!n+IIS8bpJ~k<2Pla|5P@&GNk=#ZT`PeaDPK7`5!3%2?cCQ zXAIuz7uGB{;EU=vsK@^wl!dt|t;Iic<&E{NUwc{(1SXsVH=%n60-^xSttb8scnBD< zKbq#u!T=12p_+3AJ=>cfJ70M|iYNggoU80ahAKfadV-29vIzbNTm zL%j5GV%|;Aw?HSSfw{{sH=}<^1u)=$K!_V#+x({`FEBD8h!Aza#LZwJfh6)@7{E`@ z1g~I3Bl`p3w|nH*{=DF@5z@v+;(&nM3xI(9 z-tUKit3?0j&kLnHpOuxi1L4= zU@$L%N49?tk-z94NPzzm<@pUN$QYmr9l+NMtK47Gr1%Gfq|R4;U7LUBmA|&-rES^} zQfD`SUNr!{!utya_$gWG?|~$2O-%m2gK8j^_o(X=r_BVGXEaufAoWwwtvkj2^vzAV>i)oaO_A`YIj@g*0Oy!jV%7Bu=J(TFuR&gH zd7a(R{NL}=Z|6e(#CV+`{gMa&my{3wiSeJ^`o)UZE9SpXI2FUcBmAfS zOJrUzYQC(i|0SE7zw7_kRrWufdVTrzdyw3Aeuw-c*5JU24+Mk=_{alJxl|V~|NTG3 CKm$Yo literal 0 HcmV?d00001 diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000000000000000000000000000000000000..7454180f2ae8848c63b8b4dea2cb829da983f2fa GIT binary patch literal 59536 zcma&NbC71ylI~qywr$(CZQJHswz}-9F59+k+g;UV+cs{`J?GrGXYR~=-ydruB3JCa zB64N^cILAcWk5iofq)<(fq;O7{th4@;QxID0)qN`mJ?GIqLY#rX8-|G{5M0pdVW5^ zzXk$-2kQTAC?_N@B`&6-N-rmVFE=$QD?>*=4<|!MJu@}isLc4AW#{m2if&A5T5g&~ ziuMQeS*U5sL6J698wOd)K@oK@1{peP5&Esut<#VH^u)gp`9H4)`uE!2$>RTctN+^u z=ASkePDZA-X8)rp%D;p*~P?*a_=*Kwc<^>QSH|^<0>o37lt^+Mj1;4YvJ(JR-Y+?%Nu}JAYj5 z_Qc5%Ao#F?q32i?ZaN2OSNhWL;2oDEw_({7ZbgUjna!Fqn3NzLM@-EWFPZVmc>(fZ z0&bF-Ch#p9C{YJT9Rcr3+Y_uR^At1^BxZ#eo>$PLJF3=;t_$2|t+_6gg5(j{TmjYU zK12c&lE?Eh+2u2&6Gf*IdKS&6?rYbSEKBN!rv{YCm|Rt=UlPcW9j`0o6{66#y5t9C zruFA2iKd=H%jHf%ypOkxLnO8#H}#Zt{8p!oi6)7#NqoF({t6|J^?1e*oxqng9Q2Cc zg%5Vu!em)}Yuj?kaP!D?b?(C*w!1;>R=j90+RTkyEXz+9CufZ$C^umX^+4|JYaO<5 zmIM3#dv`DGM;@F6;(t!WngZSYzHx?9&$xEF70D1BvfVj<%+b#)vz)2iLCrTeYzUcL z(OBnNoG6Le%M+@2oo)&jdOg=iCszzv59e zDRCeaX8l1hC=8LbBt|k5?CXgep=3r9BXx1uR8!p%Z|0+4Xro=xi0G!e{c4U~1j6!) zH6adq0}#l{%*1U(Cb%4AJ}VLWKBPi0MoKFaQH6x?^hQ!6em@993xdtS%_dmevzeNl z(o?YlOI=jl(`L9^ z0O+H9k$_@`6L13eTT8ci-V0ljDMD|0ifUw|Q-Hep$xYj0hTO@0%IS^TD4b4n6EKDG z??uM;MEx`s98KYN(K0>c!C3HZdZ{+_53DO%9k5W%pr6yJusQAv_;IA}925Y%;+!tY z%2k!YQmLLOr{rF~!s<3-WEUs)`ix_mSU|cNRBIWxOox_Yb7Z=~Q45ZNe*u|m^|)d* zog=i>`=bTe!|;8F+#H>EjIMcgWcG2ORD`w0WD;YZAy5#s{65~qfI6o$+Ty&-hyMyJ z3Ra~t>R!p=5ZpxA;QkDAoPi4sYOP6>LT+}{xp}tk+<0k^CKCFdNYG(Es>p0gqD)jP zWOeX5G;9(m@?GOG7g;e74i_|SmE?`B2i;sLYwRWKLy0RLW!Hx`=!LH3&k=FuCsM=9M4|GqzA)anEHfxkB z?2iK-u(DC_T1};KaUT@3nP~LEcENT^UgPvp!QC@Dw&PVAhaEYrPey{nkcn(ro|r7XUz z%#(=$7D8uP_uU-oPHhd>>^adbCSQetgSG`e$U|7mr!`|bU0aHl_cmL)na-5x1#OsVE#m*+k84Y^+UMeSAa zbrVZHU=mFwXEaGHtXQq`2ZtjfS!B2H{5A<3(nb-6ARVV8kEmOkx6D2x7~-6hl;*-*}2Xz;J#a8Wn;_B5=m zl3dY;%krf?i-Ok^Pal-}4F`{F@TYPTwTEhxpZK5WCpfD^UmM_iYPe}wpE!Djai6_{ z*pGO=WB47#Xjb7!n2Ma)s^yeR*1rTxp`Mt4sfA+`HwZf%!7ZqGosPkw69`Ix5Ku6G z@Pa;pjzV&dn{M=QDx89t?p?d9gna*}jBly*#1!6}5K<*xDPJ{wv4& zM$17DFd~L*Te3A%yD;Dp9UGWTjRxAvMu!j^Tbc}2v~q^59d4bz zvu#!IJCy(BcWTc`;v$9tH;J%oiSJ_i7s;2`JXZF+qd4C)vY!hyCtl)sJIC{ebI*0> z@x>;EzyBv>AI-~{D6l6{ST=em*U( z(r$nuXY-#CCi^8Z2#v#UXOt`dbYN1z5jzNF2 z411?w)whZrfA20;nl&C1Gi+gk<`JSm+{|*2o<< zqM#@z_D`Cn|0H^9$|Tah)0M_X4c37|KQ*PmoT@%xHc3L1ZY6(p(sNXHa&49Frzto& zR`c~ClHpE~4Z=uKa5S(-?M8EJ$zt0&fJk~p$M#fGN1-y$7!37hld`Uw>Urri(DxLa;=#rK0g4J)pXMC zxzraOVw1+kNWpi#P=6(qxf`zSdUC?D$i`8ZI@F>k6k zz21?d+dw7b&i*>Kv5L(LH-?J%@WnqT7j#qZ9B>|Zl+=> z^U-pV@1y_ptHo4hl^cPRWewbLQ#g6XYQ@EkiP z;(=SU!yhjHp%1&MsU`FV1Z_#K1&(|5n(7IHbx&gG28HNT)*~-BQi372@|->2Aw5It z0CBpUcMA*QvsPy)#lr!lIdCi@1k4V2m!NH)%Px(vu-r(Q)HYc!p zJ^$|)j^E#q#QOgcb^pd74^JUi7fUmMiNP_o*lvx*q%_odv49Dsv$NV;6J z9GOXKomA{2Pb{w}&+yHtH?IkJJu~}Z?{Uk++2mB8zyvh*xhHKE``99>y#TdD z&(MH^^JHf;g(Tbb^&8P*;_i*2&fS$7${3WJtV7K&&(MBV2~)2KB3%cWg#1!VE~k#C z!;A;?p$s{ihyojEZz+$I1)L}&G~ml=udD9qh>Tu(ylv)?YcJT3ihapi!zgPtWb*CP zlLLJSRCj-^w?@;RU9aL2zDZY1`I3d<&OMuW=c3$o0#STpv_p3b9Wtbql>w^bBi~u4 z3D8KyF?YE?=HcKk!xcp@Cigvzy=lnFgc^9c%(^F22BWYNAYRSho@~*~S)4%AhEttv zvq>7X!!EWKG?mOd9&n>vvH1p4VzE?HCuxT-u+F&mnsfDI^}*-d00-KAauEaXqg3k@ zy#)MGX!X;&3&0s}F3q40ZmVM$(H3CLfpdL?hB6nVqMxX)q=1b}o_PG%r~hZ4gUfSp zOH4qlEOW4OMUc)_m)fMR_rl^pCfXc{$fQbI*E&mV77}kRF z&{<06AJyJ!e863o-V>FA1a9Eemx6>^F$~9ppt()ZbPGfg_NdRXBWoZnDy2;#ODgf! zgl?iOcF7Meo|{AF>KDwTgYrJLb$L2%%BEtO>T$C?|9bAB&}s;gI?lY#^tttY&hfr# zKhC+&b-rpg_?~uVK%S@mQleU#_xCsvIPK*<`E0fHE1&!J7!xD#IB|SSPW6-PyuqGn3^M^Rz%WT{e?OI^svARX&SAdU77V(C~ zM$H{Kg59op{<|8ry9ecfP%=kFm(-!W&?U0@<%z*+!*<e0XesMxRFu9QnGqun6R_%T+B%&9Dtk?*d$Q zb~>84jEAPi@&F@3wAa^Lzc(AJz5gsfZ7J53;@D<;Klpl?sK&u@gie`~vTsbOE~Cd4 z%kr56mI|#b(Jk&;p6plVwmNB0H@0SmgdmjIn5Ne@)}7Vty(yb2t3ev@22AE^s!KaN zyQ>j+F3w=wnx7w@FVCRe+`vUH)3gW%_72fxzqX!S&!dchdkRiHbXW1FMrIIBwjsai8`CB2r4mAbwp%rrO>3B$Zw;9=%fXI9B{d(UzVap7u z6piC-FQ)>}VOEuPpuqznpY`hN4dGa_1Xz9rVg(;H$5Te^F0dDv*gz9JS<|>>U0J^# z6)(4ICh+N_Q`Ft0hF|3fSHs*?a=XC;e`sJaU9&d>X4l?1W=|fr!5ShD|nv$GK;j46@BV6+{oRbWfqOBRb!ir88XD*SbC(LF}I1h#6@dvK%Toe%@ zhDyG$93H8Eu&gCYddP58iF3oQH*zLbNI;rN@E{T9%A8!=v#JLxKyUe}e}BJpB{~uN zqgxRgo0*-@-iaHPV8bTOH(rS(huwK1Xg0u+e!`(Irzu@Bld&s5&bWgVc@m7;JgELd zimVs`>vQ}B_1(2#rv#N9O`fJpVfPc7V2nv34PC);Dzbb;p!6pqHzvy?2pD&1NE)?A zt(t-ucqy@wn9`^MN5apa7K|L=9>ISC>xoc#>{@e}m#YAAa1*8-RUMKwbm|;5p>T`Z zNf*ph@tnF{gmDa3uwwN(g=`Rh)4!&)^oOy@VJaK4lMT&5#YbXkl`q?<*XtsqD z9PRK6bqb)fJw0g-^a@nu`^?71k|m3RPRjt;pIkCo1{*pdqbVs-Yl>4E>3fZx3Sv44grW=*qdSoiZ9?X0wWyO4`yDHh2E!9I!ZFi zVL8|VtW38}BOJHW(Ax#KL_KQzarbuE{(%TA)AY)@tY4%A%P%SqIU~8~-Lp3qY;U-} z`h_Gel7;K1h}7$_5ZZT0&%$Lxxr-<89V&&TCsu}LL#!xpQ1O31jaa{U34~^le*Y%L za?7$>Jk^k^pS^_M&cDs}NgXlR>16AHkSK-4TRaJSh#h&p!-!vQY%f+bmn6x`4fwTp z$727L^y`~!exvmE^W&#@uY!NxJi`g!i#(++!)?iJ(1)2Wk;RN zFK&O4eTkP$Xn~4bB|q8y(btx$R#D`O@epi4ofcETrx!IM(kWNEe42Qh(8*KqfP(c0 zouBl6>Fc_zM+V;F3znbo{x#%!?mH3`_ANJ?y7ppxS@glg#S9^MXu|FM&ynpz3o&Qh z2ujAHLF3($pH}0jXQsa#?t--TnF1P73b?4`KeJ9^qK-USHE)4!IYgMn-7z|=ALF5SNGkrtPG@Y~niUQV2?g$vzJN3nZ{7;HZHzWAeQ;5P|@Tl3YHpyznGG4-f4=XflwSJY+58-+wf?~Fg@1p1wkzuu-RF3j2JX37SQUc? zQ4v%`V8z9ZVZVqS8h|@@RpD?n0W<=hk=3Cf8R?d^9YK&e9ZybFY%jdnA)PeHvtBe- zhMLD+SSteHBq*q)d6x{)s1UrsO!byyLS$58WK;sqip$Mk{l)Y(_6hEIBsIjCr5t>( z7CdKUrJTrW%qZ#1z^n*Lb8#VdfzPw~OIL76aC+Rhr<~;4Tl!sw?Rj6hXj4XWa#6Tp z@)kJ~qOV)^Rh*-?aG>ic2*NlC2M7&LUzc9RT6WM%Cpe78`iAowe!>(T0jo&ivn8-7 zs{Qa@cGy$rE-3AY0V(l8wjI^uB8Lchj@?L}fYal^>T9z;8juH@?rG&g-t+R2dVDBe zq!K%{e-rT5jX19`(bP23LUN4+_zh2KD~EAYzhpEO3MUG8@}uBHH@4J zd`>_(K4q&>*k82(dDuC)X6JuPrBBubOg7qZ{?x!r@{%0);*`h*^F|%o?&1wX?Wr4b z1~&cy#PUuES{C#xJ84!z<1tp9sfrR(i%Tu^jnXy;4`Xk;AQCdFC@?V%|; zySdC7qS|uQRcH}EFZH%mMB~7gi}a0utE}ZE_}8PQH8f;H%PN41Cb9R%w5Oi5el^fd z$n{3SqLCnrF##x?4sa^r!O$7NX!}&}V;0ZGQ&K&i%6$3C_dR%I7%gdQ;KT6YZiQrW zk%q<74oVBV>@}CvJ4Wj!d^?#Zwq(b$E1ze4$99DuNg?6t9H}k_|D7KWD7i0-g*EO7 z;5{hSIYE4DMOK3H%|f5Edx+S0VI0Yw!tsaRS2&Il2)ea^8R5TG72BrJue|f_{2UHa z@w;^c|K3da#$TB0P3;MPlF7RuQeXT$ zS<<|C0OF(k)>fr&wOB=gP8!Qm>F41u;3esv7_0l%QHt(~+n; zf!G6%hp;Gfa9L9=AceiZs~tK+Tf*Wof=4!u{nIO90jH@iS0l+#%8=~%ASzFv7zqSB^?!@N7)kp0t&tCGLmzXSRMRyxCmCYUD2!B`? zhs$4%KO~m=VFk3Buv9osha{v+mAEq=ik3RdK@;WWTV_g&-$U4IM{1IhGX{pAu%Z&H zFfwCpUsX%RKg);B@7OUzZ{Hn{q6Vv!3#8fAg!P$IEx<0vAx;GU%}0{VIsmFBPq_mb zpe^BChDK>sc-WLKl<6 zwbW|e&d&dv9Wu0goueyu>(JyPx1mz0v4E?cJjFuKF71Q1)AL8jHO$!fYT3(;U3Re* zPPOe%*O+@JYt1bW`!W_1!mN&=w3G9ru1XsmwfS~BJ))PhD(+_J_^N6j)sx5VwbWK| zwRyC?W<`pOCY)b#AS?rluxuuGf-AJ=D!M36l{ua?@SJ5>e!IBr3CXIxWw5xUZ@Xrw z_R@%?{>d%Ld4p}nEsiA@v*nc6Ah!MUs?GA7e5Q5lPpp0@`%5xY$C;{%rz24$;vR#* zBP=a{)K#CwIY%p} zXVdxTQ^HS@O&~eIftU+Qt^~(DGxrdi3k}DdT^I7Iy5SMOp$QuD8s;+93YQ!OY{eB24%xY7ml@|M7I(Nb@K_-?F;2?et|CKkuZK_>+>Lvg!>JE~wN`BI|_h6$qi!P)+K-1Hh(1;a`os z55)4Q{oJiA(lQM#;w#Ta%T0jDNXIPM_bgESMCDEg6rM33anEr}=|Fn6)|jBP6Y}u{ zv9@%7*#RI9;fv;Yii5CI+KrRdr0DKh=L>)eO4q$1zmcSmglsV`*N(x=&Wx`*v!!hn6X-l0 zP_m;X??O(skcj+oS$cIdKhfT%ABAzz3w^la-Ucw?yBPEC+=Pe_vU8nd-HV5YX6X8r zZih&j^eLU=%*;VzhUyoLF;#8QsEfmByk+Y~caBqSvQaaWf2a{JKB9B>V&r?l^rXaC z8)6AdR@Qy_BxQrE2Fk?ewD!SwLuMj@&d_n5RZFf7=>O>hzVE*seW3U?_p|R^CfoY`?|#x9)-*yjv#lo&zP=uI`M?J zbzC<^3x7GfXA4{FZ72{PE*-mNHyy59Q;kYG@BB~NhTd6pm2Oj=_ zizmD?MKVRkT^KmXuhsk?eRQllPo2Ubk=uCKiZ&u3Xjj~<(!M94c)Tez@9M1Gfs5JV z->@II)CDJOXTtPrQudNjE}Eltbjq>6KiwAwqvAKd^|g!exgLG3;wP+#mZYr`cy3#39e653d=jrR-ulW|h#ddHu(m9mFoW~2yE zz5?dB%6vF}+`-&-W8vy^OCxm3_{02royjvmwjlp+eQDzFVEUiyO#gLv%QdDSI#3W* z?3!lL8clTaNo-DVJw@ynq?q!%6hTQi35&^>P85G$TqNt78%9_sSJt2RThO|JzM$iL zg|wjxdMC2|Icc5rX*qPL(coL!u>-xxz-rFiC!6hD1IR%|HSRsV3>Kq~&vJ=s3M5y8SG%YBQ|{^l#LGlg!D?E>2yR*eV%9m$_J6VGQ~AIh&P$_aFbh zULr0Z$QE!QpkP=aAeR4ny<#3Fwyw@rZf4?Ewq`;mCVv}xaz+3ni+}a=k~P+yaWt^L z@w67!DqVf7D%7XtXX5xBW;Co|HvQ8WR1k?r2cZD%U;2$bsM%u8{JUJ5Z0k= zZJARv^vFkmWx15CB=rb=D4${+#DVqy5$C%bf`!T0+epLJLnh1jwCdb*zuCL}eEFvE z{rO1%gxg>1!W(I!owu*mJZ0@6FM(?C+d*CeceZRW_4id*D9p5nzMY&{mWqrJomjIZ z97ZNnZ3_%Hx8dn;H>p8m7F#^2;T%yZ3H;a&N7tm=Lvs&lgJLW{V1@h&6Vy~!+Ffbb zv(n3+v)_D$}dqd!2>Y2B)#<+o}LH#%ogGi2-?xRIH)1!SD)u-L65B&bsJTC=LiaF+YOCif2dUX6uAA|#+vNR z>U+KQekVGon)Yi<93(d!(yw1h3&X0N(PxN2{%vn}cnV?rYw z$N^}_o!XUB!mckL`yO1rnUaI4wrOeQ(+&k?2mi47hzxSD`N#-byqd1IhEoh!PGq>t z_MRy{5B0eKY>;Ao3z$RUU7U+i?iX^&r739F)itdrTpAi-NN0=?^m%?{A9Ly2pVv>Lqs6moTP?T2-AHqFD-o_ znVr|7OAS#AEH}h8SRPQ@NGG47dO}l=t07__+iK8nHw^(AHx&Wb<%jPc$$jl6_p(b$ z)!pi(0fQodCHfM)KMEMUR&UID>}m^(!{C^U7sBDOA)$VThRCI0_+2=( zV8mMq0R(#z;C|7$m>$>`tX+T|xGt(+Y48@ZYu#z;0pCgYgmMVbFb!$?%yhZqP_nhn zy4<#3P1oQ#2b51NU1mGnHP$cf0j-YOgAA}A$QoL6JVLcmExs(kU{4z;PBHJD%_=0F z>+sQV`mzijSIT7xn%PiDKHOujX;n|M&qr1T@rOxTdxtZ!&u&3HHFLYD5$RLQ=heur zb>+AFokUVQeJy-#LP*^)spt{mb@Mqe=A~-4p0b+Bt|pZ+@CY+%x}9f}izU5;4&QFE zO1bhg&A4uC1)Zb67kuowWY4xbo&J=%yoXlFB)&$d*-}kjBu|w!^zbD1YPc0-#XTJr z)pm2RDy%J3jlqSMq|o%xGS$bPwn4AqitC6&e?pqWcjWPt{3I{>CBy;hg0Umh#c;hU3RhCUX=8aR>rmd` z7Orw(5tcM{|-^J?ZAA9KP|)X6n9$-kvr#j5YDecTM6n z&07(nD^qb8hpF0B^z^pQ*%5ePYkv&FabrlI61ntiVp!!C8y^}|<2xgAd#FY=8b*y( zuQOuvy2`Ii^`VBNJB&R!0{hABYX55ooCAJSSevl4RPqEGb)iy_0H}v@vFwFzD%>#I>)3PsouQ+_Kkbqy*kKdHdfkN7NBcq%V{x^fSxgXpg7$bF& zj!6AQbDY(1u#1_A#1UO9AxiZaCVN2F0wGXdY*g@x$ByvUA?ePdide0dmr#}udE%K| z3*k}Vv2Ew2u1FXBaVA6aerI36R&rzEZeDDCl5!t0J=ug6kuNZzH>3i_VN`%BsaVB3 zQYw|Xub_SGf{)F{$ZX5`Jc!X!;eybjP+o$I{Z^Hsj@D=E{MnnL+TbC@HEU2DjG{3-LDGIbq()U87x4eS;JXnSh;lRlJ z>EL3D>wHt-+wTjQF$fGyDO$>d+(fq@bPpLBS~xA~R=3JPbS{tzN(u~m#Po!?H;IYv zE;?8%^vle|%#oux(Lj!YzBKv+Fd}*Ur-dCBoX*t{KeNM*n~ZPYJ4NNKkI^MFbz9!v z4(Bvm*Kc!-$%VFEewYJKz-CQN{`2}KX4*CeJEs+Q(!kI%hN1!1P6iOq?ovz}X0IOi z)YfWpwW@pK08^69#wSyCZkX9?uZD?C^@rw^Y?gLS_xmFKkooyx$*^5#cPqntNTtSG zlP>XLMj2!VF^0k#ole7`-c~*~+_T5ls?x4)ah(j8vo_ zwb%S8qoaZqY0-$ZI+ViIA_1~~rAH7K_+yFS{0rT@eQtTAdz#8E5VpwnW!zJ_^{Utv zlW5Iar3V5t&H4D6A=>?mq;G92;1cg9a2sf;gY9pJDVKn$DYdQlvfXq}zz8#LyPGq@ z+`YUMD;^-6w&r-82JL7mA8&M~Pj@aK!m{0+^v<|t%APYf7`}jGEhdYLqsHW-Le9TL z_hZZ1gbrz7$f9^fAzVIP30^KIz!!#+DRLL+qMszvI_BpOSmjtl$hh;&UeM{ER@INV zcI}VbiVTPoN|iSna@=7XkP&-4#06C};8ajbxJ4Gcq8(vWv4*&X8bM^T$mBk75Q92j z1v&%a;OSKc8EIrodmIiw$lOES2hzGDcjjB`kEDfJe{r}yE6`eZL zEB`9u>Cl0IsQ+t}`-cx}{6jqcANucqIB>Qmga_&<+80E2Q|VHHQ$YlAt{6`Qu`HA3 z03s0-sSlwbvgi&_R8s={6<~M^pGvBNjKOa>tWenzS8s zR>L7R5aZ=mSU{f?ib4Grx$AeFvtO5N|D>9#)ChH#Fny2maHWHOf2G=#<9Myot#+4u zWVa6d^Vseq_0=#AYS(-m$Lp;*8nC_6jXIjEM`omUmtH@QDs3|G)i4j*#_?#UYVZvJ z?YjT-?!4Q{BNun;dKBWLEw2C-VeAz`%?A>p;)PL}TAZn5j~HK>v1W&anteARlE+~+ zj>c(F;?qO3pXBb|#OZdQnm<4xWmn~;DR5SDMxt0UK_F^&eD|KZ=O;tO3vy4@4h^;2 zUL~-z`-P1aOe?|ZC1BgVsL)2^J-&vIFI%q@40w0{jjEfeVl)i9(~bt2z#2Vm)p`V_ z1;6$Ae7=YXk#=Qkd24Y23t&GvRxaOoad~NbJ+6pxqzJ>FY#Td7@`N5xp!n(c!=RE& z&<<@^a$_Ys8jqz4|5Nk#FY$~|FPC0`*a5HH!|Gssa9=~66&xG9)|=pOOJ2KE5|YrR zw!w6K2aC=J$t?L-;}5hn6mHd%hC;p8P|Dgh6D>hGnXPgi;6r+eA=?f72y9(Cf_ho{ zH6#)uD&R=73^$$NE;5piWX2bzR67fQ)`b=85o0eOLGI4c-Tb@-KNi2pz=Ke@SDcPn za$AxXib84`!Sf;Z3B@TSo`Dz7GM5Kf(@PR>Ghzi=BBxK8wRp>YQoXm+iL>H*Jo9M3 z6w&E?BC8AFTFT&Tv8zf+m9<&S&%dIaZ)Aoqkak_$r-2{$d~0g2oLETx9Y`eOAf14QXEQw3tJne;fdzl@wV#TFXSLXM2428F-Q}t+n2g%vPRMUzYPvzQ9f# zu(liiJem9P*?0%V@RwA7F53r~|I!Ty)<*AsMX3J{_4&}{6pT%Tpw>)^|DJ)>gpS~1rNEh z0$D?uO8mG?H;2BwM5a*26^7YO$XjUm40XmBsb63MoR;bJh63J;OngS5sSI+o2HA;W zdZV#8pDpC9Oez&L8loZO)MClRz!_!WD&QRtQxnazhT%Vj6Wl4G11nUk8*vSeVab@N#oJ}`KyJv+8Mo@T1-pqZ1t|?cnaVOd;1(h9 z!$DrN=jcGsVYE-0-n?oCJ^4x)F}E;UaD-LZUIzcD?W^ficqJWM%QLy6QikrM1aKZC zi{?;oKwq^Vsr|&`i{jIphA8S6G4)$KGvpULjH%9u(Dq247;R#l&I0{IhcC|oBF*Al zvLo7Xte=C{aIt*otJD}BUq)|_pdR>{zBMT< z(^1RpZv*l*m*OV^8>9&asGBo8h*_4q*)-eCv*|Pq=XNGrZE)^(SF7^{QE_~4VDB(o zVcPA_!G+2CAtLbl+`=Q~9iW`4ZRLku!uB?;tWqVjB0lEOf}2RD7dJ=BExy=<9wkb- z9&7{XFA%n#JsHYN8t5d~=T~5DcW4$B%3M+nNvC2`0!#@sckqlzo5;hhGi(D9=*A4` z5ynobawSPRtWn&CDLEs3Xf`(8^zDP=NdF~F^s&={l7(aw&EG}KWpMjtmz7j_VLO;@ zM2NVLDxZ@GIv7*gzl1 zjq78tv*8#WSY`}Su0&C;2F$Ze(q>F(@Wm^Gw!)(j;dk9Ad{STaxn)IV9FZhm*n+U} zi;4y*3v%A`_c7a__DJ8D1b@dl0Std3F||4Wtvi)fCcBRh!X9$1x!_VzUh>*S5s!oq z;qd{J_r79EL2wIeiGAqFstWtkfIJpjVh%zFo*=55B9Zq~y0=^iqHWfQl@O!Ak;(o*m!pZqe9 z%U2oDOhR)BvW8&F70L;2TpkzIutIvNQaTjjs5V#8mV4!NQ}zN=i`i@WI1z0eN-iCS z;vL-Wxc^Vc_qK<5RPh(}*8dLT{~GzE{w2o$2kMFaEl&q zP{V=>&3kW7tWaK-Exy{~`v4J0U#OZBk{a9{&)&QG18L@6=bsZ1zC_d{{pKZ-Ey>I> z;8H0t4bwyQqgu4hmO`3|4K{R*5>qnQ&gOfdy?z`XD%e5+pTDzUt3`k^u~SaL&XMe= z9*h#kT(*Q9jO#w2Hd|Mr-%DV8i_1{J1MU~XJ3!WUplhXDYBpJH><0OU`**nIvPIof z|N8@I=wA)sf45SAvx||f?Z5uB$kz1qL3Ky_{%RPdP5iN-D2!p5scq}buuC00C@jom zhfGKm3|f?Z0iQ|K$Z~!`8{nmAS1r+fp6r#YDOS8V*;K&Gs7Lc&f^$RC66O|)28oh`NHy&vq zJh+hAw8+ybTB0@VhWN^0iiTnLsCWbS_y`^gs!LX!Lw{yE``!UVzrV24tP8o;I6-65 z1MUiHw^{bB15tmrVT*7-#sj6cs~z`wk52YQJ*TG{SE;KTm#Hf#a~|<(|ImHH17nNM z`Ub{+J3dMD!)mzC8b(2tZtokKW5pAwHa?NFiso~# z1*iaNh4lQ4TS)|@G)H4dZV@l*Vd;Rw;-;odDhW2&lJ%m@jz+Panv7LQm~2Js6rOW3 z0_&2cW^b^MYW3)@o;neZ<{B4c#m48dAl$GCc=$>ErDe|?y@z`$uq3xd(%aAsX)D%l z>y*SQ%My`yDP*zof|3@_w#cjaW_YW4BdA;#Glg1RQcJGY*CJ9`H{@|D+*e~*457kd z73p<%fB^PV!Ybw@)Dr%(ZJbX}xmCStCYv#K3O32ej{$9IzM^I{6FJ8!(=azt7RWf4 z7ib0UOPqN40X!wOnFOoddd8`!_IN~9O)#HRTyjfc#&MCZ zZAMzOVB=;qwt8gV?{Y2?b=iSZG~RF~uyx18K)IDFLl})G1v@$(s{O4@RJ%OTJyF+Cpcx4jmy|F3euCnMK!P2WTDu5j z{{gD$=M*pH!GGzL%P)V2*ROm>!$Y=z|D`!_yY6e7SU$~a5q8?hZGgaYqaiLnkK%?0 zs#oI%;zOxF@g*@(V4p!$7dS1rOr6GVs6uYCTt2h)eB4?(&w8{#o)s#%gN@BBosRUe z)@P@8_Zm89pr~)b>e{tbPC~&_MR--iB{=)y;INU5#)@Gix-YpgP<-c2Ms{9zuCX|3 z!p(?VaXww&(w&uBHzoT%!A2=3HAP>SDxcljrego7rY|%hxy3XlODWffO_%g|l+7Y_ zqV(xbu)s4lV=l7M;f>vJl{`6qBm>#ZeMA}kXb97Z)?R97EkoI?x6Lp0yu1Z>PS?2{ z0QQ(8D)|lc9CO3B~e(pQM&5(1y&y=e>C^X$`)_&XuaI!IgDTVqt31wX#n+@!a_A0ZQkA zCJ2@M_4Gb5MfCrm5UPggeyh)8 zO9?`B0J#rkoCx(R0I!ko_2?iO@|oRf1;3r+i)w-2&j?=;NVIdPFsB)`|IC0zk6r9c zRrkfxWsiJ(#8QndNJj@{@WP2Ackr|r1VxV{7S&rSU(^)-M8gV>@UzOLXu9K<{6e{T zXJ6b92r$!|lwjhmgqkdswY&}c)KW4A)-ac%sU;2^fvq7gfUW4Bw$b!i@duy1CAxSn z(pyh$^Z=&O-q<{bZUP+$U}=*#M9uVc>CQVgDs4swy5&8RAHZ~$)hrTF4W zPsSa~qYv_0mJnF89RnnJTH`3}w4?~epFl=D(35$ zWa07ON$`OMBOHgCmfO(9RFc<)?$x)N}Jd2A(<*Ll7+4jrRt9w zwGxExUXd9VB#I|DwfxvJ;HZ8Q{37^wDhaZ%O!oO(HpcqfLH%#a#!~;Jl7F5>EX_=8 z{()l2NqPz>La3qJR;_v+wlK>GsHl;uRA8%j`A|yH@k5r%55S9{*Cp%uw6t`qc1!*T za2OeqtQj7sAp#Q~=5Fs&aCR9v>5V+s&RdNvo&H~6FJOjvaj--2sYYBvMq;55%z8^o z|BJDA4vzfow#DO#ZQHh;Oq_{r+qP{R9ox2TOgwQiv7Ow!zjN+A@BN;0tA2lUb#+zO z(^b89eV)D7UVE+h{mcNc6&GtpOqDn_?VAQ)Vob$hlFwW%xh>D#wml{t&Ofmm_d_+; zKDxzdr}`n2Rw`DtyIjrG)eD0vut$}dJAZ0AohZ+ZQdWXn_Z@dI_y=7t3q8x#pDI-K z2VVc&EGq445Rq-j0=U=Zx`oBaBjsefY;%)Co>J3v4l8V(T8H?49_@;K6q#r~Wwppc z4XW0(4k}cP=5ex>-Xt3oATZ~bBWKv)aw|I|Lx=9C1s~&b77idz({&q3T(Y(KbWO?+ zmcZ6?WeUsGk6>km*~234YC+2e6Zxdl~<_g2J|IE`GH%n<%PRv-50; zH{tnVts*S5*_RxFT9eM0z-pksIb^drUq4>QSww=u;UFCv2AhOuXE*V4z?MM`|ABOC4P;OfhS(M{1|c%QZ=!%rQTDFx`+}?Kdx$&FU?Y<$x;j7z=(;Lyz+?EE>ov!8vvMtSzG!nMie zsBa9t8as#2nH}n8xzN%W%U$#MHNXmDUVr@GX{?(=yI=4vks|V)!-W5jHsU|h_&+kY zS_8^kd3jlYqOoiI`ZqBVY!(UfnAGny!FowZWY_@YR0z!nG7m{{)4OS$q&YDyw6vC$ zm4!$h>*|!2LbMbxS+VM6&DIrL*X4DeMO!@#EzMVfr)e4Tagn~AQHIU8?e61TuhcKD zr!F4(kEebk(Wdk-?4oXM(rJwanS>Jc%<>R(siF+>+5*CqJLecP_we33iTFTXr6W^G z7M?LPC-qFHK;E!fxCP)`8rkxZyFk{EV;G-|kwf4b$c1k0atD?85+|4V%YATWMG|?K zLyLrws36p%Qz6{}>7b>)$pe>mR+=IWuGrX{3ZPZXF3plvuv5Huax86}KX*lbPVr}L z{C#lDjdDeHr~?l|)Vp_}T|%$qF&q#U;ClHEPVuS+Jg~NjC1RP=17=aQKGOcJ6B3mp z8?4*-fAD~}sX*=E6!}^u8)+m2j<&FSW%pYr_d|p_{28DZ#Cz0@NF=gC-o$MY?8Ca8 zr5Y8DSR^*urS~rhpX^05r30Ik#2>*dIOGxRm0#0YX@YQ%Mg5b6dXlS!4{7O_kdaW8PFSdj1=ryI-=5$fiieGK{LZ+SX(1b=MNL!q#lN zv98?fqqTUH8r8C7v(cx#BQ5P9W>- zmW93;eH6T`vuJ~rqtIBg%A6>q>gnWb3X!r0wh_q;211+Om&?nvYzL1hhtjB zK_7G3!n7PL>d!kj){HQE zE8(%J%dWLh1_k%gVXTZt zEdT09XSKAx27Ncaq|(vzL3gm83q>6CAw<$fTnMU05*xAe&rDfCiu`u^1)CD<>sx0i z*hr^N_TeN89G(nunZoLBf^81#pmM}>JgD@Nn1l*lN#a=B=9pN%tmvYFjFIoKe_(GF z-26x{(KXdfsQL7Uv6UtDuYwV`;8V3w>oT_I<`Ccz3QqK9tYT5ZQzbop{=I=!pMOCb zCU68`n?^DT%^&m>A%+-~#lvF!7`L7a{z<3JqIlk1$<||_J}vW1U9Y&eX<}l8##6i( zZcTT@2`9(Mecptm@{3A_Y(X`w9K0EwtPq~O!16bq{7c0f7#(3wn-^)h zxV&M~iiF!{-6A@>o;$RzQ5A50kxXYj!tcgme=Qjrbje~;5X2xryU;vH|6bE(8z^<7 zQ>BG7_c*JG8~K7Oe68i#0~C$v?-t@~@r3t2inUnLT(c=URpA9kA8uq9PKU(Ps(LVH zqgcqW>Gm?6oV#AldDPKVRcEyQIdTT`Qa1j~vS{<;SwyTdr&3*t?J)y=M7q*CzucZ&B0M=joT zBbj@*SY;o2^_h*>R0e({!QHF0=)0hOj^B^d*m>SnRrwq>MolNSgl^~r8GR#mDWGYEIJA8B<|{{j?-7p zVnV$zancW3&JVDtVpIlI|5djKq0(w$KxEFzEiiL=h5Jw~4Le23@s(mYyXWL9SX6Ot zmb)sZaly_P%BeX_9 zw&{yBef8tFm+%=--m*J|o~+Xg3N+$IH)t)=fqD+|fEk4AAZ&!wcN5=mi~Vvo^i`}> z#_3ahR}Ju)(Px7kev#JGcSwPXJ2id9%Qd2A#Uc@t8~egZ8;iC{e! z%=CGJOD1}j!HW_sgbi_8suYnn4#Ou}%9u)dXd3huFIb!ytlX>Denx@pCS-Nj$`VO&j@(z!kKSP0hE4;YIP#w9ta=3DO$7f*x zc9M4&NK%IrVmZAe=r@skWD`AEWH=g+r|*13Ss$+{c_R!b?>?UaGXlw*8qDmY#xlR= z<0XFbs2t?8i^G~m?b|!Hal^ZjRjt<@a? z%({Gn14b4-a|#uY^=@iiKH+k?~~wTj5K1A&hU z2^9-HTC)7zpoWK|$JXaBL6C z#qSNYtY>65T@Zs&-0cHeu|RX(Pxz6vTITdzJdYippF zC-EB+n4}#lM7`2Ry~SO>FxhKboIAF#Z{1wqxaCb{#yEFhLuX;Rx(Lz%T`Xo1+a2M}7D+@wol2)OJs$TwtRNJ={( zD@#zTUEE}#Fz#&(EoD|SV#bayvr&E0vzmb%H?o~46|FAcx?r4$N z&67W3mdip-T1RIxwSm_&(%U|+WvtGBj*}t69XVd&ebn>KOuL(7Y8cV?THd-(+9>G7*Nt%T zcH;`p={`SOjaf7hNd(=37Lz3-51;58JffzIPgGs_7xIOsB5p2t&@v1mKS$2D$*GQ6 zM(IR*j4{nri7NMK9xlDy-hJW6sW|ZiDRaFiayj%;(%51DN!ZCCCXz+0Vm#};70nOx zJ#yA0P3p^1DED;jGdPbQWo0WATN=&2(QybbVdhd=Vq*liDk`c7iZ?*AKEYC#SY&2g z&Q(Ci)MJ{mEat$ZdSwTjf6h~roanYh2?9j$CF@4hjj_f35kTKuGHvIs9}Re@iKMxS-OI*`0S z6s)fOtz}O$T?PLFVSeOjSO26$@u`e<>k(OSP!&YstH3ANh>)mzmKGNOwOawq-MPXe zy4xbeUAl6tamnx))-`Gi2uV5>9n(73yS)Ukma4*7fI8PaEwa)dWHs6QA6>$}7?(L8 ztN8M}?{Tf!Zu22J5?2@95&rQ|F7=FK-hihT-vDp!5JCcWrVogEnp;CHenAZ)+E+K5 z$Cffk5sNwD_?4+ymgcHR(5xgt20Z8M`2*;MzOM#>yhk{r3x=EyM226wb&!+j`W<%* zSc&|`8!>dn9D@!pYow~(DsY_naSx7(Z4i>cu#hA5=;IuI88}7f%)bRkuY2B;+9Uep zpXcvFWkJ!mQai63BgNXG26$5kyhZ2&*3Q_tk)Ii4M>@p~_~q_cE!|^A;_MHB;7s#9 zKzMzK{lIxotjc};k67^Xsl-gS!^*m*m6kn|sbdun`O?dUkJ{0cmI0-_2y=lTAfn*Y zKg*A-2sJq)CCJgY0LF-VQvl&6HIXZyxo2#!O&6fOhbHXC?%1cMc6y^*dOS{f$=137Ds1m01qs`>iUQ49JijsaQ( zksqV9@&?il$|4Ua%4!O15>Zy&%gBY&wgqB>XA3!EldQ%1CRSM(pp#k~-pkcCg4LAT zXE=puHbgsw)!xtc@P4r~Z}nTF=D2~j(6D%gTBw$(`Fc=OOQ0kiW$_RDd=hcO0t97h zb86S5r=>(@VGy1&#S$Kg_H@7G^;8Ue)X5Y+IWUi`o;mpvoV)`fcVk4FpcT|;EG!;? zHG^zrVVZOm>1KFaHlaogcWj(v!S)O(Aa|Vo?S|P z5|6b{qkH(USa*Z7-y_Uvty_Z1|B{rTS^qmEMLEYUSk03_Fg&!O3BMo{b^*`3SHvl0 zhnLTe^_vVIdcSHe)SQE}r~2dq)VZJ!aSKR?RS<(9lzkYo&dQ?mubnWmgMM37Nudwo z3Vz@R{=m2gENUE3V4NbIzAA$H1z0pagz94-PTJyX{b$yndsdKptmlKQKaaHj@3=ED zc7L?p@%ui|RegVYutK$64q4pe9+5sv34QUpo)u{1ci?)_7gXQd{PL>b0l(LI#rJmN zGuO+%GO`xneFOOr4EU(Wg}_%bhzUf;d@TU+V*2#}!2OLwg~%D;1FAu=Un>OgjPb3S z7l(riiCwgghC=Lm5hWGf5NdGp#01xQ59`HJcLXbUR3&n%P(+W2q$h2Qd z*6+-QXJ*&Kvk9ht0f0*rO_|FMBALen{j7T1l%=Q>gf#kma zQlg#I9+HB+z*5BMxdesMND`_W;q5|FaEURFk|~&{@qY32N$G$2B=&Po{=!)x5b!#n zxLzblkq{yj05#O7(GRuT39(06FJlalyv<#K4m}+vs>9@q-&31@1(QBv82{}Zkns~K ze{eHC_RDX0#^A*JQTwF`a=IkE6Ze@j#-8Q`tTT?k9`^ZhA~3eCZJ-Jr{~7Cx;H4A3 zcZ+Zj{mzFZbVvQ6U~n>$U2ZotGsERZ@}VKrgGh0xM;Jzt29%TX6_&CWzg+YYMozrM z`nutuS)_0dCM8UVaKRj804J4i%z2BA_8A4OJRQ$N(P9Mfn-gF;4#q788C@9XR0O3< zsoS4wIoyt046d+LnSCJOy@B@Uz*#GGd#+Ln1ek5Dv>(ZtD@tgZlPnZZJGBLr^JK+!$$?A_fA3LOrkoDRH&l7 zcMcD$Hsjko3`-{bn)jPL6E9Ds{WskMrivsUu5apD z?grQO@W7i5+%X&E&p|RBaEZ(sGLR@~(y^BI@lDMot^Ll?!`90KT!JXUhYS`ZgX3jnu@Ja^seA*M5R@f`=`ynQV4rc$uT1mvE?@tz)TN<=&H1%Z?5yjxcpO+6y_R z6EPuPKM5uxKpmZfT(WKjRRNHs@ib)F5WAP7QCADvmCSD#hPz$V10wiD&{NXyEwx5S z6NE`3z!IS^$s7m}PCwQutVQ#~w+V z=+~->DI*bR2j0^@dMr9`p>q^Ny~NrAVxrJtX2DUveic5vM%#N*XO|?YAWwNI$Q)_) zvE|L(L1jP@F%gOGtnlXtIv2&1i8q<)Xfz8O3G^Ea~e*HJsQgBxWL(yuLY+jqUK zRE~`-zklrGog(X}$9@ZVUw!8*=l`6mzYLtsg`AvBYz(cxmAhr^j0~(rzXdiOEeu_p zE$sf2(w(BPAvO5DlaN&uQ$4@p-b?fRs}d7&2UQ4Fh?1Hzu*YVjcndqJLw0#q@fR4u zJCJ}>_7-|QbvOfylj+e^_L`5Ep9gqd>XI3-O?Wp z-gt*P29f$Tx(mtS`0d05nHH=gm~Po_^OxxUwV294BDKT>PHVlC5bndncxGR!n(OOm znsNt@Q&N{TLrmsoKFw0&_M9$&+C24`sIXGWgQaz=kY;S{?w`z^Q0JXXBKFLj0w0U6P*+jPKyZHX9F#b0D1$&(- zrm8PJd?+SrVf^JlfTM^qGDK&-p2Kdfg?f>^%>1n8bu&byH(huaocL>l@f%c*QkX2i znl}VZ4R1en4S&Bcqw?$=Zi7ohqB$Jw9x`aM#>pHc0x z0$!q7iFu zZ`tryM70qBI6JWWTF9EjgG@>6SRzsd}3h+4D8d~@CR07P$LJ}MFsYi-*O%XVvD@yT|rJ+Mk zDllJ7$n0V&A!0flbOf)HE6P_afPWZmbhpliqJuw=-h+r;WGk|ntkWN(8tKlYpq5Ow z(@%s>IN8nHRaYb*^d;M(D$zGCv5C|uqmsDjwy4g=Lz>*OhO3z=)VD}C<65;`89Ye} zSCxrv#ILzIpEx1KdLPlM&%Cctf@FqTKvNPXC&`*H9=l=D3r!GLM?UV zOxa(8ZsB`&+76S-_xuj?G#wXBfDY@Z_tMpXJS7^mp z@YX&u0jYw2A+Z+bD#6sgVK5ZgdPSJV3>{K^4~%HV?rn~4D)*2H!67Y>0aOmzup`{D zzDp3c9yEbGCY$U<8biJ_gB*`jluz1ShUd!QUIQJ$*1;MXCMApJ^m*Fiv88RZ zFopLViw}{$Tyhh_{MLGIE2~sZ)t0VvoW%=8qKZ>h=adTe3QM$&$PO2lfqH@brt!9j ziePM8$!CgE9iz6B<6_wyTQj?qYa;eC^{x_0wuwV~W+^fZmFco-o%wsKSnjXFEx02V zF5C2t)T6Gw$Kf^_c;Ei3G~uC8SM-xyycmXyC2hAVi-IfXqhu$$-C=*|X?R0~hu z8`J6TdgflslhrmDZq1f?GXF7*ALeMmOEpRDg(s*H`4>_NAr`2uqF;k;JQ+8>A|_6ZNsNLECC%NNEb1Y1dP zbIEmNpK)#XagtL4R6BC{C5T(+=yA-(Z|Ap}U-AfZM#gwVpus3(gPn}Q$CExObJ5AC z)ff9Yk?wZ}dZ-^)?cbb9Fw#EjqQ8jxF4G3=L?Ra zg_)0QDMV1y^A^>HRI$x?Op@t;oj&H@1xt4SZ9(kifQ zb59B*`M99Td7@aZ3UWvj1rD0sE)d=BsBuW*KwkCds7ay(7*01_+L}b~7)VHI>F_!{ zyxg-&nCO?v#KOUec0{OOKy+sjWA;8rTE|Lv6I9H?CI?H(mUm8VXGwU$49LGpz&{nQp2}dinE1@lZ1iox6{ghN&v^GZv9J${7WaXj)<0S4g_uiJ&JCZ zr8-hsu`U%N;+9N^@&Q0^kVPB3)wY(rr}p7{p0qFHb3NUUHJb672+wRZs`gd1UjKPX z4o6zljKKA+Kkj?H>Ew63o%QjyBk&1!P22;MkD>sM0=z_s-G{mTixJCT9@_|*(p^bz zJ8?ZZ&;pzV+7#6Mn`_U-)k8Pjg?a;|Oe^us^PoPY$Va~yi8|?+&=y$f+lABT<*pZr zP}D{~Pq1Qyni+@|aP;ixO~mbEW9#c0OU#YbDZIaw=_&$K%Ep2f%hO^&P67hApZe`x zv8b`Mz@?M_7-)b!lkQKk)JXXUuT|B8kJlvqRmRpxtQDgvrHMXC1B$M@Y%Me!BSx3P z#2Eawl$HleZhhTS6Txm>lN_+I`>eV$&v9fOg)%zVn3O5mI*lAl>QcHuW6!Kixmq`X zBCZ*Ck6OYtDiK!N47>jxI&O2a9x7M|i^IagRr-fmrmikEQGgw%J7bO|)*$2FW95O4 zeBs>KR)izRG1gRVL;F*sr8A}aRHO0gc$$j&ds8CIO1=Gwq1%_~E)CWNn9pCtBE}+`Jelk4{>S)M)`Ll=!~gnn1yq^EX(+y*ik@3Ou0qU`IgYi3*doM+5&dU!cho$pZ zn%lhKeZkS72P?Cf68<#kll_6OAO26bIbueZx**j6o;I0cS^XiL`y+>{cD}gd%lux} z)3N>MaE24WBZ}s0ApfdM;5J_Ny}rfUyxfkC``Awo2#sgLnGPewK};dORuT?@I6(5~ z?kE)Qh$L&fwJXzK){iYx!l5$Tt|^D~MkGZPA}(o6f7w~O2G6Vvzdo*a;iXzk$B66$ zwF#;wM7A+(;uFG4+UAY(2`*3XXx|V$K8AYu#ECJYSl@S=uZW$ksfC$~qrrbQj4??z-)uz0QL}>k^?fPnJTPw% zGz)~?B4}u0CzOf@l^um}HZzbaIwPmb<)< zi_3@E9lc)Qe2_`*Z^HH;1CXOceL=CHpHS{HySy3T%<^NrWQ}G0i4e1xm_K3(+~oi$ zoHl9wzb?Z4j#90DtURtjtgvi7uw8DzHYmtPb;?%8vb9n@bszT=1qr)V_>R%s!92_` zfnHQPANx z<#hIjIMm#*(v*!OXtF+w8kLu`o?VZ5k7{`vw{Yc^qYclpUGIM_PBN1+c{#Vxv&E*@ zxg=W2W~JuV{IuRYw3>LSI1)a!thID@R=bU+cU@DbR^_SXY`MC7HOsCN z!dO4OKV7(E_Z8T#8MA1H`99?Z!r0)qKW_#|29X3#Jb+5+>qUidbeP1NJ@)(qi2S-X zao|f0_tl(O+$R|Qwd$H{_ig|~I1fbp_$NkI!0E;Y z6JrnU{1Ra6^on{9gUUB0mwzP3S%B#h0fjo>JvV~#+X0P~JV=IG=yHG$O+p5O3NUgG zEQ}z6BTp^Fie)Sg<){Z&I8NwPR(=mO4joTLHkJ>|Tnk23E(Bo`FSbPc05lF2-+)X? z6vV3*m~IBHTy*^E!<0nA(tCOJW2G4DsH7)BxLV8kICn5lu6@U*R`w)o9;Ro$i8=Q^V%uH8n3q=+Yf;SFRZu z!+F&PKcH#8cG?aSK_Tl@K9P#8o+jry@gdexz&d(Q=47<7nw@e@FFfIRNL9^)1i@;A z28+$Z#rjv-wj#heI|<&J_DiJ*s}xd-f!{J8jfqOHE`TiHHZVIA8CjkNQ_u;Ery^^t zl1I75&u^`1_q)crO+JT4rx|z2ToSC>)Or@-D zy3S>jW*sNIZR-EBsfyaJ+Jq4BQE4?SePtD2+jY8*%FsSLZ9MY>+wk?}}}AFAw)vr{ml)8LUG-y9>^t!{~|sgpxYc0Gnkg`&~R z-pilJZjr@y5$>B=VMdZ73svct%##v%wdX~9fz6i3Q-zOKJ9wso+h?VME7}SjL=!NUG{J?M&i!>ma`eoEa@IX`5G>B1(7;%}M*%-# zfhJ(W{y;>MRz!Ic8=S}VaBKqh;~7KdnGEHxcL$kA-6E~=!hrN*zw9N+_=odt<$_H_8dbo;0=42wcAETPCVGUr~v(`Uai zb{=D!Qc!dOEU6v)2eHSZq%5iqK?B(JlCq%T6av$Cb4Rko6onlG&?CqaX7Y_C_cOC3 zYZ;_oI(}=>_07}Oep&Ws7x7-R)cc8zfe!SYxJYP``pi$FDS)4Fvw5HH=FiU6xfVqIM!hJ;Rx8c0cB7~aPtNH(Nmm5Vh{ibAoU#J6 zImRCr?(iyu_4W_6AWo3*vxTPUw@vPwy@E0`(>1Qi=%>5eSIrp^`` zK*Y?fK_6F1W>-7UsB)RPC4>>Ps9)f+^MqM}8AUm@tZ->j%&h1M8s*s!LX5&WxQcAh z8mciQej@RPm?660%>{_D+7er>%zX_{s|$Z+;G7_sfNfBgY(zLB4Ey}J9F>zX#K0f6 z?dVNIeEh?EIShmP6>M+d|0wMM85Sa4diw1hrg|ITJ}JDg@o8y>(rF9mXk5M z2@D|NA)-7>wD&wF;S_$KS=eE84`BGw3g0?6wGxu8ys4rwI?9U=*^VF22t3%mbGeOh z`!O-OpF7#Vceu~F`${bW0nYVU9ecmk31V{tF%iv&5hWofC>I~cqAt@u6|R+|HLMMX zVxuSlMFOK_EQ86#E8&KwxIr8S9tj_goWtLv4f@!&h8;Ov41{J~496vp9vX=(LK#j! zAwi*21RAV-LD>9Cw3bV_9X(X3)Kr0-UaB*7Y>t82EQ%!)(&(XuAYtTsYy-dz+w=$ir)VJpe!_$ z6SGpX^i(af3{o=VlFPC);|J8#(=_8#vdxDe|Cok+ANhYwbE*FO`Su2m1~w+&9<_9~ z-|tTU_ACGN`~CNW5WYYBn^B#SwZ(t4%3aPp z;o)|L6Rk569KGxFLUPx@!6OOa+5OjQLK5w&nAmwxkC5rZ|m&HT8G%GVZxB_@ME z>>{rnXUqyiJrT(8GMj_ap#yN_!9-lO5e8mR3cJiK3NE{_UM&=*vIU`YkiL$1%kf+1 z4=jk@7EEj`u(jy$HnzE33ZVW_J4bj}K;vT?T91YlO(|Y0FU4r+VdbmQ97%(J5 zkK*Bed8+C}FcZ@HIgdCMioV%A<*4pw_n}l*{Cr4}a(lq|injK#O?$tyvyE`S%(1`H z_wwRvk#13ElkZvij2MFGOj`fhy?nC^8`Zyo%yVcUAfEr8x&J#A{|moUBAV_^f$hpaUuyQeY3da^ zS9iRgf87YBwfe}>BO+T&Fl%rfpZh#+AM?Dq-k$Bq`vG6G_b4z%Kbd&v>qFjow*mBl z-OylnqOpLg}or7_VNwRg2za3VBK6FUfFX{|TD z`Wt0Vm2H$vdlRWYQJqDmM?JUbVqL*ZQY|5&sY*?!&%P8qhA~5+Af<{MaGo(dl&C5t zE%t!J0 zh6jqANt4ABdPxSTrVV}fLsRQal*)l&_*rFq(Ez}ClEH6LHv{J#v?+H-BZ2)Wy{K@9 z+ovXHq~DiDvm>O~r$LJo!cOuwL+Oa--6;UFE2q@g3N8Qkw5E>ytz^(&($!O47+i~$ zKM+tkAd-RbmP{s_rh+ugTD;lriL~`Xwkad#;_aM?nQ7L_muEFI}U_4$phjvYgleK~`Fo`;GiC07&Hq1F<%p;9Q;tv5b?*QnR%8DYJH3P>Svmv47Y>*LPZJy8_{9H`g6kQpyZU{oJ`m%&p~D=K#KpfoJ@ zn-3cqmHsdtN!f?~w+(t+I`*7GQA#EQC^lUA9(i6=i1PqSAc|ha91I%X&nXzjYaM{8$s&wEx@aVkQ6M{E2 zfzId#&r(XwUNtPcq4Ngze^+XaJA1EK-%&C9j>^9(secqe{}z>hR5CFNveMsVA)m#S zk)_%SidkY-XmMWlVnQ(mNJ>)ooszQ#vaK;!rPmGKXV7am^_F!Lz>;~{VrIO$;!#30XRhE1QqO_~#+Ux;B_D{Nk=grn z8Y0oR^4RqtcYM)7a%@B(XdbZCOqnX#fD{BQTeLvRHd(irHKq=4*jq34`6@VAQR8WG z^%)@5CXnD_T#f%@-l${>y$tfb>2LPmc{~5A82|16mH)R?&r#KKLs7xpN-D`=&Cm^R zvMA6#Ahr<3X>Q7|-qfTY)}32HkAz$_mibYV!I)u>bmjK`qwBe(>za^0Kt*HnFbSdO z1>+ryKCNxmm^)*$XfiDOF2|{-v3KKB?&!(S_Y=Ht@|ir^hLd978xuI&N{k>?(*f8H z=ClxVJK_%_z1TH0eUwm2J+2To7FK4o+n_na)&#VLn1m;!+CX+~WC+qg1?PA~KdOlC zW)C@pw75_xoe=w7i|r9KGIvQ$+3K?L{7TGHwrQM{dCp=Z*D}3kX7E-@sZnup!BImw z*T#a=+WcTwL78exTgBn|iNE3#EsOorO z*kt)gDzHiPt07fmisA2LWN?AymkdqTgr?=loT7z@d`wnlr6oN}@o|&JX!yPzC*Y8d zu6kWlTzE1)ckyBn+0Y^HMN+GA$wUO_LN6W>mxCo!0?oiQvT`z$jbSEu&{UHRU0E8# z%B^wOc@S!yhMT49Y)ww(Xta^8pmPCe@eI5C*ed96)AX9<>))nKx0(sci8gwob_1}4 z0DIL&vsJ1_s%<@y%U*-eX z5rN&(zef-5G~?@r79oZGW1d!WaTqQn0F6RIOa9tJ=0(kdd{d1{<*tHT#cCvl*i>YY zH+L7jq8xZNcTUBqj(S)ztTU!TM!RQ}In*n&Gn<>(60G7}4%WQL!o>hbJqNDSGwl#H z`4k+twp0cj%PsS+NKaxslAEu9!#U3xT1|_KB6`h=PI0SW`P9GTa7caD1}vKEglV8# zjKZR`pluCW19c2fM&ZG)c3T3Um;ir3y(tSCJ7Agl6|b524dy5El{^EQBG?E61H0XY z`bqg!;zhGhyMFl&(o=JWEJ8n~z)xI}A@C0d2hQGvw7nGv)?POU@(kS1m=%`|+^ika zXl8zjS?xqW$WlO?Ewa;vF~XbybHBor$f<%I&*t$F5fynwZlTGj|IjZtVfGa7l&tK} zW>I<69w(cZLu)QIVG|M2xzW@S+70NinQzk&Y0+3WT*cC)rx~04O-^<{JohU_&HL5XdUKW!uFy|i$FB|EMu0eUyW;gsf`XfIc!Z0V zeK&*hPL}f_cX=@iv>K%S5kL;cl_$v?n(Q9f_cChk8Lq$glT|=e+T*8O4H2n<=NGmn z+2*h+v;kBvF>}&0RDS>)B{1!_*XuE8A$Y=G8w^qGMtfudDBsD5>T5SB;Qo}fSkkiV ze^K^M(UthkwrD!&*tTsu>Dacdj_q`~V%r_twr$(Ct&_dKeeXE?fA&4&yASJWJ*}~- zel=@W)tusynfC_YqH4ll>4Eg`Xjs5F7Tj>tTLz<0N3)X<1px_d2yUY>X~y>>93*$) z5PuNMQLf9Bu?AAGO~a_|J2akO1M*@VYN^VxvP0F$2>;Zb9;d5Yfd8P%oFCCoZE$ z4#N$^J8rxYjUE_6{T%Y>MmWfHgScpuGv59#4u6fpTF%~KB^Ae`t1TD_^Ud#DhL+Dm zbY^VAM#MrAmFj{3-BpVSWph2b_Y6gCnCAombVa|1S@DU)2r9W<> zT5L8BB^er3zxKt1v(y&OYk!^aoQisqU zH(g@_o)D~BufUXcPt!Ydom)e|aW{XiMnes2z&rE?og>7|G+tp7&^;q?Qz5S5^yd$i z8lWr4g5nctBHtigX%0%XzIAB8U|T6&JsC4&^hZBw^*aIcuNO47de?|pGXJ4t}BB`L^d8tD`H`i zqrP8?#J@8T#;{^B!KO6J=@OWKhAerih(phML`(Rg7N1XWf1TN>=Z3Do{l_!d~DND&)O)D>ta20}@Lt77qSnVsA7>)uZAaT9bsB>u&aUQl+7GiY2|dAEg@%Al3i316y;&IhQL^8fw_nwS>f60M_-m+!5)S_6EPM7Y)(Nq^8gL7(3 zOiot`6Wy6%vw~a_H?1hLVzIT^i1;HedHgW9-P#)}Y6vF%C=P70X0Tk^z9Te@kPILI z_(gk!k+0%CG)%!WnBjjw*kAKs_lf#=5HXC00s-}oM-Q1aXYLj)(1d!_a7 z*Gg4Fe6F$*ujVjI|79Z5+Pr`us%zW@ln++2l+0hsngv<{mJ%?OfSo_3HJXOCys{Ug z00*YR-(fv<=&%Q!j%b-_ppA$JsTm^_L4x`$k{VpfLI(FMCap%LFAyq;#ns5bR7V+x zO!o;c5y~DyBPqdVQX)8G^G&jWkBy2|oWTw>)?5u}SAsI$RjT#)lTV&Rf8;>u*qXnb z8F%Xb=7#$m)83z%`E;49)t3fHInhtc#kx4wSLLms!*~Z$V?bTyUGiS&m>1P(952(H zuHdv=;o*{;5#X-uAyon`hP}d#U{uDlV?W?_5UjJvf%11hKwe&(&9_~{W)*y1nR5f_ z!N(R74nNK`y8>B!0Bt_Vr!;nc3W>~RiKtGSBkNlsR#-t^&;$W#)f9tTlZz>n*+Fjz z3zXZ;jf(sTM(oDzJt4FJS*8c&;PLTW(IQDFs_5QPy+7yhi1syPCarvqrHFcf&yTy)^O<1EBx;Ir`5W{TIM>{8w&PB>ro4;YD<5LF^TjTb0!zAP|QijA+1Vg>{Afv^% zmrkc4o6rvBI;Q8rj4*=AZacy*n8B{&G3VJc)so4$XUoie0)vr;qzPZVbb<#Fc=j+8CGBWe$n|3K& z_@%?{l|TzKSlUEO{U{{%Fz_pVDxs7i9H#bnbCw7@4DR=}r_qV!Zo~CvD4ZI*+j3kO zW6_=|S`)(*gM0Z;;}nj`73OigF4p6_NPZQ-Od~e$c_);;4-7sR>+2u$6m$Gf%T{aq zle>e3(*Rt(TPD}03n5)!Ca8Pu!V}m6v0o1;5<1h$*|7z|^(3$Y&;KHKTT}hV056wuF0Xo@mK-52~r=6^SI1NC%c~CC?n>yX6wPTgiWYVz!Sx^atLby9YNn1Rk{g?|pJaxD4|9cUf|V1_I*w zzxK)hRh9%zOl=*$?XUjly5z8?jPMy%vEN)f%T*|WO|bp5NWv@B(K3D6LMl!-6dQg0 zXNE&O>Oyf%K@`ngCvbGPR>HRg5!1IV$_}m@3dWB7x3t&KFyOJn9pxRXCAzFr&%37wXG;z^xaO$ekR=LJG ztIHpY8F5xBP{mtQidqNRoz= z@){+N3(VO5bD+VrmS^YjG@+JO{EOIW)9=F4v_$Ed8rZtHvjpiEp{r^c4F6Ic#ChlC zJX^DtSK+v(YdCW)^EFcs=XP7S>Y!4=xgmv>{S$~@h=xW-G4FF9?I@zYN$e5oF9g$# zb!eVU#J+NjLyX;yb)%SY)xJdvGhsnE*JEkuOVo^k5PyS=o#vq!KD46UTW_%R=Y&0G zFj6bV{`Y6)YoKgqnir2&+sl+i6foAn-**Zd1{_;Zb7Ki=u394C5J{l^H@XN`_6XTKY%X1AgQM6KycJ+= zYO=&t#5oSKB^pYhNdzPgH~aEGW2=ec1O#s-KG z71}LOg@4UEFtp3GY1PBemXpNs6UK-ax*)#$J^pC_me;Z$Je(OqLoh|ZrW*mAMBFn< zHttjwC&fkVfMnQeen8`Rvy^$pNRFVaiEN4Pih*Y3@jo!T0nsClN)pdrr9AYLcZxZ| zJ5Wlj+4q~($hbtuY zVQ7hl>4-+@6g1i`1a)rvtp-;b0>^`Dloy(#{z~ytgv=j4q^Kl}wD>K_Y!l~ zp(_&7sh`vfO(1*MO!B%<6E_bx1)&s+Ae`O)a|X=J9y~XDa@UB`m)`tSG4AUhoM=5& znWoHlA-(z@3n0=l{E)R-p8sB9XkV zZ#D8wietfHL?J5X0%&fGg@MH~(rNS2`GHS4xTo7L$>TPme+Is~!|79=^}QbPF>m%J zFMkGzSndiPO|E~hrhCeo@&Ea{M(ieIgRWMf)E}qeTxT8Q#g-!Lu*x$v8W^M^>?-g= zwMJ$dThI|~M06rG$Sv@C@tWR>_YgaG&!BAbkGggVQa#KdtDB)lMLNVLN|51C@F^y8 zCRvMB^{GO@j=cHfmy}_pCGbP%xb{pNN>? z?7tBz$1^zVaP|uaatYaIN+#xEN4jBzwZ|YI_)p(4CUAz1ZEbDk>J~Y|63SZaak~#0 zoYKruYsWHoOlC1(MhTnsdUOwQfz5p6-D0}4;DO$B;7#M{3lSE^jnTT;ns`>!G%i*F?@pR1JO{QTuD0U+~SlZxcc8~>IB{)@8p`P&+nDxNj`*gh|u?yrv$phpQcW)Us)bi`kT%qLj(fi{dWRZ%Es2!=3mI~UxiW0$-v3vUl?#g{p6eF zMEUAqo5-L0Ar(s{VlR9g=j7+lt!gP!UN2ICMokAZ5(Agd>})#gkA2w|5+<%-CuEP# zqgcM}u@3(QIC^Gx<2dbLj?cFSws_f3e%f4jeR?4M^M3cx1f+Qr6ydQ>n)kz1s##2w zk}UyQc+Z5G-d-1}{WzjkLXgS-2P7auWSJ%pSnD|Uivj5u!xk0 z_^-N9r9o;(rFDt~q1PvE#iJZ_f>J3gcP$)SOqhE~pD2|$=GvpL^d!r z6u=sp-CrMoF7;)}Zd7XO4XihC4ji?>V&(t^?@3Q&t9Mx=qex6C9d%{FE6dvU6%d94 zIE;hJ1J)cCqjv?F``7I*6bc#X)JW2b4f$L^>j{*$R`%5VHFi*+Q$2;nyieduE}qdS{L8y8F08yLs?w}{>8>$3236T-VMh@B zq-nujsb_1aUv_7g#)*rf9h%sFj*^mIcImRV*k~Vmw;%;YH(&ylYpy!&UjUVqqtfG` zox3esju?`unJJA_zKXRJP)rA3nXc$m^{S&-p|v|-0x9LHJm;XIww7C#R$?00l&Yyj z=e}gKUOpsImwW?N)+E(awoF@HyP^EhL+GlNB#k?R<2>95hz!h9sF@U20DHSB3~WMa zk90+858r@-+vWwkawJ)8ougd(i#1m3GLN{iSTylYz$brAsP%=&m$mQQrH$g%3-^VR zE%B`Vi&m8f3T~&myTEK28BDWCVzfWir1I?03;pX))|kY5ClO^+bae z*7E?g=3g7EiisYOrE+lA)2?Ln6q2*HLNpZEWMB|O-JI_oaHZB%CvYB(%=tU= zE*OY%QY58fW#RG5=gm0NR#iMB=EuNF@)%oZJ}nmm=tsJ?eGjia{e{yuU0l3{d^D@)kVDt=1PE)&tf_hHC%0MB znL|CRCPC}SeuVTdf>-QV70`0(EHizc21s^sU>y%hW0t!0&y<7}Wi-wGy>m%(-jsDj zP?mF|>p_K>liZ6ZP(w5(|9Ga%>tLgb$|doDDfkdW>Z z`)>V2XC?NJT26mL^@ zf+IKr27TfM!UbZ@?zRddC7#6ss1sw%CXJ4FWC+t3lHZupzM77m^=9 z&(a?-LxIq}*nvv)y?27lZ{j zifdl9hyJudyP2LpU$-kXctshbJDKS{WfulP5Dk~xU4Le4c#h^(YjJit4#R8_khheS z|8(>2ibaHES4+J|DBM7I#QF5u-*EdN{n=Kt@4Zt?@Tv{JZA{`4 zU#kYOv{#A&gGPwT+$Ud}AXlK3K7hYzo$(fBSFjrP{QQ zeaKg--L&jh$9N}`pu{Bs>?eDFPaWY4|9|foN%}i;3%;@4{dc+iw>m}{3rELqH21G! z`8@;w-zsJ1H(N3%|1B@#ioLOjib)j`EiJqPQVSbPSPVHCj6t5J&(NcWzBrzCiDt{4 zdlPAUKldz%6x5II1H_+jv)(xVL+a;P+-1hv_pM>gMRr%04@k;DTokASSKKhU1Qms| zrWh3a!b(J3n0>-tipg{a?UaKsP7?+|@A+1WPDiQIW1Sf@qDU~M_P65_s}7(gjTn0X zucyEm)o;f8UyshMy&>^SC3I|C6jR*R_GFwGranWZe*I>K+0k}pBuET&M~ z;Odo*ZcT?ZpduHyrf8E%IBFtv;JQ!N_m>!sV6ly$_1D{(&nO~w)G~Y`7sD3#hQk%^ zp}ucDF_$!6DAz*PM8yE(&~;%|=+h(Rn-=1Wykas_-@d&z#=S}rDf`4w(rVlcF&lF! z=1)M3YVz7orwk^BXhslJ8jR);sh^knJW(Qmm(QdSgIAIdlN4Te5KJisifjr?eB{FjAX1a0AB>d?qY4Wx>BZ8&}5K0fA+d{l8 z?^s&l8#j7pR&ijD?0b%;lL9l$P_mi2^*_OL+b}4kuLR$GAf85sOo02?Y#90}CCDiS zZ%rbCw>=H~CBO=C_JVV=xgDe%b4FaEFtuS7Q1##y686r%F6I)s-~2(}PWK|Z8M+Gu zl$y~5@#0Ka%$M<&Cv%L`a8X^@tY&T7<0|(6dNT=EsRe0%kp1Qyq!^43VAKYnr*A5~ zsI%lK1ewqO;0TpLrT9v}!@vJK{QoVa_+N4FYT#h?Y8rS1S&-G+m$FNMP?(8N`MZP zels(*?kK{{^g9DOzkuZXJ2;SrOQsp9T$hwRB1(phw1c7`!Q!by?Q#YsSM#I12RhU{$Q+{xj83axHcftEc$mNJ8_T7A-BQc*k(sZ+~NsO~xAA zxnbb%dam_fZlHvW7fKXrB~F&jS<4FD2FqY?VG?ix*r~MDXCE^WQ|W|WM;gsIA4lQP zJ2hAK@CF*3*VqPr2eeg6GzWFlICi8S>nO>5HvWzyZTE)hlkdC_>pBej*>o0EOHR|) z$?};&I4+_?wvL*g#PJ9)!bc#9BJu1(*RdNEn>#Oxta(VWeM40ola<0aOe2kSS~{^P zDJBd}0L-P#O-CzX*%+$#v;(x%<*SPgAje=F{Zh-@ucd2DA(yC|N_|ocs*|-!H%wEw z@Q!>siv2W;C^^j^59OAX03&}&D*W4EjCvfi(ygcL#~t8XGa#|NPO+*M@Y-)ctFA@I z-p7npT1#5zOLo>7q?aZpCZ=iecn3QYklP;gF0bq@>oyBq94f6C=;Csw3PkZ|5q=(c zfs`aw?II0e(h=|7o&T+hq&m$; zBrE09Twxd9BJ2P+QPN}*OdZ-JZV7%av@OM7v!!NL8R;%WFq*?{9T3{ct@2EKgc8h) zMxoM$SaF#p<`65BwIDfmXG6+OiK0e)`I=!A3E`+K@61f}0e z!2a*FOaDrOe>U`q%K!QN`&=&0C~)CaL3R4VY(NDt{Xz(Xpqru5=r#uQN1L$Je1*dkdqQ*=lofQaN%lO!<5z9ZlHgxt|`THd>2 zsWfU$9=p;yLyJyM^t zS2w9w?Bpto`@H^xJpZDKR1@~^30Il6oFGfk5%g6w*C+VM)+%R@gfIwNprOV5{F^M2 zO?n3DEzpT+EoSV-%OdvZvNF+pDd-ZVZ&d8 zKeIyrrfPN=EcFRCPEDCVflX#3-)Ik_HCkL(ejmY8vzcf-MTA{oHk!R2*36`O68$7J zf}zJC+bbQk--9Xm!u#lgLvx8TXx2J258E5^*IZ(FXMpq$2LUUvhWQPs((z1+2{Op% z?J}9k5^N=z;7ja~zi8a_-exIqWUBJwohe#4QJ`|FF*$C{lM18z^#hX6!5B8KAkLUX ziP=oti-gpV(BsLD{0(3*dw}4JxK23Y7M{BeFPucw!sHpY&l%Ws4pSm`+~V7;bZ%Dx zeI)MK=4vC&5#;2MT7fS?^ch9?2;%<8Jlu-IB&N~gg8t;6S-#C@!NU{`p7M8@2iGc& zg|JPg%@gCoCQ&s6JvDU&`X2S<57f(k8nJ1wvBu{8r?;q3_kpZZ${?|( z+^)UvR33sjSd)aT!UPkA;ylO6{aE3MQa{g%Mcf$1KONcjO@&g5zPHWtzM1rYC{_K> zgQNcs<{&X{OA=cEWw5JGqpr0O>x*Tfak2PE9?FuWtz^DDNI}rwAaT0(bdo-<+SJ6A z&}S%boGMWIS0L}=S>|-#kRX;e^sUsotry(MjE|3_9duvfc|nwF#NHuM-w7ZU!5ei8 z6Mkf>2)WunY2eU@C-Uj-A zG(z0Tz2YoBk>zCz_9-)4a>T46$(~kF+Y{#sA9MWH%5z#zNoz)sdXq7ZR_+`RZ%0(q zC7&GyS_|BGHNFl8Xa%@>iWh%Gr?=J5<(!OEjauj5jyrA-QXBjn0OAhJJ9+v=!LK`` z@g(`^*84Q4jcDL`OA&ZV60djgwG`|bcD*i50O}Q{9_noRg|~?dj%VtKOnyRs$Uzqg z191aWoR^rDX#@iSq0n z?9Sg$WSRPqSeI<}&n1T3!6%Wj@5iw5`*`Btni~G=&;J+4`7g#OQTa>u`{4ZZ(c@s$ zK0y;ySOGD-UTjREKbru{QaS>HjN<2)R%Nn-TZiQ(Twe4p@-saNa3~p{?^V9Nixz@a zykPv~<@lu6-Ng9i$Lrk(xi2Tri3q=RW`BJYOPC;S0Yly%77c727Yj-d1vF!Fuk{Xh z)lMbA69y7*5ufET>P*gXQrxsW+ zz)*MbHZv*eJPEXYE<6g6_M7N%#%mR{#awV3i^PafNv(zyI)&bH?F}2s8_rR(6%!V4SOWlup`TKAb@ee>!9JKPM=&8g#BeYRH9FpFybxBXQI2|g}FGJfJ+ zY-*2hB?o{TVL;Wt_ek;AP5PBqfDR4@Z->_182W z{P@Mc27j6jE*9xG{R$>6_;i=y{qf(c`5w9fa*`rEzX6t!KJ(p1H|>J1pC-2zqWENF zmm=Z5B4u{cY2XYl(PfrInB*~WGWik3@1oRhiMOS|D;acnf-Bs(QCm#wR;@Vf!hOPJ zgjhDCfDj$HcyVLJ=AaTbQ{@vIv14LWWF$=i-BDoC11}V;2V8A`S>_x)vIq44-VB-v z*w-d}$G+Ql?En8j!~ZkCpQ$|cA0|+rrY>tiCeWxkRGPoarxlGU2?7%k#F693RHT24 z-?JsiXlT2PTqZqNb&sSc>$d;O4V@|b6VKSWQb~bUaWn1Cf0+K%`Q&Wc<>mQ>*iEGB zbZ;aYOotBZ{vH3y<0A*L0QVM|#rf*LIsGx(O*-7)r@yyBIzJnBFSKBUSl1e|8lxU* zzFL+YDVVkIuzFWeJ8AbgN&w(4-7zbiaMn{5!JQXu)SELk*CNL+Fro|2v|YO)1l15t zs(0^&EB6DPMyaqvY>=KL>)tEpsn;N5Q#yJj<9}ImL((SqErWN3Q=;tBO~ExTCs9hB z2E$7eN#5wX4<3m^5pdjm#5o>s#eS_Q^P)tm$@SawTqF*1dj_i#)3};JslbLKHXl_N z)Fxzf>FN)EK&Rz&*|6&%Hs-^f{V|+_vL1S;-1K-l$5xiC@}%uDuwHYhmsV?YcOUlk zOYkG5v2+`+UWqpn0aaaqrD3lYdh0*!L`3FAsNKu=Q!vJu?Yc8n|CoYyDo_`r0mPoo z8>XCo$W4>l(==h?2~PoRR*kEe)&IH{1sM41mO#-36`02m#nTX{r*r`Q5rZ2-sE|nA zhnn5T#s#v`52T5|?GNS`%HgS2;R(*|^egNPDzzH_z^W)-Q98~$#YAe)cEZ%vge965AS_am#DK#pjPRr-!^za8>`kksCAUj(Xr*1NW5~e zpypt_eJpD&4_bl_y?G%>^L}=>xAaV>KR6;^aBytqpiHe%!j;&MzI_>Sx7O%F%D*8s zSN}cS^<{iiK)=Ji`FpO#^zY!_|D)qeRNAtgmH)m;qC|mq^j(|hL`7uBz+ULUj37gj zksdbnU+LSVo35riSX_4z{UX=%n&}7s0{WuZYoSfwAP`8aKN9P@%e=~1`~1ASL-z%# zw>DO&ixr}c9%4InGc*_y42bdEk)ZdG7-mTu0bD@_vGAr*NcFoMW;@r?@LUhRI zCUJgHb`O?M3!w)|CPu~ej%fddw20lod?Ufp8Dmt0PbnA0J%KE^2~AIcnKP()025V> zG>noSM3$5Btmc$GZoyP^v1@Poz0FD(6YSTH@aD0}BXva?LphAiSz9f&Y(aDAzBnUh z?d2m``~{z;{}kZJ>a^wYI?ry(V9hIoh;|EFc0*-#*`$T0DRQ1;WsqInG;YPS+I4{g zJGpKk%%Sdc5xBa$Q^_I~(F97eqDO7AN3EN0u)PNBAb+n+ zWBTxQx^;O9o0`=g+Zrt_{lP!sgWZHW?8bLYS$;1a@&7w9rD9|Ge;Gb?sEjFoF9-6v z#!2)t{DMHZ2@0W*fCx;62d#;jouz`R5Y(t{BT=$N4yr^^o$ON8d{PQ=!O zX17^CrdM~7D-;ZrC!||<+FEOxI_WI3CA<35va%4v>gc zEX-@h8esj=a4szW7x{0g$hwoWRQG$yK{@3mqd-jYiVofJE!Wok1* znV7Gm&Ssq#hFuvj1sRyHg(6PFA5U*Q8Rx>-blOs=lb`qa{zFy&n4xY;sd$fE+<3EI z##W$P9M{B3c3Si9gw^jlPU-JqD~Cye;wr=XkV7BSv#6}DrsXWFJ3eUNrc%7{=^sP> zrp)BWKA9<}^R9g!0q7yWlh;gr_TEOD|#BmGq<@IV;ueg+D2}cjpp+dPf&Q(36sFU&K8}hA85U61faW&{ zlB`9HUl-WWCG|<1XANN3JVAkRYvr5U4q6;!G*MTdSUt*Mi=z_y3B1A9j-@aK{lNvx zK%p23>M&=KTCgR!Ee8c?DAO2_R?B zkaqr6^BSP!8dHXxj%N1l+V$_%vzHjqvu7p@%Nl6;>y*S}M!B=pz=aqUV#`;h%M0rU zHfcog>kv3UZAEB*g7Er@t6CF8kHDmKTjO@rejA^ULqn!`LwrEwOVmHx^;g|5PHm#B zZ+jjWgjJ!043F+&#_;D*mz%Q60=L9Ove|$gU&~As5^uz@2-BfQ!bW)Khn}G+Wyjw- z19qI#oB(RSNydn0t~;tAmK!P-d{b-@@E5|cdgOS#!>%#Rj6ynkMvaW@37E>@hJP^8 z2zk8VXx|>#R^JCcWdBCy{0nPmYFOxN55#^-rlqobe0#L6)bi?E?SPymF*a5oDDeSd zO0gx?#KMoOd&G(2O@*W)HgX6y_aa6iMCl^~`{@UR`nMQE`>n_{_aY5nA}vqU8mt8H z`oa=g0SyiLd~BxAj2~l$zRSDHxvDs;I4>+M$W`HbJ|g&P+$!U7-PHX4RAcR0szJ*( ze-417=bO2q{492SWrqDK+L3#ChUHtz*@MP)e^%@>_&#Yk^1|tv@j4%3T)diEX zATx4K*hcO`sY$jk#jN5WD<=C3nvuVsRh||qDHnc~;Kf59zr0;c7VkVSUPD%NnnJC_ zl3F^#f_rDu8l}l8qcAz0FFa)EAt32IUy_JLIhU_J^l~FRH&6-ivSpG2PRqzDdMWft>Zc(c)#tb%wgmWN%>IOPm zZi-noqS!^Ftb81pRcQi`X#UhWK70hy4tGW1mz|+vI8c*h@ zfFGJtW3r>qV>1Z0r|L>7I3un^gcep$AAWfZHRvB|E*kktY$qQP_$YG60C@X~tTQjB3%@`uz!qxtxF+LE!+=nrS^07hn` zEgAp!h|r03h7B!$#OZW#ACD+M;-5J!W+{h|6I;5cNnE(Y863%1(oH}_FTW})8zYb$7czP zg~Szk1+_NTm6SJ0MS_|oSz%e(S~P-&SFp;!k?uFayytV$8HPwuyELSXOs^27XvK-D zOx-Dl!P|28DK6iX>p#Yb%3`A&CG0X2S43FjN%IB}q(!hC$fG}yl1y9W&W&I@KTg6@ zK^kpH8=yFuP+vI^+59|3%Zqnb5lTDAykf z9S#X`3N(X^SpdMyWQGOQRjhiwlj!0W-yD<3aEj^&X%=?`6lCy~?`&WSWt z?U~EKFcCG_RJ(Qp7j=$I%H8t)Z@6VjA#>1f@EYiS8MRHZphp zMA_5`znM=pzUpBPO)pXGYpQ6gkine{6u_o!P@Q+NKJ}k!_X7u|qfpAyIJb$_#3@wJ z<1SE2Edkfk9C!0t%}8Yio09^F`YGzpaJHGk*-ffsn85@)%4@`;Fv^8q(-Wk7r=Q8p zT&hD`5(f?M{gfzGbbwh8(}G#|#fDuk7v1W)5H9wkorE0ZZjL0Q1=NRGY>zwgfm81DdoaVwNH;or{{eSyybt)m<=zXoA^RALYG-2t zouH|L*BLvmm9cdMmn+KGopyR@4*=&0&4g|FLoreZOhRmh=)R0bg~ zT2(8V_q7~42-zvb)+y959OAv!V$u(O3)%Es0M@CRFmG{5sovIq4%8Ahjk#*5w{+)+ zMWQoJI_r$HxL5km1#6(e@{lK3Udc~n0@g`g$s?VrnQJ$!oPnb?IHh-1qA`Rz$)Ai< z6w$-MJW-gKNvOhL+XMbE7&mFt`x1KY>k4(!KbbpZ`>`K@1J<(#vVbjx@Z@(6Q}MF# zMnbr-f55(cTa^q4+#)=s+ThMaV~E`B8V=|W_fZWDwiso8tNMTNse)RNBGi=gVwgg% zbOg8>mbRN%7^Um-7oj4=6`$|(K7!+t^90a{$18Z>}<#!bm%ZEFQ{X(yBZMc>lCz0f1I2w9Sq zuGh<9<=AO&g6BZte6hn>Qmvv;Rt)*cJfTr2=~EnGD8P$v3R|&1RCl&7)b+`=QGapi zPbLg_pxm`+HZurtFZ;wZ=`Vk*do~$wB zxoW&=j0OTbQ=Q%S8XJ%~qoa3Ea|au5o}_(P;=!y-AjFrERh%8la!z6Fn@lR?^E~H12D?8#ht=1F;7@o4$Q8GDj;sSC%Jfn01xgL&%F2 zwG1|5ikb^qHv&9hT8w83+yv&BQXOQyMVJSBL(Ky~p)gU3#%|blG?IR9rP^zUbs7rOA0X52Ao=GRt@C&zlyjNLv-} z9?*x{y(`509qhCV*B47f2hLrGl^<@SuRGR!KwHei?!CM10Tq*YDIoBNyRuO*>3FU? zHjipIE#B~y3FSfOsMfj~F9PNr*H?0oHyYB^G(YyNh{SxcE(Y-`x5jFMKb~HO*m+R% zrq|ic4fzJ#USpTm;X7K+E%xsT_3VHKe?*uc4-FsILUH;kL>_okY(w`VU*8+l>o>Jm ziU#?2^`>arnsl#)*R&nf_%>A+qwl%o{l(u)M?DK1^mf260_oteV3#E_>6Y4!_hhVD zM8AI6MM2V*^_M^sQ0dmHu11fy^kOqXqzpr?K$`}BKWG`=Es(9&S@K@)ZjA{lj3ea7_MBP zk(|hBFRjHVMN!sNUkrB;(cTP)T97M$0Dtc&UXSec<+q?y>5=)}S~{Z@ua;1xt@=T5 zI7{`Z=z_X*no8s>mY;>BvEXK%b`a6(DTS6t&b!vf_z#HM{Uoy_5fiB(zpkF{})ruka$iX*~pq1ZxD?q68dIo zIZSVls9kFGsTwvr4{T_LidcWtt$u{kJlW7moRaH6+A5hW&;;2O#$oKyEN8kx`LmG)Wfq4ykh+q{I3|RfVpkR&QH_x;t41Uw z`P+tft^E2B$domKT@|nNW`EHwyj>&}K;eDpe z1bNOh=fvIfk`&B61+S8ND<(KC%>y&?>opCnY*r5M+!UrWKxv0_QvTlJc>X#AaI^xo zaRXL}t5Ej_Z$y*|w*$6D+A?Lw-CO-$itm^{2Ct82-<0IW)0KMNvJHgBrdsIR0v~=H z?n6^}l{D``Me90`^o|q!olsF?UX3YSq^6Vu>Ijm>>PaZI8G@<^NGw{Cx&%|PwYrfw zR!gX_%AR=L3BFsf8LxI|K^J}deh0ZdV?$3r--FEX`#INxsOG6_=!v)DI>0q|BxT)z z-G6kzA01M?rba+G_mwNMQD1mbVbNTWmBi*{s_v_Ft9m2Avg!^78(QFu&n6mbRJ2bA zv!b;%yo{g*9l2)>tsZJOOp}U~8VUH`}$ z8p_}t*XIOehezolNa-a2x0BS})Y9}&*TPgua{Ewn-=wVrmJUeU39EKx+%w%=ixQWK zDLpwaNJs65#6o7Ln7~~X+p_o2BR1g~VCfxLzxA{HlWAI6^H;`juI=&r1jQrUv_q0Z z1Ja-tjdktrrP>GOC*#p?*xfQU5MqjMsBe!9lh(u8)w$e@Z|>aUHI5o;MGw*|Myiz3 z-f0;pHg~Q#%*Kx8MxH%AluVXjG2C$)WL-K63@Q`#y9_k_+}eR(x4~dp7oV-ek0H>I zgy8p#i4GN{>#v=pFYUQT(g&b$OeTy-X_#FDgNF8XyfGY6R!>inYn8IR2RDa&O!(6< znXs{W!bkP|s_YI*Yx%4stI`=ZO45IK6rBs`g7sP40ic}GZ58s?Mc$&i`kq_tfci>N zIHrC0H+Qpam1bNa=(`SRKjixBTtm&e`j9porEci!zdlg1RI0Jw#b(_Tb@RQK1Zxr_ z%7SUeH6=TrXt3J@js`4iDD0=IoHhK~I7^W8^Rcp~Yaf>2wVe|Hh1bUpX9ATD#moByY57-f2Ef1TP^lBi&p5_s7WGG9|0T}dlfxOx zXvScJO1Cnq`c`~{Dp;{;l<-KkCDE+pmexJkd}zCgE{eF=)K``-qC~IT6GcRog_)!X z?fK^F8UDz$(zFUrwuR$qro5>qqn>+Z%<5>;_*3pZ8QM|yv9CAtrAx;($>4l^_$_-L z*&?(77!-=zvnCVW&kUcZMb6;2!83si518Y%R*A3JZ8Is|kUCMu`!vxDgaWjs7^0j( ziTaS4HhQ)ldR=r)_7vYFUr%THE}cPF{0H45FJ5MQW^+W>P+eEX2kLp3zzFe*-pFVA zdDZRybv?H|>`9f$AKVjFWJ=wegO7hOOIYCtd?Vj{EYLT*^gl35|HQ`R=ti+ADm{jyQE7K@kdjuqJhWVSks>b^ zxha88-h3s;%3_5b1TqFCPTxVjvuB5U>v=HyZ$?JSk+&I%)M7KE*wOg<)1-Iy)8-K! z^XpIt|0ibmk9RtMmlUd7#Ap3Q!q9N4atQy)TmrhrFhfx1DAN`^vq@Q_SRl|V z#lU<~n67$mT)NvHh`%als+G-)x1`Y%4Bp*6Un5Ri9h=_Db zA-AdP!f>f0m@~>7X#uBM?diI@)Egjuz@jXKvm zJo+==juc9_<;CqeRaU9_Mz@;3e=E4=6TK+c`|uu#pIqhSyNm`G(X)&)B`8q0RBv#> z`gGlw(Q=1Xmf55VHj%C#^1lpc>LY8kfA@|rlC1EA<1#`iuyNO z(=;irt{_&K=i4)^x%;U(Xv<)+o=dczC5H3W~+e|f~{*ucxj@{Yi-cw^MqYr3fN zF5D+~!wd$#al?UfMnz(@K#wn`_5na@rRr8XqN@&M&FGEC@`+OEv}sI1hw>Up0qAWf zL#e4~&oM;TVfjRE+10B_gFlLEP9?Q-dARr3xi6nQqnw>k-S;~b z;!0s2VS4}W8b&pGuK=7im+t(`nz@FnT#VD|!)eQNp-W6)@>aA+j~K*H{$G`y2|QHY z|Hmy+CR@#jWY4~)lr1qBJB_RfHJFfP<}pK5(#ZZGSqcpyS&}01LnTWk5fzmXMGHkJ zTP6L^B+uj;lmB_W<~4=${+v0>z31M!-_O@o-O9GyW)j_mjx}!0@br_LE-7SIuPP84 z;5=O(U*g_um0tyG|61N@d9lEuOeiRd+#NY^{nd5;-CVlw&Ap7J?qwM^?E29wvS}2d zbzar4Fz&RSR(-|s!Z6+za&Z zY#D<5q_JUktIzvL0)yq_kLWG6DO{ri=?c!y!f(Dk%G{8)k`Gym%j#!OgXVDD3;$&v@qy#ISJfp=Vm>pls@9-mapVQChAHHd-x+OGx)(*Yr zC1qDUTZ6mM(b_hi!TuFF2k#8uI2;kD70AQ&di$L*4P*Y-@p`jdm%_c3f)XhYD^6M8&#Y$ZpzQMcR|6nsH>b=*R_Von!$BTRj7yGCXokoAQ z&ANvx0-Epw`QIEPgI(^cS2f(Y85yV@ygI{ewyv5Frng)e}KCZF7JbR(&W618_dcEh(#+^zZFY;o<815<5sOHQdeax9_!PyM&;{P zkBa5xymca0#)c#tke@3KNEM8a_mT&1gm;p&&JlMGH(cL(b)BckgMQ^9&vRwj!~3@l zY?L5}=Jzr080OGKb|y`ee(+`flQg|!lo6>=H)X4`$Gz~hLmu2a%kYW_Uu8x09Pa0J zKZ`E$BKJ=2GPj_3l*TEcZ*uYRr<*J^#5pILTT;k_cgto1ZL-%slyc16J~OH-(RgDA z%;EjEnoUkZ&acS{Q8`{i6T5^nywgqQI5bDIymoa7CSZG|WWVk>GM9)zy*bNih|QIm z%0+(Nnc*a_xo;$=!HQYaapLms>J1ToyjtFByY`C2H1wT#178#4+|{H0BBqtCdd$L% z_3Hc60j@{t9~MjM@LBalR&6@>B;9?r<7J~F+WXyYu*y3?px*=8MAK@EA+jRX8{CG?GI-< z54?Dc9CAh>QTAvyOEm0^+x;r2BWX|{3$Y7)L5l*qVE*y0`7J>l2wCmW zL1?|a`pJ-l{fb_N;R(Z9UMiSj6pQjOvQ^%DvhIJF!+Th7jO2~1f1N+(-TyCFYQZYw z4)>7caf^Ki_KJ^Zx2JUb z&$3zJy!*+rCV4%jqwyuNY3j1ZEiltS0xTzd+=itTb;IPYpaf?8Y+RSdVdpacB(bVQ zC(JupLfFp8y43%PMj2}T|VS@%LVp>hv4Y!RPMF?pp8U_$xCJ)S zQx!69>bphNTIb9yn*_yfj{N%bY)t{L1cs8<8|!f$;UQ*}IN=2<6lA;x^(`8t?;+ST zh)z4qeYYgZkIy{$4x28O-pugO&gauRh3;lti9)9Pvw+^)0!h~%m&8Q!AKX%urEMnl z?yEz?g#ODn$UM`+Q#$Q!6|zsq_`dLO5YK-6bJM6ya>}H+vnW^h?o$z;V&wvuM$dR& zeEq;uUUh$XR`TWeC$$c&Jjau2it3#%J-y}Qm>nW*s?En?R&6w@sDXMEr#8~$=b(gk zwDC3)NtAP;M2BW_lL^5ShpK$D%@|BnD{=!Tq)o(5@z3i7Z){} zGr}Exom_qDO{kAVkZ*MbLNHE666Kina#D{&>Jy%~w7yX$oj;cYCd^p9zy z8*+wgSEcj$4{WxKmCF(5o7U4jqwEvO&dm1H#7z}%VXAbW&W24v-tS6N3}qrm1OnE)fUkoE8yMMn9S$?IswS88tQWm4#Oid#ckgr6 zRtHm!mfNl-`d>O*1~d7%;~n+{Rph6BBy^95zqI{K((E!iFQ+h*C3EsbxNo_aRm5gj zKYug($r*Q#W9`p%Bf{bi6;IY0v`pB^^qu)gbg9QHQ7 zWBj(a1YSu)~2RK8Pi#C>{DMlrqFb9e_RehEHyI{n?e3vL_}L>kYJC z_ly$$)zFi*SFyNrnOt(B*7E$??s67EO%DgoZL2XNk8iVx~X_)o++4oaK1M|ou73vA0K^503j@uuVmLcHH4ya-kOIDfM%5%(E z+Xpt~#7y2!KB&)PoyCA+$~DXqxPxxALy!g-O?<9+9KTk4Pgq4AIdUkl`1<1#j^cJg zgU3`0hkHj_jxV>`Y~%LAZl^3o0}`Sm@iw7kwff{M%VwtN)|~!p{AsfA6vB5UolF~d zHWS%*uBDt<9y!9v2Xe|au&1j&iR1HXCdyCjxSgG*L{wmTD4(NQ=mFjpa~xooc6kju z`~+d{j7$h-;HAB04H!Zscu^hZffL#9!p$)9>sRI|Yovm)g@F>ZnosF2EgkU3ln0bR zTA}|+E(tt)!SG)-bEJi_0m{l+(cAz^pi}`9=~n?y&;2eG;d9{M6nj>BHGn(KA2n|O zt}$=FPq!j`p&kQ8>cirSzkU0c08%8{^Qyqi-w2LoO8)^E7;;I1;HQ6B$u0nNaX2CY zSmfi)F`m94zL8>#zu;8|{aBui@RzRKBlP1&mfFxEC@%cjl?NBs`cr^nm){>;$g?rhKr$AO&6qV_Wbn^}5tfFBry^e1`%du2~o zs$~dN;S_#%iwwA_QvmMjh%Qo?0?rR~6liyN5Xmej8(*V9ym*T`xAhHih-v$7U}8=dfXi2i*aAB!xM(Xekg*ix@r|ymDw*{*s0?dlVys2e)z62u1 z+k3esbJE=-P5S$&KdFp+2H7_2e=}OKDrf( z9-207?6$@f4m4B+9E*e((Y89!q?zH|mz_vM>kp*HGXldO0Hg#!EtFhRuOm$u8e~a9 z5(roy7m$Kh+zjW6@zw{&20u?1f2uP&boD}$#Zy)4o&T;vyBoqFiF2t;*g=|1=)PxB z8eM3Mp=l_obbc?I^xyLz?4Y1YDWPa+nm;O<$Cn;@ane616`J9OO2r=rZr{I_Kizyc zP#^^WCdIEp*()rRT+*YZK>V@^Zs=ht32x>Kwe zab)@ZEffz;VM4{XA6e421^h~`ji5r%)B{wZu#hD}f3$y@L0JV9f3g{-RK!A?vBUA}${YF(vO4)@`6f1 z-A|}e#LN{)(eXloDnX4Vs7eH|<@{r#LodP@Nz--$Dg_Par%DCpu2>2jUnqy~|J?eZ zBG4FVsz_A+ibdwv>mLp>P!(t}E>$JGaK$R~;fb{O3($y1ssQQo|5M;^JqC?7qe|hg zu0ZOqeFcp?qVn&Qu7FQJ4hcFi&|nR!*j)MF#b}QO^lN%5)4p*D^H+B){n8%VPUzi! zDihoGcP71a6!ab`l^hK&*dYrVYzJ0)#}xVrp!e;lI!+x+bfCN0KXwUAPU9@#l7@0& QuEJmfE|#`Dqx|px0L@K;Y5)KL literal 0 HcmV?d00001 diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 00000000..a71c7a7d --- /dev/null +++ b/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,5 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-7.3.3-bin.zip +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/gradlew b/gradlew new file mode 100755 index 00000000..c53aefaa --- /dev/null +++ b/gradlew @@ -0,0 +1,234 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# https://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/master/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +APP_HOME=$( cd "${APP_HOME:-./}" && pwd -P ) || exit + +APP_NAME="Gradle" +APP_BASE_NAME=${0##*/} + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +else + JAVACMD=java + which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + done +fi + +# Collect all arguments for the java command; +# * $DEFAULT_JVM_OPTS, $JAVA_OPTS, and $GRADLE_OPTS can contain fragments of +# shell script including quotes and variable substitutions, so put them in +# double quotes to make sure that they get re-expanded; and +# * put everything else in single quotes, so that it's not re-expanded. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/gradlew.bat b/gradlew.bat new file mode 100644 index 00000000..ac1b06f9 --- /dev/null +++ b/gradlew.bat @@ -0,0 +1,89 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem + +@if "%DEBUG%" == "" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%" == "" set DIRNAME=. +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if "%ERRORLEVEL%" == "0" goto execute + +echo. +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if "%ERRORLEVEL%"=="0" goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1 +exit /b 1 + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/settings.gradle b/settings.gradle new file mode 100644 index 00000000..aa06df79 --- /dev/null +++ b/settings.gradle @@ -0,0 +1,27 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2022' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name 'frcHome' + url frcHomeMaven + } + } +} diff --git a/simConfig.txt b/simConfig.txt new file mode 100644 index 00000000..d5986bb4 --- /dev/null +++ b/simConfig.txt @@ -0,0 +1,102 @@ +{ + "logFilePath": "sim_robot_logs", + "drive": { + "leftMotor": { + "deviceId": 6, + "sensorScale": 0.0524 + }, + "rightMotor": { + "deviceId": 4, + "sensorScale": 0.0524 + }, + "leftEncoder": { + "ports": [0, 1], + "distancePerPulse": 0.0524 + }, + "rightEncoder": { + "ports": [2, 3], + "distancePerPulse": 0.0524 + }, + "gyro": { + "port": 12 + }, + "frontLeftDriveMotor": { + "deviceId": 84, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "backLeftDriveMotor": { + "deviceId": 85, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "frontRightDriveMotor": { + "deviceId": 86, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "backRightDriveMotor": { + "deviceId": 87, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "frontLeftSteerMotor": { + "deviceId": 88, + "inverted": true, + "sensorScaledUnits": "degree" + }, + "backLeftSteerMotor": { + "deviceId": 89, + "inverted": true, + "sensorScaledUnits": "degree" + }, + "frontRightSteerMotor": { + "deviceId": 90, + "inverted": true, + "sensorScaledUnits": "degree" + }, + "backRightSteerMotor": { + "deviceId": 91, + "inverted": true, + "sensorScaledUnits": "degree" + } + }, + "intakeWheels": { + "deviceId": 10 + }, + "intakeArm": { + "port": 0 + }, + "launch": { + "port": 1 + }, + "climber": { + "elevator": { + "deviceId": 10 + }, + "arms": {"port": 0} + }, + "lineSensorLeft": { + "port": 4 + }, + "lineSensorCenter": { + "port": 5 + }, + "lineSensorRight": { + "port": 6 + }, + + "intake": { + "extend": {"port": 0}, + "frontWheels": {"deviceId": 10}, + "topWheels": {"deviceId": 12} + }, + "shooter": { + "motor": {"deviceId": 14} + }, + "storage": { + "proximitySensor": {"port": 2}, + "left": {"deviceId": 6}, + "right": {"deviceId": 4} + } +} \ No newline at end of file diff --git a/src/main/deploy/example.txt b/src/main/deploy/example.txt new file mode 100644 index 00000000..70c79b6b --- /dev/null +++ b/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'FileUtilities.getFilePath' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/src/main/java/com/team766/config/AbstractConfigMultiValue.java b/src/main/java/com/team766/config/AbstractConfigMultiValue.java new file mode 100644 index 00000000..c3a769c1 --- /dev/null +++ b/src/main/java/com/team766/config/AbstractConfigMultiValue.java @@ -0,0 +1,35 @@ +package com.team766.config; + +import java.lang.reflect.Array; +import java.util.function.IntFunction; +import org.json.JSONArray; + +abstract class AbstractConfigMultiValue extends AbstractConfigValue { + private final IntFunction m_arrayFactory; + + @SuppressWarnings("unchecked") + protected AbstractConfigMultiValue(String key, Class elementClass) { + super(key); + m_arrayFactory = (int length) -> (E[])Array.newInstance(elementClass, length); + } + + @Override + protected final E[] parseJsonValue(Object configValue) { + JSONArray jsonArray; + try { + jsonArray = (JSONArray)configValue; + } catch (ClassCastException ex) { + final E[] valueArray = m_arrayFactory.apply(1); + valueArray[0] = parseJsonElement(configValue); + return valueArray; + } + final int length = jsonArray.length(); + final E[] valueArray = m_arrayFactory.apply(length); + for (int i = 0; i < length; ++i) { + valueArray[i] = parseJsonElement(jsonArray.get(i)); + } + return valueArray; + } + + protected abstract E parseJsonElement(Object configElement); +} \ No newline at end of file diff --git a/src/main/java/com/team766/config/AbstractConfigValue.java b/src/main/java/com/team766/config/AbstractConfigValue.java new file mode 100644 index 00000000..78d470f7 --- /dev/null +++ b/src/main/java/com/team766/config/AbstractConfigValue.java @@ -0,0 +1,93 @@ +package com.team766.config; + +import java.util.ArrayList; +import java.util.Collection; +import java.util.Collections; +import com.team766.library.SettableValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public abstract class AbstractConfigValue implements SettableValueProvider { + protected String m_key; + private E m_cachedValue; + private boolean m_cachedHasValue; + private int m_cachedGeneration = -1; + + private static ArrayList> c_accessedValues = new ArrayList>(); + + static Collection> accessedValues() { + return Collections.unmodifiableCollection(c_accessedValues); + } + + static void resetStatics() { + c_accessedValues.clear(); + } + + protected AbstractConfigValue(String key) { + m_key = key; + c_accessedValues.add(this); + // Querying for this config setting's key will add a placeholder entry + // in the config file if this setting does not already exist there. + ConfigFileReader.instance.getRawValue(m_key); + } + + private void sync() { + if (ConfigFileReader.instance.getGeneration() != m_cachedGeneration) { + m_cachedGeneration = ConfigFileReader.instance.getGeneration(); + var rawValue = ConfigFileReader.instance.getRawValue(m_key); + m_cachedHasValue = rawValue != null; + if (m_cachedHasValue) { + try { + m_cachedValue = parseJsonValue(rawValue); + } catch (Exception ex) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Failed to parse " + m_key + " from the config file: " + LoggerExceptionUtils.exceptionToString(ex)); + m_cachedValue = null; + m_cachedHasValue = false; + } + } + } + } + + public String getKey() { + return m_key; + } + + @Override + public boolean hasValue() { + sync(); + return m_cachedHasValue; + } + + @Override + public E get() { + sync(); + if (!m_cachedHasValue) { + throw new IllegalArgumentException(m_key + " not found in the config file"); + } + return m_cachedValue; + } + + public void set(E value) { + ConfigFileReader.instance.setValue(m_key, value); + } + + public void clear() { + ConfigFileReader.instance.setValue(m_key, null); + } + + protected abstract E parseJsonValue(Object configValue); + + @Override + public String toString() { + sync(); + if (!m_cachedHasValue) { + return ""; + } + if (m_cachedValue == null) { + return ""; + } + return m_cachedValue.toString(); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/config/ConfigFileReader.java b/src/main/java/com/team766/config/ConfigFileReader.java new file mode 100755 index 00000000..60b12606 --- /dev/null +++ b/src/main/java/com/team766/config/ConfigFileReader.java @@ -0,0 +1,182 @@ +package com.team766.config; + +import java.io.FileWriter; +import java.io.IOException; +import java.io.StringReader; +import java.nio.file.Files; +import java.nio.file.Paths; +import java.util.regex.Pattern; +import org.json.JSONObject; +import org.json.JSONTokener; +import com.team766.library.SettableValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +/** + * Class for loading in config from the Config file. + * Constants that need to be tuned / changed + * + * Data is read from a file in JSON format + * + * @author Brett Levenson + */ +public class ConfigFileReader { + // this.getClass().getClassLoader().getResource(fileName).getPath() + + public static ConfigFileReader instance; + + private static final String KEY_DELIMITER = "."; + + // This is incremented each time the config file is reloaded to ensure that ConfigValues use the most recent setting. + private int m_generation = 0; + + private String m_fileName; + private JSONObject m_values = new JSONObject(); + + public static ConfigFileReader getInstance() { + return instance; + } + + public ConfigFileReader(String fileName) { + m_fileName = fileName; + + try { + reloadFromFile(); + } catch (Exception e) { + System.err.println("Failed to load config file!"); + e.printStackTrace(); + LoggerExceptionUtils.logException(new IOException("Failed to load config file!", e)); + } + } + + public void reloadFromFile() throws IOException { + System.out.println("Loading config file: " + m_fileName); + String jsonString = Files.readString(Paths.get(m_fileName)); + reloadFromJson(jsonString); + } + + public void reloadFromJson(String jsonString) { + JSONObject newValues; + try (StringReader reader = new StringReader(jsonString)) { + newValues = new JSONObject(new JSONTokener(reader)); + } + for (AbstractConfigValue param : AbstractConfigValue.accessedValues()) { + var rawValue = getRawValue(newValues, param.getKey()); + if (rawValue == null) { + continue; + } + try { + param.parseJsonValue(rawValue); + } catch (Exception ex) { + throw new ConfigValueParseException("Could not parse config value for " + param.getKey(), ex); + } + } + m_values = newValues; + ++m_generation; + } + + public int getGeneration() { + return m_generation; + } + + public boolean containsKey(String key) { + return getRawValue(key) != null; + } + + public SettableValueProvider getInts(String key) { + return new IntegerConfigMultiValue(key); + } + + public SettableValueProvider getInt(String key) { + return new IntegerConfigValue(key); + } + + public SettableValueProvider getDoubles(String key) { + return new DoubleConfigMultiValue(key); + } + + public SettableValueProvider getDouble(String key) { + return new DoubleConfigValue(key); + } + + public SettableValueProvider getBoolean(String key) { + return new BooleanConfigValue(key); + } + + public SettableValueProvider getString(String key) { + return new StringConfigValue(key); + } + + public > SettableValueProvider getEnum(Class enumClass, String key) { + return new EnumConfigValue(enumClass, key); + } + + public void setValue(String key, E value) { + String[] keyParts = splitKey(key); + JSONObject parentObj = getParent(m_values, keyParts); + parentObj.putOpt( + keyParts[keyParts.length - 1], + value == null ? JSONObject.NULL : value); + } + + Object getRawValue(String key) { + return getRawValue(m_values, key); + } + + private static Object getRawValue(JSONObject obj, String key) { + String[] keyParts = splitKey(key); + JSONObject parentObj = getParent(obj, keyParts); + var rawValue = parentObj.opt(keyParts[keyParts.length - 1]); + if (rawValue instanceof JSONObject) { + throw new IllegalArgumentException( + "The config file cannot store both a single config " + + "setting and a group of config settings with the name " + + key + " Please pick a different name"); + } + if (rawValue == null) { + parentObj.put(keyParts[keyParts.length - 1], JSONObject.NULL); + } + if (rawValue == JSONObject.NULL) { + rawValue = null; + } + return rawValue; + } + + private static String[] splitKey(String key) { + return key.split(Pattern.quote(KEY_DELIMITER)); + } + + private static JSONObject getParent(JSONObject obj, String[] keyParts) { + for (int i = 0; i < keyParts.length - 1; ++i) { + JSONObject subObj; + try { + subObj = (JSONObject)obj.opt(keyParts[i]); + } catch (ClassCastException ex) { + throw new IllegalArgumentException( + "The config file cannot store both a single config " + + "setting and a group of config settings with the name " + + String.join(KEY_DELIMITER, keyParts) + + " Please pick a different name for one of them."); + } + if (subObj == null) { + subObj = new JSONObject(); + obj.put(keyParts[i], subObj); + } + obj = subObj; + } + return obj; + } + + public String getJsonString() { + return m_values.toString(2); + } + + public void saveFile(String jsonString) throws IOException { + try(FileWriter writer = new FileWriter(m_fileName)) { + writer.write(jsonString); + } + Logger.get(Category.CONFIGURATION).logRaw(Severity.INFO, "Config file written to " + m_fileName); + } +} diff --git a/src/main/java/com/team766/config/ConfigValue.java b/src/main/java/com/team766/config/ConfigValue.java new file mode 100644 index 00000000..c6e876f8 --- /dev/null +++ b/src/main/java/com/team766/config/ConfigValue.java @@ -0,0 +1,94 @@ +package com.team766.config; + +import java.util.Arrays; +import java.util.stream.Collectors; + +class DoubleConfigValue extends AbstractConfigValue { + protected DoubleConfigValue(String key) { + super(key); + } + + @Override + public Double parseJsonValue(Object configValue) { + return ((Number)configValue).doubleValue(); + } +} + +class IntegerConfigValue extends AbstractConfigValue { + protected IntegerConfigValue(String key) { + super(key); + } + + @Override + public Integer parseJsonValue(Object configValue) { + return ((Number)configValue).intValue(); + } +} + +class DoubleConfigMultiValue extends AbstractConfigMultiValue { + protected DoubleConfigMultiValue(String key) { + super(key, Double.class); + } + + @Override + public Double parseJsonElement(Object configElement) { + return ((Number)configElement).doubleValue(); + } +} + +class IntegerConfigMultiValue extends AbstractConfigMultiValue { + protected IntegerConfigMultiValue(String key) { + super(key, Integer.class); + } + + @Override + public Integer parseJsonElement(Object configElement) { + return ((Number)configElement).intValue(); + } +} + +class BooleanConfigValue extends AbstractConfigValue { + protected BooleanConfigValue(String key) { + super(key); + } + + @Override + public Boolean parseJsonValue(Object configValue) { + return (Boolean)configValue; + } +} + +class StringConfigValue extends AbstractConfigValue { + protected StringConfigValue(String key) { + super(key); + } + + @Override + public String parseJsonValue(Object configValue) { + return (String)configValue; + } +} + +class EnumConfigValue> extends AbstractConfigValue { + Class enumClass; + + protected EnumConfigValue(Class enumClass, String key) { + super(key); + this.enumClass = enumClass; + } + + @Override + public E parseJsonValue(Object configValue) { + String enumName = (String)configValue; + for (E each : enumClass.getEnumConstants()) { + if (each.name().compareToIgnoreCase(enumName) == 0) { + return each; + } + } + throw new IllegalArgumentException( + "Unrecognized enum value: " + + enumName + + "; values are " + + Arrays.stream(enumClass.getEnumConstants()).map(e -> e.name()).collect(Collectors.joining(", "))); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/config/ConfigValueParseException.java b/src/main/java/com/team766/config/ConfigValueParseException.java new file mode 100644 index 00000000..c07709d5 --- /dev/null +++ b/src/main/java/com/team766/config/ConfigValueParseException.java @@ -0,0 +1,13 @@ +package com.team766.config; + +public class ConfigValueParseException extends RuntimeException { + private static final long serialVersionUID = -3235627203813966130L; + + public ConfigValueParseException(String message) { + super(message); + } + + public ConfigValueParseException(String message, Throwable cause) { + super(message, cause); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/controllers/MotionLockout.java b/src/main/java/com/team766/controllers/MotionLockout.java new file mode 100644 index 00000000..04646e69 --- /dev/null +++ b/src/main/java/com/team766/controllers/MotionLockout.java @@ -0,0 +1,57 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.library.SetValueProvider; +import com.team766.library.ValueProvider; + +/* + * Restricts the command to be between minCommand and maxCommand when the + * sensor position is between minPosition and maxPosition. + */ +public class MotionLockout { + private ValueProvider m_minPosition; + private ValueProvider m_maxPosition; + private ValueProvider m_minCommand; + private ValueProvider m_maxCommand; + + public static MotionLockout loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new MotionLockout( + ConfigFileReader.getInstance().getDouble(configPrefix + "minPosition"), + ConfigFileReader.getInstance().getDouble(configPrefix + "maxPosition"), + ConfigFileReader.getInstance().getDouble(configPrefix + "minCommand"), + ConfigFileReader.getInstance().getDouble(configPrefix + "maxCommand")); + } + + public MotionLockout(double minPosition, double maxPosition, double minCommand, double maxCommand) { + m_minPosition = new SetValueProvider(minPosition); + m_maxPosition = new SetValueProvider(maxPosition); + m_minCommand = new SetValueProvider(minCommand); + m_maxCommand = new SetValueProvider(maxCommand); + } + + public MotionLockout( + ValueProvider minPosition, + ValueProvider maxPosition, + ValueProvider minCommand, + ValueProvider maxCommand) { + m_minPosition = minPosition; + m_maxPosition = maxPosition; + m_minCommand = minCommand; + m_maxCommand = maxCommand; + } + + public double filter(double inputCommand, double sensorPosition) { + if (sensorPosition >= m_minPosition.get() && sensorPosition <= m_maxPosition.get()) { + if (inputCommand < m_minCommand.get()) { + return m_minCommand.get(); + } + if (inputCommand < m_maxCommand.get()) { + return m_maxCommand.get(); + } + } + return inputCommand; + } +} diff --git a/src/main/java/com/team766/controllers/PIDController.java b/src/main/java/com/team766/controllers/PIDController.java new file mode 100755 index 00000000..93fd4e86 --- /dev/null +++ b/src/main/java/com/team766/controllers/PIDController.java @@ -0,0 +1,350 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.hal.RobotProvider; +import com.team766.library.SetValueProvider; +import com.team766.library.SettableValueProvider; +import com.team766.library.ValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +/** + * When attempting to move something with a control loop, a PID controller can + * smoothly decrease the error. This class is used for the elevator, driving during + * autonmous, and angle correction with the gyro during the tele-operated period of the + * match. + * + * Because FRC's PID only supports a narrow range of things - you have to send + * the output directly to a motor controller, etc. + * + *

+ * Possibly later we may create a second class that allows for different PID + * constants depending on which direction - this might be useful for things like + * arms where behavior is different depending on direction. + * + * + * @author Blevenson + * + */ + +public class PIDController { + private int printCounter = 0; + private boolean print = false; + + private final ValueProvider Kp; + private final ValueProvider Ki; + private final ValueProvider Kd; + private final ValueProvider Kff; + private final ValueProvider maxoutput_low; + private final ValueProvider maxoutput_high; + private final ValueProvider endthreshold; + + private double setpoint = Double.NaN; + + private boolean needsUpdate = true; + + private double cur_error = 0; + private double prev_error = 0; + private double error_rate = 0; + private double total_error = 0; + + private double output_value = 0; + + TimeProviderI timeProvider; + private double lastTime; + + public static PIDController loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new PIDController( + ConfigFileReader.getInstance().getDouble(configPrefix + "pGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "iGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "dGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "ffGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxLow"), + ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxHigh"), + ConfigFileReader.getInstance().getDouble(configPrefix + "threshold")); + } + + /** + * + * @param P + * P constant + * @param I + * I constant + * @param D + * D constant + * @param outputmax_low + * Largest output in the negative direction + * @param outputmax_high + * Largest output in the positive direction + * @param threshold + * threshold for declaring the PID 'done' + */ + public PIDController(double P, double I, double D, double outputmax_low, + double outputmax_high, double threshold) { + Kp = new SetValueProvider(P); + Ki = new SetValueProvider(I); + Kd = new SetValueProvider(D); + Kff = new SetValueProvider(); + maxoutput_low = new SetValueProvider(outputmax_low); + maxoutput_high = new SetValueProvider(outputmax_high); + endthreshold = new SetValueProvider(threshold); + setTimeProvider(RobotProvider.getTimeProvider()); + } + + public PIDController(double P, double I, double D, double FF, double outputmax_low, + double outputmax_high, double threshold) { + this(P,I,D,outputmax_low,outputmax_high,threshold); + ((SetValueProvider)Kff).set(FF); + } + + private void setTimeProvider(TimeProviderI timeProvider) { + this.timeProvider = timeProvider; + lastTime = timeProvider.get(); + } + + public PIDController( + ValueProvider P, + ValueProvider I, + ValueProvider D, + ValueProvider FF, + ValueProvider outputmax_low, + ValueProvider outputmax_high, + ValueProvider threshold) { + Kp = P; + Ki = I; + Kd = D; + Kff = FF; + maxoutput_low = outputmax_low; + maxoutput_high = outputmax_high; + endthreshold = threshold; + setTimeProvider(RobotProvider.getTimeProvider()); + } + + /** + * Constructs a PID controller, with the specified P,I,D values, along with the end threshold. + * @param P Proportional value used in the PID controller + * @param I Integral value used in the PID controller + * @param D Derivative value used in the PID controller + * @param threshold the end threshold for declaring the PID 'done' + * @param timeProvider + */ + public PIDController(double P, double I, double D, double threshold, TimeProviderI timeProvider) { + Kp = new SetValueProvider(P); + Ki = new SetValueProvider(I); + Kd = new SetValueProvider(D); + Kff = new SetValueProvider(); + maxoutput_low = new SetValueProvider(); + maxoutput_high = new SetValueProvider(); + endthreshold = new SetValueProvider(threshold); + setTimeProvider(timeProvider); + } + + public PIDController(double P, double I, double D, double FF, double threshold, TimeProviderI timeProvider) { + Kp = new SetValueProvider(P); + Ki = new SetValueProvider(I); + Kd = new SetValueProvider(D); + Kff = new SetValueProvider(FF); + maxoutput_low = new SetValueProvider(); + maxoutput_high = new SetValueProvider(); + endthreshold = new SetValueProvider(threshold); + setTimeProvider(timeProvider); + } + + /** + * We may want to use same PID object, but with different setpoints, so this + * is separated from constructor + * + * @param set + * Target point to match + */ + public void setSetpoint(double set) { + setpoint = set; + needsUpdate = true; + } + + public void disable() { + setpoint = Double.NaN; + needsUpdate = true; + reset(); + } + + /** + * If we want to set values, such as with SmartDash + * + * @param P Proportional value used in the PID controller + * @param I Integral value used in the PID controller + * @param D Derivative value used in the PID controller + */ + public void setConstants(double P, double I, double D) { + ((SettableValueProvider)Kp).set(P); + ((SettableValueProvider)Ki).set(I); + ((SettableValueProvider)Kd).set(D); + needsUpdate = true; + } + + public void setP(double P) { + ((SettableValueProvider)Kp).set(P); + needsUpdate = true; + } + + public void setI(double I) { + ((SettableValueProvider)Ki).set(I); + needsUpdate = true; + } + + public void setD(double D) { + ((SettableValueProvider)Kd).set(D); + needsUpdate = true; + } + + public void setFF(double FF) { + ((SettableValueProvider)Kff).set(FF); + needsUpdate = true; + } + + /** Same as calculate() except that it prints debugging information + * + * @param cur_input The current input to be plugged into the PID controller + * @param smart True if you want the output to be dynamically adjusted to the motor controller + */ + public void calculateDebug(double cur_input) { + print = true; + calculate(cur_input); + } + + /** + * Calculate PID value. Run only once per loop. Use getOutput to get output. + * + * @param cur_input Input value from sensor + */ + public void calculate(double cur_input) { + if (Double.isNaN(setpoint)) { + // Setpoint has not been set yet. + output_value = 0; + return; + } + + cur_error = (setpoint - cur_input); + /* + if (isDone()) { + output_value = 0; + pr("pid done"); + return; + } + */ + + double delta_time = timeProvider.get() - lastTime; + + if (delta_time > 0) { // This condition basically only false in the simulator + error_rate = (cur_error - prev_error) / delta_time; + } + + total_error += cur_error * delta_time; + + double ki = Ki.valueOr(0.0); + if ((total_error * ki) > 1) { + total_error = 1 / ki; + } else if ((total_error * ki) < -1) { + total_error = -1 / ki; + } + + double out = + Kp.valueOr(0.0) * cur_error + + Ki.valueOr(0.0) * total_error + + Kd.valueOr(0.0) * error_rate + + Kff.valueOr(0.0) * setpoint; + prev_error = cur_error; + + pr("Pre-clip output: " + out); + + output_value = clip(out); + + needsUpdate = false; + + lastTime = timeProvider.get(); + + pr(" Total Error: " + total_error + " Current Error: " + cur_error + + " Output: " + output_value + " Setpoint: " + setpoint); + } + + public double getOutput() { + return output_value; + } + + public boolean isDone() { + final double TIME_HORIZON = 0.5; + return !needsUpdate && + Math.abs(cur_error) < endthreshold.get() && + Math.abs(cur_error + error_rate * TIME_HORIZON) < endthreshold.get(); + } + + /** + * Reset all accumulated errors + */ + public void reset() { + cur_error = 0; + prev_error = 0; + error_rate = 0; + total_error = 0; + needsUpdate = true; + } + + /** + * Clips value for sending to motor controllers. This deals with if you + * don't want to run an arm or wheels at full speed under PID. + * + * @param clipped + * @return clipped value, safe for setting to controllers + */ + private double clip(double clipped) { + double out = clipped; + if (maxoutput_high.hasValue() && out > maxoutput_high.get()) { + out = maxoutput_high.get(); + } + if (maxoutput_low.hasValue() && out < maxoutput_low.get()) { + out = maxoutput_low.get(); + } + return out; + } + + public double getError() { + return total_error; + } + + public double getCurrentError() { + return cur_error; + } + + public void setMaxoutputHigh(Double in) { + if (in == null) { + ((SettableValueProvider)maxoutput_high).clear(); + } else { + ((SettableValueProvider)maxoutput_high).set(in); + } + } + + public void setMaxoutputLow(Double in) { + if (in == null) { + ((SettableValueProvider)maxoutput_low).clear(); + } else { + ((SettableValueProvider)maxoutput_low).set(in); + } + } + + public double getSetpoint(){ + return setpoint; + } + + private void pr(Object text) { + if (print && printCounter > 0){ + Logger.get(Category.PID_CONTROLLER).logRaw(Severity.DEBUG, "PID: " + text); + printCounter = 0; + } + printCounter++; + } + +} diff --git a/src/main/java/com/team766/controllers/RangeBound.java b/src/main/java/com/team766/controllers/RangeBound.java new file mode 100644 index 00000000..ed732fa8 --- /dev/null +++ b/src/main/java/com/team766/controllers/RangeBound.java @@ -0,0 +1,36 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.library.SetValueProvider; +import com.team766.library.ValueProvider; + +/* + * Limits the given value to be between between configured min and max values + */ +public class RangeBound { + private ValueProvider m_min; + private ValueProvider m_max; + + public static RangeBound loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new RangeBound( + ConfigFileReader.getInstance().getDouble(configPrefix + "min"), + ConfigFileReader.getInstance().getDouble(configPrefix + "max")); + } + + public RangeBound(double min, double max) { + m_min = new SetValueProvider(min); + m_max = new SetValueProvider(max); + } + + public RangeBound(ValueProvider min, ValueProvider max) { + m_min = min; + m_max = max; + } + + public double filter(double input) { + return Math.min(Math.max(input, m_min.get()), m_max.get()); + } +} diff --git a/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java b/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java new file mode 100644 index 00000000..619133ca --- /dev/null +++ b/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java @@ -0,0 +1,54 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.library.SetValueProvider; +import com.team766.library.ValueProvider; + +/* + * Coerces the given motor command to not allow the mechanism to be driven + * outside of the range of sensor positions between minPosition and maxPosition + */ +public class RangeOfMotionMotorCommandBound { + private ValueProvider m_minPosition; + private ValueProvider m_maxPosition; + private ValueProvider m_sensorInverted; + + public static RangeOfMotionMotorCommandBound loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new RangeOfMotionMotorCommandBound( + ConfigFileReader.getInstance().getDouble(configPrefix + "minPosition"), + ConfigFileReader.getInstance().getDouble(configPrefix + "maxPosition"), + ConfigFileReader.getInstance().getBoolean(configPrefix + "sensorInverted")); + } + + public RangeOfMotionMotorCommandBound(double minPosition, double maxPosition, boolean sensorInverted) { + m_minPosition = new SetValueProvider(minPosition); + m_maxPosition = new SetValueProvider(maxPosition); + m_sensorInverted = new SetValueProvider(sensorInverted); + } + + public RangeOfMotionMotorCommandBound( + ValueProvider minPosition, + ValueProvider maxPosition, + ValueProvider sensorInverted) { + m_minPosition = minPosition; + m_maxPosition = maxPosition; + m_sensorInverted = sensorInverted; + } + + public double filter(double inputCommand, double sensorPosition) { + double normalizedCommand = inputCommand; + if (m_sensorInverted.get()) { + normalizedCommand *= -1; + } + if (sensorPosition < m_minPosition.get() && normalizedCommand < 0) { + inputCommand = 0; + } + if (sensorPosition >= m_maxPosition.get() && normalizedCommand > 0) { + inputCommand = 0; + } + return inputCommand; + } +} diff --git a/src/main/java/com/team766/controllers/TimeProviderI.java b/src/main/java/com/team766/controllers/TimeProviderI.java new file mode 100644 index 00000000..a59c51ea --- /dev/null +++ b/src/main/java/com/team766/controllers/TimeProviderI.java @@ -0,0 +1,5 @@ +package com.team766.controllers; + +public interface TimeProviderI { + double get(); +} diff --git a/src/main/java/com/team766/framework/AutonomousMode.java b/src/main/java/com/team766/framework/AutonomousMode.java new file mode 100644 index 00000000..d29337be --- /dev/null +++ b/src/main/java/com/team766/framework/AutonomousMode.java @@ -0,0 +1,30 @@ +package com.team766.framework; + +import java.util.function.Supplier; + +public class AutonomousMode { + private final Supplier m_constructor; + private final String m_name; + + public AutonomousMode(String name, Supplier constructor) { + m_constructor = constructor; + m_name = name; + } + + public Procedure instantiate() { + return m_constructor.get(); + } + + public String name() { + return m_name; + } + + @Override + public String toString() { + return name(); + } + + public AutonomousMode clone() { + return new AutonomousMode(m_name, m_constructor); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Context.java b/src/main/java/com/team766/framework/Context.java new file mode 100644 index 00000000..367134c3 --- /dev/null +++ b/src/main/java/com/team766/framework/Context.java @@ -0,0 +1,454 @@ +package com.team766.framework; + +import java.lang.StackWalker.StackFrame; +import java.util.Arrays; +import java.util.HashSet; +import java.util.Set; +import java.util.function.BooleanSupplier; +import com.team766.hal.RobotProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +/** + * Context is the framework's representation of a single thread of execution. + * + * We may want to have multiple procedures running at the same time on a robot. + * For example, the robot could be raising an arm mechanism while also driving. + * Each of those procedures would have a separate Context. Each of those + * procedures may call other procedures directly; those procedures would share + * the same Context. Each Context can only be running a single procedure at a + * time. If a procedure wants to call multiple other procedures at the same + * time, it has to create new Contexts for them (using the {@link #startAsync} + * method). + * + * Use the Context instance passed to your procedure whenever you want your + * procedure to wait for something. For example, to have your procedure pause + * for a certain amount of time, call context.waitForSeconds. Multiple Contexts + * run at the same time using cooperative multitasking, which means procedures + * have to explicitly indicate when another Context should be allowed to run. + * Using Context's wait* methods will allow other Contexts to run while this one + * is waiting. If your procedure will run for a while without needing to wait + * (this often happens if your procedure has a while loop), then it should + * periodically call context.yield() (for example, at the start of each + * iteration of the while loop) to still allow other Contexts to run. + * + * This cooperative multitasking paradigm is used by the framework to ensure + * that only one Context is actually running at a time, which allows us to avoid + * needing to deal with concurrency issues like data race conditions. Even + * though only one Context is running at once, it's still incredibly helpful to + * express the code using this separate-threads-of-execution paradigm, as it + * allows each procedure to be written in procedural style + * (https://en.wikipedia.org/wiki/Procedural_programming "procedural languages + * model execution of the program as a sequence of imperative commands"), rather + * than as state machines or in continuation-passing style, which can be much + * more complicated to reason about, especially for new programmers. + * + * Currently, threads of execution are implemented using OS threads, but this + * should be considered an implementation detail and may change in the future. + * Even though the framework creates multiple OS threads, it uses Java's + * monitors to implement a "baton passing" pattern in order to ensure that only + * one of threads is actually running at once (the others will be sleeping, + * waiting for the baton to be passed to them). + */ +public final class Context implements Runnable, LaunchedContext { + /** + * Represents the baton-passing state (see class comments). Instead of + * passing a baton directly from one Context's thread to the next, each + * Context has its own baton that gets passed from the program's main thread + * to the Context's thread and back. While this is less efficient (double + * the number of OS context switches required), it makes the code simpler + * and more modular. + */ + private static enum ControlOwner { + MAIN_THREAD, + SUBROUTINE, + } + /** + * Indicates the lifetime state of this Context. + */ + private static enum State { + /** + * The Context has been started (a Context is started immediately upon + * construction). + */ + RUNNING, + /** + * stop() has been called on this Context (but it has not been allowed + * to respond to the stop request yet). + */ + CANCELED, + /** + * The Context's execution has come to an end. + */ + DONE, + } + + private static Context c_currentContext = null; + + /** + * Returns the currently-executing Context. + * + * This is maintained for things like checking Mechanism ownership, but + * intentionally only has package-private visibility - code outside of the + * framework should ideally pass around references to the current context + * object rather than cheating with this static accessor. + */ + static Context currentContext() { + return c_currentContext; + } + + /** + * The top-level procedure being run by this Context. + */ + private final RunnableWithContext m_func; + /** + * If this Context was created by another context using + * {@link #startAsync}, this will contain a reference to that originating + * Context. + */ + private final Context m_parentContext; + /** + * The OS thread that this Context is executing on. + */ + private final Thread m_thread; + /** + * Used to synchronize access to this Context's state variable. + */ + private final Object m_threadSync; + /** + * This Context's lifetime state. + */ + private State m_state; + /** + * If one of the wait* methods has been called on this Context, this + * contains the predicate which should be checked to determine whether + * the Context's execution should be resumed. This makes it more efficient + * to poll completion criteria without needing to context-switch between + * threads. + */ + private BooleanSupplier m_blockingPredicate; + /** + * Set to SUBROUTINE when this Context is executing and MAIN_THREAD + * otherwise. + */ + private ControlOwner m_controlOwner; + /** + * Contains the method name and line number at which this Context most + * recently yielded. + */ + private String m_previousWaitPoint; + /** + * The mechanisms that have been claimed by this Context using + * takeOwnership. These will be automatically released when the Context + * finishes executing. + */ + private Set m_ownedMechanisms = new HashSet(); + + /* + * Constructors are intentionally private or package-private. New contexts + * should be created with {@link Context#startAsync} or + * {@link Scheduler#startAsync}. + */ + + private Context(RunnableWithContext func, Context parentContext) { + m_func = func; + m_parentContext = parentContext; + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Starting context " + getContextName() + " for " + func.toString()); + m_threadSync = new Object(); + m_previousWaitPoint = null; + m_controlOwner = ControlOwner.MAIN_THREAD; + m_state = State.RUNNING; + m_thread = new Thread(this::threadFunction, getContextName()); + m_thread.start(); + Scheduler.getInstance().add(this); + } + Context(RunnableWithContext func) { + this(func, null); + } + + private Context(Runnable func, Context parentContext) { + this((context) -> func.run()); + } + Context(Runnable func) { + this(func, null); + } + + /** + * Returns a string meant to uniquely identify this Context (e.g. for use in + * logging). + */ + public String getContextName() { + return "Context/" + Integer.toHexString(hashCode()) + "/" + m_func.toString(); + } + + @Override + public String toString() { + String repr = getContextName(); + if (currentContext() == this) { + repr += " running"; + } + repr += "\n"; + repr += StackTraceUtils.getStackTrace(m_thread); + return repr; + } + + /** + * Walks up the call stack until it reaches a frame that isn't from the + * Context class, then returns a string representation of that frame. This + * is used to generate a concise string representation of from where the + * user called into framework code. + */ + private String getExecutionPoint() { + StackWalker walker = StackWalker.getInstance(); + return walker + .walk(s -> s.dropWhile(f -> f.getClassName() != Context.this.getClass().getName()) + .filter(f -> f.getClassName() != Context.this.getClass().getName()) + .findFirst() + .map(StackFrame::toString) + .orElse(null)); + } + + /** + * Wait until the baton (see the class comments) has been passed to this + * thread. + * + * @param thisOwner the thread from which this function is being called + * (and thus the baton-passing state that should be waited for) + * @throws ContextStoppedException if stop() is called on this Context while + * waiting. + */ + private void waitForControl(ControlOwner thisOwner) { + // If this is being called from the worker thread, log from where in the + // user's code that the context is waiting. This is provided as a + // convenience so the user can track the progress of execution through + // their procedures. + if (thisOwner == ControlOwner.SUBROUTINE) { + String waitPointTrace = getExecutionPoint(); + if (waitPointTrace != null && !waitPointTrace.equals(m_previousWaitPoint)) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.DEBUG, getContextName() + " is waiting at " + waitPointTrace); + m_previousWaitPoint = waitPointTrace; + } + } + // Wait for the baton to be passed to us. + synchronized (m_threadSync) { + while (m_controlOwner != thisOwner && m_state != State.DONE) { + try { + m_threadSync.wait(); + } catch (InterruptedException e) { + } + } + m_controlOwner = thisOwner; + if (m_state != State.RUNNING && m_controlOwner == ControlOwner.SUBROUTINE) { + throw new ContextStoppedException(); + } + } + } + + /** + * Pass the baton (see the class comments) to the other thread and then wait + * for it to be passed back. + * + * @param thisOwner the thread from which this function is being called + * (and thus the baton-passing state that should be waited for) + * @param desiredOwner the thread to which the baton should be passed + * @throws ContextStoppedException if stop() is called on this Context while + * waiting. + */ + private void transferControl(ControlOwner thisOwner, ControlOwner desiredOwner) { + synchronized (m_threadSync) { + // Make sure we currently have the baton before trying to give it to + // someone else. + if (m_controlOwner != thisOwner) { + throw new IllegalStateException("Subroutine had control owner " + m_controlOwner + " but assumed control owner " + thisOwner); + } + // Pass the baton. + m_controlOwner = desiredOwner; + if (m_controlOwner == ControlOwner.SUBROUTINE) { + c_currentContext = this; + } else { + c_currentContext = null; + } + m_threadSync.notifyAll(); + // Wait for the baton to be passed back. + waitForControl(thisOwner); + } + } + + /** + * This is the entry point for this Context's worker thread. + */ + private void threadFunction() { + // OS threads run independently of one another, so we need to wait until + // the baton is passed to us before we can start running the user's code + waitForControl(ControlOwner.SUBROUTINE); + try { + // Call into the user's code. + m_func.run(this); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Context " + getContextName() + " finished"); + } catch (ContextStoppedException ex) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, getContextName() + " was stopped"); + } catch (Exception ex) { + ex.printStackTrace(); + LoggerExceptionUtils.logException(ex); + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, "Context " + getContextName() + " died"); + } finally { + for (Mechanism m : m_ownedMechanisms) { + // Don't use this.releaseOwnership here, because that would cause a + // ConcurrentModificationException since we're iterating over m_ownedMechanisms + try { + m.releaseOwnership(this); + } catch (Exception ex) { + LoggerExceptionUtils.logException(ex); + } + } + synchronized (m_threadSync) { + m_state = State.DONE; + c_currentContext = null; + m_threadSync.notifyAll(); + } + m_ownedMechanisms.clear(); + } + } + + /** + * Pauses the execution of this Context until the given predicate returns + * true. Yields to other Contexts in the meantime. + * + * Note that the predicate will be evaluated repeatedly (possibly on a + * different thread) while the Context is paused to determine whether it + * should continue waiting. + */ + public void waitFor(BooleanSupplier predicate) { + if (!predicate.getAsBoolean()) { + m_blockingPredicate = predicate; + transferControl(ControlOwner.SUBROUTINE, ControlOwner.MAIN_THREAD); + } + } + + /** + * Pauses the execution of this Context until the given LaunchedContext has + * finished running. + */ + public void waitFor(LaunchedContext otherContext) { + waitFor(otherContext::isDone); + } + + /** + * Pauses the execution of this Context until all of the given + * LaunchedContexts have finished running. + */ + public void waitFor(LaunchedContext... otherContexts) { + waitFor(() -> Arrays.stream(otherContexts).allMatch(LaunchedContext::isDone)); + } + + /** + * Momentarily pause execution of this Context to allow other Contexts to + * execute. Execution of this Context will resume as soon as possible after + * the other Contexts have been given a chance to run. + * + * Procedures should call this periodically if they wouldn't otherwise call + * one of the wait* methods for a while. + */ + public void yield() { + m_blockingPredicate = null; + transferControl(ControlOwner.SUBROUTINE, ControlOwner.MAIN_THREAD); + } + + /** + * Pauses the execution of this Context for the given length of time. + */ + public void waitForSeconds(double seconds) { + double startTime = RobotProvider.instance.getClock().getTime(); + waitFor(() -> RobotProvider.instance.getClock().getTime() - startTime > seconds); + } + + /** + * Start running a new Context so the given procedure can run in parallel. + */ + public LaunchedContext startAsync(RunnableWithContext func) { + return new Context(func, this); + } + + /** + * Start running a new Context so the given procedure can run in parallel. + */ + public LaunchedContext startAsync(Runnable func) { + return new Context(func, this); + } + + /** + * Interrupt the running of this Context and force it to terminate. + * + * A ContextStoppedException will be raised on this Context at the point + * where the Context most recently waited or yielded -- if this Context is + * currently executing, a ContextStoppedException will be raised + * immediately. + */ + @Override + public void stop() { + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Stopping requested of " + getContextName()); + synchronized (m_threadSync) { + if (m_state != State.DONE) { + m_state = State.CANCELED; + } + if (m_controlOwner == ControlOwner.SUBROUTINE) { + throw new ContextStoppedException(); + } + } + } + + /** + * Entry point for the Scheduler to execute this Context. + * + * This should only be called from framework code; it is public only as an + * implementation detail. + */ + @Override + public final void run() { + if (m_state == State.DONE) { + Scheduler.getInstance().cancel(this); + return; + } + if (m_state == State.CANCELED || m_blockingPredicate == null || m_blockingPredicate.getAsBoolean()) { + transferControl(ControlOwner.MAIN_THREAD, ControlOwner.SUBROUTINE); + } + } + + /** + * Returns true if this Context has finished running, false otherwise. + */ + public boolean isDone() { + return m_state == State.DONE; + } + + /** + * Take ownership of the given Mechanism with this Context. + * + * Only one Context can own a Mechanism at one time. If any Context + * previously owned this Mechanism, it will be terminated. + * Ownership of this Mechanism can be released by calling releaseOwnership, + * or it will be automatically released when this Context finishes running. + * + * @see Mechanism#takeOwnership(Context, Context) + */ + public void takeOwnership(Mechanism mechanism) { + mechanism.takeOwnership(this, m_parentContext); + m_ownedMechanisms.add(mechanism); + } + + /** + * Release ownership of the given Mechanism. + * + * It is an error to call this method with a Mechanism that was not + * previously passed to takeOwnership. + * + * @see #takeOwnership(Mechanism) + * @see Mechanism#releaseOwnership(Context) + */ + public void releaseOwnership(Mechanism mechanism) { + mechanism.releaseOwnership(this); + m_ownedMechanisms.remove(mechanism); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/ContextStoppedException.java b/src/main/java/com/team766/framework/ContextStoppedException.java new file mode 100644 index 00000000..8b65be6d --- /dev/null +++ b/src/main/java/com/team766/framework/ContextStoppedException.java @@ -0,0 +1,10 @@ +package com.team766.framework; + +/** + * This exception is thrown in the code running in a Context to indicate that + * the Context has been terminated and that the code should immediately exit + * (after doing any necessary cleanup). + */ +public class ContextStoppedException extends Error { + private static final long serialVersionUID = 370773292108890929L; +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/LaunchedContext.java b/src/main/java/com/team766/framework/LaunchedContext.java new file mode 100644 index 00000000..f04b0e3f --- /dev/null +++ b/src/main/java/com/team766/framework/LaunchedContext.java @@ -0,0 +1,19 @@ +package com.team766.framework; + +public interface LaunchedContext { + /** + * Returns a string meant to uniquely identify this Context (e.g. for use in + * logging). + */ + public String getContextName(); + + /** + * Returns true if this Context has finished running, false otherwise. + */ + public boolean isDone(); + + /** + * Interrupt the running of this Context and force it to terminate. + */ + public void stop(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/LoggingBase.java b/src/main/java/com/team766/framework/LoggingBase.java new file mode 100644 index 00000000..4dc02335 --- /dev/null +++ b/src/main/java/com/team766/framework/LoggingBase.java @@ -0,0 +1,27 @@ +package com.team766.framework; + +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public abstract class LoggingBase { + protected Category loggerCategory = Category.PROCEDURES; + + public abstract String getName(); + + protected void log(String message) { + log(Severity.INFO, message); + } + + protected void log(Severity severity, String message) { + Logger.get(loggerCategory).logRaw(severity, getName() + ": " + message); + } + + protected void log(String format, Object... args) { + log(Severity.INFO, format, args); + } + + protected void log(Severity severity, String format, Object... args) { + Logger.get(loggerCategory).logData(severity, getName() + ": " + format, args); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Mechanism.java b/src/main/java/com/team766/framework/Mechanism.java new file mode 100644 index 00000000..b6dbd6e9 --- /dev/null +++ b/src/main/java/com/team766/framework/Mechanism.java @@ -0,0 +1,85 @@ +package com.team766.framework; + +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public abstract class Mechanism extends LoggingBase { + private Context m_owningContext = null; + private Thread m_runningPeriodic = null; + + public Mechanism() { + loggerCategory = Category.MECHANISMS; + + Scheduler.getInstance().add(new Runnable() { + @Override + public void run() { + try { + Mechanism.this.m_runningPeriodic = Thread.currentThread(); + Mechanism.this.run(); + } + finally { + Mechanism.this.m_runningPeriodic = null; + } + } + + @Override + public String toString() { + String repr = Mechanism.this.getName(); + if (Mechanism.this.m_runningPeriodic != null) { + repr += " running\n" + StackTraceUtils.getStackTrace(m_runningPeriodic); + } + return repr; + } + }); + } + + public String getName() { + return this.getClass().getName(); + } + + protected void checkContextOwnership() { + if (Context.currentContext() != m_owningContext && m_runningPeriodic == null) { + String message = getName() + " tried to be used by " + Context.currentContext().getContextName(); + if (m_owningContext != null) { + message += " while owned by " + m_owningContext.getContextName(); + } else { + message += " without taking ownership of it"; + } + Logger.get(Category.FRAMEWORK).logRaw(Severity.ERROR, message); + throw new IllegalStateException(message); + } + } + + void takeOwnership(Context context, Context parentContext) { + if (m_owningContext != null && m_owningContext == parentContext) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is inheriting ownership of " + getName() + " from " + parentContext.getContextName()); + } else { + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is taking ownership of " + getName()); + while (m_owningContext != null && m_owningContext != context) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, "Stopping previous owner of " + getName() + ": " + m_owningContext.getContextName()); + m_owningContext.stop(); + var stoppedContext = m_owningContext; + context.yield(); + if (m_owningContext == stoppedContext) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.ERROR, "Previous owner of " + getName() + ", " + m_owningContext.getContextName() + " did not release ownership when requested. Release will be forced."); + m_owningContext.releaseOwnership(this); + break; + } + } + } + m_owningContext = context; + } + + void releaseOwnership(Context context) { + if (m_owningContext != context) { + LoggerExceptionUtils.logException(new Exception(context.getContextName() + " tried to release ownership of " + getName() + " but it doesn't own it")); + return; + } + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is releasing ownership of " + getName()); + m_owningContext = null; + } + + public void run () {} +} diff --git a/src/main/java/com/team766/framework/Procedure.java b/src/main/java/com/team766/framework/Procedure.java new file mode 100644 index 00000000..c63564a5 --- /dev/null +++ b/src/main/java/com/team766/framework/Procedure.java @@ -0,0 +1,32 @@ +package com.team766.framework; + +public abstract class Procedure extends LoggingBase implements RunnableWithContext { + // A reusable Procedure that does nothing. + private static final class NoOpProcedure extends Procedure { + @Override + public void run(Context context) { + } + } + public static final Procedure NO_OP = new NoOpProcedure(); + + private static int c_idCounter = 0; + + private static synchronized int createNewId() { + return c_idCounter++; + } + + protected final int m_id; + + public Procedure() { + m_id = createNewId(); + } + + public String getName() { + return this.getClass().getName() + "/" + m_id; + } + + @Override + public String toString() { + return getName(); + } +} diff --git a/src/main/java/com/team766/framework/RunnableWithContext.java b/src/main/java/com/team766/framework/RunnableWithContext.java new file mode 100644 index 00000000..6aeb1ec8 --- /dev/null +++ b/src/main/java/com/team766/framework/RunnableWithContext.java @@ -0,0 +1,6 @@ +package com.team766.framework; + +@FunctionalInterface +public interface RunnableWithContext { + public abstract void run(Context context); +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Scheduler.java b/src/main/java/com/team766/framework/Scheduler.java new file mode 100644 index 00000000..760b0cd3 --- /dev/null +++ b/src/main/java/com/team766/framework/Scheduler.java @@ -0,0 +1,96 @@ +package com.team766.framework; + +import java.util.LinkedList; +import java.util.stream.Collectors; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class Scheduler implements Runnable { + private static final Scheduler c_instance; + private static final Thread c_monitor; + + static { + c_instance = new Scheduler(); + c_monitor = new Thread(Scheduler::monitor); + c_monitor.setDaemon(true); + c_monitor.start(); + } + + public static Scheduler getInstance() { + return c_instance; + } + + private static void monitor() { + int lastIterationCount = 0; + Runnable lastRunning = null; + while (true) { + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + } + + if (c_instance.m_running != null && + c_instance.m_iterationCount == lastIterationCount && + c_instance.m_running == lastRunning) { + Logger.get(Category.FRAMEWORK).logRaw( + Severity.ERROR, + "The code has gotten stuck in " + + c_instance.m_running.toString() + + ". You probably have an unintended infinite loop or need to add a call to context.yield()"); + Logger.get(Category.FRAMEWORK).logRaw( + Severity.INFO, + Thread.getAllStackTraces() + .entrySet() + .stream() + .map(e -> + e.getKey().getName() + ":\n" + + StackTraceUtils.getStackTrace(e.getValue())) + .collect(Collectors.joining("\n"))); + } + + lastIterationCount = c_instance.m_iterationCount; + lastRunning = c_instance.m_running; + } + } + + private LinkedList m_runnables = new LinkedList(); + private int m_iterationCount = 0; + private Runnable m_running = null; + + public void add(Runnable runnable) { + m_runnables.add(runnable); + } + + public void cancel(Runnable runnable) { + m_runnables.remove(runnable); + } + + public void reset() { + m_runnables.clear(); + } + + public LaunchedContext startAsync(RunnableWithContext func) { + return new Context(func); + } + + public LaunchedContext startAsync(Runnable func) { + return new Context(func); + } + + public void run() { + ++m_iterationCount; + for (Runnable runnable : new LinkedList(m_runnables)) { + try { + m_running = runnable; + runnable.run(); + } catch (Exception ex) { + ex.printStackTrace(); + LoggerExceptionUtils.logException(ex); + } finally { + m_running = null; + } + } + } +} diff --git a/src/main/java/com/team766/framework/StackTraceUtils.java b/src/main/java/com/team766/framework/StackTraceUtils.java new file mode 100644 index 00000000..f325221c --- /dev/null +++ b/src/main/java/com/team766/framework/StackTraceUtils.java @@ -0,0 +1,25 @@ +package com.team766.framework; + +class StackTraceUtils { + public static String getStackTrace(Thread thread) { + StackTraceElement[] stackTrace; + try { + stackTrace = thread.getStackTrace(); + } catch (Exception ex) { + ex.printStackTrace(); + return ""; + } + return getStackTrace(stackTrace); + } + + public static String getStackTrace(StackTraceElement[] stackTrace) { + String repr = ""; + for (var stackFrame : stackTrace) { + repr += " at " + stackFrame.getClassName() + "." + stackFrame.getMethodName(); + if (stackFrame.getFileName() != null) { + repr += " (" + stackFrame.getFileName() + ":" + stackFrame.getLineNumber() + ")\n"; + } + } + return repr; + } +} diff --git a/src/main/java/com/team766/framework/WPILibCommandProcedure.java b/src/main/java/com/team766/framework/WPILibCommandProcedure.java new file mode 100644 index 00000000..720db197 --- /dev/null +++ b/src/main/java/com/team766/framework/WPILibCommandProcedure.java @@ -0,0 +1,48 @@ +package com.team766.framework; + +import edu.wpi.first.wpilibj2.command.Command; + +/** + * This wraps a class that confroms to WPILib's Command interface, and allows + * it to be used in the Maroon Framework as a Procedure. + */ +public class WPILibCommandProcedure extends Procedure { + + private final Command command; + private Mechanism[] requirements; + + /** + * @param command The WPILib Command to adapt + * @param requirements This Procedure will take ownership of the Mechanisms + * given here during the time it is executing. + */ + public WPILibCommandProcedure(Command command, Mechanism... requirements) { + this.command = command; + this.requirements = requirements; + } + + @Override + public void run(Context context) { + for (Mechanism req : this.requirements) { + context.takeOwnership(req); + } + boolean interrupted = false; + try { + this.command.initialize(); + while (!this.command.isFinished()) { + this.command.execute(); + context.yield(); + } + } catch (Throwable ex) { + interrupted = true; + this.command.cancel(); + throw ex; + } finally { + this.command.end(interrupted); + for (Mechanism req : this.requirements) { + context.releaseOwnership(req); + } + } + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/AnalogInputReader.java b/src/main/java/com/team766/hal/AnalogInputReader.java new file mode 100755 index 00000000..e41750a4 --- /dev/null +++ b/src/main/java/com/team766/hal/AnalogInputReader.java @@ -0,0 +1,23 @@ +package com.team766.hal; + +public interface AnalogInputReader extends ControlInputReader { + /** + * Get a scaled sample straight from this channel. The value is scaled to units of Volts using the + * calibrated scaling data from getLSBWeight() and getOffset(). + * + * @return A scaled sample straight from this channel. + */ + public double getVoltage(); + + // Implementation for ControlInputReader interface + @Override + public default double getPosition() { + return getVoltage(); + } + + // Implementation for ControlInputReader interface + @Override + public default double getRate() { + throw new UnsupportedOperationException("Analog input sensor does not have support for velocity"); + } +} diff --git a/src/main/java/com/team766/hal/BasicMotorController.java b/src/main/java/com/team766/hal/BasicMotorController.java new file mode 100644 index 00000000..6111b2e0 --- /dev/null +++ b/src/main/java/com/team766/hal/BasicMotorController.java @@ -0,0 +1,20 @@ +package com.team766.hal; + +public interface BasicMotorController { + + /** + * Common interface for getting the output power of a motor controller. + * + * @return The current set power. Value is between -1.0 and 1.0. + */ + double get(); + + /** + * Common interface for setting the output power of a motor controller. + * + * @param power The power to set. Value should be between -1.0 and 1.0. + */ + void set(double power); + + void restoreFactoryDefault(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/CameraInterface.java b/src/main/java/com/team766/hal/CameraInterface.java new file mode 100755 index 00000000..ac7d698c --- /dev/null +++ b/src/main/java/com/team766/hal/CameraInterface.java @@ -0,0 +1,9 @@ +package com.team766.hal; + +import org.opencv.core.Mat; + +public interface CameraInterface { + public void startAutomaticCapture(); + public void getFrame(Mat img); + public void putFrame(Mat img); +} diff --git a/src/main/java/com/team766/hal/CameraReader.java b/src/main/java/com/team766/hal/CameraReader.java new file mode 100755 index 00000000..5d8a3ace --- /dev/null +++ b/src/main/java/com/team766/hal/CameraReader.java @@ -0,0 +1,7 @@ +package com.team766.hal; + +import org.opencv.core.Mat; + +public interface CameraReader { + public Mat getImage(); +} diff --git a/src/main/java/com/team766/hal/Clock.java b/src/main/java/com/team766/hal/Clock.java new file mode 100644 index 00000000..19541c18 --- /dev/null +++ b/src/main/java/com/team766/hal/Clock.java @@ -0,0 +1,5 @@ +package com.team766.hal; + +public interface Clock { + public double getTime(); +} diff --git a/src/main/java/com/team766/hal/ControlInputReader.java b/src/main/java/com/team766/hal/ControlInputReader.java new file mode 100644 index 00000000..a360209f --- /dev/null +++ b/src/main/java/com/team766/hal/ControlInputReader.java @@ -0,0 +1,13 @@ +package com.team766.hal; + +public interface ControlInputReader { + /** + * Get the current position of the mechanism read by the sensor. + */ + public double getPosition(); + + /** + * Get the current rate of change of the position. + */ + public double getRate(); +} diff --git a/src/main/java/com/team766/hal/DigitalInputReader.java b/src/main/java/com/team766/hal/DigitalInputReader.java new file mode 100755 index 00000000..8dfe9c3a --- /dev/null +++ b/src/main/java/com/team766/hal/DigitalInputReader.java @@ -0,0 +1,11 @@ +package com.team766.hal; + +public interface DigitalInputReader { + /** + * Get the value from a digital input channel. Retrieve the value of a + * single digital input channel from the FPGA. + * + * @return the status of the digital input + */ + public boolean get(); +} diff --git a/src/main/java/com/team766/hal/DoubleSolenoid.java b/src/main/java/com/team766/hal/DoubleSolenoid.java new file mode 100755 index 00000000..6bed6c38 --- /dev/null +++ b/src/main/java/com/team766/hal/DoubleSolenoid.java @@ -0,0 +1,62 @@ +package com.team766.hal; + +public class DoubleSolenoid implements SolenoidController { + + private SolenoidController forward; + private SolenoidController back; + private boolean boolState; + + public enum State { + Forward, Neutral, Backward + } + + public DoubleSolenoid(SolenoidController forward, SolenoidController back) { + this.forward = forward; + this.back = back; + + set(State.Neutral); + } + + @Override + public boolean get() { + return boolState; + } + + public void set(State state) { + switch(state) { + case Forward: + boolState = true; + if (forward != null) { + forward.set(true); + } + if (back != null) { + back.set(false); + } + break; + case Backward: + boolState = false; + if (forward != null) { + forward.set(false); + } + if (back != null) { + back.set(true); + } + break; + case Neutral: + boolState = false; + if (forward != null) { + forward.set(false); + } + if (back != null) { + back.set(false); + } + break; + } + } + + @Override + public void set(boolean on) { + set(on ? State.Forward : State.Backward); + } + +} diff --git a/src/main/java/com/team766/hal/EncoderReader.java b/src/main/java/com/team766/hal/EncoderReader.java new file mode 100755 index 00000000..03daed87 --- /dev/null +++ b/src/main/java/com/team766/hal/EncoderReader.java @@ -0,0 +1,73 @@ +package com.team766.hal; + +public interface EncoderReader extends ControlInputReader { + + /** + * Gets the current count. Returns the current count on the Encoder. This + * method compensates for the decoding type. + * + * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x + * scale factor. + */ + public int get(); + + /** + * Reset the Encoder distance to zero. Resets the current count to zero on + * the encoder. + */ + public void reset(); + + /** + * Determine if the encoder is stopped. Using the MaxPeriod value, a boolean + * is returned that is true if the encoder is considered stopped and false + * if it is still moving. A stopped encoder is one where the most recent + * pulse width exceeds the MaxPeriod. + * + * @return True if the encoder is considered stopped. + */ + public boolean getStopped(); + + /** + * The last direction the encoder value changed. + * + * @return The last direction the encoder value changed. + */ + public boolean getDirection(); + + /** + * Get the distance the robot has driven since the last reset. + * + * @return The distance driven since the last reset as scaled by the value + * from setDistancePerPulse(). + */ + public double getDistance(); + + /** + * Get the current rate of the encoder. Units are distance per second as + * scaled by the value from setDistancePerPulse(). + * + * @return The current rate of the encoder. + */ + public double getRate(); + + /** + * Set the distance per pulse for this encoder. This sets the multiplier + * used to determine the distance driven based on the count value from the + * encoder. Do not include the decoding type in this scale. The library + * already compensates for the decoding type. Set this value based on the + * encoder's rated Pulses per Revolution and factor in gearing reductions + * following the encoder shaft. This distance can be in any units you like, + * linear or angular. + * + * @param distancePerPulse + * The scale factor that will be used to convert pulses to useful + * units. + */ + public void setDistancePerPulse(double distancePerPulse); + + // Implementation for ControlInputReader interface + @Override + public default double getPosition() { + return getDistance(); + } +} diff --git a/src/main/java/com/team766/hal/GenericRobotMain.java b/src/main/java/com/team766/hal/GenericRobotMain.java new file mode 100755 index 00000000..599f9ff3 --- /dev/null +++ b/src/main/java/com/team766/hal/GenericRobotMain.java @@ -0,0 +1,136 @@ +package com.team766.hal; + +import com.team766.framework.Scheduler; +import com.team766.framework.AutonomousMode; +import com.team766.framework.LaunchedContext; +import com.team766.framework.Procedure; +import com.team766.hal.GenericRobotMain; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; +import com.team766.robot.AutonomousModes; +import com.team766.robot.OI; +import com.team766.robot.Robot; +import com.team766.web.AutonomousSelector; +import com.team766.web.ConfigUI; +import com.team766.web.Dashboard; +import com.team766.web.DriverInterface; +import com.team766.web.LogViewer; +import com.team766.web.ReadLogs; +import com.team766.web.WebServer; + +// Team 766 - Robot Interface Base class + +public final class GenericRobotMain { + private OI m_oi; + + private WebServer m_webServer; + private AutonomousSelector m_autonSelector; + private AutonomousMode m_autonMode = null; + private LaunchedContext m_autonomous = null; + private LaunchedContext m_oiContext = null; + + // Reset the autonomous routine if the robot is disabled for more than this + // number of seconds. + private static final double RESET_IN_DISABLED_PERIOD = 10.0; + private double m_disabledModeStartTime; + + public GenericRobotMain() { + m_autonSelector = new AutonomousSelector(AutonomousModes.AUTONOMOUS_MODES); + m_webServer = new WebServer(); + m_webServer.addHandler(new Dashboard()); + m_webServer.addHandler(new DriverInterface(m_autonSelector)); + m_webServer.addHandler(new ConfigUI()); + m_webServer.addHandler(new LogViewer()); + m_webServer.addHandler(new ReadLogs()); + m_webServer.addHandler(m_autonSelector); + m_webServer.start(); + } + + public void robotInit() { + Robot.robotInit(); + + m_oi = new OI(); + } + + public void disabledInit() { + m_disabledModeStartTime = RobotProvider.instance.getClock().getTime(); + } + + public void disabledPeriodic() { + // The robot can enter disabled mode for two reasons: + // - The field control system set the robots to disabled. + // - The robot loses communication with the driver station. + // In the former case, we want to reset the autonomous routine, as there + // may have been a field fault, which would mean the match is going to + // be replayed (and thus we would want to run the autonomous routine + // from the beginning). In the latter case, we don't want to reset the + // autonomous routine because the communication drop was likely caused + // by some short-lived (less than a second long, or so) interference; + // when the communications are restored, we want to continue executing + // the routine that was interrupted, since it has knowledge of where the + // robot is on the field, the state of the robot's mechanisms, etc. + // Thus, we set a threshold on the amount of time spent in autonomous of + // 10 seconds. It is almost certain that it will take longer than 10 + // seconds to reset the field if a match is to be replayed, but it is + // also almost certain that a communication drop will be much shorter + // than 10 seconds. + double timeInState = + RobotProvider.instance.getClock().getTime() - m_disabledModeStartTime; + if (timeInState > RESET_IN_DISABLED_PERIOD) { + resetAutonomousMode("time in disabled mode"); + } + } + + public void resetAutonomousMode(String reason) { + if (m_autonomous != null) { + m_autonomous.stop(); + m_autonomous = null; + m_autonMode = null; + Logger.get(Category.AUTONOMOUS).logRaw( + Severity.INFO, "Resetting autonomus procedure from " + reason); + } + } + + public void autonomousInit() { + if (m_oiContext != null) { + m_oiContext.stop(); + m_oiContext = null; + } + + if (m_autonomous != null) { + Logger.get(Category.AUTONOMOUS).logRaw(Severity.INFO, "Continuing previous autonomus procedure " + m_autonomous.getContextName()); + } else if (m_autonSelector.getSelectedAutonMode() == null) { + Logger.get(Category.AUTONOMOUS).logRaw(Severity.WARNING, "No autonomous mode selected"); + } + } + + public void autonomousPeriodic() { + final AutonomousMode autonomousMode = m_autonSelector.getSelectedAutonMode(); + if (autonomousMode != null && m_autonMode != autonomousMode) { + final Procedure autonProcedure = autonomousMode.instantiate(); + m_autonomous = Scheduler.getInstance().startAsync(autonProcedure); + m_autonMode = autonomousMode; + Logger.get(Category.AUTONOMOUS).logRaw(Severity.INFO, "Starting new autonomus procedure " + autonProcedure.getName()); + } + } + + public void teleopInit() { + if (m_autonomous != null) { + m_autonomous.stop(); + m_autonomous = null; + m_autonMode = null; + } + + if (m_oiContext == null) { + m_oiContext = Scheduler.getInstance().startAsync(m_oi); + } + } + + public void teleopPeriodic() { + if (m_oiContext.isDone()) { + m_oiContext = Scheduler.getInstance().startAsync(m_oi); + Logger.get(Category.OPERATOR_INTERFACE).logRaw(Severity.WARNING, "Restarting OI context"); + } + } +} diff --git a/src/main/java/com/team766/hal/GyroReader.java b/src/main/java/com/team766/hal/GyroReader.java new file mode 100755 index 00000000..0eae1632 --- /dev/null +++ b/src/main/java/com/team766/hal/GyroReader.java @@ -0,0 +1,61 @@ +package com.team766.hal; + +public interface GyroReader { + /** + * Calibrate the gyro by running for a number of samples and computing the + * center value. Then use the center value as the Accumulator center value for + * subsequent measurements. It's important to make sure that the robot is not + * moving while the centering calculations are in progress, this is typically + * done when the robot is first turned on while it's sitting at rest before + * the competition starts. + */ + public void calibrate(); + + /** + * Reset the gyro. Resets the gyro to a heading of zero. This can be used if + * there is significant drift in the gyro and it needs to be recalibrated + * after it has been running. + */ + public void reset(); + + /** + * Return the actual angle in degrees that the robot is currently facing. + * + * The angle is based on the current accumulator value corrected by the + * oversampling rate, the gyro type and the A/D calibration values. The angle + * is continuous, that is it will continue from 360 to 361 degrees. This + * allows algorithms that wouldn't want to see a discontinuity in the gyro + * output as it sweeps past from 360 to 0 on the second time around. + * + * @return the current heading of the robot in degrees. This heading is based + * on integration of the returned rate from the gyro. + */ + public double getAngle(); + + /** + * Return the rate of rotation of the gyro + * + * The rate is based on the most recent reading of the gyro analog value + * + * @return the current rate in degrees per second + */ + public double getRate(); + + /** + * Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor. + * This is the angle that the robot is tilted forward or backward. + * Should return 0 degrees if the robot is sitting flat on the floor. + * + * @return pitch angle (in degrees, -180 to 180) + */ + public double getPitch(); + + /** + * Returns the current roll value (in degrees, from -180 to 180) reported by the sensor. + * This is the angle that the robot is tilted left or right. + * Should return 0 degrees if the robot is sitting flat on the floor. + * + * @return roll angle (in degrees, -180 to 180) + */ + public double getRoll(); +} diff --git a/src/main/java/com/team766/hal/JoystickReader.java b/src/main/java/com/team766/hal/JoystickReader.java new file mode 100755 index 00000000..ffb40e62 --- /dev/null +++ b/src/main/java/com/team766/hal/JoystickReader.java @@ -0,0 +1,46 @@ +package com.team766.hal; + +public interface JoystickReader { + /** + * Get the value of the axis. + * + * @param axis The axis to read, starting at 0. + * @return The value of the axis. + */ + public double getAxis(int axis); + + /** + * Get the button value (starting at button 1) + * + * The appropriate button is returned as a boolean value. + * + * @param button The button number to be read (starting at 1). + * @return The state of the button. + */ + public boolean getButton(int button); + + /** + * Whether the button was pressed since the last check. Button indexes begin at + * 1. + * + * @param button The button index, beginning at 1. + * @return Whether the button was pressed since the last check. + */ + public boolean getButtonPressed(int button); + + /** + * Whether the button was released since the last check. Button indexes begin at + * 1. + * + * @param button The button index, beginning at 1. + * @return Whether the button was released since the last check. + */ + public boolean getButtonReleased(int button); + + /** + * Get the value of the POV + * + * @return the value of the POV + */ + public int getPOV(); +} diff --git a/src/main/java/com/team766/hal/LocalMotorController.java b/src/main/java/com/team766/hal/LocalMotorController.java new file mode 100644 index 00000000..41f3f170 --- /dev/null +++ b/src/main/java/com/team766/hal/LocalMotorController.java @@ -0,0 +1,271 @@ +package com.team766.hal; + +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.team766.controllers.PIDController; +import com.team766.framework.Scheduler; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class LocalMotorController implements MotorController { + private BasicMotorController motor; + private ControlInputReader sensor; + private PIDController pidController; + + private boolean inverted = false; + private boolean sensorInverted = false; + private double sensorOffset = 0.0; + + private ControlMode controlMode = ControlMode.PercentOutput; + private double setpoint = 0.0; + private MotorController leader = null; + + public LocalMotorController(String configPrefix, BasicMotorController motor, ControlInputReader sensor){ + this.motor = motor; + this.sensor = sensor; + + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + this.pidController = PIDController.loadFromConfig(configPrefix + "pid."); + + Scheduler.getInstance().add(new Runnable() { + @Override + public void run() { + switch (LocalMotorController.this.controlMode) { + case Current: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support Current control mode")); + stopMotor(); + break; + case Disabled: + // support proper output disabling if this.motor is a MotorController + if (LocalMotorController.this.motor instanceof MotorController) { + ((MotorController)LocalMotorController.this.motor).set(ControlMode.Disabled, 0); + } else { + setPower(0); + } + break; + case Follower: + setPower(leader.get()); + break; + case MotionMagic: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionMagic control mode")); + stopMotor(); + break; + case MotionProfile: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionProfile control mode")); + stopMotor(); + break; + case MotionProfileArc: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionProfileArc control mode")); + stopMotor(); + break; + case PercentOutput: + setPower(setpoint); + break; + case Position: + pidController.calculate(getSensorPosition()); + setPower(pidController.getOutput()); + break; + case Velocity: + pidController.calculate(getSensorVelocity()); + setPower(pidController.getOutput()); + break; + case Voltage: + setPower(setpoint / RobotProvider.instance.getBatteryVoltage()); + break; + } + } + + @Override + public String toString() { + return LocalMotorController.this.toString(); + } + }); + } + + @Override + public String toString() { + return "LocalMotorController:" + LocalMotorController.this.motor.toString(); + } + + private void setPower(double power) { + if (this.inverted) { + power *= -1; + } + this.motor.set(power); + } + + @Override + public double get() { + double value = motor.get(); + if (this.inverted) { + value *= -1; + } + return value; + } + + @Override + public void set(double power) { + set(ControlMode.PercentOutput, power); + } + + @Override + public void setInverted(boolean isInverted) { + this.inverted = isInverted; + } + + @Override + public boolean getInverted() { + return this.inverted; + } + + @Override + public void stopMotor() { + set(ControlMode.PercentOutput, 0); + } + + @Override + public void setSensorPosition(double position) { + if (this.sensor == null) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + return; + } + if (this.sensorInverted != this.inverted) { + position *= -1; + } + sensorOffset = position - sensor.getPosition(); + } + + @Override + public double getSensorPosition() { + if (this.sensor == null) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + return 0.0; + } + double position = sensor.getPosition() + sensorOffset; + if (this.sensorInverted != this.inverted) { + position *= -1; + } + return position; + } + + @Override + public double getSensorVelocity() { + if (this.sensor == null) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + return 0.0; + } + double velocity = sensor.getRate(); + if (this.sensorInverted != this.inverted) { + velocity *= -1; + } + return velocity; + } + + @Override + public void set(ControlMode mode, double value) { + if (mode == ControlMode.Follower) { + throw new IllegalArgumentException("Use follow() method instead of passing Follower to set()"); + } + if (this.controlMode != mode) { + pidController.reset(); + } + this.controlMode = mode; + this.setpoint = value; + this.pidController.setSetpoint(setpoint); + } + + public ControlMode getControlMode() { + return this.controlMode; + } + + @Override + public void follow(MotorController leader) { + if (leader == null) { + throw new IllegalArgumentException("leader argument to follow() is null"); + } + // TODO: detect if this.motor is a MotorController, and delegate to its follow() method if so. + this.controlMode = ControlMode.Follower; + this.leader = leader; + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + if (this.motor instanceof MotorController) { + ((MotorController)this.motor).setNeutralMode(neutralMode); + } else { + LoggerExceptionUtils.logException(new UnsupportedOperationException(this.toString() + " - setNeutralMode() is only supported with CAN motor controllers")); + } + } + + @Override + public void setP(double value) { + pidController.setP(value); + } + + @Override + public void setI(double value) { + pidController.setI(value); + } + + @Override + public void setD(double value) { + pidController.setD(value); + } + + @Override + public void setFF(double value) { + pidController.setFF(value); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setSelectedFeedbsckSensor() is currently unsupported by LocalMotorController")); + } + + @Override + public void setSensorInverted(boolean inverted) { + this.sensorInverted = inverted; + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + pidController.setMaxoutputLow(minOutput); + pidController.setMaxoutputHigh(maxOutput); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setCurrentLimit() is currently unsupported by LocalMotorController")); + } + + @Override + public void restoreFactoryDefault() { + this.motor.restoreFactoryDefault(); + + this.setP(0.0); + this.setI(0.0); + this.setD(0.0); + this.setFF(0.0); + this.pidController.setMaxoutputLow(null); + this.pidController.setMaxoutputHigh(null); + + this.inverted = false; + this.sensorInverted = false; + this.controlMode = ControlMode.Disabled; + this.setpoint = 0.0; + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setOpenLoopRamp() is currently unsupported by LocalMotorController")); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setClosedLoopRamp() is currently unsupported by LocalMotorController")); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/MotorController.java b/src/main/java/com/team766/hal/MotorController.java new file mode 100755 index 00000000..80635f30 --- /dev/null +++ b/src/main/java/com/team766/hal/MotorController.java @@ -0,0 +1,138 @@ +package com.team766.hal; + +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; + +/** + * Interface for motor controlling devices. + */ + +public interface MotorController extends BasicMotorController { + + public enum Type { + VictorSP, + VictorSPX, + TalonSRX, + SparkMax, + TalonFX, + } + + public enum ControlMode { + PercentOutput, + Position, + Velocity, + Current, + Voltage, + Follower, + MotionProfile, + MotionMagic, + MotionProfileArc, + Disabled, + } + + /** + * Common interface for getting the current power output by a motor controller. + * + * @return The current set power. Value is between -1.0 and 1.0. + */ + double get(); + + + /** + * Common interface for setting the power outputu by a motor controller. + * + * @param power The power to set. Value should be between -1.0 and 1.0. + */ + void set(double power); + + /** + * Sets the appropriate output on the motor controller, depending on the mode. + * @param mode The output mode to apply. + * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. + * In Current mode, output value is in amperes. + * In Velocity mode, output value is in position change / 100ms. + * In Position mode, output value is in encoder ticks or an analog value, + * depending on the sensor. + * In Follower mode, the output value is the integer device ID of the talon to + * duplicate. + * + * @param value The setpoint value, as described above. + */ + void set(ControlMode mode, double value); + + /** + * Common interface for inverting direction of a motor controller. + * + * This changes the direction of the motor and sensor together. To change the + * direction of the sensor relative to the direction of the motor, + * use setSensorInverted. + * + * @param isInverted The state of inversion true is inverted. + */ + void setInverted(boolean isInverted); + + /** + * Common interface for returning if a motor controller is in the inverted + * state or not. + * + * @return isInverted The state of the inversion true is inverted. + */ + boolean getInverted(); + + /** + * Stops motor movement. Motor can be moved again by calling set without having + * to re-enable the motor. + */ + void stopMotor(); + + /** + * Read the motor position from the sensor attached to the motor controller. + */ + double getSensorPosition(); + + /** + * Read the motor velocity from the sensor attached to the motor controller. + */ + double getSensorVelocity(); + + /** + * Sets the motors encoder value to the given position. + * + * @param position The desired set position + */ + void setSensorPosition(double position); + + void follow(MotorController leader); + + void setNeutralMode(NeutralMode neutralMode); + + void setP(double value); + + void setI(double value); + + void setD(double value); + + void setFF(double value); + + void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice); + + /** + * Set whether to reverse the sensor relative to the direction of the motor. + * + * This is different from setInverted, which sets the direction of both the + * motor and sensor together. + * + * @param inverted The state of inversion true is inverted. + */ + void setSensorInverted(boolean inverted); + + void setOutputRange(double minOutput, double maxOutput); + + void setCurrentLimit(double ampsLimit); + + void restoreFactoryDefault(); + + void setOpenLoopRamp(double secondsFromNeutralToFull); + + void setClosedLoopRamp(double secondsFromNeutralToFull); +} diff --git a/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java b/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java new file mode 100644 index 00000000..76efb847 --- /dev/null +++ b/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java @@ -0,0 +1,13 @@ +package com.team766.hal; + +public class MotorControllerCommandFailedException extends RuntimeException { + + public MotorControllerCommandFailedException(String message) { + super(message); + } + + public MotorControllerCommandFailedException(String message, Throwable cause) { + super(message, cause); + } + +} diff --git a/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java b/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java new file mode 100644 index 00000000..50fb01dc --- /dev/null +++ b/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java @@ -0,0 +1,158 @@ +package com.team766.hal; + +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; + +public class MotorControllerWithSensorScale implements MotorController { + private MotorController delegate; + private double scale; + + public MotorControllerWithSensorScale(MotorController delegate, double scale) { + this.delegate = delegate; + this.scale = scale; + } + + @Override + public double getSensorPosition() { + return delegate.getSensorPosition() * scale; + } + + @Override + public double getSensorVelocity() { + return delegate.getSensorVelocity() * scale; + } + + @Override + public void set(ControlMode mode, double value) { + switch (mode) { + case PercentOutput: + delegate.set(mode, value); + return; + case Position: + delegate.set(mode, value / scale); + return; + case Velocity: + delegate.set(mode, value / scale); + return; + case Current: + delegate.set(mode, value); + return; + case Voltage: + delegate.set(mode, value); + case Follower: + delegate.set(mode, value); + return; + case MotionProfile: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case MotionMagic: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case MotionProfileArc: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case Disabled: + delegate.set(mode, value); + return; + } + throw new UnsupportedOperationException("Unimplemented control mode in MotorControllerWithSensorScale"); + } + + @Override + public void setInverted(boolean isInverted) { + delegate.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return delegate.getInverted(); + } + + @Override + public void stopMotor() { + delegate.stopMotor(); + } + + @Override + public void setSensorPosition(double position) { + delegate.setSensorPosition(position / scale); + } + + @Override + public void follow(MotorController leader) { + delegate.follow(leader); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + delegate.setNeutralMode(neutralMode); + } + + @Override + public void setP(double value) { + delegate.setP(value / scale); + } + + @Override + public void setI(double value) { + delegate.setI(value / scale); + } + + @Override + public void setD(double value) { + delegate.setD(value / scale); + } + + @Override + public void setFF(double value) { + delegate.setFF(value / scale); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + delegate.setSelectedFeedbackSensor(feedbackDevice); + } + + @Override + public void setSensorInverted(boolean inverted) { + delegate.setSensorInverted(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + delegate.setOutputRange(minOutput, maxOutput); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + delegate.setCurrentLimit(ampsLimit); + } + + @Override + public void restoreFactoryDefault() { + delegate.restoreFactoryDefault(); + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + delegate.setOpenLoopRamp(secondsFromNeutralToFull); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + delegate.setClosedLoopRamp(secondsFromNeutralToFull); + } + + @Override + public double get() { + return delegate.get(); + } + + @Override + public void set(double power) { + delegate.set(power); + } +} diff --git a/src/main/java/com/team766/hal/MultiSolenoid.java b/src/main/java/com/team766/hal/MultiSolenoid.java new file mode 100644 index 00000000..39a47aea --- /dev/null +++ b/src/main/java/com/team766/hal/MultiSolenoid.java @@ -0,0 +1,27 @@ +package com.team766.hal; + +public class MultiSolenoid implements SolenoidController { + + private SolenoidController[] solenoids; + private boolean state; + + public MultiSolenoid(SolenoidController... solenoids) { + this.solenoids = solenoids; + + set(false); + } + + @Override + public boolean get() { + return state; + } + + @Override + public void set(boolean on) { + state = on; + for (SolenoidController s : solenoids) { + s.set(on); + } + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/PositionReader.java b/src/main/java/com/team766/hal/PositionReader.java new file mode 100644 index 00000000..452c4579 --- /dev/null +++ b/src/main/java/com/team766/hal/PositionReader.java @@ -0,0 +1,24 @@ +package com.team766.hal; + +public interface PositionReader { + /** + * Return the position of the robot along the global X axis. + * + * @return the current position coordinate in meters + */ + public double getX(); + + /** + * Return the position of the robot along the global Y axis. + * + * @return the current position coordinate in meters + */ + public double getY(); + + /** + * Return the angle that the robot is currently facing. + * + * @return the current heading angle in degrees + */ + public double getHeading(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/RelayOutput.java b/src/main/java/com/team766/hal/RelayOutput.java new file mode 100755 index 00000000..e6e7bd96 --- /dev/null +++ b/src/main/java/com/team766/hal/RelayOutput.java @@ -0,0 +1,16 @@ +package com.team766.hal; + + +/** + * Interface for digital output devices + */ + +public interface RelayOutput { + + public void set(Value val); + + enum Value{ + kOff, kOn, kForward, kReverse + } + +} diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java new file mode 100755 index 00000000..40f3f218 --- /dev/null +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -0,0 +1,234 @@ +package com.team766.hal; + +import java.util.Arrays; +import java.util.HashMap; + +import com.team766.config.ConfigFileReader; +import com.team766.controllers.TimeProviderI; +import com.team766.hal.mock.MockAnalogInput; +import com.team766.hal.mock.MockDigitalInput; +import com.team766.hal.mock.MockEncoder; +import com.team766.hal.mock.MockGyro; +import com.team766.hal.mock.MockRelay; +import com.team766.hal.mock.MockMotorController; +import com.team766.library.ValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public abstract class RobotProvider { + + public static RobotProvider instance; + + protected EncoderReader[] encoders = new EncoderReader[20]; + protected SolenoidController[] solenoids = new SolenoidController[10]; + protected GyroReader[] gyros = new GyroReader[13]; + protected HashMap cams = new HashMap(); + protected JoystickReader[] joysticks = new JoystickReader[8]; + protected DigitalInputReader[] digInputs = new DigitalInputReader[8]; + protected AnalogInputReader[] angInputs = new AnalogInputReader[5]; + protected RelayOutput[] relays = new RelayOutput[5]; + protected PositionReader positionSensor = null; + + private HashMap motorDeviceIdNames = new HashMap(); + private HashMap motorPortNames = new HashMap(); + private HashMap digitalIoNames = new HashMap(); + private HashMap analogInputNames = new HashMap(); + private HashMap relayNames = new HashMap(); + private HashMap solenoidNames = new HashMap(); + private HashMap gyroNames = new HashMap(); + + //HAL + protected abstract MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor); + + public abstract EncoderReader getEncoder(int index1, int index2); + + public abstract DigitalInputReader getDigitalInput(int index); + + public abstract AnalogInputReader getAnalogInput(int index); + + public abstract RelayOutput getRelay(int index); + + public abstract SolenoidController getSolenoid(int index); + + public abstract GyroReader getGyro(int index); + + public abstract CameraReader getCamera(String id, String value); + + public abstract PositionReader getPositionSensor(); + + public static TimeProviderI getTimeProvider(){ + return () -> instance.getClock().getTime(); + } + + // Config-driven methods + + private void checkDeviceName(String deviceType, HashMap deviceNames, Integer portId, String configName) { + String previousName = deviceNames.putIfAbsent(portId, configName); + if (previousName != null && previousName != configName) { + Logger.get(Category.CONFIGURATION).logRaw( + Severity.ERROR, + "Multiple " + deviceType + " devices for port ID " + portId + ": " + previousName + ", " + configName); + } + } + + public MotorController getMotor(String configName) { + final String encoderConfigName = configName + ".encoder"; + final String analogInputConfigName = configName + ".analogInput"; + final ControlInputReader sensor = + ConfigFileReader.getInstance().containsKey(encoderConfigName) ? getEncoder(encoderConfigName) : + ConfigFileReader.getInstance().containsKey(analogInputConfigName) ? getAnalogInput(analogInputConfigName) : + null; + + try { + ValueProvider deviceId = ConfigFileReader.getInstance().getInt(configName + ".deviceId"); + final ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + final ValueProvider sensorScaleConfig = ConfigFileReader.getInstance().getDouble(configName + ".sensorScale"); + final ValueProvider invertedConfig = ConfigFileReader.getInstance().getBoolean(configName + ".inverted"); + final ValueProvider sensorInvertedConfig = ConfigFileReader.getInstance().getBoolean(configName + ".sensorInverted"); + final ValueProvider type = ConfigFileReader.getInstance().getEnum(MotorController.Type.class, configName + ".type"); + + if (deviceId.hasValue() && port.hasValue()) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s configuration should have only one of `deviceId` or `port`", configName); + } + + MotorController.Type defaultType = MotorController.Type.TalonSRX; + if (!deviceId.hasValue()) { + deviceId = port; + defaultType = MotorController.Type.VictorSP; + checkDeviceName("PWM motor controller", motorPortNames, port.get(), configName); + } else { + checkDeviceName("CAN motor controller", motorDeviceIdNames, deviceId.get(), configName); + } + + var motor = getMotor(deviceId.get(), configName, type.valueOr(defaultType), sensor); + if (sensorScaleConfig.hasValue()) { + motor = new MotorControllerWithSensorScale(motor, sensorScaleConfig.get()); + } + if (invertedConfig.valueOr(false)) { + motor.setInverted(true); + } + if (sensorInvertedConfig.valueOr(false)) { + motor.setSensorInverted(true); + } + return motor; + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s not found in config file, using mock motor instead", configName); + return new LocalMotorController(configName, new MockMotorController(0), sensor); + } + } + + public EncoderReader getEncoder(String configName) { + try { + final ValueProvider ports = ConfigFileReader.getInstance().getInts(configName + ".ports"); + final ValueProvider distancePerPulseConfig = ConfigFileReader.getInstance().getDouble(configName + ".distancePerPulse"); + + final var portsValue = ports.get(); + if (portsValue.length != 2) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Encoder %s has %d config values, but expected 2", configName, portsValue.length); + return new MockEncoder(0, 0); + } + checkDeviceName("encoder/digital input", digitalIoNames, portsValue[0], configName); + checkDeviceName("encoder/digital input", digitalIoNames, portsValue[1], configName); + final EncoderReader reader = getEncoder(portsValue[0], portsValue[1]); + if (distancePerPulseConfig.hasValue()) { + reader.setDistancePerPulse(distancePerPulseConfig.get()); + } + return reader; + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Encoder %s not found in config file, using mock encoder instead", configName); + return new MockEncoder(0, 0); + } + } + + public DigitalInputReader getDigitalInput(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("encoder/digital input", digitalIoNames, port.get(), configName); + + return getDigitalInput(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Digital input %s not found in config file, using mock digital input instead", configName); + return new MockDigitalInput(); + } + } + + public AnalogInputReader getAnalogInput(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("analog input", analogInputNames, port.get(), configName); + + return getAnalogInput(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Analog input %s not found in config file, using mock analog input instead", configName); + return new MockAnalogInput(); + } + } + + public RelayOutput getRelay(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("relay", relayNames, port.get(), configName); + + return getRelay(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Relay %s not found in config file, using mock relay instead", configName); + return new MockRelay(0); + } + } + + public DoubleSolenoid getSolenoid(String configName) { + try { + final String legacyConfigKey = configName + ".port"; + ValueProvider forwardPorts = + ConfigFileReader.getInstance().containsKey(legacyConfigKey) + ? ConfigFileReader.getInstance().getInts(legacyConfigKey) + : ConfigFileReader.getInstance().getInts(configName + ".forwardPort"); + ValueProvider reversePorts = + ConfigFileReader.getInstance().getInts(configName + ".reversePort"); + + for (Integer port : forwardPorts.valueOr(new Integer[0])) { + checkDeviceName("solenoid", solenoidNames, port, configName); + } + for (Integer port : reversePorts.valueOr(new Integer[0])) { + checkDeviceName("solenoid", solenoidNames, port, configName); + } + + SolenoidController forwardSolenoids = new MultiSolenoid( + Arrays.stream(forwardPorts.valueOr(new Integer[0])) + .map(this::getSolenoid) + .toArray(SolenoidController[]::new)); + SolenoidController reverseSolenoids = new MultiSolenoid( + Arrays.stream(reversePorts.valueOr(new Integer[0])) + .map(this::getSolenoid) + .toArray(SolenoidController[]::new)); + return new DoubleSolenoid(forwardSolenoids, reverseSolenoids); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Solenoid %s not found in config file, using mock solenoid instead", configName); + return new DoubleSolenoid(null, null); + } + } + + public GyroReader getGyro(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("gyro", gyroNames, port.get(), configName); + + return getGyro(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Gyro %s not found in config file, using mock gyro instead", configName); + return new MockGyro(); + } + } + + //Operator Devices + public abstract JoystickReader getJoystick(int index); + + public abstract CameraInterface getCamServer(); + + public abstract Clock getClock(); + + public abstract double getBatteryVoltage(); + + public abstract boolean hasNewDriverStationData(); +} diff --git a/src/main/java/com/team766/hal/SolenoidController.java b/src/main/java/com/team766/hal/SolenoidController.java new file mode 100755 index 00000000..8a6605c5 --- /dev/null +++ b/src/main/java/com/team766/hal/SolenoidController.java @@ -0,0 +1,19 @@ +package com.team766.hal; + +public interface SolenoidController { + + /** + * Set the value of a solenoid. + * + * @param on + * Turn the solenoid output off or on. + */ + public void set(boolean on); + + /** + * Read the current value of the solenoid. + * + * @return The current value of the solenoid. + */ + public boolean get(); +} diff --git a/src/main/java/com/team766/hal/VidSourceInterface.java b/src/main/java/com/team766/hal/VidSourceInterface.java new file mode 100755 index 00000000..22b9eef6 --- /dev/null +++ b/src/main/java/com/team766/hal/VidSourceInterface.java @@ -0,0 +1,5 @@ +package com.team766.hal; + +public interface VidSourceInterface { + public String getName(); +} diff --git a/src/main/java/com/team766/hal/mock/MockAnalogInput.java b/src/main/java/com/team766/hal/mock/MockAnalogInput.java new file mode 100755 index 00000000..fdeeccd4 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockAnalogInput.java @@ -0,0 +1,18 @@ +package com.team766.hal.mock; + +import com.team766.hal.AnalogInputReader; + +public class MockAnalogInput implements AnalogInputReader { + + private double sensor = 0.0; + + public void set(double value){ + sensor = value; + } + + @Override + public double getVoltage() { + return sensor; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockCamera.java b/src/main/java/com/team766/hal/mock/MockCamera.java new file mode 100755 index 00000000..125fbc3b --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockCamera.java @@ -0,0 +1,25 @@ +package com.team766.hal.mock; + +import org.opencv.core.Mat; +import org.opencv.imgcodecs.Imgcodecs; + +import com.team766.hal.CameraReader; + +public class MockCamera implements CameraReader{ + + private String nextImage; + + @Override + public Mat getImage() { + if(nextImage == null) { + return null; + } + + return Imgcodecs.imread(nextImage); + } + + public void setNextImage(String nextImage){ + this.nextImage = this.getClass().getClassLoader().getResource(nextImage).getPath(); + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockDigitalInput.java b/src/main/java/com/team766/hal/mock/MockDigitalInput.java new file mode 100755 index 00000000..e8cfe1f4 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockDigitalInput.java @@ -0,0 +1,17 @@ +package com.team766.hal.mock; + +import com.team766.hal.DigitalInputReader; + +public class MockDigitalInput implements DigitalInputReader{ + + private boolean sensor = false; + + public boolean get() { + return sensor; + } + + public void set(boolean on){ + sensor = on; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockEncoder.java b/src/main/java/com/team766/hal/mock/MockEncoder.java new file mode 100755 index 00000000..6eccab0d --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockEncoder.java @@ -0,0 +1,57 @@ +package com.team766.hal.mock; + +import com.team766.hal.EncoderReader; + +public class MockEncoder implements EncoderReader{ + + private double distance = 0; + private double rate = 0; + private double distancePerPulse = 1; + + public MockEncoder(int a, int b){ + } + + @Override + public int get() { + return (int)Math.round(distance / distancePerPulse); + } + + @Override + public void reset() { + distance = 0; + } + + @Override + public boolean getStopped() { + return this.rate == 0; + } + + @Override + public boolean getDirection() { + return this.rate > 0; + } + + @Override + public double getDistance() { + return this.distance; + } + + @Override + public double getRate() { + return this.rate; + } + + public void setDistance(double distance) { + this.distance = distance; + } + + public void setRate(double rate){ + this.rate = rate; + } + + @Override + public void setDistancePerPulse(double distancePerPulse) { + this.distancePerPulse = distancePerPulse; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockGyro.java b/src/main/java/com/team766/hal/mock/MockGyro.java new file mode 100755 index 00000000..32b8db2d --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockGyro.java @@ -0,0 +1,52 @@ +package com.team766.hal.mock; + +import com.team766.hal.GyroReader; + +public class MockGyro implements GyroReader{ + + private double angle = 0; + private double rate = 0; + private double pitch = 0; + private double roll = 0; + + public void calibrate() { + reset(); + } + + public void reset() { + angle = 0; + } + + public double getAngle() { + return angle; + } + + public double getRate() { + return rate; + } + + public double getPitch() { + return pitch; + } + + public double getRoll() { + return roll; + } + + public void setAngle(double angle) { + this.angle = angle; + } + + public void setRate(double rate) { + this.rate = rate; + } + + public void setPitch(double pitch) { + this.pitch = pitch; + } + + public void setRoll(double roll) { + this.roll = roll; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockJoystick.java b/src/main/java/com/team766/hal/mock/MockJoystick.java new file mode 100755 index 00000000..89c2fe70 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockJoystick.java @@ -0,0 +1,69 @@ +package com.team766.hal.mock; + +import com.team766.hal.JoystickReader; + +public class MockJoystick implements JoystickReader { + + private double[] axisValues; + private boolean[] buttonValues; + private boolean[] prevButtonValues; + private int povValue; + + public MockJoystick(){ + axisValues = new double[12]; + buttonValues = new boolean[20]; + prevButtonValues = new boolean[20]; + } + + @Override + public double getAxis(int axis) { + return axisValues[axis]; + } + + @Override + public boolean getButton(int button) { + // Button indexes begin at 1 in WPILib, so match that here + if (button <= 0) { + return false; + } + return buttonValues[button - 1]; + } + + public void setAxisValue(int axis, double value){ + axisValues[axis] = value; + } + + public void setButton(int button, boolean val){ + // Button indexes begin at 1 in WPILib, so match that here + prevButtonValues[button - 1] = buttonValues[button - 1]; + buttonValues[button - 1] = val; + } + + @Override + public int getPOV() { + return povValue; + } + + public void setPOV(int value) { + povValue = value; + } + + @Override + public boolean getButtonPressed(int button) { + // Button indexes begin at 1 in WPILib, so match that here + if (button <= 0) { + return false; + } + return buttonValues[button - 1] && !prevButtonValues[button - 1]; + } + + @Override + public boolean getButtonReleased(int button) { + // Button indexes begin at 1 in WPILib, so match that here + if (button <= 0) { + return false; + } + return !buttonValues[button - 1] && prevButtonValues[button - 1]; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockMotorController.java b/src/main/java/com/team766/hal/mock/MockMotorController.java new file mode 100755 index 00000000..d3115af9 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockMotorController.java @@ -0,0 +1,28 @@ +package com.team766.hal.mock; + +import com.team766.hal.BasicMotorController; + +public class MockMotorController implements BasicMotorController { + + private double output; + + public MockMotorController(int index) { + output = 0; + } + + @Override + public double get() { + return output; + } + + @Override + public void set(double power) { + output = power; + } + + @Override + public void restoreFactoryDefault() { + // No-op + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockPositionSensor.java b/src/main/java/com/team766/hal/mock/MockPositionSensor.java new file mode 100644 index 00000000..0501e345 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockPositionSensor.java @@ -0,0 +1,38 @@ +package com.team766.hal.mock; + +import com.team766.hal.PositionReader; + +public class MockPositionSensor implements PositionReader { + + private double x = 0; + private double y = 0; + private double heading = 0; + + @Override + public double getX() { + return x; + } + + @Override + public double getY() { + return y; + } + + @Override + public double getHeading() { + return heading; + } + + public void setX(double x) { + this.x = x; + } + + public void setY(double y) { + this.y = y; + } + + public void setHeading(double heading) { + this.heading = heading; + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/mock/MockRelay.java b/src/main/java/com/team766/hal/mock/MockRelay.java new file mode 100755 index 00000000..ab07476e --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockRelay.java @@ -0,0 +1,22 @@ +package com.team766.hal.mock; + +import com.team766.hal.RelayOutput; + +public class MockRelay implements RelayOutput{ + + private Value val; + + public MockRelay(int port){ + val = Value.kOff; + } + + @Override + public void set(Value out) { + val = out; + } + + public Value get(){ + return val; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockSolenoid.java b/src/main/java/com/team766/hal/mock/MockSolenoid.java new file mode 100755 index 00000000..7018330c --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockSolenoid.java @@ -0,0 +1,21 @@ +package com.team766.hal.mock; + +import com.team766.hal.SolenoidController; + +public class MockSolenoid implements SolenoidController{ + + private boolean pist; + + public MockSolenoid(int port){ + pist = false; + } + + public void set(boolean on) { + pist = on; + } + + public boolean get() { + return pist; + } + +} diff --git a/src/main/java/com/team766/hal/mock/TestRobotProvider.java b/src/main/java/com/team766/hal/mock/TestRobotProvider.java new file mode 100755 index 00000000..208cc991 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/TestRobotProvider.java @@ -0,0 +1,129 @@ +package com.team766.hal.mock; + +import com.team766.hal.AnalogInputReader; +import com.team766.hal.CameraInterface; +import com.team766.hal.CameraReader; +import com.team766.hal.Clock; +import com.team766.hal.ControlInputReader; +import com.team766.hal.DigitalInputReader; +import com.team766.hal.EncoderReader; +import com.team766.hal.GyroReader; +import com.team766.hal.JoystickReader; +import com.team766.hal.LocalMotorController; +import com.team766.hal.PositionReader; +import com.team766.hal.RelayOutput; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.MotorController; +import com.team766.hal.wpilib.SystemClock; + +public class TestRobotProvider extends RobotProvider{ + + private MotorController[] motors = new MotorController[64]; + private boolean m_hasDriverStationUpdate = false; + private double m_batteryVoltage = 12.0; + + @Override + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + if(motors[index] == null) { + motors[index] = new LocalMotorController( + configPrefix, + new MockMotorController(index), + localSensor != null ? localSensor : new MockEncoder(-1, -1)); + } + return motors[index]; + } + + @Override + public EncoderReader getEncoder(int index1, int index2) { + if(encoders[index1] == null) + encoders[index1] = new MockEncoder(index1, index2); + return encoders[index1]; + } + + @Override + public SolenoidController getSolenoid(int index) { + if(solenoids[index] == null) + solenoids[index] = new MockSolenoid(index); + return solenoids[index]; + } + + @Override + public GyroReader getGyro(int index) { + if(gyros[0] == null) + gyros[0] = new MockGyro(); + return gyros[0]; + } + + @Override + public CameraReader getCamera(String id, String value) { + if(!cams.containsKey(id)) + cams.put(id, new MockCamera()); + return cams.get(id); + } + + @Override + public JoystickReader getJoystick(int index) { + if(joysticks[index] == null) + joysticks[index] = new MockJoystick(); + return joysticks[index]; + } + + @Override + public DigitalInputReader getDigitalInput(int index) { + if(digInputs[index] == null) + digInputs[index] = new MockDigitalInput(); + return digInputs[index]; + } + + @Override + public CameraInterface getCamServer() { + return null; + } + + @Override + public AnalogInputReader getAnalogInput(int index) { + if(angInputs[index] == null) + angInputs[index] = new MockAnalogInput(); + return angInputs[index]; + } + + public RelayOutput getRelay(int index) { + if(relays[index] == null) + relays[index] = new MockRelay(index); + return relays[index]; + } + + @Override + public PositionReader getPositionSensor() { + if (positionSensor == null) + positionSensor = new MockPositionSensor(); + return positionSensor; + } + + @Override + public Clock getClock() { + // TODO Replace this with a controlled clock + return SystemClock.instance; + } + + @Override + public boolean hasNewDriverStationData() { + boolean result = m_hasDriverStationUpdate; + m_hasDriverStationUpdate = false; + return result; + } + + public void setHasNewDriverStationData() { + m_hasDriverStationUpdate = true; + } + + @Override + public double getBatteryVoltage() { + return m_batteryVoltage; + } + + public void setBatteryVoltage(double voltage) { + m_batteryVoltage = voltage; + } +} diff --git a/src/main/java/com/team766/hal/simulator/AnalogInput.java b/src/main/java/com/team766/hal/simulator/AnalogInput.java new file mode 100755 index 00000000..83e5766b --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/AnalogInput.java @@ -0,0 +1,19 @@ +package com.team766.hal.simulator; + +import com.team766.hal.AnalogInputReader; +import com.team766.simulator.ProgramInterface; + +public class AnalogInput implements AnalogInputReader{ + + private final int channel; + + public AnalogInput(int channel) { + this.channel = channel; + } + + @Override + public double getVoltage() { + return ProgramInterface.analogChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/Camera.java b/src/main/java/com/team766/hal/simulator/Camera.java new file mode 100755 index 00000000..7f6bb1e8 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Camera.java @@ -0,0 +1,14 @@ +package com.team766.hal.simulator; + +import org.opencv.core.Mat; + +import com.team766.hal.CameraReader; + +public class Camera implements CameraReader{ + + @Override + public Mat getImage() { + return null; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/DigitalInput.java b/src/main/java/com/team766/hal/simulator/DigitalInput.java new file mode 100755 index 00000000..7e3b3a17 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/DigitalInput.java @@ -0,0 +1,18 @@ +package com.team766.hal.simulator; + +import com.team766.hal.DigitalInputReader; +import com.team766.simulator.ProgramInterface; + +public class DigitalInput implements DigitalInputReader{ + + private final int channel; + + public DigitalInput(int channel) { + this.channel = channel; + } + + public boolean get() { + return ProgramInterface.digitalChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/Encoder.java b/src/main/java/com/team766/hal/simulator/Encoder.java new file mode 100755 index 00000000..092c3cb5 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Encoder.java @@ -0,0 +1,54 @@ +package com.team766.hal.simulator; + +import com.team766.hal.EncoderReader; +import com.team766.simulator.ProgramInterface; + +public class Encoder implements EncoderReader{ + + private final int channel; + private double distancePerPulse = 1.0; + + public Encoder(int a, int b){ + this.channel = a; + } + + @Override + public int get() { + return (int)ProgramInterface.encoderChannels[channel].distance; + } + + @Override + public void reset() { + set(0); + } + + @Override + public boolean getStopped() { + return getRate() == 0; + } + + @Override + public boolean getDirection() { + return getRate() > 0; + } + + @Override + public double getDistance() { + return get() * distancePerPulse; + } + + @Override + public double getRate() { + return ProgramInterface.encoderChannels[channel].rate * distancePerPulse; + } + + @Override + public void setDistancePerPulse(double distancePerPulse) { + this.distancePerPulse = distancePerPulse; + } + + public void set(int tick){ + ProgramInterface.encoderChannels[channel].distance = tick; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/Gyro.java b/src/main/java/com/team766/hal/simulator/Gyro.java new file mode 100755 index 00000000..124973d9 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Gyro.java @@ -0,0 +1,32 @@ +package com.team766.hal.simulator; + +import com.team766.hal.GyroReader; +import com.team766.simulator.ProgramInterface; + +public class Gyro implements GyroReader{ + + public void calibrate() { + reset(); + } + + public void reset() { + ProgramInterface.gyro.angle = 0; + } + + public double getAngle() { + return ProgramInterface.gyro.angle; + } + + public double getRate() { + return ProgramInterface.gyro.rate; + } + + public double getPitch() { + return ProgramInterface.gyro.pitch; + } + + public double getRoll() { + return ProgramInterface.gyro.roll; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/PositionSensor.java b/src/main/java/com/team766/hal/simulator/PositionSensor.java new file mode 100644 index 00000000..c8f9dd75 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/PositionSensor.java @@ -0,0 +1,23 @@ +package com.team766.hal.simulator; + +import com.team766.hal.PositionReader; +import com.team766.simulator.ProgramInterface; + +public class PositionSensor implements PositionReader { + + @Override + public double getX() { + return ProgramInterface.robotPosition.x; + } + + @Override + public double getY() { + return ProgramInterface.robotPosition.y; + } + + @Override + public double getHeading() { + return ProgramInterface.robotPosition.heading; + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/simulator/Relay.java b/src/main/java/com/team766/hal/simulator/Relay.java new file mode 100755 index 00000000..f8c0caa4 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Relay.java @@ -0,0 +1,32 @@ +package com.team766.hal.simulator; + +import com.team766.hal.RelayOutput; +import com.team766.simulator.ProgramInterface; + +public class Relay implements RelayOutput{ + + private int channel; + + public Relay(int channel){ + this.channel = channel; + } + + @Override + public void set(Value out) { + switch(out) { + case kForward: + ProgramInterface.relayChannels[channel] = 1; + break; + case kOff: + ProgramInterface.relayChannels[channel] = 0; + break; + case kOn: + ProgramInterface.relayChannels[channel] = 1; + break; + case kReverse: + ProgramInterface.relayChannels[channel] = -1; + break; + } + } + +} diff --git a/src/main/java/com/team766/hal/simulator/RobotMain.java b/src/main/java/com/team766/hal/simulator/RobotMain.java new file mode 100755 index 00000000..1a64e9e3 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/RobotMain.java @@ -0,0 +1,123 @@ +package com.team766.hal.simulator; + +import java.io.IOException; + +import com.team766.config.ConfigFileReader; +import com.team766.framework.Scheduler; +import com.team766.hal.GenericRobotMain; +import com.team766.hal.RobotProvider; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.simulator.Program; +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.Simulator; + +public class RobotMain { + static enum Mode { + MaroonSim, + VrConnector, + } + + private GenericRobotMain robot; + private Runnable simulator; + + public RobotMain(Mode mode) { + try { + // TODO: update this to come from deploy directory? + ConfigFileReader.instance = new ConfigFileReader("simConfig.txt"); + RobotProvider.instance = new SimulationRobotProvider(); + + Scheduler.getInstance().reset(); + + robot = new GenericRobotMain(); + + robot.robotInit(); + + ProgramInterface.program = new Program() { + ProgramInterface.RobotMode prevRobotMode = null; + + @Override + public void step() { + switch (ProgramInterface.robotMode) { + case DISABLED: + if (prevRobotMode != ProgramInterface.RobotMode.DISABLED) { + robot.disabledInit(); + prevRobotMode = ProgramInterface.RobotMode.DISABLED; + } + robot.disabledPeriodic(); + Scheduler.getInstance().run(); + break; + case AUTON: + if (prevRobotMode != ProgramInterface.RobotMode.AUTON) { + robot.autonomousInit(); + prevRobotMode = ProgramInterface.RobotMode.AUTON; + } + robot.autonomousPeriodic(); + Scheduler.getInstance().run(); + break; + case TELEOP: + if (prevRobotMode != ProgramInterface.RobotMode.TELEOP) { + robot.teleopInit(); + prevRobotMode = ProgramInterface.RobotMode.TELEOP; + } + robot.teleopPeriodic(); + Scheduler.getInstance().run(); + break; + } + } + + @Override + public void reset() { + robot.resetAutonomousMode("simulation reset"); + } + }; + } catch (Exception exc) { + exc.printStackTrace(); + LoggerExceptionUtils.logException(exc); + } + + switch (mode) { + case MaroonSim: + simulator = new Simulator(); + break; + case VrConnector: + ProgramInterface.robotMode = ProgramInterface.RobotMode.DISABLED; + try { + simulator = new VrConnector(); + } catch (IOException ex) { + throw new RuntimeException("Error initializing communication with 3d Simulator", ex); + } + break; + } + + } + + public void run(){ + try { + simulator.run(); + } catch (Exception exc) { + exc.printStackTrace(); + LoggerExceptionUtils.logException(exc); + } + } + + public static void main(String[] args) { + if (args.length != 1) { + System.err.println("Needs -maroon_sim or -vr_connector"); + System.exit(1); + } + Mode mode; + switch (args[0]) { + case "-maroon_sim": + mode = Mode.MaroonSim; + break; + case "-vr_connector": + mode = Mode.VrConnector; + break; + default: + System.err.println("Needs -maroon_sim or -vr_connector"); + System.exit(1); + return; + } + new RobotMain(mode).run(); + } +} diff --git a/src/main/java/com/team766/hal/simulator/SimMotorController.java b/src/main/java/com/team766/hal/simulator/SimMotorController.java new file mode 100755 index 00000000..4ca0fc8e --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/SimMotorController.java @@ -0,0 +1,54 @@ +package com.team766.hal.simulator; + +import com.team766.hal.ControlInputReader; +import com.team766.hal.BasicMotorController; +import com.team766.hal.LocalMotorController; +import com.team766.simulator.ProgramInterface; + +public class SimMotorController extends LocalMotorController { + public SimMotorController(String configPrefix, int address) { + this(configPrefix, ProgramInterface.canMotorControllerChannels[address]); + } + + SimMotorController(String configPrefix, ProgramInterface.CANMotorControllerCommunication channel) { + super(configPrefix, new SimBasicMotorController(channel), new ControlInputReader() { + @Override + public double getPosition() { + return channel.status.sensorPosition; + } + + @Override + public double getRate() { + return channel.status.sensorVelocity; + } + }); + } +} + +class SimBasicMotorController implements BasicMotorController { + private final ProgramInterface.CANMotorControllerCommunication channel; + + public SimBasicMotorController(int address) { + this(ProgramInterface.canMotorControllerChannels[address]); + } + + public SimBasicMotorController(ProgramInterface.CANMotorControllerCommunication channel) { + this.channel = channel; + } + + @Override + public double get() { + return channel.command.output; + } + + @Override + public void set(double power) { + power = Math.min(Math.max(-1, power), 1); + channel.command.output = power; + channel.command.controlMode = + ProgramInterface.CANMotorControllerCommand.ControlMode.PercentOutput; + } + + @Override + public void restoreFactoryDefault() {} +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/simulator/SimulationClock.java b/src/main/java/com/team766/hal/simulator/SimulationClock.java new file mode 100644 index 00000000..ffb9c4be --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/SimulationClock.java @@ -0,0 +1,15 @@ +package com.team766.hal.simulator; + +import com.team766.hal.Clock; +import com.team766.simulator.ProgramInterface; + +public class SimulationClock implements Clock { + + public static final SimulationClock instance = new SimulationClock(); + + @Override + public double getTime() { + return ProgramInterface.simulationTime; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java new file mode 100755 index 00000000..7972440a --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java @@ -0,0 +1,120 @@ +package com.team766.hal.simulator; + +import com.team766.hal.AnalogInputReader; +import com.team766.hal.CameraInterface; +import com.team766.hal.CameraReader; +import com.team766.hal.Clock; +import com.team766.hal.ControlInputReader; +import com.team766.hal.DigitalInputReader; +import com.team766.hal.EncoderReader; +import com.team766.hal.GyroReader; +import com.team766.hal.JoystickReader; +import com.team766.hal.LocalMotorController; +import com.team766.hal.PositionReader; +import com.team766.hal.RelayOutput; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.MotorController; +import com.team766.simulator.ProgramInterface; + +public class SimulationRobotProvider extends RobotProvider{ + + private MotorController[] motors = new MotorController[100]; + private int m_dsUpdateNumber = 0; + + @Override + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + if(motors[index] == null) { + if (localSensor != null) { + motors[index] = new LocalMotorController(configPrefix, new SimBasicMotorController(index), localSensor); + } else { + motors[index] = new SimMotorController(configPrefix, index); + } + } + return motors[index]; + } + + @Override + public EncoderReader getEncoder(int index1, int index2) { + if(encoders[index1] == null) + encoders[index1] = new Encoder(index1, index2); + return encoders[index1]; + } + + @Override + public SolenoidController getSolenoid(int index) { + if(solenoids[index] == null) + solenoids[index] = new Solenoid(index); + return solenoids[index]; + } + + @Override + public GyroReader getGyro(int index) { + if(gyros[0] == null) + gyros[0] = new Gyro(); + return gyros[0]; + } + + @Override + public CameraReader getCamera(String id, String value) { + if(!cams.containsKey(id)) + cams.put(id, new Camera()); + return cams.get(id); + } + + @Override + public JoystickReader getJoystick(int index) { + return ProgramInterface.joystickChannels[index]; + } + + @Override + public DigitalInputReader getDigitalInput(int index) { + if(digInputs[index] == null) + digInputs[index] = new DigitalInput(index); + return digInputs[index]; + } + + @Override + public CameraInterface getCamServer() { + return null; + } + + @Override + public AnalogInputReader getAnalogInput(int index) { + if(angInputs[index] == null) + angInputs[index] = new AnalogInput(index); + return angInputs[index]; + } + + public RelayOutput getRelay(int index) { + if(relays[index] == null) + relays[index] = new Relay(index); + return relays[index]; + } + + @Override + public PositionReader getPositionSensor() { + if (positionSensor == null) + positionSensor = new PositionSensor(); + return positionSensor; + } + + @Override + public Clock getClock() { + return SimulationClock.instance; + } + + @Override + public boolean hasNewDriverStationData() { + int newUpdateNumber = ProgramInterface.driverStationUpdateNumber; + boolean result = m_dsUpdateNumber != newUpdateNumber; + m_dsUpdateNumber = newUpdateNumber; + return result; + } + + @Override + public double getBatteryVoltage() { + // TODO: The simulator currently doesn't include a simulation of electrical load. + return 12.0; + } +} diff --git a/src/main/java/com/team766/hal/simulator/Solenoid.java b/src/main/java/com/team766/hal/simulator/Solenoid.java new file mode 100755 index 00000000..cdd2aec9 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Solenoid.java @@ -0,0 +1,22 @@ +package com.team766.hal.simulator; + +import com.team766.hal.SolenoidController; +import com.team766.simulator.ProgramInterface; + +public class Solenoid implements SolenoidController{ + + private int channel; + + public Solenoid(int channel){ + this.channel = channel; + } + + public void set(boolean on) { + ProgramInterface.solenoidChannels[channel] = on; + } + + public boolean get() { + return ProgramInterface.solenoidChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/VrConnector.java b/src/main/java/com/team766/hal/simulator/VrConnector.java new file mode 100644 index 00000000..25f6d5b0 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/VrConnector.java @@ -0,0 +1,339 @@ +package com.team766.hal.simulator; + +import static com.team766.math.Math.normalizeAngleDegrees; + +import java.io.IOException; +import java.net.InetAddress; +import java.net.InetSocketAddress; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.nio.channels.DatagramChannel; +import java.nio.channels.SelectionKey; +import java.nio.channels.Selector; +import java.util.Arrays; +import java.util.List; +import java.util.Map; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.simulator.ProgramInterface; + +public class VrConnector implements Runnable { + private static class PortMapping { + public final int messageDataIndex; + public final int robotPortIndex; + + public PortMapping(int messageIndex, int robotIndex) { + this.messageDataIndex = messageIndex; + this.robotPortIndex = robotIndex; + } + } + + private static class CANPortMapping { + public final int canId; + public final int motorCommandMessageDataIndex; + public final int sensorFeedbackMessageDataIndex; + + public CANPortMapping( + int canId, + int motorCommandMessageDataIndex, + int sensorFeedbackMessageDataIndex) { + this.canId = canId; + this.motorCommandMessageDataIndex = motorCommandMessageDataIndex; + this.sensorFeedbackMessageDataIndex = sensorFeedbackMessageDataIndex; + } + } + + /// Command indexes + + private static final int MAX_COMMANDS = 100; + + private static final int RESET_SIM_CHANNEL = 0; + + private static final List PWM_CHANNELS = Arrays.asList( + //new PortMapping(10, 6), // Left motor + //new PortMapping(11, 4), // Right motor + //new PortMapping(14, 1), // Auxiliary / Center motor + //new PortMapping(12, 0) // Intake + ); + private static final List SOLENOID_CHANNELS = Arrays.asList( + new PortMapping(15, 0), // Intake arm + new PortMapping(13, 1) // Catapult launch + ); + private static final List RELAY_CHANNELS = Arrays.asList(); + + private static final List CAN_MOTOR_CHANNELS = Arrays.asList( + new CANPortMapping(6, 10, 10), // Left motor + new CANPortMapping(4, 11, 11), // Right motor + new CANPortMapping(10, 12, 13), // Intake + new CANPortMapping(12, 14, 0), // Aux/center motor + new CANPortMapping(14, 16, 0), // Aux2 motor + + new CANPortMapping(84, 84, 84), // FLD motor + new CANPortMapping(85, 85, 85), // BLD motor + new CANPortMapping(86, 86, 86), // FRD motor + new CANPortMapping(87, 87, 87), // BRD motor + new CANPortMapping(88, 88, 88), // FLS motor + new CANPortMapping(89, 89, 89), // BLS motor + new CANPortMapping(90, 90, 90), // FRS motor + new CANPortMapping(91, 91, 91) // BRS motor + ); + + /// Feedback indexes + + private static final int TIMESTAMP_LSW_CHANNEL = 5; + private static final int TIMESTAMP_MSW_CHANNEL = 4; + + private static final int RESET_COUNTER_CHANNEL = 6; + + private static final int ROBOT_MODE_CHANNEL = 3; + private static final Map ROBOT_MODES = Map.of( + 0, ProgramInterface.RobotMode.DISABLED, + 1, ProgramInterface.RobotMode.AUTON, + 2, ProgramInterface.RobotMode.TELEOP + ); + + private static final int ROBOT_X_CHANNEL = 8; + private static final int ROBOT_Y_CHANNEL = 9; + + private static final List ENCODER_CHANNELS = Arrays.asList( + new PortMapping(10, 0), // Left encoder + new PortMapping(11, 2), // Right encoder + new PortMapping(13, 4) // Mechanism encoder + ); + private static final int GYRO_CHANNEL = 15; + private static final int GYRO_RATE_CHANNEL = 16; + private static final int GYRO_PITCH_CHANNEL = 80; + private static final int GYRO_ROLL_CHANNEL = 81; + private static final List DIGITAL_CHANNELS = Arrays.asList( + new PortMapping(13, 0), // Intake state + new PortMapping(14, 1), // Ball presence + new PortMapping(17, 4), // Line Sensor 1 + new PortMapping(18, 5), // Line Sensor 2 + new PortMapping(19, 6) // Line Sensor 3 + ); + private static final List ANALOG_CHANNELS = Arrays.asList(); + + private static final int NUM_JOYSTICK = 4; + private static final int BASE_AXIS_START = 20; + private static final int BASE_AXES_PER_JOYSTICK = 4; + private static final int ADDITIONAL_AXIS_START = 100; + private static final int ADDITIONAL_AXES_PER_JOYSTICK = 4; + private static final int JOYSTICK_BUTTON_START = 72; + private static final int BUTTONS_PER_JOYSTICK = 20; + + /// Socket Communication + + private static final int commandsPort = 7661; + private static final int feedbackPort = 7662; + private static final int BUF_SZ = 1024; + + private long startTime; + private boolean started = false; + + private Selector selector; + private InetSocketAddress sendAddr; + private ByteBuffer feedback = ByteBuffer.allocate(BUF_SZ); + private ByteBuffer commands = ByteBuffer.allocate(BUF_SZ); + private int resetCounter = 0; + + private int lastResetCounter = 0; + private double lastGyroValue = Double.NaN; + private long[] lastEncoderValue = new long[ProgramInterface.encoderChannels.length]; + private long[] lastCANSensorValue = new long[ProgramInterface.canMotorControllerChannels.length]; + + private int getFeedback(int index) { + return feedback.getInt(index * 4); + } + + private static long assembleLong(int msw, int lsw) { + return ((long)msw << 32) | (lsw & 0xffffffffL); + } + + private void putCommand(int index, int value) { + commands.putInt(index * 4, value); + } + + private void putCommandFloat(int index, double value) { + putCommand(index, (int) (value * 512.0)); + } + + private void putCommandTristate(int index, int value) { + if (value == 0) + putCommand(index, 0); + else if (value > 0) + putCommand(index, 511); + else + putCommand(index, -512); + } + + private void putCommandBool(int index, boolean value) { + putCommand(index, value ? 511 : -512); + } + + public VrConnector() throws IOException { + selector = Selector.open(); + DatagramChannel channel = DatagramChannel.open(); + InetSocketAddress receiveAddr = new InetSocketAddress(feedbackPort); + channel.bind(receiveAddr); + sendAddr = new InetSocketAddress(InetAddress.getLoopbackAddress(), commandsPort); + channel.configureBlocking(false); + channel.register(selector, SelectionKey.OP_READ); + commands.limit(MAX_COMMANDS * 4); + commands.order(ByteOrder.LITTLE_ENDIAN); + feedback.order(ByteOrder.LITTLE_ENDIAN); + startTime = System.currentTimeMillis(); + } + + private boolean process() throws IOException { + for (PortMapping m : PWM_CHANNELS) { + putCommandFloat(m.messageDataIndex, ProgramInterface.pwmChannels[m.robotPortIndex]); + } + for (PortMapping m : SOLENOID_CHANNELS) { + putCommandBool(m.messageDataIndex, ProgramInterface.solenoidChannels[m.robotPortIndex]); + } + for (PortMapping m : RELAY_CHANNELS) { + putCommandTristate(m.messageDataIndex, ProgramInterface.relayChannels[m.robotPortIndex]); + } + for (CANPortMapping m : CAN_MOTOR_CHANNELS) { + putCommandFloat( + m.motorCommandMessageDataIndex, + ProgramInterface.canMotorControllerChannels[m.canId].command.output); + } + + selector.selectedKeys().clear(); + selector.select(); + boolean newData = false; + for (SelectionKey key : selector.selectedKeys()) { + if (!key.isValid()) { + continue; + } + + DatagramChannel chan = (DatagramChannel) key.channel(); + if (key.isReadable()) { + feedback.clear(); + chan.receive(feedback); + newData = true; + key.interestOps(SelectionKey.OP_WRITE); + } + if (key.isWritable()) { + if (started) { + chan.send(commands.duplicate(), sendAddr); + putCommand(RESET_SIM_CHANNEL, 0); + } + key.interestOps(SelectionKey.OP_READ); + } + } + + if (newData) { + double prevSimTime = ProgramInterface.simulationTime; + // Time is sent in milliseconds + ProgramInterface.simulationTime = assembleLong( + getFeedback(TIMESTAMP_MSW_CHANNEL), getFeedback(TIMESTAMP_LSW_CHANNEL)) * 0.001; + + resetCounter = getFeedback(RESET_COUNTER_CHANNEL); + + ProgramInterface.robotMode = ROBOT_MODES.get(getFeedback(ROBOT_MODE_CHANNEL)); + + final double gyroValue = getFeedback(GYRO_CHANNEL) / 10.0; + if (Double.isNaN(lastGyroValue)) { + lastGyroValue = gyroValue; + } + ProgramInterface.gyro.angle += gyroValue - lastGyroValue; + lastGyroValue = gyroValue; + + ProgramInterface.robotPosition.x = getFeedback(ROBOT_X_CHANNEL) / 1000.0; + ProgramInterface.robotPosition.y = getFeedback(ROBOT_Y_CHANNEL) / 1000.0; + ProgramInterface.robotPosition.heading = gyroValue; + + ProgramInterface.gyro.rate = getFeedback(GYRO_RATE_CHANNEL) / 100.0; + ProgramInterface.gyro.pitch = normalizeAngleDegrees(getFeedback(GYRO_PITCH_CHANNEL) / 10.0); + ProgramInterface.gyro.roll = normalizeAngleDegrees(getFeedback(GYRO_ROLL_CHANNEL) / 10.0); + + for (PortMapping m : ENCODER_CHANNELS) { + final long value = getFeedback(m.messageDataIndex); + final long delta = value - lastEncoderValue[m.robotPortIndex]; + lastEncoderValue[m.robotPortIndex] = value; + + ProgramInterface.encoderChannels[m.robotPortIndex].distance += delta; + if (ProgramInterface.simulationTime > prevSimTime) { + ProgramInterface.encoderChannels[m.robotPortIndex].rate = delta / (ProgramInterface.simulationTime - prevSimTime); + } + } + for (CANPortMapping m : CAN_MOTOR_CHANNELS) { + var status = ProgramInterface.canMotorControllerChannels[m.canId].status; + + long value = getFeedback(m.sensorFeedbackMessageDataIndex); + long delta = value - lastCANSensorValue[m.canId]; + lastCANSensorValue[m.canId] = value; + + status.sensorPosition += delta; + if (ProgramInterface.simulationTime > prevSimTime) { + status.sensorVelocity = delta / (ProgramInterface.simulationTime - prevSimTime); + } + } + for (PortMapping m : DIGITAL_CHANNELS) { + ProgramInterface.digitalChannels[m.robotPortIndex] = getFeedback(m.messageDataIndex) > 0; + } + for (PortMapping m : ANALOG_CHANNELS) { + ProgramInterface.analogChannels[m.robotPortIndex] = getFeedback(m.messageDataIndex) * 5.0 / 1024.0; + } + for (int j = 0; j < NUM_JOYSTICK; ++j) { + for (int a = 0; a < BASE_AXES_PER_JOYSTICK; ++a) { + ProgramInterface.joystickChannels[j].setAxisValue(a, getFeedback(j * BASE_AXES_PER_JOYSTICK + a + BASE_AXIS_START) / 100.0); + } + for (int a = 0; a < ADDITIONAL_AXES_PER_JOYSTICK; ++a) { + ProgramInterface.joystickChannels[j].setAxisValue(a + BASE_AXES_PER_JOYSTICK, getFeedback(j * ADDITIONAL_AXES_PER_JOYSTICK + a + ADDITIONAL_AXIS_START) / 100.0); + } + int denseButtonState = getFeedback(j + JOYSTICK_BUTTON_START); + for (int b = 0; b < BUTTONS_PER_JOYSTICK; ++b) { + ProgramInterface.joystickChannels[j].setButton(b + 1, ((denseButtonState >> b) & 1) != 0); + } + } + + ++ProgramInterface.driverStationUpdateNumber; + } + + return newData; + } + + public void run() { + while (true) { + boolean newData = false; + try { + newData = process(); + } catch (Exception e) { + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + try { + Thread.sleep(10); + } catch (InterruptedException e1) {} + } + if (ProgramInterface.simulationTime == 0) { + // Wait for a connection to the simulator before starting to run the robot code. + startTime = System.currentTimeMillis(); + continue; + } + if (resetCounter != lastResetCounter) { + lastResetCounter = resetCounter; + ProgramInterface.program.reset(); + } + if (!newData) { + continue; + } + if (!started) { + // When the simulator has already been running, we seem to need to allow the socket + // service loop to run for a bit to allow buffers in the sockets that communicate + // with the simulator to flush, otherwise the messages queue up which results in a + // significant control latency. + if (System.currentTimeMillis() - startTime > 1000) { + System.out.println("Starting simulation"); + started = true; + } else { + continue; + } + } + if (ProgramInterface.program != null) { + ProgramInterface.program.step(); + } + } + } +} diff --git a/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java b/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java new file mode 100755 index 00000000..cf71649b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java @@ -0,0 +1,26 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.GyroReader; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; +import edu.wpi.first.wpilibj.SPI; + +public class ADXRS450_Gyro extends edu.wpi.first.wpilibj.ADXRS450_Gyro implements GyroReader { + public ADXRS450_Gyro(SPI.Port port) { + super(port); + if (!isConnected()) { + Logger.get(Category.HAL).logData(Severity.ERROR, "ADXRS450 Gyro is not connected!"); + } else { + Logger.get(Category.HAL).logData(Severity.INFO, "ADXRS450 Gyro is connected"); + } + } + + public double getPitch() { + return 0.0; + } + + public double getRoll() { + return 0.0; + } +} diff --git a/src/main/java/com/team766/hal/wpilib/AnalogGyro.java b/src/main/java/com/team766/hal/wpilib/AnalogGyro.java new file mode 100755 index 00000000..7417cf86 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/AnalogGyro.java @@ -0,0 +1,17 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.GyroReader; + +public class AnalogGyro extends edu.wpi.first.wpilibj.AnalogGyro implements GyroReader { + public AnalogGyro(int channel) { + super(channel); + } + + public double getPitch() { + return 0.0; + } + + public double getRoll() { + return 0.0; + } +} diff --git a/src/main/java/com/team766/hal/wpilib/AnalogInput.java b/src/main/java/com/team766/hal/wpilib/AnalogInput.java new file mode 100755 index 00000000..eca6ae4a --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/AnalogInput.java @@ -0,0 +1,9 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.AnalogInputReader; + +public class AnalogInput extends edu.wpi.first.wpilibj.AnalogInput implements AnalogInputReader { + public AnalogInput(int channel) { + super(channel); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java b/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java new file mode 100644 index 00000000..b33b2736 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java @@ -0,0 +1,30 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.ErrorCode; +import com.team766.hal.MotorControllerCommandFailedException; +import com.team766.logging.LoggerExceptionUtils; + +class BaseCTREMotorController { + + protected static final int TIMEOUT_MS = 20; + + protected static enum ExceptionTarget { + THROW, + LOG, + } + + protected static void errorCodeToException(ExceptionTarget throwEx, ErrorCode err) { + if (err == ErrorCode.OK) { + return; + } + var ex = new MotorControllerCommandFailedException(err.toString()); + switch (throwEx) { + case THROW: + throw ex; + case LOG: + LoggerExceptionUtils.logException(ex); + break; + } + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java new file mode 100644 index 00000000..4825f211 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java @@ -0,0 +1,232 @@ +package com.team766.hal.wpilib; + +import java.util.function.Function; +import java.util.function.Supplier; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.revrobotics.CANSparkMax; +import com.revrobotics.REVLibError; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.SparkMaxAnalogSensor; +import com.team766.hal.MotorController; +import com.team766.hal.MotorControllerCommandFailedException; +import com.team766.logging.LoggerExceptionUtils; + +public class CANSparkMaxMotorController extends CANSparkMax implements MotorController { + + private Supplier sensorPositionSupplier; + private Supplier sensorVelocitySupplier; + private Function sensorPositionSetter; + private Function sensorInvertedSetter; + private boolean sensorInverted = false; + + public CANSparkMaxMotorController(int deviceId) { + super(deviceId, MotorType.kBrushless); + + // Set default feedback device. This ensures that our implementations of + // getSensorPosition/getSensorVelocity return values that match what the + // device's PID controller is using. + setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + } + + private static enum ExceptionTarget { + THROW, + LOG, + } + + private static void revErrorToException(ExceptionTarget throwEx, REVLibError err) { + if (err == REVLibError.kOk) { + return; + } + var ex = new MotorControllerCommandFailedException(err.toString()); + switch (throwEx) { + case THROW: + throw ex; + case LOG: + LoggerExceptionUtils.logException(ex); + break; + } + } + + @Override + public double getSensorPosition() { + return sensorPositionSupplier.get(); + } + + @Override + public double getSensorVelocity() { + return sensorVelocitySupplier.get(); + } + + @Override + public void set(ControlMode mode, double value) { + switch (mode) { + case Current: + getPIDController().setReference(value, CANSparkMax.ControlType.kCurrent); + break; + case Disabled: + disable(); + break; + case Follower: + throw new IllegalArgumentException("Use follow() method instead"); + case MotionMagic: + throw new IllegalArgumentException("SparkMax does not support MotionMagic"); + case MotionProfile: + throw new IllegalArgumentException("SparkMax does not support MotionProfile"); + case MotionProfileArc: + throw new IllegalArgumentException("SparkMax does not support MotionProfileArc"); + case PercentOutput: + getPIDController().setReference(value, CANSparkMax.ControlType.kDutyCycle); + break; + case Position: + getPIDController().setReference(value, CANSparkMax.ControlType.kPosition); + break; + case Velocity: + getPIDController().setReference(value, CANSparkMax.ControlType.kVelocity); + break; + case Voltage: + getPIDController().setReference(value, CANSparkMax.ControlType.kVoltage); + default: + throw new IllegalArgumentException("Unsupported control mode " + mode); + } + } + + @Override + public void setSensorPosition(double position) { + revErrorToException(ExceptionTarget.THROW, sensorPositionSetter.apply(position)); + } + + @Override + public void follow(MotorController leader) { + try { + revErrorToException(ExceptionTarget.LOG, super.follow((CANSparkMax)leader)); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Spark Max can only follow another Spark Max", ex)); + } + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + switch (neutralMode) { + case Brake: + revErrorToException(ExceptionTarget.LOG, setIdleMode(IdleMode.kBrake)); + case Coast: + revErrorToException(ExceptionTarget.LOG, setIdleMode(IdleMode.kCoast)); + default: + LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported neutral mode " + neutralMode)); + } + } + + @Override + public void setP(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setP(value)); + } + + @Override + public void setI(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setI(value)); + } + + @Override + public void setD(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setD(value)); + } + + @Override + public void setFF(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setFF(value)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + switch (feedbackDevice) { + case Analog: { + SparkMaxAnalogSensor analog = getAnalog(SparkMaxAnalogSensor.Mode.kAbsolute); + revErrorToException(ExceptionTarget.LOG, analog.setInverted(sensorInverted)); + sensorPositionSupplier = analog::getPosition; + sensorVelocitySupplier = analog::getVelocity; + sensorPositionSetter = (pos) -> REVLibError.kOk; + sensorInvertedSetter = analog::setInverted; + revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(analog)); + return; + } + case CTRE_MagEncoder_Absolute: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); + case CTRE_MagEncoder_Relative: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); + case IntegratedSensor: { + RelativeEncoder encoder = getEncoder(); + // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the integrated sensor returns an error. + // revErrorToException(ExceptionTarget.LOG, encoder.setInverted(sensorInverted)); + sensorPositionSupplier = encoder::getPosition; + sensorVelocitySupplier = encoder::getVelocity; + sensorPositionSetter = encoder::setPosition; + // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the integrated sensor returns an error. + // sensorInvertedSetter = encoder::setInverted; + sensorInvertedSetter = (inverted) -> REVLibError.kOk; + revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(encoder)); + return; + } + case None: + return; + case PulseWidthEncodedPosition: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support PWM sensors")); + case QuadEncoder: { + // TODO: should we pass a real counts-per-rev scale here? + RelativeEncoder encoder = getAlternateEncoder(1); + revErrorToException(ExceptionTarget.LOG, encoder.setInverted(sensorInverted)); + sensorPositionSupplier = encoder::getPosition; + sensorVelocitySupplier = encoder::getVelocity; + sensorPositionSetter = encoder::setPosition; + sensorInvertedSetter = encoder::setInverted; + revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(encoder)); + return; + } + case RemoteSensor0: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support remote sensors")); + case RemoteSensor1: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support remote sensors")); + case SensorDifference: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SensorDifference")); + case SensorSum: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SensorSum")); + case SoftwareEmulatedSensor: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SoftwareEmulatedSensor")); + case Tachometer: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support Tachometer")); + default: + LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported sensor type " + feedbackDevice)); + } + } + + @Override + public void setSensorInverted(boolean inverted) { + sensorInverted = inverted; + revErrorToException(ExceptionTarget.LOG, sensorInvertedSetter.apply(inverted)); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setOutputRange(minOutput, maxOutput)); + } + + public void setCurrentLimit(double ampsLimit) { + revErrorToException(ExceptionTarget.LOG, setSmartCurrentLimit((int)ampsLimit)); + } + + @Override + public void restoreFactoryDefault() { + revErrorToException(ExceptionTarget.LOG, restoreFactoryDefaults()); + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + revErrorToException(ExceptionTarget.LOG, setOpenLoopRampRate(secondsFromNeutralToFull)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + revErrorToException(ExceptionTarget.LOG, setClosedLoopRampRate(secondsFromNeutralToFull)); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java new file mode 100644 index 00000000..ec30728a --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java @@ -0,0 +1,190 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.IMotorController; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class CANTalonFxMotorController extends BaseCTREMotorController implements MotorController { + + private WPI_TalonFX m_device; + private double m_feedForward = 0.0; + + public CANTalonFxMotorController(int deviceNumber) { + m_device = new WPI_TalonFX(deviceNumber); + } + + @Override + public void set(ControlMode mode, double value) { + com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; + boolean useFourTermSet = true; + switch (mode) { + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + } + if (ctre_mode == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "CAN ControlMode is not translatable: " + mode); + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + } + if (useFourTermSet) { + m_device.set(ctre_mode, value, DemandType.ArbitraryFeedForward, m_feedForward); + } else { + m_device.set(ctre_mode, value); + } + } + + @Override + public void stopMotor() { + m_device.set(com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput, 0); + } + + @Override + public double getSensorPosition() { + return m_device.getSelectedSensorPosition(0); + } + + @Override + public double getSensorVelocity() { + // Sensor velocity is returned in units per 100ms. + return m_device.getSelectedSensorVelocity(0) * 10.0; + } + + @Override + public void setSensorPosition(double position){ + errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 0)); + } + + @Override + public void follow(MotorController leader) { + try { + m_device.follow((IMotorController)leader); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Talon can only follow another CTRE motor controller", ex)); + } + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setFF(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); + } + + @Override + public void setP(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value)); + } + + @Override + public void setI(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value)); + } + + @Override + public void setD(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + } + + @Override + public void setSensorInverted(boolean inverted) { + m_device.setSensorPhase(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSupplyCurrentLimit( + new SupplyCurrentLimitConfiguration(true, ampsLimit, 0, 0.01))); + } + + @Override + public void restoreFactoryDefault() { + errorCodeToException(ExceptionTarget.LOG, m_device.configFactoryDefault()); + } + + @Override + public double get() { + return m_device.get(); + } + + @Override + public void set(double power) { + m_device.set(power); + } + + @Override + public void setInverted(boolean isInverted) { + m_device.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return m_device.getInverted(); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + m_device.setNeutralMode(neutralMode); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java new file mode 100644 index 00000000..7eae784b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java @@ -0,0 +1,191 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.IMotorController; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class CANTalonMotorController extends BaseCTREMotorController implements MotorController { + + private WPI_TalonSRX m_device; + private double m_feedForward = 0.0; + + public CANTalonMotorController(int deviceNumber) { + m_device = new WPI_TalonSRX(deviceNumber); + } + + @Override + public void set(ControlMode mode, double value) { + com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; + boolean useFourTermSet = true; + switch (mode) { + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + } + if (ctre_mode == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "CAN ControlMode is not translatable: " + mode); + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + } + if (useFourTermSet) { + m_device.set(ctre_mode, value, DemandType.ArbitraryFeedForward, m_feedForward); + } else { + m_device.set(ctre_mode, value); + } + } + + @Override + public void stopMotor() { + m_device.set(com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput, 0); + } + + @Override + public double getSensorPosition() { + return m_device.getSelectedSensorPosition(0); + } + + @Override + public double getSensorVelocity() { + // Sensor velocity is returned in units per 100ms. + return m_device.getSelectedSensorVelocity(0) * 10.0; + } + + @Override + public void setSensorPosition(double position){ + errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 0)); + } + + @Override + public void follow(MotorController leader) { + try { + m_device.follow((IMotorController)leader); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Talon can only follow another CTRE motor controller", ex)); + } + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setFF(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); + } + + @Override + public void setP(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value)); + } + + @Override + public void setI(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value)); + } + + @Override + public void setD(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + } + + @Override + public void setSensorInverted(boolean inverted) { + m_device.setSensorPhase(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakCurrentLimit(0)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakCurrentDuration(10)); + errorCodeToException(ExceptionTarget.LOG, m_device.configContinuousCurrentLimit((int)ampsLimit)); + m_device.enableCurrentLimit(true); + } + + @Override + public void restoreFactoryDefault() { + errorCodeToException(ExceptionTarget.LOG, m_device.configFactoryDefault()); + } + + @Override + public double get() { + return m_device.get(); + } + + @Override + public void set(double power) { + m_device.set(power); + } + + @Override + public void setInverted(boolean isInverted) { + m_device.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return m_device.getInverted(); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + m_device.setNeutralMode(neutralMode); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java b/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java new file mode 100644 index 00000000..1dffa99b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java @@ -0,0 +1,188 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.IMotorController; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class CANVictorMotorController extends BaseCTREMotorController implements MotorController { + + private WPI_VictorSPX m_device; + private double m_feedForward = 0.0; + + public CANVictorMotorController(int deviceNumber) { + m_device = new WPI_VictorSPX(deviceNumber); + } + + @Override + public void set(ControlMode mode, double value) { + com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; + boolean useFourTermSet = true; + switch (mode) { + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + } + if (ctre_mode == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "CAN ControlMode is not translatable: " + mode); + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + } + if (useFourTermSet) { + m_device.set(ctre_mode, value, DemandType.ArbitraryFeedForward, m_feedForward); + } else { + m_device.set(ctre_mode, value); + } + } + + @Override + public void stopMotor() { + m_device.set(com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput, 0); + } + + @Override + public double getSensorPosition() { + return m_device.getSelectedSensorPosition(0); + } + + @Override + public double getSensorVelocity() { + // Sensor velocity is returned in units per 100ms. + return m_device.getSelectedSensorVelocity(0) * 10.0; + } + + @Override + public void setSensorPosition(double position){ + errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 20)); + } + + @Override + public void follow(MotorController leader) { + try { + m_device.follow((IMotorController)leader); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Victor can only follow another CTRE motor controller", ex)); + } + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setFF(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); + } + + @Override + public double get() { + return m_device.get(); + } + + @Override + public void set(double power) { + m_device.set(power); + } + + @Override + public void setInverted(boolean isInverted) { + m_device.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return m_device.getInverted(); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + m_device.setNeutralMode(neutralMode); + } + + @Override + public void setP(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value, TIMEOUT_MS)); + } + + @Override + public void setI(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value, TIMEOUT_MS)); + } + + @Override + public void setD(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value, TIMEOUT_MS)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + } + + @Override + public void setSensorInverted(boolean inverted) { + m_device.setSensorPhase(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + LoggerExceptionUtils.logException( + new UnsupportedOperationException("VictorSPX does not support current limiting")); + } + + @Override + public void restoreFactoryDefault() { + errorCodeToException(ExceptionTarget.LOG, m_device.configFactoryDefault()); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/wpilib/CameraInterface.java b/src/main/java/com/team766/hal/wpilib/CameraInterface.java new file mode 100755 index 00000000..4f5122c5 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CameraInterface.java @@ -0,0 +1,39 @@ +package com.team766.hal.wpilib; + +import edu.wpi.first.cscore.CvSource; +import edu.wpi.first.cscore.VideoSource; +import edu.wpi.first.cameraserver.CameraServer; + +import org.opencv.core.Mat; + +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public class CameraInterface implements com.team766.hal.CameraInterface { + + private CvSource vidSource; + + @Override + public void startAutomaticCapture() { + try{ + CameraServer.startAutomaticCapture(VideoSource.enumerateSources()[0]); + } catch(Exception e){ + Logger.get(Category.CAMERA).logRaw(Severity.ERROR, e.toString()); + } + } + + @Override + public void getFrame(Mat img) { + CameraServer.getVideo().grabFrame(img); + } + + @Override + public void putFrame(Mat img){ + if(vidSource == null){ + vidSource = CameraServer.putVideo("VisionTracking", img.width(), img.height()); + } + + vidSource.putFrame(img); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/DigitalInput.java b/src/main/java/com/team766/hal/wpilib/DigitalInput.java new file mode 100755 index 00000000..d9abc338 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/DigitalInput.java @@ -0,0 +1,9 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.DigitalInputReader; + +public class DigitalInput extends edu.wpi.first.wpilibj.DigitalInput implements DigitalInputReader { + public DigitalInput(int channel) { + super(channel); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Encoder.java b/src/main/java/com/team766/hal/wpilib/Encoder.java new file mode 100755 index 00000000..509ddee2 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Encoder.java @@ -0,0 +1,9 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.EncoderReader; + +public class Encoder extends edu.wpi.first.wpilibj.Encoder implements EncoderReader { + public Encoder(int channelA, int channelB) { + super(channelA, channelB); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Joystick.java b/src/main/java/com/team766/hal/wpilib/Joystick.java new file mode 100755 index 00000000..b5a267f2 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Joystick.java @@ -0,0 +1,29 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.JoystickReader; + +public class Joystick extends edu.wpi.first.wpilibj.Joystick implements JoystickReader { + public Joystick(int port) { + super(port); + } + + @Override + public double getAxis(int axis) { + return getRawAxis(axis); + } + + @Override + public boolean getButton(int button) { + return getRawButton(button); + } + + @Override + public boolean getButtonPressed(int button) { + return getRawButtonPressed(button); + } + + @Override + public boolean getButtonReleased(int button) { + return getRawButtonReleased(button); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/NavXGyro.java b/src/main/java/com/team766/hal/wpilib/NavXGyro.java new file mode 100644 index 00000000..65430501 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/NavXGyro.java @@ -0,0 +1,55 @@ +package com.team766.hal.wpilib; + +import com.kauailabs.navx.frc.AHRS; +import com.team766.hal.GyroReader; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; +import edu.wpi.first.wpilibj.I2C; + +public class NavXGyro implements GyroReader { + private AHRS m_gyro; + + public NavXGyro(I2C.Port port) { + m_gyro = new AHRS(port); + // NOTE: It takes a bit of time until the gyro reader thread updates + // the connected status, so we can't check it immediately. + // TODO: Replace this with a status indicator + /*if (!m_gyro.isConnected()) { + Logger.get(Category.HAL).logData(Severity.ERROR, "NavX Gyro is not connected!"); + } else { + Logger.get(Category.HAL).logData(Severity.INFO, "NavX Gyro is connected"); + }*/ + } + + @Override + public void calibrate() { + m_gyro.calibrate(); + } + + @Override + public void reset() { + m_gyro.reset(); + } + + @Override + public double getAngle() { + return m_gyro.getAngle(); + } + + @Override + public double getRate() { + return m_gyro.getRate(); + } + + @Override + public double getPitch() { + return m_gyro.getPitch(); + } + + @Override + public double getRoll() { + return m_gyro.getRoll(); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java b/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java new file mode 100755 index 00000000..553cf741 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java @@ -0,0 +1,16 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.BasicMotorController; + +import edu.wpi.first.wpilibj.motorcontrol.VictorSP; + +public class PWMVictorSP extends VictorSP implements BasicMotorController { + public PWMVictorSP(int channel) { + super(channel); + } + + @Override + public void restoreFactoryDefault() { + // No-op + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Relay.java b/src/main/java/com/team766/hal/wpilib/Relay.java new file mode 100755 index 00000000..7b9fbeec --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Relay.java @@ -0,0 +1,38 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.RelayOutput; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public class Relay extends edu.wpi.first.wpilibj.Relay implements RelayOutput { + public Relay(int channel) { + super(channel); + } + + @Override + public void set(com.team766.hal.RelayOutput.Value value) { + edu.wpi.first.wpilibj.Relay.Value wpi_value = null; + switch (value) { + case kOff: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOff; + break; + case kOn: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOn; + break; + case kForward: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kForward; + break; + case kReverse: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kReverse; + break; + } + if (wpi_value == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "Relay value is not translatable: " + value); + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOff; + } + super.set(wpi_value); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/RobotMain.java b/src/main/java/com/team766/hal/wpilib/RobotMain.java new file mode 100755 index 00000000..1459ba6b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/RobotMain.java @@ -0,0 +1,151 @@ +package com.team766.hal.wpilib; + +import java.io.File; +import java.nio.file.Files; +import java.nio.file.Path; +import java.util.function.Supplier; +import com.team766.config.ConfigFileReader; +import com.team766.framework.Scheduler; +import com.team766.hal.GenericRobotMain; +import com.team766.hal.RobotProvider; +import com.team766.logging.LoggerExceptionUtils; +import edu.wpi.first.wpilibj.Filesystem; +import edu.wpi.first.wpilibj.RobotBase; +import edu.wpi.first.wpilibj.TimedRobot; + +public class RobotMain extends TimedRobot { + // this file, if present, will be a symlink to one of several config files in the deploy directory. + // this allows for the same code to be deployed to multiple physical robots, each with their own + // config file with CAN bus port mappings, etc, with the actual file used for a specific robot + // to be "selected" via this symlink to the actual file. + private final static String SELECTED_CONFIG_FILE = "/home/lvuser/selectedConfig.txt"; + + // if the symlink (above) is not present, back off to this file in the deploy directory. + private final static String DEFAULT_CONFIG_FILE = "configs/defaultRobotConfig.txt"; + + // for backwards compatibility, back off to the previous config file location if the above are not + // found in the deploy directory. + private final static String LEGACY_CONFIG_FILE = "/home/lvuser/robotConfig.txt"; + + private GenericRobotMain robot; + + public static void main(String... args) { + Supplier supplier = new Supplier() { + RobotMain instance; + @Override + public RobotMain get() { + if (instance == null) { + instance = new RobotMain(); + } + return instance; + } + }; + try { + RobotBase.startRobot(supplier); + } catch (Throwable ex) { + ex.printStackTrace(); + LoggerExceptionUtils.logException(ex); + } + } + + public RobotMain() { + super(0.005); + } + + private static String checkForAndReturnPathToConfigFile(String file) { + Path configPath = Filesystem.getDeployDirectory().toPath().resolve(file); + File configFile = configPath.toFile(); + if (configFile.exists()) { + return configFile.getPath(); + } + return null; + } + + @Override + public void robotInit() { + try { + String filename = null; + filename = checkForAndReturnPathToConfigFile(SELECTED_CONFIG_FILE); + + if (filename == null) { + filename = checkForAndReturnPathToConfigFile(DEFAULT_CONFIG_FILE); + } + + if (filename == null) { + filename = LEGACY_CONFIG_FILE; + } + + ConfigFileReader.instance = new ConfigFileReader(filename); + RobotProvider.instance = new WPIRobotProvider(); + robot = new GenericRobotMain(); + + robot.robotInit(); + } catch (Exception e) { + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void disabledInit() { + try{ + robot.disabledInit(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void autonomousInit() { + try{ + robot.autonomousInit(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void teleopInit() { + try{ + robot.teleopInit(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void disabledPeriodic() { + try{ + robot.disabledPeriodic(); + Scheduler.getInstance().run(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void autonomousPeriodic() { + try{ + robot.autonomousPeriodic(); + Scheduler.getInstance().run(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void teleopPeriodic() { + try{ + robot.teleopPeriodic(); + Scheduler.getInstance().run(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Solenoid.java b/src/main/java/com/team766/hal/wpilib/Solenoid.java new file mode 100755 index 00000000..e72f4694 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Solenoid.java @@ -0,0 +1,11 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.SolenoidController; + +import edu.wpi.first.wpilibj.PneumaticsModuleType; + +public class Solenoid extends edu.wpi.first.wpilibj.Solenoid implements SolenoidController { + public Solenoid(int channel) { + super(PneumaticsModuleType.CTREPCM, channel); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/SystemClock.java b/src/main/java/com/team766/hal/wpilib/SystemClock.java new file mode 100644 index 00000000..de5c9d4f --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/SystemClock.java @@ -0,0 +1,12 @@ +package com.team766.hal.wpilib; + +public class SystemClock implements com.team766.hal.Clock { + + public static final SystemClock instance = new SystemClock(); + + @Override + public double getTime() { + return System.currentTimeMillis() * 0.001; + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java new file mode 100755 index 00000000..4b8a7301 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -0,0 +1,184 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.AnalogInputReader; +import com.team766.hal.CameraInterface; +import com.team766.hal.CameraReader; +import com.team766.hal.Clock; +import com.team766.hal.ControlInputReader; +import com.team766.hal.DigitalInputReader; +import com.team766.hal.EncoderReader; +import com.team766.hal.GyroReader; +import com.team766.hal.JoystickReader; +import com.team766.hal.LocalMotorController; +import com.team766.hal.PositionReader; +import com.team766.hal.RelayOutput; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.MotorController; +import com.team766.hal.mock.MockGyro; +import com.team766.hal.mock.MockPositionSensor; +import com.team766.hal.mock.MockMotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.PneumaticsControlModule; +import edu.wpi.first.wpilibj.RobotController; +import edu.wpi.first.wpilibj.SPI; + +public class WPIRobotProvider extends RobotProvider { + + private MotorController[][] motors = new MotorController[MotorController.Type.values().length][64]; + + // The presence of this object allows the compressor to run before we've declared any solenoids. + @SuppressWarnings("unused") + private PneumaticsControlModule pcm = new PneumaticsControlModule(); + + @Override + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + if (motors[type.ordinal()][index] != null) { + return motors[type.ordinal()][index]; + } + MotorController motor = null; + switch (type) { + case SparkMax: + try { + motor = new CANSparkMaxMotorController(index); + } catch (Exception ex) { + LoggerExceptionUtils.logException(ex); + motor = new LocalMotorController(configPrefix, new MockMotorController(index), localSensor); + localSensor = null; + } + break; + case TalonSRX: + motor = new CANTalonMotorController(index); + break; + case VictorSPX: + motor = new CANVictorMotorController(index); + break; + case TalonFX: + motor = new CANTalonFxMotorController(index); + break; + case VictorSP: + motor = new LocalMotorController(configPrefix, new PWMVictorSP(index), localSensor); + localSensor = null; + break; + } + if (motor == null) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported motor type " + type)); + motor = new LocalMotorController(configPrefix, new MockMotorController(index), localSensor); + localSensor = null; + } + if (localSensor != null) { + motor = new LocalMotorController(configPrefix, motor, localSensor); + } + motors[type.ordinal()][index] = motor; + return motor; + } + + @Override + public EncoderReader getEncoder(int index1, int index2) { + if(encoders[index1] == null) + encoders[index1] = new Encoder(index1, index2); + return encoders[index1]; + } + + @Override + public SolenoidController getSolenoid(int index) { + if(solenoids[index] == null) + solenoids[index] = new Solenoid(index); + return solenoids[index]; + } + + @Override + //Gyro index values: + // -1 = Spartan Gyro + // 0+ = Analog Gyro on port index + public GyroReader getGyro(int index) { + if(gyros[index + 2] == null){ + if(index < -2) { + Logger.get(Category.CONFIGURATION).logRaw( + Severity.ERROR, + "Invalid gyro port " + index + ". Must be -2, -1, or a non-negative integer" + ); + return new MockGyro(); + } + else if(index == -2) + gyros[index + 2] = new NavXGyro(I2C.Port.kOnboard); + else if(index == -1) + gyros[index + 2] = new ADXRS450_Gyro(SPI.Port.kOnboardCS0); + else + gyros[index + 2] = new AnalogGyro(index); + } + return gyros[index + 2]; + } + + @Override + public CameraReader getCamera(String id, String value) { + System.err.println("Camera support not yet avaible"); + return null; + } + + @Override + public JoystickReader getJoystick(int index) { + if(joysticks[index] == null) + joysticks[index] = new Joystick(index); + return joysticks[index]; + } + + @Override + public CameraInterface getCamServer(){ + return new com.team766.hal.wpilib.CameraInterface(); + } + + @Override + public DigitalInputReader getDigitalInput(int index) { + if (digInputs[index] == null) + digInputs[index] = new DigitalInput(index); + return digInputs[index]; + } + + @Override + public AnalogInputReader getAnalogInput(int index){ + if(angInputs[index] == null) + angInputs[index] = new AnalogInput(index); + return angInputs[index]; + } + + @Override + public RelayOutput getRelay(int index) { + if(relays[index] == null) + relays[index] = new Relay(index); + return relays[index]; + } + + @Override + public PositionReader getPositionSensor() { + if (positionSensor == null) { + positionSensor = new MockPositionSensor(); + Logger.get(Category.CONFIGURATION).logRaw( + Severity.ERROR, + "Position sensor does not exist on real robots. Using mock position sensor instead - it will always return a position of 0" + ); + } + return positionSensor; + } + + @Override + public Clock getClock() { + return SystemClock.instance; + } + + @Override + public boolean hasNewDriverStationData() { + return DriverStation.isNewControlData(); + } + + @Override + public double getBatteryVoltage() { + return RobotController.getBatteryVoltage(); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/library/CircularBuffer.java b/src/main/java/com/team766/library/CircularBuffer.java new file mode 100644 index 00000000..d14c8fb9 --- /dev/null +++ b/src/main/java/com/team766/library/CircularBuffer.java @@ -0,0 +1,72 @@ +package com.team766.library; + +import java.util.AbstractCollection; +import java.util.Iterator; + +public class CircularBuffer extends AbstractCollection { + private Object[] buffer; + private int count = 0; + private int headIndex = 0; + + public CircularBuffer(int bufferLength) { + buffer = new Object[bufferLength]; + } + + @Override + public Iterator iterator() { + return new Iterator() { + int index = 0; + + @Override + public boolean hasNext() { + return index < count; + } + + @SuppressWarnings("unchecked") + @Override + public E next() { + return (E) buffer[(headIndex + index++) % buffer.length]; + } + }; + } + + @SuppressWarnings("unchecked") + public E peek() { + if (count == 0) { + return null; + } + return (E) buffer[headIndex]; + } + + public E poll() { + if (count == 0) { + return null; + } + E element = peek(); + headIndex = (headIndex + 1) % buffer.length; + --count; + return element; + } + + @Override + public boolean add(E element) { + if (count < buffer.length) { + buffer[(headIndex + count) % buffer.length] = element; + ++count; + } else { + buffer[headIndex] = element; + headIndex = (headIndex + 1) % buffer.length; + } + return true; + } + + @Override + public int size() { + return count; + } + + @Override + public void clear() { + count = 0; + } +} diff --git a/src/main/java/com/team766/library/LossyPriorityQueue.java b/src/main/java/com/team766/library/LossyPriorityQueue.java new file mode 100644 index 00000000..5837bf11 --- /dev/null +++ b/src/main/java/com/team766/library/LossyPriorityQueue.java @@ -0,0 +1,61 @@ +package com.team766.library; + +import java.util.Comparator; +import java.util.PriorityQueue; +import java.util.concurrent.locks.Condition; +import java.util.concurrent.locks.Lock; +import java.util.concurrent.locks.ReentrantLock; + +public class LossyPriorityQueue { + private final Lock m_lock = new ReentrantLock(); + private final Condition m_empty = m_lock.newCondition(); + private final Condition m_notEmpty = m_lock.newCondition(); + + private final PriorityQueue m_items; + private final int m_capacity; + + public LossyPriorityQueue(int capacity, Comparator comparator) { + m_capacity = capacity; + m_items = new PriorityQueue(m_capacity, comparator); + } + + public void add(E element) { + m_lock.lock(); + try { + while (m_items.size() > m_capacity - 1) { + m_items.poll(); + } + m_items.add(element); + m_notEmpty.signal(); + } finally { + m_lock.unlock(); + } + } + + public E poll() throws InterruptedException { + m_lock.lock(); + try { + while (m_items.size() == 0) { + m_notEmpty.await(); + } + E element = m_items.poll(); + if (m_items.size() == 0) { + m_empty.signal(); + } + return element; + } finally { + m_lock.unlock(); + } + } + + public void waitForEmpty() throws InterruptedException { + m_lock.lock(); + try { + while (!m_items.isEmpty()) { + m_empty.await(); + } + } finally { + m_lock.unlock(); + } + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/library/RateLimiter.java b/src/main/java/com/team766/library/RateLimiter.java new file mode 100644 index 00000000..371ecd54 --- /dev/null +++ b/src/main/java/com/team766/library/RateLimiter.java @@ -0,0 +1,27 @@ +package com.team766.library; + +import com.team766.hal.RobotProvider; + +public class RateLimiter { + private final double periodSeconds; + private double nextTime = 0; + + public RateLimiter(double periodSeconds) { + this.periodSeconds = periodSeconds; + } + + public boolean next() { + final double now = RobotProvider.getTimeProvider().get(); + if (now > nextTime) { + if (nextTime == 0) { + // Lazy-initialize the first time, because TimeProvider in + // simulation often isn't ready at construction time. + nextTime = now; + } + nextTime += periodSeconds; + return true; + } else { + return false; + } + } +} diff --git a/src/main/java/com/team766/library/SetValueProvider.java b/src/main/java/com/team766/library/SetValueProvider.java new file mode 100644 index 00000000..b751e481 --- /dev/null +++ b/src/main/java/com/team766/library/SetValueProvider.java @@ -0,0 +1,36 @@ +package com.team766.library; + +public class SetValueProvider implements SettableValueProvider { + private E m_value; + private boolean m_hasValue; + + public SetValueProvider() { + m_value = null; + m_hasValue = false; + } + + public SetValueProvider(E value) { + m_value = value; + m_hasValue = true; + } + + @Override + public E get() { + return m_value; + } + + @Override + public boolean hasValue() { + return m_hasValue; + } + + public void set(E value) { + m_value = value; + m_hasValue = true; + } + + public void clear() { + m_value = null; + m_hasValue = false; + } +} diff --git a/src/main/java/com/team766/library/SettableValueProvider.java b/src/main/java/com/team766/library/SettableValueProvider.java new file mode 100644 index 00000000..565ef7cf --- /dev/null +++ b/src/main/java/com/team766/library/SettableValueProvider.java @@ -0,0 +1,7 @@ +package com.team766.library; + +public interface SettableValueProvider extends ValueProvider { + public void set(E value); + + public void clear(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/library/ValueProvider.java b/src/main/java/com/team766/library/ValueProvider.java new file mode 100644 index 00000000..49ffc6a1 --- /dev/null +++ b/src/main/java/com/team766/library/ValueProvider.java @@ -0,0 +1,14 @@ +package com.team766.library; + +public interface ValueProvider { + public E get(); + + public boolean hasValue(); + + default E valueOr(E default_value) { + if (hasValue()) { + return get(); + } + return default_value; + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/LogEntryComparator.java b/src/main/java/com/team766/logging/LogEntryComparator.java new file mode 100644 index 00000000..b4c90ee7 --- /dev/null +++ b/src/main/java/com/team766/logging/LogEntryComparator.java @@ -0,0 +1,30 @@ +package com.team766.logging; + +import java.util.Arrays; +import java.util.Comparator; + +class LogEntryComparator implements Comparator { + // This LogEntry should be ordered after any normal LogEntries. + // It is used to signal to the log writing thread that it should exit. + // We want it to come last in the priority queue so that any pending log + // entries get written before the thread terminates. + public static final LogEntry TERMINATION_SENTINAL = + LogEntry.newBuilder() + .setSeverity(Arrays.stream(Severity.values()).min(Comparator.naturalOrder()).get()) + .setTime(Long.MAX_VALUE) + .build(); + + @Override + public int compare(LogEntry o1, LogEntry o2) { + // Sort by highest severity first + int severityResult = -o1.getSeverity().compareTo(o2.getSeverity()); + if (severityResult != 0) { + return severityResult; + } + // Then sort by earliest time. + // Each Category's logger ensures these are unique. This is important + // because we don't want two different log entries to accidentally + // compare as equal. + return Long.compare(o1.getTime(), o2.getTime()); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/LogEntryRenderer.java b/src/main/java/com/team766/logging/LogEntryRenderer.java new file mode 100644 index 00000000..29c10021 --- /dev/null +++ b/src/main/java/com/team766/logging/LogEntryRenderer.java @@ -0,0 +1,17 @@ +package com.team766.logging; + +public class LogEntryRenderer { + public static String renderLogEntry(LogEntry entry, LogReader reader) { + String message = entry.hasMessageStr() ? entry.getMessageStr() + : reader.getFormatString(entry.getMessageIndex()); + final int argCount = entry.getArgCount(); + if (argCount == 0) { + return message; + } else { + final Object[] args = + entry.getArgList().stream() + .map(SerializationUtils::protoToValue).toArray(); + return String.format(message, args); + } + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/LogReader.java b/src/main/java/com/team766/logging/LogReader.java new file mode 100644 index 00000000..2bfbc05f --- /dev/null +++ b/src/main/java/com/team766/logging/LogReader.java @@ -0,0 +1,51 @@ +package com.team766.logging; + +import java.io.FileInputStream; +import java.io.IOException; +import java.util.ArrayList; +import com.google.protobuf.CodedInputStream; +import com.google.protobuf.ExtensionRegistryLite; + +public class LogReader { + + private FileInputStream m_fileStream; + private CodedInputStream m_dataStream; + private LogEntry.Builder m_entryBuilder; + private ArrayList m_formatStrings; + + public LogReader(String filename) throws IOException { + m_fileStream = new FileInputStream(filename); + m_dataStream = CodedInputStream.newInstance(m_fileStream); + m_entryBuilder = LogEntry.newBuilder(); + m_formatStrings = new ArrayList(); + } + + public LogEntry readNext() throws IOException { + m_entryBuilder.clear(); + m_dataStream.readMessage(m_entryBuilder, ExtensionRegistryLite.getEmptyRegistry()); + LogEntry entry = m_entryBuilder.build(); + if (entry.hasMessageIndex() && entry.hasMessageStr()) { + final int index = entry.getMessageIndex(); + final String format = entry.getMessageStr(); + m_formatStrings.ensureCapacity(index + 1); + while (m_formatStrings.size() <= index) { + m_formatStrings.add(null); + } + m_formatStrings.set(index, format); + } + return entry; + } + + String getFormatString(int index) { + String str; + try { + str = m_formatStrings.get(index); + } catch (IndexOutOfBoundsException ex) { + throw new IllegalArgumentException("Unknown format string index: " + index); + } + if (str == null) { + throw new IllegalArgumentException("Unknown format string index: " + index); + } + return str; + } +} diff --git a/src/main/java/com/team766/logging/LogWriter.java b/src/main/java/com/team766/logging/LogWriter.java new file mode 100644 index 00000000..4cd06718 --- /dev/null +++ b/src/main/java/com/team766/logging/LogWriter.java @@ -0,0 +1,108 @@ +package com.team766.logging; + +import java.io.FileOutputStream; +import java.io.IOException; +import java.util.HashMap; +import com.google.protobuf.CodedOutputStream; +import com.team766.library.LossyPriorityQueue; + +public class LogWriter { + private static final int QUEUE_SIZE = 50; + + private LossyPriorityQueue m_entriesQueue; + + private Thread m_workerThread; + private boolean m_running = true; + + private HashMap m_formatStringIndices = new HashMap(); + + private FileOutputStream m_fileStream; + private CodedOutputStream m_dataStream; + + private Severity m_minSeverity = Severity.INFO; + + public LogWriter(String filename) throws IOException { + m_entriesQueue = new LossyPriorityQueue(QUEUE_SIZE, new LogEntryComparator()); + m_fileStream = new FileOutputStream(filename); + m_dataStream = CodedOutputStream.newInstance(m_fileStream); + m_workerThread = new Thread(new Runnable() { + public void run() { + while (true) { + LogEntry entry; + try { + entry = m_entriesQueue.poll(); + } catch (InterruptedException e) { + System.out.println("Logger thread received interruption"); + continue; + } + if (entry == LogEntryComparator.TERMINATION_SENTINAL) { + // close() sends this sentinel element when it's time to exit + return; + } + try { + m_dataStream.writeMessageNoTag(entry); + } catch (IOException e) { + e.printStackTrace(); + Logger.get(Category.JAVA_EXCEPTION).logOnlyInMemory( + Severity.ERROR, + LoggerExceptionUtils.exceptionToString(e)); + } + } + } + }); + m_workerThread.start(); + } + + public void close() throws IOException, InterruptedException { + m_running = false; + m_entriesQueue.add(LogEntryComparator.TERMINATION_SENTINAL); + + m_entriesQueue.waitForEmpty(); + m_workerThread.join(); + + m_dataStream.flush(); + m_fileStream.flush(); + + m_fileStream.getFD().sync(); + + m_fileStream.close(); + } + + public void setSeverityFilter(Severity threshold) { + m_minSeverity = threshold; + } + + public void logStoredFormat(LogEntry.Builder entry) { + if (entry.getSeverity().compareTo(m_minSeverity) < 0) { + return; + } + if (!m_running) { + System.out.println("Log message during shutdown: " + LogEntryRenderer.renderLogEntry(entry.build(), null)); + return; + } + final String format = entry.getMessageStr(); + Integer index = m_formatStringIndices.get(format); + if (index == null) { + index = m_formatStringIndices.size() + 1; + m_formatStringIndices.put(format, index); + if (m_formatStringIndices.size() % 100 == 0) { + System.out.println("You're logging a lot of unique messages. Please switch to using logRaw()"); + } + } else { + entry.clearMessageStr(); + } + entry.setMessageIndex(index); + m_entriesQueue.add(entry.build()); + } + + public void log(LogEntry entry) { + if (entry.getSeverity().compareTo(m_minSeverity) < 0) { + return; + } + if (!m_running) { + System.out.println("Log message during shutdown: " + LogEntryRenderer.renderLogEntry(entry, null)); + return; + } + m_entriesQueue.add(entry); + } +} diff --git a/src/main/java/com/team766/logging/Loggable.java b/src/main/java/com/team766/logging/Loggable.java new file mode 100644 index 00000000..14bf6e7d --- /dev/null +++ b/src/main/java/com/team766/logging/Loggable.java @@ -0,0 +1,5 @@ +package com.team766.logging; + +public interface Loggable { + public abstract void toLogValue(LogValue.Builder value); +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/Logger.java b/src/main/java/com/team766/logging/Logger.java new file mode 100644 index 00000000..473dd5d4 --- /dev/null +++ b/src/main/java/com/team766/logging/Logger.java @@ -0,0 +1,132 @@ +package com.team766.logging; + +import java.io.File; +import java.text.SimpleDateFormat; +import java.util.Collection; +import java.util.Collections; +import java.util.Date; +import java.util.EnumMap; + +import com.team766.config.ConfigFileReader; +import com.team766.library.CircularBuffer; + +public class Logger { + private static class LogUncaughtException implements Thread.UncaughtExceptionHandler { + public void uncaughtException(Thread t, Throwable e) { + e.printStackTrace(); + + LoggerExceptionUtils.logException(e); + + if (m_logWriter != null) { + try { + m_logWriter.close(); + } catch (Exception e1) { + e1.printStackTrace(); + } + } + + System.exit(1); + } + } + + private static final int MAX_NUM_RECENT_ENTRIES = 100; + + private static EnumMap m_loggers = new EnumMap(Category.class); + private static LogWriter m_logWriter = null; + private CircularBuffer m_recentEntries = new CircularBuffer(MAX_NUM_RECENT_ENTRIES); + private static Object s_lastWriteTimeSync = new Object(); + private static long s_lastWriteTime = 0L; + + public static String logFilePathBase = null; + + static { + for (Category category : Category.values()) { + m_loggers.put(category, new Logger(category)); + } + try { + ConfigFileReader config_file = ConfigFileReader.getInstance(); + if (config_file != null) { + logFilePathBase = config_file.getString("logFilePath").get(); + new File(logFilePathBase).mkdirs(); + final String timestamp = new SimpleDateFormat("yyyyMMdd'T'HHmmss").format(new Date()); + final String logFilePath = new File(logFilePathBase, timestamp).getAbsolutePath(); + m_logWriter = new LogWriter(logFilePath); + get(Category.CONFIGURATION).logRaw(Severity.INFO, "Logging to " + logFilePath); + } else { + get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Config file is not available. Logs will only be in-memory and will be lost when the robot is turned off."); + } + } catch (Exception e) { + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + + Thread.setDefaultUncaughtExceptionHandler(new LogUncaughtException()); + } + + public static Logger get(Category category) { + return m_loggers.get(category); + } + + static long getTime() { + long nowNanosec = new Date().getTime() * 1000000; + synchronized(s_lastWriteTimeSync) { + // Ensure that log entries' timestamps are unique. This is important + // because the log viewer uses an entry's timestamp as a unique ID, + // and we don't want two different log entries to accidentally + // compare as equal. + nowNanosec = s_lastWriteTime = Math.max(nowNanosec, s_lastWriteTime); + } + return nowNanosec; + } + + private final Category m_category; + + private Logger(Category category) { + m_category = category; + } + + public Collection recentEntries() { + return Collections.unmodifiableCollection(m_recentEntries); + } + + public void logData(Severity severity, String format, Object... args) { + var entry = LogEntry.newBuilder() + .setTime(getTime()) + .setSeverity(severity) + .setCategory(m_category); + { + entry.setMessageStr(String.format(format, args)); + m_recentEntries.add(entry.build()); + } + entry.setMessageStr(format); + for (Object arg : args) { + SerializationUtils.valueToProto(arg, entry.addArgBuilder()); + } + if (m_logWriter != null) { + m_logWriter.logStoredFormat(entry); + } + } + + public void logRaw(Severity severity, String message) { + var entry = LogEntry.newBuilder() + .setTime(getTime()) + .setSeverity(severity) + .setCategory(m_category) + .setMessageStr(message) + .build(); + m_recentEntries.add(entry); + if (m_logWriter != null) { + m_logWriter.log(entry); + } + } + + void logOnlyInMemory(Severity severity, String message) { + var entry = LogEntry.newBuilder() + .setTime(getTime()) + .setSeverity(severity) + .setCategory(m_category) + .setMessageStr(message) + .build(); + m_recentEntries.add(entry); + } +} diff --git a/src/main/java/com/team766/logging/LoggerExceptionUtils.java b/src/main/java/com/team766/logging/LoggerExceptionUtils.java new file mode 100644 index 00000000..2f13388a --- /dev/null +++ b/src/main/java/com/team766/logging/LoggerExceptionUtils.java @@ -0,0 +1,25 @@ +package com.team766.logging; + +import java.io.PrintWriter; +import java.io.StringWriter; + +public class LoggerExceptionUtils { + public static String exceptionToString(Throwable e) { + StringWriter sw = new StringWriter(); + PrintWriter pw = new PrintWriter(sw); + pw.print("Uncaught exception: "); + e.printStackTrace(pw); + pw.flush(); + return sw.toString(); + } + + public static String logException(Throwable e) { + String str = exceptionToString(e); + try { + Logger.get(Category.JAVA_EXCEPTION).logRaw(Severity.ERROR, str); + } catch (Exception exc) { + exc.printStackTrace(); + } + return str; + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/SerializationUtils.java b/src/main/java/com/team766/logging/SerializationUtils.java new file mode 100644 index 00000000..ac6b7997 --- /dev/null +++ b/src/main/java/com/team766/logging/SerializationUtils.java @@ -0,0 +1,50 @@ +package com.team766.logging; + +public class SerializationUtils { + public static void valueToProto(Object object, LogValue.Builder value) { + if (object instanceof Byte || + object instanceof Short || + object instanceof Integer || + object instanceof Long) { + value.setIntValue(((Number)object).longValue()); + } else if (object instanceof Character) { + value.setStringValue(((Character)object).toString()); + } else if (object instanceof Number) { + // If object is a Number but not one of the integer types, treat it + // as a double (this primarily handles Float and Double values, but + // also handles any weird other type that might inherit from Number) + value.setFloatValue(((Number)object).doubleValue()); + } else if (object instanceof Boolean) { + value.setBoolValue(((Boolean)object).booleanValue()); + } else if (object instanceof String) { + value.setStringValue((String)object); + } else if (object == null) { + value.clearKind(); + } else if (object instanceof Loggable) { + ((Loggable)object).toLogValue(value); + } else { + throw new IllegalArgumentException( + "Value of type " + object.getClass().getName() + " isn't loggable"); + } + } + + public static Object protoToValue(LogValue value) { + switch (value.getKindCase()) { + case KIND_NOT_SET: + return null; + case BOOL_VALUE: + return value.getBoolValue(); + case FLOAT_VALUE: + return value.getFloatValue(); + case INT_VALUE: + return value.getIntValue(); + case LIST: + return value.getList().getElementList().stream() + .map(SerializationUtils::protoToValue).toArray(); + case STRING_VALUE: + return value.getStringValue(); + } + throw new IllegalArgumentException( + "Unsupported LogValue kind: " + value.getKindCase()); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/math/Algebraic.java b/src/main/java/com/team766/math/Algebraic.java new file mode 100644 index 00000000..3bce828d --- /dev/null +++ b/src/main/java/com/team766/math/Algebraic.java @@ -0,0 +1,7 @@ +package com.team766.math; + +public interface Algebraic> { + public E add(E b); + + public E scale(double b); +} diff --git a/src/main/java/com/team766/math/Filter.java b/src/main/java/com/team766/math/Filter.java new file mode 100644 index 00000000..146980b5 --- /dev/null +++ b/src/main/java/com/team766/math/Filter.java @@ -0,0 +1,7 @@ +package com.team766.math; + +public interface Filter { + public void push(double sample); + + public double getValue(); +} diff --git a/src/main/java/com/team766/math/FirFilter.java b/src/main/java/com/team766/math/FirFilter.java new file mode 100644 index 00000000..4bad9289 --- /dev/null +++ b/src/main/java/com/team766/math/FirFilter.java @@ -0,0 +1,21 @@ +package com.team766.math; + +import java.util.stream.Collectors; + +import com.team766.library.CircularBuffer; + +public class FirFilter implements Filter { + private CircularBuffer buffer; + + public FirFilter(int bufferLength) { + buffer = new CircularBuffer<>(bufferLength); + } + + public void push(double sample) { + buffer.add(sample); + } + + public double getValue() { + return buffer.stream().collect(Collectors.averagingDouble(Double::doubleValue)); + } +} diff --git a/src/main/java/com/team766/math/IirFilter.java b/src/main/java/com/team766/math/IirFilter.java new file mode 100644 index 00000000..ac146be4 --- /dev/null +++ b/src/main/java/com/team766/math/IirFilter.java @@ -0,0 +1,27 @@ +package com.team766.math; + +public class IirFilter implements Filter { + private double decay; + private double value; + + public IirFilter(double decay, double initialValue) { + this.decay = decay; + this.value = initialValue; + if (decay > 1.0 || decay <= 0.0) { + throw new IllegalArgumentException("decay should be in (0.0, 1.0]"); + } + } + + public IirFilter(double decay) { + this(decay, 0.0); + } + + public void push(double sample) { + value *= (1.0 - decay); + value += sample * decay; + } + + public double getValue() { + return value; + } +} diff --git a/src/main/java/com/team766/math/IsometricTransform.java b/src/main/java/com/team766/math/IsometricTransform.java new file mode 100644 index 00000000..dc75c294 --- /dev/null +++ b/src/main/java/com/team766/math/IsometricTransform.java @@ -0,0 +1,40 @@ +package com.team766.math; + +import org.apache.commons.math3.geometry.euclidean.threed.Rotation; +import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +public class IsometricTransform { + public final Rotation rotation; + public final Vector3D translation; + + public static final IsometricTransform IDENTITY = + new IsometricTransform(Rotation.IDENTITY, Vector3D.ZERO); + + public IsometricTransform(Rotation rotation, Vector3D translation) { + this.rotation = rotation; + this.translation = translation; + } + + Vector3D applyInverseTo(Vector3D u) { + return rotation.applyInverseTo(u.subtract(translation)); + } + + Vector3D applyTo(Vector3D u) { + return rotation.applyTo(u).add(translation); + } + + IsometricTransform compose(IsometricTransform other) { + return new IsometricTransform(rotation.compose(other.rotation, RotationConvention.VECTOR_OPERATOR), + rotation.applyTo(other.translation).add(translation)); + } + + IsometricTransform composeInverse(IsometricTransform other) { + return new IsometricTransform(rotation.composeInverse(other.rotation, RotationConvention.VECTOR_OPERATOR), + rotation.applyInverseTo(other.translation).subtract(translation)); + } + + IsometricTransform invert() { + return new IsometricTransform(rotation.revert(), rotation.applyInverseTo(translation)); + } +} diff --git a/src/main/java/com/team766/math/LinearInterpolation.java b/src/main/java/com/team766/math/LinearInterpolation.java new file mode 100644 index 00000000..41a1f2a8 --- /dev/null +++ b/src/main/java/com/team766/math/LinearInterpolation.java @@ -0,0 +1,53 @@ +package com.team766.math; + +/*import java.util.Arrays; + +public class LinearInterpolation { + private static class LerpArgs { + public E a; + public E b; + public double t; + } + + private static LerpArgs getArgs(double[] t, E[] x, double q) { + if (t.length != x.length) { + throw new IllegalArgumentException("Keys and values must have the same length"); + } + if (t.length == 0) { + throw new IllegalArgumentException("Interpolated data must have at least one point"); + } + LerpArgs args = new LerpArgs(); + int lower, upper; + if (t.length == 1) { + // 0-th order regression if we only have one point. + lower = upper = 0; + args.t = 0; + } else { + int index = Arrays.binarySearch(t, q); + if (index >= 0) { + // Exact match. + lower = upper = index; + args.t = 0; + } else { + upper = -index - 1; + lower = upper - 1; + double a_t = t[lower]; + double b_t = t[upper]; + args.t = (q - a_t) / (b_t - a_t); + } + } + args.a = x[lower]; + args.b = x[upper]; + return args; + } + + public static double get(double[] t, Double[] x, double q) { + LerpArgs args = getArgs(t, x, q); + return args.a * (1 - args.t) + (args.b * args.t); + } + + public static > E get(double[] t, E[] x, double q) { + LerpArgs args = getArgs(t, x, q); + return args.a.scale(1 - args.t).add(args.b.scale(args.t)); + } +}*/ \ No newline at end of file diff --git a/src/main/java/com/team766/math/Math.java b/src/main/java/com/team766/math/Math.java new file mode 100644 index 00000000..84b109d9 --- /dev/null +++ b/src/main/java/com/team766/math/Math.java @@ -0,0 +1,22 @@ +package com.team766.math; + +public class Math { + public static double clamp(double x, double min, double max) { + if (x < min) return min; + if (x > max) return max; + return x; + } + + /** + * Returns the given angle, normalized to be within the range [-180, 180) + */ + public static double normalizeAngleDegrees(double angle) { + while (angle < -180) { + angle += 360; + } + while (angle >= 180) { + angle -= 360; + } + return angle; + } +} diff --git a/src/main/java/com/team766/math/TransformTree.java b/src/main/java/com/team766/math/TransformTree.java new file mode 100644 index 00000000..6e73823e --- /dev/null +++ b/src/main/java/com/team766/math/TransformTree.java @@ -0,0 +1,83 @@ +package com.team766.math; + +import java.util.ArrayList; +import java.util.Hashtable; + +public class TransformTree { + private ArrayList tree; + + private final String name; + private TransformTree parent; + private IsometricTransform transform; + + public TransformTree(String rootName) { + this.name = rootName; + } + + private TransformTree(String name, TransformTree parent) { + this.name = name; + this.parent = parent; + } + + public TransformTree addSubordinateTransform(String name) { + TransformTree subtree = new TransformTree(name, this); + tree.add(subtree); + return subtree; + } + + public void setLocalTransform(IsometricTransform xf) { + transform = xf; + } + public IsometricTransform getLocalTransform() { + return transform; + } + + public IsometricTransform getTransformRelativeTo(String name) { + TransformTree other = getRoot().findTransform(name); + if (other == null) { + throw new IllegalArgumentException("Can't find a transform named " + name); + } + return getTransformRelativeTo(other); + } + public IsometricTransform getTransformRelativeTo(TransformTree other) { + Hashtable parentChain = new Hashtable(); + IsometricTransform xf = transform; + parentChain.put(name, xf); + TransformTree iterator = this.parent; + while (iterator != null) { + xf = iterator.transform.compose(xf); + parentChain.put(iterator.name, xf); + iterator = iterator.parent; + } + iterator = other; + xf = other.transform; + while (iterator != null) { + IsometricTransform first = parentChain.get(iterator.name); + if (first != null) { + return first.compose(xf.invert()); + } + } + throw new IllegalArgumentException("Transforms aren't part of the same tree"); + } + + public TransformTree findTransform(String name) { + if (this.name == name) { + return this; + } + for (TransformTree sub : tree) { + TransformTree subResult = sub.findTransform(name); + if (subResult != null) { + return subResult; + } + } + return null; + } + + private TransformTree getRoot() { + TransformTree iterator = this; + while (iterator.parent != null) { + iterator = iterator.parent; + } + return iterator; + } +} diff --git a/src/main/java/com/team766/math/Vector3.java b/src/main/java/com/team766/math/Vector3.java new file mode 100644 index 00000000..0cd38152 --- /dev/null +++ b/src/main/java/com/team766/math/Vector3.java @@ -0,0 +1,60 @@ +package com.team766.math; + +public class Vector3 implements Algebraic { + public static final Vector3 ZERO = new Vector3(0, 0, 0); + public static final Vector3 UNIT_X = new Vector3(1, 0, 0); + public static final Vector3 UNIT_Y = new Vector3(0, 1, 0); + public static final Vector3 UNIT_Z = new Vector3(0, 0, 1); + + public final double x; + public final double y; + public final double z; + + public Vector3(double x, double y, double z) { + this.x = x; + this.y = y; + this.z = z; + } + + public Vector3(Vector3 other) { + this.x = other.x; + this.y = other.y; + this.z = other.z; + } + + public Vector3 add(Vector3 b) { + return new Vector3(x + b.x, y + b.y, z + b.z); + } + + public Vector3 subtract(Vector3 b) { + return new Vector3(x - b.x, y - b.y, z - b.z); + } + + public double dot(Vector3 b) { + return x * b.x + y * b.y + z * b.z; + } + + public Vector3 cross(Vector3 b) { + return new Vector3(y * b.z - z * b.y, + z * b.x - x * b.z, + x * b.y - y * b.x); + } + + public Vector3 scale(double b) { + return new Vector3(x * b, y * b, z * b); + } + + @Override + public boolean equals(Object other) { + if (!(other instanceof Vector3)) { + return false; + } + Vector3 otherVector = (Vector3)other; + return x != otherVector.x || y != otherVector.y || z != otherVector.z; + } + + @Override + public String toString() { + return String.format("[%s, %s, %s]", x, y, z); + } +} diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java new file mode 100644 index 00000000..0528d3ac --- /dev/null +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -0,0 +1,18 @@ +package com.team766.robot; + +import com.team766.framework.AutonomousMode; +import com.team766.robot.procedures.*; + +public class AutonomousModes { + public static final AutonomousMode[] AUTONOMOUS_MODES = new AutonomousMode[] { + // Add autonomous modes here like this: + // new AutonomousMode("NameOfAutonomousMode", () -> new MyAutonomousProcedure()), + // + // If your autonomous procedure has constructor arguments, you can + // define one or more different autonomous modes with it like this: + // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), + // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), + + new AutonomousMode("DoNothing", () -> new DoNothing()), + }; +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java new file mode 100644 index 00000000..1163a781 --- /dev/null +++ b/src/main/java/com/team766/robot/OI.java @@ -0,0 +1,36 @@ +package com.team766.robot; + +import com.team766.framework.Procedure; +import com.team766.framework.Context; +import com.team766.hal.JoystickReader; +import com.team766.hal.RobotProvider; +import com.team766.logging.Category; +import com.team766.robot.procedures.*; + +/** + * This class is the glue that binds the controls on the physical operator + * interface to the code that allow control of the robot. + */ +public class OI extends Procedure { + private JoystickReader joystick0; + private JoystickReader joystick1; + private JoystickReader joystick2; + + public OI() { + loggerCategory = Category.OPERATOR_INTERFACE; + + joystick0 = RobotProvider.instance.getJoystick(0); + joystick1 = RobotProvider.instance.getJoystick(1); + joystick2 = RobotProvider.instance.getJoystick(2); + } + + public void run(Context context) { + while (true) { + // Add driver controls here - make sure to take/release ownership + // of mechanisms when appropriate. + + + context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); + } + } +} diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java new file mode 100644 index 00000000..b2b3c2a7 --- /dev/null +++ b/src/main/java/com/team766/robot/Robot.java @@ -0,0 +1,13 @@ +package com.team766.robot; + +import com.team766.robot.mechanisms.*; + +public class Robot { + // Declare mechanisms here + + + public static void robotInit() { + // Initialize mechanisms here + + } +} diff --git a/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java b/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java new file mode 100644 index 00000000..75f24df9 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java @@ -0,0 +1,22 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.RobotProvider; +import com.team766.hal.MotorController; + +public class ExampleMechanism extends Mechanism { + private MotorController leftMotor; + private MotorController rightMotor; + + public ExampleMechanism() { + leftMotor = RobotProvider.instance.getMotor("exampleMechanism.leftMotor"); + rightMotor = RobotProvider.instance.getMotor("exampleMechanism.rightMotor"); + } + + public void setMotorPower(double leftPower, double rightPower){ + checkContextOwnership(); + + leftMotor.set(leftPower); + rightMotor.set(rightPower); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/mechanisms/README b/src/main/java/com/team766/robot/mechanisms/README new file mode 100644 index 00000000..a6f5072f --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/README @@ -0,0 +1 @@ +Add mechanism classes here \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/DoNothing.java b/src/main/java/com/team766/robot/procedures/DoNothing.java new file mode 100644 index 00000000..566ad756 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/DoNothing.java @@ -0,0 +1,11 @@ +package com.team766.robot.procedures; + +import com.team766.framework.Context; +import com.team766.framework.Procedure; + +public class DoNothing extends Procedure { + + public void run(Context context) { + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/README b/src/main/java/com/team766/robot/procedures/README new file mode 100644 index 00000000..fd6888a5 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/README @@ -0,0 +1 @@ +Add procedure classes here \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ElectricalSystem.java b/src/main/java/com/team766/simulator/ElectricalSystem.java new file mode 100644 index 00000000..398d497b --- /dev/null +++ b/src/main/java/com/team766/simulator/ElectricalSystem.java @@ -0,0 +1,35 @@ +package com.team766.simulator; + +import java.util.ArrayList; + +import com.team766.simulator.interfaces.ElectricalDevice; + +public class ElectricalSystem { + private double nominalVoltage = Parameters.BATTERY_VOLTAGE; + private double primaryResistance = Parameters.PRIMARY_ELECTRICAL_RESISTANCE; + + private ArrayList branchCircuits = new ArrayList(); + + private ElectricalDevice.Input systemState; + + public ElectricalSystem() { + systemState = new ElectricalDevice.Input(nominalVoltage); + } + + public void addDevice(ElectricalDevice device) { + branchCircuits.add(device); + } + + public void step() { + double current = 0.0; + for (ElectricalDevice device : branchCircuits) { + ElectricalDevice.Output deviceState = device.step(systemState); + current += deviceState.current; + } + systemState = new ElectricalDevice.Input(Math.max(0, nominalVoltage - primaryResistance * current)); + } + + public double getSystemVoltage() { + return systemState.voltage; + } +} diff --git a/src/main/java/com/team766/simulator/Parameters.java b/src/main/java/com/team766/simulator/Parameters.java new file mode 100644 index 00000000..0a226972 --- /dev/null +++ b/src/main/java/com/team766/simulator/Parameters.java @@ -0,0 +1,28 @@ +package com.team766.simulator; + +public class Parameters { + public static final double TIME_STEP = 0.001; // seconds + public static final double DURATION = 5.0; // seconds + + // Robot mode to run in the simulator + public static final ProgramInterface.RobotMode INITIAL_ROBOT_MODE = ProgramInterface.RobotMode.AUTON; + + public static final double BATTERY_VOLTAGE = 12.6; // volts + public static final double PRIMARY_ELECTRICAL_RESISTANCE = 0.018 + 0.01; // ohms + + public static final double STARTING_PRESSURE = 0; // pascals (relative); 120 psi = 827370.875 pascals + + public static final double DRIVE_WHEEL_DIAMETER = 0.1524; // 6 inches in meters + public static final double DRIVE_GEAR_RATIO = 8.0; + public static final int NUM_LOADED_WHEELS = 2; + public static final int ENCODER_TICKS_PER_REVOLUTION = 256; + + public static final double ROBOT_MASS = 66; // approx. 145 lbs in kg + public static final double ROBOT_LENGTH = 1.0; // meters + public static final double ROBOT_WIDTH = 0.8; // meters + public static final double ROBOT_MOMENT_OF_INERTIA = 1.0/12.0 * ROBOT_MASS * (ROBOT_WIDTH*ROBOT_WIDTH + ROBOT_LENGTH*ROBOT_LENGTH); + + public static final double WHEEL_COEFFICIENT_OF_FRICTION = 1.1; + public static final double ROLLING_RESISTANCE = 0.09; + public static final double TURNING_RESISTANCE_FACTOR = 0.15; +} diff --git a/src/main/java/com/team766/simulator/PhysicalConstants.java b/src/main/java/com/team766/simulator/PhysicalConstants.java new file mode 100644 index 00000000..bcba78d5 --- /dev/null +++ b/src/main/java/com/team766/simulator/PhysicalConstants.java @@ -0,0 +1,7 @@ +package com.team766.simulator; + +public class PhysicalConstants { + public static final double GRAVITY_ACCELERATION = 9.81; // m/s^2 + + public static final double ATMOSPHERIC_PRESSURE = 101325; // Pascals +} diff --git a/src/main/java/com/team766/simulator/PneumaticsSystem.java b/src/main/java/com/team766/simulator/PneumaticsSystem.java new file mode 100644 index 00000000..768b8aba --- /dev/null +++ b/src/main/java/com/team766/simulator/PneumaticsSystem.java @@ -0,0 +1,61 @@ +package com.team766.simulator; + +import java.util.ArrayList; + +import com.team766.simulator.interfaces.PneumaticDevice; + +public class PneumaticsSystem { + public static final double PSI_TO_PASCALS = 6894.75729; + + private static class BranchCircuit { + public PneumaticDevice device; + public double regulatedPressure; + } + + private ArrayList branchCircuits = new ArrayList(); + + private double systemPressure = Parameters.STARTING_PRESSURE; + private double compressedAirVolume = 0.0; + private boolean initialized = false; + + public void addDevice(PneumaticDevice device, double regulatedPressure) { + BranchCircuit circuit = new BranchCircuit(); + circuit.device = device; + circuit.regulatedPressure = regulatedPressure; + branchCircuits.add(circuit); + } + + public void step() { + double flowVolume = 0.0; + double systemVolume = 0.0; + for (BranchCircuit circuit : branchCircuits) { + double devicePressure = Math.min(circuit.regulatedPressure, systemPressure); + PneumaticDevice.Input inputState = new PneumaticDevice.Input(devicePressure); + PneumaticDevice.Output deviceState = circuit.device.step(inputState); + // TODO: implement relieving pressure regulator (make sure device pressure doesn't exceed + // circuit.regulatedPressure, even when including flow volume) + flowVolume += deviceState.flowVolume; + systemVolume += deviceState.deviceVolume; + } + compressedAirVolume += flowVolume; + if (systemVolume == 0.) { + throw new RuntimeException("Your pneumatics system has no storage volume"); + } + if (!initialized) { + compressedAirVolume = systemVolume * (systemPressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE; + initialized = true; + } + systemPressure = compressedAirVolume / systemVolume * PhysicalConstants.ATMOSPHERIC_PRESSURE - PhysicalConstants.ATMOSPHERIC_PRESSURE; + } + + public double getSystemPressure() { + return systemPressure; + } + + // Simulate the system venting all of its compressed air (e.g. someone opened the release valve; + // to simulate the pneumatics system becoming compromised, call this method on every simulation tick) + public void ventPressure() { + systemPressure = 0; + initialized = false; + } +} diff --git a/src/main/java/com/team766/simulator/Program.java b/src/main/java/com/team766/simulator/Program.java new file mode 100644 index 00000000..c83d2cb0 --- /dev/null +++ b/src/main/java/com/team766/simulator/Program.java @@ -0,0 +1,7 @@ +package com.team766.simulator; + +public interface Program { + public void step(); + + public void reset(); +} diff --git a/src/main/java/com/team766/simulator/ProgramInterface.java b/src/main/java/com/team766/simulator/ProgramInterface.java new file mode 100644 index 00000000..6f7aca38 --- /dev/null +++ b/src/main/java/com/team766/simulator/ProgramInterface.java @@ -0,0 +1,99 @@ +package com.team766.simulator; + +import java.lang.reflect.Array; +import com.team766.hal.mock.MockJoystick; + +public class ProgramInterface { + public static Program program = null; + + public static double simulationTime; + + public static int driverStationUpdateNumber = 0; + + public static enum RobotMode { + DISABLED, AUTON, TELEOP + } + + public static RobotMode robotMode = Parameters.INITIAL_ROBOT_MODE; + + public static final double[] pwmChannels = new double[20]; + + public static class CANMotorControllerCommand { + public enum ControlMode { + PercentOutput, + Position, + Velocity, + Current, + Follower, + MotionProfile, + MotionMagic, + MotionProfileArc, + Voltage, + Disabled, + } + + public double output; + public ControlMode controlMode; + } + public static class CANMotorControllerStatus { + public double sensorPosition; + public double sensorVelocity; + } + public static class CANMotorControllerCommunication { + public final CANMotorControllerCommand command = new CANMotorControllerCommand(); + public final CANMotorControllerStatus status = new CANMotorControllerStatus(); + } + + public static final CANMotorControllerCommunication[] canMotorControllerChannels = + initializeArray(256, CANMotorControllerCommunication.class); + + public static final double[] analogChannels = new double[20]; + + public static final boolean[] digitalChannels = new boolean[20]; + + public static final int[] relayChannels = new int[20]; + + public static final boolean[] solenoidChannels = new boolean[20]; + + public static class EncoderChannel { + public long distance = 0; + public double rate = 0; + } + + public static final EncoderChannel[] encoderChannels = + initializeArray(20, EncoderChannel.class); + + public static class GyroCommunication { + public double angle; // Yaw angle (accumulative) + public double rate; // Yaw rate + public double pitch; + public double roll; + } + + public static final GyroCommunication gyro = new GyroCommunication(); + + public static class RobotPosition { + public double x; + public double y; + public double heading; + } + + public static final RobotPosition robotPosition = new RobotPosition(); + + public static final MockJoystick[] joystickChannels = + initializeArray(6, MockJoystick.class); + + + private static E[] initializeArray(int size, Class clazz) { + @SuppressWarnings("unchecked") + E[] array = (E[]) Array.newInstance(clazz, size); + for (int i = 0; i < size; ++i) { + try { + array[i] = clazz.getConstructor().newInstance(); + } catch (Throwable e) { + throw new ExceptionInInitializerError(e); + } + } + return array; + } +} diff --git a/src/main/java/com/team766/simulator/Simulator.java b/src/main/java/com/team766/simulator/Simulator.java new file mode 100644 index 00000000..792ae667 --- /dev/null +++ b/src/main/java/com/team766/simulator/Simulator.java @@ -0,0 +1,82 @@ +package com.team766.simulator; + +import java.util.ArrayList; + +import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; +import org.apache.commons.math3.geometry.euclidean.threed.RotationOrder; + +import com.team766.simulator.elements.AirCompressor; +import com.team766.simulator.elements.AirReservoir; +import com.team766.simulator.mechanisms.WestCoastDrive; +import com.team766.simulator.ui.Metrics; +import com.team766.simulator.ui.Trajectory; + +public class Simulator implements Runnable { + private ElectricalSystem electricalSystem = new ElectricalSystem(); + private PneumaticsSystem pneumaticsSystem = new PneumaticsSystem(); + private WestCoastDrive drive = new WestCoastDrive(electricalSystem); + private AirCompressor compressor = new AirCompressor(); + + private double time; + private ArrayList metrics = new ArrayList(); + private ArrayList trajectory = new ArrayList(); + + public Simulator() { + electricalSystem.addDevice(compressor); + pneumaticsSystem.addDevice(compressor, 120 * PneumaticsSystem.PSI_TO_PASCALS); + pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL + pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL + } + + public void step() { + time += Parameters.TIME_STEP; + ProgramInterface.simulationTime = time; + + electricalSystem.step(); + pneumaticsSystem.step(); + drive.step(); + + if (ProgramInterface.program != null) { + ProgramInterface.program.step(); + } + + metrics.add(new Double[] { + time, + drive.getPosition().getX(), + drive.getPosition().getY(), + Math.toDegrees(drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2]), + drive.getLinearVelocity().getX(), + drive.getLinearAcceleration().getX(), + electricalSystem.getSystemVoltage(), + pneumaticsSystem.getSystemPressure() / PneumaticsSystem.PSI_TO_PASCALS, + }); + trajectory.add(new Double[] { + drive.getPosition().getX(), + drive.getPosition().getY(), + drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2], + drive.getLinearVelocity().getX(), + drive.getLinearVelocity().getY(), + }); + } + + public void run() { + metrics.clear(); + time = 0.0; + while (time <= Parameters.DURATION) { + step(); + if (Math.abs(time - 3.0) < Parameters.TIME_STEP) { + pneumaticsSystem.ventPressure(); + } + } + Trajectory.makePlotFrame(trajectory); + Metrics.makePlotFrame(metrics, new String[] { + "X Position (m)", + "Y Position (m)", + "Rotation (deg)", + "Velocity (m/s)", + "Acceleration (m/s^2)", + "System Voltage (V)", + "System Pressure (PSI)", + }); + } +} diff --git a/src/main/java/com/team766/simulator/elements/AirCompressor.java b/src/main/java/com/team766/simulator/elements/AirCompressor.java new file mode 100644 index 00000000..febca8b3 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/AirCompressor.java @@ -0,0 +1,56 @@ +package com.team766.simulator.elements; + +import java.util.Arrays; + +import org.apache.commons.math3.analysis.interpolation.LinearInterpolator; +import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction; + +import com.team766.simulator.Parameters; +import com.team766.simulator.PneumaticsSystem; +import com.team766.simulator.interfaces.ElectricalDevice; +import com.team766.simulator.interfaces.PneumaticDevice; + +public class AirCompressor implements ElectricalDevice, PneumaticDevice { + private static final double CFM_TO_M3_PER_SEC = 0.000471947443; + + // Values for http://www.andymark.com/product-p/am-2005.htm + private static final double NOMINAL_VOLTAGE = 12; + private static final double[] PRESSURES_PSI = { 0., 10., 20., 30., 40., 50., 60., 70., 80., 90., 100., 110. }; + private static final double[] FLOW_RATES_CFM = { 0.88, 0.50, 0.43, 0.36, 0.30, 0.27, 0.25, 0.24, 0.24, 0.23, 0.22, 0.22 }; + private static final double[] CURRENTS = { 7., 8., 8., 9., 9., 9., 10., 10., 10., 11., 11., 10. }; + private static final double[] PRESSURES = Arrays.stream(PRESSURES_PSI).map(psi -> psi * PneumaticsSystem.PSI_TO_PASCALS).toArray(); + private static final double[] FLOW_RATES = Arrays.stream(FLOW_RATES_CFM).map(cfm -> cfm * CFM_TO_M3_PER_SEC).toArray(); + + PolynomialSplineFunction currentFunction = new LinearInterpolator().interpolate(PRESSURES, CURRENTS); + PolynomialSplineFunction flowRateFunction = new LinearInterpolator().interpolate(PRESSURES, FLOW_RATES); + + private boolean isOn = true; + + private ElectricalDevice.Input electricalState = new ElectricalDevice.Input(0); + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); + + public void setIsOn(boolean on) { + isOn = on; + } + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + electricalState = input; + if (isOn) { + double nominalCurrent = currentFunction.value(pneumaticState.pressure); + double adjustedCurrent = nominalCurrent * electricalState.voltage / NOMINAL_VOLTAGE; + return new ElectricalDevice.Output(adjustedCurrent); + } else { + return new ElectricalDevice.Output(0); + } + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + pneumaticState = input; + double nominalFlowRate = flowRateFunction.value(pneumaticState.pressure); + double adjustedFlowRate = nominalFlowRate * electricalState.voltage / NOMINAL_VOLTAGE; + double flowVolume = adjustedFlowRate * Parameters.TIME_STEP; + return new PneumaticDevice.Output(flowVolume, 0); + } +} diff --git a/src/main/java/com/team766/simulator/elements/AirReservoir.java b/src/main/java/com/team766/simulator/elements/AirReservoir.java new file mode 100644 index 00000000..0faf6870 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/AirReservoir.java @@ -0,0 +1,17 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.PneumaticDevice; + +public class AirReservoir implements PneumaticDevice { + + private double volume; + + public AirReservoir(double volume) { + this.volume = volume; + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + return new PneumaticDevice.Output(0, volume); + } +} diff --git a/src/main/java/com/team766/simulator/elements/CanMotorController.java b/src/main/java/com/team766/simulator/elements/CanMotorController.java new file mode 100644 index 00000000..685e8ca1 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/CanMotorController.java @@ -0,0 +1,21 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.interfaces.ElectricalDevice; + +public class CanMotorController extends MotorController { + + private int address; + + public CanMotorController(int address, ElectricalDevice downstream) { + super(downstream); + + this.address = address; + } + + @Override + protected double getCommand() { + return ProgramInterface.canMotorControllerChannels[address].command.output; + } + +} diff --git a/src/main/java/com/team766/simulator/elements/DCMotor.java b/src/main/java/com/team766/simulator/elements/DCMotor.java new file mode 100644 index 00000000..5cb95ba5 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/DCMotor.java @@ -0,0 +1,49 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.ElectricalDevice; +import com.team766.simulator.interfaces.MechanicalAngularDevice; + +public class DCMotor implements ElectricalDevice, MechanicalAngularDevice { + // TODO: Add rotor inertia + // TODO: Add thermal effects + + public static DCMotor makeCIM() { + return new DCMotor(46.513, 0.018397, 0.091603053435115); + } + public static DCMotor make775Pro() { + return new DCMotor(163.450, 0.0052985, 0.08955223880597); + } + + // Motor velocity constant in radian/second/volt + // (motor velocity) = kV * (motor voltage) + private final double kV; + + // Motor torque constant in newton-meter/ampere + // (motor torque) = kT * (motor current) + private final double kT; + + // Motor resistance is calculated as 12V / (stall current at 12V) + private final double motorResistance; + + private ElectricalDevice.Output electricalState = new ElectricalDevice.Output(0); + private MechanicalAngularDevice.Input mechanicalState = new MechanicalAngularDevice.Input(0); + + public DCMotor(double kV, double kT, double motorResistance) { + this.kV = kV; + this.kT = kT; + this.motorResistance = motorResistance; + } + + @Override + public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + mechanicalState = new MechanicalAngularDevice.Input(input); + + return new MechanicalAngularDevice.Output(kT * electricalState.current); + } + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + electricalState = new ElectricalDevice.Output((input.voltage - mechanicalState.angularVelocity / kV) / motorResistance); + return electricalState; + } +} diff --git a/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java new file mode 100644 index 00000000..bf6295c0 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java @@ -0,0 +1,52 @@ +package com.team766.simulator.elements; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.interfaces.MechanicalDevice; +import com.team766.simulator.interfaces.PneumaticDevice; + +public class DoubleActingPneumaticCylinder implements PneumaticDevice, MechanicalDevice { + private static final Vector3D FORWARD = new Vector3D(1, 0, 0); + + private final double boreDiameter; + private final double stroke; + + private boolean isExtended = false; + private boolean commandExtended = false; + + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); + + public DoubleActingPneumaticCylinder(double boreDiameter, double stroke) { + this.boreDiameter = boreDiameter; + this.stroke = stroke; + } + + public void setExtended(boolean state) { + commandExtended = state; + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + pneumaticState = input; + PneumaticDevice.Output output; + double deviceVolume = boreArea() * stroke; + if (commandExtended != isExtended) { + output = new PneumaticDevice.Output(-deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE, deviceVolume); + } else { + output = new PneumaticDevice.Output(0, deviceVolume); + } + isExtended = commandExtended; + return output; + } + + @Override + public MechanicalDevice.Output step(MechanicalDevice.Input input) { + Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); + return new MechanicalDevice.Output(direction.scalarMultiply(boreArea() * pneumaticState.pressure)); + } + + private double boreArea() { + return Math.PI * Math.pow(boreDiameter / 2., 2); + } +} diff --git a/src/main/java/com/team766/simulator/elements/DriveBase.java b/src/main/java/com/team766/simulator/elements/DriveBase.java new file mode 100644 index 00000000..9dff5032 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/DriveBase.java @@ -0,0 +1,4 @@ +package com.team766.simulator.elements; + +public class DriveBase { +} diff --git a/src/main/java/com/team766/simulator/elements/ElectricalResistance.java b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java new file mode 100644 index 00000000..c4d3a621 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java @@ -0,0 +1,35 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.ElectricalDevice; + +public class ElectricalResistance implements ElectricalDevice { + // Wire AWG -> Ohms/m (copper) + // http://www.daycounter.com/Calculators/AWG.phtml + private static double[] WIRE_RESISTANCE_PER_M = new double[] { + 0.000323, 0.000407, 0.000513, 0.000647, 0.000815, 0.00103, 0.00130, 0.00163, 0.00206, 0.00260, // 0-9 + 0.00328, 0.00413, 0.00521, 0.00657, 0.00829, 0.0104, 0.0132, 0.0166, 0.0210, 0.0264, // 10-19 + 0.0333, 0.0420, 0.0530, 0.0668, 0.0842, 0.106, 0.134, 0.169, 0.213, 0.268, // 20-29 + 0.339, 0.427, 0.538, 0.679, 0.856, 1.08, 1.36, 1.72, 2.16, 2.73, 3.44, // 30-40 + }; + public static ElectricalResistance makeWires(int awg, double length, ElectricalDevice downstream) { + return new ElectricalResistance(WIRE_RESISTANCE_PER_M[awg] * length / 1000., downstream); + } + + private final double resistance; + + private ElectricalDevice downstream; + + private ElectricalDevice.Output state; + + public ElectricalResistance(double resistance, ElectricalDevice downstream) { + this.resistance = resistance; + this.downstream = downstream; + } + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage - resistance * state.current); + state = downstream.step(downstreamInput); + return state; + } +} diff --git a/src/main/java/com/team766/simulator/elements/Gears.java b/src/main/java/com/team766/simulator/elements/Gears.java new file mode 100644 index 00000000..220b00dc --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/Gears.java @@ -0,0 +1,26 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.MechanicalAngularDevice; + +public class Gears implements MechanicalAngularDevice { + // TODO: Add rotational inertia + // TODO: Add losses + + // Torque ratio (output / input) + private final double torqueRatio; + + private MechanicalAngularDevice upstream; + + public Gears(double torqueRatio, MechanicalAngularDevice upstream) { + this.torqueRatio = torqueRatio; + this.upstream = upstream; + } + + @Override + public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + MechanicalAngularDevice.Input upstreamInput = + new MechanicalAngularDevice.Input(input.angularVelocity * torqueRatio); + MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); + return new MechanicalAngularDevice.Output(upstreamOutput.torque * torqueRatio); + } +} diff --git a/src/main/java/com/team766/simulator/elements/MotorController.java b/src/main/java/com/team766/simulator/elements/MotorController.java new file mode 100644 index 00000000..d837e20a --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/MotorController.java @@ -0,0 +1,22 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.ElectricalDevice; + +public abstract class MotorController implements ElectricalDevice { + private ElectricalDevice downstream; + + public MotorController(ElectricalDevice downstream) { + this.downstream = downstream; + } + + // [-1, 1] representing the command sent from the application processor + protected abstract double getCommand(); + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + double command = getCommand(); + ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage * command); + ElectricalDevice.Output downstreamOutput = downstream.step(downstreamInput); + return new Output(downstreamOutput.current * Math.signum(command)); + } +} diff --git a/src/main/java/com/team766/simulator/elements/PwmMotorController.java b/src/main/java/com/team766/simulator/elements/PwmMotorController.java new file mode 100644 index 00000000..a0791220 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/PwmMotorController.java @@ -0,0 +1,21 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.interfaces.ElectricalDevice; + +public class PwmMotorController extends MotorController { + + private int channel; + + public PwmMotorController(int channel, ElectricalDevice downstream) { + super(downstream); + + this.channel = channel; + } + + @Override + protected double getCommand() { + return ProgramInterface.pwmChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java new file mode 100644 index 00000000..a8263dbf --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java @@ -0,0 +1,55 @@ +package com.team766.simulator.elements; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.interfaces.MechanicalDevice; +import com.team766.simulator.interfaces.PneumaticDevice; + +public class SingleActingPneumaticCylinder implements PneumaticDevice, MechanicalDevice { + private static final Vector3D FORWARD = new Vector3D(1, 0, 0); + + private final double boreDiameter; + private final double stroke; + private final double returnSpringForce; + + private boolean isExtended = false; + private boolean commandExtended = false; + + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); + + public SingleActingPneumaticCylinder(double boreDiameter, double stroke, double returnSpringForce) { + this.boreDiameter = boreDiameter; + this.stroke = stroke; + this.returnSpringForce = returnSpringForce; + } + + public void setExtended(boolean state) { + commandExtended = state; + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + pneumaticState = input; + PneumaticDevice.Output output; + double deviceVolume = isExtended ? boreArea() * stroke : 0; + if (isExtended && !commandExtended) { + output = new PneumaticDevice.Output(-deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE, deviceVolume); + } else { + output = new PneumaticDevice.Output(0, deviceVolume); + } + isExtended = commandExtended; + return output; + } + + @Override + public MechanicalDevice.Output step(MechanicalDevice.Input input) { + Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); + double force = isExtended ? boreArea() * pneumaticState.pressure : returnSpringForce; + return new MechanicalDevice.Output(direction.scalarMultiply(force)); + } + + private double boreArea() { + return Math.PI * Math.pow(boreDiameter / 2., 2); + } +} diff --git a/src/main/java/com/team766/simulator/elements/Wheel.java b/src/main/java/com/team766/simulator/elements/Wheel.java new file mode 100644 index 00000000..1f6efc18 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/Wheel.java @@ -0,0 +1,40 @@ +package com.team766.simulator.elements; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.Parameters; +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.interfaces.MechanicalAngularDevice; +import com.team766.simulator.interfaces.MechanicalDevice; + +// Simulate a wheel revolving around the positive Y axis. +public class Wheel implements MechanicalDevice { + // TODO: Add transverse friction + // TODO: Add traction limit/wheel slip (static vs kinetic friction) + // TODO: Add rotational inertia + + private static final Vector3D FORWARD = new Vector3D(-1, 0, 0); + + // Diameter of the wheel in meters + private final double diameter; + + private MechanicalAngularDevice upstream; + + public Wheel(double diameter, MechanicalAngularDevice upstream) { + this.diameter = diameter; + this.upstream = upstream; + } + + @Override + public MechanicalDevice.Output step(MechanicalDevice.Input input) { + MechanicalAngularDevice.Input upstreamInput = + new MechanicalAngularDevice.Input(FORWARD.dotProduct(input.velocity) * 2. / diameter); + MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); + double appliedForce = upstreamOutput.torque * 2. / diameter; + double maxFriction = Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION / Parameters.NUM_LOADED_WHEELS; + if (Math.abs(appliedForce) > maxFriction) { + appliedForce = Math.signum(appliedForce) * maxFriction; + } + return new MechanicalDevice.Output(FORWARD.scalarMultiply(appliedForce)); + } +} diff --git a/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java new file mode 100644 index 00000000..f4472268 --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java @@ -0,0 +1,27 @@ +package com.team766.simulator.interfaces; + +public interface ElectricalDevice { + public class Input { + public Input(double voltage) { + this.voltage = voltage; + } + public Input(Input other) { + voltage = other.voltage; + } + + public final double voltage; + } + + public class Output { + public Output(double current) { + this.current = current; + } + public Output(Output other) { + current = other.current; + } + + public final double current; + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java new file mode 100644 index 00000000..a3ea3526 --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java @@ -0,0 +1,27 @@ +package com.team766.simulator.interfaces; + +public interface MechanicalAngularDevice { + public class Input { + public Input(double angularVelocity) { + this.angularVelocity = angularVelocity; + } + public Input(Input other) { + this.angularVelocity = other.angularVelocity; + } + + public final double angularVelocity; + } + + public class Output { + public Output(double torque) { + this.torque = torque; + } + public Output(Output other) { + this.torque = other.torque; + } + + public final double torque; + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java new file mode 100644 index 00000000..c943b093 --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java @@ -0,0 +1,32 @@ +package com.team766.simulator.interfaces; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +public interface MechanicalDevice { + public class Input { + public Input(Vector3D position, Vector3D velocity) { + this.position = position; + this.velocity = velocity; + } + public Input(Input other) { + position = other.position; + velocity = other.velocity; + } + + public final Vector3D position; + public final Vector3D velocity; + } + + public class Output { + public Output(Vector3D force) { + this.force = force; + } + public Output(Output other) { + force = other.force; + } + + public final Vector3D force; + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java new file mode 100644 index 00000000..72a0fc4a --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java @@ -0,0 +1,40 @@ +package com.team766.simulator.interfaces; + +public interface PneumaticDevice { + public class Input { + public Input(double pressure) { + this.pressure = pressure; + } + public Input(Input other) { + pressure = other.pressure; + } + + // Pascals (relative pressure) + public final double pressure; + } + + public class Output { + public Output(double flowVolume, double deviceVolume) { + this.flowVolume = flowVolume; + this.deviceVolume = deviceVolume; + } + public Output(Output other) { + flowVolume = other.flowVolume; + deviceVolume = other.deviceVolume; + } + + // Volumetric flow (delta m^3 at atmospheric pressure) + // Positive flow is into the system, e.g. from a compressor + // Negative flow is out of the system, e.g. from venting to atmosphere + public final double flowVolume; + + // Volume of air that the device contains (m^3) + public final double deviceVolume; + + // Note that an expanding volume (such as a cylinder expanding) + // should increase volume, but have 0 flow volume because no + // pressurized air is actually leaving the system. + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java new file mode 100644 index 00000000..25a4de82 --- /dev/null +++ b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java @@ -0,0 +1,147 @@ +package com.team766.simulator.mechanisms; + +import org.apache.commons.math3.geometry.euclidean.threed.Rotation; +import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; +import org.apache.commons.math3.geometry.euclidean.threed.RotationOrder; +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.ElectricalSystem; +import com.team766.simulator.Parameters; +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.elements.DCMotor; +import com.team766.simulator.elements.DriveBase; +import com.team766.simulator.elements.Gears; +import com.team766.simulator.elements.PwmMotorController; +import com.team766.simulator.elements.MotorController; +import com.team766.simulator.elements.Wheel; +import com.team766.simulator.interfaces.MechanicalDevice; + +public class WestCoastDrive extends DriveBase { + private DCMotor leftMotor = DCMotor.makeCIM(); + private DCMotor rightMotor = DCMotor.makeCIM(); + + private MotorController leftController = new PwmMotorController(6, leftMotor); + private MotorController rightController = new PwmMotorController(4, rightMotor); + + private Gears leftGears = new Gears(Parameters.DRIVE_GEAR_RATIO, leftMotor); + private Gears rightGears = new Gears(Parameters.DRIVE_GEAR_RATIO, rightMotor); + + private Wheel leftWheels = new Wheel(Parameters.DRIVE_WHEEL_DIAMETER, leftGears); + private static final Vector3D LEFT_WHEEL_POSITION = new Vector3D(0., 0.3302, 0.); + private Wheel rightWheels = new Wheel(Parameters.DRIVE_WHEEL_DIAMETER, rightGears); + private static final Vector3D RIGHT_WHEEL_POSITION = new Vector3D(0., -0.3302, 0.); + private static final double WHEEL_BASE = 0.585; + private static final double ENCODER_TICKS_PER_METER = Parameters.ENCODER_TICKS_PER_REVOLUTION / (Parameters.DRIVE_WHEEL_DIAMETER * Math.PI); + + private Vector3D robotPosition = Vector3D.ZERO; + private Rotation robotRotation = Rotation.IDENTITY; + private Vector3D linearVelocity = Vector3D.ZERO; + private Vector3D angularVelocity = Vector3D.ZERO; + private Vector3D linearAcceleration = Vector3D.ZERO; + private Vector3D angularAcceleration = Vector3D.ZERO; + + private double leftEncoderResidual = 0; + private double rightEncoderResidual = 0; + + public WestCoastDrive(ElectricalSystem electricalSystem) { + electricalSystem.addDevice(leftController); + electricalSystem.addDevice(rightController); + } + + private static double softSignum(double x) { + x /= 0.01; + if (x > 1.0) { + x = 1.0; + } else if (x < -1.0) { + x = -1.0; + } + return x; + } + + public void step() { + Vector3D wheelForce; + Vector3D netForce = Vector3D.ZERO; + Vector3D netTorque = Vector3D.ZERO; + MechanicalDevice.Input leftWheelInput = new MechanicalDevice.Input( + LEFT_WHEEL_POSITION, + linearVelocity.scalarMultiply(-1.)); + wheelForce = leftWheels.step(leftWheelInput).force.scalarMultiply(-1.0); + netForce = netForce.add(wheelForce); + netTorque = netTorque.add(Vector3D.crossProduct(LEFT_WHEEL_POSITION, wheelForce)); + MechanicalDevice.Input rightWheelInput = new MechanicalDevice.Input( + RIGHT_WHEEL_POSITION, + linearVelocity.scalarMultiply(-1.)); + wheelForce = rightWheels.step(rightWheelInput).force.scalarMultiply(-1.0); + netForce = netForce.add(wheelForce); + netTorque = netTorque.add(Vector3D.crossProduct(RIGHT_WHEEL_POSITION, wheelForce)); + + Vector3D ego_velocity = robotRotation.applyInverseTo(linearVelocity); + + double rateLeft = ENCODER_TICKS_PER_METER * (ego_velocity.getX() - angularVelocity.getZ() * LEFT_WHEEL_POSITION.getNorm()); + double rateRight = ENCODER_TICKS_PER_METER * (ego_velocity.getX() + angularVelocity.getZ() * RIGHT_WHEEL_POSITION.getNorm()); + leftEncoderResidual += rateLeft * Parameters.TIME_STEP; + rightEncoderResidual += rateRight * Parameters.TIME_STEP; + ProgramInterface.encoderChannels[0].distance += (long)leftEncoderResidual; + ProgramInterface.encoderChannels[0].rate = rateLeft; + ProgramInterface.encoderChannels[2].distance += (long)rightEncoderResidual; + ProgramInterface.encoderChannels[2].rate = rateRight; + leftEncoderResidual %= 1; + rightEncoderResidual %= 1; + + ProgramInterface.gyro.angle = Math.toDegrees(robotRotation.getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2]); + ProgramInterface.gyro.rate = Math.toDegrees(angularVelocity.getZ()); + + Vector3D rollingResistance = new Vector3D(-softSignum(ego_velocity.getX()), 0.0, 0.0).scalarMultiply( + Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION * Parameters.ROLLING_RESISTANCE); + netForce = netForce.add(rollingResistance); + + Vector3D transverseFriction = new Vector3D(0., -softSignum(ego_velocity.getY()), 0.).scalarMultiply( + Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION); + netForce = netForce.add(transverseFriction); + + double maxFriction = Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION * Parameters.TURNING_RESISTANCE_FACTOR; + netTorque = netTorque.add( + new Vector3D(0, 0, -softSignum(angularVelocity.getZ())).scalarMultiply( + maxFriction * WHEEL_BASE / 2)); + + linearAcceleration = robotRotation.applyTo(netForce).scalarMultiply(1.0 / Parameters.ROBOT_MASS); + linearVelocity = linearVelocity.add(linearAcceleration.scalarMultiply(Parameters.TIME_STEP)); + robotPosition = robotPosition.add(linearVelocity.scalarMultiply(Parameters.TIME_STEP)); + + angularAcceleration = netTorque.scalarMultiply(1.0 / Parameters.ROBOT_MOMENT_OF_INERTIA); + angularVelocity = angularVelocity.add(angularAcceleration.scalarMultiply(Parameters.TIME_STEP)); + Vector3D angularDelta = angularVelocity.scalarMultiply(Parameters.TIME_STEP); + robotRotation = robotRotation.compose( + new Rotation(RotationOrder.XYZ, + RotationConvention.VECTOR_OPERATOR, + angularDelta.getX(), + angularDelta.getY(), + angularDelta.getZ()), + RotationConvention.VECTOR_OPERATOR); + } + + public Vector3D getPosition() { + return robotPosition; + } + + public Rotation getRotation() { + return robotRotation; + } + + public Vector3D getLinearVelocity() { + return linearVelocity; + } + + public Vector3D getAngularVelocity() { + return angularVelocity; + } + + public Vector3D getLinearAcceleration() { + return linearAcceleration; + } + + public Vector3D getAngularAcceleration() { + return angularAcceleration; + } +} diff --git a/src/main/java/com/team766/simulator/ui/Metrics.java b/src/main/java/com/team766/simulator/ui/Metrics.java new file mode 100644 index 00000000..2615c6ea --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/Metrics.java @@ -0,0 +1,160 @@ +package com.team766.simulator.ui; + +import java.awt.BorderLayout; +import java.awt.Color; +import java.awt.event.ActionEvent; +import java.awt.event.ActionListener; +import java.awt.event.KeyEvent; +import java.awt.event.KeyListener; +import java.awt.event.MouseAdapter; +import java.awt.event.MouseEvent; +import java.util.Arrays; +import java.util.Collection; + +import javax.swing.JFrame; +import javax.swing.JPanel; +import javax.swing.JSlider; +import javax.swing.Timer; + +import com.team766.simulator.Parameters; + +import de.erichseifert.gral.data.DataSeries; +import de.erichseifert.gral.data.DataSource; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; +import de.erichseifert.gral.plots.lines.DefaultLineRenderer2D; +import de.erichseifert.gral.plots.lines.LineRenderer; +import de.erichseifert.gral.ui.InteractivePanel; + +@SuppressWarnings("serial") +public class Metrics extends JPanel { + // Color palette from http://www.mulinblog.com/a-color-palette-optimized-for-data-visualization/ + private static final String[] COLORS = { + "#4D4D4D", // gray + "#5DA5DA", // blue + "#FAA43A", // orange + "#60BD68", // green + "#F17CB0", // pink + "#B2912F", // brown + "#B276B2", // purple + "#DECF3F", // yellow + "#F15854", // red + }; + + private static class Inspector extends MouseAdapter implements KeyListener { + private int sourceIndex = 0; + private double selectedTime = Double.NaN; + private XYPlot plot; + + public Inspector(XYPlot plot) { + this.plot = plot; + } + + void update() { + if (!Double.isNaN(selectedTime)) { + DataSource source = plot.getData().get(sourceIndex); + int index = Arrays.binarySearch(source.getColumn(0).toArray(null), selectedTime); + if (index < 0) { + index = -index - 1; + } + System.out.println(String.format("(%s, %f): %f", source.getName(), selectedTime, source.get(1, index))); + } + } + + @Override + public void mouseClicked(MouseEvent e) { + double x = e.getX() - plot.getPlotArea().getX(); + selectedTime = plot.getAxisRenderer(XYPlot.AXIS_X).viewToWorld(plot.getAxis(XYPlot.AXIS_X), x, false).doubleValue(); + + update(); + } + + @Override + public void keyTyped(KeyEvent e) { + if (e.getKeyChar() >= '1' && e.getKeyChar() <= '9') { + int index = e.getKeyChar() - '1'; + if (index < plot.getData().size()) { + sourceIndex = index; + System.out.println("Selected " + plot.getData().get(sourceIndex).getName()); + update(); + } + } + } + + @Override + public void keyReleased(KeyEvent e) {} + + @Override + public void keyPressed(KeyEvent e) {} + } + + public static JFrame makePlotFrame(Collection series, String[] labels) { + JFrame frame = new JFrame(); + frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); + frame.setSize(800, 600); + frame.setContentPane(new Metrics(series, labels)); + frame.setVisible(true); + return frame; + } + + XYPlot plot; + JSlider slider; + DataTable data; + JPanel plotPanel; + Timer playbackTimer; + + public Metrics(Collection series, String[] labels) { + Double[] first = series.iterator().next(); + @SuppressWarnings("unchecked") + Class[] types = new Class[first.length]; + Arrays.fill(types, Double.class); + data = new DataTable(types); + for (Double[] values : series) { + if (first.length != values.length) { + throw new IllegalArgumentException("Data values must be the same length"); + } + data.add(values); + } + if (first.length - 1 != labels.length) { + throw new IllegalArgumentException("Number of labels does not match the size of data values"); + } + DataSource[] sources = new DataSource[labels.length]; + for (int i = 0; i < labels.length; ++i) { + sources[i] = new DataSeries(labels[i], data, 0, i + 1); + } + plot = new XYPlot(sources); + int colorIndex = 0; + for (DataSource source : sources) { + LineRenderer lines = new DefaultLineRenderer2D(); + plot.setLineRenderers(source, lines); + Color color = Color.decode(COLORS[colorIndex++ % COLORS.length]); + plot.getPointRenderers(source).get(0).setColor(color); + plot.getLineRenderers(source).get(0).setColor(color); + } + plot.setLegendVisible(true); + + InteractivePanel panel = new InteractivePanel(plot); + plotPanel = panel; + setLayout(new BorderLayout()); + add(panel, BorderLayout.CENTER); + + final int TIMER_PERIOD_MS = 50; + playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; + int newValue = slider.getValue() + (int)deltaSteps; + if (newValue > slider.getMaximum()) { + newValue = slider.getMaximum(); + playbackTimer.stop(); + } + slider.setValue(newValue); + } + }); + playbackTimer.setRepeats(true); + + Inspector inspector = new Inspector(plot); + addKeyListener(inspector); + panel.addMouseListener(inspector); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ui/Trajectory.java b/src/main/java/com/team766/simulator/ui/Trajectory.java new file mode 100644 index 00000000..bc97b9fe --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/Trajectory.java @@ -0,0 +1,143 @@ +package com.team766.simulator.ui; + +import java.awt.BorderLayout; +import java.awt.Color; +import java.awt.Graphics; +import java.awt.Graphics2D; +import java.awt.event.ActionEvent; +import java.awt.event.ActionListener; +import java.awt.geom.AffineTransform; +import java.util.Arrays; +import java.util.Collection; + +import javax.swing.BoxLayout; +import javax.swing.JButton; +import javax.swing.JFrame; +import javax.swing.JPanel; +import javax.swing.JSlider; +import javax.swing.Timer; +import javax.swing.event.ChangeEvent; +import javax.swing.event.ChangeListener; + +import com.team766.simulator.Parameters; + +import de.erichseifert.gral.data.DataSeries; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; +import de.erichseifert.gral.ui.InteractivePanel; + +@SuppressWarnings("serial") +public class Trajectory extends JPanel { + public static JFrame makePlotFrame(Collection series) { + JFrame frame = new JFrame(); + frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); + frame.setSize(800, 600); + frame.setContentPane(new Trajectory(series)); + frame.setVisible(true); + return frame; + } + + XYPlot plot; + JSlider slider; + DataTable data; + JPanel plotPanel; + Timer playbackTimer; + + public Trajectory(Collection series) { + Double[] first = series.iterator().next(); + @SuppressWarnings("unchecked") + Class[] types = new Class[first.length]; + Arrays.fill(types, Double.class); + data = new DataTable(types); + for (Double[] values : series) { + if (first.length != values.length) { + throw new IllegalArgumentException("Data values must be the same length"); + } + data.add(values); + } + plot = new XYPlot(new DataSeries("Trajectory", data, 0, 1)); + plot.getAxis(XYPlot.AXIS_X).setRange(-10.0, 10.0); + plot.getAxis(XYPlot.AXIS_Y).setRange(-10.0, 10.0); + + InteractivePanel panel = new InteractivePanel(plot); + plotPanel = panel; + setLayout(new BorderLayout()); + add(panel, BorderLayout.CENTER); + + final int TIMER_PERIOD_MS = 50; + playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; + int newValue = slider.getValue() + (int)deltaSteps; + if (newValue > slider.getMaximum()) { + newValue = slider.getMaximum(); + playbackTimer.stop(); + } + slider.setValue(newValue); + } + }); + playbackTimer.setRepeats(true); + + JPanel controlsPanel = new JPanel(); + controlsPanel.setLayout(new BoxLayout(controlsPanel, BoxLayout.LINE_AXIS)); + slider = new JSlider(0, data.getRowCount() - 1); + slider.setValue(0); + slider.addChangeListener(new ChangeListener() { + public void stateChanged(ChangeEvent e) { + Trajectory.this.repaint(); + } + }); + controlsPanel.add(slider); + JButton playButton = new JButton(">"); + playButton.addActionListener(new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + if (playbackTimer.isRunning()) { + playbackTimer.stop(); + } else { + playbackTimer.start(); + if (slider.getValue() == slider.getMaximum()) { + slider.setValue(slider.getMinimum()); + } + } + } + }); + controlsPanel.add(playButton); + add(controlsPanel, BorderLayout.SOUTH); + } + + @Override + public void paint(Graphics g) { + super.paint(g); + + int slider_value = slider.getValue(); + double x = (Double)data.get(0, slider_value); + double y = (Double)data.get(1, slider_value); + double orientation = (Double)data.get(2, slider_value); + double vel_x = (Double)data.get(3, slider_value); + double vel_y = (Double)data.get(4, slider_value); + + double pixelX = plot.getAxisRenderer(XYPlot.AXIS_X).worldToView(plot.getAxis(XYPlot.AXIS_X), x, false); + double pixelY = plot.getAxisRenderer(XYPlot.AXIS_Y).worldToView(plot.getAxis(XYPlot.AXIS_Y), y, false); + + double plotAreaHeight = plot.getPlotArea().getHeight(); + double plotAreaX = plot.getPlotArea().getX(); + double plotAreaY = plot.getPlotArea().getY(); + + pixelX = plotAreaX + pixelX; + pixelY = plotAreaY + plotAreaHeight - pixelY; + + Graphics2D g2d = (Graphics2D)g; + + final int SIZE_X = 30; + final int SIZE_Y = 20; + g2d.setColor(new Color(128, 128, 255)); + AffineTransform saveXf = g2d.getTransform(); + g2d.rotate(-orientation, pixelX, pixelY); + g2d.fillRect((int)pixelX - SIZE_X / 2, (int)pixelY - SIZE_Y / 2, SIZE_X, SIZE_Y); + g2d.setTransform(saveXf); + //g2d.setColor(Color.red); + //g2d.drawLine((int)pixelX, (int)pixelY, (int)(pixelX + vel_x * 20), (int)(pixelY - vel_y * 20)); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/web/AutonomousSelector.java b/src/main/java/com/team766/web/AutonomousSelector.java new file mode 100644 index 00000000..22170e55 --- /dev/null +++ b/src/main/java/com/team766/web/AutonomousSelector.java @@ -0,0 +1,96 @@ +package com.team766.web; + +import java.util.Arrays; +import java.util.Map; +import java.util.Optional; +import java.util.stream.Collectors; +import com.team766.framework.AutonomousMode; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public class AutonomousSelector implements WebServer.Handler { + private static final String ENDPOINT = "/auton"; + + private final AutonomousMode[] m_autonModes; + private final String[] m_autonModeNames; + private AutonomousMode m_selectedAutonMode; + + public AutonomousSelector(AutonomousMode[] autonModes) { + m_autonModes = autonModes; + m_autonModeNames = + Arrays.stream(autonModes).map(m -> m.name()).toArray(String[]::new); + if (m_autonModeNames.length > 0) { + m_selectedAutonMode = m_autonModes[0]; + } else { + Logger.get(Category.AUTONOMOUS).logRaw( + Severity.WARNING, + "No autonomous modes were declared in AutonomousModes.java"); + m_selectedAutonMode = null; + } + } + + public AutonomousMode getSelectedAutonMode() { + return m_selectedAutonMode; + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String handle(Map params) { + String locationReplaceScript = ""; + { + final String selectedAutonModeName = (String)params.get("AutoMode"); + if (selectedAutonModeName != null) { + final Optional selectedAutonMode = + Arrays.stream(m_autonModes).filter(m -> m.name().equals(selectedAutonModeName)).findFirst(); + if (selectedAutonMode.isEmpty()) { + Logger.get(Category.AUTONOMOUS).logData( + Severity.ERROR, + "Internal framework error: Inconsistent name for selected autonomous mode (selected: %s ; available: %s). Autonomous mode will not run.", + selectedAutonModeName, + Arrays.stream(m_autonModes).map(m -> m.name()).collect(Collectors.joining(","))); + } else { + m_selectedAutonMode = selectedAutonMode.get().clone(); + } + + locationReplaceScript = ""; + } + } + + final String selectedAutonModeName = m_selectedAutonMode != null ? m_selectedAutonMode.name() : ""; + return String.join("\n", new String[]{ + locationReplaceScript, + "

Autonomous Mode Selector

", + "

Current Mode: " + selectedAutonModeName + "

", + "
", + "

" + HtmlElements.buildDropDown("AutoMode", selectedAutonModeName, m_autonModeNames) + "

", + "
", + "", + }); + } + + @Override + public String title() { + return "Autonomous Selector"; + } +} diff --git a/src/main/java/com/team766/web/ConfigUI.java b/src/main/java/com/team766/web/ConfigUI.java new file mode 100644 index 00000000..86dfe69f --- /dev/null +++ b/src/main/java/com/team766/web/ConfigUI.java @@ -0,0 +1,89 @@ +package com.team766.web; + +import java.util.ArrayList; +import java.util.Map; +import com.team766.config.ConfigFileReader; +import com.team766.config.ConfigValueParseException; + +public class ConfigUI implements WebServer.Handler { + @Override + public String endpoint() { + return "/config"; + } + + @Override + public String handle(Map params) { + String r = "

Configuration

"; + + r += "
\n"; + if (params.containsKey("configJson")) { + String configJsonString = (String)params.get("configJson"); + ArrayList validationErrors = new ArrayList(); + try { + ConfigFileReader.getInstance().reloadFromJson(configJsonString); + } catch (ConfigValueParseException ex) { + validationErrors.add(ex.toString()); + } catch (Exception ex) { + validationErrors.add("Failed to parse config json: " + ex); + } + if (validationErrors.isEmpty()) { + r += "

New configuration (v" + ConfigFileReader.getInstance().getGeneration() + ") has been applied

"; + r += "

Remember to click Restart Robot Code in the driver station if you have changed any motor/sensor settings

"; + if (params.containsKey("saveToFile")) { + try { + ConfigFileReader.getInstance().saveFile(configJsonString); + } catch (Exception ex) { + validationErrors.add("Could not save config file: " + ex.toString()); + } + } + } + if (validationErrors.size() > 0) { + r += "

Errors:\n"; + r += "

    \n"; + for (String error : validationErrors) { + r += "
  • " + error + "
  • \n"; + } + r += "

\n"; + } + } + r += "
\n"; + + r += String.join("\n", new String[]{ + "", + }); + + r += "
\n"; + r += "\n"; + r += "

Save to config file on robot?

\n"; + r += "

\n"; + + return r; + } + + @Override + public String title() { + return "Config Values"; + } +} diff --git a/src/main/java/com/team766/web/Dashboard.java b/src/main/java/com/team766/web/Dashboard.java new file mode 100644 index 00000000..e6d1bad5 --- /dev/null +++ b/src/main/java/com/team766/web/Dashboard.java @@ -0,0 +1,60 @@ +package com.team766.web; + +import java.util.Map; +import com.team766.web.dashboard.Widget; + +public class Dashboard implements WebServer.Handler { + private static final String ENDPOINT = "/dashboard"; + + static String makeDashboardPage() { + String page = "

Dashboard Widgets

\n"; + page += "
\n"; + for (var widget : Widget.listWidgets()) { + page += widget.render(); + page += '\n'; + } + page += "
\n"; + page += String.join("\n", new String[]{ + "", + }); + return page; + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String title() { + return "Dashboard"; + } + + @Override + public String handle(Map params) { + return makeDashboardPage(); + } + + @Override + public boolean showInMenu() { + return false; + } +} diff --git a/src/main/java/com/team766/web/DriverInterface.java b/src/main/java/com/team766/web/DriverInterface.java new file mode 100644 index 00000000..9c49086e --- /dev/null +++ b/src/main/java/com/team766/web/DriverInterface.java @@ -0,0 +1,30 @@ +package com.team766.web; + +import java.util.Map; + +public class DriverInterface implements WebServer.Handler { + + AutonomousSelector autonomousSelector; + + public DriverInterface(AutonomousSelector autonomousSelector) { + this.autonomousSelector = autonomousSelector; + } + + @Override + public String endpoint() { + return "/driver"; + } + + @Override + public String title() { + return "Driver Interface"; + } + + @Override + public String handle(Map params) { + return Dashboard.makeDashboardPage() + + LogViewer.makeAllErrorsPage() + + autonomousSelector.handle(params); + } + +} diff --git a/src/main/java/com/team766/web/HtmlElements.java b/src/main/java/com/team766/web/HtmlElements.java new file mode 100644 index 00000000..010d8c77 --- /dev/null +++ b/src/main/java/com/team766/web/HtmlElements.java @@ -0,0 +1,31 @@ +package com.team766.web; + +class HtmlElements { + public static String buildDropDown(String valueName, String current, String... options){ + String id = valueName.replace(' ', '_'); + String out = ""; + } + + public static String buildForm(String valueName, double v){ + return buildForm(valueName, Double.toString(v)); + } + + public static String buildForm(String valueName, String v){ + String id = valueName.replace(' ', '_'); + return "" + + ""; + } + + public static String buildForm(String valueName){ + return buildForm(valueName, 0.0); + } +} diff --git a/src/main/java/com/team766/web/LogViewer.java b/src/main/java/com/team766/web/LogViewer.java new file mode 100644 index 00000000..8738594c --- /dev/null +++ b/src/main/java/com/team766/web/LogViewer.java @@ -0,0 +1,109 @@ +package com.team766.web; + +import java.text.SimpleDateFormat; +import java.util.Arrays; +import java.util.Date; +import java.util.Map; +import java.util.stream.Stream; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LogEntry; +import com.team766.logging.LogEntryRenderer; +import com.team766.logging.Severity; + +public class LogViewer implements WebServer.Handler { + private static final String ENDPOINT = "/logs"; + private static final String ALL_ERRORS_NAME = "All Errors"; + + private static final SimpleDateFormat timeFormat = new SimpleDateFormat("yyyy-MM-dd HH:mm:ss"); + + private static String makeLogEntriesTable(Iterable entries) { + String r = "\n"; + for (LogEntry entry : entries) { + r += String.format( + "\n", + entry.getCategory(), timeFormat.format(new Date(entry.getTime() / 1000000)), entry.getSeverity(), LogEntryRenderer.renderLogEntry(entry, null)); + } + r += "
%s%s%s%s
"; + return r; + } + + private static String makePage(String categoryName, Iterable entries) { + return String.join("\n", new String[]{ + "

Log: " + categoryName + "

", + "

", + HtmlElements.buildDropDown( + "category", + categoryName, + Stream.concat( + Stream.of(ALL_ERRORS_NAME), + Arrays.stream(Category.values()).map(Category::name) + ).toArray(String[]::new)), + "", + "

", + makeLogEntriesTable(entries), + "", + "", + "", + "", + }); + } + + static String makeAllErrorsPage() { + return makePage( + ALL_ERRORS_NAME, + Arrays.stream(Category.values()) + .flatMap(category -> Logger.get(category).recentEntries().stream()) + .filter(entry -> entry.getSeverity() == Severity.ERROR) + ::iterator); + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String handle(Map params) { + String categoryName = (String)params.get("category"); + if (categoryName == null || categoryName.equals(ALL_ERRORS_NAME)) { + return makeAllErrorsPage(); + } else { + Category category = Enum.valueOf(Category.class, categoryName); + return makePage(category.name(), Logger.get(category).recentEntries()); + } + } + + @Override + public String title() { + return "Log Viewer"; + } +} diff --git a/src/main/java/com/team766/web/ReadLogs.java b/src/main/java/com/team766/web/ReadLogs.java new file mode 100644 index 00000000..91aca8a7 --- /dev/null +++ b/src/main/java/com/team766/web/ReadLogs.java @@ -0,0 +1,158 @@ +package com.team766.web; + +import java.io.EOFException; +import java.io.File; +import java.io.IOException; +import java.text.NumberFormat; +import java.util.Arrays; +import java.util.HashMap; +import java.util.Iterator; +import java.util.Locale; +import java.util.Map; +import java.util.function.Function; +import java.util.stream.Stream; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LogEntry; +import com.team766.logging.LogEntryRenderer; +import com.team766.logging.LogReader; +import com.team766.logging.Severity; + +public class ReadLogs implements WebServer.Handler { + private static final String ENDPOINT = "/readlogs"; + private static final String ALL_ERRORS_NAME = "All Errors"; + private static final int ENTRIES_PER_PAGE = 100; + + private HashMap logReaders = new HashMap(); + private HashMap readerDescriptions = new HashMap(); + private HashMap> readerStreams = new HashMap>(); + + private static String makeLogEntriesTable(LogReader reader, Iterator entries) { + String r = "\n"; + for (int i = 0; i < ENTRIES_PER_PAGE; ++i) { + if (!entries.hasNext()) { + break; + } + LogEntry entry = entries.next(); + r += String.format( + "\n", + entry.getCategory(), entry.getTime(), entry.getSeverity(), LogEntryRenderer.renderLogEntry(entry, reader)); + } + r += "
%s%s%s%s
"; + return r; + } + + private String makePage(String id) { + String r = String.join("\n", new String[]{ + "

Free disk space: " + + NumberFormat.getNumberInstance(Locale.US).format( + new File(Logger.logFilePathBase).getUsableSpace()) + + "

", + "

", + HtmlElements.buildDropDown( + "logFile", + "", + Logger.logFilePathBase == null + ? new String[0] + : new File(Logger.logFilePathBase).list()), + HtmlElements.buildDropDown( + "category", + "", + Stream.concat( + Stream.of("", ALL_ERRORS_NAME), + Arrays.stream(Category.values()).map(Category::name) + ).toArray(String[]::new)), + "", + "

", + }); + if (id != null) { + r += String.join("\n", new String[]{ + "

Log: " + readerDescriptions.get(id) + "

", + makeLogEntriesTable(logReaders.get(id), readerStreams.get(id)), + "", + }); + } + return r; + } + + private String makeReader( + String logFile, + String description, + Function, Stream> filter + ) { + LogReader reader; + try { + reader = new LogReader(new File(Logger.logFilePathBase, logFile).getAbsolutePath()); + } catch (IOException e) { + throw new RuntimeException(e); + } + String id = Integer.toString(logReaders.size()); + logReaders.put(id, reader); + readerDescriptions.put(id, logFile + " " + description); + readerStreams.put(id, filter.apply(Stream.generate(() -> { + try { + return reader.readNext(); + } catch (EOFException e) { + return null; + } catch (IOException e) { + throw new RuntimeException(e); + } + }).takeWhile(e -> e != null)).iterator()); + return id; + } + + private String makeUnfilteredReader(String logFile) { + return makeReader( + logFile, + "", + s -> s + ); + } + + private String makeCategoryReader(String logFile, Category category) { + return makeReader( + logFile, + category.name(), + s -> s.filter(e -> e.getCategory() == category) + ); + } + + private String makeAllErrorsReader(String logFile) { + return makeReader( + logFile, + ALL_ERRORS_NAME, + s -> s.filter(entry -> entry.getSeverity() == Severity.ERROR) + ); + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String handle(Map params) { + String id = (String)params.get("id"); + String logFile = (String)params.get("logFile"); + String categoryName = (String)params.get("category"); + if (!logReaders.containsKey(id)) { + id = null; + } + if (logFile != null) { + if (categoryName == null || categoryName.equals("")) { + id = makeUnfilteredReader(logFile); + } else if (categoryName.equals(ALL_ERRORS_NAME)) { + id = makeAllErrorsReader(logFile); + } else { + Category category = Enum.valueOf(Category.class, categoryName); + id = makeCategoryReader(logFile, category); + } + } + return makePage(id); + } + + @Override + public String title() { + return "Log Reader"; + } +} diff --git a/src/main/java/com/team766/web/WebServer.java b/src/main/java/com/team766/web/WebServer.java new file mode 100644 index 00000000..56e59fed --- /dev/null +++ b/src/main/java/com/team766/web/WebServer.java @@ -0,0 +1,213 @@ +package com.team766.web; + +import java.io.BufferedReader; +import java.io.IOException; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.io.UnsupportedEncodingException; +import java.net.InetSocketAddress; +import java.net.URI; +import java.net.URLDecoder; +import java.util.ArrayList; +import java.util.HashMap; +import java.util.LinkedHashMap; +import java.util.List; +import java.util.Map; + +import com.sun.net.httpserver.HttpExchange; +import com.sun.net.httpserver.HttpHandler; +import com.sun.net.httpserver.HttpServer; + +/* + * Creates an HTTP Server on the robot that can change the + * settings of it. It is initially just used to change robot + * values. Hopefully this will be later updated to support + * graphing and even small changes in the robot's actual code. + * + * Can be reached at: + * roboRio-766.local:5800/values + */ + +public class WebServer { + + public interface Handler { + String endpoint(); + default boolean showInMenu() { return true; } + String title(); + String handle(Map params); + } + + private HttpServer server; + private LinkedHashMap pages = new LinkedHashMap(); + + public WebServer() { + addHandler(new Handler() { + @Override + public String endpoint() { + return "/"; + } + + @Override + public String title() { + return "Menu"; + } + + @Override + public boolean showInMenu() { + return false; + } + + @Override + public String handle(Map params) { + return ""; + } + }); + } + + public void addHandler(Handler handler) { + pages.put(handler.endpoint(), handler); + } + + public void start(){ + try { + server = HttpServer.create(new InetSocketAddress(5800), 0); + } catch (IOException e) { + throw new RuntimeException(e); + } + for (Map.Entry page : pages.entrySet()) { + HttpHandler httpHandler = new HttpHandler() { + @Override + public void handle(HttpExchange exchange) throws IOException { + Map params = parseParams(exchange); + String response = ""; + response += buildPageHeader(); + try { + response += page.getValue().handle(params); + } catch (Exception ex) { + ex.printStackTrace(); + throw ex; + } + response += ""; + exchange.sendResponseHeaders(200, response.getBytes().length); + try (OutputStream os = exchange.getResponseBody()) { + os.write(response.getBytes()); + } + } + }; + server.createContext(page.getKey(), httpHandler); + } + addLineNumbersSvgHandler(); + server.start(); + } + + protected String buildPageHeader() { + String result = ""; + result += "\n"; + result += "

\n"; + for (Map.Entry page : pages.entrySet()) { + if (page.getValue().showInMenu()) + result += String.format("%s
\n", page.getKey(), page.getValue().title()); + } + result += "

\n"; + return result; + } + + private void addLineNumbersSvgHandler() { + HttpHandler httpHandler = new HttpHandler() { + @Override + public void handle(HttpExchange exchange) throws IOException { + String response = "\n"; + response += "\n"; + response += "\n"; + response += "\n"; + for (int i = 1; i < 1000; ++i) { + response += "" + i + ".\n"; + } + response += "\n"; + response += ""; + exchange.getResponseHeaders().set("Content-Type", "image/svg+xml"); + exchange.sendResponseHeaders(200, response.getBytes().length); + try (OutputStream os = exchange.getResponseBody()) { + os.write(response.getBytes()); + } + } + }; + server.createContext("/line_numbers.svg", httpHandler); + } + + public Map parseParams(HttpExchange exchange) throws IOException { + Map parameters = new HashMap(); + parseGetParameters(exchange, parameters); + parsePostParameters(exchange, parameters); + return parameters; + } + + private void parseGetParameters(HttpExchange exchange, Map parameters) + throws UnsupportedEncodingException { + URI requestedUri = exchange.getRequestURI(); + String query = requestedUri.getRawQuery(); + parseQuery(query, parameters); + } + + private void parsePostParameters(HttpExchange exchange, Map parameters) + throws IOException { + + if ("post".equalsIgnoreCase(exchange.getRequestMethod())) { + InputStreamReader isr = + new InputStreamReader(exchange.getRequestBody(), "utf-8"); + BufferedReader br = new BufferedReader(isr); + String query = br.readLine(); + parseQuery(query, parameters); + } + } + + private void parseQuery(String query, Map parameters) + throws UnsupportedEncodingException { + + if (query != null) { + String pairs[] = query.split("[&]"); + + for (String pair : pairs) { + String param[] = pair.split("[=]"); + + String key = null; + String value = null; + if (param.length > 0) { + key = URLDecoder.decode(param[0], System.getProperty("file.encoding")); + } + + if (param.length > 1) { + value = URLDecoder.decode(param[1], System.getProperty("file.encoding")); + } + + if (parameters.containsKey(key)) { + Object obj = parameters.get(key); + if(obj instanceof List) { + @SuppressWarnings("unchecked") + List values = (List)obj; + + values.add(value); + } else if(obj instanceof String) { + List values = new ArrayList(); + values.add((String)obj); + values.add(value); + parameters.put(key, values); + } + } else { + parameters.put(key, value); + } + } + } + } +} diff --git a/src/main/java/com/team766/web/dashboard/NewSection.java b/src/main/java/com/team766/web/dashboard/NewSection.java new file mode 100644 index 00000000..69655dea --- /dev/null +++ b/src/main/java/com/team766/web/dashboard/NewSection.java @@ -0,0 +1,30 @@ +package com.team766.web.dashboard; + +public class NewSection extends Widget { + private String m_name; + + public NewSection() { + this("", DEFAULT_SORT_ORDER); + } + + public NewSection(String name) { + this(name, DEFAULT_SORT_ORDER); + } + + public NewSection(String name, int sortOrder) { + super(sortOrder); + + m_name = name; + } + + @Override + public String render() { + String page = "
"; + if (!m_name.isEmpty()) { + page += "

" + m_name + "

"; + } + page += "
"; + return page; + } + +} diff --git a/src/main/java/com/team766/web/dashboard/StatusLight.java b/src/main/java/com/team766/web/dashboard/StatusLight.java new file mode 100644 index 00000000..57de7cb3 --- /dev/null +++ b/src/main/java/com/team766/web/dashboard/StatusLight.java @@ -0,0 +1,45 @@ +package com.team766.web.dashboard; + +public class StatusLight extends Widget { + private String m_name; + private String m_color = "gray"; + private int m_width = 150; + private int m_height = 150; + private String m_style = ""; + + public StatusLight(String name) { + this(name, DEFAULT_SORT_ORDER); + } + + public StatusLight(String name, int sortOrder) { + super(sortOrder); + + m_name = name; + } + + public void setName(String name) { + m_name = name; + } + + public void setSize(int width, int height) { + m_width = width; + m_height = height; + } + + public void setColor(String color) { + m_color = color; + } + + public void setStyle(String style) { + m_style = style; + } + + @Override + public String render() { + return "
" + m_name + "
"; + } +} diff --git a/src/main/java/com/team766/web/dashboard/Widget.java b/src/main/java/com/team766/web/dashboard/Widget.java new file mode 100644 index 00000000..3a2573ca --- /dev/null +++ b/src/main/java/com/team766/web/dashboard/Widget.java @@ -0,0 +1,31 @@ +package com.team766.web.dashboard; + +import java.util.Collections; +import java.util.Map; +import java.util.WeakHashMap; +import java.util.stream.Collectors; + +public abstract class Widget { + public static final int DEFAULT_SORT_ORDER = 0; + + private static int c_orderCounter = 0; + private static Map c_widgets = + Collections.synchronizedMap(new WeakHashMap()); + + public static Iterable listWidgets() { + synchronized (c_widgets) { + return c_widgets.entrySet().stream() + .sorted(Map.Entry.comparingByValue()) + .map(Map.Entry::getKey) + .collect(Collectors.toList()); + } + } + + public Widget(int sortOrder) { + synchronized (c_widgets) { + c_widgets.put(this, (((long)sortOrder) << 32) | (c_orderCounter++)); + } + } + + public abstract String render(); +} diff --git a/src/main/proto/com/team766/logging/logging.proto b/src/main/proto/com/team766/logging/logging.proto new file mode 100644 index 00000000..40dc4b72 --- /dev/null +++ b/src/main/proto/com/team766/logging/logging.proto @@ -0,0 +1,63 @@ +syntax = "proto2"; + +package com.team766.logging; + +option java_multiple_files = true; + +message LogEntry { + // Time as nanoseconds since January 1, 1970, 00:00:00 GMT + optional int64 time = 1; + optional Severity severity = 2; + optional Category category = 3; + + optional string message_str = 6; + optional int32 message_index = 7; + repeated LogValue arg = 8; +} + +enum Severity { + DEBUG = 10; + INFO = 20; + WARNING = 30; + ERROR = 40; +} + +enum Category { + // Don't change the numbers. When adding a new option, just use the next + // available number. + JAVA_EXCEPTION = 0; + FRAMEWORK = 1; + HAL = 2; + CONFIGURATION = 3; + MECHANISMS = 4; + PROCEDURES = 5; + AUTONOMOUS = 6; + CAMERA = 7; + PID_CONTROLLER = 8; + TRAJECTORY = 9; + OPERATOR_INTERFACE = 10; + DRIVE = 11; +} + +// `Value` represents a dynamically typed value which can be either a number, +// a string, a boolean, or a list of values. Absence of all fields indicates +// a null value. +message LogValue { + oneof kind { + int64 int_value = 1; + // Represents a double value. + double float_value = 2; + // Represents a string value. + string string_value = 3; + // Represents a boolean value. + bool bool_value = 4; + // Represents an array or list. + LogListValue list = 5; + + // Add schemas for other serialized types here + } +} + +message LogListValue { + repeated LogValue element = 1; +} \ No newline at end of file diff --git a/src/test/java/com/team766/TestCase.java b/src/test/java/com/team766/TestCase.java new file mode 100644 index 00000000..a81de41c --- /dev/null +++ b/src/test/java/com/team766/TestCase.java @@ -0,0 +1,22 @@ +package com.team766; + +import com.team766.config.ConfigFileReader; +import com.team766.framework.Scheduler; +import com.team766.hal.RobotProvider; +import com.team766.hal.mock.TestRobotProvider; + +public abstract class TestCase extends junit.framework.TestCase { + + @Override + protected void setUp() throws Exception { + ConfigFileReader.instance = new ConfigFileReader(this.getClass().getClassLoader().getResource("testConfig.txt").getPath()); + RobotProvider.instance = new TestRobotProvider(); + + Scheduler.getInstance().reset(); + } + + protected void step(){ + Scheduler.getInstance().run(); + } + +} diff --git a/src/test/java/com/team766/config/ConfigFileReaderTest.java b/src/test/java/com/team766/config/ConfigFileReaderTest.java new file mode 100644 index 00000000..9a6b3531 --- /dev/null +++ b/src/test/java/com/team766/config/ConfigFileReaderTest.java @@ -0,0 +1,43 @@ +package com.team766.config; + +import static org.junit.Assert.*; +import java.io.File; +import java.io.FileWriter; +import java.io.IOException; +import org.junit.Before; +import org.junit.Test; + +public class ConfigFileReaderTest { + @Before + public void setup() { + AbstractConfigValue.resetStatics(); + } + + @Test + public void getJsonStringFromEmptyConfigFile() throws IOException { + File testConfigFile = File.createTempFile("config_file_test", ".json"); + try (FileWriter fos = new FileWriter(testConfigFile)) { + fos.append("{}"); + } + + ConfigFileReader.instance = new ConfigFileReader(testConfigFile.getPath()); + ConfigFileReader.getInstance().getString("test.sub.key"); + assertEquals("{\"test\": {\"sub\": {\"key\": null}}}", ConfigFileReader.getInstance().getJsonString()); + } + + @Test + public void getJsonStringFromPartialConfigFile() throws IOException { + File testConfigFile = File.createTempFile("config_file_test", ".json"); + try (FileWriter fos = new FileWriter(testConfigFile)) { + fos.append("{\"test\": {\"sub\": {\"key\": \"pi\", \"value\": 3.14159}}}"); + } + + ConfigFileReader.instance = new ConfigFileReader(testConfigFile.getPath()); + assertEquals("pi", ConfigFileReader.getInstance().getString("test.sub.key").get()); + assertEquals(3.14159, ConfigFileReader.getInstance().getDouble("test.sub.value").get().doubleValue(), 1e-6); + assertFalse(ConfigFileReader.getInstance().getInts("test.other.value").hasValue()); + assertEquals( + "{\"test\": {\n \"sub\": {\n \"value\": 3.14159,\n \"key\": \"pi\"\n },\n \"other\": {\"value\": null}\n}}", + ConfigFileReader.getInstance().getJsonString()); + } +} \ No newline at end of file diff --git a/src/test/java/com/team766/library/LossyPriorityQueueTest.java b/src/test/java/com/team766/library/LossyPriorityQueueTest.java new file mode 100644 index 00000000..73172577 --- /dev/null +++ b/src/test/java/com/team766/library/LossyPriorityQueueTest.java @@ -0,0 +1,26 @@ +package com.team766.library; + +import static org.junit.Assert.*; + +import java.util.Comparator; + +import org.junit.Test; + +public class LossyPriorityQueueTest { + @Test + public void test() throws InterruptedException { + final int N = 100; + var queue = + new LossyPriorityQueue(N, Comparator.naturalOrder()); + var producerThread = new Thread(() -> { + for (Integer i = 0; i < N; ++i) { + queue.add(i); + } + }); + producerThread.start(); + for (Integer i = 0; i < N; ++i) { + assertEquals(i, queue.poll()); + } + producerThread.join(); + } +} \ No newline at end of file diff --git a/src/test/java/com/team766/logging/LoggerTest.java b/src/test/java/com/team766/logging/LoggerTest.java new file mode 100644 index 00000000..a287fa14 --- /dev/null +++ b/src/test/java/com/team766/logging/LoggerTest.java @@ -0,0 +1,90 @@ +package com.team766.logging; + +import static org.junit.Assert.*; + +import java.io.File; +import java.io.IOException; +import java.util.ArrayList; +import org.junit.Rule; +import org.junit.Test; +import org.junit.rules.TemporaryFolder; + +public class LoggerTest { + @Rule + public TemporaryFolder workingDir = new TemporaryFolder(); + + @Test + public void test() throws IOException, InterruptedException { + String logFile = new File(workingDir.getRoot(), "test.log").getPath(); + LogWriter writer = new LogWriter(logFile); + writer.logStoredFormat( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.ERROR) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("num: %d str: %s") + .addArg(LogValue.newBuilder().setIntValue(42)) + .addArg(LogValue.newBuilder().setStringValue("my string"))); + writer.logStoredFormat( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.ERROR) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("num: %d str: %s") + .addArg(LogValue.newBuilder().setIntValue(63)) + .addArg(LogValue.newBuilder().setStringValue("second blurb"))); + writer.log( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.WARNING) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("Test raw log") + .build()); + writer.close(); + + LogReader reader = new LogReader(logFile); + String logString1 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); + assertEquals("num: 42 str: my string", logString1); + String logString2 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); + assertEquals("num: 63 str: second blurb", logString2); + String logString3 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); + assertEquals("Test raw log", logString3); + } + + @Test + public void stressTest() throws IOException, InterruptedException { + final long NUM_THREADS = 8; + final long RUN_TIME_SECONDS = 3; + + LogWriter writer = new LogWriter(new File(workingDir.getRoot(), "stress_test.log").getPath()); + ArrayList threads = new ArrayList(); + for (int j = 0; j < NUM_THREADS; ++j) { + Thread t = new Thread(() ->{ + long end = System.currentTimeMillis() + RUN_TIME_SECONDS * 1000; + while (System.currentTimeMillis() < end) { + writer.logStoredFormat( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.ERROR) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("num: %d str: %s") + .addArg(LogValue.newBuilder().setIntValue(42)) + .addArg(LogValue.newBuilder().setStringValue("my string"))); + writer.log( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.WARNING) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("Test raw log") + .build()); + } + }); + t.start(); + threads.add(t); + } + for (Thread t : threads) { + t.join(); + } + writer.close(); + } +} \ No newline at end of file diff --git a/to-do.txt b/to-do.txt new file mode 100644 index 00000000..4f10a487 --- /dev/null +++ b/to-do.txt @@ -0,0 +1 @@ +Add to do here: diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix.json new file mode 100644 index 00000000..789d831f --- /dev/null +++ b/vendordeps/Phoenix.json @@ -0,0 +1,257 @@ +{ + "fileName": "Phoenix.json", + "name": "CTRE-Phoenix", + "version": "5.20.2", + "frcYear": 2022, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix-frc2022-latest.json", + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.20.2" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.20.2" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonSRX", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonFX", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simVictorSPX", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simPigeonIMU", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simCANCoder", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.20.2", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.20.2", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.20.2", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.20.2", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.20.2", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.20.2", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonSRX", + "version": "5.20.2", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonFX", + "version": "5.20.2", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simVictorSPX", + "version": "5.20.2", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simPigeonIMU", + "version": "5.20.2", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simCANCoder", + "version": "5.20.2", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 00000000..997e2a46 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,73 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2022.1.1", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2022.1.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2022.1.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2022.1.1", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2022.1.1", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json new file mode 100644 index 00000000..83de291e --- /dev/null +++ b/vendordeps/WPILibNewCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "2020.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxaarch64bionic", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/WPILibOldCommands.json b/vendordeps/WPILibOldCommands.json new file mode 100644 index 00000000..7bdad212 --- /dev/null +++ b/vendordeps/WPILibOldCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibOldCommands.json", + "name": "WPILib-Old-Commands", + "version": "2020.0.0", + "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibOldCommands", + "artifactId": "wpilibOldCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibOldCommands", + "artifactId": "wpilibOldCommands-cpp", + "version": "wpilib", + "libName": "wpilibOldCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxaarch64bionic", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} diff --git a/vendordeps/navx_frc.json b/vendordeps/navx_frc.json new file mode 100644 index 00000000..0fb49a7e --- /dev/null +++ b/vendordeps/navx_frc.json @@ -0,0 +1,35 @@ +{ + "fileName": "navx_frc.json", + "name": "KauaiLabs_navX_FRC", + "version": "4.0.442", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "mavenUrls": [ + "https://repo1.maven.org/maven2/" + ], + "jsonUrl": "https://www.kauailabs.com/dist/frc/2022/navx_frc.json", + "javaDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-java", + "version": "4.0.442" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-cpp", + "version": "4.0.442", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": false, + "libName": "navx_frc", + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "windowsx86-64" + ] + } + ] +} \ No newline at end of file From 8f2e55d83b972dcad2f5eeda784543ad9e5bd08c Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Sat, 14 Jan 2023 10:27:39 -0800 Subject: [PATCH 002/103] Initialize swerveOdometry --- .github/workflows/deploy.yml | 32 ++ .github/workflows/main.yml | 36 ++ .gitignore | 168 +++++++ .vscode/launch.json | 28 ++ .vscode/settings.json | 35 ++ .vscode/tasks.json | 41 ++ .wpilib/wpilib_preferences.json | 6 + CONTRIBUTORS.md | 15 + README.md | 7 + WPILib-License.md | 24 + build.gradle | 164 +++++++ deploy_sim.sh | 60 +++ deps/commons-math3-3.6.1.jar | Bin 0 -> 2213560 bytes deps/gral-core-0.11.jar | Bin 0 -> 280268 bytes deps/json-20190722.jar | Bin 0 -> 65003 bytes gradle/wrapper/gradle-wrapper.jar | Bin 0 -> 59536 bytes gradle/wrapper/gradle-wrapper.properties | 5 + gradlew | 234 +++++++++ gradlew.bat | 89 ++++ settings.gradle | 27 ++ simConfig.txt | 102 ++++ src/main/deploy/example.txt | 3 + .../config/AbstractConfigMultiValue.java | 35 ++ .../team766/config/AbstractConfigValue.java | 93 ++++ .../com/team766/config/ConfigFileReader.java | 182 +++++++ .../java/com/team766/config/ConfigValue.java | 94 ++++ .../config/ConfigValueParseException.java | 13 + .../team766/controllers/MotionLockout.java | 57 +++ .../team766/controllers/PIDController.java | 350 ++++++++++++++ .../com/team766/controllers/RangeBound.java | 36 ++ .../RangeOfMotionMotorCommandBound.java | 54 +++ .../team766/controllers/TimeProviderI.java | 5 + .../com/team766/framework/AutonomousMode.java | 30 ++ .../java/com/team766/framework/Context.java | 454 ++++++++++++++++++ .../framework/ContextStoppedException.java | 10 + .../team766/framework/LaunchedContext.java | 19 + .../com/team766/framework/LoggingBase.java | 27 ++ .../java/com/team766/framework/Mechanism.java | 85 ++++ .../java/com/team766/framework/Procedure.java | 32 ++ .../framework/RunnableWithContext.java | 6 + .../java/com/team766/framework/Scheduler.java | 96 ++++ .../team766/framework/StackTraceUtils.java | 25 + .../framework/WPILibCommandProcedure.java | 48 ++ .../com/team766/hal/AnalogInputReader.java | 23 + .../com/team766/hal/BasicMotorController.java | 20 + .../java/com/team766/hal/CameraInterface.java | 9 + .../java/com/team766/hal/CameraReader.java | 7 + src/main/java/com/team766/hal/Clock.java | 5 + .../com/team766/hal/ControlInputReader.java | 13 + .../com/team766/hal/DigitalInputReader.java | 11 + .../java/com/team766/hal/DoubleSolenoid.java | 62 +++ .../java/com/team766/hal/EncoderReader.java | 73 +++ .../com/team766/hal/GenericRobotMain.java | 136 ++++++ src/main/java/com/team766/hal/GyroReader.java | 61 +++ .../java/com/team766/hal/JoystickReader.java | 46 ++ .../com/team766/hal/LocalMotorController.java | 271 +++++++++++ .../java/com/team766/hal/MotorController.java | 138 ++++++ ...MotorControllerCommandFailedException.java | 13 + .../hal/MotorControllerWithSensorScale.java | 158 ++++++ .../java/com/team766/hal/MultiSolenoid.java | 27 ++ .../java/com/team766/hal/PositionReader.java | 24 + .../java/com/team766/hal/RelayOutput.java | 16 + .../java/com/team766/hal/RobotProvider.java | 234 +++++++++ .../com/team766/hal/SolenoidController.java | 19 + .../com/team766/hal/VidSourceInterface.java | 5 + .../com/team766/hal/mock/MockAnalogInput.java | 18 + .../java/com/team766/hal/mock/MockCamera.java | 25 + .../team766/hal/mock/MockDigitalInput.java | 17 + .../com/team766/hal/mock/MockEncoder.java | 57 +++ .../java/com/team766/hal/mock/MockGyro.java | 52 ++ .../com/team766/hal/mock/MockJoystick.java | 69 +++ .../team766/hal/mock/MockMotorController.java | 28 ++ .../team766/hal/mock/MockPositionSensor.java | 38 ++ .../java/com/team766/hal/mock/MockRelay.java | 22 + .../com/team766/hal/mock/MockSolenoid.java | 21 + .../team766/hal/mock/TestRobotProvider.java | 129 +++++ .../team766/hal/simulator/AnalogInput.java | 19 + .../com/team766/hal/simulator/Camera.java | 14 + .../team766/hal/simulator/DigitalInput.java | 18 + .../com/team766/hal/simulator/Encoder.java | 54 +++ .../java/com/team766/hal/simulator/Gyro.java | 32 ++ .../team766/hal/simulator/PositionSensor.java | 23 + .../java/com/team766/hal/simulator/Relay.java | 32 ++ .../com/team766/hal/simulator/RobotMain.java | 123 +++++ .../hal/simulator/SimMotorController.java | 54 +++ .../hal/simulator/SimulationClock.java | 15 + .../simulator/SimulationRobotProvider.java | 120 +++++ .../com/team766/hal/simulator/Solenoid.java | 22 + .../team766/hal/simulator/VrConnector.java | 339 +++++++++++++ .../com/team766/hal/wpilib/ADXRS450_Gyro.java | 26 + .../com/team766/hal/wpilib/AnalogGyro.java | 17 + .../com/team766/hal/wpilib/AnalogInput.java | 9 + .../hal/wpilib/BaseCTRESpeedController.java | 30 ++ .../wpilib/CANSparkMaxMotorController.java | 232 +++++++++ .../hal/wpilib/CANTalonFxMotorController.java | 190 ++++++++ .../hal/wpilib/CANTalonMotorController.java | 191 ++++++++ .../hal/wpilib/CANVictorMotorController.java | 188 ++++++++ .../team766/hal/wpilib/CameraInterface.java | 39 ++ .../com/team766/hal/wpilib/DigitalInput.java | 9 + .../java/com/team766/hal/wpilib/Encoder.java | 9 + .../java/com/team766/hal/wpilib/Joystick.java | 29 ++ .../java/com/team766/hal/wpilib/NavXGyro.java | 55 +++ .../com/team766/hal/wpilib/PWMVictorSP.java | 16 + .../java/com/team766/hal/wpilib/Relay.java | 38 ++ .../com/team766/hal/wpilib/RobotMain.java | 151 ++++++ .../java/com/team766/hal/wpilib/Solenoid.java | 11 + .../com/team766/hal/wpilib/SystemClock.java | 12 + .../team766/hal/wpilib/WPIRobotProvider.java | 184 +++++++ .../com/team766/library/CircularBuffer.java | 72 +++ .../team766/library/LossyPriorityQueue.java | 61 +++ .../java/com/team766/library/RateLimiter.java | 27 ++ .../com/team766/library/SetValueProvider.java | 36 ++ .../library/SettableValueProvider.java | 7 + .../com/team766/library/ValueProvider.java | 14 + .../team766/logging/LogEntryComparator.java | 30 ++ .../com/team766/logging/LogEntryRenderer.java | 17 + .../java/com/team766/logging/LogReader.java | 51 ++ .../java/com/team766/logging/LogWriter.java | 108 +++++ .../java/com/team766/logging/Loggable.java | 5 + src/main/java/com/team766/logging/Logger.java | 132 +++++ .../team766/logging/LoggerExceptionUtils.java | 25 + .../team766/logging/SerializationUtils.java | 50 ++ src/main/java/com/team766/math/Algebraic.java | 7 + src/main/java/com/team766/math/Filter.java | 7 + src/main/java/com/team766/math/FirFilter.java | 21 + src/main/java/com/team766/math/IirFilter.java | 27 ++ .../com/team766/math/IsometricTransform.java | 40 ++ .../com/team766/math/LinearInterpolation.java | 53 ++ src/main/java/com/team766/math/Math.java | 22 + .../java/com/team766/math/TransformTree.java | 83 ++++ src/main/java/com/team766/math/Vector3.java | 60 +++ .../java/com/team766/odometry/Odometry.java | 127 +++++ src/main/java/com/team766/odometry/Point.java | 81 ++++ .../java/com/team766/odometry/PointDir.java | 70 +++ .../com/team766/robot/AutonomousModes.java | 21 + .../com/team766/robot/InputConstants.java | 22 + src/main/java/com/team766/robot/OI.java | 144 ++++++ src/main/java/com/team766/robot/Robot.java | 15 + .../com/team766/robot/mechanisms/Drive.java | 405 ++++++++++++++++ .../robot/mechanisms/ExampleMechanism.java | 22 + .../com/team766/robot/mechanisms/Gyro.java | 54 +++ .../java/com/team766/robot/mechanisms/README | 1 + .../team766/robot/procedures/DoNothing.java | 11 + .../robot/procedures/FollowPoints.java | 188 ++++++++ .../java/com/team766/robot/procedures/README | 1 + .../team766/simulator/ElectricalSystem.java | 35 ++ .../com/team766/simulator/Parameters.java | 28 ++ .../team766/simulator/PhysicalConstants.java | 7 + .../team766/simulator/PneumaticsSystem.java | 61 +++ .../java/com/team766/simulator/Program.java | 7 + .../team766/simulator/ProgramInterface.java | 99 ++++ .../java/com/team766/simulator/Simulator.java | 82 ++++ .../simulator/elements/AirCompressor.java | 56 +++ .../simulator/elements/AirReservoir.java | 17 + .../elements/CanMotorController.java | 21 + .../team766/simulator/elements/DCMotor.java | 49 ++ .../DoubleActingPneumaticCylinder.java | 52 ++ .../team766/simulator/elements/DriveBase.java | 4 + .../elements/ElectricalResistance.java | 35 ++ .../com/team766/simulator/elements/Gears.java | 26 + .../simulator/elements/MotorController.java | 22 + .../elements/PwmMotorController.java | 21 + .../SingleActingPneumaticCylinder.java | 55 +++ .../com/team766/simulator/elements/Wheel.java | 40 ++ .../interfaces/ElectricalDevice.java | 27 ++ .../interfaces/MechanicalAngularDevice.java | 27 ++ .../interfaces/MechanicalDevice.java | 32 ++ .../simulator/interfaces/PneumaticDevice.java | 40 ++ .../simulator/mechanisms/WestCoastDrive.java | 147 ++++++ .../com/team766/simulator/ui/Metrics.java | 160 ++++++ .../com/team766/simulator/ui/Trajectory.java | 143 ++++++ .../com/team766/web/AutonomousSelector.java | 96 ++++ src/main/java/com/team766/web/ConfigUI.java | 89 ++++ src/main/java/com/team766/web/Dashboard.java | 60 +++ .../java/com/team766/web/DriverInterface.java | 30 ++ .../java/com/team766/web/HtmlElements.java | 31 ++ src/main/java/com/team766/web/LogViewer.java | 109 +++++ src/main/java/com/team766/web/ReadLogs.java | 158 ++++++ src/main/java/com/team766/web/WebServer.java | 213 ++++++++ .../com/team766/web/dashboard/NewSection.java | 30 ++ .../team766/web/dashboard/StatusLight.java | 45 ++ .../com/team766/web/dashboard/Widget.java | 31 ++ .../proto/com/team766/logging/logging.proto | 65 +++ src/test/java/com/team766/TestCase.java | 22 + .../team766/config/ConfigFileReaderTest.java | 43 ++ .../library/LossyPriorityQueueTest.java | 26 + .../java/com/team766/logging/LoggerTest.java | 90 ++++ to-do.txt | 1 + vendordeps/Phoenix.json | 257 ++++++++++ vendordeps/REVLib.json | 73 +++ vendordeps/WPILibNewCommands.json | 37 ++ vendordeps/WPILibOldCommands.json | 37 ++ vendordeps/navx_frc.json | 35 ++ 193 files changed, 11963 insertions(+) create mode 100644 .github/workflows/deploy.yml create mode 100644 .github/workflows/main.yml create mode 100644 .gitignore create mode 100644 .vscode/launch.json create mode 100644 .vscode/settings.json create mode 100644 .vscode/tasks.json create mode 100644 .wpilib/wpilib_preferences.json create mode 100644 CONTRIBUTORS.md create mode 100644 README.md create mode 100644 WPILib-License.md create mode 100644 build.gradle create mode 100755 deploy_sim.sh create mode 100644 deps/commons-math3-3.6.1.jar create mode 100644 deps/gral-core-0.11.jar create mode 100644 deps/json-20190722.jar create mode 100644 gradle/wrapper/gradle-wrapper.jar create mode 100644 gradle/wrapper/gradle-wrapper.properties create mode 100755 gradlew create mode 100644 gradlew.bat create mode 100644 settings.gradle create mode 100644 simConfig.txt create mode 100644 src/main/deploy/example.txt create mode 100644 src/main/java/com/team766/config/AbstractConfigMultiValue.java create mode 100644 src/main/java/com/team766/config/AbstractConfigValue.java create mode 100755 src/main/java/com/team766/config/ConfigFileReader.java create mode 100644 src/main/java/com/team766/config/ConfigValue.java create mode 100644 src/main/java/com/team766/config/ConfigValueParseException.java create mode 100644 src/main/java/com/team766/controllers/MotionLockout.java create mode 100755 src/main/java/com/team766/controllers/PIDController.java create mode 100644 src/main/java/com/team766/controllers/RangeBound.java create mode 100644 src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java create mode 100644 src/main/java/com/team766/controllers/TimeProviderI.java create mode 100644 src/main/java/com/team766/framework/AutonomousMode.java create mode 100644 src/main/java/com/team766/framework/Context.java create mode 100644 src/main/java/com/team766/framework/ContextStoppedException.java create mode 100644 src/main/java/com/team766/framework/LaunchedContext.java create mode 100644 src/main/java/com/team766/framework/LoggingBase.java create mode 100644 src/main/java/com/team766/framework/Mechanism.java create mode 100644 src/main/java/com/team766/framework/Procedure.java create mode 100644 src/main/java/com/team766/framework/RunnableWithContext.java create mode 100644 src/main/java/com/team766/framework/Scheduler.java create mode 100644 src/main/java/com/team766/framework/StackTraceUtils.java create mode 100644 src/main/java/com/team766/framework/WPILibCommandProcedure.java create mode 100755 src/main/java/com/team766/hal/AnalogInputReader.java create mode 100644 src/main/java/com/team766/hal/BasicMotorController.java create mode 100755 src/main/java/com/team766/hal/CameraInterface.java create mode 100755 src/main/java/com/team766/hal/CameraReader.java create mode 100644 src/main/java/com/team766/hal/Clock.java create mode 100644 src/main/java/com/team766/hal/ControlInputReader.java create mode 100755 src/main/java/com/team766/hal/DigitalInputReader.java create mode 100755 src/main/java/com/team766/hal/DoubleSolenoid.java create mode 100755 src/main/java/com/team766/hal/EncoderReader.java create mode 100755 src/main/java/com/team766/hal/GenericRobotMain.java create mode 100755 src/main/java/com/team766/hal/GyroReader.java create mode 100755 src/main/java/com/team766/hal/JoystickReader.java create mode 100644 src/main/java/com/team766/hal/LocalMotorController.java create mode 100755 src/main/java/com/team766/hal/MotorController.java create mode 100644 src/main/java/com/team766/hal/MotorControllerCommandFailedException.java create mode 100644 src/main/java/com/team766/hal/MotorControllerWithSensorScale.java create mode 100644 src/main/java/com/team766/hal/MultiSolenoid.java create mode 100644 src/main/java/com/team766/hal/PositionReader.java create mode 100755 src/main/java/com/team766/hal/RelayOutput.java create mode 100755 src/main/java/com/team766/hal/RobotProvider.java create mode 100755 src/main/java/com/team766/hal/SolenoidController.java create mode 100755 src/main/java/com/team766/hal/VidSourceInterface.java create mode 100755 src/main/java/com/team766/hal/mock/MockAnalogInput.java create mode 100755 src/main/java/com/team766/hal/mock/MockCamera.java create mode 100755 src/main/java/com/team766/hal/mock/MockDigitalInput.java create mode 100755 src/main/java/com/team766/hal/mock/MockEncoder.java create mode 100755 src/main/java/com/team766/hal/mock/MockGyro.java create mode 100755 src/main/java/com/team766/hal/mock/MockJoystick.java create mode 100755 src/main/java/com/team766/hal/mock/MockMotorController.java create mode 100644 src/main/java/com/team766/hal/mock/MockPositionSensor.java create mode 100755 src/main/java/com/team766/hal/mock/MockRelay.java create mode 100755 src/main/java/com/team766/hal/mock/MockSolenoid.java create mode 100755 src/main/java/com/team766/hal/mock/TestRobotProvider.java create mode 100755 src/main/java/com/team766/hal/simulator/AnalogInput.java create mode 100755 src/main/java/com/team766/hal/simulator/Camera.java create mode 100755 src/main/java/com/team766/hal/simulator/DigitalInput.java create mode 100755 src/main/java/com/team766/hal/simulator/Encoder.java create mode 100755 src/main/java/com/team766/hal/simulator/Gyro.java create mode 100644 src/main/java/com/team766/hal/simulator/PositionSensor.java create mode 100755 src/main/java/com/team766/hal/simulator/Relay.java create mode 100755 src/main/java/com/team766/hal/simulator/RobotMain.java create mode 100755 src/main/java/com/team766/hal/simulator/SimMotorController.java create mode 100644 src/main/java/com/team766/hal/simulator/SimulationClock.java create mode 100755 src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java create mode 100755 src/main/java/com/team766/hal/simulator/Solenoid.java create mode 100644 src/main/java/com/team766/hal/simulator/VrConnector.java create mode 100755 src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java create mode 100755 src/main/java/com/team766/hal/wpilib/AnalogGyro.java create mode 100755 src/main/java/com/team766/hal/wpilib/AnalogInput.java create mode 100644 src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java create mode 100644 src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java create mode 100755 src/main/java/com/team766/hal/wpilib/CameraInterface.java create mode 100755 src/main/java/com/team766/hal/wpilib/DigitalInput.java create mode 100755 src/main/java/com/team766/hal/wpilib/Encoder.java create mode 100755 src/main/java/com/team766/hal/wpilib/Joystick.java create mode 100644 src/main/java/com/team766/hal/wpilib/NavXGyro.java create mode 100755 src/main/java/com/team766/hal/wpilib/PWMVictorSP.java create mode 100755 src/main/java/com/team766/hal/wpilib/Relay.java create mode 100755 src/main/java/com/team766/hal/wpilib/RobotMain.java create mode 100755 src/main/java/com/team766/hal/wpilib/Solenoid.java create mode 100644 src/main/java/com/team766/hal/wpilib/SystemClock.java create mode 100755 src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java create mode 100644 src/main/java/com/team766/library/CircularBuffer.java create mode 100644 src/main/java/com/team766/library/LossyPriorityQueue.java create mode 100644 src/main/java/com/team766/library/RateLimiter.java create mode 100644 src/main/java/com/team766/library/SetValueProvider.java create mode 100644 src/main/java/com/team766/library/SettableValueProvider.java create mode 100644 src/main/java/com/team766/library/ValueProvider.java create mode 100644 src/main/java/com/team766/logging/LogEntryComparator.java create mode 100644 src/main/java/com/team766/logging/LogEntryRenderer.java create mode 100644 src/main/java/com/team766/logging/LogReader.java create mode 100644 src/main/java/com/team766/logging/LogWriter.java create mode 100644 src/main/java/com/team766/logging/Loggable.java create mode 100644 src/main/java/com/team766/logging/Logger.java create mode 100644 src/main/java/com/team766/logging/LoggerExceptionUtils.java create mode 100644 src/main/java/com/team766/logging/SerializationUtils.java create mode 100644 src/main/java/com/team766/math/Algebraic.java create mode 100644 src/main/java/com/team766/math/Filter.java create mode 100644 src/main/java/com/team766/math/FirFilter.java create mode 100644 src/main/java/com/team766/math/IirFilter.java create mode 100644 src/main/java/com/team766/math/IsometricTransform.java create mode 100644 src/main/java/com/team766/math/LinearInterpolation.java create mode 100644 src/main/java/com/team766/math/Math.java create mode 100644 src/main/java/com/team766/math/TransformTree.java create mode 100644 src/main/java/com/team766/math/Vector3.java create mode 100644 src/main/java/com/team766/odometry/Odometry.java create mode 100644 src/main/java/com/team766/odometry/Point.java create mode 100644 src/main/java/com/team766/odometry/PointDir.java create mode 100644 src/main/java/com/team766/robot/AutonomousModes.java create mode 100644 src/main/java/com/team766/robot/InputConstants.java create mode 100644 src/main/java/com/team766/robot/OI.java create mode 100644 src/main/java/com/team766/robot/Robot.java create mode 100644 src/main/java/com/team766/robot/mechanisms/Drive.java create mode 100644 src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java create mode 100644 src/main/java/com/team766/robot/mechanisms/Gyro.java create mode 100644 src/main/java/com/team766/robot/mechanisms/README create mode 100644 src/main/java/com/team766/robot/procedures/DoNothing.java create mode 100644 src/main/java/com/team766/robot/procedures/FollowPoints.java create mode 100644 src/main/java/com/team766/robot/procedures/README create mode 100644 src/main/java/com/team766/simulator/ElectricalSystem.java create mode 100644 src/main/java/com/team766/simulator/Parameters.java create mode 100644 src/main/java/com/team766/simulator/PhysicalConstants.java create mode 100644 src/main/java/com/team766/simulator/PneumaticsSystem.java create mode 100644 src/main/java/com/team766/simulator/Program.java create mode 100644 src/main/java/com/team766/simulator/ProgramInterface.java create mode 100644 src/main/java/com/team766/simulator/Simulator.java create mode 100644 src/main/java/com/team766/simulator/elements/AirCompressor.java create mode 100644 src/main/java/com/team766/simulator/elements/AirReservoir.java create mode 100644 src/main/java/com/team766/simulator/elements/CanMotorController.java create mode 100644 src/main/java/com/team766/simulator/elements/DCMotor.java create mode 100644 src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java create mode 100644 src/main/java/com/team766/simulator/elements/DriveBase.java create mode 100644 src/main/java/com/team766/simulator/elements/ElectricalResistance.java create mode 100644 src/main/java/com/team766/simulator/elements/Gears.java create mode 100644 src/main/java/com/team766/simulator/elements/MotorController.java create mode 100644 src/main/java/com/team766/simulator/elements/PwmMotorController.java create mode 100644 src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java create mode 100644 src/main/java/com/team766/simulator/elements/Wheel.java create mode 100644 src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java create mode 100644 src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java create mode 100644 src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java create mode 100644 src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java create mode 100644 src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java create mode 100644 src/main/java/com/team766/simulator/ui/Metrics.java create mode 100644 src/main/java/com/team766/simulator/ui/Trajectory.java create mode 100644 src/main/java/com/team766/web/AutonomousSelector.java create mode 100644 src/main/java/com/team766/web/ConfigUI.java create mode 100644 src/main/java/com/team766/web/Dashboard.java create mode 100644 src/main/java/com/team766/web/DriverInterface.java create mode 100644 src/main/java/com/team766/web/HtmlElements.java create mode 100644 src/main/java/com/team766/web/LogViewer.java create mode 100644 src/main/java/com/team766/web/ReadLogs.java create mode 100644 src/main/java/com/team766/web/WebServer.java create mode 100644 src/main/java/com/team766/web/dashboard/NewSection.java create mode 100644 src/main/java/com/team766/web/dashboard/StatusLight.java create mode 100644 src/main/java/com/team766/web/dashboard/Widget.java create mode 100644 src/main/proto/com/team766/logging/logging.proto create mode 100644 src/test/java/com/team766/TestCase.java create mode 100644 src/test/java/com/team766/config/ConfigFileReaderTest.java create mode 100644 src/test/java/com/team766/library/LossyPriorityQueueTest.java create mode 100644 src/test/java/com/team766/logging/LoggerTest.java create mode 100644 to-do.txt create mode 100644 vendordeps/Phoenix.json create mode 100644 vendordeps/REVLib.json create mode 100644 vendordeps/WPILibNewCommands.json create mode 100644 vendordeps/WPILibOldCommands.json create mode 100644 vendordeps/navx_frc.json diff --git a/.github/workflows/deploy.yml b/.github/workflows/deploy.yml new file mode 100644 index 00000000..80bc5106 --- /dev/null +++ b/.github/workflows/deploy.yml @@ -0,0 +1,32 @@ +name: Deploy + +# Controls when the workflow will run +on: + # Triggers the workflow on push or pull request events but only for the master branch + push: + branches: [ master ] + + # Allows you to run this workflow manually from the Actions tab + workflow_dispatch: + +# A workflow run is made up of one or more jobs that can run sequentially or in parallel +jobs: + publish: + runs-on: ubuntu-latest + permissions: + contents: read + packages: write + steps: + - uses: actions/checkout@v3 + - uses: actions/setup-java@v3 + with: + java-version: '11' + distribution: 'adopt' + - name: Validate Gradle wrapper + uses: gradle/wrapper-validation-action@e6e38bacfdf1a337459f332974bb2327a31aaf4b + - name: Publish package + uses: gradle/gradle-build-action@0d13054264b0bb894ded474f08ebb30921341cee + with: + arguments: publish + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} \ No newline at end of file diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml new file mode 100644 index 00000000..ab5ab753 --- /dev/null +++ b/.github/workflows/main.yml @@ -0,0 +1,36 @@ +# This is a basic workflow to help you get started with Actions + +name: CI + +# Controls when the workflow will run +on: + # Triggers the workflow on push or pull request events but only for the master branch + push: + branches: [ master ] + pull_request: + + # Allows you to run this workflow manually from the Actions tab + workflow_dispatch: + +# A workflow run is made up of one or more jobs that can run sequentially or in parallel +jobs: + # This workflow contains a single job called "build" + build: + # The type of runner that the job will run on + runs-on: ubuntu-latest + + # This grabs the WPILib docker container + container: wpilib/roborio-cross-ubuntu:2022-18.04 + + # Steps represent a sequence of tasks that will be executed as part of the job + steps: + # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it + - uses: actions/checkout@v2 + + # Grant execute permission for gradlew + - name: Grant execute permission for gradlew + run: chmod +x gradlew + + # Runs a single command using the runners shell + - name: Compile and run tests on robot code + run: ./gradlew build --info diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..c0044d2c --- /dev/null +++ b/.gitignore @@ -0,0 +1,168 @@ +# This gitignore has been specially created by the WPILib team. +# If you remove items from this file, intellisense might break. + +### C++ ### +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +### Java ### +# Compiled class file +*.class + +# Log file +*.log + +# BlueJ files +*.ctxt + +# Mobile Tools for Java (J2ME) +.mtj.tmp/ + +# Package Files # +*.jar +*.war +*.nar +*.ear +*.zip +*.tar.gz +*.rar + +# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml +hs_err_pid* + +### Linux ### +*~ + +# temporary files which can be created if a process still has a handle open of a deleted file +.fuse_hidden* + +# KDE directory preferences +.directory + +# Linux trash folder which might appear on any partition or disk +.Trash-* + +# .nfs files are created when an open file is removed but is still being accessed +.nfs* + +### macOS ### +# General +.DS_Store +.AppleDouble +.LSOverride + +# Icon must end with two \r +Icon + +# Thumbnails +._* + +# Files that might appear in the root of a volume +.DocumentRevisions-V100 +.fseventsd +.Spotlight-V100 +.TemporaryItems +.Trashes +.VolumeIcon.icns +.com.apple.timemachine.donotpresent + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json + +### Windows ### +# Windows thumbnail cache files +Thumbs.db +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk + +### Gradle ### +.gradle +/build/ + +# Ignore Gradle GUI config +gradle-app.setting + +# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) +!gradle-wrapper.jar + +# Cache of project +.gradletasknamecache + +# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 +# gradle/wrapper/gradle-wrapper.properties + +# # VS Code Specific Java Settings +# DO NOT REMOVE .classpath and .project +.classpath +.project +.settings/ +bin/ + +# Simulation GUI and other tools window save file +*-window.json + +# The list of available sim robots is environment-specific, so it shouldn't be committed +/sim_robots.lst + +# Don't commit logs written by the framework when running in sim +/sim_robot_logs \ No newline at end of file diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 00000000..8fbfc758 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,28 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + + { + "type": "wpilib", + "name": "WPILib Desktop Debug", + "request": "launch", + "desktop": true, + }, + { + "type": "wpilib", + "name": "WPILib roboRIO Debug", + "request": "launch", + "desktop": false, + }, + { + "type": "java", + "name": "Start 3d simulation mode", + "request": "launch", + "mainClass": "com.team766.hal.simulator.RobotMain", + "args": ["-vr_connector"] + } + ] +} diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..3cbfce66 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,35 @@ +{ + "java.configuration.updateBuildConfiguration": "automatic", + "java.server.launchMode": "Standard", + "files.exclude": { + "**/.git": true, + "**/.svn": true, + "**/.hg": true, + "**/CVS": true, + "**/.DS_Store": true, + "bin/": true, + "**/.classpath": true, + "**/.project": true, + "**/.settings": true, + "**/.factorypath": true, + "**/*~": true + }, + "java.test.config": [ + { + "name": "WPIlibUnitTests", + "workingDirectory": "${workspaceFolder}/build/jni/release", + "vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ], + "env": { + "LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" , + "DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" + } + }, + ], + "java.test.defaultConfig": "WPIlibUnitTests", + + "editor.formatOnSave": false, + "editor.insertSpaces": false, + "editor.tabSize": 4, + "diffEditor.ignoreTrimWhitespace": false, + "java.format.settings.url": "https://raw.githubusercontent.com/google/styleguide/gh-pages/eclipse-java-google-style.xml" +} diff --git a/.vscode/tasks.json b/.vscode/tasks.json new file mode 100644 index 00000000..e0ef0c9a --- /dev/null +++ b/.vscode/tasks.json @@ -0,0 +1,41 @@ +{ + // See https://go.microsoft.com/fwlink/?LinkId=733558 + // for the documentation about the tasks.json format + "version": "2.0.0", + "tasks": [ + { + "label": "Deploy Sim", + "type": "shell", + "command": "./deploy_sim.sh", + "problemMatcher": [], + "showOutput": "always", + "presentation": { + "echo": true, + "reveal": "always", + "focus": true, + "panel": "dedicated", + "showReuseMessage": false, + "clear": true + } + }, + { + "label": "Gradle Build", + "type": "shell", + "command": "./gradlew build", + "problemMatcher": [], + "showOutput": "always", + "presentation": { + "echo": true, + "reveal": "always", + "focus": true, + "panel": "dedicated", + "showReuseMessage": false, + "clear": true + }, + "group": { + "kind": "build", + "isDefault": true + } + } + ] +} \ No newline at end of file diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json new file mode 100644 index 00000000..c19547e9 --- /dev/null +++ b/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2022", + "teamNumber": 766 +} \ No newline at end of file diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md new file mode 100644 index 00000000..56850b77 --- /dev/null +++ b/CONTRIBUTORS.md @@ -0,0 +1,15 @@ +Brett Levenson +Ryan Cahoon +Margaret Chan +Zhanning Zhu +Maya Khodabakchian +Alexander Youngblood +Yarden Goraly +Aiden Tai +Samir Rashid +Alexandre Sauquet +Nicholas Chang +Adrian Deutscher-Bishop +Jason Lee +Rajit Ghosh +Debajit Ghosh \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 00000000..04231c15 --- /dev/null +++ b/README.md @@ -0,0 +1,7 @@ +# Maroon Framework + +[![CI](../../actions/workflows/main.yml/badge.svg)](../../actions/workflows/main.yml) + +Software framework for developing +[FIRST Robotics Competition](https://www.firstinspires.org/robotics/frc) robots, +developed by [Team 766 M-A Bears](https://team766.com/). \ No newline at end of file diff --git a/WPILib-License.md b/WPILib-License.md new file mode 100644 index 00000000..3d5a824c --- /dev/null +++ b/WPILib-License.md @@ -0,0 +1,24 @@ +Copyright (c) 2009-2021 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/build.gradle b/build.gradle new file mode 100644 index 00000000..efa7a9ad --- /dev/null +++ b/build.gradle @@ -0,0 +1,164 @@ +plugins { + id 'java' + id 'java-library' + id 'maven-publish' + id 'edu.wpi.first.GradleRIO' version '2022.4.1' + id 'com.google.protobuf' version '0.8.19' +} + +sourceCompatibility = JavaVersion.VERSION_11 +targetCompatibility = JavaVersion.VERSION_11 + +def protobufVersion = '3.21.6' + +def ROBOT_MAIN_CLASS = "com.team766.hal.wpilib.RobotMain" + +sourceSets { + main { + java { + // NOTE(rcahoon, 2022-10-16): Gradle doesn't need this, but VSCode seems + // to not automatically add generated classes to the classpath. + srcDirs 'build/generated/source/proto/main/java' + } + } +} + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployUtils. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamNumber() + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + } + + // Just the (static) config files + configFiles(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy/configs') + directory = '/home/lvuser/deploy/configs' + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// Set this to true to enable desktop support. +def includeDesktopSupport = false + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 4. +dependencies { + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) + simulationRelease wpi.sim.enableRelease() + + testImplementation 'junit:junit:4.12' + + // our files + implementation "com.google.protobuf:protobuf-java:${protobufVersion}" + + implementation files('deps/commons-math3-3.6.1.jar') + implementation files('deps/gral-core-0.11.jar') + // implementation "org.java-websocket:Java-WebSocket:1.4.0" + //implementation files('deps/Java-WebSocket-1.3.9.jar') + implementation files('deps/json-20190722.jar') +} + +// Simulation configuration (e.g. environment variables). +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// in order to make them all available at runtime. Also adding the manifest so WPILib +// knows where to look for our Robot Class. +jar { + from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +allprojects { + group 'com.team766' + version '2.1.0' + + repositories { + mavenCentral() + + gradlePluginPortal() // for protobuf + + maven { url = uri('https://frcmaven.wpi.edu/artifactory/release/') } + + // CTRE + maven { url = uri('https://devsite.ctr-electronics.com/maven/release/') } + + // REV + maven { url = uri('https://maven.revrobotics.com/') } + } +} + +protobuf { + // Configure the protoc executable + protoc { + // Download from repositories + artifact = "com.google.protobuf:protoc:${protobufVersion}" + } +} + +publishing { + repositories { + maven { + name = "GitHubPackages" + url = uri("https://maven.pkg.github.com/Team766/MaroonFramework") + credentials { + username = System.getenv("GITHUB_ACTOR") + password = System.getenv("GITHUB_TOKEN") + } + } + } + publications { + gpr(MavenPublication) { + artifactId "maroonframework" + from(components.java) + } + } +} + diff --git a/deploy_sim.sh b/deploy_sim.sh new file mode 100755 index 00000000..de5a53fd --- /dev/null +++ b/deploy_sim.sh @@ -0,0 +1,60 @@ +#!/bin/bash + +set -euo pipefail + +builtin cd "$(dirname -- "${BASH_SOURCE[0]}")" + +if [ $# -gt 0 ]; then + server="$1" +elif [ -f sim_robots.lst ]; then + PS3="Which sim robot would you like to use? " + COLUMNS=1 + cancel_option="Cancel Deployment" + select name in $(cat sim_robots.lst) "$cancel_option" + do + server="${name-"$REPLY"}" + break + done + if [ "$server" == "$cancel_option" ]; then + echo "Canceled" + exit + fi +fi + +if [ -z "${server-}" ]; then + # Sleep here is necessary to allow Theia to finish opening the task terminal + # before displaying the error message. + sleep 1 + echo "Please supply the URL of the sim robot" + exit 1 +fi + +echo -e "Deploying to $server\n" + +set -x + +user="root" + +./gradlew jar + +jar_file=( build/libs/*.jar ) +[ "${#jar_file[@]}" -eq 1 ] || (echo "Output jar file could not be determined"; exit 1) + +version="$(md5sum < "$jar_file" | awk '{ print $1 }')" +deployed_code="/tmp/project-$(date +%s)-$version" + +rm -rf "$deployed_code" +mkdir -p "$deployed_code" + +cp "$jar_file" "$deployed_code/project.jar" +cp -R src/main/deploy "$deployed_code" +cp simConfig.txt "$deployed_code" + +deployed_package=${deployed_code}.tgz +tar cfz ${deployed_package} -C ${deployed_code} . + +curl --fail -F "package=@${deployed_package}" ${server}:4000/uploadrobotcode + +set +x +echo -e "\nDeploy finished. Your code is running" +echo -e "\nOpen simulation viewer at http://$server" \ No newline at end of file diff --git a/deps/commons-math3-3.6.1.jar b/deps/commons-math3-3.6.1.jar new file mode 100644 index 0000000000000000000000000000000000000000..0ff582cfcb687e5c9608457628f78e9a782be932 GIT binary patch literal 2213560 zcmbrm1yo+ivNnvnySoSX;O-XO{l(ovaCdiicLD?_xVr^+hY&1Ske|$)duAr*US`hs zvsPHFm9D3&s-KeXy?ZN2gMz^T0YL!)NmVHuAbMPnUNn zDEoS9xtGliydQZfC8eci*i9Hz;%|R=cx4;uIg%^Z&_5vb!&Hh1W{a+l_suBdVy<1> z#>(rXnXwpn3~xi~*N!t+(vCE_V`Yp>EiA72;MYE_Jq>r;P?l5zwC(S#0#^|%1c;&m zp%O}rIT;%WU29}Xg@f_sw~=PKcrr4z92XDR!0BfzOG-N*a3fPKH0nSuT;CDhYaGhh zH6Ow5n2YN-kgZUV5>0SnWf!4jE#cA=d&~09!yZRq?H@mhW_=P!g4qv9W3>tAi3B@C z>zO63h$)UTY^t-WHl-mG1F9@;GlO2Nn5FPm!J_chGWFhF>8u(p^r%M0I!(1iRoD=* zYQL}q;Q}?y!bKXa1ML;)Q(UI|L`=JA3d$2*DB<&_2%W4ofd0Y>HrSo9CcUtPe_4I6 z1soEYXaWP_I%dShK=MPa&@4_fOuol{KXh0cKK){+LU(MjF%>iHp^KOeYI3GxmLD=x za^=eMpdc6;|KQXbQ!jBKh)vs(BZUU7WB8mw>-P{-*to8Ukv7p}&$;#304ZuUrg}A0 zL9~e&TzaM-k3O)RBC#CkR9R8Bj(KQq}l9W!d}}4i)P@R&^x$J?_*Jz*e>Gt;M}jGwg?#d)i1W z23LPrQyHGWEJx_gGg0uxz#z+lc!)Z*)Ug_#;Q}5LO*ziuL;D=wAp-{AUeK^QdA)N3 zacR4sf)neze%Ec6c!05}HS(T2Q2jOq;>XN%;@}KIO@3vZu2#(wR*W@5W%;Eeuv}-q zSPr)dK@sJTHjp|vN|fCx-B6#aGRGWmf=4VV&OZ4e{Y%>I$hv!Wl-#g*Z<+6lxM4Qw z?JzMq_Uc5E8taaN(7j50>c{pMf?2?hO}VlS=Lfpg?p`X0t(jW1_bC+&HykUPc1hO8 zn!Mqs$s_!lfvU(Go9%WeH$T(`{4P;Yv@xZ;hR=6!yxa)D9c|)l_H`}a z!tj-n@#uqM)cTirW5NG;=Y-~Y;L_1mjR$M%8nqm49wwgg3AGDIZiMvg!0Owo-nX*% zrh0b~>pE@TjWy!g@avz~wNTHvb5=~yR`OjF6W((=u&)dt+CmU z8kP^E48RyJ7ZGwLH&npDXP)iX#g!rq|;G$Ld#jT-I{>r!X`3N<}S4m90cWHk^$Wpde$# z+s~SIWA+7bQf78u3e7o5(N&KYS=dbA1P=Ut$x=N^)Ms8KJR=8y}BeGKA@V2tq2KOalTs67u40 zCo5XqcB4-lHX2$&dO+tQ`$&kI1KUt7vjG@`l$pf0g>Z7G2Z}FxG$(V=0qdO@ReG}> z1cFjmAk%Lg3e{9UX8C=%RT92UIj%WDdWV*&fx69{>sGW?$4khUwnH=QXX}mWsuAL@ z9OABqV@>B3FC53PfZJ5Zuh=6scc|N=)Ol27GQ&RRexj$h;tj`O+d*4~l0URDlu1XJ zy)u%P?tOaB*3RvI*Q%?ksmjA4R!B7MTCQo(0#zzolGeE;L{WQVez|aw~~#2U$9N_@*Saq zG$d4SVzLVm1P~B3HW1Ly3i5lQ*)jQRp#giTAhr&sztx!keFW^kMi|%`7?}ZH8HoDV zfkw90*0wf|e-c=<{OjB=iv2eCzmWe&z}mpcjO9;azp9M)nwYiKpCp%mnULadBy9lB z4hB{>0H;?l-uz<>r}wtTe*#+hMH$Bb4#?Tb{58}5xmvb1fIqACtB?LUkfW`M^`Gqf z73iPa_Z!gP*hl#{-ZHXsc60(bnA`lB%D<|_{LeuEE(TW422SR-Hm{gS{x^8W=8jGV zHb#FAnqO5Sc@4tA#=z=>qxqj>=vVnyP5QUIvAKx}zyV<6Wd3(1(f=cT%x#PCyoU2? z!2H{|pRRX!QS9%WPw<*nFSL9u$GsYCzsdfl#Y>3%DL9sX$#1VF+uuMO3~Vf44_NBI zHR2z|J=NdBnA`joAFqb$tLyxmK}NO?4uHR1nZL&|1~?iynAdObRbU$f?=o3gV4xcLht_4{J$Dizbo*vkpBVm>q@>_xPFCk z0T?;iz7}O~|K2NqDD^Ki3j-rtLvw@IdbR&bNk=0Ct5;LOf2HKV&|VrQWAoS39Or*y z`@djqUgFKc+~rS^_AAFY@_4}ibf z3cQ;3{xfU->Wx=3@c)Qg0Sp|S9POPAUTVspJo_v2UrnLLCU&ogzS{VkI2in02m7iQ z9PI!`FJ0^Z>-468mwN2Dt{;v%AZ{dE~o&Uet32-*DGB*ainh#n2neYFN zOTH&D&?y+=I7K- z=0>lTw^s|k(@S^kXkzQ|T9Zoj8gop{tzM2Y{$%>rFYPJhi?o5GBj7KafL{l}{xRsU z=h(jvMEUE$|2WS6bv(}hI{tqSssG^8uX04M%Kdt{{j2oPy817hf12~Z9*zIUw&Yik zpAFyNf&9^K{okhiOmP1k=ig-f{aN*|O8wks#$sjL`H;nmbQ0>bn1HaB5C0pq1@}xi6gXtYE1^=Yf^dXs_T=v zk>qur`^grnPqun(3twI6PLHlBX6(N?1gV+%hGQIu70LjBdv_~46=oPIEowZ*;sdO~nE^B8r)`jLj>u4M${ZnK6l#49h<@X>aUK(gxo2GczP)B)evwXY@4{hAetaP#ET7 zHv4>6QLUOkfgeda6YTa}%v%Ym=PY=mBpyKb@vH98T#No9J$e|hm(oRb zeYVE_ENWjGCLFsCH3DMMo0g%oE>eLC*KQKc`;ZXkK2VhJe&^tohNVF4o$V&6a5ju! zQnAOCzPW+JaWVGfC&2+B24KhZqR^8_@`3jIV2!|LUEZrm1s*-q zD7|$HxndaKhZ5C4R94{wXpxXI1jizluJa>zAhmxVW0XY~j$fuGhwG(44#z91YW`hD|2UICpwfKKY7AcQ0xY+c21> z4Y9j60&~N)=&k6O=sW@Ghxs zs*=&y2d-+;&u6g!8K5J9b}}b6C6h_b8tO;ZqEh(uq<+lShbA>yPa8GF+7&@a6I$7? z(MXDU*JQXfu>a@p%la56cMRF zvgnUrKp0~0IEgVEpI|F81Eb?dswmx&Lxk+cG|luqglZ>hFe!1C`(Ri$f}i?a7}t*C z`0GBF8QgfkqBtbIYCQCzomEVT4)si1Zt=#Cfe=LAe5%P~(;8>PRTtgyuJ>5`2KJEV znD69vu$6Km2crqQVBP>=-ph-@5|-qs6@7iTz7LYp45rG1pvy-k2zT8r;}R)gT+%}J(_$o!V{6R^_|=7 z7x0Xyd85?BGf}t~$q-^|u><8o@vb#8CE0UFqo+BA19~rdL2r~5mssG>&P`&S$En#aBGsBFI0oo8%k~3}gJH5#_}Y@9tnVzLAV3_I0IG|yW z0Q)w}g``=PPaH`iZgA0l+Pm>n$RZE9IIwCK$$%6TAlvZz{_HP4q?`-B{on&U41pe( zUP~#AVTQe^bLWz--;!ELyHTo8oT&iQJWY0nK2SY0l-m1P0i%wfRZcrG5o+KXA*xE^HJvSZkwNZ}ocysf zpTe-vAINSLMbE$wwE8x|KR+c0dP25Lr?RdjpssP?0_Vn$|^=x1| zjFb^U;9V>I5tTBr1fg-5TVCD3$})jYhLX89s?rTQlkkD_5jR6yW+GK*r%-r$J6hI9 z(42!ayS09s9w}m>`WhOpAhA|qr|?>V6*M<}Kjr$8(XkBKWFomq#{ApLa}>V4(%lMhkZd0w$M!Em+ZOeV5z1~wf*uP1TB7K zctU?rTLt;d^-(5pKzk44_=5_4JZ{Fu^hKv4lz;$4Ngz0E*)1Mo^ZSpIwS17!EFiF5 z#L$^l&KN;Y$0=i3ZO}Xi%1h{XM8PF-Y9dt54iVO|14~~lF6ph#IQzZTQoh~d999}i za^T&gNkg&SI3fjjQw$f^v>^|WM2A6 z1syqe5o(U(91Qp#9lJDf*d7_{IS?)#S<&bEye~xd-y+<4;; zqJrEUKi@yRElu^+5Gg8Vbc2T1FA z%-YFFB34j&G858BdM97BrUS)1^c|;yTX!SkgxFBX+B0pQx4HvJr+)KV^s;wmNst@$C`AEfevy)p$2=h^8adH0MP{3WCRS!nr9~oscI2@R5zbiu_D9D zi44M8?DfS^CspYvKz5nD74!kxW09NGu3-Fz%eQb8SE*tcJ_e2YLur}50Xd`5j}M|p z*wbO6{yk`OpK(W$**4j0tH9|$Pi57t6?D-r$FKD=-&Aq5V~-b|RPhotLeA*28uZkz zClTt_UT^UJ@U)!-Zz6Suyag`L|KN-w=|z4$T#yL1O3(>A&U+i5;cGzkdU^*Xddrb4V*MCS{xudD`*Gud z6)SFZP`re=)+(J$O&!pct$~uH4&>43K}Ag!J<;1l>qHS(IY?bUmrc3?@5F)cM};j* zDf>R5XHD}uBN;sIS#$-`@eN8Go~mX2_mT74#;V6_@9A!>G{O+SlV^_vr0w%Yw83r2 zYa-#h!8au+)S{XN$Sl8USdhb@QrJv}Q>>LD%c%}D3#wYipOi@I{4s>pUR89DJSCaONwD{pO>{bbk?vK;ABHN7K||r;GL?CC`g?LY4q$nqj~efMq}^?{SFP&yp9oD^r}W*ZW*V@ZIZ?Z67Iuf zA{lu+7f0pA-Ck5_Dl9rAP}&ywk+ox|4v^?-4&=qG)_I4kN~ zf{lP41V8>@zwd%x!kgcuMe0n?9$&kd{!pLiLH*MlE!#V&4g+ZF14B7;RQAJ4#9&X1X;V9A?s( z6P-P4vf)|Bt$BxU7L8Zpder$aJ|l+6&ZSuoBJNM$Kc{45cjf8M>Zj%A?Ga8=U;*qp z+m5YwCVq3qO#;|=lRV>i?1dC!5qnonp{}0kJ4Yqa1FJO$RW9R2EsC-a2LguG>T>UR zq6jlN+MoTjViy%ngG#aVwURkjjZGsvS+a3KgG1W;>mE1{ZbSI9bo{$da^@BYXCSP= zL>>7(#*n%T*KT!YZ|(>l?))tS6cwwXf%t(DDc-V|T&)(#S+sMmmVbw+heIxxYlSkg zv1a^KIoDhwrdlFwK|OTd1%V_UXnEBIAA$aTycpX{kXi7&;CKLce6gea&4jWjLKTMP ziMl1ABrVi?sb@WVF+0R2=Q3yH-n3F9wv#iVH}`{A7N^e8 zWsC_xpwk|j!tpFf>Suo}Eg!Ft)&PEoBFriCu`=nd@_}f94dY3e-2=#^Z@-Z!KkK;8 zxBD@-S4I@kx8_Z!NlqOZN4rKCnDBI2DmSL+4BB#A+$p?kiej8xY0Yq3I>&@0=OnWuC z84#32(fcu2GD#nR7RsSkRC3ui8-Y3t0r|lLh#VR!wxUAx@Nl&aJj>y+CGoJmep$}U zUCrXXV=7;xeS>uDQ!jC!VPiOgypqe_;#cj0bZ`t<`}{q@XIhu?Rz+0h^;9;y#?Uc>@bWvRJ&g zAvyDFY&-z5U7o?6kL+)M|JD4PPVZ^Z_PYF9cjOEWA2xjkDJHG6*AHqs4o98Rp^>-! z*|dcg&rvPx!3gBl@D{4uo^Doe8kGRR2M)m&NS)jYA2G`Hljzpx`a#Dofi;6IF$UaF zzGrtzb89DC8IFR)!3%&fS7xL8+_+1#D`C6Q8JMI2!U%j$>v~3Zwm@J&Q)YlE)%5xK zlePN-9l7W4R0(!wR)TFV$Y`btbs9dN(C|Xd4j^*18%lj7i=d8_r*+tcnWWCxz&$w4`J7Rp#d)JxN^5FK_i`Z}L zO=9iw*!u{N;+C&&74jRK^azmf64?(!g4G;4D(U{hXxJ8TLGi&jw<_+1=fGFdI`2?t z&*zwcYhnk0rF}BpTy1cyjH{iotO=|jG6k{i1h^3KyzvVv;LX9hELRUewY?D>R3OW_ zYHSD*6H0D!OJ|@;N%5B;TDcB$!p%QPi?lJrz|emZ1UP9OxX>ROC)AsFOSTu*e%-`4 zHpTw%@slQiI^}EU6)|+zvHe+uha)%e-bRM>M-Gq@)RK5F3qMU&Zl5>d+GNtpdY*aZ zntIHL2(9IUXR;&R%Qv?aYQ^iPt71km5VyBOXBIGeVnE@G#_TxX-QRub-q`@c`+UFu>&T6eo{5?k08!xi%L$4EAzX3A zdTZfWv9M<6${`&Z5VCmTS52KCBBI>0fD51wKKg|0c962*dUto`)K#&1NB$O@8(+LS zNIsaIXrlh>EA%C}#ko@_lWiBsK_4QXBk>t1bLjJ&I!PzCV^nkX?lWVkxj-0>UjX8+l!jr4wC#_t0&Uw^Xm(#WW zsUB&$iJ4&eyav1;RD;$nSezWj!VTNiZHP~v0kk|>lft%VOfg!4+&d(chq$@a^%8j1O9sO;WG&TK!>xfG;*uz(no~MYC z@P1RSQ1?>J<;`Fta?82-Hh2w`oh{t@*TztzAWECQBZ@MR&@|%C zP779#El@%ER(x)nBR1R>Xl4Z~cYzl&SWrCzN{Z^D=wP)bqBi`-XRro$p@AR?qRzDG zfWtLUf}{b{pDoXZVysi;*)oFT$IIscsS=3{^YJ98Fqc7zQQTk`elR<{v84TZiPLBM z4$!%i+%V(wo7}w{0_ahd7A+kRzRe~^XBtQ+JDsGwXl8IOPohYp!c|?S+k~n;`U7Ad zBw+6JIJAsVeBc4K(S9|D@DOec2mbr6kZWZl^y}FX2UUDkdO+fck!M7m%s5`cS<8W& zs9kfH`kS$^utmaOgQK&J1_V>tD+YEqI2l=ZQhVO6x&@@H)XRooiEmWZkHA?BaJzi% zuT`VZx}#say@~;!B4iS(AK)^X)&6{WVJdG2n(AAHXXtI*HD&Db7C46~UF^h-^8}@R zBXj*b*VK;t{>fpx=hyRd9tu2{6V{geTpOITA)Bi1K zq~J7txx?lZN5v86a}Gox5WcD#8t6L3Ak3tzbeiNAVwwMaBz5|@7SUE3y%u@;f0GWepNtG?XWFeqJ~+pP@=2oDllUYO|U-hrdG6qu+~-E$2R@`jDie5zZ_ zdW3XiG!sY+4F?^3hFe^Ege;|`cWm!2?|O=CsHM`@NrGDo-flWH%UmHr_8dm?K5h6! zrC+(_NPZyr)_lE^z-RUjD9ygn1cD%wnM%}cUj*zYViBs@1%K;&Qs$i4yD;H zXtZB1WWk~v`G>$9Rdyoijng#gia#QtqO<9hBI_2Rkiy96phTzHF_m}` zfJukjf_~}O8wBxdS3sn*JFK+U{UoB@(UfcmnY$^P@pYPP`~2n^!}KCJJh>9~Vd9%^ zBYlVa_VP;-T3Ra@PgB2 z2PFoZO-H4AvKLhd4l#7bdf&nN_Uk<_<@Iljz|ug*Fx{@W4V$-Nd9-CXcvO%&VR;zh z@1o`yoYgW9?{9Q(IHB)`3mDibi`*HC+`4{v4Byyzu7Z)mhp{=J3{R@+Kj$P{CaY9V z2%{{e!T~dqi@L#+NtgU#6ip3Zwe-arnC4^b@L3~Oi94KEf%V>dyC=>GWnyU`(5u=fj&+ZtUlOo>z+ezEA63&&y#0pknwv( z1nOE3=jv>DknC420!OG*cR;7!o6}#AodpeFWwOGB{h%MY3haPJK5P1J1lxr7?VRp7 zU)60+98x4grl8qK)DA;|IiqiRug1qQs!4u9PO?mCUPe!H^YM$5?J*p0 z63DZA-r~bU3hG^|854`Ub0F=>g^X9BMJjNp9Heb>5L3V+p0J&Fu^0-uoK{tEhJLcIB*xN^} zThY9XrOe(|@vuOwxsH=_4TRF9fIsL zAYEfZS#Cdg1OL3Jbh(XM_J|7vw5Rj?MWz4!@!`+gMgP7LD<`k~@&NJY)5FBcc9?EP zH1G{xd3%nplj~hwvM_%Bob?Py>Gja;&BV9FAG>2beYylXAXIQ{5RAiXuWX$fs>^)_(M}fN^S1(FpGwAFsW` zv)qcQ=ZjoJ7_9pN4DRtwpW~;^i(cn;buSi)0RP$MUtddj^#aAqO{YKZE6Ezzsl2=m z;z(~~_42@WOyh%-@*Mt?&E8ns&?uSUpg`6~Dk3ss1F|LM?mQ-7=%4^&q{!05NVt zCjoOf>~*+*Tlt~Yv3?))n9cVC#0UJgH~4O0r}>^i;rXEn!QacO|GUFN-ZliG)5^hs zY?Hx|8PkWBno`k2JnGVge2>dbYYr8$GP2vbQM+Zq0 zUmb395pOody&kaqxlV5k(#X_~g~@|w?-^0~W5a`YtklJ22735L`zSt~AX5+L zJGjayF6M6A}% z5hp!Y_?&vc%Qm}?85YyNh*^u0tFqVG4Bg7mAzreuGM5CC^ z%D)BCQ>$mO*rk#>9WU<7XTmudp7^5QtO?S+SM0lWwK(lf5itZFxv~kZmffd*C1Fpu zmv&}A8HHBjbdlldDy3$|^EAgLGG6oHgBek3%{cmkx?4apYO-i69?Yh6oJqvVcDu@V zak@I0;VflEj5AT%*5XFew1_^y7GA?Uo%-sDBbfy$tM{g?*tw~FZmC9Nz`iU|?_4!7 z;~p!gMz%_^7l$+)5>rDKaR)_14@sc+LP^C^R}3-ZuP-XX@I=e9cNQ!IGt~u&@_Cu+ z^fudDzca22MEOe2C$OczLpw8+aXhl zqsv%2CdaZI(3@aejl@(!SxbYL@4I@_Ti?s%DLoxQb`n{1l>?|%XQj|LX?)&Kjyk-5 z@5N4`r_+(It%RpOF9K=I3U{@Xi9n-! z*ebmPq2V#jDAM0ZdGmN|R+l{JEw&4^ z@=l&5P;0IDfCSKlVRh%|b99^WBi`i~v!~L?zR?j}m2dX_OzbFex0hVHP#dBrup9fX zk^>{a75xk#uHe-WXE?fu8_5gR+mS$P3EZ|ro7N9fHlOpiSAo`gs-5wWIBm4U;5M9S z6GYbJy}8++!Ow6#kUDM84S)zYReZ}PX8V^W&EW@W(JaE|S;`rtt3l0r%YgX$tAM;H zgV&7+^^P3;1K%;xXgdzLCCPL=M!grmX8d&daUdwSp7w|IM(=rR#c8`q+t5;s0>dh1 z4ZG-U9;d7^oMqhEje6*As+weFy$m~8F@B^`d|iA!r%}&>E(5Qp&7o`6_WPY^P!;i| z(zm(V3=HT5OQ(vab>Y@_jIe5jOjhV1b&k#FLn9k5+PsUR^$DoQknTuu`TP>Bd-%7y; zi8)Cg{*jPCa}G^AC^+iWsIIa!8B^zw_}1QlUPUqLdTGSbsqEv#(O7uhSJ=^^J+sA# z3O$Q!^2$9M?6KgcE;G_Y!xN|sFJs{N$lxzgWb;z&8N)T7jF?FZ+zY(|6d1%}1I)#@ zIH40$s=b1)NaU07pfZM4Lgc%OTRk{><>W5xaKxjRXnQy~Arv7MB5f~H8BiJIheo`E zAPBQf!;1`e=w|mK1yD=Qv9gexz)!^_#(6+~(o?QK>wc zA>6Evu6PtK=0~!-vgbwMmM$Hz%!+K|z(4SI)69BiM?GGw&$*sinj7#-sbD<@TXer3J@B zzS(?E%=R6X0B%u!=B-Egy>} zjRKUrSs_ATjh11IpsN@+)ic1vO=D~q@VduR&!)b#^p&F$h zC(wW~o0W{IGnbV^SpsiRwu#_IjV8J*gk-ak zrF=$FW)Bj z8NN=A5YuA_1-jajmzmNZ#!dCBci|)P_BVLCPgFPL_DW}Ep>2*H?s&5Onj;zY1k@BH z1$YF#P@BB{!GELA zP>5$BT*J}Z6#87=(m6=jrL0*tN##V#rZ$czjSi0yg7VDMV~Tbj^-*nK==rSc2A=Mq z6y}KhNxv(}>^Mhmr;+BNnx+2TLpo#VHWHhsPY9oc2%!)(fk~V@*sg1WDFJB}cgP&7 zQzK>RrBZ#LT+8K5Q`qD82CHh@?M3bn`??WS%PV~W2BamliXuGwZ^F^yRJr|)p^>$P zMzlk0QJdW;K+JIoORE*;ui^)oHHlRklnsK0q2UVa*}nNp9t({Xz=IclPWQzu zV%vHC>SVu{N72X#)oMP5qCKH-;#@&3Oy0Ln@$3Py-&cw>G~=r3w(Z-V(vOt7#wxEV z^M;@2Fe6@)i^bTFy*`YWvsSD+LGrG^GeuI^O|QpZ+tQuU64NA`Bf_w%Kt+CjzVHU& zle6kd4latW06~M-jXr`ML-md~JycW4nW0F})S%3G<%S z>agh53iFfL+d|g1$g=|v_Lqd8D&;;dkGD|qc8iD2%)RBeDdLw%-=AqzeUm;?@9gt& zmO7nKVII>WDQbfQ88GbpE?X_JkS*&}m0+{z;W$CuwWLq;UMWH`Qmml>SFKQcTEaMw zOY$jsi@BKVIq`h~8eQNUow?JC9!tj$MeGwLQ;@595#JXl_az$#dv}I6{l9^)-gJJ( zbUf59WJm&E)yk76P%VBI3-T_WeD0)uh4s#4pK&sB+tUH)Tk;^pr zNTigh#mv}XjG`l5#Kln#HfSvL#`nOE&RHco zIwGw$mZ=1~hg6WNd}@Dafy%VQ&@EmGBRh;|1#}`O{OL|n0T*<%o=(u3mih7!4GA@t zk|I``$t09$Pa!TQ#SeYUHIErx){v{)5MrrsR3;PNfTp7-kGPh`S-aZDsAb&6xaLSf zj&znba*nI$uBQ7)C@?Xpi$?T@W?FVCrlhc@B`w=>_CzzIyEvK^Rzq3n>=EtTN_E^pLf4a z%mEIs8p7S_P3HM#`NsKH`Q0&yqD0MK&;_YHzZZN+_WjB@%I<+~QRS5Ej%t96 zvEX*dE9|C3Q`(3X*Qc0FJa-1^NBkvDs-AK?3yR<}OFZ>1X`NDCZsUr8Qpt@>I4Inj z3EE>052|pNh1xHOe{CE1i&y6cYhqr+K#zjLSGf_yAo}&~$5^``Pp&d;D@Q?eZKPFe?uw!1^dM7N=zmT;~D$Q#$0hZJ)5NHxI(%OHr-KdP1{?dWfqr) zg{57Frek|HC&KS8qIzGvCsJHeqwr{|C`}xX3Pe%qcyA3Yhb59kiK&-a)&K{3ffF1D!Z?PUUzjw>M>u{s!o>LUdz#;*h`I zq+>6TtAG#P))k|LJ?Am%1MSaxL17} z<4JGyVk)K`LuR}5u32z7q_-@TogzkFHb z42=WI5|52ByC=9Iv7})y8-@1TtE~rOt%19z<%FDNn)njWWT5tj}KS{ zEl(ED~o`jTHIVL#5QO4|V$ME{mqJd@I847S#aY!cVUqfr!?$K~c z8?dKZFrugj7Y|Do4~heHCO}c6`0B&HtvKc3*jBzr1iW>D1VlQ-f#6cUd%S@zHy6Zq zscczsGdGkZGENb>y9K>VP>9INefZ4*ClXcsi7)2WzWn>Y9q{T+zrRGXik@!8KT5AR@>g9C;^`S6GuCE&!QX14z zuxcMfH{#D+7CxLQnDJu$m%n)6*IXw0^1uHym;KCPWJ)i0w|+9tF!g@AzXt6jT?t3p5(9OnZOupBG6?``6k0*3McG0S zZbcHiup*NoZg6Yt=1~`+ZpBJs zH{)!!6!}*ckk!b{hP4o4tb zs!yl40lDU2*&WD%;|LNSwad7tm!MfD+FuK+`+pc3hN4*?PRsO4AHuQAFY!9HVeQ*- zh~d7A0I$b7eGVs8%Vgwvo}f1K^>!ea|06uc$~wM6Pco9i257ys#) zSZr&LD5EL23@bz0FoUvQ79DuC@`*{^`wmL?xeNKB8r{B@CZ9E*ju{bt&&U_NN#Gm- zT@jmpE6iOyU@5UeSZ=cTo?JU~gh#A$xZyMD!YN_gF!6)YY)8h?tWH*+%D3A9?r&c= zHJx<_04-3kU%tY|8*dzM zQfF-xk%nklt}3g#EJ|~m6T(Vj1+5YRK_(w>Ec5B*(-H5LEY}~%pTGkH{QUSk^)~nO zy#?D?;5{cX!x`S6j%K)@zD@pd_~l15P*o38Y@Y>&V^cvl0KKY2VI;?f1fJW!99w%t zKa!X*baLBEDK$A(* z%M3Arn?)lU0ypHxhAZPXPl6d^f}pOoHxMIzZd<@;=4){2-?gW=cd1I|mYbyAM0ACn~8mjE#NNIgw za6rU`-$jx9$6|Sh5+;R@rFk-omSpCieak$7Oc>;2Ym$p3mUd^+s9UXM4BBQy(ZkTe z0ok#JdNBaK+Rl#L!H)cHuNCrsh!Xq_lm#Y2h7@D~kZqvUMsdw)m;tY&j$mG?x(;aV$#atNDf8)dyxe5{Cy1Z4 zeHTgqCHztj&;CN&U&|r?Kc=nHZ+DXA0OqD6=dG=tOn6|7ry^>zuH_!yN}8?3)zm$BbKGAJ)A;**{=?P7H--C@~HOv2UiA2j=N z*sa#l2v^M65OQGcWS$ya7EBqGwCj{?OoKOq7!4{gpkbDi;WwK?2p5@i1z{}k_PF=B zW2_Dmi~QgfZk^=W$JB0Uno;BKFy(r*uqU3hnwe{!+s&e`q40_8u@=640?GHXEHb)x z4qCyZuMXE4zJ{b2Bb{RUfp7yFO(P21ja+>=Pu9$qxNHZ~`bhxQ*)Z`WrVzJUM$p?x zPFZ7vS{+%su`CBJadX$(h-PrJ*^hf6Ed)@2ZX9DGF~Kf|TdY+jTrm&ZS6Z~(?kIc{ zdiQjN6-~>Br@H^Ry;wHq57Ukin5BG0#Lx*mjh(B;E*ifR8zX>WNo4$yAP$4_Ey$0E zLHNAvLBl3d2kNU`YQEs*_*+kr?&VpWf@#cN8=}yFL78p{NdTVMyvaeaeT+7uo_hkH z0R2~M9izhw!b9d$nA0ZAek;8Yj>s6x;&~N($jU5;*u^hEDV~m^6WJleVAt(O2d1v%#nfh7lMY*(oBe8AejuKJWKoE6Y?;j{ z_V*3V#j@0q4jA!vGfmn3{;cy@CM3xBJZ2$`7l|Hq?R}lP%sX$S#F&!p{UJjo-s#mu zUZ@3?3JykJ&k~Vn#}gO#gu%ph6v*hpJm-8-m0VCN8>!Jy+4LQVb}goCi#oa~E&Z}@ zZ`*SWnS~}f2uf{O{Y1Z+Tk@#UHned9OF)?$Qs#xmvQViSz97qYUP#Dqv_Qj_j(Jes znut65DX+zEQ*kaiFX?KT#A9q37yzR(m)mEjiP*PYfPdqGqFIt&c}Ms`Mr#>OOW-~+uTRmxQa7e=Sx z+61oEOTl@ls8m{%vH0iRUn2G=8g;+0A?($j>O&;sqt&POW%$2o8a}%c>UG`*4_bY$ z%sM?<*E9#E*nRU2&em&2q;#bdM&}OB3|}HQ1P|}x(kYfsCf*Q5&P&jegK~(2(z;VW z2cXbL@*$gQ-ZtkT%cohIRQ>b<3iWge>Qk#(bj-b>MHr4SA{<7rbwg||SIVcBlm;-2 zN>AFUn}OoYnh4x`mDu7`#%*)@q;uAE=xuX8c7U3lm*Z zNTsL+{Mq(QoYHB{ch`j7#OKU!=|dc;*dYZn`Z9j-BG7`&NQ~+rrBY!2u_F1UU^>{$@r<0Qq4A;G zwCM9Cg`afHoh!He`die`Kwv_#z#26BY?d1^8Rk^oYp*`Fd>uaJ|55S7ecjfC8FiXZ z(*9Z9bFV$)hWF+&%dz92{P}Y99nj^Oo(*m1sR!B?FdL6q?s{bKnJfpMtGeKm2E6<1 zSxBI5^Jc$p!=h=f^fq*px`mH$|-uQqJ z&vriwoCfEXSSgAjah7wws$f*hyP#D9ydFoGhc;XW{lUn^+fRP&B|-iKZ2{j(HUY5J zC3V|jedQP($71L%T21qj-d#7e9_x`751rkgHC@NL5$PTzfP5Q?F<>c^#Qb@AHwgp{ zq&bnH#Yofrha`CBGeT@vj5i1TBr7*Xn5PLM=EYGqU7SreDgESiP~=6}2aJX)K)bMc z)1cnDHGMA2)g^iZhMLrG#5<%dJOUcoT`UMsw@?6A}XaV0!4-=t& zptU6g`2dFE%NU}QC}^#nEeY1{Zl@G(ZqmhoTkCufsw}=*FNcDcITBidp!D|CS`}7q z6?~}v`y-+B&iqfQJ<$IjY3~@M*|u$qR%KS&cBO6Gwr$&XrEO<^Y1_6dZQFKM8ZXy6 z>%O>g?%O-g+xN$e8FT&|F-C8FwBB3mwRQ!L8>?=%2HIRd5$B`jgOjm50>Z9Gt&B$Z z!UFqhjS2__4nPi17nHbc?TJvu7a>k5S65{MUQQRv&rBO3u_gC%>Hb(n4)jqrR;hw6 zi9nEBMa~IV@@r(jBFin_q2a4IXa^E_yF>y__u#L#vLeK+)M=q!s;g?tqHK^`E{e7( zV67_Hk{qPoj!JJBU0r~KC3J?_$r=`rijyZI0yr@HBNM4nV60(^jpONeY3hT_a&Vp8 zLXa9qKDQFfO)G-3I(k2P+hAL+4ev-@ma8L+Sr;ivZpo7X1$9PW9FrX=^ zGBZQx*FOS~dRj~eE1&eP*+c*8x; zILy6+bJzL^!}^7fV=U8nmR_6weJA${i!rD3Qy05bXsTEY7pC(S6eI~99r9jo_`O9M|_m?4f8;{lF~27VMlY0ITK34e2xha@pBy#P#u zjn0u|qARBp3w(37q4+c<7y+l!o#HBxFO&dzjX1Zd2$-iJG~XD_d5e6s z?g18BpCFxHfBM+Y$k$+WLOj$+9e~&X(if?;wrmb3dKVNXWS0PG4t3>ugLTk|v~04| zJi6O`xBK`M5X9?oWBb$-0avR?N6&iS`Q-XG62ZI2`@__DP@4(!5?Vwv-s_Kg^xN-< zgeO`4yOV5Y)vq1m~5!j3jX~L1Zh3$`$CYvJTSjW5Hr|-W$ffmkxQ!Yb6Kd^A1rOn<&&% zImwj6i7^ZGDqINR*Nu>?JoF;@1M>sx4kGzYqW%1s%|7c|qR)9bsvn2d2qdHjNeBl? zo3O!dhvjUI%M%uo-8TT5UrkzQ=js@nsq?vglF_M~`{g9n%t(TiO3m<)rISK-+JjHK z`d-b-)kd|anx7&8Mt#koQTh+ zQu=4kj^o)8n&1lk(PS|#%~8b*T*Y_?ZrJLpd$IwsR@R`baG3Eq7@^V}DXYqYU>>pDuSSc2E2=qsU3^=;!?EQa2K>ri@nk5@`Zc9 zQq`qxjZu_7%r_kS%#M}FGlfmJgM=wTN|-sNtg<_4m|M*H^9& zuI%C$IuiML9yn_s0nQ=ii?O9>d&`vlyKS}Xh`kT3l!`&6=&ig{&$t+G=%Zmf)StzY zuyj4y1?1TVzi^Gja1FL$r}bp#ghEbw2+u>a234>Jt(}H4-C*0_S6Mprb}q| zP(I4F8qz@5WlXDc?YRd^L}EKO0+%eC4;Ya(8rGDSai>}?*j6EsIyI6U*6iENTV2-d zFC;>A$W=N1P(;FVSiumiCZXCd!>m>ft%p*aXwuR zp5UKQYQkM5E6&3wJ+E%*vdxq(DRJKH9<8ow(LJ8GLcCzX9;cYoI#n>|yJl+V

@` zL0*D(wkr$v`x_6lCw#)A>3xO>k6t(XcU(P4%}EB9RAm5~T{k$cc_#&V817)G1uwE5 z3+^9>N@+`pB?u{32{0eZG8TZTM2JOa$f3++mwuJ|v~Ta?eCI zY~G%dlL%s3tnfe@0l_$3XFeWQOf(-2Cd%`WeB4CbZ_}voakvoVTf&ZF>2)hRGiqT2e@eWmKZAuJYBjZ{MpmJR_RWuOLdZ#ti;q!*E?$@JU z0O}+CEUE!W^#bCz25Mmvsx}bAh zkn?M$x12c2z-*4Gt(t@WTCgzMbevT5Z>B0IQ_hqiW-D{;VqEA;jpONwK?8=w?s#7l2pEj^^r zT}_=U+qI!pN+^@Ab5y!Ti6_Qn#ouz@B(M-pH*w7_ zWIeii)a5*uc8BJf;WDmzo2M1&{g#=FKzA6)0S$I^!%gP0*M24J(U?`{cfe}q)^j9$^&C3ozuxo%BWt+1jct4B_OK(c#){#5gAM;_90 zm&=p%3Pn-zPjDd14+=kKLh$7{=Y%PHTnm)6()x=AUdX7$oqQ@F&)=K!x8Ejlhgd}W zCpkuquN2NR!#fG3`6x9w1jZKiQ6wB!I3-bDwX7U}Jj{Rj3l}^zuPIn5i;yYj6-34M zla@pmo12_CGQPeESO-&iF`{)#WusXFbo*w2?U`bXvom+=A`-LGu-L;V=P8m4ryL>^M=VeB@<+<+>d9iNiv((Z-)e@? zOWM(zlq(n3Py@JsIij70>+UPKZnV)(C}y4jxN*A|j}o~*HU=Ip9Knvb-eRV}# zCwBxs?sH1%((XOpLh>Z54w7#rDLiM5$6iSWz40agwyaa~AyXYYbI9z#$9GpGxJ~xr z-%RFl7rji$mhA4J^xWrWC+JQ@+gI&y7T8SL8VR`t>&N$Hg4_qr*WzIUx+Trm`LJRd z6CKicUOr~hv!aLIL+xj}WCjcYi)7u@=wk>5kGXCBX7#a>V%lVYjD(949}>@>zDG}( z5a>6Rp${KtA3}EQqF=D0D@sejGB)|0YO`rEPItvLN$-luIH7&p@+|E>zHX^>+OYn; z*_~8zGbPn$IITFhl+6k_7c}EJ*0jj!@1P8&-QZqU@KR_n1Z@} zJY;$1O0SKQ?rM0+NrQ&rYG~<8ouOJbQfs?0k>uxVbb={>l22?$)hy0X z)>t9@kST>>S6i}PPQDS6NiOjkmdmkuxD)MaqcY6NICmp6gJUaB?iu@i+;WEc3S#57 zi$3raket$a`G(M0B|j$OL0^O}DQ7Z|-}B6MX&Dt!=dpokO}%iIRbE+GU^{u=Ci&+m z|9bsWv5e&O+V^Jkabw?Nu0F08nSJIm6kPJJpbATnUW%YKc>AZTW?8lb%~mGlYF#rSIw+NBxI%d?^&7*M%Spt~xiR&2ub2#) z6y`ZtFVRKF=c-U~b)BSkluJ$tLD5hWcfpcnb_AwucTtXBp#EtP%%wXN12E^1!<3rL z^nL!Z;v@ogl+Y>F4On%+E~;@k{Z`N+s+jfcgNBcC1xH!s&fNexaet4oGgC11_)cv! zDRlK`J0@_xo5eP$jm!8q1<=`1qgaDuUQRd;PvxZqB94Ty?DU192bxOJDDF?vAZW+p zPaU^lC^YNV`ZCCfIVaZpxxqYY6J@Y(&rZXpiMZJE{Yn^Odg!V>vBXXh9Uk%4HMGa< z0{e{k!3cG=bWI}9`RHf+Q@NyXs~N#8Hz+fNX5rJ0!FEX%_JCl^mY+lBO-A)Q8)&&` z)1)NBun23PP}-#41vt(90Q&*^kn>tZ{>&276V8Up#GmX!Z{Nb;i5lVWgL^`Qb7&s| zAXB`;c+>(VTSN^AGIw1e$g}&2nQ08nT4H(!&;K5- z0eV9{=<`K0&4T>9Bk(^jasDgbl>VO$udMmC;gLUznyt^uK$K`U`Idk-Rpj!)QESl1 zn=}gxMP^bjTnZ(dINLS^b`!!nGSEK*rVIo^=|8^tCeUY*lhHqXuOyj!o^&;ta^_&v z?eczu)`Jcrli6|l!7WEXl!?GZqpublM!dT?5=#?$Vt`CR6ShzbF23hK z6y&5XrAnlgWS6-Ur=V5Om7lznO}?(Ja&Ouu&xjJRbhd6z=Dbm^t#aD5n<}l^j5DX$ z!K|aql($aKV|!Ya#){Q=lgKcveFoynwIQQkW$uRRitZ(;9vt#XC9>kgJ@!N_a2k_o z>p3rF*{ZT5-8|%;gwJKXoNVY00s8sdEDb+)UpZk%Z_+`kQoTCWM!b5t;AGN%G^e6H zd7E?8ERGAqWC*d~@o}8C>bRW4U6M0+0xP*5z}ksfEs+{)Cpbh@WOTn18kr&XJ9P-U z{}-LS^@h3%vyK&JW2EuwLc^JZ>JSwoq76iUVx*3Ks))#tHT?uWAwK2eVUc#5XPz+U7_b7f2gz%6VT4!lmWbtoqP_(f2F%Qf+1zv0&}N>W(wDJIn#~6521pBnEH)Gb%-uis70GKKWR7+Uq?YM z!jg5yrz|i9bL(Nu9VyyYk0m^92eSy}&ASHMp&vg2_V~)|veS_yiW(I>{0y8>^Df@! z=TtN=I~1+o!s8uIq{4EabOB&!byeItMQ-UUPdmI3|)@(R9XE)PGi7j?sb{)MUoU&IJ$1~(gFLzJmS(l{>{ zr~I9|92m<0dtK-}1Z9RMuUC6j+G*{S+ZZ#~!ULgTU6xSBEsUn=#}3nB9O?Y^w;1s3 zU3RWM5}jR?9S)s6m|VEwk~Ux^;$=_hdS@;Zmgs~@(zZY(>JuVR2w?QQXUum{vqI4t zwbY+;_(Y~JCo9-}Z&IJGe*sVMuL@P*uR>bpmownMZmm%MzXl!^<1fq3FPqr^19tv7 zg&Qtwb?d8;sMpb}{&hgR#KJ)2%=o31vkJo5!Nyi8R;JGFgWbf$2>CPD=P?Xf>X^WO zPXyy6NBbF$uahfj&wpOmWWUwBVTJ^20V$>~(&z2@00F1U_eJW{@ehHG8nOf@&N|W; zBxNn##Ns#H#Ot@vaBVfU)LVG=-CCh1K+ZX6QmZyi zpgv~YnT*jF9=ol_^|8LoUN)(d9FLw3!#)l`&Dcy<%4C(rnuel=A86QT@@rOh&@dh+ z{7IS>sU5BPxFi_8a463AC^dFOi_@iSS@YMgF_M(OY-kEp-P44IHJBqRn9xC-c!3O(K9NUl?Hi`Q4;^gT$|3wJoneAj zy$Un(9xa;Ir*0fdtsz6Z%z>(zn7O#y+We(}LsD+uQ{Qc^OvmKLVaXRmZz;I!3-trx zn!QQQb(qwGj@%3LJ8PLi3J}8-Baah_*Wcc!LMKSxlgI;19!5`;)-?(~msFa54#w#3 zJY_>&T7OjZyTmK|xF=`%fA` z+#FeHS!}$v#~8cJCj{4ZNG}qEe(QKqsUOaHi=(b)8RFbtzm|D+zl)iDKZg2+0Kw;b z50-0}68%xMD6H$uI4kVyjB9me+dqP5jPvd$_(Xk)m}Xb~gd-qfN?$P~jDUHmZ^nKH z_SeowJdP4_{lc5xe~UM=|NnOW--eA!wsy8(&g6Dx=7z!!4z>mP{0dEqQ1;BP74|PE)Y8y^?Bvsg>J-u^Z|I!@WAmTl*|~!E-6}d@K$a%s**|xE&vf)T@;Z9G9ou5{`8FLm zg&a6@HSB?nx*O{M9U79JXh0sLAJParp;lK!_1iE#Vh`C+AbLuzc5gXb?lv}zh9ZN^n3yR6)i~^%O?DnhyWf^b0cEx7gg_~top{pQceWZq4dao zY(f-_ItG=#MFw%guB|5O*Kg7Yz~&sqi1-PP_m>UHInjH}gE^12mT3WV>=Q-0D@Kl@ zl2eH;A`t~lj0h(#PMT_)3Y;v9{HqLzWw=q78XjtlR+tAF)AdAcwS1blCU)7Z#)HNM z7%siphH4}@=Pc42HnQd`6*3QP5hk_}WnX5L&g~whl=CZ#(C?=vls5D$67?D!gaii& zA0Ckw5SF)IEqpY%(Ztw^yKgJ&DT}{HFHsz1`bd~X+siNbAI!tp@q{@4AczPQ=;@Ts z@JI*FDpuVgK2*f=^lHrJz--pi->T$AcsY3*SzQFE`?Az0KBGa3Wi0N-7q%=|H+a4? z>^DU_hmwEh#L+Q_3~Tf~ecJhJF+VF7Kx?pbR=HyOr7lQxpvvUplkP=^V~mfomG5HfsNR51j=3ogYPx9-aZ=E1cLW9-psU`{ z94d8?LVM%RG0>DfeZwt#665o&*hTUh?SC7f$PH9}G`q@9o!uiU&R2WVp`PmvV6!rE z)EH%JR`YAik{jHiFGXk`szNzHtIi0#+_%m6Py}9-S{yvkujsJt*pN7wB`HRxPpt+< zOt-Lzpuu@n@%R}ymIRj#f$DBpn^Wg7U1JPoebAqexL=TbF=vXiWUq6`Gj~y;4%A8u z0Y0Oa`W*Q#UxsgtFHiM&1G;7@1AA&uxfQ3k6zNQ*nuB}yF1M`QcF?UFCl1;=R}&QX zo#l#neMKOkS&bA*I!3@|NkM}Fk4B9b>)9)@rm^IHZ*4+amoN^Xw_;?)5#e&I12hwi ztVm#+Nk@UJMKbAN`J2KNX9B*MOzFW(dZbf`e!J2hvdazl$2ri#gY29=*Q*~5x6 zkT>c`Fu@0M!j5EYo5!3hxHJfo0tQp7XKF{iDd53lw|COLPd!PT*+|Qd5c0P3xVNg> zLn^jP5ajq<#!B|N-RuRCtO)W4RjX@}cV4ez9W@pdAmY9uK2n_b$ER*8k#v3&npM zy}CO89GMPdn^rZr&jW3o&qb(&{UaBKCJ4NzEHiH%sm@5qIu>Vb1ybt%gVvA}`NK-1 zC7`ymSFE#79YnR&mQ>RRp|%~NOL_p6wXbqF{u730|gv?73K^xnhI$0avX2goukuDLS<+~@D|F;?QAE=1#mH_654>2_yPczd$ z!%7|ErzTX1fESap$MdUC1N3hMzdK$|P&}ET^8A7$wh^kSt+gxL8m7B@-{jTV`nHV? z3x$qGCvT?&wnV(snjef(A&Z93B8Ia-ZMfOG?de2xLCg`6rATz9E|=90ylDd6Ru;1lN#u zS?3gFeKxt_49tpt9>$XH2bLl05Ns1Y2I@R%NCg@<=h4GTu z?njK~VZom?90?l;R*h3VT=6+8G~ZY4f)m55v^2(`&64q#g!86;vL5$keU?tmLnSBE zJ9C=jjztkcHN}ZvvPQ`Z;-)q8)l(Y=%ap8hE7$y)tY8s&whk*4yF6qteZZkML-ihw zVQpewf`x5@aI0TU?1?rWMZA`}XVA?Al4#RYZ!=FIItY>4K*z$JM4|GFf-4zR=F2tk zSAZs8hQHQC7OM5z0azc^0U@}~p2br}cwo6w7eJ=xa9~9^#hZm0pw@M^8oIkKrjPwr z?}cGD+!YcTF>}w58pKHZp<*`IHh4`tP(p64MJuyQfSF|6Q)dch9Z&FgVA_Pd}5-6T)^^Yt}u}2W&vHO-rW?83x+6t8}E0wgp(pB<( zEjc+C)dKu+Cck0RMy#|P4dhCsRAP`rs#Glk6D51_XrC%~7l8;FTUj5!x-VJq`y55I zzDO?;Mb>~KWLM?x51CQcDKa;eK`I&XQALU_!jY*RcaUObK(8xGN6s#lj*^|spu3ms zAV>$%bPaOx4;Nnw6v-Mkgh{hQwK`Kb|L>^Ftx7YVjiuiSr>e}bmyG;F0|U>6*HVP6_;beP-H!0geWxw?=)oI5FSbiHA}8;Dll?U2l082x6QuSf|v>BWK8Rf2g5dB*;M-Odu`mjX(z$Qag zF-&7#zC<+3waU&G%wG*6G<#tRza}$awr-L4600n(KLp%EfyXw1_fXdpg!YEtK(S}7 zU?4G_(rp%3kqBQ6ch3qompxDs-_#x^&Qk73E*WyTA2*leG6DqCkbeu_`+7+5hEBaY ze?4N8!1EqcWqsljYd83H*%Zb8&%=2|wqcXeGUp?v%d<}ZW%KFJ#yHNa%tlOATYmEH zaOEnHd0bUV5i9Bh5zxK3Agb8`H=`_Kjw^rL5=hGOv9kOV@ue5S=s!62TQFN<3A~qg z@e5na!{Ye`Ejj~ls&W%(68TFQhJMnQm%anuu5~`WBaXap%Tv`EzylY11-Sg&Oji8q zv2!ycw19x$+jMoQI|qmEIy#dEn5rXpj<=tPq&Gja2BiUg*=_;PlrnpUn|dGORcmat zc`alt+wpGDyvQ6fVd4N}(VO(t-k3r04w}hr(p>@{3ZH?av!@`#neHd$CYXeVe7~pD zf=ig?--v9XHbgflt8ECfcaqh9Zk5A~X8TkM2UG%Upwk0s5>U89OHZ`kUKT; z{I;ooUClUfRp;6{Oth(2@0tDm`4{YG@Z@K5 z>=VYy?93hCRk1Z#ZsYt1U?}35XG@{n9>ySDDu$zbJ8}DCeA7U~Zhsa|`aLHilY_!dUho&SsZOw2 zkQw7sYpcEmOK!$eiOH6LeUip z#MBWkA&9K;ryH;gcKsB`>`%w)Rm>fJd$*%N(zGbB)OlM2Kc9J2K9=QX%5(`&m*H{8 zb^1O(Ql;>art`Fqm3gI?xrnV(%pKyZDUgqd8p}wTmoUQuq2T-wTI~kTp0d z4r^b2ePGA{n)J#eX_D1V*Ed0RY*$?zotsMyo`Fjf^5GM-TN~)%x}zaOjqpkZrbfEW z;_`7U*o zv-bX6JSrD_=Oi9XPC8o&^T#4tgNb4xq_=nZ&7hj+Va4#FTlNq;?)c^KYWG)*W&qzdk27CgV%`G%k(WRCtZYljRg(|Rn{_MEFX;*O{7h)FX_Cs6O(US5fJ z8v#uyjyW0k<$BL4_D4?MOV`Vf=cS00Z#;wXVf>L8HPQog$wTy7ETun}cEeG#)1I)A zNV<9!pt}Z`frXJUI*n(AP!%=Q8SFNCVEhP`yJ-Z6AAeMYAC=~ukJ_j@gUnu1LUn_c zo!!Vge28(8}`7KPx@`5Q5f( z<#gGL6-Hv-Ovdp$3#o`#_l(d;1YwXyxy*WWeYMuZZB%o!Jo+s||FPWL2bIdq3wdg> zI%8_@Mf;S>gA8@GOX=6E%`y4gCL*zcE)w9EfjZh^ywij_*J7wQBmhzm+SMdC2=H@< zf@-0pd+shRwLL4#--|!hFW+q|Bj3;<6Lj`mBd|N7c9uYMn(8C404nU)k8f%3&{oq{ z{S%8kc7~tIf!xo=U7+mihPsIQPP*}vW?27N_oePi#M(Qlps@~&fG(?A>0zu42UUwJ zw3{#ah63gwXfi#&y=UG8B>FN_|NCC86JcYGh{1s=lx?(|%M^+zdLJZUN>$g^qV~E- z0l1kV0nvdclWD9!za&!~1bto5 z@+iq}Hy(YP-#)T%8FIGRK4Nj!j*k~Xnq-zw@X3r8LCX5CT0g>W0&i;OTSi1u#VP%v zYcK}Q-|+n}mDL*pF2e1$yT^{u12@~|3SOU&5ycRrxIU+a_dEwbK3TVgi0wduTgDQv z=m#-*h7d*UafPWIKYq%!`=dJlw8sCrgX}s{^NWCHhlxjz{^M01(NkNZU!`qS-M#w#(URaAzR6dgG91?R zDN~>yN$0v*(z1Nl9k}O}F>mC~CMfm^{8tzZ&L;6U`KrQ{{o5+ce{u;{w6?W%GW)s( ze-RA-orhM@RzxyI_DS}l5=Vt6vdEFJw#Mp74`-?TE|33U;B!~n)WQJ)4Vv7LL&2INy_%c^aai$+Z8w**jesec=9#wj^_w)1bFOtUE<~a z1k&T>fidKa4yl2`zz+^$Ll^>=fuyG}q>6;IqkzWPW2n;)q{rV=`%z4f(Tf2U zV$7^MkH|hoM>QvoUZ%+vOD7SA(kbNO?x3KU8D8luxol%LRAIs?+{tCJ609+6TT*3{ z))1Qve?B9zmg28OV$G)g6~6~eh`AhQU8vN)MUSrhH-KwA6= zLSz&#B+Gnmo}x*Eftht@QuA48a6vMxVmLlow!F#%P^AW<$&6k!Rf>*?Y>-G{mlAPA5Aa5;lgxo&6L6|aMZjo1z9waohV724x`Z^9Bc9&EEh{Sdz5~x5d zGm=uQf0ZoTGlRZd39Ld}hn&x`Ib`;n8dV51)x1k&FCPG~Ctp~&LxiQlXq1R7Qb(7G zsPE^949MkQ#Z7BP&D38F9&0qwnUxqrh_Z~}B4wK9{nT_%7x&PMhMJ+}FY2uD38(@& z>NqCG-XQWFfI}7zqr;>%UCXK(Iy*=TU$2dJFy&i*Dh9o*rMu7TXJivq$~D;Zp*2MYosj7)U@R-C=s2v9-ACN4u` z-jh;ONw&^qs=1AU*6tC71O=c6}Dg``R}){@ujm*39I+om`))>5>?VMX=| zj6qpP#`hu+KzAe0}1ump{B#Dh$F;N$!;?Flkrf(Ez-Zsg)aQ**6p2ioA`YK&u70 zx-8luS36xyH3H|FSJnvl(ib<;o3y-JWg$e@macTAEnPA6)w}t16HO$-NDTrS5EIC>BgzI|I*JXf*Y1kAo^t5D()%^{#1u5qG^L=Ax+GZo* zQxxu)d6X65mgh^5wtN2V^oFJhPkirch7ZveKgj!d=xm-t%usVClG}+2FLDE9loryI^D^&{#f2-73k8OY zuTstNdQ0?pDFj^Bc~g`KrQji3&O+gKlX(7St%^mZJy#a}S9;`oA zf|tJTP3F@Y-oiO;9wD%XipYY}1%fkZ!6f)25$Pd^*g<;#-X$P;Vgl%Y@i_MMA&EK?&;M$sKP}tGH=o8E_X+L|<@AnvdX{{TZ)Rlwee>$RYsz!| z>apAB4TF!if@~LE#SRFAzfQg*8i8NLI8qovL`K9H+E$M%7(xn?fjFNt+`NOliB@z1-bI7>lu!-ojO)%4P;H zDP_?jE3WX0f0~Uzzy!We}_MY)5PNhNT|Z%?T*u;{fbRY!w4JW}DI z1d;SlBh{VdWW}No?;3T*%x6h#D$7M)X(q4A^a_k*aPu5=vFh!l$3n{3YUGvX6kAfd zv7_Zv3p)w?FzzH{(@)3dadq$u9IzDMw;g2&2lZ+h3|tQ$8y^aRCSLPRq&nJQjdSnd)Jq2yI z&)UqQ<>r9FOke*{&Dv}YR^ftp0>INg1LVl&xds)#=Zd^URVRX8T02`4GKndqK)wfF zdo5Z2K55gVSWgFk4;RCucHIiaf27UG z2@B>#jiD)OD3Kz#NXc74ro=n!WpH!Iz=x2^`|c5E6MTJOMUNsrw83Uqims3-QOFFb z*o|d2MGn;yY3EGFM{wtamzAKvm+0UMob|XJPd4CJid;wvLO&%FjWitW^jHA;t}Qki zeS|)8tUl#<-w=3}0rF3Wr_|~un5?Hr+a_9e8;1{SnrE7IAtY6u9Dpf8VW0|E2;;n5 z4&~a+_Zc;;8S$ztjhE>`Ix;{MBQkgBHph%PfbuD^crrc$9Bm6~1T{O^+efU)F8T?$ zVcT+bn!nxP36k6aU*itM+9S!6`U$(*o?1$X)y$CBNCRSbIl(@Q0rY(yefQIUO1l6A z&nIkZiY_bU_HSns=?R_QsxM{f66F6L9sm2tR?+_;I?6lie>pV$m$%8^eHj1LepIY& zk(H5sF1wsuOo}@aZH$$#VRF|NwaHpWlWC^4!v|+2pitVBIWu85dNL`D#x(H;1$;Pr$p?v&IKL`S&08U2sSEmgDmg72n?#oYAjM%W zDiBg*A!-QWC+B7HKYz>K!9Qw+U zH9GO9o8#>?R-iR^xCqB;FC($J+J6R#H}&j(rXWfxk(-XX1rKM+fETzq|0W;ImkYcV zDQM-9u}<{}bgewX6q3DS4fR5~boW2Q6l%2*hF;6b!;)1vv$z-{u>utk&%31!D!yjg zLQs4I32N$@*enl4Z5_C+y+Yuf@r1DsdMZ*nMD`$oG54w*Xi?GwaPZV(R$ z`G)6V7x;Ymi{~gN+kr~74{G-<`oQ|K{1(I?%r@k{h@jf6FK|sSnL=O{ub_&E^^+N} zKF*z&ITJh<#vMxt7;&o;gLegPgtq2Athz{4@(SJH0yce0Hg47K$T&7#CrEUekqvx) zi{^S1KDkmojMu+WeDcG%IBcJIN_U6JiTdC*Gzp+`id%fKj_e#*Mq`=w(Gkp5GJqNp zLEz#ZzTukp{UQm$zzc3%87{seY~q&}-oGXdx&Oxz_U{qy{}@tymDFua|0}K*sz^G1 z#nq3?4vrHhGXmgUp+Q7v1|sMj5qgL`J*VANJqNg!iDt7LBLk=czdAn*;Cdi!kP}XqL3U%X=%b&voe9<8YV1o%AAaH5 z)njcvQO=c&`0pIfStB^e@Pt5Eux>WoH5*?ejG2tEcX;vjS{T@No*jW!I*z7{F4DCD zNh^7(m9qqzjR7m3^$QYShBrfGXD5baU%Z5Z}YDCutXx%u;az2{e1_85FJd^ixMfM&gN?=l5N*6L$P{QQ&kU|aHZF2fZ^h1!AYML}~x+#)1%~QoVdBHOGff;|9}B7J{P;msyU~u4t~g z>=%G~*|z}{@F@|@rJl&Vz_n6y=7+d-DZOP~5gTZ1;287>38+9FiK=PY$oNKqg`K zBZ>Tm?3ss$Mu9Ta%bv@b)aXv`DeO}({mO|I%f$9h;s6?zHS7I+NvZYWduP38)=E0L zd-Ik3F01WDu~o?>%d5`AA$}J!F%_MANf0N;+A%!E1{!eR`e~As9-%rCb+U*5m_JHw z!}|QO`5pqYt7Y4Nv2MF3O3}xvU6#>ur2tc<`cSB|qNla?WXL_67t_ug`|D+3fg$3{ zS2f}Ye#9$G?2W343ZJ9&K^GtOh_)&8sZi<^8?keS8|~3JSx>5It1Yz2(QJyW6AI@@ zPvq5bB$XpmI6R^h?xJ&KIqUA2jR_YCSL-9Gs$$Byf%Ex%7?cMLz8_EO+zRV-r**M+qS&EiB>9a1| zNmj^tth|Tzh}3Oh#J?kp@IV5>=}demR+Q1hNFG&tW#CH{m>n7Pl>dHX#N~`CII;|~ zmn+n;C5AbI&c2>5hUqPCIJLBlN5^9e|6!Y++>&Q(DUg6zeBbUH&k!lYGxmcyz-63a z#8Jv2D6EpfEoR%2s7R*sn>!Po-yWGg_Yj6__$})-=HX2ni8$jfO?gLuHZ`r2!3vm?J0bP zT<(bwUH@yfKKAny@ zY*rPaobp*~387XEmpb%{d|{cv6ius2H7!nbKDKXZ6Nxv6rt5S(6{$P&N?YF?gj*^` zQz(g(^j*K>BJPVyornCmhJe~pd{`h&9WZ6{pHipO-Nx}Mg;*9*AfRf3fAA(UQLU$w zVHFRn;S9-8g1#*%G1KgmPKa1`Itf?OQ4_Y%jF@L}c|b~^$9`q&I8jbckr2)9yQ7YO zK9+N3ljCr8GHshObkye&`01 zlm~QT2|6ocXCYR?mo?9NU{9%<5KoQWxIy>%x1(3La-RSz=(le(|CS+<`_B>TUz;T< z{9{QcUGIV=oxV8rg3xGzI3WCjSMr32ppi@=0&Ja4l0lzVmquP+|7TCNv;i6U?fVA= z@6UIH-Ar?`JX-=_*UNSGM}TA6^V?lN>9^*YaQNL>DhjhUJNAJjaAPf)TI^ko&@<>i zTIeJ7U39JUr_ZN?piM(|9p%b4t##g6CTlnK7f`5Xxo9GB+jchRd zE2%B2)>9-_!Jzdm6Cf{m8lC>g(aj^44tUUGfZs*JF_bYOX2vs-0y|})j=4}dww<}_ z-oiBRpM}j->m=-!DfBrpW*zy{iRVp_9ddHvM6fL+K)6Sfu1Blxilb7>qi2!p8&(d` z=@jRya9b8&Qh!SO#OP0g^LSA>WM0I_461Oh9JX^!wqOp%fUOZU{s{MIqbqeI%3ONh z61Qb{LV;N?+5KUmJWoIM|FHJfL2;;YvS@-k!5xCTyA#~q-C=Nd2{yR9ySrN;xVyV+ zAh_$}$nLv$@7q)7zS^mxYHI$Ze%@bq+Z__na^-;o8{gRpJ8rYDrxH3zoV^0?qrWt) zc(WXj2I_MFKOHiJhg@+!L6LGevJmaVvlmvkdii|`Pq3ci%;{L*{B%O|JAbaVHF_%( zGV5lFsh=M8C-Nmb(Q}lNG6276n+3YZOcwY!2Ayb5yZxekKzG~T{v?*b&gEH97rga} z**4mV>g_G~unOO>c#Ty1;zK-c=1jEw%PN-e&p(Hu&-Aa2zdrzH-hUL2`}gbS|EZ-a zYGCvs1?*13^!He#tYtgPfcmy(DnpM&JFBlfhzY)8MWjvACnHpnKT`lQBjD+(RDNrB zI&4qY9SuUrn0wiUxFtp?D@j0B@S89aHG6kA{@lx@b9d9%=MCiIQ~C!+$xEPma$%qE zN40?666#FQ?A74CW?F*pFwdqMg_Q*#fhYFzeGmnypG+b`Hb1a^IG;ix7Cm)e5*FhY z+%*-ATa#-z@rCBp5$F+R)QX=PxIKI9KkIW~S^(|E%<(gwJr@Q42kHsB%i*Vs#Df zyz#k>_!|jk05nsjrpiTY$2PNAKiN|wMf465)#P5UHu(7W8Uhx%RLK%OUPN0$u^wAc zw&=J%Ta-YWe}$?EvH2dZeu)IJ)CJR9-U?uDZ~%$j@xblCISXHkB?{|d`jHWjB=kF* zj&k5)A5J5aHfqP=bYfQh=0qYfIy|<>N7CIP2kdN?bt_)FoT5>)735PL2}m22acl zchojxj1t!Xh|tR|KaDqtr8`h%pb)TNqD^?RO;t6G9l~J^^QiO+`^U&#t7idy`4MHm z{!udP-{bU-wx-tfQnuzFqqmK+g8{(iW9n8maJ2jzr&reci^`~_uBA%XNTe%p3G!Qz z`>R`MjHr;2p_K(ukgz*;Qm&4bS^Dp)WDElD3xWq&FS1%}Zw9_+f*0yvsk9~L1bbIC zW)m5&cNyniW@eo}?>AUoG*#rWeQqGo+H(hSY{}1d;3zB7X+tEjLDq&NeGQ?w0lCIq zT~b+k`+1ZZX?sy0^xU$39HNr(OVLbftfxF#0o|l-=1JeWE`}CLkuOhm&h#;zP(0a$ zIxEO>;E15j6R!Dz(lqTVXa-oKZ35_vVc`B62982tS5YV}S%xjI*%6u>rU9Gx7Flr? z`_XU-wXV}DHuCyziOXi5>)4z$*{4)OUc;+j(I6zN;`VE5>0ZOstCdJpu5cCf&^pWS zxx3xu9kn2p@^)Z<>8McW6$Z2ZV1EriunAoh%aLaJnJ+(hA%y)ScG|~b8P;2D!n$4@j@ECK3!$14yMakj4> z?84_lF5kd+@TMnFf=l#as zs^&Z%v&gvo+V=G#v_5KU^G66Mley2s*AvPg@vPAy)L1^$XZ zO(e4)Ny`$?7@y2$tQd`Ewk)uhJgSoJE+)Wi%E9h^WE%e((v`~GtWKRb+hS};Otu91|@ z`g}_0oF3~b@TpT6pSOZO+tQ%uW&A;zEb5@zV+qM+I;Z=#Tr@xm{wiORTsH0i{Z78Cwk};+atp&+smee|+%o$_tRjN!W<|uv#Gi?=ei3 zYO?t@HsD*K^)}aQE}6|sB+f+Zt;kusubnNO9q3vak*yMhJn*}fPo=Uh$zRrF+2y4# z10SVv^&cDXzn}H~3?gY01BX9q;$JcIUm}R)Z^n0}(qE$1s~q+y+SnjqeUZ#l1ce1f@7D;k%V6H#YIGkK;}*r@p=( z4$^;;vBFRg9uE-{<)OzA{efX*ghx_RQl_I&yNjI#a6 z1=kqX5knqtO`nj34CpIF4#hZ`%uOcqyK(8nH78X@wp(VzTvvXS$eD))CQ>Fh3V;uP zA5~_kK@jTiD;lsRwVkaQFEnm3_W#vq#0%_^Qo2uz@FAWYr;UKEeafd9io)hTo;8W=rt!J;1(AlV~!YE2hIT94!x@}H3U{S!Ry0bjn z4h$7S)edLxnTX8LmX70=et$RKTH&_d+B8D~JiD9&>)i(YeNZ+-!$hPn+g+(xL%NE~C%KuPtM&{c+H z|ACH&N$R~L@Gvl=YVX0TMc=PM73S=qC8po|!N1p@Da`gETWY*{^L({7z(cgBw*0OT z<(~8o@<)~1I_PmA{-|N3it=CpsLFY#@b2=1|*Vg8gvpal+^Qav$eA z8V{ZbzT;g=^PnKU5d|m3VQhdIuWLn9%AgJn=LH@Ox4OX)tME`Xmc=TW#nVejFzt45 z(K;K~-6{{D^2vJNayqnShUn7hy6Cqna_P%>vzRDsrg#-dxWexvhFDR4BMPV1v_wrZ zNNr~@P*_Z|%4*Bsk;culRd$7#0~Jcy8WjT!KTNL|Bq+hZReE*BRHi@}MA%BvQqe{ja(B_5h*wYNv-}A$t!7N+N%aB`O%`PRM_h~q) z;FFPYW$EP7Ij-xin@BZYp{rD5T|FnDgq1ZEj=jQ~9LKnFIyaRHnHZL)a}xnlfdQU$ zs`i`x9AR{1r;MT3baY#vd#}HZ5AWzWDRgmS%(@+I#fA^M_0%v=1shVVuzB}8&u*3z zgfSRELD+-$hJRL-bPnU!4Wkp6;P`Uz#ek_WVNw`lCHV2Df00u86~{7R{0?y`N;-N1 zC{6DfYb=h&4%j#X1v;&qBIk5+ANms++;q06^t4hz#{dOxT=<3{;u!Tk!=B8($BmUfjEE{nKh!+e(SLv3r#Rj>^Y>?B0a!yii$J8-53f?GhoDTe58!({cQAYR7~ zlZ4mXeWsI?_K>sZT-)*LtY-htiw+(J;wZ=#a?DD&p3zL+b9L~XS!}qwUX}O_N{oOisklV5{%XNvu{KeiUQCNll&Uv$0}3Mi4Zk0k#2@%P_f#s8<%{O_f(Qu*&zMB*IJ#X>7D zAYau%QZ(0L2T7QlCQjP{g{I<9&NdNe)wn_1sZ2%CoqXXxC;zvsTodF_{QgDS$P>+PY zv+yXcUY(P@RTn}iBBJCzeY0m_1eAK=GzXI5b8=%RLz9Z7FJ@SBdr_ytqD`Q%GhtIM<-mp7eY91ArT&5D%f4H!pe(e za*c2l!z*blLLWG7DX*lhQew(=@TJ<%xWfTzWN`X+iw)?PWjhi?L-nuxLDtaA$4%1c zu91NAq2?Vm85#T{GQJGmq8&*{{&1>=MI6h74%3p;sVsSxLK%|-Jqp;5uBv1r=Tst1 zcmz6g4a z%?sxqUx*L0!5FrIk)Z1)w#QF&j|4M_dDi_Hlb=DTF+8n{qzh{{>;RouV~2pDKWGhu z@qEZ5>W7~r$uLnEjrkaO)qele4|pA!iEGRRS$X%Z!Z{SV*t2J!=MAPRj&29L$evHm z-;^dA_wi4fYPL)W^B-w``HyM-?`f+4Jf#1X>CO?{2>yR$x)7hmK1@a9Wq%8}P+kyv zg+8Vj1QP)$T#(csnLYvqdx1{QUd-{gZw!#8HzNkF2TUY{{qVy$hQ`ahaKw_i?N($y zkxneX<0sm!(th`F=bg=B$hR+1ot5f5fpcMn%?s^Ol}ERJl?KIv)DcR&u5UJvw&68t z7FL1f51MR}ca(l#46yqHv38CLv9JhV|NO7aTZk=WePnw7KW6*?zlHq&bd#x61GwU- zVfj><0E_`N+#eNamP}q#!-c4hrNM>4o+g8=5icYYb2Zn5Ci1t0D6=7p!P^>BCz4;7#c8Unad-@{*(wOL{Uy_#@_+Z7p(Se~=`FlYjjRo3c zo9#vPYK)EUw=(brUputqY;j7w{`m3kE^!MU`q=+v<-&ihox+TMWI0)|C6J!ljWV$E zAq=;ZD!4l6!ubcy2W7RTVk;e{lk|%;4yRhZVq4b+;cBXkxdtt3F}b1(nUPkju&Cpq z3ptaiVGvy`jSSG4Hre$?*Ds{hGRj1~K0tG%5zo)hIhKa^+`Oo;Jv4(iUIMPNjVGm9 zvC2RzaNY2D;B>7a)AhiLo7W;EKO$iMYxJ7?PmmuQBW6X;heKoEP1892mZl_rHzW?y!=!@1S2On>fSQAy3u_n4R!3O7LoCS*&_v z433GjWCj`l@!T>(E|SdAmQjR@h2xs86FH4{YQ66O&xt0d6Lq%AR*&~EP!M-p+8Q%& z>P}d;ymm9IL*;X2#SvN>KRleyR9BuN)&XJ=TC^&@y`i`mskl@#Rw*C5fGT1?|JV~-iJQez4Jr1tWohYmop z$f+hSmV8YM zQsX*DMFAa3UoqZ=l&9pEeBNV+aylwla`gQ1M?T@eO_&y`LJTc9`hFk4Qy5(%dj zY@XQS3FGZg`kY)RhDs8lBmv5l;P|vLvrHOT2t=ec*Bjc>Nx0(@H{4NdzRG3-$EAi; zFoMCNfVu=ebMc%zR*NA7EJCXG^JZ}Tb@j`nxlM)Gu3!}>qN+UDb*d(#;IMN;>F#@F zF9Lpf#vl}!s-b>Fa2H!5F_L_O+JJSmJ{X^h9db93ZWT2C{z>H*+@JDxGX3EvDwo&;%0HsmmA$YhOCIoSN;rVKFg9gwD7Lk@D#wVWqqJzS z6ea3?t1w9g5a%W812`bw=aondV!Sx1X{_lSOx`n689F$<+L66|N$WH&>ORA&sz^+9^@=db?KQ5y2#JP5b5%2)xZpg4da?CR0K=2lT5K}X*-mtPUopD zr|!z?vL^{Nu&AHb-z2rGDeJQCs~Q*Gt0yp7Bs&sb2^U&jqOIFJlY@+8MX{o;^wn;jY7G8p~i2Ve>2pd_#lEiw|&)gbBohMbSq^MPDn$XVTW?nLCx>vZN z$>@HFh{PjUE*lwV#_OcdKYm{foJ28^39$Lqq3)cE5c66PQK(PH|C=jKy3B0x_)B45 zbxHS0%@4ErjkxK$UiVqnx`US#-m-LN8n)Wom9cd%@Ex3D^pqcyl9h47_SSL|R=aZZ zMqB(K7Skj+kiJi8#^)EERsX`mQF@xyOqF{*C$dGdi^-Uu?bB|~Q&S`;u}^0U@}<$akB4+6#% z$#K#Y&6E;BrJi7T7n)Uky{aF7UL`qlv}jwtbLFo>5PWsv=iAlyuaYI-j~+x+8pQ zWHelQK;j-+4g- z70AZoZnW6zdS>|15ww%Y>$Jey2$+2)NQf7Md6|nKx8)BIVp-91EQ+hGp(h%i>@9vA%m}8K4TYk<@vdTh^_p{S=GJryh29ub4nC%mz4dZWSM7^V<*ulO7XV`EN73OlWWw z{rc(ZG`ED0hY^)CHN%Ak)p)=iqxiRk2#@l4zzyb=3~$cdyiHEu3Cn5t5#G5}m~z|7 zVclSU*Tc0w9~L+xC}xItq3~P+PZYRF+q+N&wOauQtCb`F^t7#D@rJ#1ataz*am3ZF zY=AgpzdY9zU@zQ7|JTw3dEZ@%9EZI}l~<|JhzDt0EWY{$E>B-nz=sZwJewgr8YD)| zXwA=>3Cyl=1l$UamM9#!%>H$Fq2-us5;dW78DE;0!0qMKODtWQGErb-{!d%rR=qp- zbIg?0$E^y#ak{85A4v=!&2e6!)#@qj_)1&J6=0BjR2U_HM_R`>B@up;)XoX&h{H_N zI^P4wc@O4(j{|eQPT60KnnmR5zXP{$_}8r}5?W@5NdqAl8NF%?drVXQ=i$4%KQ8Zg z8HR-?3>x1jP{lC>Jd;oJa8p^Jm?vatGBmYW`CpZdB~IEul&zBSQXh zonPj|EJ0`;s!T}ZeRr9f%6#~IaCJ3lHu+gPw>&>=k~L$25n5{S%Y=E#%q4h{^Paux zAZG?aD-+DEc}q@yNH};zPtsAGur)k0cBk=FTny_EJ9xhTeIZlB>X>d&dJRg>%uKHL`(FX4y^bIB{v1r8Qq0Boo@H}g9*X}bpEP3@>Bs7U=V{mrNuM5dV78M%b% z?Lv;G%@UNq!ii2i-vqzD;&a+<42yZiC(A>k8QpbRy`1y-3ZdO3iDS(AY!z;AQOAM- zYK|x0*GmkV0;yZ5_Ny4jUI;iK_%aNJ~ti|BoQ|ru+j`=pTN!9*4`=Zh(a5c zB83CI&Cb^Fh-0JX%a?zF8odu>r7^XOLtKFZD}W5)D%^ebbLqEOE?Q?dq0~> zdf{_v7OF>wx%thfRbuRdO*CXdckcQrT8@FrbK!c`P0q!7Nt5?|i7q04O4}By-F#_3%o@|B zu`yuhDv(Vfg#sJR2)3}8qS;5R^$L>8rBZ~J^%8Z!c4W=KgP!69Bc@m6sAkv(hrj@$ z*dEJ_F}%D50@Cql>Y47qK3kNh%h@Xc=gX1d_w)yRI=-)o@NHETyk6ok@<&FJDU?ou zQ#FEOm(V(%2mk_NS>k=EhXi@Qn_{~R`B>A`KC{3PmPN{puf|gmWU|O*GauG5fffbU zd97NyS1D@DmEms*?=^z#tugY77(_>NJaf+{&* zp=R^rt^3{By*Kmq z@4@8iPrz8UX+KyP2xaX)QZ(z26)`OA3xrBROw`w~h%lNeNhg`S6Br<>Ib6i7n!Y(k z6XPmNh6K=Vqe14L&(A4WeuRbrthmoIfKZps+GwDh7JGt6uOUPtA!wo!{4B+xQw(Cg zY+0WoF-U3JE%QW0=)?Ml>=dZFYvZh3u90T#hR|%)JCAKxTI5~@0L+# zR-^H1xyl$EViGYGg4?+75m=5~=1QeX+m9N`pL+L6!sQ-R(WKCslrT8Ux<%Qb%A{&; z+H1klUXw-V!LnnLMUAhj&quZ;STgryI^rq0RyLaD8MK+srfldbGvM|^i59NQ0AGGC zJ<52`q+sNYWsc+~-?S8NHL?6a5rMM@H&R&ZcSFq#5sU5R=-qvv2LNT4p~iPyMACJ% z*_@IIW0G9Ah6KO4y?vwhDK<;S^q38jesujNdnLBCPUJX4^NR5%caWGcfN)$_Lk+j? zRJE@su>!bQLVp0qaPRe&R4N-lMsw$cxpDxDnCF5xQgE6QvJetvOOY46TQI}C<^NWj zZn}B=jgm#RUQ54p=^4JSdHRlNUQi#lJ9F%F{IZ$iIbV($4q9U{2(CgV zEQ@ckGgcNTzn7&Y8@{;5!&QdMlw`lac~C^j1G_N&oi3;bVukS!?GORd`cQ}zvUwqt zV+vk=VkKLQ9>>u%uiqZy-bl9cm6S2ArvZYW2{OAi$|7QoHgyYUp`I;umM6{6?-u~_ zYMLCiSC?N4YizIAHpwJ#LlK*fuV{~1cYai#zeE24%9t%;#+83Gy0U+4bpMxW@{g$D z-+fL=M-D~d3vV;+x=ST^+4oJgz{V>DDg#A93bB`>+|nuRZt zY~2GBG)J~|gCVQ<5WA!sPLRdw3;nCcJ=d1en)1E$hNte_8`|}svuH(d?c~CS5ay$7 zo52tZsM{^qLX~UKrN|u;PqPs)utfX5$w?3rCwn??UkCx6%XMv4-}M5QuG>}+?hQw> z=CQ(_SM)+l7F5pM;eb5X>hT6QI%7hvy}zGE*71#*Q9a7U7RNv4t0;9xXY!(V^@TP3 z%|mch#<7c?8KyozVvnb!^{D*22^_liop~(N9MvwRF|3+K@1o^{(p$Cp$5i+6hZicW zP^;InA#*w>MC<4@!{+9@K$KUAd6f+5g4mbIJA~d8mFgxsh$*m$w;pUJWE~`i2(8HL zTF?xCJ{F9^a~K7ir0X40 zH|Kg&a@*f}7(!2srS|sYhJ473|9X#48Cn-D{}Ia=|5)-xJ}#C2&dd2j=|sf|VC6_6 zZvb%k>s`LEt+Sz($zLH{sATz<>#mjVNmFR;!hJs5FVpgMWqvYIL;tS@5&%m=0`ikM zt7Wkzu}i&Db4rQ_&=-ZBObIwmRP4H%vCLG@3Eq2#`@zZT&CjP>fX|%D%6pgc!qEeE+I)$U=G$IaVyo=B2H|Jo#gEQT&$4_f z@Ne(LOKNR+pGyKabr03;aU@+z-h2Qy%i^LC8K7m{3)pDux)sefWM_190y51_$YE=|ez zm@t`2U?t+gW2-v2^;|ee&|yPAI_aE6kG)+iH5qyU!ee*%BGt2i43Q^-n2}RdzZEGI z59b*BO}0N*!n|6xNMfC!!b1_th7DjT4lGd40DWNYB>X>!pgQ$js0#vq9bHtGiqP`i z4d1sRY(SWhO;RF+b5Z-7?L1Wn3RKoiBIw0^Gvdwq2|Y=n8v#8DH3@@wYncH`jttLs z2o>+(o#gX-66*tSKO~lS+Hc@Tw%}4Hhr$k)2v8vkd14yUugqY*B2|2(3`~IP2K~!xyh}?@QEDS~d7abo!0`R;`WoXqy5?w&of3WX zjYE3~h=pdmQjg9YEej0`Ee9M#^oQeu5rwpye7qzX9A_my6VI=p>8btfkFB?gAZjo- zY@Ja~6j8g%%?@{T$-8$r9f!k zZMYsKeJlW2SMuCxWk&YCrCFYf3);J;wG%aikHN6)vV-gI?tg!4` z7Dt_UxX{@T{JN+~+sjy3(>Hh%&*L#H=(woWt#+QP8ti~6d^+SbvZ`%X-qR@z)tpi- zU?}N2bB^Zx>ljHROFWwOEGHI+T(g?ECpf5k9FD9v#DUd#&0a+sGv{r9fXKHp5H9RF?2gJwUOII^l;h$`c~Bgjv$sDH)fNo>>FAG>bs z{}z}3)vcWQUzbf;lMk^dhrgdtj%#>&X{mX?!)xweAhi;W5WMe>zr^F2_ot)*-%Zmpl3%zTh9;zrOk$x>o7A{k}o{ZmAMaVB4nw znth!QXEv%3z@IQkfaNxUNI&s})N}Z1K8Ru5eGSohBqlIq@(|~TVSF&^!}LL4wl^DGKGYWM;_w01{fF@uJ*av_^8O_)Xmv={Po|5-yzSMV zi_A~h7x18)x4RY@@LQe_odo<{o0tz;{MeVSM2{-lPo7w>0lKvLzNiPjant-b54lSZ z^gb1RKf~U9QLcWD9`PIBWPi3oOQ*W@27M=`y77NUAAKL}ihgPN#=^ce2*Ct_%=8lK z_kL>x>tnIS3VH|!9#n=;9Unr9;yO?l>h$YC`YDPS#?*|;#DtC1sJC~aCO4rc&&HA@ zUe@_eqtwdK*FXNaJ6D}7NyZHI0MQbwy<&{PWNoH3)xVii*-Ek)SYNB`qDI4M=njQ5 zS2mCjvrkEDo5-tY0KGDt$|;aw_}TL7jPQ8w%gQ1B#9X2?;P9)u-XEDKlYMCUWVIqoiInv~Bk0 zo%c{$z+0Z^))-a!PC6+|jX$?Mm6gUifT&`=d&Dvh7igr2aO8;S(dBe_I*yWc326WJXY*hr(sNe%||pu?FBicGQ>+hNcF?4r8}2;s5J z8AK7weqiL9bV~)N+fD~xv0h!2T}XlT#`M$94J0O{Pmp(oVoaIdO>k<}nCEhla4X^F zD!-)>@v+kG40|WR)VhU)!Lz~r8LnxwBi5XGc>DS~*w)mqI??7mn+oc%t`<>Ky1!_b z4Qngu2%L{;a-B$#W-luOP>Yp1<-G&NFB~{iZo9vI2r03yF5QvS|OaE1>F+q z(XHZ`#l%Zc(Y=U=D7FYCmsWkF7>#`FQ=N?zHWT*fd)tV!aAP}r)9ofEG3bZMd`ofX6)YH2M|FbfLUY2G zx;GSI#VNnpJso1aN!k5aY7QzpF3PJZzjc(@jPiyo5jF@#*$j0Gm-!_PA8G7ar_Ed< z1<>$sJPBLW5H1X6wzBh?$Cez}8O!{IC20+zk;o71W0B+Gjm!Hye7&gK7LniGT3)F0 z{KCuf)yA2mV4F1)!YPP`%|4wPS2Yf+kK$_q0IK0RPk(y8)iPOup=HWVvx!Lf)ft&$IiS1~Iir7E}p!gc{14W}fB zF#>;w8cg&bMQtM~>6E^Z@d2Z$=MLeIW$zN?G$oUtcqllhUTRAfHT{8+(8DEU03_8 zEeKetQ?+i8&CX}e(4#RkMRdSKwh!<0FAw_V-=-m-ZOK++!C~+t-RcN(r@$ZWZ*xwL zkEABEKJv{hHWQ|L;SH}T$<$&|IUp7@Crqmkm7OO$u9>+G>y#<^rd6LTbkdE?Mq-X7^nYG>xJgCK5uG zJV$u{y21pzTuv1H6j%}zEep^CdS>^qlWy7#|N6r>0zX~D-&0edm!qly+>7!}TMQ&4sHyJ$^r=y|S%0uTFg!f;+X&X&!ME;gsvNwUGMGluiDu zRoYO!PQ#b;93kM*7r)9R$EFBZyN>Zk*{FmDKnBXEMFBvt>JomN1&9<{))?X5e0($@ zUfMG^e}s-Izn~+$WVuJUfBRCF6L| zZLJ0S53K|t)3_`9S83~y4yNgM$l3JF3Y|d=x&{{BIMxqQY}TwQtW(U2K5Jkup;6?F z&Aetd+-HY0h_c$jh`XN$?@gnwayGhzSSB_E!cpY#?SG@x?;Oqhb6jyyq51@0ER7Wd zAj;9&jJa{r_b4ueiQ$b}?sikyLlZr*Wew&zRI>qLa~>?to${8v2%JRntb0+Bnut=q zohwVF_rw-&jO9mi?zo*mk2GY1d98e&772Gpn_PHK3@1j`-IW76GV_cX9$~ez%5Vp^ z8ou+dh0M!zE%FP@rVK0-JkwaAN~>PN^+iz&R@!1HbuI_q zz)~Dxn6EA{X#ND&e7?v^|HM!zi~8wX7v=TcM&MQG+6G^# z3Xe^>{9wiq$8kc<*%8v#D$zB4wTs@fJ6tj-v5fBL7fE4tR9}73&6&7jZ z>kI*&X|tkd53R|WvpF)d>iD_V3BMV1Nr}goHV)wHirh7Vu+mV}i#2{?IUT-Ek0683 zLuRi;o0Ji-mwdKThIT3eJyL>Xtcc?%m}!xM-&Szu=KCNwOPVyk12HW}zs#N8*PLjU zN@b>ZjX9dH(?qlVR-pOXk^Sb&ZrLzJk|%fI&Kc!&ZJzaS%@Q#O!5M)X9;iB+t6yqZZ|tPwa)#q3p61eRPqSWQ zr{+O1zi!d&xEeUiABVz5C?mw;+}_$v94oK(VUPB3ul6V`r8_#ta<+fyBWXfq+nO%2 zcN&}6MdA4-t9Xi8rF_~sN7+CH{d2ZOMaD4O10u--9n>Q1BAT(8KRMt{^=g&9C~^$o zx2&&Kuh2|xBdOQR#`EoHkx4vj+BKyg4r;XXq$akZLv`FUYRv<6wIHGMc25pQYb7Az zz~Q?Oy3*4g9T$}XtVq1`=5$Qe0?6qB_Cd)&}9GXtAzi$ z2s8a(EW*wX|6v1~sIn@D`{7MBuB(m-0jqu#ITPMNGioALo(B$~TwM^6%w094tmJ|t zU~qPE;pSeQ@sRuI06VM$WsH}FWUQ3oNV91V2l-_4eQGG#FBo&1?A$cebVbI@hwT}T zKAVp|hZ(lMFDI+*pV}^gVVN8_-JEEjBNhdE>lHJS4F$tsk)+F7LZqn5E;H8L`TQ}I zquNlF6ftMqHDL%VO^G-v4AGN`Qk15_lvcEpeqpGnixf1#;G{y;QEBcyswp@0gmi^| zEzV&i#Z_t^!)dcLJyjrQ_SNxAYOvmh)AXPtH&@EOwi*bE&mV6!7W88($gyECI@Dfw z8FZ$m@A*NJAY{#sR&vl#qvJS$8s#rP@q_RvMp>Sh*opmId}v~O^ht#`%Tfo`|`6b2eB!bEBthM4w=csN>;u9+3mxf4B6B1&*h2Y;y_0a(=KNbu9L81 z$7R5JVy-a3CmRlGQL^1bsyP0q4>}y`wcG!=5afAxb!B> zOWes{O6acG!ORfHa}rdGZ>B?;%+Rx}8TO{T9;)mIV7(H>!}dIt?T*1a0BW1?ANg8M zcDuwGCRPKeDaKraqGY2#@Ism@7dvcJTZZeL!1Jx8tpnRB>20-{9UHZ?DM;y2t>c5) zkoe2F4ZE^r6U&LGhrzH~1gQGFR59tu-J{8Vd3m5&5$_G9NdPEkRlm0Tg*rIT${qu@ zRS51;;}Z{|yq|97OwOlN`Rh%|bk`(TmVcx>0OHRQp}bq*eeNV4`*B-Bi+=hpe~)&Ayn_&hD%(=hJKjOLJlsn--`$ZA(@iSY&`OHoVx@4!rX z4pjr{JAL}Y=Ld7h8iL5W1rFPU{ewsvoL}uc-Wisvh0VTGIF^sKEasP(X10V8Uk0<5 zh!U2NK~Px3q3FIUvmp+;(Bx1pxVwHvvQd+BLKlc^`@T}$A%tISB@%cA)!imPNvvg; zu#LdbWi*GF7rc@QHIjb;mX+YknbGL37F&;iTjYY_F?|?p%G~g2u!__ir55DZ18>8S zSnDf7@2;AF_h)$RpjMdY^3}o+?2hnAhBO6H_5l<{UDRPF1uym!3S@U7{na z<=;=4a)8KFUy=EyTz_wLs0(0i4qI))mZsiLN7C#+eBJ9IYnIc22t(eJ=fn? zfX}}3{h2SG*OCG2bd#<)+eqp8?kwu}`lf#R;C}kI{n4NAP?cX)Ph+#imnKP0`O050 z;%=#75BLzDDurjzT_%|e9GsgoZjOIlhQMC1M=1HkcyFX(s0)tv5jAaUIS+4+TKsGa z)EM8(DB|lvjd&Cn(@37lcZaS-se4nSGC|^2P2SEn*<(!};@%xb#osPbT$Bu7m;Z~p zQX6?&k^2E2DgL9N)4#va|F;0rf3VUD6Qpcs1wPof=^XZ!xY$8gK4?&L?o%>bU4$wM ziQknI&gtn_Z%IBQ2J^NY z$^ETUnaWr(Q7X^=Yz(y~tsp5%C$(v?#Fv3v5%Z2!qZ+`zv@q&+M>59JD7^V81FBQ9 z0XO@|_bi4A&t8;E*$ep+Mqgg8Sf82aS;HN=b4Vl7xVgQZ-#^g{Q6ui_6GDZ>(p#Hb zMR1(&oUtFTO!N`j9M0MeKos|X$orJ+3Pie^Fij8AC2hA{Ow~*~*+bLfSOX6^*$u_Z z6YkeoMdsU6xPkLONuzzVA37s;KiHfGn0wVf2ez7z4m*^tAV3{^aNY;Sf;Cr*WVP}( z=;P#f04{zkvc#-}lH-&51QL{8g|5q(8n9?H>&%ea!tg~plpWXo)kjYZ9L>&Qg6Vsx z{fMw|S&R!4F9&e>Is=IjCp%PtpkHkE)#I&`L#q#JX_dA$DrsiOpzsX|bz3u`UKxp!K8}r*1Plc%&SwoDl1BG_>^3Tdf8?kbIsFg(a$xx+HHPea zldc1IeLedm4>x=L^Y!9A!6z8?#n}D~2qiJNNmf)R5{Bws>@W+r+%bAqnj`V;M4$*B z;KxEuL2lnC;21EWNzKKr9>9(jH!29@n@DK0cZZ2=;<{1i~wyMXe7yf(L!v!S+TN)$m1CR z0&^BJ*`&6gbna2yCkV5tpvXy1CyHuhWoM(mXkN2 zz3mn9J%`9LQ49LjdL5WL!;h6`w2nNRdH~*(`>Kt}BOK%WHxKgKdgyi6Z_NQ8Fg>m{DC#zE8 zMX3Jo)2T@jlF{DPKLVuGwNGr~^>+-lLPVZ+spHgY`j9OO{)iN&UF{KI^91f;HB{@w^nY;x zvEK(OcpzEaUw+jl=;Z)hGK}?7jG;f0iAR+&%!>JqXE$`}knrDK2X z*$8Qhu_0DTAD%_Ov8l;)OqflGA0$-ARzlim$r4T|EhJh}A*%2{u`aNzPgs>^{}t?r z>Wn!QRKj(YQh1A*1>EHC{W5GYGqe5lRRnt9_K$ZgJBW0@MnAI02I_yE-B&H`#XrXN z|NQWLeETQt-^j|@(aGcw={O z`7*(cr*emyl_SawY$p`k3yoZb=cHeU6K@iF_AO^Y|_$>;EC`9iuFZnk~^v z+qP}nw(UG=+o($0W~EhW+jeH9ZQFkNp>N;5V|2gU?~SwfkNxwE5wX^c84+`iVrHph zQ}HLmgI%_yAJ-0$4veC+7-{REwY=lyy>>#EuYRk@^k&hs7`d45frz&m5QHf)chg`k z0=yp@s1BQI#;{q#8(L}7W7toq_;@W?gA;E&nBy%Y&K3=wRd^RsV@z36;@MGVi(_nk zFKjn1xPHakDb-jIpVzA5zxHAo+nrq5uSgr(AI;Xp*U8$c%m`l<4@Rb8$tVOx7sGqk z%+Ii_G|UonD($s~2Sl@g5KSxfpQ0j_-Y>C$FJxUd^b10PHjueVg!ShH!0>TWt^X3S0JOzLO^l5moQ~qiH)io`2CuMGoQC4F>=K?m2DKmExNsE-SbBhS+pKv zBo1;;4-a!xReC>gN{4|VAd3WK_&j$@?KuIG7%ZdtJapsWlg4!&)#bLz`ChulKM!&x zpF-6$Y-?!j3JYlGT|X_Iw5DW^tBpCLzgv1JqNNS^GId1XytpQc4lNiRiVi24C(LRD zn}T$3fCDvyvd(K@Z@OY<oKOHqgFp!1GT0KenNDGODf!pp^3**bMl(RoL>2gN^Yf?>A>9t+F z04sif3QD1!bmm2UKlXb6ujk=DvKZW z7THAIjdo$*Y~AEBr}0DNic7`LP%AGdj(0g0?kmwBhxZK+j|A(DABNsbIbEMq`e0pU zpLOSG{K3+h3DX*25@v4qQv>fYP)JE7xfEHlnr-PL*9y(K{?EUlCorN@3tsY{ZZCjj z@SpC+xu?Ll#nHCvL0rd&exDNv4MKj$g>twVf2S_Qc`xnxpjXUgURFgd5DpL*@^J(% z)Vs9Ju4X+MPEGn1#B)Xd02v#E?WDcZ;ch$Eb_KSO+Q#|3Ig>eT)rafSHvTU!=X5>; zH#mGIgui-1u7)dU9x#WMzj?SQh!LZ2?L=!)16@8DC%J{im@M4{xmV89HohO5OgeG8 z{mDqM>K660hV2do7Q+{AU|w0J9LMtYr#Vkl&wKidEc*KJgYsW&&I zbrg5Vr4ZY73C;sd)zQhD5bIK`z@d?;Rj!Z~pXn1j%t2kSUTT8{%0ns-I1po2gB_}R z!ei|V=ji+<;O?Jq?-v4KK2;$|w6JZymrAtCgcIH%G(!#;d6)3z(LlMU&M)h56%yMx zgS*h@Jh5B@EkR@jn%bi$7c9|N-0)!O7(GzPUI~W+k=ncpfd+)N{rkIQK@QMw*Ua!c zXm!ujAr9CIyRbP!T2jIc8{9!)E{)mrA(&b4E(yi1$GvX6qTl`a0eC+oB7w`GcTWBo zg*f796E{Z*FgEiVlnuA3OG0gU_te0(z3t1CRv;^i~vSIBSx!^FZVH;AdPXm1lMP zmggbnU8D^k@!UTHOJLLnxu+j^#EQA3ZyM}8Au)SKe?}8WorUdz*R_mNZuGHqL}d-U zMV(BWHYne_B8=Y}F<%~B^7}+E-69sCKwLwXgQ3Vrg_x?MaUs|Ki6cSUlIB82`jbF{ z#DPIKzB|wSIvzhHgkDDt@ch}rRmm5#xKW22k_`zzE_vj7;pXzd+2)0(_Yp%MkJMU< zzZ;t>*`E0kX}#eSdaitCM@wJZxF_?c_lP@`EWe>@w;wz8GKYBfEL zApu_mtf+5a<{|eCrTqqF2lo5hSNCrOF<-8<-KF>b_-|gDU+TkO>N!x^bCK%o5K8Y0 z_iu~}VF6!UQCVM=F<-{!vGw)CD_G9&u{;H!3Afq8fxO&kp0E(w7+?Q%M`M2^jJf*; zR!JED8CL2fafGkomTL%}7#N$Ij6UAve(574k8r(<(7UGZi@*TARr?_Dww@q zAu#1_Rs}}-FkUP^+Fy6h@y>C!oBp`D8+ZQ!%#6EH5bCwL{5; zp*5h4300ihFUj1AJcKzP3&y*HNONS(5b5OG9$%e&n=BkJ(qVDg9tu`4@5UzKhBvsN z9f~`UU}`DftGH@gIcZd3!$T*vqVZQxPT6+8p|Z(@`tma01UtbiWU(^k-b+N~&m%cq z&GeSKb8*#J!a>}#oJGBM`QL+!vBjY~v`77`S15;aJz!{Y~gdq3MSz+~XT1<5Pp)zSK`@K1+LNANp7FiEn!mbvkoeK0}iF{(#_2vAJ&Yz5Y zERF#)vjW?|mrR!}SA)EQn3f6Vviyo<=Vkt2TewKT6p#cYyI4w_EU$bbuwFwy&A$h- z0g}(+>c3@3=JwlqR9*}Z99({uFkVy zn(C3FB0!Oxl^Oh_CRsK^TB!N1N%+1MSpTOI%70B8_Wyp`{70hvD<`u5J>Pj&=$II? z`O_gZr6N12O^$?KPF0nRkVsk3N|orr@{GPJk|7?Tajo_fRQTW*!gc{-eG^V25H+&a z?ZnhM7t0yfS#EdN*N>VgZ6L1oF#v2cg#&~;g#$tcw4PYHkSo}g*e^qmnMaWEZ9Th7 zsQ!Dsr6;eD@%~P9$kRPpJ?$sdnS|2PkJ_{g(kim zW+!*inH?T@F|)O<(QG>WWv6WL`kkB&KxvNlv`fA|CGc8(l-X{?&sDl?()SrYVqZ>H zor3wYYNVnJaxB)$&S``eq~In1tM4$9nZ=vFo&dVt{0)?<$Ll7lUiw8@X{n~+i2Z8H zaK8uc?vBuGu_R8BIvc6xx7>Q|F6tT*z13v%4xEDq7w7Z8_dPg1C>aM?bfm587}CXB8^d@nG4hOc2aS=y zQ&ed&lm?;u=W2*e((q}gulI9lcO_kiz$Lf~Neo zBoHxU^~|g2_m@OQ2)}8x_jU>RQ*1x4YF#j*xGA}HA)a^NaIxqnV{dwN0+CigKrE-@ z=XqOqzpwOr1hjHfQI|-E(jSCIqf7WjwgNWdK8F-0$;D+(;{W|f|KD8@|DJ4a{CDJMW+oc0A}VL35JR(( z0tKld?gFW@iNcFc7DdcMmLV@JYLQj>gxi#q8Vs-y5(Oy={LI}}K&-bUWVldK8?EOt zUt}@&bzAKIeCGtK38&Da-BAa(q%|L*k#5O1R0~*h(o}Jf=;iK*n0&X8SS%eJ&LDtg z<3C)Kv`D#X>%y?2j}@P0TbiXcM;0fp>C9`IM_z|T8|W8R*xzR@!6@ z-oJ^aMCHd=!*?mmlceo-LhxW$GJBa0anZSmQ!rkmSncM0^~tcmc#>dxJXfo$)RcNp znZL_D2@~WqFbbmY2f_1^{t>Z^@iNd&6o2d^Y-|p#0-EStiYP0$V=g`Y`==?X(f~M{ zJu(?@KTHNdv#_ts@?~pe7Lz1$Z|Lv%9{D8H7}#aP0aZ#0Woj{jAP~+P&A((2u@|7E zF}_2Q@qd|S{;x#PKUksvZ$uEOqP?Y^i;9bpi>vd$nbiNG61(wja0+dU1auRiZY!jP zdQ$`klp-vdky29>|122d8cgQRv_{u0L--G5a{jF=x58emwj1ce&P8E9b?`Qop8hXj z!cdbH6huMAE2bo_Kcou{eHiSK(jys>H7zzE46K!>h7}20>jluMW-fH+9f!OB36aen zSa;D@T)oniHQzCg8BQtO_^n$lF}W&C98;jHknPF3-d0JI<%fvFK`BS>?(h z+dZSvFu~YX-?YYSVS{hc$k(a0VHyWh*|@5&W?tHb2QU7fw1(H~S)qxoEG2cfnLf~E z)@s(dhnwM-NU+*K5~>;f1ZyABh~hV+x(*XC0_!Gi-&ez@ zQA3mRT0Fza%M|^S+vCIE1~cUifz(I$;H+wrF#GnDm`^=e-^0aKx&~a*JQzO{J&`yz zh;+yi#^un2kCaaR6!#p3SR>4jG;)W1)Z=)b(hpgs^Vw9iZ^H$DZryyKiZDEAM6i!l zst6~9Ck^U@RU!dpXPQEqfN*+pT9?@GG1dj^3Cx`r5?~fj*j3L*?s_WvC%8K9(b?%9 zIUI&mgoG?uocl5Q&oP(Yrtb-^`!gIE~0mR^zsWzZ{=_@FMOwlGxs z!pT2D#62-5wf1*B^Zp;(0{?Hu-hlr}Y?`_m*|`4G(VIcV)mFjm-=IR>$jQ>k4q*B} zf?8e2d0rg#bFr4rKvYshn#o;zbydEWQmSQSC`p$IlZVU>I-CDDWu{3W8J5&k4`atY z#eL-m2rqL-kQC4SiSrkTf6@IPQu7Q}Q!9*VkEg5+zOB}CF7t=s-0pYqZ5iGXLr@eg zS!3$R@fPCH3g{}+xS#Z?<5;-jV!aQrbEVWRL@(8(&MNTp&}OI;%%n7Z=zhsN+Fh3| zXBo3h6L3}OF{WHiC0ZffOnF+iwrU<-Mwz;q(P8cD*KPC+7%5o0EK}6xoVpn7_AZrZ zmrYU0?3GcAc=HwvI8|{z4VX_HLBopPCH(ap4?dUB-gF;)jquWV6gM-*6n{E?;6~yrmM?24>;n?h5nYuc-HdY?HlkQjkEy-u* zM~n-SW(ap(yAITCum1vu7)r+Y5-BP=3)J;;{RtYqf7FL&&Y_%6R&ti%qdzhs;Ae=P zS~yM3-%}dEg?6W@=pZ8o*Q~ZKl%4lC7lHaRKQEu^0ON+uHUC$=vbJmNj`Ej~YHd(T zgniAQU7c^X&qG0Mn(^byKGev=K3@qaytJy!`2YrD>FroRqs)c_wz@YLaX_)_8t(y^ z$8gAt&^FMa|ufR!S0uew(si7ki;o2B;@%xhHUIj*!|hblt=S}}n$1lI_cLc54-okxhJ zUn(nqK4>Z<3edeEJ5;2MRU49)x*4~j2d#)hO7BzVW1H6lUgWYi$u z?;0CRFWjxjhdMQ4e_E0{Zu;~jOL?NmdDOOajq`r@BGX5HWvE8W`{r@@eO#|ZdSs4M zXh?3Cws@qIhV`^GKPt4er_a?T%sU{{Bjlv#=ITV`fCzqvbqdiHCpUhdt5DJooM2u% zVe0G|^eAs;%GXDl0(t*_Z(CQFyBnwB=o!}&S}|${hH{R!U!zbZFT`;U(bz`_GjBg! zZxn`93z}ZBz+Y0YaGH_J;Psy>>FgVGvnXKh1kDN5&M5P zMk>|yz8%dm{p9OTiZc%?;v`jTD5d8NMP5o1QX=948h1pr$0aISzKOVC6An@wRI{v` z0IUy)u~Lrp`ynhx@e@^C@L?YRu)S);-1_!tTcbE}2Cpga&91Avj-wCGm94MW7oeX& zx*Cqcfjv@iYu7O$r1EYm*fNG7n{tM@WN;-8+`m{jD|Y$du%|}*gCe9_yK{R`r^XKg zc=c5sr9=>l)h0@x1qCa$#OoJoK*43~0Q~lU;p&YKu!EVh)9=$@%#z(fqTCO7ApK_#F z=7H8urRYQ5s%6W@S7F3+=XutqWQ&z^!TqxL%Z+uW1ui5(Th6hdOP1wPU>iX}9zHs5 z-=Vl(c65IrqnIYKlTD?~SeN6LZo2AFh81@V9juMw+;jN)-6^WN5p#;~46m;z&_lv! zAI|MA?LdhO>3W!X(D)JA`e>MikT7CA^aJ?jfCp07_tliZJoyFxbU-2mtBfTnFxx}M zK)fnFWsgm_-N#Jc(5|x*>pDoXt5kd+^jynD2_3TqdYzDZ-h1vQ61r49 zZepyCitvW@>5NV>PN1CutG~29oOfRDaAcE8uZ7Ty(|M48LCM^9#Twf-4GQ zB4Vrw4N*4h0cacOMpI+zNgB3LxNld}wBBB}mCM6-Deml;^kj+2d#*K!9GddkIu*^l zRHns|^I|Wj_tgxpSv3b1oIm-}&-X}L92-MS+?*TKpX{Cm5>kOdwPeHD(@q?)^FfXF z%!cX|PA^;Vy4c>ebkX)AI7*Kk=>V0OlkZTA`$oU>kx?jP|>wb{E>SZ>M4`V&Oczs~rv**UZ*6rB7Qi|m| z2!L^&!=)cu5Fsi13J|C02&eYw`|AZ@4?bCQPFHWsHgc&<*mi$?q24AD({QTTPWir{ zM@h=xu+6rW>5OcMyrZ79f!UFeUmp4eyWxbdi xwX}1zf${}}E^kZR8=4F=SPA8Q zi2o9%#nb5{Kk?9%&J1p#aVcu|Sqs3%i=x=GJm|$MoReneXNgl!yaBpfuWZruxIgME z*vb#AHJRX8mJeK>`0=Y5(&sX#9j#!L;Az&GsglC zO-;Xgh~0q^DD|M?4yX$}_D!zKH&^);n9gVPL&xWw!Z9Y=A-(j?@rR?=xd{ngfb|D(eW=l?~y@y`wOe-;`4 zDld`~#_i?>QA55Q>E#30iZz6xQd7{KsMtD5ppz9vl$3r(B+;%euxds}0x*Wbd$Gge z6nda*g@pBff&vq%{#w4F=ly}RJ+T}_c>#=`Gk(MM^);FP@_4t0|5Iv$B9D0O7o-#Q ztrRLFeMr4=nqpoBXNhqF(E_7xq7GWWZCZ@4chN{s6_X1+ms|f{lg3Vp{lH;YaqgDy z>nVhY%`lT~tkBBuiD$8S_D-<~GmeN>Xc3puRsf?*s_a_J&JqWld$hea>Iof}n$ym{ z*c&6}gOypJQSp9@4)@m1LPnlOwpaF_2ks}Ud9RJRij=MEu-VPI$QT9J3SdJauPR6d zv$|ki^c7eWnYDNRB|3R!4vyyN^5!@l3cTS8tSZ6vr_6h+ z4kZ|Pw9&($Uq?xNLj5zjlZ{EBO4L#*cw3d&(s?; zxWiE)NE23=gSegz&R^}f$~CZ61qP>SG5RSAeLko`C+o=qFHwBr!R7@2vH(5r*>q%gV&Z((aksuZbw#Dj_v!Y-R0 zN+o@}h56c6=L%d<803!ok6+AkqImN-x%b(Q0e|(3h)2wH!Jkt&jfK-FE7u35kdcj_^i}~@zGiE{POqG(`ie= z9d;^Q4k3jTy#Yyt0AC~8UanO#<{^itBKk!*9#N^8qALaO86~kO2y5$>qOC3^-gm2217S_tLHOhCWZilCW6Hg2_{$sD z|7^qD;F~3#n!Qd#3F>yr$BX5mKe@Q_JE$DqoV^Z0fd@QPXKO|>Sb5Bamt2!kWIa1E zG5Cvxl$c_s?qFe&v+B}MOJTu}U;haqkynK*IlAtEVb~VKh}o@Revc06UbtqXDE}7C zyLYAN`qk~coB5mq;~$%v{mlL;)bF098Fj^d!`DH~LN@;tJddDT+E;BK&}YrJuNyYw~Qq@~J|hKRg|DX<*{90<;&qf1S%?=QHo&s%upRvu4oZ z0Nb4u{Y9<%bvS_Y><;&px1#~7@U|MWNYln{Yp}M4alSeu^4m>VN{2W{I&}ABGH+Qk zXes0cWB(z3=F*Tm0k)_>R*-U&sma}*6<_K`H!`X?zg9GBTQX!9Bpj))u1eIYhKLm# z8bJ)ZFFYP;^DiT^G(x2Xqa-$axr8|>Juk{Ay6}mlNufZ3ES#7`yU2-&3rBC8E6w;m zrkv=WC4XsywYh~xsSzz+G@FZ*X%oo>W};)B zCA(+(u3lq}pj*NiOeUX-9*w{U1+S$RNTizQu3TmBs`55bDUq~8r-yo*s zXB2cLcJ+LJbMe6Wu!n$Rqk)@5M9BT{^^~wd;s{?EAO>!T+jm_h51chtw2kp%I{5)` z=HE^<3u^@=@gCCQ`nZ!nvIe&!2s;XR+#IU5F-cU>_iaZicLbnn`-E{&{kX(;)!RCOO}@`qq0U`?`^?8M7!b4Pd1dWBPpSJn%J$l!KLuC2h8|e zrshJE6CH2+BVD(8PufR0#INu6X{`EebxA>{woc`SbE@&OaE&BAV%hNTv!Rs=@hk^& z#9&>ca(}h!JH{rezWoWLadr&7%c&+qywL!a^8^zoQ>KTM2TssL3iI7Gvrb7xqfA&EMDell8pP(JU1bempgebYsGpl z2NOW1dW#Zb$~>`9mes+H-`CI0Po&wZ6EeLA^rD?N%bV@9zhv2!r6r}ttv0V4JvDb? zBkHOx2;;g={YpD`0y1z=aNx_T6?CV-kpP*Rg)ga{7zoH3nAgfe%m6mu>`$h49~9Pl ztBZA)GTp2RY`+$4PanO5yoFBDW(z1bJseZ(>wfIy#v+N<>-C7&5#q$!!5ner@cB?Y zxwywBe)@abZ%ULgeO8r1cahC z*D#69D8I-1O^nRKQ8wZ&UXpPW2PRnUZPrfG0%4f5X}{w$>00fRez#vP7+d~stU$YP z<3u*!aTsM3X@Q7Jh;wzB`C?4m)3VGS;cQAz$5Aq@FI7Y z!VS@Fj#}-ibfc|buy%8!HL^~R{qBy>h`zW$I(!1Z949LC9FxYkCr|3KOn>l? zTKPwq=Zdp^B1bwByZNGPSpE{XB!D=9E0_q^wT7K7eW;db+iM|`oggL>(?SX<=;aWHQ53^mE# zeZhE$aw#NgmK;=2YSpBJgI72Cd-gp;YMz)yOl3oNAiT%m9(KwL+?)dq!e_8+*QnO# zz^NLL{@W87CZxX?1fJVvw*n$;IPe#4P{s;Xj}GrAINCFwkB>w~>{bDoJ%DX1v1tzh zHcR04U?0yX>58FwPp^wGtEWWMn`wewUYtqQ2qV;yNrhq1b$K!Zq88k{CRML9WB!vL z-Us6Dd=J%=59b1Rlf-}wYuyNYVOW);w2&#cdn0Y~Z^ATO7YCC;;ILmZ@8yW_KKDD9 zO8Bh7kuxbDes%Uh-)g_6XiJN<@<3o3g;t#vGC`b%A7=P1B)WZBb`Mt~r^Z}fhrA&a z#UOU$1zD07r-s=PpW0Kt*%C+XD(`?zHAm_rYylzSQ05 z(Oh7z2-MZXYG(|Ddepq9J(CpAB9ke7su9BnJ;f@C}sus^xYA+F-TcRceVH*NjSM zN1}B$lFEJI%w=Y*G>?&6PL%&D(WuX07u)n>?{-Bm8bi1ma=01`=!L{8AwJ#Q32Da; zm%=D0a^w`^%g%xOgnHdT>&0kTlK4scK7-jR<9~scgn@9v`1f|*I)qj4!{;T|Z~KY& zmT;kN=w|Y$dbD$HH&4n%TRLC_ zc;~NvlrG{l%OC60TrE)!#1Yu1FPxTzW0SSdYRgq%^H?uT7-K@=0RMnU-z5H;V^pdO zCcCQ{q^_)>h9fYLw1I7&pkdir*Ncf<)WQZs*Jpu(LF=OF)uMpW50%ofHQAD4<#2p- zCFp=ybJAKPi&LCANlJ&}?kt|FK59ySmR^Ur3a-GVlUpTHePf;4BMW!Zr5(A2CCAh? z`gAg0FM%?uEg5x%mX0v2Zd?=$>w5(t${EnoCRc)j4uyT}8VFmPYUv zk8Lw|2p7EAFgWN*-am(5g+{OyVbhBac7a2mchePI+9ih0i|uQP0I!K9Zi#ktFvT3u zV-51QpvcKL@(D)vND=4C_6bvwN&reRbGYc6w&3uS^S)-k802Zlrgh;$LM;4lMn z$C*NF&kNe{2Wrl4$8tcjLj@zG2aiZzn~~4y%*xgq_!!rt4!_@F3dvF}(rEQ%>!Rtm9jIIg2jI$Q=%%jMpM0- z?txWcrugM}gqoJOl2Imk2NyfCmet>qRCDt)INM2<4ri;S!2UvI_RDyR%v`Ejj-y`2 z&M3?`2xW?nGuO@(o}(bpZdyO^aNDM+>UTF^0b&JrXXMEQ^p_{EA@mnYOu=`jt}Sp; zJaZ|fq~}yNcsytTIT^xsyz|ktaR{I&cyZ13tXxN43cc|JzwF_|Uj3j+`hFtM{-~#0 z0?%A}DGsyIk99^!zt@Q0reIm8-3X7JOTrNh-Boa|B46j6=osi(a6Gw~tMBv68m^X} zZ>;iVsdMvB4#JL+%CwFg#R880=y8jnYPq&u<$;0vyi@}f#0Te51T$9-zL^GZfb)x% zM6B7Q{SK&WAhSUIG_>aT3^YmwKTV3#9DXm+gU|iHcGYlH<{*9`{P?j>^q)EY|2kYG z`rj|N|2HES|01C}wP1Wy7t+7{@7h=rM-yR9NS}L3Js}VwQ1Fq7YJiZL!doy=Lr3Fa zNm&@ve?PBNTdi2R>un^9iHSAWu4i=7zG@pZTAeLgElCjYpEj+0aXn4R zK|%>Xx9)R1<#XSNL`uzuK|$WPm= zVs+m@5P2OHTaa5ZUVnO<)%IROFufN{+Yy!u+i^bZzk?=lds9yAC8wwFuFuQKX|W9_ zK)!QB`wnbxwv*~1qqoU^9YZkqoSgC5h!A;Gm5cnPGy5T~x2cl4h3&Bwig3*X^0g-c z#ji?AV48V#v- zN62CZnPP5hVjSYxDor`omHGaIZwt(}vuEtP~;o#R}2ekpaes-qTdDlz8ryhsYuC@s=BfC_x&sUOCulV^D)O|$(M(iC(!H6^;>l01Il*wpX!^BGSW4jaAfcZ17H+eopb zoB{WyUOnN;23{mJig_wrrv4CP{77n8c0FOrj0p>ZDw9l8Ic**1&CgLvisUGF&3#hW z0hzGS{s!j$JUz@XIF`g2j}Sr`Dr+p$eT0Y1^iBm}oDA4M*ge#yu}20pkt-^JuzJXX=WfO_dCSq0N95Yq6HG%Z(0(B>vLO_r%_Jp9-ttu-W6a?(ClH9e?)40RGf;yk*`7b(x4~pt=8bnH(uG{Rzh+H zfJ&~UMKqvZTwBVvi@qsZZ@f{x(vNxs@J3vw8EPyz89>5kO7>TEH=SHJ zN&1mCvQQIX**T7Ue1WXTPJSK*qp^-7E61kONY|SGDP_% zqFO4eu^eAe7`pPfGP)ymY<@`DxoH!fDX~;$tjkVK^N%^`4qUlA)#@6`1Znrd^V=J< zS3H(z^i_q{bkQ2R=}j6o(3ky1T)^zZx3^-(5M}m_Y78)8ICbX)G{?j3-6;Cf=L0E- zy>yF!6e2sQGwjhoA%@0RGIZqLT2A)kJv-BXsMiVM@b7(UkHUD;#ojD}Bs(fA^ zLZF7y_&KpU5Y3R{9~lb=sI&;%stuS4C~>-@ETjU2V20{bSSp&d^Ywqzu4hKvh*nln zzJ;*bu|&v03l#&THwS)n1-k<2M$nyug#;MnN{g{qbdJYK0Z}Ey5ru-8)S*I{MBsj+ z!Q=1@gE$4@V#O7p=9Y0X5K53>_sF$y{k*Ce=WEeoJo^!)6DMmEfkcEAWaO3%x{t|~ zqF4ZTVuqpPJeJ`qYixSz2t<`!_cKXG?8o2RwP8_$9{9=rEH{1wrI!>G?GY=ufD67yzuci0)A)V~w zEOT_tSk6m;XQh~xx0KL;`=56Q+u*%UvTB#+QT znP)J!^FlMNorSGVXMR^vZI`DINPU6J`<74)PNH&Z-P|!NyqDV77FuMLy?kBe@ugX= zRqscQ@GLBh#2TpT5vD+_M}~mt{76cjO7O%o>d9qfS+oPBcB z{ScN+!2IelT}PES`z3*~w!!8;(XO|v{%-}%+}cFq&qrPzZw+Aq)RdG9YcBUeS&(9W zKvK-N7wB#$Hw&nFazhS^f<$`;F^=@{C-VFUS<0JC!<&p(n@osP<^HzQq+~JoZa8Ft z%Px>fc3I)8)i9zft#t7-a5SZrh4yBX(?fu1Nn;aR!yh{v{Z1EG6%k+O3PS;&TaB6` zf|N@N9f^`f9Iv^S?{;%&yRxjb91a6;}nqQ<4(HmF+8}T)VLe>1+@$uF+7% z(s{G@sr+`;1gYIa2LSQm>VeF+XnJ}1m)&p+>S9EdlLp2_Y`Rz0D*l~euY^qF(=$gN z3`bP#8pxk8VCCk!rGkxeuTxV}TPwUbIS7}K7JCn@{MpbHxTpT4V-!5#gaZ3B;bj}_ z*+5UThM8ytEuYoWlzSzbZS5D$wGF>4u;92_k#-qzMd$#zjz)clV{Q?J$+7IRfthLo zGhYj+r|Y#U3^>Lv7Jg(zBTj+lkv!PxZ0WH2@p(J?L{ic5><2m~QuS7*G2$!W6vE0a z+x_+p3$U%+>7rlFL2nq+qRtvZ?qv0wLI(fiNeQtkM4sf6T{6~LVvDLTv*x?9n$+_n zsOvJPIhal4X#gg#T~pqU>NJye!z-wRi86W01~I|tUsYN*-Qo+_(1RGMLeVRz8OIv6 zTLP+!1mK;FOgZA1*K?v(dHiTaYmcW;)L(~M)cllo-UUJ}<=WJAM8T)3#uPM4Y`y>8 z-P%zXK!wb!=XnP10Ymla5o@L}dgXeNFU_Di1jzC@;5OEqcwgKswc^}fz?wGc1 z;8=hyhyMP(8`l+Qk5PO+v}3gsgna4 z$LA-4*fo1pYODqO=eFf`^*ft_lt%iZ4ALWh~lZbO#N-NJ+JzL!EqBnhKrss~_cHZonw4vyBwwRQTsRy|2Oj5ApG z?JGs$b-*g}3+}1SBu%}hd@-)Tkp`FRBGX`bnsH9tuyk#(RiVnCwkgVLNGy<2DDS|{ z^55;R#!mFn#R=WpUsF7&+i*m6QCAb4rd*s%Q`p zi%p8f^D^;T9Cfdn$$3z$wm&U3@v)I^=}D=z zr#K34cwkrSqZQF+lkL(PwwG{=k7d=GFKFzd(<=1Pux!Hl7O8q$Tr%V8BOP-LxeM?l z-L*rXAW?Euf)BryOj7y&xo$kr-gh{-3Ha#Tj_e&6Htm_oX78RVx-1op5aW1R*7#pH z_nx0Q`k6AWHStZ?@!7XrtW-7aup55s!V*lB&^x!LDHO9ElOH{IFX*pb92VFgq z?jbYP_g0rt>cY;S4B55){(E4M?u=Apas1nLZFG(#^sZIZt4Q{hl=f)Em`fpJAJ{TA zvPh(>x0!zDSh-cVX=K4E-DYndKE^KI+U25S6nA~%wG~<8rY)i6)%LIrfdkojff8oA zzUePzEShH;TU(lUP(Eec_)5(uh(z#TcmB`#ikE>jdOdf~hQGlTt*0bbT?6=s)VJOl zxYaw}D;_ESOHT9>YQLi0o3%VJ;%v`dP&eh`DpsyonSjNd$l7yk|BMyvD;p~?RMbjO z^}1Dg9e=sD=r6rNdp&}$ZZEKn!;j8c(zr64Hm=pt*O``eP3(IUy=1Jb+9Krb%C)Sl zuN~l>3KsSi1asCZo$8{I)3&L7T57HriZ4#d)J&XrtT~2wQC9B7Xb#`zOir%qs^W0W z&Jqgpjxr$TZ7-`qE8$e2HS>&2?mL!D0w6p~vu6hzC%T^bKD+GAdyK27*0+wc zXeQO4^@vi@x}DhOZZfO0rZFw1L-~XhZfprjr{P*N-ym|US2>K;s15fEK@L|9ddy~e z<4U&UO0XKt8P#$`8ao6dFrda5n1T&@bv^MOZoyN=b!a1-T@AI5udU`bi^k2UBaYM7 zEFFH#H})^w7#3VyN2m1T>Aw8pS8Tz=KX51tKDo{VAJ}&*fnOD0n~WIV;I`mfox~c$ z%fdQ2B)D~ty)Y{#5rMR+hn_@o(}=PWTD?FoOv}vA8yl~%Q#ox3ehKtbleyoO5B}=< zEdcUW9@W>VCH8HE(!$0T62+}CL*QnAgYuGlO3-0C5dhux6g@=T77W@Tr90}mfB4-PannReKl z&17*`6t2VXZ;grSi3ie7^Uu@50Y3K^><7v8b3BG zlfh{n{jy!CA3X4_QkW>9=_M)`DzSBGr7>hQi9A@{ji;kj{yT6h8*;PM@XUL`0bKLeM3uO=_M!u*? z__{H-+HOD?Ohm7{94S2KaCxB$EIj#}(^uGA!-H1?jodlaTldVpW-Z z3*igx|A|KXznI_p_o#}|f7pb`Me+T^!#U`P2w2+_*49TT_IK^Vz}#uA=MF{tpI?Lh zS{^?TOoNs=2ThpM?Kg9eU<6~tB3Q-5N2K8}44Qu-R&z9y7u!L0!ttmZVFi?i^}(#GGaAW0IE!u$Mi@A~;A_;+GC zej$GLGu7;Fw&+>jSOjwdh0AFnyJK5VI_|A)12jP86*y6ui_ z+eyc^ZQHipv28mYcWm3XZ9D0XJGuXZnYnY;eb1dW>s>4Pl5f8!`>EPh&#u}^F}%JX zDf}fthdBj2dgi_)75t{Y-U$2a+jO!J97>jYZ9#!u`?4?&q!Xpg(!))yy*0snn{3wO z^p!pPj78+4bgqLd31S=D3YyP4edVG^0Y_nRryQvX@>f(e(?Fion+9pb$}cgaiXhO2 zfZ43K(mROi4^OOfCtMef%rUBEbPKzxqlIBe4zB)Ph176p|?UKn@G1LBbx36wsVhURSXzC=RWT(U2G~b+m2~3XZP;;<0iK8s8(GuOL>n9o@f4xL)3pjH*6=`m_tsj{gf6f7Ojk{O3Jo85e73i@$9wSE_E?tt+Fv zXE8e@nm9LTNdRnofl~_CJF04aqU&T9Zq5~7stXzHkIKkc9;_%_C;9b9V}u#$U>qMQ zB*+_sUV}3H>5ic)Wzb#@=CMHU4f2uP8QP&jUj;@4(~5D4bYM)h-?gDlHMK^*;S5!z zvh+|#=8M*1naP@@ii<0Ga#`L}M4N_!>N4|U1HL>#jyAGEihZWXpmMgTPGZdh>4tVG zGZ!8Gq-dk^vPypn0qRrLWvQr;3$@~u+gX3}ERE7FE;Wn7N&XCQ8rkMamhIUTcWY7G zq#0o+X&#-~C4DBa$mYTl_M%Otu3|H+Bv_=X21}E2amaO7&GhQxrP6^-SI!kx(Zgal}W8=QeX+Jaqz@ zsRU}Y>~J6LDJOyX7VDmXs9;D9iawiEjmEDt)8`G2l2s*JD@xqVFCP75y zk@}NCrgjHGruGGa`rW_ypSKY1cY-wC_yFPW#0P1^ueAncmdK<8wGU^QPv$EuJ?ZL) zD=Qn->RKqbjthuLw9J1NoML=z@DMTbfzz0BTW)wlpO{KA^N;9I8g{+rQTmvdbM*o) znoM9}^1kC6s!hqSHEX{%Kq7KoMPh&{T3eUTusN=O^mLigx}h?J!(G+5Qt>xY_n><~PHN5~D+k6#D* zF>TAs2*VQj-N9-tZ5J9lNV+c7%`($B-XY&Vd%!+x8u>5D_w2Kz4x;7`HfO!ElQZRf zh?{!h&rY219!&i7{?Xh5L)>>u`%>#yuTG+wGJB}4iwRG>lMLfd>aA-?T8HS0>ES>E z93qjMSCZ`PMA_0MyNc~Tf7~|0mWMq07IiZ3r@nw%)gp|P6CihR=aj&}h6?mRY4W9z zqp5$4uc?>!0z%agY$#TLb$jZrU#X@;6jKZB67)jv4QoFud1;Ec38@RWbqDDk519ye zqmzkAVb_tw!*8I0Iz@uR+pm6`kQGTsYK%%xq!9o8d0#V9DFhTO?T1OcUbYW*5}$z& zuSu_W2-g!1Qxe^dRO+Mm$eRx&l&#_iWwSLo?@`$hVHjW$2rub=mZd| zk^$EJ{wvb`_4SPTKaX_(p81qEZIJ{}-oeyWDVoH!EN`3NUGm0K${2tME$GRx@@4p= zbUAv!iZxtE>(Umuw#AWU3dnf<*j_$uJ%RE1-%eZ!7P$-2xlT`KJx@Jm1Jv5b_iCR& zF9z}qm4ea4ATk+*<8}Dqv?y)MT8fCK<8ZKIc1-8(L;9L>cszP~@R+iy)|O@tQ`QfT zM&x}^wugM*U*0nbIctIs;Vg`7a=VXSMo^1&k%gKE5XvK~1~=o4=qvEFXxXrepcaM4 z`;csd2`fx8VdBd+^UjJgYNE&se8%muI!qMFRO;7-Bat~G0*wbQAuT&~>a(k+z&kdX zel%@fBdc{zZ*JLi+MU@rF*{2nEiRUKN!iTL+k*!(9Bgvb4spuf%9_c=1nlOpl80Pq zC!8hw$J!s0d}0>d6GUDd5pPgmwtozmm#|n}z1PT;h*`XGEKui$43B^}cO2uhxx}_< zJ}?Uc?Ay&G-2$=Rckw)Ehz=Eu;X(8}FmV9-Ld`^t@38KI<3j*RRue{w>H)M)K@U)2 zh&TUW=Lt#vxHVGG%7Kwdl})>5ShLY8ITJ=> z%&A>&mqc9Mc-Ya14RGNmUIED6XGD(;Eh>a{TzHPlWw4RCcE8A=X5Pk>^a`B}igxKO zuqqH8w=W4%D62m=3w0Kxwm!sy7>NZTv7TzwPVYOdTCP^H|Cnq3yhQQwo4MUA0JZ-@ z>|b;9|Btg7TR1uYHswht;$mcNVGP*9BK+rH{=wO#c=e19Ml+oME+mEv999$o>eEV9#kmAA{P=Rp>AK`9~_q zlcGgBeD`}i z8&EZOYXC5}GXO&V7tkSOZesY=$=t;CujrVR{T&@2qNyVCD5%Q(+|>FP7*Pxg;uCOW zX*wLAJXe+E<{4#<%$Vkd22zQ#=<(b?8-M;v+d*4`RN8n zF5|mFS2(!)$!>foD12nlskWJ@sCV`unao48H&7?JwCfy6Gh?kcCTg3{?XUYKc+}va zA?!qqc8TvzYA->WqjU~I8s@^a3lBQ!0YOM``Xy9YD)Q4bp4?kRn?M_F8NfL!>k#Q_c zAnD%2t)yq?8R-~J*IJN@hxZvMmcm~faz>wJgS*Me8>$D;mxS|&uhyv($=@)M_i39F zW7P$dQ-kEq(uIKW)~z~tP_@knA7v}ZIfzz})?dyzPAa5ZdjSABW*BU9N%ynZFdnD! z$DDH1&$U@Jspk0=Fm{T6a){LFp3Wf1b-ewB*j^oJjE*#|p& z3jiUP|2qhgF|ai^a0bMZzapg77Jv}%#^sf9ENpC;6&zMFbznnde*~n^AZ`MGSBFnq z#symr`1JgphmaPoE5hL5K(l4$z;_2hMM4KaU_0eJ?0K?<_m3y5{Tl0<8%i zw_&bX8{)`%wD0W~fwu|>7CaUm1kOe$lXAlc2l`5swmvo2SGEABtbKNL?$&Vaw+Dowr`J z3Wf#WL_$#GoAByMNbbOUjzh4}<)aGL7b(6p;VTI4;#esu+G;MCklx~RHAqXL<0z2J zP&y%=rmUiynyLHxiV2}#BP}oEz6!d0@^s4J!!x(`rGc>2khZ_{+`Od3j)o~WAKgU3 zIU52pKL%KePOMatIMT0hA?N3BAtas8cq{Fowt{D`M?p7)r4mXE53oox`wnX^;3&%P$^6^?9D^j+>eou3{xJmy8!0s4RhL@()>WPz8wnc zhiky$%q;0VEL!C%yxxF&6bM%1no7@1afK@_dP9%@uw<9nX7LPhY}!+Q2K|i}>0fv$ zcK}dw{xJ697&r@!Jv24Me-!c%>DQ)BU2p}{B8+`{6NpM=tf zG(<3{p-q0Z#sgP(t@pVnolW@h9f^$=HavVl*vC(+`5ol(YJmxLCK$tr>~Zt;YQyuY z^?ECId+Qn~ZO|GIjrNeifBdVqfQF%BK9K?{M!3rXrJagcEjE~3N+yt@$hQ^*uv!Iw z4Hez|%4WS^LnW7VT0p?fn>{RUpmoV-W&E~;+RH%wG;A~QNZkbm!)5!kOlwfMeUt(B zUB?sYIoQw}*1-zPs+nV_7VD7SxsBF(>02u6j~6a%G#BQc3L?eJaLwYCt;g-81nD*D z82O`PnogA(r27Ws;Y7G;zvv(09(EN|zDN?(r*Lutfyxbb52DJLCq16$=y_e8$n=+l zkruoAqL9TGq;4enoWe(8VOvU}%JVDatMcQ{BSiyQPe5!uZL@Nupe#Ko&ott@vNjlj z9KA!@;OAGWWC;tmIhki{*(FPK!OcB4Z>D`@ZS_(?D8o(4MV+tOWB}x{ojclM82j8h zUMUpSMS)ePxD#QSitk)gNW%$+4za9@Zkq!qfts9(U7UD39_`8y3aV23tR=>i{ z8Yw|rTAkqzxbhjN9rJI0#Utj1<^#4zDOdm+w$D*yp8(iQV>=N1L6r$??U}7JSqOL7*h)EfI=m7(v zm8X4Zjrss2KyV1);+||B0El1zt(Eatg3tM%0{I{41?;VJa&i3A0N6#IK^B++0Vk9= zgkK&C?=x&UMT0ZAj&MBV;!uTS%+&GxYG^)pbO87bMG`Dfg!mWLoZG93ieEo}-9qX| zU`NIeCJ#3HyD&6(qlvhUJ8EpDf)yNBCbGV+kVMwriCl1z({(M?uFsWBL?^b|pK*O% zx#7a*9}p zm@5l5vfX5fUnmiA#A`9F@&S*Dg#ptr^#femKz>JiRbC^nWU)=2yXO$^w}aEWcfg+o z919sB3jEJZg6ls$I3WXDLlZ|wgMS?0zi6fspg;% zP$~jTiM=6Bm-w*fz2l9s*)sc~zc(}h>tLcSA$b5J88HN#7H}f!)z++KKnW| z9grxlKBe_a!-0u9w)oBB4AI*f_6e^Fi+rO~%p=}ZK^2wV;nOXH4h!MG_SzAv{jsld zN;c-s_jtB{zOaPsKLI=JwwDQ1>S&@uz=K~w;hS6XB1duk3C*~f5 zeB`n=Bgc%f+#WK@_uqH(!%MlTrJ=Q->0mqTqb*wJ?6e-Wu*YIRX+Mw`cn9hd6p)ZC zu4Y&p=@Mje?tYHbav@G%O!@ox-{t)RxI!;6_G=ZsC(tboW4)gC)eE=D95(My^#b3( zM}6R$DTvk%?IDk#)y|plVu!>Zeo6a(EMp`!T9D@pFZ5_~!Se;HQCvM@E1kaPe2`@PGTa*m{o@l}1#8i}N*R!i@*TZAedR-{+d+CPjuXD7(t(rf;V5iM5Dfq>)V}n>9fzrOLAkzdJuh`@?;P>;^N$MV51`R#cG((V}{Yc zaZ5%TRh@`NM6vh)59ITHRKm>Ew7P#p7{atR;#x7)PcTkBK$SQmhuLD{ktM1nc9Q+z z-{9CmmR-OvrC1Uz>otmpbJ-S|9Hv?DZb`dW=!=N`nq_33okk=?dX6}x4ck}J35-|- zQ(ixjLC9_329`Pp*O=#ap6=_ubXbQafbM4DiTiR+q+XODlbF)RuNWXU%cxO)V1`)z z^_5Be9vTY&9w(PsCEj))#e%PyCu>Nl8kG@>O2`dBON28;c*ne3L<2=Z8Avi@woE4|TAT6WSo`vedar~eI1f6XYu{}Gtv4IB+@Oq?Ap zj8tqbTz}iVDoU0yJSGUvz=ib2Jy z4|hIuC#89O+P>S_zrFqK<){bk9-|)Pix9i~yi|yJGU_U)k+`Ik8fl|Zm~X`mJx}@; zRC@W4T&h^zf}~k8yA?~E%7O8g)o#*kW(Jty3bvMGTl{wt^kSRnD|e}?HHW!{4X(vo zU$l_HlU>-;1bo^?6k0?5H2nz@cm0S@H@HN11HQN%3BQ-1)7U5XRe-PG1^oWciQ~Vy zY^;AANu~1dix7B_*Buf$nNfg(9*K(_pj;BaL6nAp%1~*7s`C>Qsv?`MNgqbVUkcZl zf%^7_kP`SK5V%AtBVhCTe|)Nv;rCN-kk@cKnws#=Vsff(?&??tkq=H3z$&SycQC~< zqDW606CBn+o+le4vj(GAAD0Z*@7*_`5Ck(C>72vr-^)(Hui$#4b@S|V_~o;$mN$Q_ zP<>@T*!h|VlU=N>h3qdMe}F4jLCJC8e-N*ZMZuQPm0>2Xmmn#cidmK7Mw-8AI)naJ zrJrUlL0Sd>f{VBjQHe>W)ivJfdLei|Ta5RU1hL$X_%)WgJpM`5?4wNs!691=2Tngk*!zlh2>?l+Txi z7w+51DA7#qr~25bp*gaeYw$t$+KkGIEHC)R@%u@YwU?H6ddjscb(SXDgDRCjR@ud8v00Q11j#R$9*=&KI0aaZNXynfJ?}TcdmLV}bgCcAqx&SQIMNlC z#4xq45F&!{{U~2i!!i32ad3Cb$gK$O(OztbOu1hJS4#B4Ohg4(aHJ|?_CY2&i+Dr| z1xiYTNKPn!8V|AkMsT1(1Du5bNrCcj7pigmNB8(2clM8@!1PaBA7vdtb%Vf@>Z-9; z)$~o}O>h>S^6e${>Kb%U;j;J zZ$oAfLk48S*mi1SipR;7tX{9%cNJ7#@XKf9)I^NFWDv!XB74;RFC_GNvq9k!$X}5` zLwajS12>|=iGVRGSc-zWFYX8sKKENM-e=*lUrm{T#BPNwEcqb5RcH01Bg=ZWan>$?# zK71I<+dcHYPll~XqbzM3m*yF7k_N&45_K$fX2xsVME95pu^lnjVJeuXPtoQciEbRD zG*rVsfl4zTMON<4(2DIR1(Akn3LQ54n5~hS&}4U+e?CB1VluWRT{;3D)RtI-kr^j` zWt!`ZR$XaO_$V?a!Rh3B$fNTz1lLLNv?SBveB1X;DNY%_^B8NpZ3Pp09{udDYFt3* zmDgu}=WC+#;)|x8KZuzxBJO9x=;7QT2W)I%Ou;E_9^-{8fmXunkIHAXW0b@scua8k zX`Nl51a+50mI%62llcd)5Ior8C(6^YgM5Vx|DOo!(aY!)70+<@!9FBbTPp%t1`8|x zi2d_p)h%$aLpA0dERS2)-c(*IYV@Kn{>KNM-ze!y&!|@1qe=T7Z^#r`#q2^HkPFz6 zP1IhnSU4k{3LX6%r;#HROfk_RFoTBkDbY*C__KVd_Sr?vgA7Yg9^?l^r{RCYY5wjE zs{jC}VSn53{cmu}`cIrH$^2$N<-NY*kdVQOqS$2t{bdq-0hR_42_HN`*%Ec<(`E4d z&?<=*hm|oG;>I(!c8k5RxX5>$7vL5mfx+0%rj>sD%K0=+rf#m>KKBpNNBhn2?Vl*^ z=fn+JfuWr&jO{IOQW=I>jOs7E zHR-2WOOoQjywD(WAJN1TDamXfZjr$k^2P>)bOHBA_oI)ig;jAJZ1MM_oDFgUCmLHB zPmlcI&>!Kx1NWy=HJR9jj~k@nJrHip)1HPeI@>~5n6_J|$TudAHew}{Z*o9grlwvS zG01S{0a6O7pgnZgcF7K{q}dgPq51$@lXv|7Gh#qaJY+2IJQ2(W5kZk8w6J$l@b;7C zhfcw%kSFu#da)?mPUc{K4+rrF>KBd{k`3mVVJ)DMaAMYAiMK6^4c{eJ)I#*dbHwXVWG-mE@ zIFSR;X#Q_#{44w6|Bs^Pzc`PK0e}O!|09b2k>*{ZxZwKeQ9vGpz5F7eXM_TSPres8 zhXE-Rd8n)Ijnu~P3){0m!S&=JjDAitWLY!h-CoA-!Ha~^2;m^aT=@|ZXM1O(aTIho z_*1t`F!NSNuM%&?3hr#6_grjN3$vlVJp`N#C%YPCTVqL5e7R}LHUCf^A4H3FTGnk( z&%Y)EtFNYV;CYDxQxS-;4`eV1b8j>*3Y+lP@6s8k%;rxSfUoQT{QisO{Pi6Ewy*Hd zl0w<>|IPhOBLA-wh@s*S4BmlI)r4y4>90c)i;2eJLQ*T(`Gf-%zaU+URmq%teGa=5 zrV?D%mmnWyok*6%_2p0(X-O?NV6L%tzP%Ha$&nt%B|9r(s9k877~T~zxjTeX%1fpJ1!R-GUhcCZ0+>~{ogRzV&n0KU5B zZ@>I+7wi7>%Y`jWO-&pDq9KdlbW;Dq!@naTJ8oJMSO8|IyTL{69G@H2>yrQ-Tt0Yj zqM`>S1Zro=d_#5}my)R|x)%#PuOB?AsT_|x1%^1p!K*jq^ZWA~kbPu5(lDv4WEN5g zba>U_g(e}lwvL>THs)5HPGoIfRiIq)QAZckMeB<=Z8}>uzjKz!oO`CuP3+k{R))FB z9_7zgoc2S-{HF_d-BG+CDQ>A*f^u7-6WQ#DqVsU{sISSZ z3~dizKU!aH3A3&z^p3D=)9pWU*-$_PnprY5?c$rvxw{y3kUFAyCbZ(%^}rU(4S>WL*vlLrQaCtQQ^G^gw;qikE*ZE+c2 z5AL(HVLmc$i!DJYHt2zZ>U@oVCdO!9f)Gn67U6o`<{g^B(`4~= zuXj~qkd>0HO*p@Md;{^R=TZi_mTOPM_m8br`$54Ajxqg^83#EJ#tc&K z(kzLfGfsirdp6L#7HXbb0$ba#o!UA=XS&yz%PK1Hijqi=g*d{`AWpOQ!t}>$1{Cfl zFZfR}`&A-yu;XrKF-RCx&B-2(vIL_>@nQo)r=NFC4*A|YXo22;iZ=~dq72BQfEyOC zk?{q++T0sgyg2NHfu@tZ#lA&duh3*pn`}90^CfLPM1*0zo5B^44cU(ilfxi`MrF46 z;jzFT=$CeW?mH-j50qE@OtbvZR2hoR)wj#!zVOZ^RwFwqI>Kheme78Mw>yc6+PAt; zt*U^^x}CBf0BI}ELEFLoU0JbY+FNp8!Edx&hk8>q1i$Bdv=7K4FY$d&Bh1w8MlWlR z8_HK!KO3}R`2kBol=8&rVlK@Tt zZD-?R+6CYVqg!QfnU! zOC(0HWC$ihSjKu-AxOEY4#C@;zAmtv5}aQoaN|CHe^>~X->>%pgI-cWdI2uTH{eeN15Bq862E39LnrFm%}l4b?{k<^^}4%1K;#E4!M_N$|+wlk+Ai&5wu@Xhw|2#-5m0x^}$%Z$`j5l6HDmlcLvM{k|G11kh1Rj4u~Rb zlrlHghdMSA$+8w5Dw}1D6}Z5>Xy;rmT`9-Gn{Vn70=ZGOy+V3d(uH)d6WA{?D+&AT z#X%Jh&tXa}@X7lg{>qyn5T3g0!n1;qCeR$}XlM!y0B){;Q=o4a+bF*ng$>heia#E= zjAfHrUiGVCv4qsf-HYDLqlo;Tsq+lxAu1nZEDs(3!>7xW6^y$|b&WDSpBJS1h&*lA zHOuSGO;b{4qY!$mkc$E~W%@i?;!!nVO9Ur>iL`FXUJ75u4i*v^|B=vjI4qf`86vL|6{o}}1eqPPcS$@a zhvFW1G_}ywfbVQPC__3(a%W-XoOx=7FT9>zOj4i|EP9SqrgH!8cQ+d-b{+>@<8kI*LPtB zYkkN7Mx`DQtf|d_Hi$Mx9wm$H$_R$Hhj&S{X>im}yJow;W$^uI=JMkR;dtQy3$mRg zqZEAjsxA!=-KYOG{tTy~UL_`WfD64-naU=?sw152B%|}_+k+(7vD)m|5D%BbWRTr4 zbgx;87-=EZI0~^O+%R2l%4FkQvU{!o2FsVe8k&KJ$E28`QL9E)QB-RmFGMMm{`>hT ze)GI9X9#O2Bv)jXrYW3qZNXc=tE9I&KKb?o4&>wCa{vFz?PdGppej{1<#1F`J~rFA zm@Y1os$I?1df`EI)Gwh#Ec5uOpj}ZVK_iNkFKaev=V_UYT~nHPm65+%L`N@{G1O)- zlkw(<2Q(Ho4wdkxKbh|F?Uc)Pg&j}bSm2rB)ID{E_2?$v_i~D2DF{ zttA zhav>?VSCxJmWW3~y2ROM#pRWnj!O0C9KGR=3Qpol0Ss9zHX~%YsLl?99kQ;PA#aMrGsR?Q=*6V;zYEzXodl zU3e6$dPABri(zz)(fI&VR(_gp${gF1_G6GQSh3Yc=;sB$bf+9FqLJiE4yl7 z1Z;Nry_kHo?babovd=5;mw%PJAwQOGkJ!?*|A3o|-VolJs8o@enVeTtikAMCNbH`n zwJhnu+!UCcI^HEXZ5t+v>Wbusu0XT%~2u04gN5rD?J1=ps=#NS`!Efo*2!wRDHP_JpWs;Bz^2%H4?$e zdk8m>#JTjAMXV}F-*8;EyqF~~cpBo; zB-BS2R2Fi2B_I&hikqi$s&{^GKFwSDj#=3iGnHm5+7Fzk+RselYC|n}o=BcyNLoCb zL?3;W#v41wl-{cm2=a?IHWbXXK={KM*`#2RrFH~ptXtQmG}MyF?AvWU#o@91=(G{J zFS3Kr=gBu3=bPr)>Fr(y-bjf(jyEDNA4v44_7>s$*Eb&R{ZxkGYW*BvKaqFBtDEwc zalSsfH>0;9zTRBsk3qgcr0y}4cMXKDaS9Qj&F?}yC|RUBBt?5_+!A^`CL`1A7&rNh zepCizXI}=sj9|^r^0(s@Q3r|U3npbs1!=_6dujL2C&58Y@{$fP1#yQucxYIDAw4=x zmq0@8#l^|1u+5jYhMS8-mLo0X@%Pod!I?B@Fr>2#@G6QyB+(k>`>lN5?>?wo2b9h( zQ2%$?_}2jX-!OcRKjWwJpVBO|5PuU@RTNa=&l<+23L*GH%oy-@$b{d)g9qF#O+8nK zRxufw+T+{Fy`kyw7KM!#g1~QByxbfU4~D-tARd>3_eRP@|bd|&Q%KlM<*;W_UL z;;{~S&PFFhhjUA7H!xWAH|`?x+b`vdlS$=?E2Se<6hla<^o{jLv#;I`=0I4^!S8wS z#3**t)~$8W5g}fcQ2tC+X{1EPG?BCpb!1YMiKmDkT@*zzri?*@)LB+3tiuk{x{7!I z(FAd%s2v~F1&cb$75&mAePv}O_#uiDW-n!D(8*(A$}%``1dsSjENN0Y*y40;?{VMU zocyY;S(;$5Zs;ye~l8SWPq2^v$4Ozf~1fC^-%#TD!fry&fYV z-gx^cCwsy@5yy3=eho4cQ??VE2MZ~OcI*8WO7x?NzCYU9soFI#Ld1J@V;fBB z^RRnU>@4cR6Y$+(Y4f)`t^?ir6ruPJotbFfsQoD1=y)+cS$;RZRH^lTC3S1aiR5j+ zsMgU(dYFn#=q0}*Gq@b1nR)#l%W57?U&GnR>fFv$KH_Xc{BMXT<|snUA&jw1%v%xK zMn$JqW~sw;C|b_ZfDl{L^A-@M&p3&)^NO=mtF2WMQ+c zG_r>wV#z{rjplY1wIfNMC?=P}et$Hb7Dg-(1<)h9f1^i#h3bFB)S3TLjcWbI)Q3OF zCF&K}>}# zF>2q7pp1smFQWT&iL6wB8myzz1uw@}p*y$x$81!EaZy#x^!ehJj@Xo`N`)v6OAb)Z zT&1XbBi;$Cx>3XGRXsMCu~s0>xh1RK^7P&J8L(3sSl-B zgXZ2{hV?t{A5`8@z;QK!VfpB=9vq9kI~+UPUO&T>%+stuIzjE;SeL=9n^XU}>RKX? z1KfqYR<&N23)(r8cy3AH8~br+GmDOMD0KNOQ0V*`AH^jwFW4)9ND8jO4rf|pyxSJI z&)&-*i)Ywnjll-dOvWcQf*D;!=e+Jcx00eO?M|Oj|G13TfgZq>htVg96E)Puk(Go4 z%qfXoB3P&I_a{o3M?Ev%9E)rxLdVULz%i zFHj^W-f^q}#PMEia5n9Rb69IMRKpNzL@yG4?;_qZE!;nm!s~~|N1Q&e?j4p3Jn+_| z;2K6>@HNYrYZpZp-he8KF@{ku-lNyDcUTG*C4rWx>Ak;qTx_n_9zHtxK6~MM-nU93}^^;y7cCHYQlEQ6Y z7zkT>w$pF&lUxobUZ1bca0Id85FT;iL;)2c+9*&{!rzQ)(9I0QAF@I^LI`1xG5ZAO z@03U|O+N+dI^gUkTLacOPt$9=bcPu4vRcU)ENr;0yLc7YfKA?qoTfe0**y;_50`?b zoNqu=uge`mr$RVSI9BKf7?5=0`c2>jYC4_=7`QDu4pho|3b?yXf@YFPUZNvhSHHf(A3}t!W_dn5| zV)U~EfPWQDNLIjRJ#T@*1Wlt*Ffsfd<6Li~q+I6@#2_YG^$474aIy_-kS1-`WFPM9 zD&r_YkbQAW(v#LUn6`n72n?iqPmsxY47ZK>Z4_KHX{COg5#s{*<&&Mpdk z)0}(6X2lw4E&9TZ_ztLf`~tTT)%gy@!PZ)T-X4HcG$#dMsU-piE~3h>^SH&4G9$~M zRle6#QF^}rbb3Htp$Y=qCYn%CPPEcwNYai(>z5RWv@+(5gBWIUAw!I?f@DGT0lth$ zqF|!JTJ@C-(tU%e3)2yf5!y{W*-fnt)f0$#pr$iQk~0d>6AD+8KU{VQ-R>dQ70G@= z%RMD~i0iu^R3Nd3pe&9%Q_PSyC)SYoNi1~XP-Lk(=S=YIz^1dCLPM`vJGz@ZG#2ZzdIOY($g(N0W=N!f7_Y)Z>Y(i zrCqin;N4yxfk$cGVXqAV>Ptfh6bKeJWV3|`X~ar{vSo5#z71=It#;zZp0=8gu=8}p zw0=Jlp+5rk%jY*RY!d#r&-ARH!*Qc4TJLYNIgY0$hVk)ZK2d*D@Q;x~gVDwlgRCd3 zN^7y)!|KHdt9ehWdHaq!s3V61(T(ozvv4g&dHX_iN#h|HenTH0-dujbKcHCH>rwos zENU4n4`{ncUn5>Ii&pG5K)zTupd-jO6++<||B^+x4wD^;A5}ewtjR8^;e$D|kRt;@ zxPUDRaA!f0K(aT!<->UE-IOs&TS!&&VIv$LXI;u-0g_08O(~&n#Ye8Vq=@{buY;EL z{>8yc4+cc3yZVh@vhd6n)Pin}Nuk*Rm(4njV*R`R)DVd*GFpsGy!<3Xhy3@d$C`Tl zr!NK;NxH}#M)}BNzo?}T1>D8MMDcFFuNSdou^xT(hQ)J*RIWU_JgCGoD(%@jVb_wn zI7S@rd`3Iy>R&nEidZEHH)n;92!Dof*%~%~JD?FKz+536AeF1l!)J%Nc$IT0LY_W{70^j@q0d z1lP(ETt8tL(0quah2=XhGKraGR=E#E>qr~1d?q6MjQ$(rjS=y|yaV*JH~vj7^H&=2 zUj=gZf4pBds%Y6Q08GkEFLb!Di4**^ny6_~L0#EkO@-RxpiweN$0C9V=0t-JO_sPM za5!8|Jc&<~s6@oQFXeWMstFtvS_{jRDGvP~yB^&>nZX?1`T0?(V@;<|?_X!#Pu|`Z zkT)-XQg-No);XCb45fpGIrz5AkIveAIwYVBi-O8%z7yw92&~6ooG3y^i^nW)^eJ!= z0thqul_m#>orqD4m1($cf}C_59k#0`i*R z>;@@8vosKWLfxYj>ve5e&tWDCX1~=6?-K#b_4)}|4R13^vu^jRtY_w?#={`VQN+sX zhywIKRF16SoVIh}B+sU)7!#zsAvAIn?+f0nQEQA5$$C&kY}l?uYO?O7pX`k7^(87G z=1z@wUJNckq30PjVAjzdc4|POdC)u@f_4u=g33oiXrlBNdeVYz*e!Q4x{3ugVsBu0 zC_RSJdjpsNrdGCn^bfYhr!jI0rBLDr4dO)CdmkGxf%te3{kMwGJTdo|wx=kK31ylE z3+BvcV~VIMS!OK&rTf=Sgc}Zi2?RhX21q)P;r&i%j80zT8F`Z?fFl zXo2;KbLPW(HiI0M7S?)8r1S1_uuc3UCN({>n`p_j?U14C-UF+XL*H-WPQf4H2Jh%Y z&)(8^;Aw}x`#`>7XdmE^zCrjFzmRuRpZA%cze;vs>+LXEhsJOy%M*+be2FSf%bW8h zjIMLtaY7R7H}Npz8Z_K9~D6?ac6P-);B>J@q2#}Sx)mx*c2{{8>Y^){QqL-_8oz1w1f&EWX1VhMbf2 zFcXqb->nk&cr7xYRsXbuK%Wzi0XN+)XbgpJ(hZUrxDVlODvsw(U67u`fCFGzGKa{0 zM35TkTgYda-ooN9g9Tq(l@%pn-i6AFu|hFB;>|Pi4!`pj(QhOvvY51JrzuAm-5KX- zE|vVK$dVfuQSoZV(u%@N#>oECnHD)-@8~KTZuV19U|I4uz*m=AHccK&|c^{YysVc+(>^O=2aVR?52&_w`AeeqUgIh zSgAxaNV0l|kc74hb9o436x*OiNC}R~u4wDHSqo8+!8gJw`kNp|E#fb>^zZS#erTa_%c|JwEZ`?DWQj z+~CL;3h9Uto@wcTGOS;~i2K?SA(7dw5oz(Yvew0k_#Ig_7Iw(qm&uz2`M9CEe}E&V zvQ|X}S);6W+CTQ}&`=dqc`|wpmaCF$z{(QgwI;X8qI{$1@(iVKyA8n=a@UGBXjAa1 z4cZ_UdQulX1MuTb%WR9c{5hmbg>R2bWN6#IfVq4hN$7EG%t8uNPBuJ%^(gR(NVW}g zp`v2DRl${Mqq9Q%`DBugw*tFBRACb9`5DAX4^$p?QR(_O0Xkl@{q4@z&# zl>Gq2DyN7<%BU?TA+oh-!VRRHNL`Jj1A9P)x+T0?3}MTuV1p{j*RkLNb?kAI;t}$Y zg>CGY;IkRq7_i_oddL%HGR!#|+beORnfbE``^n1!<)nR?gqU~`@6tCXOhKJDKK5$y z$a^8Tb(KeAJo|P5vP&QENRjk1THBoFGI%PbK#zD%dDJaNZbnuILt|!+6lr*Am{@#1 zMtes?V|&Afk0*dl7scYioo(f(lGLzFbSv&sOi5XsLvg1)V?*PNJf4K8VoQ%W>k}hK z1z&ju2X86$#iCj1i-fN!Gvh~yP8131oc4|BL(#&Ph>bLlke0ET;FCL<<#^)_ao~_4 zo|*N_86*Q;n~&;A<^o{lbeS#5X8}&aD@(3ZL`3)%W$#oxnPyRKWJoA z;(rcO>f6l*gM**W+p&hsisklNg5&h*80QWcY}kai@3LHjqV0?#^t=|s&UAtx^c>IH zeU4cG(gf)-1BY4tBu2v@5X9=I_lbn-n?5j194_;{eeB|KTDbHQbeRePu0s0z>n_f?7mMY+bIjCu@O>o^nOt%_W zWD*B9);J>Te*yUS83;`+ig?_h-rrMujOzA)IcIolmMWIH#+qeo_)U8vu57u3# zY?`nBOwlo0ZA^jHOwnputn(RfQeRSP{A0P%b1qkd6Zof3=tO_lbr$`PvbyoVBs;&2 zLC`7L8#p?dh&dV(Ntn^Q{v=o#srCJIojSoV>mZgH_hy!g6F8xb7vznR~yf8iuQ3k`cAfm4jqNA_fpnwBvF_F_2 z4D57jiQyu5OHSJULuu8On+9j`;raB6hFwg!kpZUkioGRWY*vmMOf4LcJtseCwRM?z0`0Rsc&nC%6shwxXC{u& zQMZ=O)+K0WVIQt(k6yDiY!>!h4m$n1oY7!uTEja3(ZP)aq;m=IeVA0u@_9r3)|UA4 zuJHp#pH6Pv>K>}rA3S7g8r|>oTMw4+?y$|BDWfjZUDL*ijUL7wf#>NPJ;qFl*y$Ss z#?XnGn5SrD&5Y0fKNVhU`lDG;11lCa{mbq4i}?=bd>t&P64%o=dJkmD*3+!b?ug0U z9QNDO-&Xv&Zpfvt3>@hav*9*^`ApP)P53|V{?b0%9fGG{oiv6|1W&&(xr>7pySYD> z#xuQxNEA!w9y&mm_8C1;lg2Z<14$%L=N>$;AbU;Y?mt+T_US*+Ae(0RnllP5t!sRT zl$e^{(RZLi_L|-?bl^hP-MEX*`j!m~Pw*+Ao)zOquo-Aad>CCo9PVxKudN}T48R{Y-f7?;u`nUcU8Bl zt|Gtu$2{zgnL%C+eXVA&FQJrP{|{|%85?J`rEA79+ht~EW@bBPW@ct)X1mPH%#7uj zV<%>a8DeJUm>I6m>F&9GdZw>Ntr=-crTVi~TJ^2{y;^&{&#K-qR8%qq-!QT@w`V@F zy$i26uC@`;mj~NyK87$6=q0+9tRUO#utoKu){i#I$FR9_K7221D5@zL#d5esr4zY$ zRbo5dr#L^-uVI&5eI-8`e=2gaEo+-wT|20;Lv(jbY)T{8uv&eTah%3Gihm?aV|f2l z<8N%pd_n~&+WUJjZ^LPTi|fq(N|gduW9die#iSOMDjKA`y7mIqroL%udH6HHbI!H( znf_?qqO_8-2>nB z7n2B-DWb28I3QU5O^R%?>_m!`dIzLDNLs-4?e9i9W|-{yrok=PjKNh~BPCezk+@T$ zTT5>^nB(^Zf37bgDoWF9FxE-+-5KsJnl27WHz%U{P9`QAKHtRa=Kq_6BC8t=={3xzLCFL5SlEm`7?XS!vi7 z%uDuLo^d|clAUEliQQd!qs@U*b8sD@Nl6y3sBKh)TskG?8ZaJoD+AVzjY7aD;XA9T>Ke&rF`y`HQe3JS-MC?(Y=0l^^Ig-g@zNBZ>y%hx zkGfRDo^&YWwQ$OQO|GuR>yJ&ZgrYCI+O93aix-c`zBqXemz25f{3^j#W^21*&9+@k z0BzgjSLNSUzpZlvM&a^`A~QK{pe$CDG!l$OEJk6ccLwnCF;1+mp~Y>({4eHy`cr{_ zVIi)b#Qh>XLX*mFXW$-Ps-jxEm)Tvvyg15_g7;3i&FZqFT+A~mM2k8<6U6+DCma|v zJ21c(FT3ki3ivj}CzDJm_)*}+6O9Z-Z87Xx8ZSA{Ekk-o4eL>MCDi*)6!sAX#uW^` z1~Cx+5eT)W%xckl!uMkguaLtvSl815RCr8p$adEl;u&Y(H3~1j>V=fG+J<7Uz0#G$ zd8g-~env01xwBbM%W-m!2rm5LXbTvu{diz7j%<4mRJRvJDKD=~Cb>BVr~F0YSG7c5 zS{)%grj~WH4*XLR_c{Ni|Eu5>Yi$EdW!pB9ofoq4_h94X_y9po^a!c%;6D*@55Qg0 zOX0SV)EP0cVBTH3PDaa3oh#|q&T@7S>vRnqTX(aDVTJm*@)|K5D)O9P@x2N6V|^Se z&@O`b>>tz7Hiv|GuM{8S5s-MU^k2UtY`X5eJO-nEgt)@2Y$2~k1rG8kcqRX`q{{E) zy>h%vMH3oG$bIyD#V&eY)#(L(IPC~sq0PcvnCvO$J>mph3@~l6P!SGwut45X?JB%t z`BTK}!?69TgCHAboxS0FosBZwUR3bX1*7VM@Xfm<<=<6PQqH}^?Yao#dg>2--DY5X zOA_kpFMGg9QDvdStS~V*QJu|oO61vy(8NB$p*l0YrdjkSmKnd#BG&WFd=ZeNzSQ;V zFJH=w4$TdsdTU?X2A}V}-8y7s zc!H1Z7 z-Rl=*2k^p9qFEvau*%#qHo-rRXm_i|0?OHnQ5*6ccu{k5Qz-e+Uj!%~LU)$o%lDCj zo&p-x_`z`UUyeGUt)Q00C*&?oi$i;5+;~~?Av`L9ewkpQMwEaE+$CYd=qdu?KE*A< zE4ow^5p;A4%pr&em1P>+R@FG#4F!@lM)~%sN}_jrxtJs;#xXRdzfEUgczuLYB@hB56+8iDyyH2uZ4rH2;X|DeDBGIE;Qa4s_LF%!ru z+y&0PH1E5Gjh^dMTd2SoVL`A*5ejUK*7>d{ic=IhumT>6?xE`clwvfthS=)jveb?G zhon>onrFH$roCwPLiDrmhiPAVBxraW)+VltbH=9z{qGmd6ZsA<;dyxXVx7`T#fl-n zDiSt^OErsJne(M7-Q{z9wV-*+Y7kZHsXbzVA#LY5SPwC0UqZa5;Cw@dd*Z1q(t(#gy@;st zuA}0LM$zrXYmHvcrdos3=Z3jsi(1asi_FTE6EFJVW8HbmF*gV(Z{3tX=eaZ)HKi%a zF$FIGZy?8XN5HrWZa}Pgv6^f*l2HY|T z9OxC`WocK(s*U?mxXJAJr{knc(D|TGyqJxBOA6F-20@y0DDVwuT<4&tdYb0ok>NWMkb5t$v~RanM_IkKK*; z$LK66)DCJ1357E?KCir&wn@%ZaeN%CoYPC{tKrn{Hc7(qbNu0j;u3;>g)xBpiWP84 zV06*Y$QUcehWPuQ+GEl%_lta_rI0;Cg?Bw^)NZ~)vIG-PAG;3islcdj==Fwli=t}x z+`_2crowW7W(fF)1YH}F^@txt%cZAPM1r;bB~teHcWLW;G#!6`DClkYl@+3LjSo~r zJ+X2;1yObR25n|_*@pG$>auM*8j>38c7o1kk1;F8*s|?}J*5|^4B)aoEn|gonyUN= z(`b=^rf$^!XwkYsar}947$~j~Z`Hf0pMQNRKpeb|LdiiL8JuBd$)K49wpJWkm)IDd z`iKan@x}c2V_Z7x>>Ul+tz%iN0hvnZ(@-ktI8t>8TU!y*yzYqFdIx)v&pCA%{cNJJ zfa^7C8Jr+70f!lu&6vWXmv$V8kO{tM%(xci?ZkD^A3!fghbY3=`IE#~%>4fH_Zdjo zB7uR`w{+|*iShez#hY0I0;}&?hOw4xJ;yOwIeDr&sthWNXo{HJ=kT5q@~S?C3NPU| z7gKvdfOH72NSnoEhV8+oN|U;0@b2J9k^i^>c4w|f$S}p%cK0tH2;bJfy~Up(O6eb3 zf4BBSXvT|XPbGeWjv$XKt_@k7cnxlcu4edxI) z#76l`t;+4pDSm^G9daWUK?stfOCm_Oigy=5k>_ngJ4BX>5K@X-_flH%ZS|@s-9q^q z+w9m0Im<7=Y*Rr6>W4aUBH7y_&HHm*y1bd1h}Pn-&I(#xN&bDjV6BEZmMj ztbr@il?O1%1QSak86etL#2w&9Ae9fNev|$hSQ9TKfBh>(4k95K222zMaTL2lFDA)3 z+t;Gfnbjq^W9jFyg%f)AvhnhuT;55{;CIzW#d|d=9I#6}nONg%1Bl|3 zw6Au9OSSX^I8Q;o*sI@Avo?qC6Xu8#c=0Qx)1D}#Wae{~NGv3ob&{c%$Gl-gWy9Z(<|CjQdN7?rjLZ@NX5;EIIXW$UOaps)H*N2soF#B|0cPv! z33IwadJd9{jpJtOuU*jxtu;k34Z$*9>40X~^4&XTXvZL^E)>jNd9%hG>&YJoI?i-% zJLl7Jt6Mf*x{OUa#(-CG`byr>r$7ocZL1`X)O5Rt>Gt+)9X}}wyt}qsOqB$szph*8 zIs*cvfNpJEA2x;)?)r1H@j$C>)-)a0^j06K{n0408)bdMwpkUWL68miNSlxgrCa2c zFMdRxRs?XKM|S(yy_xIIZf8+oF8*_Y%#!#D1fSO3N~-tH9s^N1?s${QOWX@}bHPlM zfR?Cy$@yBv%I!_ofT4^YD21(0NO*AScLbWXur+bZ%J9wnFnp&V@V6iwtnT@)D-US{ z@tYUDB2Ck)QrL27p14MfTXN)3ZE+m?l=`B}rh|_&R+g?uKOppCaE9e49OjxL**(Wd z-y%)tMv%#C9=|g+6c)q0BUXrf($4}?tnvu+cN_9vttXT9SOW&i9n_6O%{D6M6Uk;Zpolj&|X{?x|ZU6c>D{%|blhz*M9iT$f` z5RgFm@=#VUDizJdp?~+pS8r>FShcXTCap4`8l}v~r`(X>=EFmgo#Ih@Qpp1_w6%Ij zHpn&0h@D*Pf~@wM7=yIr5ueN@%xqJgU-N=DOIKYe`iS8z3aqOZBI;M_QC|ezmz6aO zR@yQts_EyJ?P3`X_V1kp_7cCM0=G4l6i^kE<(O4jWL3vYU*T79o=`#4UzMLLMk+@# z*0V1WRyL}X;+|6eWd8l(j|!^iCYG08#3@%A@}b0$;Ldf7;5fsz-{<8%m|tf$JRRcB zOtsU8ii}g=d+|na#=INY)N>x-<@iMoMn4VKNnWV^b-_BTnj29|(ZQB@?Oi2}RV+f6 z-kG6Oyfj)DeONz}g4|vKiboDwo1CPMS4x+3kLJX5W`#Vl1cAimv*9Ayos)YK8M)^G~+KMq}PWr5=|^-Pn6H?Gtm4Ii~lCM&n_B^tsVQ#GLO| zEHL`f;%xjyc!t0kX&}APEbl1COpR$^0oyzrZ4JJM%7T-36YY!|Lw7nA(b#@eblhuy`kwJ$bs~A` zwJk2dOYS>z&Q6a+q_F6~ni+T%k6@xs3ZN7Qq4bCgP|B}g%ZF;(O+lET{Wj>+W?Xyt z0DV3u%=G~7|C7W`II!QUB_NElf8B^X7LMWqFcCOB;H>-ohzWLWpSRtVe2wL;w*^H{ z7q#6MVT*A<_-J-(vc!XbM3P0VuIjg*5u>jc9sX{)z=#&oU$)oti59FJ=at-YzdJohqHz^AGK9YG*IN%PXB~S7}uYhJQXgySH z7VShYUp(!x9;aC@HaW1{4F4)ej~Rouw^>{zsp{3$8fai>fm@-A$06mek5PKj?((df zq8F<4nAa3R)FjW5Q%w(v>7c&Fs#??|5;v*i1`5~d(wtH)ZqaLQR4VGJZf$gl zfs+YHU!UIK>z1cj7G9QaU4>-auTYYik_qS4Bn(RNLJ^%(O@-c8GiUNjizp1uN7*;# zHuP4@mpSMIWyevep5WE4J6BN%4r(#geJ9KxMCs!_btX?kUt!9xTL&nFr8uK|4+1Jg zXyVJ0A!REm?89dmYPG7L4ii0io0|BmFqT8`xpx2z7K7LA7-Oay^nc9uCbIXyBmfXYTT?4bCr$xLn_A2M?t!=VN7tOTzh5P<%mIG^ zl~OIs#eL`WesXq8wY0ZFDpYX>Fj)ptvqYo7+*F{uEE4gHKn@I{d>3{>L?E@2JAlZT zNGtE?zi4{cMa+nk&Yq?p$zDd|;KP*2j^0L}qb^#uX)&zQE^(9lmvw;6D32b$t%8v@ zYeXK4va%B1n!;{xNMTP?BciWj*^wKHpS{YehXdt+x97yO%WFY?!VM*nHPo*+XOd8}r50U+*CA zh^V?!!u82g2&i)J+bT@E@~1@W>Ii;SZ~zxWVLK0Gc_wBryDC|(vCdb^oOF?aW`F|+ zL&U0FMX$!(u~WpcocFjdR9*1A=?1S>Il;|AZwt42OpX04*{Tz6{+FxGwaVO`%#6Sp zM9>T6or;B3ybJZPT6KNZq=Rl6_^P^UILe9!#jDz+Te^dB8NrzORH0QaBFObO;F+k$ zIX@Zh8gUp$h`tl=qHy7waFDoDKCVCK~ zV(Nj->L?Y*Gm-eTGoNV>9M32nvg0uO$Fw0NHy`lQtNjB~&wDhNJm)@JiX1Al=FW9Q(zlor~^)hL`^+S1;Lw{&0g}?m8 z#=Xj(k9}+D zD1w11#uXJ7MgAmCtAb{0>cFh`Qk2O zThgYxpL&(uO{&MMdg>AKKrc#BDvxTblGKP45rQy$s8(TOeVe3DmU-pJ+xhSe#R)|U-$(7HHzB*qbN#PJ6OA!|3}PB%|Ai0 z{}&tLGkoN1{}#YOO?^3har}>o^YaU5yI_sh`<3Ey6W?#=SISCYF=?SbKB?(UtFzT( zte$O+ZL%H@jL81v$2BupB~elSEI+MH7y=;Tq*I2V^Zi(?XSwA49!AC9rZ$wPWyHcB znb|&`&d2`>-F#$byQ){&X<~|AxyD;6*Pg!Z{gOp=ByBvRqA+Nr%S92g^w&iF))>4giCV)xaz1)3D-L3tglE|IGFwk|6#~MbAw4w) zOMx_9wIsp)xP(I_2$D|HgXRbmULu1S2y^Y#+qecrZW}Jge(Q%-GL;suu!|G82Kk!_ zP#6t1UI;)X=91olTB!Kk=q}(_dIZ-I>rAXb|6KvGc8_Npy z4*oXh#LaD%LeU;HG>C&6c}xk$R+_8{B#a0|+UxvRvwX<}dRGdXyq# z?{PsB++b7iZ#G_V2?yASlxz&k&=QH;$)oa46nrm)V)Zbm(Q)$X@$M^HKBlGwzHKbC zE`G8rDn`py#{EcQHq*t?m>tRr<#Rb$i!_*27;%FLm9pPX^X78+){Ad;KioDQ5A_rk zD?F1W10}Hif>Bv9^j~5=3}p2{_I2A znH`C`Z;u~&`&%WUm<~3};z7--q?5Egp27^(O`Y077D&xfzg2XVcp70Ie!>Uq-9N3m z=hj$LX}Xwb2E}TJSrR*kkT3cJEXF?L}y@s{f58C!?J(D`h))4^J7E-m|P!W4>Mz=jl__0mtZ89lkyP7`0vcV z+%PV4y`e4utRw7WbkJrx=!?EqOy6%%$(%_i$1f=A<)D>oHdH$Cy(d zUZX8GSn6mO=^Hd|*1pwb8N17{>CbiGEd{q;tmu|I=8#Oa989p@hO6^QDKgid2N#)T zjIA9yNRhMak1f{|xO9i>@K67M^7>g=fF{bw=2t}c<>Nhf5*-H>-XMyt^tyGdVZkyiZ!n|Q{)^o6Pc7H$c#%b;{`q*2O>A|Zi6o^pL{vlt&NeyTWAR0ot{xA%G5%T~3Rq2y+AV*`sa;4&GHi8bpe?Ef zM(#ij>H<1?V|`)dDZo|HJ?w9Ow zpt6yPYH+wNoJ`+NA8kx^2<_k=*cu~{q$u(r(?MK!xod)fx9ZQwPbI3xPK`pV(H7U) zS3)t}^44wcE)!nOSD9`Jdi!%z?^(M)nG@ zg_Emnu-0PxmZ_3*L^QXxKv_DYEZw_Hd%ZjoHMs$__5#fW43_JOe0qe7l=u z((|>!Kbf4*B&E0@X1@i(lheH;ga1ONf+_;{8N+C9-K4kp`d_UDTVPzl*)juAHZXI}aOCkGsa zy2A1Q3sT#AU{7w3UrZEEr@yYO>p>iHPVeGu6nm?PYzyMa4VCb5Q;RYs)p12VB(sag zPDr6p{p&Ok`s<%Z&_Z+G(CeoIz!d)fbOdSrk2K!@R?7cL+|K3wJdqSqG{0t)%8j>Gh)>-EDlSU!-{bJ&ln)yh|%Zl%=IXliEjcVw8Q1T@uP zNZv22wDz7Rm)MK9@=t+SI->ks-xcx0uGYVA+j|nzaAOJ~$+PpfC>-R`cZn5$X+N`; z9iAJ?VRQu*r6Uu52u?7v_E`@v#J}oHrQ>npZ2Nc?Gi$~Re7 z7kJ{35Ccl@_Y6VbsEw!{$mg&Hq>;Gz#`hQ1NGy6}< z`5!Hs|IwWJuVHTaclT@gkM(dBu%v47n!+Iaw#Fb3t(u%0WDYv>x9ZPcl4S+sQI8Be zPwDnUNIyu&u0LWF?{{E+uz&pkcXBM>x>$N$SlAB7Kj%|DP5Nay3JGz1qQGc@hFXaAwdA}R?RK&IE@+$i0c!Jn6g)g0=nNOK<` zK(V?XW9*;zQbP(XYS_~*SH=9Y_pzKBD*vO`D7P@*d$V?BkB|&|oh2_(Da~zgL=9k5 zAzvZ|y_$ax1waAOsN+px6KX0X&TR>{1g-RFeidpCnLcD==-~i9wQhs-i?^QCFSx`; z)dKAX;r(N#mWwT;eq|*%X7O3zJMZm87R78U>(Zh`n$iyKazhKm!^*MpKYnZmGM zSB?6Q(D|bJzMV?m6OeW!L`pPPa{Q{CW1RpUSEg#BMz?ci#!{kt)6h_*g3NBgQ_Vpn z4Cgd%FTN@Pu3C=yT3|fX*d@F}&S?uMa!GEEGuniZYm`4dmHPDg2ifye9JdW(7FqAA zz-h=Mi^5(8bhM(4oJU%K@aJi#b*XRk}Mz~ldiUK_n znKX4kt__~P^+)@9ab~7dFWMu_hF49L%P95SQDL2ee?CeL9G z)6Mx|1Z|KY0H_p7$H5)!fk8kbbyOP;Y>(#LCRZa@cdI(GFd75Mro{g!zHxV`&F~{x)yicVCNquXjlTm z;9Dq3(63%g;1F63XHg4I5hw6KrW6^^HceE?&^UIwk|q~f&$4(q8}uZ8SgPJ@)Uk>_ zBdg0h^^fYV2~Jx$g<{c#Rois9@n^`QwPD5q;y8HqJ?U3XVIsk+lzvV*ad}1#SkF;# zMxwYbxY7YNohOWmoPw|IlJ_k&@Y{?!&6DDt2B7DSQkh~jlV%s#89D1G#X1Y~vxsncmfM8ZH`<3f*fx*E*?g8`KBD}a21c>0d8_e*(a&FBdh zb#Q8KZ2(+Z$ZR62a_8|yB73QXTJS6if`pnkFRf(id*q6|EBhnji2#T}-mxa^(On`DCH}+grUwMcxsO1=(LA*Dl4uT3VK-`I|L7d5lrG55!$^5ITCW zm<+`2p55BepP`s81@cFl$ObgaL{#;!QA9lnBC%Y`NIfWwyV_GXzHHzB4o@{~g01yV zupT(IKp^Qd+WlzU-PXZ@)O&F17yTm|XH1hO5!Fs6Uyb_KyliBIgoAk!rBFBBO14u( zk4&+|7}&3b3)|;unuXdpsw5?+hzqrWrop_27+L70Xl?$0-DUILd%DuSQcuw**%(yT z?8lDpR<`U(4oK5LO?r)W^BA=^Ld>^UN^C*-~MWWNN(GYPPXigv7-wjeCai zhSZEN=^QzsvL@Xhol~t?F>H8$^!$+D=Vn%3+HHMIq+E zmyc5KVgLB;<&PDJj=hHtYrN$&nLZB-;ya(`)9XJv&^czUJc-&p&M4;NsuwBYE?R{h z*3hY%Yq(7*oJoJShKToQ%~||iJ<)Q5AWzZuLgHYrd+T5yGXVbiJG5CiuMFIQ5vYL) zY_H(yPm;CD44FTNA?>&yR1Vy<(|Pu*^5-U117I^OfBOz(75yx_vPUf8Te zdoL5i^3-i*bK=uK?fEJfG^agcgbh zR5!H7AeU>DN@be-FRCMgrju5ZZB2oR!kTJ|YLt$QEe!t99vlDE{C~2}KHfgXC+g>) z@!!LYW&cN-|Nr5P__wH^>%#k?f0~3mEj*}xEQgUJk0e8URY|r(75O6EH_Nt2a|ce1|O~$wilPTR0$W*L98@?!1}e~(0)!Ha4+j=$hO^7 zsvQo@`jKX!cF39EDYOPLxP^o=6hp;C(UZ9FB$d(X9)z*mO{9OvQ1F1%{cN`KaiK_3 zr@cwerHiU9&W5780j0UEO10spX{c63$xNtSqjmfqt+xQ9ZQ<6YgP)z_to{L%ij>Nf z3X|eX;t*R<*>%5<`}_4n)bsQlPl)+KX$Xq6fWn0#X$s|uKPgV^=QlVmlqb@41Ie-p z+LvTBi{tx%tdTphpCWruq=ppN9Hd;R9Z@3_Vh$ut;UgNPhEy(eNvl$iT$Q)-q-|)+ z5@vi!e35=JT^%VSh@IUr+!r2Ad3IQ77t$7+77r@Nd}0?R(3=$30;HQ%*WgqyB&&5z zFL{N=;C6Rpq`r~--}Z*Z0z~$N)AncYNJx>;j)|Kxq^Oc4Bl%^_h?0gQUsFc{NTDP7 z74~3Bg~+a5Nq-SvlP4LXK4BzD3bShc55F%Qb!Hp6z7eoRa zjX;=iFQIiYHr3dTJOCBi(7Nr&HjbtxJgY^!R64t27wAxO!^W}+qG=I;#R8P5eAxzP zLxVQm;0dM~js2BGHdVThZg=pVabSD%%rD$Owsk1KxI(UFYcSPtU+1u?hkQ#^qS#+h zVq>Nxm_pj1Vr-islazii%@WQ|GwBM;BV=vc-2l57bRa%DXmBn^WvH9VL!$P>8AcO$yiPEQxsi=4!b;F;WS6uC0i* zQ)nF}XgGX-g%)OlA?;A1?UM5s$Gi=wxS|)9U=MQD8~#cglF7(9&XQtGf1hwT2GKRlrZFwNJR#E;yHk@*4=R=n zU*p`&w^&CsOp ztvx;=9Ts1V9R>@Cz~HTo=Yzr}K5&KPzr-gl?37)hiP}5<$!4Ah*uX(4w4B)&azC;Q zK`piNA_IykDfTMVn!-cQ>*Dw?xQkZ$-^&;7F$IHLKlv71OU&a;09%}B=^~Mk(wCIzeCxQ3m{}F&PKZI9(-p==Cao#t3oIyFrpb<5 z6K=NZW^z~{OS3C{I+EFgejJ;-)XmeXNV83$mp)pwQahfAk6&mKZ?~l3-r`s6lbP-^ zOvg|Y0(3v7VB*fNM2TIoqcZ$pcQc`mm^5YRE2Fobb-3tUP{+W9|eYUn_#wy zbC;LU)?XO+cYnYcFKhe?HZoI#N>`V{)wK+sKBZD~$hO7CqRw$h+Qh9=LyPyF%?5Tu zyi}u%ZJ##T_}JZs#IKBo8PbhAu#;8J-^}=~_HjDIJL=0U_*vlXzi)v~U@KdW`wFbw zDvf?YjX2ai;8-=XP`}9mJn@dzZL~|1i`zD$&7Xtxo>oM;b@15CU6wXyF(WrdH@*ce z^pDj{@;GIB#K$!sre_Aric|%A;3J?_*5tX$Zh(!ItA0$Be{h*Vv9>u|@|@(#p1Rii zO69z-3cS-DY;I^%u^fCPoYx-eRY3pnkpICIWP3dxvQpD!+f@eUXscTF9^$LB&8kNT z%Q3oJ$b#&r1vu&5X=`d%w=eeP z1v=r@@euo&IzMlrHfgyDu8=}}rI;$Y1hC7W=6Hb(DVqnx*}rEosjm#0K` z8!4S}YuNc6!HqqflNSqORaEetRLDN&JH6L1N(sD2k3Qqlpn=Nr7~?(M>o}xmzXBHD z;g8w}kc!#T6=L&qdnuUdGH?rwAO@J6$s7fgT{VGjbZ=KZ6GUC~bBt z>>-dkvSua)z0wNxNkYfpyc+u**mBZ%jSar{ZD@?XdM=q^@e6Of;s*>B`h1)A0R3wE zmE;w+8w8IC@=WSUVf2cZnNmIWrX?``TYdJI@gB+JH>Bk8fdH0o!P^|<@Rm4M*SNxu zEez7(sMjdM+`?JBGjOb~Q9(CQ!qP9jGgIqxhVN$TP4R;o86UK665DExQIf@*`8QB?CnsSFUS%f^z zOLazvGtyx$vJ`EUm^E_*nKUaB98bn9le}Y#hPzURwLGGL|5zRRaSa z6WUNQ%6}KF)5;^sX*U`9a~HQTJ9&wc{Pp3@GuZ-ZAb=FO?+1@r_ zJr-FYFt)+F;Q`o&?qLFa2Z*SOuJQe5IYMqw;z;!ka zNfCIVLYh=`KJ#?&y|-hm5MKmVqAZmG$9Sratuq z8r?Gga;rTHw(g*6 z2lt^{A2~M|2KZnbMEQM%uh9hnvHzbm6=e9tB^& zlqnxaXeAqQrDN1OI}tqK@oJb5_#>x9^WKM?c*CG~H2#!Tq|G=5=VKRvv(n3mcuA#o zD}&Ro0y5IR!Q2x&de$Lf>o`j0c|5D2v{=yilF)GZVgZ(+&i={!;#5u3$uq_&5CMK-OTo{vD3O6<>_O8Vk*{bv7cZ7eOlmZ_hzN5Gbz2=v;t_r z3J)B?RJ?Y0gkR7IADrdO-OPCMRJ%;unQCymbm3QNeUCE6er3k|X}lnXLw|@fg$}t%$Kt_~?bkaP{)CPVCfWOx<(I#}SpUS<`Sw-#V`v$-z(;>7 zvjK^VHmi}pO1EsxsQH722hB0}aVj%hGR8uPK0eT`rt-Miiv62lrjNP~fWYPF z%ZSDs6y)=xpx%Ujw(G_jzV7?~_n-Xw>6MnG(gfe6fH zDTjTT_U5lHx{B#HH4SGeVio1=*twUynKR>9EfT83^XY05)hYR6H8jzhFc}8bAt0XqGK+>-uz4LxJPyp!HGykv>n$!+FP!B zbK7jZhy~0$Xu^IgC~rA>U!UcbiJEzP2NcFjqehcbC2CGt+UuB|&0szI5cWq(Q#S@@FX zGg)ho$Qhw5X!wP!by~!(qHO7tSB(Hli8T*qqaAP!j12>)gjFEf77GN>H8G!MqyzH? zeip`bnGjgg(qI@;w!dua@iZ?kQgMG&V5z?Ypd zr-BaUWmiUvb>)W6!OQZ|=B_x_{>Wx>l{nS4vJv56jp|ws-Qhm28arw@=BL&8-UIkXsEl6C)Xr}YBVY91PF;hY8^2y)2lWBefWczSS_@Irzv zn(M1mi@k#%x?kqUKUQsnpJZErj8%ZRRYr+$;j0IMA!bVqRz~bz1PRYHW495w?6@$y z!lbI)i{t#31DFdi%WVM&n6050U8p9;N9D&1+?j~%Cj*JOB!AHq=j5)bxAvF~rc{aX z8o6}TjZiOr-l*4sm$#og@EP!Kg&=0?)OY@o)7wzE5V7TiLM4YyrhuGGv18Vk2?St0q zl0|cN;eq|V^xxlI+G)^IAqnG~|8*to$)E@I7Z=1$ZQ_jlKKb%(F>I?x>$N|#=yx1K zZk~Z|+VHKlb-A^%MT9C)%r|#H{*utakGzEGn6J!Q{KYz&~?c25% z=sSc^1p-@8fc&zx-w|ppF^7F{zA@=ek7=L{d4JvIp8=I%v+=&MiU=h!1%APQ`9#as zGsbf8+Oe(}!@Ln~9H4ax^?y8+J9PbyU~upQIrtIi4`asc>p-gw)c+~XnR(Qmeq>mW zt-#23c%^Z0nfGG7kIe+{JZAq=gBG-p$7?x!+(qE-Aey&Y2WA?Jbhqw)&m=Xs8`6yC zej$?gK#pI^R^TA7gY$zj&BL^yiwGz!6oP7yP(WmW<)0WQL$- zr;{w3;XGWgYHprDGWvp>dxhXQs7WZgdKaDGn|MM=G1aq@*=a#>%nmw%n7Cq5am9<0 z+27CayXXQj(TF9*htEo-_lh$V&e8Gzi@0|HvMpHCHp{kc+qP}nwq13~wr$(CZR?bM zN~esedvE_S-5ve+AJH=t6Y<7ck$bNdv3KswZ{^PX@_7pjjmytQ_)tjy$}7rd7b2IR zkx+THz>CIyQD!2So!P29!co0h<40zHDzmW5ExebX<&~eg;72CDmzA^0Es&R=!5kSi zxQo{QT#sHQp*BEDUO*&{AF1?KR!%3Uh(#qOE{f?(A@%8EeDJZ(sE7wQ;lu`$W;hms?;_W$uO*K7LVZA(WLPp{f=XUhtuqKFTi)a)`E+Ti{VuUJ5Vl|GbS-27z9B zZ=}*(3@O40398Y_Fq{@Z4EB7_!_nDi=%#RM5!w5j0Z zk?60pi6}r1aGDrS&jfa@ylw{ey+aJ&Y}he2Y|&F}QezE|3VI^Vm@ z3YoJ2(>LqAK9s`;C(&G+sb*B;Aepwn5Sgsq!BE;=Do5&^dY{S~iP1^axPDX^UQD&x z$)qHvBngXFZQ4nhOoeEEUvZsUJGsI%aJv>@wN&zsq$3(_-e0n)nj+gb#XSzD({`F) zSnEgFhVeegFk{xaKF~s4prcdThFp5)Q*DDduUYjny|`G%w)J3jYm@GSuJ>^5f~$KF zt%6K9p-s_kOCkFwq}V!!-C6nWu-qWQ-20lTQ|<)Z>ku@O>rU9%6LFklgIcL!q@XAL zKx|OzH*6YUDK;#7mipjB8=fyL6vH`^z^`H9*LK5C ze#36;MqS|d$9erIuY%?A_<^7vx>W9iRIi8{wER?Z9bNS_>iG%n@Xt`%5#N1rItHZ*xZxi*ILaeu2c z`BG7mHLOTRG%zelL?KNy$wYts-bQ{Q!K_1lJwo-3HFzmWJu-IKd7>E!Zy35J7|XUR z%Pw(qpSJwHP90B|7qD<|tw7NSS8|U{Hbxa}jCw#F0(FxqfyxV@U>x8#D+pnV z0lRowFDqlV`zXl9^|(@uL)SLlJ>N(UkvV6VcOKH8oo6L`F!xK1zPtDw zG)bVoQB4R?l#E3?b~R>;-M~1(6NN8sTRN#pxrZ;(5LAXHOzM;?T^Q6d;nOM8u?ij` zBfN^-y!?AbZx?i)fy?s2B|wwMQo$)gsbC_&26ljnSnd!|nI6WlZmKnBHqYLp?0~bG zx-TFz*l^2G3~o5$afWv!wIJV*%hPnaUyOw{<6eU7xhbGV7j$diaFP7pbD`8rUI~zA zl~7e1GAMyGqX2Ahz=pw7Gcy^c0UV`a`z3oMJuZ2`QM&5U!^wp!S3Fc@qWDnh;*oS! zFu2FFoj7`;$~eX{skP)iw-5>!kuyhzomllU0KeG<&k{x4)>F@A23>B$B8gKgEmPHR zlLfRO+>Nr!D(-bJjld_x-f7Ue0J;QAk2{a@{&z9@MVN=~2`Jp}=3@Wu$%BGo2= z);3Slwk5)6v1nS>?#wJ)dndc#Iho)RtRTA4m1Q?3mc0Quh*uKZGKp;{BcUvkJ~Vnk zc`BU6wXD$NxPpr~opmXpbtEBm2#xi^2&gx5nh~L0xWv8Ed>>Skp}*y&Y_#kP>w4mA z=5RVQO@?p;W0^Kn7_zZklSwSeD9?Ce2QTA^3LA8xIpZ5P3AlXKOPa(E2nP*NnvvyL z=J1t+CR3ekH0MU5r>@boob<`x2u5z240e*yY?FzPjp6j`)af;{QJW@{FCC-lNYaN> zWaCuY40f_%7;`U~Rr*I}O~vJqc~`5-KF*n&0NI|2hAfy0gzdL@^XGl4tEdP^f0G*S zr{Pxc8+cm8ZaPK~{(6(#OpFIh>64iV#=aHfD7UQ`(MbBBj%@5Vk@)&CoF4a-&Y^#4e}K~h z_Zbrr@)gedEF0m-Z$E?kZs`oaJ*VlsmyPjEXnnI@H{$)+RR*w~XaR85?wK(Y>Wtxq z#8!g8VA9k($WGr-yT)xD5Jd5WO{TKCOU)MoJHNQX|YC#7a{~wy*T6r)i)hY zl+UIrb!H5T%Ft1{4f@UFfQH`WsYj~pOvAV)9W-p2ntqB}7WJw(iL9#EAV70ugoti_ z+drc75uQE)#3{7Ewe_{! ze80Ej7?jXiDA6OiGmSGW%DIChF6yD9Js=9-*^!XmF+p92hKt5Af|TyBl1_Ewu&GVb zN@}}KJo)DGJWgF4sTK&T3_tTC9_H>URvkW`tyOd@DN@7e>hFZr(oheV7ZFX>(bUm- z?3kE=ZO*&RQ3-2pBC_)HybSMy!H}gaq?RG#nS`@Oj8S$L7S>i6`|xHuY)+mCR}2iF<}ysJzt4P?3DqModRn15xbj3akCfoqG|ajcE|tV6mzn@kl`~D-IJa<<(N*v z2OUIx|D>boU|rL&U0`+HTsrW6#uK|O^yTQ+bN3tCgUNYycktn*48iR`Ec!F&L6@Cu z>4|4Uwg7p+mIc;2pIJsfOqL!yI6=}eD|P>Q^pK`jxE#%u-iNZ<2ZDD2pw3E?%YPPJ zlGEWx;k8C`o|aLT{y^B#`TDauGgtwg;`g!md)Vqkh?ZPf^e?!Z?60&`$AS=FJT3)M zqzGfhl`$;EjsuG6bxqp@uUKMekdWW`4!aGGzRwjwKt|O0pFB3vx;+YjO@!FL?D9@u zK#A?((bs2Bfq={5+;?L#HKZ?T%4+*Bbh!D* zyU0hWael{iS0KG-V6c!PMwNK6(8jsDA4UxIfiCh*Wc=+{AaP6tQ64@aJwJ ztAVW)GGJCKK}X&|-`cdXWQ~1g7F6#FA6;nX{YuC?&>9VaR)YN{UWtCOZzcamF@8fbiL!TC%! zw!RH4P0hVw#67%h_;BcHTHbE*C{pL#-^^KB=92uIc*+q7+tpQ}NfB5fY&hp{s}SJI zauqa=ptHcKF{=%SLkrqSb!iG2>F!4ph1``)49^h@UgR+$`2Ea(vP)YhgR9*rTjyNl8uvF%nX zBei>8f@?^K;%YnX|9oWo+@-%kaep1zIlxmJ>hb88MQ3*w;lJsMd%rp5yI=A{ zIRNx~BY`oN&*yDHG=$g4%$8tbG!jY6FZdq*n^I;Y zx=32KERJOzrcT4jJZe{X1@6Sah-j}HdWIcWT3@%)h<=un#{an=@|y+>*Ufa|Az4D2 znm$_9fjePA&kTiZF9;{GHddWD4r7Aq1nnb_W(j_JDiqXHJtTca+c*hnxFs*;jFoL7 zH{|4$_WBSM@8eyjEToMkqr98URMX}3%|LX%RtANnzHUP@b0V;ZgIM(M8s*MwXWoN=cn2aJ1($x>f9+qT70xm+GjQh3JuD?eVuQyjs$Bw7mmormms zww7%)%z=3E*6fka`6B6dth>)EQs?1P5uQyaEH92Mt;j1#+-%xs=&$UGo4$!F_(eD(c*%VvId)*K&?QSXC_*|sscef7ok?W#yew&W#n6ma z$ukJLBIr}@zGaevA;lUhX~kT(DoM+v`7WI(&9RD}8vdxdW>Mr{a3ik@;5TKDGbkR( zOlB}!f}dfwbG;#hLyb{wr`tjq<<61r@#3q`X7E9B&2mhkwtotz9XaKeuu4&##Upa7 z)WKbQ-Y6#>QZO}aF375WSXn>3)Yb(kXVG;vGMw!g(WNw~}2%(QBMmH!T@ z&QC#R=_+5FX{N9MtI0%SFYSy9QoCDH!E@OYNIffNxmmJqZ<|JLR^nO+`C_UQ<`?Oy z3cSfjeG2Z;rr;<827azf+NukD92y)oyKweej~AjEnl2)k6#rE_W)Mwo3BfB|@<@{- zHMijNMoU|m)10gakmx2hb-n~;H7ubLa&+$m%6oIg1-!_6DS$9DNp*F(7fLUZZyLxh2Rz{ zsJ6JO-V_BM zDi6pbPceY6jKLRj=L@v+lRBojPw=EqiPX2IUr%6668C&sQ^`o72JY%qs;8rVSH*Lb zbv!tDDOD0COy)!DEAi@bVzT2`w-?)#D?Ld=YuXuTBU7N)e0eJTq)bc!`ZBu$T^wM2 zbNvLViBUh3-EPAe26lOUzIQZUb7fSCT_UWErb@XmIFF_J`jwgxWXUg1_>Pb?AflMJ zaF@vt%m-1l7?hrKlVxTRwj4UA3OyXz)4*N{m_#W}5Ky?FOKn;}#;8bKC?Tr9I)%&5 z5k+{VbP0L|@Hofx#X`=On7YuD`99T?u?xZX@kQJLFEH{No>BQc?y-K%ua99ps+np7 z7Z2+f4)jKkyOG}>C9oO2SIdDCZ=G&PbwLE zrw{ySZ7c$XX*Am1We zglte(No&vx4MAWx81g4;k}nIF;4yEa=NStp9Zs;)t>ORN3VyFm&h%)XQwVnV$Wz~e zf69%4S;2Y-ebp@Qfug7DrlQF$L9HpN&ey4@6@xFW)Hh(H)`o%(T6!6B*YeP7noXP?|2ioY*103f@l7j2QFht;+%0_e5>$%bn?`?#5? z9|>O|F+y5~f6@$Ab^(J$LZm{Fwnz?N5nuT&Y6lxJ#jwS6PM1SNa zhcPS5uz%s<>r4}LLY_f}6UY{{oJofz@dN)dAeDP1mmv4Z#?L-l^2%m}f0+<$-UIOQ z4K`;Fx?hmV_ib@`63BMCQYTMu>7xdEMg;%UQQ^Vfd1q(L3rj#BpEB}W(`aYrQ)|7(aUX1z zS1|i8Y%Pq~1{#*e$uXp$yd&mxSI=-=N-^kC;1?_r^A&U{YFbIyQrqQ~IFNt@2QC3v z^x!#H*Sw93c`)<7qU)oPfg2n_&Vs18ItFRRfXt&!{?~5+<$>uzo2MzB;;7h)vvH8- zT@bh-z$2Wo(4Lu0E^L}IhhrgW$$E{AJ_I)f80EG)Jc zN5TVvP+UN!#NNF3F3;;TP_-LabHnx_sZ?P9lZF~%ScLDRclhJCT)1P>Fr3MkfuH59 zVtx74UCBoI8 z)}?EmpA$vbrEgvIYKXZ(gkNB5$k7w|tn|pqSwb(h*M-A#*!@@Ibn zpYcuiFGp+JA$`c&YD8H z>t}S(iOgmx8|}{q639LER}3v1}B?-cp7-B&iWx!2)ut?t>>dvOux^xnDNaBlqLLyOaNyV*M!BiYt_2-m1O-hNTH`MoF*)$z1 zvyIy}o_+vW+*ypNTnDRdnPr?xeHZM0mPf7JZzC7llC7h&vk&1M#N|`85yYAr|2tC2 zUOmR-1H~J%gH!T?Fl^%Mv3|(J-y;dlv*ucUD+gQ9-%G@3Cf|lqh$<;iAD^q@3ZuH; zTEpjCuIC^FX?}(>z8-~yW+Jw~FK!8WR%pmH>qvCh^;B?*CT;5F8gP~g=(#SJ%o<#t zuWxKZzG9*TV`dI$)*3{eu};b3mZ?fP6|&saZGLH%Dek}rP=`gRG?Rn-H!KUpL;?F* z6`oFj$d0-$3R8S|N5(~AK?;+qPtCilXe!UK_4uDoL~|clSofMFZ#qyK79Cj(C%#=l zN+%Gxr>4Xr#CFbau}ue%o4Hn4@%aZ2D+w#|T&+Z}0l83to^ZanVz+`h>Jrb1gcIQL zaFU$K=0pJo18HWU0vcY7`VvSA%k+DKrCa6|(IF~sp!mzzpkprtC)>h=a%tVIVjWzG zLlzOLRO)_j%8too9aE`VCQ|i`#44Ey)zTxXq8*QmgykuZi=<`hMRMj5r83FL61g;` zzKd-uW(48*O2v-R*9clyO%CR8ouSmuw8S4}RqM`p7^wpYLnV$_;6|i z;0gnHTv)ETm&C4X%h~9NG-AC-UIjQ2A=d9yU+gP_gj*wq5zjoB}8mfKG!<}5A7#ujyI1=alUD;Mcy0) zXQ|JNs>1J*P;HBaT;n9zVC;n@c;^;+4#RMsHj4J#XS@|BBe+B2zAXG9Ei7DW!pXwC z(o=_jBRiCB{Dp2BPIa>W@S`&zGR21|K%3Z=biMuh_et8veIW`^Y#kJ(~8UV|G|wdA<0 zk6k<+?uz0M{GWvLwT)89KVeL9#yfH@J`a-BU}V8Rih(l}t_1BeUU_V$jEZgT?TNG3Bdy|6;^skI~A^iSdSsJ1YGF$l=RMR^=^Du;}Epsv&*6i=W!>t zrO^6?Y*A-Eq)j+F|xH{ZTA+nM>$?*V+y%Y0b!>oskzRk#*Yr=yixXO+t{B-U28O0p@0?4ipko!s5yNzVce zXH)clFMQ}v7TA^P#NNQ(ZN^3%e>J+4|>XJDyt#qzMYS~Ka*(%5g zE97ymT7S#kRjcS`DQWyDr>LF*>2-5 zVnr}0&fL`tJ!Pj1#pa~81af;nyE}L#2fNv-(?X_#+k%wU_Nmx1iFHSk82HSVszpf6 zj#|Enx2xv0H~l=Q4$f0ZE$47>Z%S9y>ipx4+!B}h?3XKz#@HmRmzCN|iq;2Pe{1YS zH@-oR*yJzQT5?@&VCWqQ&P~}{+;Qa=ZHsU>?3hI^z~?Q?%2veKZ#a!JH?8R4PO+{i zs}}Ea#jdne>u12X=cVIKU>Ddk>lWH(vCBd^Tk4%M+oCW5{!-hr(-!d((K_K+#abFJ zsEv~qCJveY&z;thjak6EUwuArQIE7!jw*a8qqk^aYccP?q*^FeA_Z#KMd;uQ>vaJf<81MWPl) zsg7d`>2rs}E%7PXRX@ZG-l5(nN;NZrR*ia1g53tR(_w)>bK}8+>66ROvaT)lA2mg! z{Mu!Sz+asZg5%uu!y4CJ8TLbG<)1pvvm3pI@Kd;G_q@K(_S?a?a^cr}uB(+S`ESWG9pFQwiVc)1VwcqsDyRkSI1!zvm~!Xlq38j-Dda|&@sgBXm# zEkMWwsHkhA%A2D6-7+ATE(F`0zIYwK{GX!8SS4wZE}W3|C0zo8{75pft{GBuq|#=? zAyW^9-MNvw*IXse^TjCe;=j$1?)h6}5ziMN`Dm=znHBeQ`INw zId=aj0^YZl>%)M$2mq%2=s>1=Frz(sv?#Y)U$W^juY4`;wVh)92S!3mdSvtOG$AFS z4Eb6~d{iwQ!n1dCnd< ze)vs|@s~GZ+lzV)s|w#kS{oH9ltE{-_!i-y?LF_wnySm&&oA-B_V&nwJG#-GGFwa$S?hK`lZh| z>Sk5{9K4Zi+&6rSw6D}R91Fl(68~~RBClG9!~WNEkWQ&lH~d>qWIFh4Azb-2h`5LQ zD^k;uv}9C$B{d&O&AXq1IS#eiLeU^~TpL1fF|TfhMvDHuuXg}1uCdz!%vf%ngQ>Ri zr7UyO6AXw@u2!)cA%0@pB1-^wawsB03E|$Hl(c@HUM3(m=p)vbu`?)4FQ{`B33Yl) zD3vf~YfF>Cb+iFmHE*(Zy;~|Taa4^h2=G*(rd!w6z9u*Z4>VXGIJI<;IYSa=L34av zYz8!#fZ6f}eW0}$OHX&iSziBRo|3>fOzAgH>31a9rT)<4yTO~iMfDf0%r`FFrk|EY zyG28R;^6!_&rtppY*H;7%>~nT^Um!&+~fD^?UEgF%q|1dnJsY=-(dG#Oz&e1VyZ$r z6o3X`U58rlhK`K76orWbDN;w@r2Bl(IVWgHSctxmAq_9ZqREe;uzQ5d>GgRV6y6?{ zhfmf1T}|NFPeGsS7Q$e8561%pg$D?Z=jks@oF*KPTUkHx?Ke9|^uQ78J%z!M@;HXj zXN(b+O?0v0C~KKw4+M~V{R=I*}R!C5wDF* zA^F00He-exrt+DqF;$PHOc8JTa|L5mFB=sq$0jNV8l}Uu6yO*$9ETW{L$u<4dNNR~ zFBHx@3da+r!dRhNn2hdm^DhCq^$0Ck{&k8e#8TbCWD~E#!DF<9wG`3Rw!X`4q z2_95*AYQ-#Y0x3Q@L?@JP|Vr0KoQn_H~^M3Knz8`BDlpeFcxe8SgnB=atwQ>Wu_zA z46_zs99t#(re#M%Hdi$2EiU!B;GxZ?S+;Oo(KqIykJmtZfF3Jd;Wryy=`-UWV`J89 z)>?&miFqDyELE2j;26wiJwfBJahLoCS;0d;aIC{~JJ6Uq6qa74`4=g{L+XDP_*Ca# z6a=d62SnonPn zw6}=;`)4dfCCCdZIbbaZ3t+8V_Q1Re5RRm5KoBKlea^R^!^_9o3vKMi!}8X;BeL@RikI+l*2!2 zX4^H>?b;cRZA^!DrlaPnvES*FcfwS1<{XZ1S-FQU%Zz7JyrbvwW<*|<9s#H;za4U0_G&gHhD)vg6I_~9PVg-lTA+h!-T)m2C zFFyrn)JlG}0m%U1spO37_;^}a`rod@y*mhIuk+ufs&7`zuV+GI z;&?~!_&aKXLpg#&K>}ms_y)}Jbs!U$1rKLxS?0C{o`*GoF}F%)`~tTJ#m;q~Xtk_3 zVhtWa?HO`J8a%;zk4(4Bxq0dn`?J33y+!ZzXY&Wrx31Slp;1jr%&!!xp+91y%2Y#p zmGO>wleb+74eEr(bwZf? zKdQs~I;6@!s&voW|0P_t2G{Lczh-N9zveE5M|9w9`Z#f}zNfb0v%{NF`LBP*k1vR4AdF!2C9e*3Rr*y2_sJirVEJ$zM!+!YFl6@2&G0aS}az zh>OBE78SdOH$Ss#Y{h%Psp5+=M>JD#3V+s$Gu|nNKEUd~Q^C^r1bf~si%Bg?O&4vX zi#SsS&GY%KJkMmJZCiaVl=C=`P=QAl6fPK91gSQq2`iKFZ?#wgN*8jJQurb%Ra+@k zTf>cU{&B$lIUE*Kv09-8F{ppy*BLQ<-HY@-)ZBBYbNxlNi67oiRnjUXrp`DXBhZyS|koahk5ra%zf z^NYBu8bPn{3!Hbyoqd&}CnJD%w^4lH{{z0E@sq=LMhXB>toZNq%KkHOOzVG?S0?Lf z^86i>dVSqKK*3i0RP?PA7j}q-l~$5wBU?dbV4bU| zrDw%Nl6S3b4gR&!K!R^$vdyhm{{kBm8;>MoRx+`E-X}76f&a6K#}3^x6r8BMP;6+} zs^or>qnlAa1q7arhx6FbmFy*#zM?S1Qs3#utQd#g`DOzB-yxq7GD00&|8sKBq0ZNp zaeeZ6 z?nKBQVPNpt^PXG#1T+ZM3m_0kW8gTWP?E!}+n^q_?QXoGcp1De4sMn-lBGg=D(f&9 zx?^3bSjWt1qW;Ceyl8EWmV{sLr82P0GIh}uM@?DK*OHM$wd}ZH`@g&;noz=xvT^402T zJ#d^@c$(#q@S_`%fkYGb2g-Jb?_je~4j8m>bJZs#Cw<5k~(~d zvcGPgRlmCqHsW0T^ds>gdtG9solYC3Q;Of$HQ)gYh+D|m$AAg~YV&jRh4e^U=zPK1 zc7HfA;1G%Y8Ts!&)r|4qHe%WT(GT%oaAQdR4N+U8Vk^I-fZ}(<##WvZlSYwGKy<;D z9Jo&n9r2r%nPLC^3;Zj02Hunl+g488AcZ$V_l;sE|u9CPj(Ezp=~q4oT_qioLe zEqiI{;qY|r4}h8C#jjseU~<2uz|>($64(_46zP?{yk`jdU3+BA4NMu5255x2s;3N` zLJe(q)LEncICas{Y`N?1LDQs#{pF1E-uA>C@2{M^wk-%om%@|UYf24C^ftMPkSfP= zTURjpMIpVI^qXiX$VVnSL^gCeQ6Cj%!}UBu9M)aByv%2cQ2x8q-q}2fy5gDET&ipY z0IccCQ;3$62Li-%@=hW%yF`SU6_F2pl6=*Nu=gJEGPF#Y^iVQrzBc@b8D`$v?FFw5 z=VqmPToRBMRr8@e*382jMKSZOsacgW`y!H92T3)OGDwsQ6U-mEv7v?dDt@~zmg~Ea zj!zRtY{Z^IyIN|8Ncaa7sD-QQH`0X5AFp>^0CDNJG7LMN!4ac}tU1kGJzO|3EW16q z-x|T)Zhere*Qmk37-)zrj8WRhRBC5B-h!TMc=a;L?4k_bIvsJy#WSejo8Gd1n>IBS zA{#9XZ-m8X(2;$EjkRFe**Koi7FX>_at0E8uuNWmz=!nnFI~VtxOgH3fCW;H{JRoHLs| znJlL?$1fF2ppo}!reIx#+Kpu}`uHZP9-7urEvl&M1#{<`Busi`g`{A=Aa;P49DN9`C#W!rr$;W+F(w9efig5UNXh!{{{`08K>|ZUcAJOaZ6PwI`Vw1`H zw(7rPQ(g?H5TLFiuVP5Hl$GuqoK5#Xxp#p`Rzv@YO^E+(Y*POp#isv*SHZuY4Ko_r z4%o-2UutbB!&0$9qBJrP&7;+(0%|a&4MCJK2Py**xYTaO+tRCxTDuyHm5Y-clF+t} z*ix3i1RM#91%PCw3xcDro6lM7ubY>ieueGQPd~C8+>)#&{Oh!H|aI+ z^C3Qa-*NivM$zvB()*+%-HFm$-I1>4*r#>#*~B0?jz_ts-yaD2Y(!b#Aw<>Hd!&!3 zi~7WjiEHpo9x$SXY4Xq=K+H=ju(QNWa zJkfe3>R5XIYK#5|w9s%T75MliBw&og66 zv1ThqH?-C#sxH1mYY}EIi;1svXR@-44mW5MDsEqZpeizs-?sZe zc8H%t%EogQjK=sd8lpT{nY(aob_*#y9z8AeiBU^eS_*Fv8*EJqVguQTQB$fgY%!<~ z*`0Ahu@+*7<`R;fy^^S}WGUZEiLr)!pOK z3PP{@aAxQ}PP$Qu>1FApq^Jt&UrnNQc&C8avV@GTsulj(FX?{$(_(!WYn)}H3xTTH zqp%P{fvrs~)T*ktt>x*6t^Z-mn&`=ISJ*lM5fwwTSq|aYlP+JrgN3gX^QR$S`-u`c zGC1cfr5+L&iA&SwXERgO)*T_F?wQ#g&fR?=XVvL!eZ6buC{&j#Z?59v`TaTBfhXjc zqtGxkPw#m89*V=e6N77!JiSHtJrhn>UiVqDSF(>(jl{V&Qg2Kei4VBDv`5AW^-FEA zdV_HPDypYY_9-P=oumh@eZ7bBAk1#QpV0{9CdO}xrYfMGgo4u_;z3M-JoI|Y!Thp0 z)5wq|X%^IT>{XGlfWY^$&Cco5#s!Br9r)wNkfmtB96xSl!R7RYg%^jN+ucHWK&Kd8(y;9=-M~G zO@O3jOud&tqm)^iUD~xN=g9*Y#jL4HE54l-Hn*{qySA-a16qpRPE}j#3gJz*bkALy z8?jx+XNE}SAGU(MBstA|Wfj)&u-RDMOVin!buu$&#nmg1^*V}-y1D~TV|69T(l+jE z2N}Cm&}IMffB4Inbpre8lc?@=!yR}9&jW$m4bHTK8n!#IvK7YkF4>pJ+hN-cY4LqZ z>QCkT;&e+L{c-4pbAC*cN53J#|57bLw-W;ODFEw$Gs5L@Za-i}zNdRIhr*tKAu+i_ zT&xYsAvcCDJb_2zV=gza!dVTi`S1pfX)*aNu%kxsTP!>nOeXAvfR#fo{|3fK_}=mb zw@lGEZz!{=AQaO}{8K!(-~`5M#@kuLn~h|yAFXmI<=!KR*wexX?1>9R$bOJd?@y(B zacP{<5N7qyHgFR5B{|}O)jZQfOAz)B;lFUJ$bWB!VQ>n((Dh3$b}BGA&{MYsQGxIZ zDtW-*;goao`oVZ2uo+??a)r2K7Z36V0AhbHd7y#c;@}NGup9jPqFlxfTdMK zmh1z0)fZjaP;+nT)j0Y2LYiZ@WvmW0fl?H)nq-}h^CNI)mn@jtqXQG^sxLTJr#NiyfY3Jr{DO;k@hnoxk6`!} zj(*2xc4sd13hfuscOd`5y<6b@J-|N`=9oR772)73g2!GvOyHJ4wx|RDhA0lJc&c0) zbIzq-y2WFP$c}%+qqtnS#pCH8eReY1S0BbgZuku>T--r17Diz%MrQ;yWY!$i4v$~f zg*WL1lt+LY5N!w3uXt1JyG9J5*WK<-M(A zu&P?~c)CYrD_HWbM}ltDimAb_dJt(VdFote4QMUTTs=622sDz-}Q5m%PxI1!d z);sHo5r#94xM#TPtlAGX&25(E{7NI&*-g^?{XY9IX%6}|fi(B2MOgD}hOWu6ei&~7 z8s}MhkirZkG=Yg-Bp!7C@;xb=w*p1O2Jn!{1JJw8u&!8E{xfK^;TGZ0n>AHT%<3)w zKgNp0zbgL{KmY*LqyK+7R{W2n!~c3NfENmg@gKHSZB!6=!iX?Nmegv2Ar!5~(^e+z z2{tI*5#|lI0C-ZuG$0O zsoX!dRLa&&35|QOpxAP=8MDKKXUJVT^(u?n?3`HtvZXpGG@M5EPw6 zAmf7M^v+{KAu!z9dx(In@;CB5MBeNOl32GHvFU-YV+AS*?k*RiC`yzs57iU8hWtk@ zPQp-2{QqT3#q_Vi-iZ2)J+>&ycg*!)vf0*G3tR@e&}gY(Ze8{i=Gx$JY|hdQc_a^jOAJ`0W} z2OtCS{TTu!33=>}*F#W}8Vx8fGu1(H)f$arqMJxJRG75lYgb`n(PoDYZAi8}F1(;s z)jm<2p+S);!k{gGa`IPUUH-T()Qg_Q_R?%|SvkS1-6%~dpT#r1-JJ4bT%Tg-g3hh( zZ62nzTNe>sDuUdZx5cX~#G)U)1WQlN$43?(#oUFv2L6XD701wi21`?R0c#2NhfziS zcnzm3qr8Op5Yih9@>LY|QV}MRP3yhuY$%;_|GSl8m4XCjRPXv!{VMvJrPd9?O zL6u7RlWdLEM`}LhWV)$`HGON0a}?$eN)Qp&C+xc%YLw?+BkTwu99R-Bw41 z=Od_GT`+0ipF%B%`fWftC;a5Vp%J?62AP`^KDnpMADYzaR0wOW=ooaY+fXpz7v>5S zyBjltdz^>YzkRM|{aj482@@2=pK9@hm1DOosi$beVw}R{SH>w^xc@E+&Rvax5~*3% zfod(*d&*VQb7!#k49{aqg(}0xGNPEX1OV}+-xGJmCwrv}g zth8+U=K-RZvb<3yZ@bAImFd+oK>vzLfj{wt2k{ytYT z!Kt;EP&8!J+!Ew<_E9e)5hb4x^=P)buMl`DH~~D<*CpH?_G@BJOZOMlP<N#zf@o+aMc&x;Q{#_7 z8Es(G6>qs181ro%LDLE1l_q1%>*gS$Pn0dqaqt3u&*KJ&SxRu1e9nce?GBHw2@>L$5OvyrM&)Atkgep{r_5!g1oh^tsUThM~wVCMK@+S_Zx{Tj-6IN_V>%S zYW7d-SOiv}8vIgk7C{jov7Zh-mb(&hCFwQ*js%q(;p%OC6!&kq0nK|tifR77@yoUh zc7M`O8J8X>tG0MNfr|AB!GHo0t&3wq(W-e) z+dbhsz4qF?_jD`ge0l#rWBQOEx&0aJTW!6xfAR^&3ePG_y+(uPIHO-x5?zrCnu!qS zNd^{jxi#P5_|+UZ0rPhfCpa@=*$Z4nI&t#RG`T0axp79jasxqkpo7q<&<-Is5bI3Vw6q176oeZA+VLdif;oQ@0vcuEpsLB()!X5mx8{A|5+SiTD zA(zB|O_fu~C0m*{djBRM?U3n7+pAe*7YuN!395X~3bu_F#z5 z9@@yLGSQIVavX?AJCkDi3oQMwUk}!ZW!In7FMJrx)}RAyUH1FlA@?=E0wE7Z&C`zE)^`S5UPLVerN` zrX-#{_s1j@xiuVgDzlI|IRKYtKyB!pTh`SPW-`847mh*WK-~`=BBgQ8*a6EhSWgF7WWv93IYChUl7BHFz4(NgTeeAwAW`*vocaW zGKN$97PNcQ{FJ{Rb8IjDsgbZ##VMmzWO{Erbj~%#ZOQ>u=}0lL1plzRRB;H4YY`{{ z!hJTA)FkdfYL9h^$B(%y`-;8^+?a$mb!!J`f|usCIe5&PnmY=())s6^CO?WUEvtJ` zO6KhfwfhxI#{}aEsasUJTI5i?Mf3Yuvl!iy?bc~CuUUvEQIpI>pImDTs^{NWUBIsn zEzqx0wEb$M|IX_EV+;N7$)*3X6pj9>Jlg+Vhax6M#xk}5eG|K{GL>`qO2*RtOLTJi zJIHKMHnT=tLjJh85ThKS99!%&v@td*?q)&r`OXjE2X6$IdZ(~W{|#hFOnrl4QgGr! z4;Kq30v1Iy!BH>6m)a_chzGN5!ccG*(>PaXGAC8^zJQxz@@fAP^l@6Bb682WmXe)6 zXX16VZg;`;$k}Ok*;1zM{6(QCvmZw2@sR!%WeWHPo5z*8#1GYzGsoL~?wh=qI z=o;lgGC#tFOqSc1PELM{$KbCd>Vo<=>*Ao{J3dOkWL!zc`Ek`P10wdj{;Mv8Pv>GUNQn zb1b=X(yq%p2SlJAjmSr_DlDjp?kCi!vL+*C`)^Oj_DA_E@T61tv<}tL66c+m<6-ln zSz~iNCx&BZLXY5fn3x#i(bYsvgoA{@qKrioZ%W4RrX|W!!VPE0eh_jk0z~O|jWY#X z;t8b4N(*w+4_fKP!);=Mk)-YBR~%y}Jk=O>UqzVEC?p~GJ2&1<_=2m;#|`c~gj%C1 zCFeKgD>EO)>q9w95d+iX!f_&~+Snfl?x2R)N&O6r`bCn}I-?8lE?%a*O)2*p$L~Nw zjfT7&pjb?Pc}Oj+jjlNf&IXuEY<=nApgiYKRELfR;pEFvf)FS0yZO956)OGPT`8y( zqKwMy+1s~Zauumc6e{DtYzA(aArh@07Nv)zdU$`fl3@v-3a?-|) z4<}q2J&u_|v@@^jb^Alh(rLvolTzSTl`re%_xiHgRVB6QHQNjyLmypL=b4gCc3qMy zkX4qN5^gprKQ*Glj|L96NLOKe02dq)4Q-LyqB@D>I5+o>SAi~c zO;A;13b$dEZ%Vw|h+IQ=&s-BI$`Uk^1@JT~TIWwxdrDlze3dJdIs|h_&g4Bz6=jQw zd+3+E8J2zvqW|z*;4$m2Y9+(gUM`@BkKifCvZ=eqoIpy-D`toSDKHqCh^tiC(2ZJ_ zLoQ~Y;M~`yL9bNWh?60u`y{j^m30ECWr7KL7(Yu=bN`O(<5&-tY6WBL2}!Ii3WYSV za*wf4@nST0H$KrK2ffa8sMerVL4Kf7=1La4T74KCWy|&3C7a(tau;QR-{1+V9SMI& z%-gwll#P=}E(44dc1Hmu?Kr?EW9<+MGyKnm4RqfI`-NkZM3reQ?298) z?wXl}M+_~NSCFc&F~xmW6^#6~_ed0XlN#r#mOamiIx{e&NgI4DO}~4n_<5S5!khPh zyXeL(w>BtAQU-?Z3jj*Nm0-Ua6 zwN2!(Ab*B|quCI7v@a?t7ocT_DzFR z;&$k&@`=imxYPf!KkTW&8Tm5oa=U4_?TO23@C-q5hl=FL1S~f;+C5~|9uBAXR@8Ky zR{_3MxP*XL0kP8UChkZtAbs`(CZmajIJDlgNYgVcUnq}`$_1QCc!FgiGH{Aum zN*R7UkirI@>5BT@&al%H*s&Li2i&Gt#zT#~a}Z8A9@kIw9q4k>NgrS9@0h`MdJ@jS z+C-B9{JmrLa=yjgx;ujFLg~E{j=*Wbc6C^QbNJ ziGY-7t7<9^uvf9M+BhEbg2Sk04r5vmK=9rZ!p67nX8pHE_)-F8PY!noq`G-eSR3JV z8*!eed)_fq6^qoN(^bRJ+frs&Z>)cDaQ;`(oylKJCIZ}l#7F<=$r1e@L-oJoBR*X_ z!2bbP1SXVKET!8jX3peI@x<6%gR$C~^mgR{|?^SuI&) zPL{%~*jGy?pYkW4cFi1+)NHD)CZD9APPB6}-B`i#Wzr_?8Co9K-8wxF*X^b@cs`#U zAiGW6&-&mchJ#Sa~PTaNNiN!CWYTYOHNU(xC91< zteu2nP%OK$ASv7RK{+tG4$7SS7SKyv?nknXm75yy(f2Jfq%w2rs-;Ay%FBzZkpXCE z(}cL|%U8wyA{XOJ)d_D$_US&OW}|W{Fa-Ols0>HccYnErjSFK*Z^Ca(pUZ+YbvY&S zwwf0*+xJyOWjwX*lLn3M(aFt6y}U=kO>$5c90$f(0ccXoIp9s(WVXBljwA3N(+2Gyo4k zY!Jnz6Zk`7B^e@bphGWaA8J;B4w6}cg$C4+MdoMqCM7m@O%=WMu?j>*$%-W3Cq9zf z&yZfZzz3|QDp@2BUP-Lmej&9)pt=)qIv=M}sbdyd6&P<)Zk(9GB<^&eX0d6;AurU? zlOWE3m0s0sH;IhjXqKRIQEq5m0tS8Su2R6e>y2(pIFhpwnm2{JPF;H2-k_kF{=G7Ln@x(2$)YJMzrbYP7s-CN*w+#ZfaXTPUZIeX<8Lyx zoS0c#XC`l`)pUEh|8+PK8SoB~2?Kgjz_VAF>bCHyuZLO#UZOTv6uv zWV%9Iwhq|h2BpDflhLtD{L>5n(Q$O`^XdZQPm|YYWKc8>?mbN)&gaF=#YWlg#{4g` zBDdfrV;$V*uoI=s^7^O8_^bTdLf*%cNFpO9Q)!bKcrzQ3YnQhgv@FcByrRJ*6l}{x zQVq^^_>#0vlgR1EILL`NZr>fjnv+}yr-2tV4>o$w1QSkC4oGW6VEdme-9Ty96Bga? zkogv~w}dqtM>*HuCh!zPl%S6W$koUr+286xfH)j|nHcYKvhJGex*!oE*L^&Rn5I zoEj69s>*<}PTypQKcYR%IQzK6?BET8JrnaWM}8Ne4@T<^4nqSXqW4C52@>#U4V$q( zA$}n$2+E>L$FCF@SQeCveA7|oCS&L;&>|^OHa;j=5#LIZ+MPmp)cA$?X#6LY3n@_n z+tJQ@Xrncf1^&~o^E`NU8~!8pXj|>L?12nr#8ORQ=0Jr?|B_tKieSWt;ejO;n>=!P z2O0%loJh0REmLV8E6lm80C@=#RB#g30$6Ym*1{twQW7h(Y;*HB2ajw?y)-;XhTmFc zp`k1!NrpsZ^|Cz+Fno|7okk=f)pQ-i-420k5UWVL>0MuJ|Lbd}&GXag?|D(J^!_*# zFN*DN8DMPR`~B4OGP*|i5pX##>Nb_E4j+#!lhitTlrB>o+UYhfOzt0$kEPqsg1kO= znOA5U+#Kh1yx+cO$q{=73b{+oc=D=T%n)}-ztNUxbrLW=!uKo@yp;JDg-zOrPfm`- zgdFj{C|^??1Y-bA=;mq|oD$H)rKeG4l0xnwNs=BAip3Xcltf1K)J9MOFqMY`;}XgM z6oF=Xp67p4yyiXM2Wo)7eT#wqk8|Q5_h^ZKaZZQ;Y%NUe|Ep19W{#!&wK<=aFKs4a zyA5?bShjoq;GG%;gv`Bj0v1mk$tABnl-;oRP~f_)k1(GMNzO%4SHP_@ z>)UJKhM;~LN9~J&GhcvdT3=@H8y$@z zV+U^ibW;M7{KOfI3aZKHoStBKc?%}o`My9Jb3+Kd=7-F~AOarl!Dc~2cY}{4q4Npq zDr(vJu}p?Zq)n1qJH{DS^tpm=-XL#^CXr>paUTV zi!5mATQ5G&o1K~Z<>sga^M3)gtVcL{pSm>rx?L$4qgm0KfvIYn_>2J45g|HQBdB?$ zeX%5|v0x6biB)QW6;4xs%LC;DMhtB!w$?Np5zo;$y!HgPAg|F@9AbmIzQIAu?>^Ns zTLDs)*ZzY`)bt1~*sDDZ*Rf))j*_KbQ|jy8_3k4p@YtJlI-3k3I_}e!joXp!q^jK7Jo6 zy_JZE$%Hv%j$k9QLUT3#63ezDdSQY26&5Ak8Nbw4l`b6{@ zgZh-1Y}**iIT)pp{oc7Sjd@8QU+4uPnDy=V>K7_a{$Vsj>D4!ch8@yyK)gD#S_p##H;cHSc;wZGn1i>8_4BNV%%pUO2JKvFhin z>CwCk?pd5fKPb&Ku4jIJH(C_v&c477~RZm|};>Ei@mXtXiT@4>qC!g1shX zIKQ{-$VhvynS9HWN9%Cb=@H|Erj+Y59ct&8VM`98gPnUWf z8@wl#3umeqb4eYpr1U6_Mi5(m-S)&L%R%|h;)p1ya=F#hk7HlW=avlqt4@mkOg>$e z_{Zx=HfY#x8{6-FeFqHe2i}SV?7Synm6krV!pR|52R1FBa<#C%0$J$V2>haHUNtZ% zW6+chytWIPbE$__FySpN3%EQ1_KU?Ao8aMyKDGD+7(44phRqIvd$t^lJ~oSvGihcv z;5@J1<84vyQ{&M0(uZTOzo{bu=e$faU&@FS z`W#a02AmTi8U9pfv-xmP@u@J9v_vL&OeU?8Cg4pBHAR#CkrwWvtDu$y1ir{olr}R2 z{b2QKGDwG1V0gAskbELit)hwgPFbtY1ilH^VH?r zX>Zmi$TrA2GCwN}M)N|q3X}!f60F`HZ6F+p-cc_;t|Z2C#pnB;csa{@A+Gb`?6IQ+ zdUId5t`GM~LdT#d@7nYgxDSigNSkkey|QBzQxfX>s*O>OfY_rw@nO6a8}k&86+**c zt}?2Gq_Sy1xV(dHm?ep_s#azEX$qjIrkQdtK4W&JRe8$!AW*&d7j%`}BvQIzM`ns6 zq~$MdyC`Pyi~Kk<1yiF(h}9Bp3l^YKouTRZt4B;LmUg*6#d{0Is21f)Qq&oxnXSBd z^1fFjmSsxVawI_Yzw42*v0|jPucXHW@U_FOdxAPOXxRR|5u#FSlQZJ9q-kevQM71% zK*f+AQGq6;a(UGEGO0#Snoek5Q%t-N`?^fs#n$Z_h)K0XrxY`(at)R%v#t!5o+6`o zho(vTEtvTgx3;n_?66n$jY4T~h!m(q)kx~I|VHAEjo*d4OY21}4VQhQGY%Z|-*dy-9R zJAb<|tArPLkB7hH=WFLusN3-_BjRSQdL`n7v%`&TnD*mOOv3?k=8cs(ATwh<=d#UJ zdV6#SN8OPL<_FKDU7lxw9*d_QN%}JkJ2(N6lsnV=K)hc}Z<^Gdv+mo6{`$HS zT`_686hy4zijGV_(z|Kdl3M+a5q+PMCKh(d`!t(_oH~JAe(6{pmV);4-dRUjf&I=& zY70b~#WGS@RD$n8RzR0Bqunj-!egp>N4B`N$f)8=Tk{t6fA6ED`)FpYIGDn>g_-ff zV~Hbq4enacE$AySZ>BC&Z$Pv`LX=G5T}|0E(jYj93L_*o9oa!dd-Ej`iw=s`$)|%WC_R+X8Qm z)avP%cc&IjG-_jk&sW%Q$PtHw2C~G#hFLOgG+!;pxJbo1bXGm5SdK!meA$CA@dC7D z;@(uigIi49Rcp)$RH*zrpwjXNgvHscwVtLtzi+|F#;td;!Ms0|4jv$gaVkcu7K7*b zb#>5G^9}Dj?hLG>G&pox-Mk;d$r1yqEII0J5bb#34dftr{;t#TdQNx297^-$pv)xMvZgZOVKan6}td9-^l?SXyH*mF;;4U>Cd zAN(nwJ80b9HtxgExA0QC^6LS#bhI|>)ZpucBo_(X>$GmxVnWy6SoZ~*$%PqY=yQc7 z@L^8rrIST1yTfrrNGV@vYYrUN8~BJa^E><`-|Ppgi=2B^5WI)x8H-hy)y*Kv zy;o{^g11ha+kofn&o+9};|k&X89E1=fUo*8zNc`+&D!tRW!?|ZZOXq0Ju)kT-o39y ztp@x*PM3cq^kn|UMeQF1_x~hwRw!Hi#p`)miqsk)LK4UjP{@%HmDCQHCZHGxz-dYN zAPA7vw^Ah;nAN7OY}7M&It*Tu9!X%Ihwm-16BZCMV)MMBzL9#$Ol|l_Um*}eGk%eJ zNgk6flO7i<2T@&KZZJA%Cg@dqQoX_qoXL=Q;ragR4DJIx?f$^%69YZD{%Z{P;takb z;AX15Lkw#DI>1@OY*C8fh`HLgTLRb8z1Z|MG`jq~nt^|)r0w*_cA?}&=fo&YwH6pO zX2vxpnaqic*i$G&O^a8s)titvtescous4|E>(#0)0DKM4a`&2r3dgy4}o(P z8ESUP1*-qrz<2zR-I&g>2`m(`59r}Av79j%mt%c$$8Q>`03`SVjKxz^Q#EC&HN(Z@ zv`F*Tphg%4IjC1xX6sF`NxVoHFfD!(@MbV-z(B5rkysSTtWfo77_i`2#e@DbAm-fiHZvR$IysqEup=4T;p%KZEScx6=Tg*;4ot>X$7VdcoqGtO@ z6(GByIkYwaipE|xP!q=kH=Gf8^dvWMKpq+^K(!+uScTd9WB}?=pli?7iG#{Yv8__7 zYn7%HdBGo141=g5@0Z|W$iBfe#9|X^%s4=y8L&t>O@b-Y&e!bgBuKymxr0IW3QaA6ps=IE_!C+k-&%&b z{c1}N?%G^F#Bv=nAm{$dmezdp5Ci;Uu;l42TZi(tFb<(V{cJMVrq?uab?sHG8slPLE)^T~10^3g2X6>fLWt_j|N_^pi2$KtwOYY)KB+`<^ zbs!WPQ;y_13thVuA?#+hjr72iB*vps1#6t-QpT!h>I&XZq4(eB zuvCq(Q>!?sjyuG2!i8R_2q_Z=AddK-yLuY=jnG=AZpG&Xmt)+a2LvF-Bnkq3cm(tE zE4=ml2^Gz3o%_y(Pn-@l4=Q{GGY%RlBO5DlVHJ9fTnC>glnU^Ex4ZKb zR5wa^Ld{JhHYcEq_%KYny$h;6$3*LZdzL_rstlRon_Y$#Ej7$SZP@Fp^kIJXfFUtS zoQ35g`dCwj(RR2zt7}DOj7% zlJ4t0E;&+-vS7Q0a)O!%?)xOoHGWwy8M$jPmplUX(N*nwj9gFV2PBKGy#zCEhSh+b zD44>v8Qn+`Kh0Pc1mjkWGq6C9Dcn5TGejj}>t^wncFJt(fOqU3XnK_wieb->!zqt+ zZOGT&4=#J`K_2gK4O?=r*c;x$`2&~aQ9RSn@4>R1LcV82p0>}_Gm@u8SP=+i*}*XS zXih1WyC4}Lb`@y`%MGPU`l~C973aXQ)jdgY1J!qTLSAMN4kKT7DqL zcGhwJljrTQ&(=-nBLOmzUbpmX)vdzgVP&?e>-~<=+a`W)Scf12(^-)>t2)jke?SU@ zb>L171VjtfSgfbs7acsrWXY~i6R9?ub-wK?bpS=`MRFdLs~s z7MJK^Pz=GNLXmqo^9S)m@j5K0llng9DkSw30&*G#fV==CsG6hve6cyX(yn0$-nJQw zIFcGXt_X1l8@M7>vyqFmyq0&J*e=PxyusjFbHEBXv12=Q7aDu%+Y(OdS|J4T283l< zvtJvK3vUmo~zL;~o<>5q_t|qT23X_C}N# z9ijkK{12Pm5MG3HADTOB#a(uxGNi#uPQSbOYRHcCx%zHqqU=4WnSn;kS~koXvf-R4 z1)zIG2VHMAUN;yuqH8Qd|9;SVUrJ>(j^9hP!85~5Q*d4w2e(D*P$Nc!Ek2IJF&Z$3 z*PJGxAqyf(XHf9qswodxTEVehzujXF6a1U)yW?M4y0r09(c`;>8{s&-85VB|W9d0v zInk;n9?)!~VuB?}UgP**RjBVsVWS!3Vid#2lM_SJBP??>Sk4w0)S4E}xMmR|V-^gk z&Cq{Q7mY+FI)wWtGVV{s&BAu^pog<|4vOfC&=EHn2rK&+peHs$Dau2Cc}s8;K01yh zZiDq>99o8KHxFCJI9Ct?Yr^Tvb%4r}d(-Yp;ka~Sma0RXws$mt-mMJ0KKZw4Z}Ync zL|s9%Tw$LTH@>EmT8C*QMH7rkhQk4d9gu0^9pY@zXc6yYb8wSFY7H)VGs%RrAcSOp z$DSSLEfX;_#Av6A+3pt!iDkU587(S1liIk8Cjd#a2h*--0dIZ+yAP7I^*8Ifhbjjn z++jtX*u2C3h2N5*^kuGpeEU}LPoE+GtAgx*-DeavmA`=71|naeM6YmPP)WsCfLq*e zjsXG-jNj4UBB8&hq3oBP(@FHj)A=!iQ%iR~ooQQBYrpKOX|~os)u7z3Xz$U=Jbuv$ zf;m))u#cH`m+N+u+^-iY&*xEDkKduTb9`Y84A$k~_*g=9!^zMFKp_U{Xb9m2Ik*+* zd~9|OkRvp)*K{RX%`aNq`fbjf;}qq);B&qsaropazjiSx3Ec zPf25lC2Y}1ag4q~$m{#@ykuSJY40YRmIb5z5ZBc5y_->o!`RqLCSdWV9(yzRG*aIM z5zzNYtyP(eN^&6)iF)75RPYR;h^ra|At#M7n#!qf34%V1+$CN_(^em^Mj&pu;^4nI zukdjNfLke0?kZ(=kzUEvE;(*7PN}S;(Y<22M1(&_J1Bi}E^SeOL49tx*aqeC_m3v& z`1)AiZa#`dF=STuRP3? zO}z05G}Eov32oXw_$)b`Ud6bDr{|pIhMqf|o7I(!iN+f%O*?P8L-pkxmDY&^lFo+Q z(eS48zr_MN#0-aHQ#RqR&j1n%Z!pkfX z>kT2v^ALR|t!LI{M5h7hnKBp}s>M~9lA}`sdPkJr!-DV5rjkx>K^&At(W-|R5Gbh; zKOx{N5PCdfpT9L-Me`W^katfELceSDC7Zh2(bOQh?&z zuFdMN4FbUg*3bofbfn1dwZNI3HVaA9(R)9hY-r~pYb>~a6#B3uoLPbxo0R_$t5fIgf%fOeAN6leyBR+l_4x+)Z8*b)5uA~N z5R3a_*erWyhD!?(QsoU|I57YLt%!f;^M2HB3{5AtuH zL?_L$OPg@KY9L_K$~Gf+XL~;0obBg=aC-e@d8NU-QNR>51As7nHGy8EF9r4tProfk z@g`#WVO?UR_$Tilt?##rwTFjLan_z$zWM6p(rO=9HSkdy^ZEP8{p=P?Fl|Uo^#^Wl zx6cp!5V>4hGji3PI&F*5`{=AB*m5i=oO9MN=$+Jyih4}xwdCge7!eaeiQR@3zKXT$ zxmNF^mKf#D5UK8CF+;7Ab-S1({DpV1<`N*8^5DwR>Z5o0=4^^RnQMEB>oU_3EtE5e z9(IMygkV0Qh~fTV-qu;ewpbWpn}TjfM)?&Pp~$w2sMMrPPp8WO_3{D@p=VoKF`QBQG*mqmgG0s)q;uLfMsx5>MdiCh9%p)tT5paKz0X9|R2 zSI-DmfllKqmU2IB!oDz@eHbpJH(vHsm{2D;YxP`lw_&rM%*?bN$wR*ErMOleMm`MX zvZHdeW_UCn1_S**T;{CQ2b4K?rF^z@ z#rj?7+6nrz`xZkBZdJ%0x9@!hq63S?ZUpF%@pRIhlA;}wk9yN zZH5!pmuY*$vqY|O-8#U(Qc)y(m$xtDGL1Ps)SgNOUxyh73d63p1&pQ47+JZx%mTIT zG*c0*)W0zc?4)BtIx9>|F#7`Xn|w`Xp>b6#25-eb^`FuJbc%uz0Es zR8xG+NNqB?qO%orU6Hxo8ij_VulWy)rBa1? zYDc~D-R!BD(z3@2B3^M`QU~fiRL8dJ(8eku+;HO{s0^vY)hMm7!JwN)_16=O zYk?c{Wg=%Z_A>**8fzwd<}kb3!?W5S&v@1ra;v%4{MnH*83R{yjdje>E6nnpJl18+C4H+0-3i{EHF}x6tqX)iY#;iv_o}0upDVcub zw6r_ly~Vw6OMyhCeCON`oCl{qCsm>okM zLmqdx@*!~$STlpAF17NwG(|GA2L&FsGWO7VZj*$|(_=2uu6bpAFw0VbTkS((=)5LA15mDYuHavRSCcCS2q0E*HU)sm#c58;7e0CSEP zeD?y0E|_F9jjNrDqq&f^;pCS_MJ8JTw7$O*5%?vkm47QJo0r2COd~_Be!s%%On{Bv zwHoswT8kf>fP})WlB(D5Jz(<;wkQj2-7qqMAUkRtpfyeyCmMz)m_>CP;uAJ5>+^47 zU>_)kXyTU`i2I-Tg@5$b2>y@fqMVh59>CV<-`__4eGnEXZP_6zB7HPI*GSeDyg?K; zu4V(7WcLFRA7( zHDv&i_pE@=$jw3@hm(axNhZSpu{x{N@aIU;NR0Kgw+~Df_~Uz?DVra}{PM5}$sA)r zcUq$uAFtbDacGSzKxrA+V=>>*Y?0#RPrN0j?UsUT#;?3Wyo81`TfVHNFgpU-dJ5z} zVhZ*~7dm`ZCx7H7iiyKZ2}c_*(3F^CnhdsW3rlLxJb}|JbZ^dmMUcZB)M;tpAHf!0 z%qJL5Cn+47`R0)~#@TY=X)PAYBIi%TPLKWa!UXAQk(rUJN{1=01~7{5`}Z*@RAF<# zl!w|wB`HbmYG;L?IS*p#uruOURP*%cO7*Pw6#m>U3IbCb6+ouQP(ZO-g#q`KF0Cu` z_BIMG*syjsVXJ2;M{nZk0=tHYC(6EH0<^}cu0;?jRQ9+16`R6#lkrb$^`ZM-r%oYT z1Hsslpg0*?oQD;1WnU#KbW~M0Xu^0?eTTSX!%^m}QL4$!k)gN@$H>vvRQz>2NaX66QL2w5lp=s#5V305xAX8T zb{A|(u-3@f|ICt?84d?(=Q#Eyr06uIm92w*261fIx;mKH``C4JsaW_u+r8wv)#Rs< zh0IbsQrC_k6lzhEYH0lwl?4#cf1so>Bp#1c*6834>6Oh#?A=!_NQ{+XkVBF-eJ~$( z9Higc3@5n!fT)4is`;d_@)C*+kQ8b#4uiO~V>HA3UV&G_{JoMV%aI2`W`lmbpT1)- z@0T4XxDk$(levK5`k?nSbDpfJ{AY6b@`zP0igoTKMO@~M9jE1 zh?A9_Q*IH-Z^*;vMB~nr9h*&R4r7#%68)rrbL3wH!>kdSKc?uaD#2 zxSp&8Jhc+lRtqfNS9L=`eVtB7%lz{@wi~0QP1)O_4G&2<7Ef*QJNzC6FIJ(FTI1jd zl!~oiTKqAquT4oE4V9GxYa*`A54ql($X09~nHwzdoWi0$dHzD}*~b zGGVON?I3+PseL;#JM*LXj;dQPjm@ko^Bl&R!OCE%+k<}W{8o7f3CX6#N>+ymEgR9X zV%w&^CuZg*R1;V`v>c1cRvgy`Cu7BVTg6m*jkVYRd2WUk@{^$R#-g5>U%@=|iA)Gc zBNVkU@13uf8X>e^vrVeNz3X6A`AQgQOBhIWD*{w6!2gy;)Q+gh#oj$vp=FUs7w3UwI@2zrEbjYm@}^O)pu@yzNhFhhr9pl6B^Gh z;+uaN%}ACmq6a%V>nIRd<1@Dyh8HTf0IfKB_Mz5U5sknn9YXwS@HQmpRE8KuF2yryEFp8Yjp5>?u6{+ zn0fo=W;W|DD(2iZdVu^(N<02fJInujZRjpAf5^WE@;WG5#Zum+$Zh8Z!IxHqbBDr=~L{uEIqN<6j8H0D2fsth0 zsnB2s>vPH)Q-r~ErIA&1k76I}s#+uw^Lp)(_ zcW;GJ_^9f_kdvo@Kuo5y4f{a^{3(3SDRpFi3NqNt~?6HDvmNZC%b= zjyXQ-v00nsl-fvZ-Drn|ld(qsl=zJk85mg*d`EzCRfaFT$aIn$8AoTIRbwx4icHY5 z$2{3U5aAQa?5XgwmKyvSaZn>i^G$!K{GHl#rN&h2bf=80L*T zhFfbEanvD3D}H zda~JHPWQ@|qRDO_0?zap#Q`-nea?)r-pJjLKEl{SlD->&%X2MrNz z#9%Ky09H=oc;dsm2lPlSjQkP)WMUR>)$i?8+9#yQ3k>}L{2?YpVj1|Ua9k0q)O9i# zo_Mzf&5j#7hMi&bD}Lvr>&^3j#bL-SK4hcBKElOx^`(60OcWb^v^Hf-fSSqU{x;FF zme*v6{wslK0tcUhD4pcKxfVU?M}vewIk@$j@tMOh zu>Pju3dcc$CkWbI2!QNUyI7fKzQ+&R7$Q()IWY90vHWYX?q9d4f3>`<5Xm_2FPaAY zpSC>V|1lg@u+_B&xLTPQ{A1IrP&)k!kbYX+E|W;6-iT<5yO2*40TX2FWG5EVib&$t z=lrf&JU0|gvUKEFk+eX^-inePqAm6dW}{$qH%Oo9Jqq`HteS@Xz}&sG6gvWAqnn+~ z%yhfxIQ*Er%(S!g`g}dq{(k0%J}7iIas;dY%}VEf*es5Iu=rO)uaP~TL&%M@Mb267TMBAvY zvlP3hrH+=TIo+qX@U~mF^;XlaPvYXL&)k6;*c)fYJ7@~xD@4qvATaWKN=6pNy7!ZN zs)$WaaMC)okC;T@DUTX&YlcoZ_PNW0Ic~S1{61dK6g4a);$?vPM)#Qec=39|Y@EnLpCN8}D`hTyE@3M5oSJYq)^fIKuF6VVR^Jsg;kVD#EFdLv*=Pv5MZ2m`)9h>c(%h=ylz>KPhyqCco*%j!7qYCZU) z1&>=zi+r(<4i}TxN~2PU&h_f+n&fDMvz*zIDE?JriF@gug`Co@#|j)!Mb)YVO{mTs z7RO=$$Q!i#u!=j_Vi=E>QpSoM;S_D`0BHTg2MDV~NeM!a#ma`RXQWLL#RL@ zWJl82mC(V$Z{*`{lmRHgTnWf4uX5&+Z=uCl+pc~NZ7m!~2waTyEhL4%Bug9Lh`448 zgIl#M(ia)0r}EUTtY6I3YDFNODHXO!kmU0vkq$MD4DRL6p3nIP40>z6A!MAC%=Ka1 z;de?xr9il0Flggr)EL2UbbsxTAlwi{+c@y)is0TL8n|rG@cV*<*PHi_$var`yT4!u zXc!`Hk7uK5=*W+*=}U1cq6N3m=vUVlpE>V4uBf*SYc!v59L7oZ?Q@9hLL==}0O^Da zL*EJlitvI&XXxRPz)hpjeZ}4E4Yvu{cQvPDI#Q8TzY-;iO(?=4C92RHs|(p8R;SEs zy94qE8aT@L=oy+u<3Q}1)7;|U6pbGBY&jOnfs(sL6`_=do^M4ph{~^Q$X$mQ&*$xJ zbvYnka+nh7Al|-dUXfH>F&g*{+;s-pY7d}y_JDL6b^6K~R(tfjAeqLuxdjJ+afCA+ zu^uQx1H`qdjupixpc})ab99RWKIj~)$eXx4yc4${?KAHY?%)5k-fi#ZqYC}xyG>C4 zRqOC~zAO44gTIW0vAo@&Iv<<1B&^RZOk5Gn2zvJ(w( zDMm`hr5H*Jece^`QVWMfNuVr7J{vi#-wjz?nv?e3T9dZ5bT`zeR720m#GsUpanKp2 zFvoJlnPkKHsI*uVX1cwn3eBv=9_1_ImoaW=)4r(;oQl=@2E`hq8I4|{Vk+V?lG$Wo zf#(uY?6Xj*dDCeC^K_eBqHjM}l{|ZpuaSv%oUc_zulB?6`4)V(*l2|+d%uWg2yMUo zSgSf=LaWFj1)$w`pc+FJsuD83Pr@Kiy-;rI5YpYioY9bNwfO3C;2u&-Rh)Gz!m|~t z<>YO_mXc$-2uO)ARKVm$nWa=WWmlkU;UF+c9ZL);BuE)IO&BXz@0hr9M7Gwc3?~__ z@<^Dm5_D(D5XgWG%#&JJ)85dY7|kFxi*v0}H6V^LR+mjfOjhYA(N`MwQLKWPVU%bk zw%*(`Dvj1eiC{p{CBRS+kSgjyq^Z`qQOQ(t$c7|a*K8t})rx;V#|q=NpVww|L0`(- z>SxLccNY}@@gC{4k$4)NK3}h1AUObvgXSPH==o`5kCVbsunXnslBzgHm{$-QA5E;t z2_i{(;G9^r*x_6|RgwGg@c;;{LxW~8_cYXBxLu}sZ#1GA&b}Xb_V=0Wi#(NkR;f5z zrP{4F8=lZ6It*#cGS*r-ZO-wGK3_{_%SzfNk+qgjZK3VHRgOLMnP?VSZUisi*A!uY zhgR*LfHM`hMIuqqZ1IV(ZfvyS+;{G-#IGt3ri8NIj25Ql_|X%jlr3J#v>6@aA z>8L4IVHlsh)Uf7!6T8*U>TAMYIjueb zu-7zgPtov~UW8r4a9snQcDFWnz^D%3xEDLXujuq1VU;nlLj?l+DQ$d6%Gv$sRSwm- z2gcaY=!OHZ*?py;nUrh0Tkcbt4xN*-^3Y5lB96;4$vK}ILDAy^H$Q)`ExSJ${Ul=_ zmcb{e@BM|*|6LFK?|I05V)*~|;`%?9_J4=BTluzrK{M$9296JndpeT&>{G0X9p0Y40e_j;4(|OLA_Sx& zCpxKkD^5~RA&hO$Ku|l)ZZqyUu50dsO|x$q>YAj$yJ$-ctgPu|XM`kUVk^3}s}h{g z7^UY z)4Ar2`IaROPjyBB+Kb~sB8PVM_7(c+<_yqRAP#Z9^dUU3n=j~W4eDPwqqH=r1A|^| zjJbX-1$;|1K)aSq-jpI@e7GJHxX1eAXpu#1mQ6mhR5t%&mH+qqTIxT(um9z0^?w%& zsanM%f3DNr_apQ%l1c-K*ZIHr`_P-}jh)eIgwp=x8MkiWnH`me zk1>a#437bcgp?o_1hSm^jUPa5{SD|EbWl&VyixLlm{&>FLgl?oWyEtLD;vB%QQk!D zzU?sEY4WuFG5bPK+xMK?|K&;*;qA8|%X4kcFj|^-*lF zPn{OG=-w>_^{llKzoPNo<@;7*bCF0yGU06Jq7fiMy0mmfHPM=y@l9k<=ZGP0XGe@j z;`CAt=91U@0taPNK`nW*>$sW!CB2oKA5PrdycOf+ohOO&o%GxQlbYp%j4R*J)NEMPBvLNUG1% zU1}Q6+>mwr*r@}|I_^RP>LgFzS+v$(Y5UM{asG3mZDfW*pF~NPG;R9A`t`m7Pr<5} zqbjYXi8fQxyw2#bu-8~(nuO`NEl7#d>s`Y0rx%S&oB7^<}mU?%A46Y6A7IvftU^mq>8hyl8ULUqjLh zm82ue?^tN^mcC)UBov>YFt4bt?6ld-u(P|)s9Xc1@DUqK%qzjjDoHQdlq}|3Ot6qa zo;s{=B$L-#P;qRjXC~35$R+4k8F*<4GEl_m_YRxEHjEn9qGlBB`VeSWsaqT znPeu~Yh{Kv%^cJwHJF#IFkuX#kWbmJ&-8&QXiXO8n`E$HHg6RIzFN=G_YzMSGbMl| z2#^X%1JbMwZ@#cfn*TgF$Pg(l_{kiz+?+OZ{$Nd+!^&i9fv5b(xIQ!goQ71xmt-hf$rT@F~>GI!4!=IF@V=B71wPZ*AIe>NgLyh4KI8_7eq*;Rqe`bbHj%DWtVt(qQj&*~n)Ow0-sax3KB#iHnKOX!k?% zVb1p5^Psou>CX3_>Hev1en0Qpgp1P?E4GFY#OUWmnSCT`*4e@=Wel7KKdg1`69^u) zD*T3*3|nUM$4wS3&-a(!%1;N7AH{Urc~X;Y-gsrh@?878^F2PF6S(7My?I>?%&u~@ zm(n)Hf&v`FQI5vqIa8;6Hw9?;ghscAjk64A*E%GsK3Vew3y-QKhI&#qFuSlz&xPdk(Q)06%k4W5r}Bz5tN~OD0c!u1)>nBeQ{QPQH&{U@Slg)7+|`DAuiK_ z`T2iuNcGw_iR&g4R)2Tl^vA^RUw6kIJtnhZ$?g_ACaVIL+xF!i=Q9KuFrYlwh}?l_ z-X@=Mhf84pRE+=)`=e6kgb%15<@XDr2MPGorvy`s@CYZ98ut{5Yt^EY$%cq{f8l+m zT8oDKTB!3Sz8fwyNwY8@R{3Dv8TEGL2|VO*Ht{3z7ZKsBRS|ciBCaL{{P<{)(MaK} za7QDW9n*jjUQ-+Z!4@vhS74VKk*p=nEHyO}1F4{SYO1J_lmA}Js8*Qo7P@7h zB>UAEBDuknF$A>7!Bp?(^fPPoQhGPqg4z-e5ES)72FE<2RpMYKrM|)6jK|5~l&ieO z7&k@-dDlWwr&j>iC4k;F0M!wMz99ntF8<{mlH(PF>lzogR}TaM%N*;}{FW57)gaIS z+yQFYg+NN%zf#cH2+MAghPD?!4~6qi+=e*%@$+jF4%YId^T|C;#@G6Aji55?JhZlc1?mKw~K-5k&MDO zG@ioZEz+mP;w_VFW&YdUlaY%dfj1dzR8|&dvJf1cY-l!U7RXRM*P~XMn#*)LjS(6} zqs7mgJtO;<^!(-JhBnr4F}K20yN%-g~u%v4FLxWV14d`CS*`E$^>A5YCm@&XYCH*BJHAR{(`ICm{M zU6;IWoOKqRI_I4l2mG@M);BRqiiW&r7?L-&@>@N zU{JJs4+_+1Hfiull3~&(pfgJ#O{Ae#vw5U!IKRnoxVkIXq zkfyged4hyABnY^a6Y@)PrAlH!Qjvy*Txx$QzgBZ18?;ho%;1Ibltv@OVwjG9U20Le zU73-oMzPr_+|$Jzzv&uIcr*IfJ0f8&n~c#>Y$u=J(z>+mW5K_^0`S7s)?0lAICodo z;rfw;=9})CbDd|-Lj4fLsdsI!z)^~dwx9V~W`&Dsn+g_8W#^Q?jo8l@uWpC-hyFC_ zWnuM_JizGiLJhhm0MM3l)iNzRCd46AC?%&7agZHySF>NHNTC`*Bo!%Xpt565YU?nn zP%M%wo^j`8kQIf@SV)+WE9a3fV|JEpdj$M4z1wd}BZ5jlkW5QwK=J$jx*Eml zQqQ;_rbr?7qFmo#=bzuI-T#eJ7ZYGO8+r{*i5inoR8>X-2mYKUu z-zk`HG$QcfQj1(5p(7L-i0DU`Nbreu)s@<0LU)~;X`fsTfDPoL18-s^|>gI4M&76iRu&Bt^h+U4dnari$zfvY=c4^fYdxEGe zoMjH;;{M21E7XahDlyd-QaI7Pt&py(y2yqg6PaMJG2HIv3YWSf^_05+-Dgan4grau z>q^qq!*kaY{3Q zoUSTwUj}rCy~#%yp;nMz6)|rzjU2c4-W~nriX8DbdXHabE?)q3c0X};ug@J1V}#kY zKs+WsAp|XNaAZDd%^F(yP%wycOc_Mk#`iKbQW^#CV2F8fGNonyW)_ith+#%V4a|n% z>@%6*RZTW~9oQOKxh;?0=fK`tIgM!^m>=H-+!$&P6jF8=X2xDJ63)%7#9lUR@%GJn z+_Ypo8cI4eIEa*EvMgH1Km|_ZT4@W-qaQ;;KLAeI0k!GgIuvZ>SlatQc=sr9)+p~G zHCOD8*|k@}L^U>u8&@dVSHX5pAy^zX3)6Kf?`$qNQQ5DBHQu9~wo8;BTzXGsS!Z?$ zexqW%p)uQqSeu=r`&=!62YBRSzUQM~lstjFy+NrDQ9_Fg?61q;NAQ2*KS5qDQ@*0< zZNJ!eoep6nweZU&4NWwd=OE`GL z&gBkL=qpcQ=F#KUz0!19c84z|@nfm}gV6*H<6G<;v`2{pE_9en%XFK0@8+T2$1x|4JGD-tS=lxB4Cb%7ayLwy<_0W?=n? zJhCbAToy?H8L&BOemWX|{c*UR-}A~ntGDkW6NHO7mZEhv1bAgd9$tbdH{wMl<9&1bjVx>(139 zD11W39qXiX-Gci`!G+p;&1_^fo~hGJoMsI36weIPCs?^U3R=9?Al_W`=8)ZF-F1(W z)RJ6}o^X_Jn-*_u+VTm5;9S_-h#o**e)l%v(8=5S$N*q#O!X;8p>0SboY->)@J(UI zOc(-3&kQd~4@y{er;k6A_0G8siXSxvWgpErdaJZ*nq8OB1)q#3wnN<3{6uO!6NP?# z*Jay+H*2!_(VblxlcH3g>$df*5lYN`QT+13Y9T_U$*y8i7f!(|%jB(?o~tce4b=OAg`B4Uw^O}gF)^c zDDyS!FbFTMK%{7BoU3N!)HI6r{$sF0FH+L=DbFW|Cl5)MAFp74 zRP+?bJErw#_pbAQ3`+R-%o_enKGbJm_kWG@{%elZKPo-xkCagXn8B__mzD)S_ix_7 zJV*Gr_qp<(!fECB%xuxOn!vGhmEXz@;C2jf|rcUckZY_W9xHhJb+qEh0a!mdsH zRt;p((3J40s3K?Yll*}bT9#a|$Z=;7lbKSe-qt`kTjkYMRY3zKAEGQS<~}7`f+lk3 zEibWcgjMf#A*l4QuR(KUG~P$&yPg{%w$1l7G%6HGwhyk!$!Ls#DTT`uq*AdX1F;5L z#weV*FiJg9iu>F1nDOr&E{oe%Q!U`HvMjk*IA0YoC#(nlIk5`qTc%Pb8%JUn`S>r6ZamzUnRH2wx1&F~J`i&G(S=(76C zLLieB>=a!k#%!eRiJ4e2+s>m~k!PgJ9l6^gne$U&5-1iZ7${1?ztUCC^+*eys?`{( zR4N(?$Ktgr+GN)&HQq-YW*sX}R$ba{i_iB>wjqaFs*1|hozGZC8))>TSu*48+GWEL za9VIy`GnZb8iDCG@W~TwH4xzTti{HdEv0(3Vi$sgI9iNVpdBG&7L&re3>P8sk2Ho5 zH;m`Y7eTE=U3<*>F7xfwPT%^-6sumDiL2veiy@tpu>3YRW!(3xu87OiP;teMR;>&- z9x+L}w!@U`W!R-h50XjDE0WFTgXy@VIaN0r_Z3Qi%@vF`Wb5q4=2xr1MGA`Oit^fN zuKqGlt01YPghkiOaKqA-kY4VoJ{P~4rdmiJ$jESzRB5s0O0w9lX*EGPbj}o09TH+M zEWn~GbJrL$a@Q7vn+=xM3Oz~fX^iGJEsBBWJfN>J6c{3eQoMySc-6xRi-H(mC>vWq z(`GaCK&iuM4_9;1?k5RTA;w;Pfh6uX0gRRJE04X-peXFvq_28iX*D%99I(D3j`743 z-92CU7*qtutSG&~+hc!F$@69y2XlAzVX3$s~Qi-)wOKV~n%2 z^q2emmf_g#?6i?_LYo(LYO;Z~QcF0oOU;2|z5n5Fozoqz7kqNuPX*7UPO280r}_)M z6cNNVUoI?+FDRxt;T`CwQh1*i%47Q@lsDOhLa2|(9r*@ji^>ScAP|wn)Ot&5DlP-! z`}GqazAqHMCy-d33j_tuAQCrSPxc-MSOK*BbdS?`50*SH^w^by|H88r$V9-jR;add zhPk?@i2y7%+q8p@r5st}Xv=(BURHyXqchSA1Wgj^AO(qo7FGm6Y~Gf|0rt&j+E!&4 z-odR+4dX0gga0gwqYUP7Q{{NJolm?A(xepf?U}||5^7{|39pe9&btNUH~It9Y>q>! zZx8xgIOH=d#xqXD9k}%~65Lxz%Msj0Ub}lt!HfS89zgInF*0PlOE%IqY4jGwT?2Cf zW40+pFpTaHQzd+#DIOS^d_Z59R6P2YvC|Ig>}o%L_P#M}UFB6v!Xh^8?=)}PLR<8q zz+g*mEcgZISJ*$GoQhFY^Zs*h8|g1|w!cFQ+y4VOVfrVsD35BSRH#$($oO7rf$XExLsE_}O62Gzv{7-Owf{W@x=eBPdnnl%;2 zUgut(IvzP$Vz#D%_(5-H4_1-((Fh6LU8L@}&ANLT4MJfRg}`NyGs3u0R= z?~l3OYGVC)VB?QC6Rt#C`O<1{yCHli#c~Z6Fw!vAuxtd8ACs{bkU1kT`>|)XiIu>6 zPgW(2k3R!0LtQY4o~jayaCrAX++{eb(ZuK5h1CvM!@~-GAuZJ9 zp;E?ud=oOURs(1&XP-OH*Ilx>1tT%8y?@A!>&Iw72ML(^(B*>h=1jH9m_o-FncJpF zeb5J~0;^fXz-rD@)N0c{FEnmQ_66$I%QFei@&T5W&>iPw=iI1KxR>F&u*4;~Q`n7!wc-}KT zGaNZTNO(#Ai1F9~4R&Z|e6y)%7hrX&Q*lUSi;te=A*unAjZY+gLY9rOEF0vEeFr%w z2${-2BLvEoKfRI7TB4tu!rXUk4Wv_I@ihM?a z8oxU8+!D+x$7^WWcq_Q89S80_%O(`O{@jt|TWmX`pcmn)$_hJM7dD6m)vR|>*fw}o z%V}eo{*Gtc$EF8vRFWxGTalq?QK|6GS&AL-wQ9y z`3HKV54K^bD~`myh!2eSpVF$Iy=GpZpQPjI|3C5I_!sfeu}1#f?7CRXN?TuEo}tZ3 z?mHziCI@gZ9P0VLphdWPPPcwBzod!3O#_K2BEr4XOke2oqKq|U1 zVt5XY>5RSFLki=5+Sv@+YHO#lAt8>iV0F7_J6wCo%JG_Ldzt-N0sVzjUu?>s7S_R8 ztPYI_^Q2bJ`=Nq8cN<@KCO212L{tdGM{tIYwG(@Qz*q$vHB+shti+Ii01+h!=7yu9 z_8vxv_V6iz!fJ3tZn>;OjoQZ4d^g) zpG#FgX6dQ>_GQ$T*Pgp2Lty!|Rkk+9fW9ud+lB}xPuH&3R6WH>`$fEs-S%aup90`M zF{%}U=n%UQF(yyHpNQU_Yo@dK;03K(W{hN}2J1?5%!A7wGP4lPvp(;h1gRzwX|giN z2y@0AL>wA}WW>TROWjTxtAw#irZ=qT#eOyVlzXa=j|ATw`w@OP z`-3K$?31Q7y4(nyYXZOgJ#HH&(vRYE*gjyt+lR@WBGL(f~8$@9zIG})2V<;|01cM`k zuIeB?WXfH(%P#8N0X99eGMwU1d9s^vT$#S_$n_4AC7^0&(ZwuZ3o%Xa=$<)NYI{ z?7T84!}d4VG+G)970|veaZH7{v*Lhp7xGnUUOp725Hq;ipy-HvO9>g`UGzzezt+ zHiFOKSQBfaF*9=q$RJFjx>Sh-zePYyKh*TZt96rjKjDS8ql6ZpG>bq8@PyD1qv^{f zM0OW`>%EivV(k|1rYl-n!Z`dA4}C0eb;QK18^pNsOfwgYehaa=Ww9I^HHG~^2CIQ> z@q~O@L%{f>G4s1?f#hgag|K472m05TEuHFZp>)0-PTCuE+H23TTd>#e-PYm7U9*i)t+j5t4oEk5Cf{AG z)QJp@Ogm$&)*jYt)aERMvz?PTStW zhQx1}w$oavxi|{i16<~07Q(~>iYEw3{Z5JOl&b-U5|nw-O$J;F*bdFG6#0S>S41k^ zs54%OIr8x~1V2-*zVeu6$uq<})+WgJDgzTLkj&&wJ)u!DNE@+@6Lf^~m{%F|vgAmv z06swf;A%xqyk+E{*Wkd^q|D%ueUcBm>r(9+(z^`mgvo5GjF^C1j zrVIni2L{5R4Z9iuw>%NQZi8gBg95+B1HTo5W|`06-UIxbe9#PGva(6Era#fzbYe1_ zW0UQ0Y%Jw6NA8QXQ8^l9WJzp)6>sXVV+y;S=CHspNPuue`;!hJ>YQY9v*GEh+exo$ zhiIQt!1|Vf&)`9L`y?>N5=&b%K1 z2}WzcNuZV$W9L>^hW?IDfbxJ$1UE6+K|+vCCPYX+xHouLYPYGIu?QDL4<&bG=mpQ|n+uMJNkO&#vD44L(_ z;lha`E>fPTj0XhctO)(u_CY&UWInlstN623rs zF*6%i=w%pa!uUhuE+3s)@o2W?d!twAv{?4co>=V+S^q`?N*`$Yy<~291ak=yPlzuJ z|0cJk8&{vyNGh>LYH2dBe^$TMBhqp|BA_uzCb7y09jyF&*z977UR6uhSx`T$I)N1m z2KS&#yho*oIZ1!mHhukhsUVh`l~AkXFNSa&((%yN$i}t~e7{U%TgSF>6WcS0AWb|f zIUFL~zMDJ&;ZB*KFA=|#>YE{6F+?SzjoO8XMPk!KX|=0`h{ZOhLw~U&VvtyDX(l>F zHUnw80kb(!P+~?P_-Et&QOZ$D#T%xdtZx1K>TP@_ihwT zbz$33Z{kK04Io4^_k?!yaHHD(XYMl0Yx3%zXUmae4jXTy@n}^@XNk#HJ5}M_+M*PU zY6hF219nDh?IVn<3iRZiF?`lhN5dHaV0ez%{rX>HP%&JABMx*La5NKVzwJ zFq1vNMH-B+`+LZ3>0w;-ynW2%+?D5}y5JXS#+F^VDUkXiJ}!*`#v3rl_Bu!P-*#Zt zIw%_DtHc`yr{vOIM3{sVvh=hH;s)7eI-@{nd%i|}THHU|s5=+W%y3G#FfJ2Yv_OBl zNgUgWd*^8dRthYLG6f)$#`PdqPuT=J8%JSR15FR-DoVv4Xhyb)vkuNudW-BRfmg@O z@oytX&Ii=l^8oTv2+V+$3cCl1oPzfrwg?n+CI!aDn(} zi`?jLT0j1jI0pL6*tvg}_rhPw`|q!6=Krj`Kji`csO%*9QOUl~wBuPd%SxLn%^ZB& zMwe*?XQFWYaMhD_;^QGtty0Tm@tU*j`o2~-6z@lnh$r-XzH!Lo-o@yiLe?|l<@ zQ8IegC2BFFmBIR*QYsS0U9SHiQu9Z#y`eR}99fCU@jJ&zBj^C5OD1E1_L?u4*GOjx zc`~CtEbG7s+Sgg-fD;U5vK?T2(;1#Y7OWGh3^(37>pLeFAb0I+}61~8)N&phRf4PgG=Th^cm}GwKOF^B|j%`_=`6-S{WWgF~l%|;H}>V8V~|-?jOzF z{I+4WQ9m4S)r#7Zv6isS$y%%;_Y5-+ICYWX-BOiHOpO4hyc?I@ zQkVP@y=>o})Wa%d`s*Cu7};_F6WB`#e%w>b-SJlv_RPjlL58oMlX+ieiiCM&1>Jv= zf@RnKS~68%fy5?x$*1s<=*8oRu5dpR-?@$Q;oU19&#LAKBj{}x3|zBWK8BD(;MqYm zsPt9y2q*%QvnJyZ`Ua;HYv}H3&Fr%X%Plo$qAtl(K5FWY2If3wMUK@Pk_lJ^V>Q5J zkLdtZO{p6!aas;wpprelmN(H+bB<0-$1qa3+SCiN;G|@4Ut1q-=6yWC_dVyu@=L5% zI_dq)C26YT;mqRTI!)~q1F`H-*`HXre)mhaU%(+b`K7T^8jy`EMaIZ2cb7(HVOfbU z_3@JMKQ?GfU)7PfU!nttSLCw7ZhT`<8ot=YQ_Cwm}P>^L>^l`(Fkvf5#D)|ExrXOf0Pb z2_y=me@NbW_E{JS@hN$ccENf=V5g&|TLWqZbxO}h)$@#tjZ8U(yGB}PTCad#$#>7i z4Gj$=BR13~IoL{kKHPnPrv{57u#>f^jRpkPd&+}Y0KH)|BbkiG8C73}s*yIt0g`$a z9@!v57&>8jatWGzcfouJarJN3sZ2&FOpPxF%sV@>?nc8u=^+GhZuwKMzoKdWhOY~M zvdQNu5FF=Hd>VpzD!W3Wnm%j(0dtlOXY$A>O(^$}m_(;}_AV?f0tw0vw;;8|pBC`p zgeNp#Zm)NQ*o7`zXoe2=f!elUX^DfioH5M6>{~=4`qV*Y=p;(Racj=x8e3#W)^!Jt zF|rr5gZ&4PWNvzac}dnpAVVM9L(>k-pnbXh1QO6hvppg~v-9-}XvP@6U#k>tvJH0i zRg|U0Txd$(=SY9{P%S?k{{RxqzW~YK$;^LxN`{XAA~OHNk@4X<*hUbDL?igAgD*OY ztzS?G1cVS2zmyfVZL(*WQVms~xq#U9u+V*7ghQFc;g;_R~;fsWZrb_8sL7e(@+q&%|KN6gfr^G;F&P_em>p z+^9_1NnJ*nuNqS@>qsrpY?s;NU@`qD@djwl-n+IgA*sqaj-Eg23?2I9c|Eq;2ft0I z@m_*O7bTruMKzZ!V$=g0fD_~^(=B2wX?dEna?L0K=gs>+;3keh{#u0tjisi+y2c1* zJ9V5)K*ivKamolNP|<5ntPy`i8ggiYz>)B(Yoh`ST#FZiKzERiq9 zO$ak@XF*r%yfu7J>?You2Vwy@Bok$7S?g{v779tqgc_~KEGC3UnguKOSQG8(&f-?> zxo!2&4`|P;8|;ozw*xFIBF#0BgN5d^5R z+Ck`b6_T*jpy<#Fa00GufaDixEZyoO;fId9B`754q7xbw9=W;VSdHD|jG{!Y7Ep9TqSh_vLLNIPop$t3JfN17P|}7*y}+2u#O*pkLDt@H*8s zj`|hW1tnDI#o`QA;SiofRf{TCi@Y!T{n^Ex5K5;&G%5es5T4Qq*W+01xUXM=UB>u zwi-v4ghd!z+TKXvwd%`9Z?Ff!$({7Pck_DoSR#{lX4b@tqF*9Nw3aY$er(3(TD{Emb4T$2(_r<$(Bf0 z*Sz_0UwCvy`IhM@`I zlcH-S6VxL?=+?)oZ-nApnmXW`#|%9P7ho_jG45o+Z>53bl7}N(<#zYTEA#rpZ!`JN z5_u31mfd!yI6dISEEg6`M ze?tHb2v)0SB_6sdhB24YZPwxHkR;I}NA^qxZA6sg$jPkNIaMucw0w$ioX;!r7-1@E zp!U%kKNY1}YfL*>Nj$XMGto%TP~EtbB$=LIHgb}h` zsRU_ih3}imBWPju@cd(6OB%PxC~*A%Rj|ttfU=4CX{sj{CiH6kP71n1atYKVumAen zum-wc6*;X?2orH@y4)g(2*E|#iB@J7DsZB+lh;#~Xj<+zQ0-dAYD~4?!YdK<5ak(c zB7c>i%NBz@3Kh6YvN2C&C^A4}41@hUn#&lLI{)`*5nw5G)+^Kv)+;zpn2rdP04lkD zv4CP9(y_{oI%y#GkIn1V5+eh@kjhn(lJ2O!pm(R!0vNPZ_k2?>cwW4iq45q)h^@}xSEZ&DXxx5x%WvPt}~cu=VQ2vsFwWGIt5B= z20qdt`*bBiV^3@MJ9XOv{yqQ-?P9j9plTuqwt_vCk5~+wc_|Aszjxq9)WMXL&>yJwk&VgtZ!aQ99fTDn2)B!(dOVA$O z6lkX(`GPs}XsO4%k&EcHZuyI|2$lEqNeEnn{Cs})`HFzh_4W=gk9=mdHAwvoGE`mZ zE^agoaeQNOo9g+`m^oq*O|MHfA91BG##UcoNEtP?^QN-p+YXpkfX|&GjhXk6KlnXR z=M{|{bdOp3ac|26>SWr^TN@<@RWg zZ%DX)hadiC`GE5g^6wnL?(DN!6N=k?`OR=*A2?6Bh&!d}71 zHzKm6k1rB=aB^D~x&YI{_dk_EWr7)krk_SEhyUX^`9JLI{JGF)VPN|&F#AWi<{(!C zQ(D%21p7)6{0wo^B363SF6o>Lu1td~eN#fMEDV8Fkx6g`963TWk7K37PufKG6>~9MF2=ry6@wK=Q&8YOk&c(XDl<%W9FwF z%SGGEgxIDZbT@vd#SSYrs{>bOX@R~Wl$dnCy)(|hY@oM9EZxv!C-f6igV8nkjGK=; zv7g*XznZ6bm=)FJ4?4_JJsrP9fOFSC8$XLAbZW%$!Z2x8_N)6Nku1iTEPA=84**`v`X`%ugkX&Mlw^w5!2v9cj;>oNIDaSmcsJJtE8Cp(4Fo1rOesHAP% z83>$@Bwb^>b8#7YDO!Q&R%GSAu~l7Pt;+AH+l)i95duZ~tp$ymTdIcc=m?ncxUz=+ z#{A2~QBH5b5G`sJ{Td@ZefI#U1Q=*uI>-KEP(IT^xThp7$`C7}1N5pxR|v1X+a+0` zOR^=I+f+<(KS^l08T?Bgm3}jn)KF%~EJSeIlpr0e))MhARDp{@Q=GUEPC&4rXzW*< zThs~to?f`KMtf8tPTZC&knF}QBhu=?z=?e*F6Wy> zC1YQx4?oZ3QSPpeUQ1m{Pf+-3+q>tg4-Y5gv$ilITaD!c*BXK}4_#3@Vzy&|Hq}J4 zqK8i7jjxU?q0U2?P-QQ!Yj_wIifFKRNaOU1sPOmWH(~nwUsVT#XY}cNi8SQgIP`RF z^KxCt$?{yS6YVapd8ON9vB;GPK#w^y6I%67JO}IZvV1)u0c7tf6k2Dcqmx z!?g{PHFW$U-iN5*RP;!Fy2<^8d(jT^vpxDsR>k?kDMpJ(m@9jqE+>w>aCqjIPo|g| z0(;cMH{e= zmMwE-6{pfZ$so?mHC^H^&AJkW>_gfkAm3=W$Y;f)@Ztj`k@e;ir?}oRnmocuqk@!v~PG)FgO2Ry}aVP80tx?EYb{KO=7i5y(b*0BRqFEUa~$3Upq)GpD3f19({Xi zc?dUz&gUqTf~bJAmoR*tc2JTtJxIi-(tx}ft|rVp5MvWZ7R}^u9fb;>H~8+@B1h^0 zx@&T@=1ye9s>Sz)2_e?LlJ_u>{pM+=`Vj+?wxov(CQ;g0{XIo1KCYrYw86YM_L@M@ zj(P6Ptw;|2rk7@DZisK=)G=ejlM2roUy8V8%DIx%cT*VN-BBaCOXH9{6c!?(YTI?evkMF0=_k8^DUpskTLQF3(dBWQ^weE3s`_}CJFWD~;e?h%=bKhfr0esz3 zTfW0D9Vm`T9G#Nhve9iPq2=w7s!vqApwMjxi%BGcEUEM$cybeXaK&vSfr)Hk`7&6< zHF#{D^UUagWB-B#S&u`$D0R=nneD99%MI_9slsPCa>?kyOnK9W=4v9cgC)F>|KWR{ zt#X);ga)TI2ZbxXfh8(<;X1RGJ#NLR;oF^_WeG*k0C-;l`;QMt|4jy0#p+LL5Xj&H zFHA_q8#VP=zlj%-4zTQr;0d=#J3(HGIehxJ0>`mdI0pR)<;D(27{NG(Q{A)3aoAc z@PG)^5q)qmh8#UCv7YmUkS(UwxX5@$qAkDoJN3I}DqYUfI=)F&G+hgyCoEXA$vV_3 zNX0c=$fTh&Q-2yaHj&<=4k$qTJiBy6AmK96Zke@k*>I3oU%=2>3)PmYh_d#fZ2=h9 zWfO##d5pMoL)Z!qP(?-Sid2>gjSG{wD=4!yG4GLaVWA% z4f~&p3?CdN9Y-hyZKO!zeOx9tAr$RHJ0R#TVu~3Lu((3Op;I3kcal^Lr;8J}x%4z@ zivs<(m-w7?lP8(bN2rW3?w~}KG;`^GNg74NMX-$AN93^Ar>H}e`D)PMgmpx>RQ*`J zw(531Y}9fM!5g};<>c5_+l}60?&;fP9>_@}Q)@GyK%2JCR?k_8wL5>nlN4@a9LbIW zn`&e{=uz&K2xHY@x2SP$X=&MJJYn_DTIg>;ZaUrX&7d^OW@9NA$PwuAAW?SGi#6j? z>7FRvG_D@PQn^4_RjI(SG)hsd0M}vaRZi)}MnBu|#x_++`A%l2?H}d~17=iru`olS z-;+fW7MjlP)JyYvOsF+&>|zhNv@BHaY|RxQSbMZBkea_a#xM1(CgSmKn~Rqxec2xb9 zm6}5}xWKKMOik};`yE~rUvsDG2JU|5s+I2;$LOCm5gl0B9kjp{uiq;T96^_UxzzyN>mDdXHgl4)29N9X zqu9`-AYGau@CquMXO!MVteF*S>?wQ>FNL@P(F6}Lb3G(8UlX>&n7kp^3*eo1p~s&9 zuT*gIG(uO9#I@^!azs2J=K>8>EI#T2>h4-!QO=9{n$K=4C$CrQ*1g*elXCpWCslr= zqpk~#Sy#UwU5O7^Q0N8;h_3pfEx>bv$+tb_bFFw&&oN80qHr$G?02QfdmfzE68Ka)diW>*; z`5fd+5Be_vy?GO0E$|%D#^Hqb*8uug_eeS>2}6z$G~{eyijO0x#J`#xFUYK6@q&pxsjU@V22wvaHHlHvAFAc|Q{@`TUKc2_?>MkP44Vm_jWb_k+mMS?= z@0|W8cgnvGefBDjM*NOrt?nkEz}IP& zSTP$xE+YtvR;U&-ma|`v7uWfdLuwCzoUBmCp=8{BfcdB+IlV>VH)pxoj*5Z31b4;l zlWp{wC6`{}p198*9T88$E3;w@a=E%;inWhX*iB73qKTFpZv*;`2oIS)qoOZYUJpDW zF$EIgu!?YFvLQdu8huOy8{wo1#GDtP&N{z^VZ&QO%tp@H^|eDtgJCL+%R`5%00!-; zM;X{#_tZ+f^(Qo3!oJ4XS6FW06&~bY!-eMwy&^oZ9s_^66z?2uZ#b`)zkhaJ)z`m@H@8u2TW7tdF8qoki2c8Ata@w9&jR%q~#%K zlo@@nBxeeIGxM8JrH`m86gHKw)dUuYNmg-HAZhQ7_v|LLJ zJsG4H)CzK5KVOHcymX`mNQcM7vAd%TUd#G1GNwib3iBWrI5YFd^tqcUAuqr}d?nmWvHG>uk-@E} zC+GBm4*SqBIxq4A6?@(TF;{A^zgfFjXy#pbCY<$NyJ2SDFSZmZvFDEbGK|wbRRk%q z4_Uyv0rYWAYQJleAP|+52;@idGCg_`Pk)1wk9Xyg6&Kzh&c(<~g~_?~asa+e*XdNg z*U3}NMKBzxXT_sR=jx!=05;=O1zi8itKZ(XA=2qJW*`@S`%irM|4*e;$=t^9AA20o zW{mYRy85$e#ip)W$)pF@*Lf*uC`h#~BO}J4LVG!mirtut+d9D7G-+i)(|sMh*Vb2$m)DfE zR=Z7-Z!8YTEcz<%sT#X-R0CA~_Fh-#YQ%%};Aa7Gay%QYO_pO1<3Y*m&;F{*YGm6l zjZmk8ai? zak0l6U(z{rlXkq?AkYK+JcgLbJ}1L@Y3$K`3hSSu&aQ3}l65zckin{qtm>8Ua}LMK zWyZKtlu64}C*XZUU%;buN}TF`iW8fhuHqgn`+ZZ?m^@3-DDQQi!y&()H9Df9v8kox zch#wCGDtQd*4b6>VCgsd6=*f!Qle0`Mx`0Dhp^tt}V2e=Bbx3c$ga z8trr$#rePjOIG9gn4fv*U8Y5WZBw8}mns8SHPNNK!#V4q&NJp!R)ncdhvmn>VU<>5 z9PY^W;qsSA@Q2TlTCLX7?&EgD9Rgokv{B_2X5vR#Ey9YE7={_?%V1778s{j{;i{IR zb~`KaZ6X@NHeqODreYO_yLMnsLk(axv-&ecI%X+q^*zz7&D6??gP!cZqHzlpXpx${ z3n9ND7?S_U=h%-6>5>RxIQDWkZc0^RX%YagQo`-SO<#I_mi0=b>$CKt5~v}=P!p2m z5;^Tr)X!_^#&riu`%3lMp(IkdPS* zUs`a%dU?*b7F=)qg_h@B(uZu}dpQhSUtGhQ4sFpv<`+<{*9u(&5#Si{qfvEly&7>O z1Y}@+i#_FA7hPA_0j3io8#)TGq#CrP2>Vv#IK%Q0(4Y}@-Sq|3*Rx)j!p9pXus z4;6I^^mb;8y8TPozocdhD|FAyb(K4o*LN;7b11}8U&Ini8jMn@`#zWqht#(|Q*1ue z3>fjDeq2DBe<+>AmXtN!fc_egMHM(c5PuO-_+E_5LYcIDPlHCrPg$fSGKc8qp6sZh z!f|o}^hQ7hJ1l^Qt5m|n_gel7MS7~>UWm5LB?t@|B__>Kj}S_6EI7G1`#oQYo_RZh%QlflXiAQy6`-E0&U51Lb;2?j0T zHQTjvL#2fhk3wOhux!~Aq;NG#Du6$2Kg+3gE5l76wUe`_W@uCNLm^$8a&8X`X?h@| zl6@3>h>WH5ZjIfl9{%RAkmm!`lDi)^={T}#mu|up1@dazPll~MUB2vNc+?jiPa-F@ zP-fEWpK4SHOYR}LYI+y-H1YO)07N}bvU!K5ihwra?bL1|4*!4)Xfk_<@O3GkK-+V) z(M{}M-=6Qm$2Qn`!X4crYwjzdHqaFU=7d3&HZ49N(Yoo-^a@m91PFgxMIrrw;W@Ar zV7Mvq0h4~ikK>zbx92>)?1r~J4#5v*4${`nfK3`cluwZ_iL=HH=|B5`lA^)OoK{x_ zBD;gCu%C66Ukugaz17f)$>TNS5=93DcL1V2bAjmNr4x1l0k#-q0Y?p3ot;`{=#|$Q zYP0z0y4o(0kEWWi5BP&Gj}49 z*LTqW;|1kEj;CBD9XX)!ns@3Hl4eGAI_NW$U@rJj?F1yWq(MFj2|Bz*G$8N5#VWwc zb>K8EqZe|kN^}eHoIGES)nI+1o4~laY8pi*1c$)oG?g3pj_GOYLfIPM2?#~Dl|Ggd z27tkuFhGjTgvKm^DY8y4L(gEgJ0)-kuGjfsz$}n3k$xJh+PIApYf|MPu*N2j(D$i% zL(!=EkbAl0g1^xFQ@)5bHj}!mdpkD~OiovX<_!-rO%o3sc-Bu1$P?h?jA;Vm?DT-edov7F8%= zg#hl+Y#4DZ8iWEu4d`l2XE4@qy`(XTc6wZGjx3Y{n>)!P4^ajVublgIoAVgZQ=%SO z$V)xT+%{0>4nr)SYX^c#7DPGRWm12;G}?{GdaF6-Yzt9h6R-`(GO7HMRZUbtL2_0L zcQ9;@co>_2(zW?jI*u@Vu~O%>=9oKFW@EfM?gh^6$9a47(jlv`L9Se<{G*x(i{U8; z5nP^BuAt0j4Cn0Y{XAi z=ZJ4`VbR_IR1OJ^LbudQmdeBh1H`~YgG%k`L4rsx_V$W?P?C&HfDf>7_O?N{3CU{w1a8ocK#}jiOq2h5%ai?kKgGZM7XIxIDN(kz1wJbN z#m1noz;se^c62KjZnj3EX&BnDJcQ9NP6hUGR#8-;8qw~^V?f86{8DNOL~s-F8^6~c z`MY#3#%gcj&9-w)r0|spqMsdn=N)`+b=y}dd)l90fiKJ;g0R>x_yr~fLenIw_iCUz zr!cQ4j4LpYGw5fSud{;f!8g;%Hx>)VY9mvqS|)=o&UDn0Gc*(mo|)iSxlhnG>@YL6 zaM|UyQ4+_NhzZah6sfms$4A07lPH#cn}HUhZ#*30xUIiiJ^Xmc=|Hj4x>x`GBbHwU zYJbkx)yT~2vmPp!)11uYe1U!Kc;vg-CXA-RJ7cCFyWv0s=eTQbdQ_dV^_tDxBB((+ zVhP{yScllwIcBMmBvY|vHJC}nv)s*XhUSfFTE#iM4bzlz>Oo>7<+j8#>CA$PDWCgwhZzyv#&G$_p_ z+qBF#hi@VpGDKtCCm^M7f6J2}4if#A=nCp0%k(|k4afj()1s;CN1Tf^vk?7CjWl1B zl@(8m6P;8IEH0_k(Oj+=vKgu#k+`g*(ORk+c^Y@oL~p9BpGu;7HgF2At(llPE(k5P zQDgh^fxV#}8H5p9k*#@X9)GDx>`=}fnokHU{R+h^61Khzj*Ssx92<5&!I>e2k(xaVfOgY_I92Nf zy$_%N3_s)A>_Pv)QyIT~f0CR3VPe936b0lyNab_%0dCm2*6q1Ysqrn6d9g8_+Q*lU zmIOnU1?)>ibKg&==F-2Q-+t(+!_}`UU_jdDKU&p=|K1P%cFH+AnH&DwZ=9>FVGDe- z`-M!mH?h7JchZhhCMj;xq{Dfc)JZ(Kwi_Cr16Ec`|M45yQ~`4hZ?s$Q!R0&9zB3a8FmYdHl(Y7NRqkmbC>R z`8GIIt*Z^((t2FUFKtR<7%|`+R|gYpY7V({e_GsMK{5jjl}p`f;~V5%rPo|irB`Ve z(rlAG*+2r&h2ugbQx~#Y8XOy1Q$Tl^2oC#wos`BM!eFhBE6r)eu}nf^EqdLT9K66S zkVtuBIQfE?fh4Z%il@I#si6$LMh#`Ht&XmqP_Ut*NY3Eo74Ypa8|x{qcB9-%G$w0v z*&q>0ILZ%`-I^y?09$J(y%}|xoOtvIZR^>RIcdw~xMk~xx#O4M-YDcg)#^U`caSP6 zL5868g>IB#-u-=yfdw2tBh~D-Gqr)Cr!nan>e%QS#g@U-8Ks%ytgc#Bf1m2chgz~^3yaZ&qRRhd5)9Os^?BoS3ZRzd@G*+JE>lu*CdC^)rOp*va3V<#GnukrOAIq!LH9dl(Py<-clK>T=D+($(#4*UTLY#e z(3rZvi<$+Al&$JsQp5N_cWgtV_F|yl^x#qx$rClxC0!);o#|RVLVHeFy?c-v>c}1$ z{h~4rDKMuX&nVHNmZZ8;9NHQjSzG~ilxg0Ry#lH$l$m8QIQ zif9%ASxS7&sH;k=I(Ql;%Q)+hw_rcqf{}y^wx=A)-$2-k9xdBIEHgjoRFIL(17?lQ z9DC2_-C1NDqWDArPa$s3Hd(>_kN8g77_V9J~ zcx&%tzKms)Qp!lGCC8N7$QN!Pq;2XZxZ4;amQb{O>YA!H@UqdP&+Q#PyF4HodAdOG zFeg>-S=!HzHJ}aN&zl(yvVt2w)YB>3#MVq*P83Lr(+k}SIoq7p?y(Qk!aQmK2)s0@ zk2$MG<<4BS3)J-w*&7b78ss`y0U*AJE#XXWG8r6!xhhR)iI-;9P>dLx9f4I?Z9XT@ zHv(#jPSCsKD~y4!EjIBGI3 zC**i{9ME8|Q>-^5Fw&9q-5JnXpgftvXmk|HCv>X4_6WCAs{CS%g79l!6Ao0cQ0D~r zG9r=r6?OtMF*b8`BNvW?J$-ZJ7%v_`vxf)GWO`FDaGf!Zu}vz*G)J|WJb(&X4(k#X znZ!lBWyOrS9MWTZB~6xS>`a_mKE;I~tVcLT{@a#bwx0|Q6U%GKfP96c+sEmM&+xsi zrdVMw_>S4z-KW;SMy)<}t(H}H_kVL0wxXlRed;Y>bBWBonwq`F#J;SCUEmz#a2MtK zdJcM<61O)1lzMUL7AC7fM1uG)Kru|W4G%{b7hkBEGayprHiBL2>}Q zU$(50N>G~S|23;q`j*wvy6J3MT}ZTjO~roND?9u2PPyEsvz-+cR-L87ZwFg?t1%Gh zurId&J`iS>(amtf&nfxINE|ar1~80TM~iK8G#E+${fm@GnMjdXoc2nMNEsy$da0qI zsB7$)d_mJH8)j4IsiaNQbL-K4GriLt0%q8L%T??cw~wLa4p;LK`Wir9Vyfr|3b@{aU|G_LgrZ`yz+AXtp5 zmHx^7*!9Nx@XMW?+wjW>q394_`aPJ3Lo0z%9b#)HYy20YY(+IOZsiI64QzZlzzgo< z*E@#d4^Yt6hZjlbH?W$DSC11rC^?2uYeesySE5|VhwklS5K>~YgikmmaGl4d49$fA zdx5PNBzU1B(i5NP{ZX%rz?k&($*0UFf~JPeM&nw2y?@4|$xd>hV`JI{iCV6KR3&65 zZm>AmpL<`*26z^EihF;6)eZB#GQtH9ur;+~CFNU-9so@v+g8lL%$Ryo{1Ido$_SYNsw>2u^%zp2`_t^hUd@AeP znElCL|4$hZ)_-I`SShvt(!LG}?{H10tYV9)J@GoU>_(*CvCG%5gSb(2&pSiCSFtbB zb(`bnzB*}RHhle^W~G{y#;Vshz=tKns9*`DTxPL{9fDAWLxYcji@|mX&xv|u6lzqr zU@}T;uo-p>qdJrY4`PpoJyu=F50!=C7;>nQCsx^Gax%l z-la`7dyhZ0eT{+0nb ze1oT@!5At65T1^>K9iO7Nt5w8Pl1Z1yP3r1^eiq9-W!6 z>kkX;4Z_7Kg1bdN8e!lbyiA@gwc97d6>ICypRSoeP;pXs1LQ?#z5-s>c;SWu1VL#% zT~ePO(P_J0!s+5a;tAcef#e@y)NpI`25dR4=b({V^hqq{d#0s}<1#f%Ux$((n9+O` zdu>LOohU=-|K^`6oh?G0Y$EDd`wRV;xh2OgsaM-5r4JjY1PpRmFU|x|)!)~FIKYi} zT5?Q$V^8Bo2}2iQjrO56wd-MD`q7SpqkB1=HDSj)r;V`d+&o0(LFxx~6`g3aRK=J! z&B-N!`SJSpAf{2Dy=8!SlW$REjAi8O&DtA0F_djX-&%D3a|GmX+L?gx{1ctZzmtx< z$;rXLmDxGnj1llk>kW{_8Io=aIX#8Ryri&=AMX)tffY}25rx^?|39p=+N4Ntna;d%4d@buE+_;Yp&{i(}N zSk>m{K?oKBby@m26r?kb_a9X>XSa}qZD+Sz$*q}cv3J?P#EM$2s6Iy?_l0d)Aag}s z3mVG7y+4CCjSpw&J}*u9_{Z$*#=k)Bl7Ei71=WH~TNaNJLc!ca|uk*fQE|!#(-sRzq~lD=~E;0v)8<5 zvQ+sj-ISbA&Ao-d>yKT*!k9b~+=d{W9%qUPS*CC3^nOF9EOR!e)(hxu;1@*>8ACdz z(Ji>p*-S7K1}Ww)jcvnou(#n!4NNj(fzgYsgD!}!pPzjg6=OVDMB>P4z_er-g8W04 z#Zucr1O}9x88@5Io`!oS>0aY{5s20Jh`D9!zW7yB*W*YuU_5;Oqu62&;^gTKoo{UG z|Ne0Qo9GmA`zwe0ze49`?fE+@LD0$HG2E+Gd$y6^G2HxL;A6kupM&~C@_h>z4AFV> z4b&ZecWtS198FnBTuE}>iyJHy=Yt~EP7hqTx-Z2(EQY)*LXw{5^t z3uqgVd$SGPD*a&_@W`y_d$SExS%v}O+4=@g7p_j!KjB$>2`UAiHvcC)d(Jnf=dZ2V z&uJ9m|AHsne!{FgqaCI@{2iRKK2E)#FJNZ8zE_@Cw+7op%=FjK8giOJ!=roi5EvcY z6M5bMV^cS_#Ou%duPt5WUL+D3Io7icWx5klbRkfV%;bF^9L|u^G;I_bqE);&B%Wlr zGKE`!hkMQFZUGRUL;p*73Q$M?H9Vhl?Bae8Pfnarp+AP_Re#^Q*mf$yohm}aBL{?T zP&;^KX#2(*xORxaWDTL6_|?bRjCjO|Kk{>>gP#Sj6OJ6ZT}f{fgL8GBi9_*3OT7eK zQf!`~%;)TQqa27Y+a7+W`O81ktG}J?{|wK6%c>ID&#U5;Yh&7<$B*F_A7YCF02A|6_5=tzhSbTN~;_9J& z!XX65=tV^?KZ#EjC|H8uGdccc|8N}hNP~~l$2`zn zX$?KPhiCMo?Zy{;M24Yt>2cy@-SL`og9urC5$!ZM8xjUIK(5!+B062JrRSv;JTd-B zRoewK&+99Ou{uX2$#mu3v|GmKiMW^ek1(e_1=Fb;##xo*=7cf(_5=DbQ{@N9gWnP# zr`+OP5Jra8;}P0hCkCWAkwZI3(O$yjHL~0-qZ~4UkIE1CNLxA0oa3I;uhWVr&>aW9%(u;7Wvnpni zVsrCef6gAPxLknz%84y0#oMUQJWOgdKP?$~bM|+N5N(dvj2(!~=l@9F{Y^iMgpsk0 zlev@opJ%($iN%{V64r z<5aW0Pu_zpc6to^QnqD8em)SiL*80~RG0iY?8n-rtaxOs>h@Lnh@ttdMtO#(L;HC> zde0Nxr|mCt^9R!@s*!SxU#q6%%fIfwgr zXM~$@BUOBGpbfY#JDA?nyECezHW0G%Yf*Yno~g-FRj53C+pSOI1p@(B)C9eAE24!! z0#X|r#KImpEmPv$9EA+dBL>#;Cpzj;K0p>^fNf{3^P>`i%L zug!CG_ik+RR6qe@d!$AkC;dWb%Lv?f9xfF8v>)MlTH73KrFfl)jut>LXR4l-vXeaO zb3RbE(sPnj&Eq}M3&GHQf5*+`0cmYDPE0#tSz`xCvqK)f7u(WUY+zwVZTSj!>yN>y zY(|sY!Adisj!nA$p^zmSj3eDAUEXC?kL}aQ$2ldVPy;eP!K4`&x*YI>cTnaWI21WQ zE?u`*)xslRd4zU;5oV<*%qTVvX^h57&mIQSuu=WeiyL|lE-tEvsBM<1ES<7hj4z`Y zo=n*ts!pguv)}rC*TH@2{(=ZZ9ov6I-QPT}f%EXMWpV*nn*jveNXL5|iuZ$xP*Ta& zNRVzI=!CHVW#CO5g6M+7o@_)pOlM&W>c#gHh_2>)6oPg!!qfVngbLK0S%_&nqr9f0 zIy`M(zP>`QgB+4wQY6>=FF~9ph#!sU&?GXHTV)tzSm^b%Qwg0GIOTfuMwBXZ!zIF( zkz?&@PNJ7}>8st_y3Y{~J;a$h=5=`&+yR$K2qwM!I-ajfn@!93P(!x>p)vSkLbdN= z7_JRhj1fLFh&oylV>OGDI)?pW^{5sA$?QcvJ%au0g=6T?Vf9hOT$ZYZ&_8f1*Dzb{ zR7j3frR*m2g_&C;=$LU0<}lf?J>g)r2pg-x5WHyiA6|b54B724K!(wua$a@_bh3dsUpl% zv$5XgW!2&vG{9JU{SQtYSV#nl%?~5jvwD0Gp9s&Y`LtdD(|eS5oS^ajY!F8?z*G4& zXO^)1r@J^GPUNf4^^>fP@Fn!K{0wWuSA2>7%zpWJx zPzrsaX-+`9bY8NVhdU0`-OPiVO$`$2vmP=M_IXSeV#E-^Vvw=ItoV*1boG@On<^0M zPI!Eey(RO=3^2QfgXxe`T)c9t9kQ{mrdpiaw?s6lhBhf8X5s5?bZ}fv@hkw~p%tj* zM9b+wXI*~uQ3vyM0!~iLLLhF_1mXG4lRyEAoFUv>ebAixG+|Bhxm@% zjDtdNrUPfz+G>8jx}rxfRf6<}Q>b+ThXIW)n;Xb{L=Uz}c4ZQ*1?lrAdeC1AGayy4 zT<~a&6DKl!xXZft2^QN3^*R;N$13m(5De$ira+cPO+0^6cGnaQy36GUF{9&S$88Wsk}<5e9OvU~Twe-g3-N zFSGR#s8yA>O^%F!@1Hda;y})VgzqSGf&q&91nykiw31&Vh~=arXcf8#m@j*>)ym_G zoB3x4qu@D=hN>WFP(U|Gm3NKeg+p_k=RJf@A0R#14bLXbq7y6N3$x;8XlYOfQA$13c)Go8t)y= z8n5H&ugB*Wm<&u*DuaFb@dBcc&e|g4hji%3B+4X_QCUqG@#Dn)rJEog=+~6{Y7Fi2 zU5=&tjdZ3^#l~i~-0oAGX?j0GlHv|RnJF%6hBbd$`V+Dk?;YgW%vN`MHN>EfqKu&r zOmbM_HrIFJDV>Ig5|-&T!X0QVEsQ^4u)_$lA1e;jYPWQ^2)2#V>K51kEGmnq?P9i; z`h49zJA7f{=W{Y%$dEt94VaG-RqGG}oU_r#83(%k3|42>)SnuJJxI$fDn^yZJgGGN zfvx0V&XHVi8g1(cFN0--#TTE#L0K>sAKW8hnyrlz=PK!!c}A4!0`UALJw6Za%S5K) z06mgOmx}E_bV%+z z$AWlCwOU}R+sV7@UXw<}v=O zImPLNZf2m;K%ZO7`nEsuR=5ef!Ms+izccWLZTh@l`Q=(7CoX%#l`7bmTXdtJbt+bb zn>Q89?ED~+br3LhWEsOtj`z_Ml`gtfut~?`o518%AaD6LB1J*^5B!hijREWWm5&&# z1&7?`(2=BG358@u1PZR-`V0L$D z)%%n0^JA>INg6T+GY&^PgE+bYEVox&x}iqu5$^N-6PO8BKBBeDbY9LOXP^sEr>=Bb zM_q~%P;d!yrOx{=HXvH_#39r`@MZeIO{mhRoXG_6W#``T8npJTiIT#hSRr_Gl759` zC5e|0HYR#akt|b8#H=iLx;C7uM;+ z!`Umy8#{*u!~Wp{I0e!F>E!xXA?j~NCxDaC`Om_*66F<}DF!TFn`A()e=H-!mg|=7 z0mP7=;5R@-uOzY}i1~L(?Z$#74~tYvdzfZ$TVSy?in!g_)cN}#^cw1O7MKOHOM-t8*zm!xQg%v>ZRdW54Sp1_5_xk+$Y?kKoGPY2Ttd zrsOlV)mU|C*VFWN%`EwS&2*MmOsRgqNhVCcV$NG&!n`p>wW6f zV8IOryk}M_QJ5pdbXTY%7%WWwzGqsR6G?Wx-809+Lr?SzwFy#JXz8zY6k-+R)a`xZ zvso|{x+MTJjE#ohF<8~Od{^1*^L`j}h@^D617hu)LNZzMcaM5&?I;bCx5%xKuI-AR zr9ir-Ue6|x*zLp8g0j`Nxb zoW^Ad7C$A%B!*dwbY~Ae#t)$AW z!ZB_lU$53Kd6aWPRRV8nin&WMqOgEH%Zy39`wIGoQPXgv^|$E6?*C1U{&qwDx%R8B zIHIbcy;?UW%hV=g!1`1N5yeD6kXlbjQWA~J=f4M~R0jDp|1;T%aOH#~8KHF_mbv*5 zY-=tAuD?GTl-Uc-S>7~7;li?a;==!HJNql>jjQb>J=V`2Lgt3MWyiCJRL8OB700{V zPw8u*bW6;;RzaQpMddh8JJe&<;}y!}}7!QNQ|L4nU5 zbuWNl&@&)-oOnW92!|XwhUz{QYgAfWwVz!sVTJ|fYKERkixexUVL(ace4>6b>{3A4 z*lYK#6=o1l2nf}z;ntwDn0}aBRl_5w7=kQ`L}8`Hrnij+lvEP;I_DmSa|$1iy6qSY zCY4_rx=@{khI`tOvf4Zt;wr^i#;)db#42YV?t1q*Dq)xH-+RMU3v$s57t|e|~$pnUp+;eSDe)D;}qDNj;us^z#+Im1DEJMc16g=NjH%%mNN`^lhst{d$Q?k zHoz|j)-$ysmo)>nDy$DbL&XZgR1idtq^5@tw76OzzxIPDke8%WfP z=EO(gh)$E3E9SCYpPEN?w;q_fW9H!kP);!^_Qiw!KFZz_e+%=7@AUP=ky^|`|Hxb| zz$>qNsA};J1L5%dtK(M;$@wh0DZz@H5$@G$wOC`>cv32+^(@S;a;anTc0%n06T8eqnxis;1+i?@Q%+9IlSQPi{CsZ6keDdVaocapOp@fAoq%>5$aJA{85P60Sp!xRZ zs|Mu@3mat3n%|6@At{7=7uc$5%|Mu|qg6p;TZJ{2QnIv!m#W^xd4Px(719Yg${tN* z;i&8(TdVk^%~Vg6E>p@h+@F2Mw9jY&Y~NTgmZ;g565j$0H&#V!$WcPYmq<>C7&n=o;GO zN_lp0><{YRp-inE$;WbA+|A$5>>)m_)7Weo{t_QbufH_)3jTaf-S>5!-5nG>?ZV!K z%U^c$Yp1R_@?zdWUT7opeDBj_ucreB@4PsrbhnK|F?{GIoC$|}fLd9=Ue1P`dlrbO zJHnX$)Uu;Cir^Vs9>ie^Ob@Cr&z;>Tz5r4}tI{eG;bj~t!R9Yl8Yt_=Xjodv(Z6=~ zaOjU<{9b>TzWJ8w*-Haw_2>WSUjLgrg#fT#`7hS`zZB_p98J*ogB6fwj^7&L-xO&W zLMX~_)04}#DKb?mmH*yK*hl(bt%SeZO@Fr%&dRguum23>98Okm-$aw$iVIv)X96-c zW*J5q!x5e&vD3g-!XCwF!mDXuyXgTyc@x-52z>@`d($6fTaR$Y+CbjrY&E=JdW~HO zKetrzfbZJa>9YJ~O{H~ZuhDaCH|TElVX}_f$D!IOwk5OSuoRfaY{v8p`7Nv19%L?9 z!O9`j$AK++%F~eY+foD5n3`{C%zsGIRmp!!(j;C&lxkPwk=>X$OO*!aNrwAHcF`$Fel2bJoSANsQSS@vtPfy z=&N&~p_naH9WB49e%8YQc~#`5ycxErJ~*}lP0`L?9I~jgjoHF@oD#UK<5j2!!T`)b zzAF-$Q1|Wqw)jrU#}yFl^744|YBS^Co{6^Ko{7=%gy0ZI4ykNbr*;+-GZT&guMfW> znx{5aFZmP+`hf1GH`%XaW653nhr?u^PzT}em*NhZGva4>Y=E3$F;G_-PH?8&)Cu!8 zF*H|u5jX4_j-~Gp+bRTV(m|GyF-MWFp}#e0AM5~4KHx_2pUX}ECPIOHjqzWtcQL;U z!24dOFyiQjdT@hWextG*Uq=XkV7R9-Ehw9Nhr(!-*Zl;a7vFh*|P+@W%p#q^F>lj4b3wBb~;5Cg!$ zihP=PaZ7CiZobc&BX@#%y)&a(UA(&9sDtARK|E>_YmT~)oU`Z9N<*Q%;?^w@bNKgvj=X`&)64hMUD)OJwC>YXE&8%UxUkdN9ANZX?>1(Uc} zw~uG9SK3*vof;+V)M^TDpmwm7dhff>7!Cz_$gYgkKn2q+$!@t15W>yDO1lm*vAI`R z4+6fG%(9gFYm-_d05sI z9Fo}@C4kFb@gbG97__AGyQfirF7u6 zNi$lLa7QU*`jfdqPW+ho;RR_yj<9{0Ape?>N+yjgC=3UL#e%Z7rrA5EH8Xsp3whRI zxH3tBcGhjUX+Eey*p~L}GPBvpao3#o4E8ac2*{(mf~y&F&TZZwwf(-yeQrL`wF6?> z^FJ!te^V+HvUU7x=>ESg6)s%+o^lD9w0mY|Qm9d@K-~K9C7sls?|if5%&5|Ai2Bw* z1;^)VAR};HV&5t@qVs1vSJ>#4%lA8l))AUwW8QDxA{OBW#Ao;SUKJ|F$AP)`4|nKL z{&Ao?l!SES4(-i!P~HAid7zLPuIxD_Mctx-N*!v1vL6w=-Vyk#2S|#GL)o97j(V7= zTDE;{ZUvd|DhvkQ)gCtN0G3H-eJ2G>1_HgVOxw642tpguYY=d;waOhLIL_biHJyYG zrxzD7^~Jg;H|?wRAei*$ZI9~5dQ#6JLGGN<%wx~R6FNXJCH)WsrQPUNS|c^>>8H8) zOen&H6Ewp`ixz;TMott>YFweu?a{MqBmLY$j3~x2z)~YRLvUuerq|Sd`5HDJw8Am^ zrml8&xPY%s%M_fIQpxSOPrqyFL*W|8Q5T#gqe=K0go(mp;5g)vzR+WR8?59;1B zstzpM8V&9eB)Ge~ySux)yAw1J+#P}j3r--oySr;}x8NG!9jH`SceUO6?)~#Ja>n2< zoVC|pd#))3!{lgnSsj_*4kg0!OB=wG4e!D~P!#iDF`M>o5E)+UWQ@QW2x6UlEp*PDc~ zibdxZ9NO!EnfT>b6OH$Jdn-D$*amF?o@Lp*Yt#z*wSHsDdJ-V2JYgbUF)eKUm4#QQxv z<>-*MFlNCoRISzod{;4-rpfp}s9IA0f~rNmApgpRsW~M+r)RMFoZ4rD0=qnr3!d2r zh649GwJlB*1Bis2n{&rH77Dm&Vsb{xdjK=(0}g7guK0nxXTj$mH~=$g3E(p86~tB_ z38_YU*A%QQY^VMf8F$MDkz-lavvu}kw*3I4s|{kCY0fd(JO~V3;>Iq{6x|n(LgKem28;RpuV`xH#sk`bpRj| z?$08`x`L?@QOprO|GME?Wo)EwAEaeHjP!5Nl)QP-O&eKk0EOxukfCsGOI8zWqdk{_m zA6rm0m2(Nfab69&fFzR6O{B;D9?WxKP|7%xdf|geEw^1eBLSkWfQdk@gt8Q7Um4q0 zrf?aPbTuMug@9mV?-0L2_+7GXWtcwF495VlPZSxnuF2F$YPu=97h@WsT ztofuJ@84MS-{#)_3u+zO)gRsD)spAmbrX@7e)6|&Ld}A~m}aZRILw?tqzAC%xzr7R zr6pU1>ngcZzS5E@f1}oEAHg(HH5^|*ly6?Nj(=~`X3x2q1z6LAMwJ1q>1F0t_50z4 z=^!z}Y7`^=TC$@}t7v#w5H;b$$gKyoa;bPKHk0@|BpN;FpsogOp7V4|G!8rN zbR5Vc$c(Jl)V9gbY^V_$hC@W9D2VLuY025pw(G#q;HpBKm_k?XGo~px8D}N4nbj20 zWt#;Il+HHQLRZ*H8S4YalWl;23;3?{SYkg_9$mCnAA!H?CPMCl)BtPxFn}SCPrNL- z0-fxnXxYW3utyBQkOw9+FQf7Uc8eQ@^aK-xaeF84mx&zIf=?6aG`>I&!h96zUl`CZ zb{&F5566L+Qu05oQ=c>30=+NjYDomi2`0QrqKh#NK`^oE*&VKox9I$VCQF!8G`y<=&`*2(NLM68}ksWkOZ zpeORpqxXrCmGkc}u2zPRUVDkt(VTp5Z7>c(6Ye!+q7=^lWthCJTQBHtuQX~l!(?pZ zNM~pm-WKtiw3V?JMubVJjW%(Hb2)P7LVq_CK~^50S|^)2;GeIUp5m+p5WNOrE9AX=C}#zb8K1Dv_p<;KKVS5sbfiHR@?geenE7r zDSfe}-vxaB{qXS@-!F<5zh`m*hQya(Ri1sTBlRWC8eW0r>Dj>SJy8@kKys0P^vRTi zwUQ~)rva2lN{9T{#E~;oYDoW(@a4V%j$Oz2o9H>VH#VhB{RSO9gh|-bIMiI~2ISZh zBqIz$wF?JKTe6ptWAghF+gT**?a}4k`1pCVQ<;$WgmJZ5{v1qk3_?u>xddo#omh9v zQwD`9!$Jn4o`9u1cQ@lsUFdlPz4mF#zVBvy3&x12~lK&!ylC;tT*uGY# zgdjoNW0xjX1TlgH_@-%7aa3YqwQi2>Nzh!R z&KZ~&Ov=o-&gbiw|H4B)D&I%JGy5xryRTTcl>cTz=NW0nYOfqZ$qu-PbB;VvW zr?sG0xk>1sf*@xmH|oK^N(#)f;_pg!cx#_dn(izX%IO%#YWdlWY%&y< z4#|5*A{FzZf5Mk8Q0cPiMGr*>&_fM=dF||A57KlL>De!x-9AawYVU)^@c6Jj{2lu( z!AoZcXi9ja!01Ff0Gw(6uDXkQ#O*w}V1J?ENA-^yD`NLpjIdd~>WOUuDGY~--A&jJ z!@ZN`KVy4?K2g17j;H{}#J@SMy*839y%E;`o?P@7nW-`^*3K68*1wpkFHUPO?VZXk zoe=U@dtXL3%&+7Z4AeB=OLhwEY0+`46Wdb5phAXurTDmIMkfC1@1uRYOI#n2kCf#* zML&$Z(E_T)7~CBsck7V1tOB#0nV`mJ8v!!`#g zXv#0LPkUIHJ(jy#!C0n~Xq^;?Hex(nnB*q`OSaPNX^Aoy%TzcMxG$}CgT5tAIiM8x;uroKRlR{uLqtGs%5C-Na;JMC-yAg9rp&PR7@>DZEw{Lpn z8*ikXB{+dHTtZ`139;n6p)j(2FQKpFl9LCLF1Bb@`&HYp zcJ-E9(wpRrigfLn?BK4NPqGDcYo|R%t$lv`X3*pq{=3uKUo_2?uyr+YbovzsQ>Hxh z8-r5}uAD#~UtTwVeS$bpGmth6VALqDOaWY!zaW<`!Ia1pb>slh1EprYVQqf*0twV_ za^?kyXio?3j%u%Zo_uQf1-zCT_VmJ*FR8ajYNWU4L_*tY{vr-1p_}3YI9WzPUNy6Z zu;?;1r|$NfKrlJrWjxHGE_AQPE}^6ZQzs+xR#Nay!O~BhUA6Micy0 zM+B-{I((!Wwqps70Wwf*6u#@HYiadScv1whf^UxU=LRU^`|TZGJjc0R%Q2i?#Lgzm zphcX8<1l$d4}UR8qH8YB2p*hZL!u$vZ)-18AzELM=?_qcy-*p8)cw2+4TggCHDYTR z6$qAT901G;GX#IKf!p<%>z1}Yd>f%xa}y}`Fwc9>+8b#b@hs0LW@F~giF5g5+P9`_ zO%?(J?1$xkd=MpP3jD*9?yULI-W|12)c)<%zdTW!$R*mj35tMy~ zp^ltjSn>}Tfs^b~RLRstTBR?OU_3T9rWw*Mu9SlQ66R+ynMM!l!@rVl(;!KmC^% zn=RH$loqPsA5mJrDb@ZlO6&h=X_beakH?f3o=+;YQ?!%>I|aAhuO`q&(!%yHlxl^n z+IGR=JO%)Zx9>iyE?z5Wjh@jkVwWp-gS#2+l{Jnytp-g#ZW#nzh%JCfKC65{B%c(* zh^dx`C4M#L_{v8^3LuZAmq%|ga#~xK80*K^;iPT|0Y$i*` z;SD3`d@uw=^3Cjv%OL?G`PTV=N!7IF9D|6l8(*br<~vDP?zN>Q6$z%w$%&`50I3=y zK&l1-kgCy?e$c89@%MYt0#$fShcOLDoZPussVzDujpX8)C?74F2U~i`djygFCZyzp zl>!JU%RHKCy&mI|rh5(DIe9q_fxOcor`=%|GfFqR98&EkUn2PcN=m=X3~@5XX7SfZ zzF{J<=N5pH^2du-t>q7`8uaxiT}5`G7p)qAd^|f2G?kM5X&w9A;Z*2Ft2XrTD)f!; zhj|tH?m7?*N@T%<1*bezf>$+1U$Oysbdi;mzEBKCv-u%z9M_*B^L6fsBH@_STJgD} zN^l8}Da%C^%f+79d|vmeWasx>|9r9inPvPJgPW9o^Bn&tyOcyFtruy~)0gkZor)GB zBFzS|T3Xag{+N+r3@AuQ{2-E(r_A4@j$@8(tD1T+jUw9kbI%sCKJzAq_=zF=CY&89 zN-+yC$m|YpdnG%WUOz{5Z_fSZD? z$q3UIr`g_%6pE zR%UStrcBh&l0Z~ry>)L7GMU~o^}G<|zH!P~rjq<4@FtGfl$KXo-`l=Wc3PtRju4_~ z|DaForVf$oJFzNZdaV&NUrfHcm5gv=95$NNd%~J4Aob@igkA0pm%5z!6&?B#amXfP z#0mHX^&A(UeQqX^K3HCEqd>sGU2^1d$7)qS>Zc$6*+yo`$0oD>-ssMYxB1-AeH&R! zk;U5rBYgQn&0ONEdNt-H?G%Be3>}RLE4?7zNBAJ#dw!HK=Wyohslm_vZAG94 zJ%QiWg*rTHNWLYvfjv64A1Kcw2pL&TyP+snB5nZ)=MFJa^IcRtV+NQCoSe7N zD($o)R^?+6&lSkMTXv%PtmxR20Ubmrkh@GF+w@Q!dOKI~f%l%->4&02Gj`{Wr*T}U zhVnJ#c?HpA4q56JzSnVs%2oxd4balh|G_ZqfB9AcXgh5fenC+GvZXgdy(;6G|Bi=X zEq2XG`HwCAH62l;U1lH ziX*QDqDK+b+s2bS9)wz7-94V7JTF^2?@vYG{G=`Sg(Fe5y?Tc%lD zO*`xWB0?CHqZ>fm^cxW&_TFY2ED4&sGIk4Ag56mlZ2c~D;#J-`5o17cRY+^Ku7f_# zkeh9|27iuuf~o$|VvP_Qb5_VG(crNj)hq>T_2Te4vto~0tB-H6e*WqVe#TkZBdB01 z+c)@Wi4T@aOc0pl!Sv(90SUksy62ZIG|s=Yg|2>2n9+YqIANBVS5z5-{dl9uF4D$@ z5AyDsF%rB?Iu&DN;T)|(?lP_u1Jfzi0m#gP8U7Dj=-&boJwE&!TWCD1@!$2wpf4~K zAZ0boJ=rMhPJJ;Ekg{s9GiYW^=1@bFr_)m-K6ust+)MXDZR8d_ng8dO{^t_?i=f8~ zRpy^6^zZUJfAenmd!|fc)ju<3UMuvk=6A+P9snv-u>nw_2Y?EdR-!zk+W=2;hCh|F&}JkWv7sK6BSjj{)*{v&rCJJeks?-+3|zuRIxsjbA9~v$zoinOYlQ zp zvm`DeeXd^5m#>)<3paS`R?+>|>_^X)!MPumvZ#32+i zJ#iZI=Ge{L1>~pgjQRT9!L=g_;$)!DopC~Ak~&KpN{TU^5LVnr-ndZf$FBQDkx(;vb)LqozwIi3&9b=F?lOYYGrv{rQUktk-qu3JxR0XImu@P* z>>E-=?C0lKpN5`hEh>W~=2jcEk?>6lk}FgJ-C)C>gX#l~`{aLrMF-Q}+oD1-uIjAK zp;b~U{_Izy_~lbnj+xfB$&i~nwoGrQOE5eZjfW3~nF@`k&W`n0#j|C6waU(`_4IAc z?E*jKty#-*9L~%%Di0DeNE|LX-Fjg|!=)q@T>>E*E!BozSEfK8SD&<5wfrB}8rfAM z7jsOHaM(3lalm&Ng9Cf=oKkfC#dJ2Q+NkVp@=ihpgvlB01cY_kb1-H7!J`{NH747G zNm_$A2V2nrq1;oHOi@}exX@nl7VWtzW;QbSaihuwG2gvq!?X3Ox>D&bBI&KV;R9(< zQaG8c8cmiMAw9q$Aiz>6 zRv%Fa6B`5zoxURUTTmDfTBaXmCi*D`t9$)`;u|^rTNDkNai0`kCn~JTFGK3L&u$JW zU4dPwk~5DH@9Mq3O*|L3-cp11$_iBOnlD(4+Rw0eHmuDkTZ~UDWojX_i$yoMdkJOk zMi0+g$z(=u%U)Y#wJYu=><_pGuM8-+ag7M^>|eYCUY16HMna}Ql)DE3 z;;Cbrv#Fgy{L5oG&J?@j)Yy{+l8ScmfzOU2er#vaUYQSW9_Ya{X zf4;hf|C%c8_q@q}dXD9*tiG7gKBeD^9hh1y+Vof({iM{HjBB)jVRk;`Ooa;@WaTVG z+1{UZnQ9_-HQ}1M1~)%t!_Q^_4N+Sw3Y0B#7u<*j=H=4hgdZjmoj3s(UfsI zBv_gVF>UgS5KPoR_SVyK^4q9p{d_(Cbrskji`Pe~_#H^ergD$3q*m zh5Bl+x>$e6IT1=9{g(H7%XT>+)-xAPtmDWRzvm-L)Mn87{N<(dq}EJcU3KT6q}Q9f?egn=)2;c88e)Bh7U@!Cs!Ke<(nqDW7zH`?i?zTu26k%N3A6T71QQF zo--w)$U03U8+~BHuF`=>4-~nh$n4|r=t;vHrxW7fRag`{P?VryqdXYL$dl4+z~J){ zshd`8wBCOh_c_XqjsZQzV8BCsbV~0-lgQ)H44Dl_u>!ysp}bLO_HQjbvbw^ni?lJi zrKX)pA-;)|X-l7bf_=TdeH786K7`^sFD%rF;~Y?7WKg1-+FJdZlEiEL$yj4RvpCVl zvB=_+jFg?KqiR&=;B8{_(|lom*^#D9jiVLI$l%w1){18KsUhFdVy z!-Q_SIY~wdQ{?hPd`hXxKMnU1caRASHsa)-qB=nKYIxAa;)Cyrw%}um6qdT$C-PKB zz3&jaAn2{8Zy4%>k0u<_v;#UEveesRI)GyF;(G`*a1GwIku*fPZeBWNNHHoub=WWp zc;k$b;32jy%%|m|-@XEg?H@rWzW`iqE&d~r_*X}I0Fd~fMtU8^KjVm0eg8)zy<*fP zfc&2C7!Dx6ABzWl`r^1%@_99B1#6;qK+(K0sY0t$X`PeR)LHKC_0efxNmiP`{+ zqsATtZ%!Q6As;fndab}=OHs|OVV8>qnjmpT{LbI}Q#=}6d{avOE_C0>$< zU}x+s=qjAo2Cja03*03WWvW|luQC=2OiYI!`iA+15CM4#y!idHXh(Ynw`#{l{f8XC zrtHez_Gopxpaq2_y*jsi5jMbnOhh!lJleG|r>paK?)wSA@e06wH@OHpy^;dh1%~Z8 zLQOIR*dc!){1EdfE^94_ z9c-$fDxv^bROIYlT)`I;pDx$s?L!*ytmvs8#C?T=)~C=*?voLjOm!mM|6oyd49vVx z-)G_f%%VCYWc~QxNBX~7pMVYSf2z;_|2#Qcl@DPTfZY5M6^fG&VUK8dnA3392Y}`r z`8^RNw?VgTM1Y8;!bQEn*GC%XF9KwG;k%YiKfi2XE=l%R%+IYa=;ZBXbV<>^-jB3DY*AcO=@BF@Ck$B^2v4W3DZ$ymCjte!MO zkNW<_kZoj>6&n0xs}h9fwJNwHn@bJ34VxKha)h_VrmtEj5l>3)mAWlh# z_Y2D1%-yK%?+m-X1p2xB#gGjHFKWs!UNNB%hs+}P#%#_e+{F_$tjv&RHXTm1c0HM~~(q{Jy?j_B@{?C5uqgw-u!YBQ z1;qKMmHa>o-Pi(VRW?3%7w!GQ7B1i+An5LBs;bJ=D0{rSdIDNQXMq3%5I{PLBU!Kx zSy|Cbm5TCsjr!-Xbb>lfoPRJSa4Fu+Sn}% zaRs&LsQ~;L?81fh6eJ#?m@u09r!JHvd}DK^!{yVn!<0-D!XW?wS{j~7If=0>>?l(4 zFeyZ!ofqmUVLFT~NwYqia1Fb72glMaLb-5E3RudbB!^n+#0g~DBMDNkYMM%sa_1K} z4Vr(T4gYyB!Tmp)gkSgUt_F@42F@n`XwP61&HxQ?K@r~VODRk&V;k>{hRnpzLxzzm z`SFbyi?u242)sEp5aLwcaFVNM*l5kW^()&4kR*d9tu`%(4Tz0%b7ELC-RabiO zPrlJwUZ3HBwS;3Rm{Lc!p{)E(!lYELLk(13frYjNjg)V8w0(=PG8)QlW0o5Pd;yfJ zC}{bnQ{o^MCN8&?3AY#aL2hXCT4EUROQL4mZ>G->lYaXSI6!BBvGI=*`tt$$pP_7m7XR|}n1pk|chVyYn+fsqi}YZ8 zHVAYCLCMcw0}VGJiNeMri6SW%?Eqp&AuRf2xMPubbJx1^W^^8f9J&-r1BGkF+k@HOvJ!zXnakvw6-I`)57~77 z-tmGD!y3|}l%{V+yv3&4>ww?(#c|)rj(7ZM^bCdGP_2uXu`#s&uG`etzA{0mS9SbhKSgBeP?4Z{+lmZ%ugx!nh$Q3X9`JjM>q%8_#)9 zO@Y8x)qo`}2=a}^hG6k-gs7h?h)fu#)GX<7cph4FB1TFbr%;DhTE{tW?kz=RCYeT1 z_D`jBq9q2_cYA<D0%{&pQ5!o-OZr;vWo~!nTIZ%aYgDiwuiP?KdMet%g&_{)s<2=3EJFyY1iA6#8`Mm%+&Z}0A4K5*6B5=H|Iqb(0y z7TQ%nT!3+$oHH0?<=CL^MC+E8iT1Q6T8XJ|e#-OW!rwFcklq8C9qDd`>C1Ju zF3QDw9Na-=*V8N){`k@Vw&NfOknIc{OB@$n>#5+i7DBY{G3k)ofe(#rhOhXeoJjC( z1QMS^RE|E1D2N_t=*1B&im8|C~@cu`*_hkOOr(e*na2 z{8P5`ROF5nt!F;-f-jz&9jY4`3zB?aF~#1JLWW1^+6N9&*YWyk&M<9h)-ajl zeN&~fngY`FlVuI74kOVN3ca|Jz)GqBHWrV}hAk4{=w($cFgh{u{5*XhqTS%t8Gh}` zjio3btUMA@Cb6E7QV}$muw`6aGxY>t^$2&*wN>NrKy@h=cFo#HVJ$Ku&lQ;67F-^= zTe{p$_+2nGwW8=MIB|4X5@Oe$H(sv`Y;^m!A*E7V@RQorF(92gcjt8>jEF+n{t`s% z^be!JpHXGe|54NWj}^!C+iNIaY2r7JRqJmKaJ8Z(6UtgOf`rpGTM9Ijwf6T0+p_p2P2g? znY)wgPxQc{vFT7Vyk2T9L55W<`u3cra*V@QiAiHqXY##YZ|QTy%j`g-!MRmG@xgIQ z6jFnr7xR>vEQi+D#1Ue7BSY}=Z4oB4(r;Ey%;H@TTR&)D?DbO~;-&71r&VsmUe%4B z9tw-N=0C<{BZ(IeAQM`$d6u#HmUDzPh$l=u1wl6|NrTM;MdIQd>sv*3EU{Wp8>^WN zqWPFLw~ehjaNd4-7h5R_F=mXE%7a!{Tp!7$QeQ}4`V=2PZ4tOWQ0mq}pH*~0R1Wgo zW3Lw$uznn&q9+;KTRAQ08i5^|Ag@Svy}vamGhA^whjUmZp(1$a-akv8w%-B$4%op7|qQ%XvZ`m~VG4Pkdu-&?yq9df6 zyYRd89v(;{11m7bC|*aJ;85=|5d_oJ>#zE{MmYk1P#**nV2R>%o(?_m)u`d<5pXL& zK!R)z5WQ5|n}1-({CVh<{$Es@lD)Ns?Vnz8WojDs$R^m&Hc_@sr6@6ueOlsamek~` zFyt|U9|?-`P@pZplP> z^K!)2^HTI(C6zIhB9O#$y=hxLYx8;Dd}zHpoU(XBj1G!7tDbe z<#wE6Qx>ddz5qY8oU^ps=j=e${tbl5Wk{9~BRo|-j2o4@zbDG&hAvomHbwd&va+P8 z=FdIodj@>nkB0Lx48)ru5fPxzZ>Jm`k+_42klw**ePWmz#MBHD;zH=7_QWrRvnmqc zN&oguV`wXZJ8e?T{6}x z$gBvtXsxM$vQ-6hPJXt&ijg`KL6v~W=JMvS)|OK_>!{O&CO#@dj^n+SU5V(Nb&H0gn~c4t(wLf7oMvj(i|AkH=J z3sB~eYL#nLwse{2Of&{clLiuMhboj|Hw$64MBt<3$>cF{v3) zrA3XG3k*?=D9d|UC~5mp8Ka8o@esu89}Qy_97xLJDjJ|!kl&L{w8=3+TtesKq4e?+ zUvkrK8lXn6DWJ{~m2Qw)tDd3DiqF^3hf)TVCZE-Zk)7s+71%3^TP9Wrx8se^cgd5h?#E%6 zs|YeRRNZLSEm}-RfS#r(i6!U#2V1F_@8z+3$rXg?HW4El9X4)R1v{Bqg{RJ1U|$8p zGL5!k?9=$rBg5?Mbt!0nv=G-V)v}7ZQE10=##Kypg7SGb&g;E(9;i&utsstVrE)bgKE=XA@X?q#v-Wv&^cXYr&ivU0VI zAw$DNduyZro`Zm@$##pd(N=`cTrcKHWsmH8pcAB%|8X8`@((9#8RZW=oqjM=WEzBO z=b(oIZ<0I0O>#gl^qZs;WN(HVhwX5P6|(DXL7tz4;pTwlm}U5(y}=sptf*7{3(SC5 zsreR=|D+#Bzq;e^bVd3If9Ih9KC3m_+oE zrJrzkXC^E+q$1M|KUy~8wAmZaOzaM~Ym+@l^rSgQA2k&bSXkzTdwb4d1SRRxI;DHE(<|2AOhQh7LE~%; zEZG*OIcV|2rkouNq*TGG@Cek8RexA(XAN*o@ZQRwEpgjw3Ro33rM(g!>ljDfRr8U% z?r86U9?l5iH}aujf+gRCvx=VZp!wRiVz9d~%uNGG)Exloj%w2zstH5+SbxF?F zRF^j<4;@us_DUZ`?9>da?`hVWgF2^S4gghXv)yD@C6;r~t9yQOfu`~d(8-1>rG(KG z=xtxBK1Lxr!x7!1IJmVPKnmQ0F5@{-Dg7)+V`le-j~Fd&HiwZ<(W1kOnK^1^LLcMv z8ukZ&G~f^z+V4kJr!C<59byrnI)VecIn!%P=txpnUNoEPOi?u^X|qhpAEFCK`l@$f zZM#5oQnmumkO^5vmR2<`*J0**N!c<*rOYEY-sKE&jE^iPh;JVlNlo z?`zb1d&(}?D#Ui~&_+QAm#21&jMR)v*9H!Lp>{ocjG}$clz&`1*HM_)0ycuOrSq@E z;R-{7mq)I&JeIEQ)AkJ>Y~U5^m%CgXi#X8(oNOBCA|vY~=Zgdp>|+rEo}N>f;p9l4 z9~P_o8iqc(A*%zo(a;QjaStH#+oUjd6eq1wzONVMNRZs+SHLn49P#g;Q-2=G16to=bGkv=BDIAT=B`H{1`~VjpWg=20@+lAabX}r%dgq zvbUp_x%0RMa1nUdD^5Q+Jbl`nTz@?7c7cCDR|R$lKYIg@KhZ%#F*F3E%`aIP-svtP z#QBD=*La|xk#;D6I@x$2Oj&k|4u%Dz9YuHMvek5g2*_i#*@ zuwWk9mZKvYU_+(sEMPWjo6rfsc;}gm{a9s5$%j!I#D`)2I=iJ|+v#eb1Iv5A_C6G# z6z0z46zR(?7N>mjct2ZBhgC(g;+$Usmdk81pOoGrHKS2sPM1->c%fjlKu(=9Ay}hb zu4*~)ZJiocG%`#o)NHtES$xBrL|Ln@Y zfqISwt_pflEkaSJG;re)X`Y35c@>f;Xd#D%&1@0&JEO1xv+d$6^Z+W;?);U%Qr$?^ zBUfIqt%jGP7d9B(kMvn+DHY~jn|O)SzcRy}KH5HhKRTgeCite2qzVOZq9Cvf?VYYAqe9MXxYSE|yjASdq)$rY z*S#)Bc@ipO)HCh?syEKypUauqBY+cZFE1n@_V!EEuDyC62P~ENk@%DIuz`4AGqqU7 z=dRA2C=y|pgaA&uR?wbE0Qw-LAqJ)bM#nu_fA=PRLYl>vT@f{3;$vSW47{my@^2{9Q==(R1eB0QAMM!dl8% zFm_Y`#5>ez)an=&-*Y`728MPeJ%}GVoXy>f*=Jq#u z9>t~}MyZ5F#ikQ0#Amnaze{3N5u5BzS|znU`{{smTS`6`% zr_!dn0qG6g&&zMIw;Q4hetgE^J;_4&Di8|0ETF|cc`M!orsv-NeI|tNr_!xgY%fkV z0%X}ecmVu^t-%~b`NnPo?s_sFdI3oCxF7X3A(`)+Etzuw<3Y$BH7mQ@Nydpi2ysnu zBXdJ>!yfBi;(-En=c^zB$6Hu?R5P(cofRKNZX~&=?|#?0Nia>?EKKE}a90#6Om-x& z`=HK6bf%SVoLVPFd2aYKgvZJln&F?Fw^%uEK?5)%%GN`r?tOktNnQq+BSlSZrsZBT-Z`AhrN^CJyK!;a=e8d9ch;2rOF3y;J@ zTsa65WJ#v2>M~7p0_Qn>`gdC(T_Zo;zNy>mAZ@%;l!yHzi@Ln-%UV+9v4BP9Y+I|1 zCgn>~ndU1B($QLJYIoB6LZ`W<@y@!+VB-R_vMP%*r|=qFG~gchAfkc&+ZM575)@D>fn61BdTrZl=7T&+2MwBsps*w+FeuwF- zup)|MfJRHna`l#$tnki2>xv#lwja+!Bf0H4Y)Qu|;aweA=!bCc#_)dfW}>YKxG97)6j{;lWEx6cEFAI%{p_1v z>VWgg8nPpLR#pGbtT>7Y-A=dnKqv9t=(26Yx~cE{XX;yT>C@*Rg`e-#>c`gH0`B^5 z!F}YMpR#9EGtzy@zV~u;HK9q|%`0O3h+^>UvFT&`9&zSL(&nt|(6%jLN$v%qQ);JH zf5vl56j@j4iSzKq*S}zP+?#DVgn9at+jvbB?g|ghF3VBdLr2p6Q=rBZmD3~J{iU1g z5#Hrqmi30O-J2!(l42oUmAa^|WbLxt-%_vOA;81N6iM#_lGfxP%g>NQPecW9I!J;OC#AKtUjvhqXyT;y*dy@{iv~ z_}A9fswi}eQ6v_VPgsfv5~`NoTH2_o%^gH9&dl)9HdWW~-B(?6xzRGkgMucPYB-(n z>>jm@JzZZc-#p*+QoM1w%>|j6-)^^sEu2>hS+Z{edFNG!81E1a;AG-c#PJ-O&P^CB zcI-YJ_2|k?%aIi$1#zUl-yY9SPA123%A8rbsR7{=CgkX@4A1AZM(;x#ysM0@a0Y`q zR^l$u6Am23qA7Sdrxa?>-@YF$dL?WmEJb>i$1kBM7f>T!mnj}(G~x0@3REenZ)ilF zDs3^LT=!1ma8_*PZkX?OTQu^>FQwH+iyd(`m*N|mHStFqKy-`j42(Jz8>@;740&Yb zXIlAX%&3Fo{U=?XO4Y+i`}}H_cWVZi(Ob*f%8K3wVVWzLQUR7V_3!qktUxNCd@SXc zzUJSTm(Ap88slTg&h{F``k9wzL6cd{8Lw(hPVk2<(q*3rljr<=fNFa0#veTtnHQEj zZClXYc|n<0Og#Mkr_}LB5AtlM?}{2CwR6UCi_8M24jL zgR_=00)~%GaWnPe`~wE)y1Vg*_X&2gOpX!eltU5&8Yz+x7o;$B5*aQEjKq1jUZ{!; zja1lhXT*{V<;T;OM4HUXX&NMfDu*(x;#CvxruyDe%LNlD2RhT54!ysN6vS7$=T5uk zrCCU(0G@RxT&9aXtovfYKtUg!o9otuD^63i*d7yhWs65Mx||oGUMwd!&Z$%BO!&Dj zz+@qXbLIMi;%C*?EBrS&KwhwdL``J-D&K{-CFE4_EU9m zG88_c$e11(koqt(?m%@+l;y65Sg!16Sk1@X7^Po)O=pJVa-(w#9X4=EW0u-f&dT$6 zsDfj{ZeT@SgYMKy+*d;pPP38m0IvK#KZH^6xZd{R&AatBYJ9#((_%t_!b zP@$!DWwml@G48sF(bt1_enn$lUNW#MXoAcShbo+&v+*~9|HF+SE|%;8)jqakw#Sa zZ?N3HsC*mMEx+deaVV56BK5_Xo!;@jOX0m85lUOSMKj7mwYzrox0X5OsISMHo&x16 z^Ms~#H5GM`^;B4GQ67r6LwGX#1Qu{=`OnQGq+@zAmDRCcBt`>Ua5R|GCoyv}VvOfM#NM}GKY4vW!1(}T=ya6)R2MTY=W z^A}lTd1ZC8sOpr{Y#-5=ZUH5EMho4F%CB+N412#3A=BS~k2>g}zUoXB%&@Sl>JOkt zBYd{6SSumY^Imt!Qq~I|F*|DoPwU|UzCzthH^FYPx3~89H=Up8M2JQu@0GNyhE`FR zIbJN3PkbG9HYDG*AHph{~an( z1>O*)0TGmaxI;Tic`UgnKSAP|Qx=1)3u8_>LF872ltMwm+5|&fEk;~A2BuORKUKEz z?N_!fAY|fadT6;W24+!VLb+~GrGSYx8NFuV@FFkTvq^*%rK`*dpHq)Lf03|0Ol^Iq zg-l_M9%hr^Ig=6?YDI7x=fT~n1nj5x!cfaHu{ZL2E!_4ouJw4hM=T(JFotfQ!t@C#XHPzN=swFbWs(+czAZY*@keL^A5A7^@bz5oV+QGNAMoo< z`^`5jJmSi76BQ7Z@5YSZ(h4^C$;URD7-gq19~M3f8xDdlxm1gg%~2a6x*E0YAIddQ z9;2{*zT2Yrml!%X%fHHuKQQe1)_(A<5ut-g$3X**ewI^j=j|SLbr_M}BT=6VB>WvW z@JvO&bI-8@#3v0h`UW%3GS#Fm-e3mE<`0C;;=^=IchL;TK_OS@H9m=`jH8(Qdd-&Yt8clO_RPNlIg)Scc|UxN?B}lfT-PlfpgP zPH+P1;DSd95_eIp#sSZaafD)7~a!};W-}ZY_jsRQ|e*cLic5*nF&%= z0@#&lSG6+Np?}Q2KayZPJ&e8=W6E}rB?iU!grZcbAu+U6$88O1dD&u~q@2-gM-aX~ zkFhE85>tVzqbrXCS7&%lW2KT&gOo9UC<8x2_4q(kZ&q?4QPTWi(Xd!0JF_PzU_s?4g)`OmC5YK-?c9=y-17>Ik2 zhoBk`S%M@p9~P!IdgLH)rFWwcgVj<8kv`5?rjSQXYVKZHz`hpcKP}DBXu?+K5yD_heRs}fVws$_C1H{W9wrDjnTDLY>WDL^ z5rt>#^tmhL>WOAtI2YoX_JBB!A@bruf_(sQV$fmsiHxC#=*k=Q^Kf(zoMA@wG;Uv% zeooax_;4a=&E;9bbaY^R6vCvkj1o>^ej{e8aYwiGBexu1x6#rWGab zF#4vsS-2Nvi#E#yb;k8O5j$l~=aUY7B`&{R3&{t1%E}&nCD?-jlhR06j}b~IlrZa5 zg4f%spLJX>uv0Pz++|xWi$e8FnG=~~38NAww93gz<4#Y;{^RY=X>Z4=$Obi`?6R$> zg@kdgid0OsYRg|zsFo&XU>2A{4=|wIeR1PZ9aU$`v4&FA%U1suNR39+tC*oxI$P5^ z^MVO2Y5hjT6}jF0{#(KotA7VB$u3+=f0k5dyIoQXnQT_LRc^^PD%D7z_V?Ib4Im$L z!Bd$>i0OS`)%vo<-0RQ3G#@?AjWpt~RCXQo|9CI|cPi_DaxZuMr*-XL>Y}wJGCzVh zYwLcz+bWiIqec{+a)KFv<`1z%T(A(ZxnjCTn14;Hjl-IbOW#IetWP07;`cvad1&^R zSTqoX4EQFGt*!2d#;%87`2kzsthy%&0@g^O)QRoL6kLg%>7bFHq$^V0^mYjZS7-9p zU@;cASR1zLUwk>MYH&BMEK!%e@Y*t5mX2h|8|#{lt66)dLf^C~F>M%#BMJq<^7CT8 z_h|`I)^eV^2Ksb!;(ZOty|BBAePevh#)z6uN<@QE(Wcl@<-+^!Prc?-9YA#%1&p~2 zauJnyDR~L{xcSo?Rf0}!<<~4DH$Q{BSQu->!|eUM?vSuOyRs1w^4f0&8o?hYLh0=IUw@5NH6{1G8QXE?Pj?@PQjKh2b>zMNF zjdL7mG9x!O!+EbA7%yFNQKdYF_-GVL7@h2m-;bD3pZCk@mEVI&hS0w(4605depE73 z+!$r|kDuH!jk&KZu!9+=-U&U~9+C0j)nO@CmnyX~87aB;Q}O%xqJ`YjvD2Zk2S~ZN z1rR_%x281?uT)4E`xqlCYZ!fIjf#c^8ac5a2*^ibN4ww1=%jOstPp@OlYvx9@NjiIrit+9!TxuN;jd{IYH zV;f@!eW!oL2Ny=yN`UZxIatJZwYi82YMW|9qaq4Ws9}VF{qxiydt1h}S;K_l@&6GjT$K6}?!)uZ{FI{lt$3MkhOSohm~EHX4yo6TnbW)FHdnsGh#S4oYs~{) zdCZ(g#aS;a()F~LdCr!HNXgY3wLvOsB0K=wc4@LX*t$b@a4-Rs*D(xe=SG%+v+2w% zPve8Dd@C~Ng|L42Fara2CHVf4kQJ3_H_M;zx`dFCF>XK-F$0q`&V1mbE4WtHHa*wdAS z3jWrgAo?h#D}gm&@j94i2vs>SJn%<2>`jPjjZ`DeC3h-+4-s`K&juZIz#gF{)K46HWEB1?ng9cdY~s{_k{2^o`|drfIngJ9(jS4KSAby=P{X*8)X6$@u5 zgKQAbt~j!q$PRfW1a#Y3jE)INbn9~j%`X1NcH0tGv<0%!uwd3(w zQ*azj8SpIY1WbAC35D2d7YViI3*BKCOZ&Bp@hv7{5REp$T22pcUCxm)=1(*1wtIv7 zHa`<;BfcZC@@gd)Cnke9RvDjDa2leP6c@8gNN+MiCtFTfLt#O!E<~@r2p;@^o;wKF zZl}LYX++9|mr)0O8@^Y@cDP-G0(JE89_hoSZdl?vM=`s=cOZo}FJDR?Xg^ytZh0&D zX?)rO-R?v!m=W#LU~cCmwT*~7Rx2Qi?_x=QOrBR@2-4^0Bmmr*FHN9UoF*G$D$*>_Nt9 zx|`Xd=y2=eG3;S9J6c?MdReVLKJ8R%WbgGAOhtSl6-yOoxAjoI5!>NMN#Ty(dE!7S z=|bC-ktfNI#3Dz075~zcnU>8fbih-8y2#)$VIV$8urSdVxd)q)+kW)}+2&ib<_cLw zWJM6gl+@VAJm2S};2(hNRx^>a*{`SRZN566so3t0qX88EX|s* zI0Po_D>F~{Xifm~_bva?;P#y|HRGZ!J|^lrr>m@FvjaXq*wP_dHPosF-RkLtmk#CS zY^Dg|6_P(A9~Y&#Yr*kE1>2qoX*7LUfoZA{O6L~5Y1r@V;pG(^3$~Z**U_7HNq`8LZ zboXzqO*}%i8CyhPHFyD@k~`nJ_$!Kx0q({S`F(#J=+7_3TH@CeLJ<8lG*}o^$V~Ip z`s6PyvE>U~H{LZ=rh11aM)?>784!8784uI;nPe1h7wbY^-G_Iy|)t zGO@+!)|3b#Jt`}ouZ+`4B!(Y&s~?h(&kj{h8tyC?d><~`Vi?BlsSTDo>-yzL>}b&R zvN9n305%Z0NMXVCR?d=jxJ4V99jzIbqEfAjbX$8ULxYp8pSvxZ=TuH$a_6_3UZL)X1J^js!vIz zWno-8VCh(wiQ=@Fm_}}tNZGo^-efw4TEO^_>BE-|Y6wS&wi}itB*GMyjuTpGP%;?U0g^(g^awA|>6PcO_%EWf!+@Q!$LZTS6$b>tSA^rBemaHl(e+R=)en4!Db~^wW20ThaCLm~(MTDG}>F2O}p?Kz5C*VoI5o3(b|dvLY43nONX!oaq0ez>K4S<`@eKZ5$e zD>2=j`q7Y+`}CULoYu=(eVS63R+++~Q~)t(nY%%;b?K=lAU_dba8jI40DwBP*{Yp&o;7}b!@>$^+dj4nt>OyU; zl2a+iY;3wb#>HCyiK@{z5sxN<9pyG=!TgR{IoJzOYABCFO_E=^1NDZGSCJx9uEv~s zJjc#RtLZ8%$ktKC`vMd^81QXn&uSbCrxQ*uFk45pE>SxXSUj_KQJgBfvqB!2JWC_j z;scQ}mLDIH5*VC$x8ZFL4_t!=!%$}aDIM3{2vEt_tpa8c5gI~4@Rp!cg%I07JWmlE zMnc@t3cLhpzlhVXOUwqv^|uxCK&L{5pBWFTLkHNYR_V!-cW7p!UHcv01uGDAW@v%) z#HkU=g(B20X3xKy&xq}c`MWJEr?eNyi-)~wW%-ktlR0BS`ovJZ*dgVRVj2(+tH=NG zmcXJ5nX3w+l+-=RN;h)~>$fc_aIXe%Cts5wwM4~v-5yC4=I{uIk9=(5rk!O1fMAcN zo%q6S^>%`WaoUBhanj*Cp!zr?&{h;Q=hQHYg_(tZx0Xo)hPU5 z`U?Jk0Anow1Y=6pUx{uA-pQNVlBG@l11U}Z;j=0`LWE)RVSW%Q{88kP1PoTyl2_Yp zl9yE^o-7|fq=|{KzR(yJvhE)Eo|PsE1B1wjv1xW%*3!lb;OWnT<~QUTfc{P-scAx} zA#t>$I0ifZkQvSZy9A6$#2XO}n99knHP~4j*>AISlmUsthH<^|vUEK$IyZ%NOV%<% zxBhY-^H=o5zCXrzZW@=AQNs@cVDtr)3gLQ-NBZPqO!dF~+a{V@_Mq0}qk`jeH@4$A z%^gSnWKBa~&>UQeEnK(Yufjjx>i3Jf0&CvJbBHDO2IZHE404HZ&YQ=CIBgYxC-ABghQ>>JiQ7 zL6KpC2z2VNKsr0i-h;#py31OV2kM*Fr740}0q*;S41pEIxh}74>yx3MP1>yRdgY#B zIhwPFM3tOuAC@hb3C7`$ludi&(lh#^eV_P*0GMHw zLT(&JaEp;zlip*F-X^~Xj2P4)2haabL~whJtkrrUS;mUXZu|3!Kp;f2KWoE3hRoxQ)a5j9VmfWnkYIL5mKB2Fqwbca=IH;=U zPB$sXLiOHn^-b)S3}%}tdJh`vIb7b;($%S5(Ycu@Dtd-s283U%>8n@kTM%-f0kQ2i z@jZO$H$NPLgxv~4+2OoD0-SdgFoW50(Y*H1SEiFH5aD0KDVPp-gO$}~9oU!KM@;rPf z17urr)kTEy$P5VmbOC&Efw*7>v-vDBNq<3XY=f_PceG!F+^ZOw&uj4~M;6bl`CES0 zNlcSZdiHPCWaHdvdut9wkyY;Yqx0tWt)BoFW1ihojam#?2q(Qy71@t?;}<)5pDv#TsX)##*olrfz=F)rB6i!5u{&5bv1n$0$j zoS`FY8(TxQWhXxFk~U;}?tPnC!y5^#)uN~11vkPnhIyls@^r!(oo0>_uvcc+AB^+} zkVESr79G{&8_3Ea_S{G=wo8Dscn4#a9UANFrpxC#-9vn{+ac@W-$}vcrow7!Zp+bjZGNX!mJr_@3BQl~Fc4P5 zi7&?TWR8Z7McTqvARl3>Xx5|A&aTZOt(5V1LRAUf^~<5jAA!&gsd8SiEy4X7Z|_vB zBid{;^%?jD8+|~jAs@2urDh-Vupx0BUNf7g+oF0SYV@p`LWI3FmM!{@z zFxI~8du{D~P&DF<%RoG+BE?4=KRPDZahH@&0$t_Fuz*aE)16hL$e(~>hulw_>TFK( zDiL?P5*Yjqk*#sXzE9At2(xWH!YXH&CQ(v%*=hUswTLMgnQZn8zYlHssOTa|QuR8WCu(Tw^D9s zX(L()4Po{eH~Ru3%UekIIOxFiq&_+$@wY?jQ|%aq?R#y8Tf*>1T7vM$o+0UIZ+D9` zGjncsL0}X}Gghqvu+H*b2?Za{A0=(gL6{4I0UI3(mi?Tl3k?NjEFU^m~ z27>43BRdt3mnLHF7Hve1T8{g^EWoPO{KFL`8B&e2nhzu3LI7&irUbsAhnf%B1&e+{ zUH=>z0dg=7^f0V~ojw1U39u6GzYRh0g&zFTVo>Q23ZRR4qDg|!S` zR*&CwGn`6onJZj)U{B4eXKb0lkK}ttgTQtctv*gTDnM&qgEbmJt(DpBfQ8sEDtN!Jk5J3{#xH~bnraZh%ChIbF~ zePDTvRO5;g>K7{%fnPOOD-~^HLO)Dt05PY*Mz2->hT>BMPp1@Sn0fY$6*BpK#_uK4^y6Pg^9MZ62ptt zr1&x>e#e!fx1m}mQ=3wud~W!x_XoFmL2|GZsaM= z{N`x-Ot(f&iUqG_z~CyPJ}!H&%O3NBt^6C;8KWDX5S+>neC_^%P!hEmFXELGw<;+K zhFjPrj%iV%M@*M~0z6XPo>-3B9E_%2uJ?k*_=BG%1*kO$M8_h&o~3c5X4~TLxMJ-) zca7kwogLXbQ6ZNr_Rs(F>O;3)F zpguV?O46vVg^lY)%MP-JBn(zmqpDUP_MYiOJGWzMa~xJgcs@*ijajriP*Akf_rOr( z*L=Fo@)9mczzB+eZ}mvkEvVWAI}WU^%CE0cTL4+qYSmEqVu3ja;)_lq<9{3Kh(hj}TAv z&gG1McBGJfzYFzuAedTyhxjOiKuH(!?b1@KULKSey9*r%rymgx%2%r`#+o!p=_ApQ zq%+JKJ3+G6YKbJgqlP|+C!}aXbZWst{TY}m_F+zca^X~flR};>to1R+n! zx|kNs9`r++AT=K*YbHr(=Tgg!;h<54nuI6YFCnYj;E_7H_9%8rr(5HZkhL~t*s^+C z-v#OSIm>;$BKzoM1sRq8+3{!+DU^6A6pzkpOI#{Xqi z>z{cHg^HhFJ#z>jtgY)TH}hDPjVhWxO45`b7N1Jt%*0q?mBcJap!)S2#F|$wW1GUq z&=8$bk2(H%@Y{l6j^YJ!2&FsAD=W4pooQ=XFE3|j@ZaF=o4>(F;8pF%^(-h+ql!@j zS`K&GLa<>jkqf^JBe66|YcMhc=VHP2u!RQ^`twOH8Lol?;jlz*%ZDn3N07(FAgD~f zJ=K;p)+GD(U%ka<7;Es)c<3OQ5XizJL;U>-JsRCC@K1)Q-~iI~B~k^h$bb~l*K(nt zo6-Cs7$z_AOs-rZ%R-Nri?1tda)b~ju2qS*bsjPhK(>5R&MYk#wXSG3{V4jVt!s?e z?)9JyEjKLb(stBH&xNbvxg}_g=a!s)om1Wc-&O8bUPc(N97eYIH+=9)!{m?sHhe2* z*FrIjP3e)$Hk^M}8h=Wgn68nMS}-eqGRP9*eF(N$)#c~e*w!no>~lul+o z+hZ&Q{}jV!vMn5<3EJ&`jM#J)v4@PB?Ez_}lUPV#Rlv|#KyhRd()`LY`PRB1SVKot zFFT9thi{)=!0XbDnJLIYBb=G@oh^*HP}8A{Xl?}W$J!}7xSdAUIvcPGFix=r_u1MVJwKY49stWbeA>edrVrHlscRILs(_L@!^vbuBFERQ$4e&b_1P=OG4?<2gv#9UCV!jO#^y3|OWu z(bDmlYP^v!8i7G3#4Rs;FDH6uoofOFkzO5Ek!gYvJJ3%Ywexe{@5eLl4*C>3=!-fD zp|RqCAJu&YY3(ff%!^{MLR8T?_5Ie~io+YL_`uz+>GP`OIE*%MpU$>BiGkhs^K_*t z2~&d^1PNd<`w9K^o|p6;u7BsdET!hXxQieN?iman~)qiqug~&@-8ybgvpc zZinNG7~6sQH=yqCOy9Wuq-EoZOuyy^lg~gWuH@vVaBox24d(^!VKA(e+*4rKqL6ts zP!1bLvaF;U7#K>CM==h*ln*FDlQU-Ls+~#u22D(P3+!&t3Ftmtk7gPYf|Eaf8@S9* zTxN6R8d)gz;Fj4VUxOKne-AN@`+)qbS}F}vzzcq1?&ts89mdT6@&Ii8291giF>H%W94G0R(Sql$h2G1(FA70m?JlJ@i|# z5*-*Z9K9X;S-#9K!H@3KyCQ?PO6I~Kn2f$Xl~g2BB->y7QvJqs(bbLMC4At~*^F5E zH1>^I&58X$K)zh?W-eTGBAz&2;N~TTH|od_Ex>aq!4f)3f@q>yy%Js53t&8Z$D6qE zw#m4Q^^0DDJ()i-@7sU{D=r-xL}$TN?R+*Jd;@>SEe=sl!atTP`*1{rby^yvLAO+M zjqAhd`^}WJy~}#ppG^{6T<;ChC!m#wZnyB{!U5hJgRwb@;Vk=XXc%}aEF7UD`>Iev z?#cS%YK@`tVP4Ck2?-{L95Pik(HTL}Bd{5N~1lV2Mz%wD21j>}ni2kz(QO z01fYlAZNecoIv66G1K?Z5BLYw< zWIFVUKV&P&1*<19Vr*-Rrv5>@-ZvO3^;v0R4BnrdehKq8sA!!e;wof*MdAidh$-Yz zLC(}j5;K1e`rn|ELp9X~mB*1s6KE5j_e(O3*T*^jA^PuiX`+7r+IO7)sdE0i=>PvI zC+VNP>{*Kc7%-c_Zl91&s-G^K>jE-e*H8a`0T?b9OhNRX?4 zvCxf%m?u-hr>eXq3xxF{?e_+xY~RPn5i^5HjHwE9C7v{4h;%sG#0Ctx}EGpre~+@NGK<_taN7k)DqXX`{SL#ndc?&M_QpEcU>X5U-#$J zQ@;}Z(h)~wywu5!WSVSzTtqwGrT#!4js@On>eF_Q>&#vU>G!bk!Re4`bVSi2tlV@A^CfKN*o3)b)JRk1ox57!)MBcS-FijAUSKlIO zBINM;mTyd<5o#QPC-yycK`+1>`iie$#s0EGdORAbBx5@egKp?)m~7FKtRIY3*QeW* zRXbb&XP)xq;nuCcO4m4@Ma}=7ll1Rf=)V`oA!Kf1V*F(daWdC8urmH%=_V@1hF{K* ze?5f%QNprfr@kB_FoRv@XH|>5Zb+UW!gdI@Q2uff@Syy)PfqDg6zxpLCN4dyciSM( zat4p{3FKf%z`EYL0z6%tyx-Qh3;OlL@{xwX`ang^DI~|h;L%g&5LA;YAAen6%KuA~2-|<_g7dFc z{D&v(pE5+F@`lVjAIgWxnu1!Hm7LNCigVnBf1>t0b|N+!jFBobqQS263EX+CjpXX3 z$W`kMRZdUpb4Cf|FSj0$XROW;k0O*vQc{CtW+rZ*Ka*^xCNf`5|8?NMd`I9K2r`1B zcVrs&!ZSr?hkNGZmKe$mBl#^?ZCsM{PxM#d7pVb#E*9$!?;aaZ0_8TMjpAdER!{ci z0_Bt{s_xyt#g^l)xh+SKr8$2DrFgrmXz?sv<6zPcOuHz$5vH5C#d0RY95M!Q?5X|~ zR8@C-m&xz!4R~V=&TT*EY-*^+n)3G;)*x??89Qh>+EKKL*^Ai=9MHCY|wUzUZjMi?XQ^B+AlNX1MMf1POvGhJ7s5(`|k~ zT&gQ7|N4pvCAx_d94Tei+SF{ap{;%dcQNvNF^4}`(+Bhbe4th$Z}N9+K{&+7(LCJQ zpdPNhHB7j6C1VG75vMa(CEv)%7{^+CKnUciHOIz|OO2EW9*%`ORFn*c5jX!VOTjVF z?8}UG%{y5EPkeH(c={SSn42GMdX$H92|L@!f zv)Q^QoZm$#9u56R)K(Vf2QjvXZ+%jx5Fl>CZq+j(Y{PQ^;H%wn_mV{CP=m=q`GLTI z#K~MX69y^WhuKl$YVY2}j_lZ~QM9fpODA*-C{$+;di@19(x9IHT9C@RQZWrf{EuIa z!ggzk7T~16X*_uf7LukFc6mpDDuD;!`WxzmEPZRhM#|z3xP)~=XF}{4nzX-C8;637 z?GgPRbN;F{!;PeixnB>fbg=&jDgXVN&-dRt1^;zzagOBv3T8tI_#@%t8wOp|ClI)t zT3!VMfmS4n(pWnCz0jPbYOwpSWH#<^cvfS{ol{Q_U^PQ|eDZoS!y>E!;jI+S&G9u{ z?LCsp=Ey@21E+Dn4}VojfE|_hjQ+~nXyjttIrgM^?x~X(XsdE;LdOj`{IOi;{@8~8 z2@$x^j}UB4BlECpX<2Ml6mDc6DJvKP&xP3JSyH`o;5lZRZ9Zu* z5MT=d6nc4;V|R>gc>tLEAliFq)tYqPd7V@{xsbY1nlSnwBITtGmY-Mpa>6JSrv{h5 zuR2|)xStF^o}U&hzcuR*L3ee&9IagWd?pHUiXylx< zMul;bcCt)&)wCF;NM@`(z7KkocC@xwqemQsxZKnN8TRl2W}f`z+;)<`2Bv}BsGp3~ z=>1?!-(WCH!;@jEN}wAUS$xBodHd1RaAN|LTqc=V?OQu z$%=rj&E8(tu8cT(=um(1paNklL>Yr6?g)Zip8^dRastu!7Pl+S9KE_0$b^`00ua zGw$PAp$#eU_=6fySNiqsM?Zq#{acP;YgoN}q}_%hq-AuEleL&b+G~!2EpON5D$jq^ ztaIz!2sBS3fNXTsZeh=_56yK+wd0IZsvcWNU*f#ZLTf4>i2=f#hMCWjKo%;B)>hRT z={oRU^d`XwDoGG)0_}1ndj@*Z-{m=;6EHElS)3Gfk4~VR6LrzsC;-Q4LV;*@EK4AJ zC~;f&|w(efFsQjaLLV|t1(>5F=T9EI*cCcBETMbx0!`nfs!vGP!lbpB0>DUM{J zbc(6vQg*#{va!QMj4LT(hiP};tzVk7R+Tv7WD3^2&!1l?kjx!le(st(vSh3P!jw23 z#}b--n*3)EBcS6GI7YZh>&4x&nZt?O1qjQ(1PJe6qM z!Vi)!;O6+BGVT8TME>_Ioc}tJf5*ECIOrQ%8atWWn94Yr$vPMrI|%%BIr@)>bU_W; zO-s4)V=0r#(S)?vo%yG=Y(fJ9VO9a8If#&$BndYK`!d>bL7}<3G-L5dLqeJpp7ku% zFQi^UA)&YsP))wP5`-BZfyOUL!_}cGhw@$CbG>2v={QdI2FG%(<7s2&KE~Z`BF~;l?b)s0P zel7;uJ}34PeYRM*UUGc7avNysrREcIAix{%J{CWxr_W&8*Ni74WNHU-%Gn1K^U
dl!~PI5`>*YCZ>1f}>^tB{ZM`Rx zOlPzRM9B!Axn`nVnUloQz3tIVp5~Hc@y1-D7f??^?Y*@T35ZPM)2zn37bj+fHm%e1 zo7v*QYXC^-7#o`?%xHB|)&6l>rfidZBy2L2;5CIXHB#NykP74ojN$HFeZr{)urQHt-z8 z_7xMeT4VGN>@bKcnVwOzb*-!u3#J5`ohA%RlPal(5W}qYqt28DYSXXLUmklm1?(y0X>V_D}>W1iN7n3v?9HmqT?1#ED zb2cuToa4msHH#m$2o%TkbLE3}a!^V)`s8&FR3gj#!=@V;!VFaDq%{?+ax64$Z6L~M z`az8>$PgSMjp$O|lOAbspTpGGxn$A=Eic?O{ru$yCL?YMTVKOZStr-8TM+_1>q!{m}W@;xRrB(1T($dXlNO!^e{=dbb% zRmTTr`?;~GjJea-^ZKNmY&&q>uDoW`R*X6>PU1H!?QHB`|BjiqV;j!2es0M1pkgA! zA_bhoy}6OOIUq+4!+@TX+Avn8c|@jUxOyB^?AlP|wqZx?`Yx-P@Vm`Iny4tnX6wEV ztAoSqCOhp&3Jq8LHIsTT4RDf-+=*f0wV$-oAxLRP?e6?aO2E+3Ih#`mHl-~PQ;5lU z3j|ClZ)fKoWT_V7!~&TYhBC^(w%t*;2D+d$KZ|w&UmeK`nZ>)FndNzyV_(Xdbb^^q z|C6$o@2_xty{zyQp*z9%P&pQ3HRX;-RVA&k2`KN1UFD9VT{1WA0oj{2|C~}c5MFc< zUHNNh)UN(&rFYJ3#cO;@@2IU3H{>qm>*VmQohQl<#R{)UrC!;{UnhaI0v~j!J_yhs zh`b6ntRDs2UCQs6TG&}Ep!Ma?+9*BZo6o2tMuZenAHoBl+ec6zsso=pxTtJ9CZM0y zyAZ*`*XK9lH1{nv__8zRm3E%d4v3zNxK&ye*YX3cK6lLnD9v2R5iBH}j0Vy52P%GJ z8Jf(%>MjH_+<7f5bca|LD!z2NkVMakV8HqFk8v7|^7Z@`+o(z9e;(BAE8^Lo{v7XI zW7zk)4`Fc!O;yRW{Ei#$pKGF0mxmHv&Yc56wrwm6qjaG}+CW3ylG6C)J_`gLeNoDe zZ>hemRDB!!NK=k%UQ5@zO-xH~6||OrGFf{`2aWSZXaOPS)L_;@2fGh#LYM#rH1?F? zNB}1UOn8|T%AK8TpHi?}q3BUG%iulRSG(PEJfK`O&#QZ%m&%)Fiy zyqbGQtKmEBItIpQ+}Tq&h|gNZ6j2{>b$IFbpvwMg{i)XIm$sG^R+zuR5G<>&?O6XS zv_I%e-($2k?=-ofDG*A`VAFZ+z~jdL7)?5Gdy33Mm*zw~G)ds?a4!n?xsAx*+x zeYaB7uda4nX;Ia(DJ;H=+Fk?hTAol1H?{NP^;V|ZBCdJF)JAN(f-^orL>_ozN!#&# zUA|SRNN>WAOmyAy42P7V!}UlngUB|LUim3#*Mo1K1_8Fqt2RJ<9=!K2{9Z{|iS$vM z7djwn&=?nMoiInI!{=&&Se8QvT5w=n{6X5|H`<}f-S^d-pj$9f)O^gD>#Cr|zaP{Q zBUTxS1AoIz(V!YxNwdsM3ucaQF3s-h;Qp{_QD9|6vTG@5W!^#L74&y?dz zo^4oHx&TsVqr=Td977ICXIjc+IWl%U)fvaIW#AdjbM+UlHnjgULwy+2++rAxrs+})Pw zNqaYi0Hx)I6huOfB~VK&wDB9AWN+!cqVbRs(A2j9rDct)OAs_;!cYTzp?<0Iqc`44 zoRqcJl!&^@PL0~cg`El3w5VrKVDXjKX}7_OOP(rw!iB3-fycg>enz)?1-??luF#3j zL>$175kubP5lkNO1hznvr+tJ~?pJDM%zo^R_vSp8P88he@G%+_q9 z4Yy*HS^Rc@rLqLC-w93NZFqtrz@tl4ya`f$jO7$8!KLI7EU_0N@em+jiCtRL)Qe~T zBvW!3%+<<|+szWq!lvoSxwyVp*&4*sx_OCdJ24k~gtmAJx80z!MsZnp0ZDL_Y3Pbi z2@k2{wADjR%;c0)G#d9h=(%AF4eIfMuxV_lRf5j$5I0Y+2vcQCjV5@8EqQNHtT-o$ z z>ly-2g19IqY4X zRyE>W+F{h)!%M#U<;)mZBiEClSq<9kEl(7dq{VQ(|AV*&9yq0ek%(s9L5to;8dl8D z7HH_V+hCR?;TH>6E4I;oOxMGaR&%e@8oe6fm-0rgXw7?QX>~EXRSsYxTmdHD`7im> zv$ow(X3L9Rm~JnDJ}0J!{Pbyp*yPi9A#ExPbPrB$%j#6od^?NHA%$UMY>E6DwiBx> z2+1=8(mgdI(lj-8%E7}Y`fljXlf)-Q)C*qQ4d~M!-JZ(ZH)h9pJxcYO-g|uLmBka) zcAMlqzOk$K%q?MUYuCC%*ycU^{TW1g*IL7uSDxlWs*+tGOQ<19t092+lq~J?2it}? z-l{khx0sGcq^FbbyHhOG2@7SOt67m`zQGdZtQI%(+JpG4_LE$xC0SBCn0e@0MHyhjpk%4R`%!Ipf6Qy}Yz&1q~zi6U)rNr!LKuro@^ znR$6fq=G~2tOK<1{@C#!hs3J5_7ja4L8mNFCNI9uq^cDBU)cL0rMljMHi=KO(zgg3 z)cARt2ez}K`+ZIs?}T1T-eEQ=xr+V@M=s8Z z)%|uDJf|p7OCKWtW`3DPr(j5{UY{tvNNt?JBDrETp}_j}R)54=oX{E|N8kgyrdF(1 z`%d0ezaK;?Ti(MFdKFnEoG2W{){;N^}=jy2Sr9qI<9##_c zE2e8#BN^%h&K$MMur%~Ck+v7y?NVx$0`vLDS@;RRIR(1;n7lxYc!V9dBo=Ng<;>75 zH3xZCIJVoMmAqaoxMTe?7F<(sK;@2}CHp`B?O9%B$AXKttYbHUMuX<=;+70v?=mc{kmCO=MU`Z;8lSX?AP#-GaGL=ZU)FK-A^q`2ONVad{Npc}k4J z11yJP8XdD-)O`uR&zw0_^2HtVtm+r{vH)PFkK&%zds9?ajl_~|ieeAGMl%&(N2CxE z-$Z=px5Yumjh2WRl~37*!3hR*al?jj7IPhOk7Ei6WVU2-Vgt`uAn{~ohPw|d&)4)M zl{ibE{R@Zib#1g}hs9T1%Rg2V+2+?$fD{|UEE+GAX3eRXoehMoZdyEbcoYwNg3f@a z-Y3<+Ft2U*%%&6Ew{Jc~{}l`M-(&s%g?ax^?EinnyM=$T{tO6%UC*XVf3f~t0JhMf zB!7kQ5dZDGC-Y1j#X52EI_S=@sofs%>)ifxj~WPxovyt5}wSfkI-*!=J}L0+?vt ze%O*<2Q1LIOUI4r{9g6NKYPjKUMn#-S)`Q0D$jFi!axP?n`P0t5z1gbTCp8gox7V9 z78vZft%!dow)5C3I8VoSo`!5~S`iz}=kxc*xwzBt*yefy&JzJ1Z4|7Y@#@Bbb7r|)R2Xl$te zpNWM^RWB<|Rn*Uo<;il~Vi#?)j*5*@mF6(%C98%py9{IJ_u3*!jgkbu#pK)F4)*FB zQIoC$3KUlI$Vw0bgt;agLFCWxxz>JV(u3hDorq%B;J+Y0^mYXyKE6Q`e22&l-}>!s z-_Dw}T9CZidbH^}^^)ay`SXb9^L`fF7Ptjn_RWry=XfB5es@5Gi*SUX)kQ6yC<^`q z?(}HyHRNDce#A=%Nibes+#xlc)E7Y8c;S`(q{Z-1;=fxdxx;%MeOomczdzaRTE0&^& zP4D@5QiQOC6B;bQK(tt%5sIu#rLkUvc04u7!ZeRGkp{iUx?F2jS~5JEWF$jw&QfWj zA}wECy%DLjm1x0PlVt1?(XE8Y85%_-1ay7mHkAV5xLM-x<7Br)9g|rES_|?a#Zg3m zxkSz3lDh2zGD7}J2b6sS0xMq`lZYv9Oj}(tODBmbg@H>#ZQD(B3-$+WQUxZa#@aahsmoSkkZQ3;;z|W-)XIINyq?X|4JP`r zMj8olRi1MEe5$bp##KL3s&;Ec`NPbRL*@La^0uGyaxO5d%H$&4!~(&Q|0ZjsBqJb( z_-V9se{iIA=z>x3jMYL=7}l}^NxIQEA0cMC?cQoKGai8&$#!ux1qRS2@Mr5cX0vEH ztKw*HTSB)Iz4>fadD6Pr0WES3-eDk}W_H#7cq9on|JVXa-Jetj!)JT8B9`%I zdmIMdy!a0Awf)-)VzT$peAW0we0<@-m>6*fB>bm6WQQ?Bhu0S3oWy-a_Jg6~8%)2q zYRjfplv^2AN33`@$)EM!a7Yi3epzfkc)HznM_8#M1=|!T?)+aW@MR^|vg2LOd(8c` zscZ>>f0xSwZxT2EfL`uVoqzOU0j47^h@PCh7}(t zJ}byA!3sRPgfQBD04M~Er72Col_ zs%Wv#xq`k8r=mu{nL;Md1LgD&T$!}blARSv*`>OWA+D+>m}?|J`a69z+CJ)~%xS(8 zZgXSwn#Pdzz}xV`qc}8kXN+NrA%D=T1)9~e2y&jjS;5PQRz}meE6)vok;29jIe=0@ zmC#0%4fq34r?uRAfb%=I^ZR!q<-RNDYuVm0UeMdXwT@YP0TCDdmw(GxC4>i-y!E zwG3{DIA84tfw+SogExdWTb111LbufAb6iJ`81)0Mdt70w7EZQRf#!y+OOtCzTcnI7CROjpuMQX6cfK7YS?l z0PZDIoHmWRKb6Lb;*;I>_QU6Mp*3S-AsRV(dUTM#~ zBzNB}Q-&}tqa@}23RfB6dIL_+zmsIY*CAvU6(@TrTB`M{(ooemPU%^lB%35t?3>Ml z5eGzBf34w3#aFV#2-5#U+B-&Ro-JR(Rh6i;%}U#LrES}`ZQHhO+qP}n)|=gT{_EcE zS##I)yx)EwpY@!GbM}tdvEyMaU-sVa8Hfz#jpu5Mp6=B6A%Bv45c#?AUexc6mh}o^ z-8I8iQ*XYb@9r6_bf*;J5rb`X(F(A#W=B&uKeIoVIg%9V>Ao(A=!&Av2b?+3()NMS z!z=WOrXw;l))kzqd-Vy`V{$q3O7so06At}4p$VW9DfJq?8mJSIrj4Ru8(Qb*2k}L3 zCO^{$uFI8TbT?O@_M0qwuxIe>Q=}8{CnD9Z=Z?G@oaGhWgKJNIgbtWE3LL+~G6l#^ z5Vdlos*<#rRv`xa4%?Be`w$VORwk*B{SF3}0)LjQZYQY^mbY02-T*k3&68gvScR zi6EjqvmIu*PC8DWzC3n%JR^1?9Pln<@GWL2z!%w+x|EN(m-YOa5Y0wRI%(6}PO`)qMJl+b)(`~#ETmbL*BLJp{b2&h1hL?vD&>%TVp?1F&Vy-VNc+p7Zp~ZZaq&Y_E%_zx`NlucVI%E)N0Cz}--DeSK<2R*`a`nEx zG7PcK8Xt)dlfETXBBa=7=M74dyVIar{%$Snhso%EUbJ1C#8?CwS^8+cb6$cnb!**Qk}q?@I!Q7c&B3-#VJdo` z802X)Z5S1tf(aPDaoKV^Tqu;dL82+!c^ZK)5IG##c<>d~oQwJyP%zH^MIH2;Kq7{7PpP#FD8x1 zJKUoYUO~w?LB~p+X#mkxJ!hOM`HZF`m18YT<3vV6+D-F8U+x094PEN4btOIlYHrJ_ z_mNsE?Ra(>Z@}d~LRbdf>Sn+AL*Bg6wNz=lc^lem?><3H!uqn?0!+%%p$3Q3%>@iy zQ^L&!pw7z+pbH`hub+P(c>j^CG1uI22mJ?!x=W+KF8S&kiu^^-@b|tU$3Ft|Qu>D4 zw)VFFNtw#yq$THm!wi0&s;gGWaRc)40|8a6`G&t}edA@n{3a~HQ>5XxPDZ9UYbxH@ z?gzc?c!gIKOmp2Wi2X*%`D&1+?gAK0C{h7kOP8L!d1mMEdVY9F_3fgEVR6&_{rX|| zkqJ?)TOJ*+so-nKc9CMO$||1xPT5*sQ(t~7^xQ+4V+$cL#4R!D;`-mjq zl1EIT_m}(5gJ-GhA>ySixGj{0ZZ|hjs0cZUw7!$ofCY-eC&w*KVh{57$Xafj_p@Pe zN&W@#hvQrb1Vgq6{*|DnI3Gg2a|^Ti_d`zJT`q(BL|XcKibfW|h?EU@wB0DF)e}Al ze}88sJK;H5;9OblSPTMF{?#rcbGS1AkxVHM$paQdmd*$1(**3_Kjkz`!^(D@O z<)k_G{I3Q;Y$4bU_)1{D3eHVf_VR)80~Y^Fih6E?+$unW?U(~t!%TrN9r10=!Pr&; zAOSZLnF>|m#gqoTYt3PyJ|lX!2SL>|9}B)-ODMJUqNY`)*eM6``i#-eT`!jfjA5??9; zeCBRRFKCXaN=)r*Zw%^nR2Ty0=wKP%F;^;`Ge8v7umW)PlxV&--CsGbS%CFEs8Vc# zha*L%+yXx~y>i;|;N7ir!1@iqV}Xe-t%a638QwG*By*Q08<@N28qgF?mYO1#QYyx# zBGzi;&(AJ$a0{PXH&O^!B8j#a7nMD+`Djnsu~%X^v2W>Va+~g4W!tr1H*#pOaeAU1Ce%-fMeX+A&3CpKNBo$W_Ah2mcxkk$%Yr; zAB#=cp}SuzF=;Hazt7TA4`8<+zb`F}{VVd3lKp8?8Uv_3tE(Cj!kICb^yS0Gl*OE~p{K%{!zYbYYWaDz|z->6nK@T+Y;pwN! zxGZF;LPJ8R=#@{=7Lm6gwu(WT*eNUDJsNoK^r6BVpb-TLaSR@|->i(ZB4&4k0U2T8 zW+!CI!BFXE6#2d$rew?93#{K(Kj*C^67-bymSF~zuw?lNr-3?yie=7N1Ep=4auYjdFRqGK8x-2zaLno3Mn2s^>d*uum;9JRV4Y!NGZl|t1z}w? z6th;NF7|wCbtC+hT{v|WHbZG6vJM!QlcZ7F`DU(^flFn_OBL!FyD(T7D!VYku0Wx@ zwFX~IRA!~_4N-SCI~r;HtF<(KWj;{f?RO#XHaoHcvEs3LebrEH8kM+{5`nyQv2e|` zMKhu+*5w`sZq!fk9X<)+>YFSE>oVLh%^C&C;W1)uQawds)>FqJc#^@afl`wGHV&cl z7)_@0cZxAV0g>M+{tz-42F27f*4lY0+Ic40c`ko`!1ovE0{rB*S09yR6M#|r9;m15 z_&jbtN^YCP`EF^I^zzzIBth9?%8b}h+}xdQe?BKbHwR#Iu^dogfB;2jNV~()sWn?? zLM0tJz(CL{V=F;k3LfdnEi!#0dHSpH##97yj}Alm{WWMI_N-I>06L(Ir=*~`xvj)j z=o6XOLs&WLUj7C?A>LnJd}C-NrGn7)h_qR#QHprEn-%SsxxPp{3NJckYy-TzU=r=t zI!;qARd6K8c`cEfmk|CZRy2`(7#t%*6j2x>wZIS)wFFA(4i23Br0we&ERzoot(+C3rXiDuJ%uuEXxM+v1-|f?VLpTmO|L!~Zo& z{uw>_*W#4FAQ3rnTXcRHcU|ZDh^Q)f_}o62pF%pqer9QaL;?cZJ#?9BFHwtacrBhmG)?y7v{3oU6s>z8mPl=D4 zCatNvRiVdk@PG|y^hP?61=d1W*1~~!ZI-Xoiu$64_E#Zx z^*uush)yGj7IrlR0mV10jrY~o8=F@Tyzvfu`>%}#K~XQ}-?L1wI2#@Pv|rn?;;CKO zSDMYOB3oUv;nA`$q4;3XPIp#^9>0VM_x!m5Q@dZdx`f*^c7;bBQDx%Q zRqyr%igv+CTlSftTyVmJ`9kiXq3*F)+eyZM^xhPsabz=K5`JfTW3J+#k2bV*kUK_? zeD;#{B6#txB5@A280k%7Jqd1rXPrwpcJ}B)Gz~~@5u;YSun$*c>8CHSmL3#A(^oQX z3lu?j%g7N>1t-uk0_$okli$Ynxd z)3Gf`L*-)28e#M4$H6pw-b_h%weICZ??m+j`HMp91WDtD0frCvym1ah;*m@BtAc3@jK}f< z9*>h6h;7)d#44rANfy$`CbefwnoMS&<2~Pj&=w2HA*^BkDCoj#f}qrvI5)IP21JqF z2$aLkZi^h6weo+n4rvj2KsyN3&y<>`lZoh|JAxh(E1RG)RxXd4&)5#DA?a+*GrTWb z_!3RtY<_y_DR`#LC)QzWe%SY2#^82J*fSQrTNatbGS^#Snxi<;_qbXQsp5Ithy)<; zkCT2GZ*x>GO-KuPv%e!=lEm)4I1RmC1gUl6r6=;y4eqzF+js=ps7tr%%H5D6zVYd= z{R+8pv`uRM_6GjPv)Sz}?o#wcPV&Es7XR)v{JmiDf9C@8KLv|FVB)`p*Z+Alq{pmE z{GfpeC=4Or0__LD!un=u7Ur0Pf*>Ts7hd$JJ6mSj(yAvJt$5q>)zt}`t-+u#0!=mh zn0QOKOflx-+}!xS1@b^atXkEpHJ%{-Q!^E`1O;#Kkq7uT-j~rA(WWC`G_Hutzas=s z85tK!>TdjCpsO`Dq=67#Be|x02_EfAC=b-sn>kp|O2t_7*?YV?a7Wo@yOok*mr`JI z5Q9VReG2s1_Yfb28D$u!V#VmF!~dW(io^CdxC6zKZqy}fL!dMUjC=7+hb4!aW1D5Z{h@N|dX@4rIm)RlN91RB}qlk7>)gNXrkijN0mp zH(IVm<}6_>r?`~NdlIJ4|0D)6$y^v-UjrsCU#I@>6aPCM<@`rL>C1D}UjNJN^*_(L zUUAhHT@m%O+t`p#L+5Q^XXnkuW(FAVpbUz-l8kmB>~G3GM8UEqpFN;nULOQN z60jXm88|(bFiS1|un|&9ziA)Kkl}vn4*x*;GT_U1@I6hGa~{oaksvokNg7}kAG)S= zUY4&4OiWDvSGuGf@B`&e>`l+y`dm#f-AK6+mtZ%3A(zEZ9U<7nUO&wHtjBu1%n?Ej zq`7y!Qb$)0Mw(2iQh|UleR+G2hsXMw?}D#qlZS(|ZI8XZhpX?p>VD`;-LUabTD6h% zQYNPvI*w+JHTnC;MKjfe8icsA)D+qTG&&iMSV6R^)rA!2>`@fZ4)6?BlUvmvk4^rl*7$?xLYnwZw2*JU{{B4IK`A`DYbC8I!PGF_4t=!UyJ$=Ot`L($mm zSkDId*vq0`GaHM^-%CC=YmlR^(FgM0)6y^1S_v?uxLg9W5xuA%PfRN_Y>wbFN##zr z%?Cn7hP~e>7nIWVcg58itwO{gjx>XO-q0ApzEW#FXib{(Gbe?=WP!nAPX^2x#!Al{XoL6VAh)8xMF+n}m zf;&@F!NO&!PceIKRHkhp)ekNICd3^n#VC`>7>|msf&@B~XUi}tGgIp#XRkQ6hzEz| zDC%FvViv4pxvt*g2m-^f=C2DD@X0hNZS-0lz;+EpbAr6r6p*R)yLZ-y9dAey$XUUR zJ@8OoZQ<%i#-bHiF4#p!1@?ggN1?zvJUgyvfguZcJt=a5N5S@CQ_c=QB-OS)&~W>Y z{B6Xxl5K{zif!bcR;H_hfS=v8>>t-%d+M!cO)OYFIwxZ0>}nhfJ=LXX8$GLN2h~ow zFkHYUKtvCeDH#+le8Z~_Mxw%-9kT1WS)S0($yV#K0kTN^nk8vVDhUV}tD-*p^&B#J zIbqUD)Q&-y#hfAy>6GMgHtd~jUj?q>I$+4jB^)`4i%z<;&i;E0#B`h{EteaSL;&kz zCL8JtRR8h{v_rS2+*LvNd!^fb>)Y&@W4+;3LX(X3Pa7ZhY$=N9+icbF~GzNY4(_`=i*JR6+P;O1y#8K24{3btlGNeW)RA(14*{Z7>&sno(} zsR?B5yhe1EOMtW3CaVjToB_t*W73>sudx{@Og$pLsV=!<9Nyng za>VuHehD@|rgcPI3C9e%n6DUh<(S(K z$tCF;i++bwIg4{G62eprwi0IoaOTmfJ-M}%kMRL(<%MT)iW9S!2tIu|zW~zi&i{V% z_c@5Y-=cLD6)s`$M8ps)=lu_!9oJbEh|G)mhGx#y#XUAS^H2x+_D?i8dGCUTBW;pd zHO!5LMHaTS;s4a^Pdw7H~D~UsTt59btf)l8)Q*0r#w;H;^qKgjikjKVFf# z-OxwVH2W&??VN$#fg5kv(zTy446EIfw?hXvwR>16;PkWVb=35$6+*1z_f<#+sl2(%zfFpYYsMaaawGYX>k{Jsg8nUZDbldk z7NNRP?2j53;Muv$9$*sTuOuF@20hHqGXdTRb*+GO8i3XmE4 zrPGHZSd2#4a-=E6EfkIxH!xfc9N~X3%vk8WU@mtVhi*Rz)VSvj6Z1L!gpNE=zQ)G1 zI}G&wIOOy_cy;LH#(tBU5y^ZnGHf-K|CzGuJKYV^-t9S%MKxDyuygZu>k1KHIG zx|q3rp}G#(|9t2Fj_m%Kbm!lw?yn-A|9toJrMUmFbT130G2Q9s+OvRXuh@g(xq`W> z+WVd^Y)Gf=KsYu=`GmK*)&28{*xHc;5RgEN*OAvzQCb~4)AI70LDRTZtah4q4mG9N zG4nh(g2tktMG|>yOh%*NG>PV`6kMhfwqIQ(=_Rgw8WeP2#JMPabWUTqpAdLNjdj7c z7PIiQBsNvo<(LN*x0;Fe02`|<`DAK&y!^SHW7MRrzwq{HmcG7Osp|{+o@$@_V|>r- ze&ySEq1EFok^l2&7#ayN#7Y|vG62M@OStrA?VqrT=Kj-o_6roX{ny!Cp??IMxOHsp zzGi>yq%6&xEiBEAwaxzXk1Ur{m4ugu`H-*_T{KZe_znwX*&bBpg^XYXC{hoKLkL2} znO?D4W6-*KmhbIJ5IocOb2s-|5cLovAwf>KD`k8lna=Rw)!<<4Vp3DH^LtWn4j3XG z4?CQW0tiJgK31s|b)l9<{CV^fEr zQOm3uYeOMJb7y0gb*k#mjAP?=W=YrAp965bI?Hw9oqaH)iQuhuWo+0G0e1z)=&Ibc z22Gbvuf6A9L#Dd&@Ry5 zS&GnKTc+WVB)e?`_8OL}nz5VsUUq*pRu6FO?g_Y<4KmfRI}M76A`k6T!Dm~rd6%Li z%0jH}Dd*C?MmIWxDMlgb$OT;^5L$74S(Fx9AwQyMK&piOZWGpA-^!hkdgfy4ySmw2 z9j$UQsIsP2Us2FfF15fjnt5_Cq+}HTBtnEpJPHpYob{yePHOs5qi3YZ6NgoUWQ$qF zJA*qEBWDa`6NDG3JyS92{zK6kGHL~6IjIi~vbtmsvrwMo01T7wrTc)`NW({5SR^03 zKugRARJ==o;LHi6l~=)k0lzz zc@?uM0nd#v(3!nnp(;2FAvY- z^bI@YX}qb}?>FwqILl_T?S$pT+q1L12j~`n#^Sd2dJ3ee#*@?WZhWM;_lmbf-7$z< zV=EhPOXM*!LDkw~@Qa+70O>2aAdO}GS;j%Gt=crLx4{^HK z3_di`OxPn&^3W6cqH|K=wVb}Q6Z42TA)al_(bq%6V3pkPn>Rv99>pGoAINk9kWaB| z^`d1OEjc8Ade-z9O_s9prCta(cUF&hcSnVrda5v(o_|1_>VjrJdTd@j7V8b@P*SoI zqio%HQ}wRh5m7e9iB?hQzLl$wJf<>h^lByR2qu6OU2!476Sn8>aPQT&fv#4<)LYNTv@PNsSkEc-jmV}(iNk2%Sl_<|Gp z+^>Ona*kxNOQ912e(w5C_X)!9h6aCp6Aq$EO7b$zgmM%PO1C?=)aXo@d2-Y1^^oIgFlBp? zS^y!8l(}dtDxeoF0;CQqGK{bwR<;n{H+C>)Ru-=io|ktPJ~%t}hmO)OdOc*32x%*W zFtufbs|Qt}QB;_s^W${bBJ>(V7M098umdNSOxjRc0n)+ffxL7^8#;k$nfDW|bUMR$ zz`H#4vA%F;JPyNwSqIKZiXG?P02oV@K%sez{#>?TZr$TE0jp% zb-K$y8Lr-+cDF1J6Xaht!Fh@F(VG0L_xK9fznyNMpf@gh8c6?Gh3_QP@cMyAeF=0`cm#-<&*TdFAbo@PKBynyFIjTgbf zlVA(SDwP+Z!kM%HGOC`}wCwAnv|DKHqY!#PoGnlHFf>_<@V+j*@H{R}p!YL)?#E?V z!NWm1M$r_dMp5^PoW65%p47O6StEq9C^UgZ38NCU8?wRO=QUs-cKxL=iPoKa~@6L2!hd z!)Z=;%Lc6NZo7~7WpBv~lt18?LSqqzNjyX~x?$T!0*@IUAo89@@xq;xm?P<${8-ey z{R#G(1hF=Ay|7tc=_a<3<*v{*1~ZkqAjx+KH@di-;2W+cSc*iC-ogx%CZ0{0F4}c9$SRH1;ZgWb&Wqmou2)RNnC^Vjs|F}q( z?7%!XzH|XVApc1X{$2v){YO~#Uu_^6Z7U<&zxqqm%ZvWe4f+_EF)8QACA9Vl1MvH8 zCQPH8>IXO&5fhFT9QM`~qqc8l6|P|FEL*BR&*}G$*JPU=fj$_`o?5nkV5_0W-xpdlAyUXIh zkf!!4%Z^(KdlzyA`6-~_)O+-v1DJ$;=!#e!t4CyZZG%y*_d)y%ikB~#*OI9{g!gFq zt5E?pP%@GufT4ngtR1xWQ#KOw>Ay6fntTS*fZ43p`R}zth*&E!vFdckT4$yivCd;D ziU6@N)G&=+Z6Ur9qfoN!q^jqhw0d9stl%y{9BFY)x{qF0#yLPi3Jf{*TH(Sa!jtTh zC$h57)e8v`dKdMmB_LJ0?gHuBCMJyXp65XOJ zqbtkw!1B9yM7ek?%+Xgu|7csdaw9eT#Gi!1u_fX`3#`vsz%Wc+bgPVh2dov{a$ z(i{w8+-2l|arQ0xvRBQw#=|Cv2EgAc7kAE>gb`8pa(~JAr({ z9|XC_x-9ZnU1+wUn3}i>yppP(WPv9w8%wOPup|!VuZKMlS|nC!kZlVXYIAlU(H(U) zu*F!uPa7lh;KyM;{5j5F;ys8nxpk%?d-T(%$?rhcHpoMUk2qZTG%fTTRQj?roI8!X zB*wTM(E7Mo@50Mpi#8vxQ)W{VWo<-EIQVgI=NE(W_lQWGHC`SnxgyfiaiydjV~d(e zl<<&C5FXJCqzV(=e6eoC*LriK#3G8)2jxTT8QJ46XJd@^O;8A~Uo;_x@kvbSaFS7L zZgGrnycUuKrrQ<@?N62HJ^5+zp4vWi=&3M8FSY3_{Yvqqf&p_8Lf~yZ0sgpJ_zIY` zPQLJ2>tC*xzgHdpnQaZXnVF@dzTOvxxBtVu=3g3&d^uCeSuF&Q7JF000rM^|&>bNA zFS!wNKV(l=wkWA6`2@KKHC1jzOa;Sfz_sI(pdP*sJsRh0ZrGta31Hk)cm1&Q%iUUr zt;@e`U~82kxCb~O>823#5Y`r>y2zQJmOvqNAbA`!@i zrEXK>nGCLlxp@|@&=}I&b?4PZD_!ne4qsf-85|Go4rmX3EnizMSzZ--7jGkW+Z!Fk zCXE@)C&xvCQ2oQpvtk}{p6-@WmB~=@6$|k@6-bePHf}YXG(!a_;mD^P*Q3ds_8#2){0vIkZr?%Kr!pgr7|im^|GYpR1hlah+fmR0 zrbZcrVG_0oXh!YM^2-RN6A6;ToZSC0n{0cV*zj0p5=&2!wt3Xj>&E4}yxXC~(8?-` zE$7oQadbkw_yYzCC<(%fxeGSJoumVNBnq|{F^s#1xfd%`NjQLO&P z-j4qYdvY^@(2y?{%l{W)#oxnT;UB%I|5F|MH;es07v1XRPygVw9|h|U#^pTHaUqIr zQeZVZhzO;>aTb0dH{%az&gy#+tgahSLALov<^=Q1^*yZ;U6X_v2ITXH!-|a?7*32O z-=<%taTq?FK1ODKhtQ=Bhk#&N6Wc`zkfmRnv1SVgyujcEbIiZUh1i*ww zU0L86gdktkR!XsMxA$FaYQ}+>Emu$FUE-qfuVdWu!9;O+s_QCZ{pt`S|qCc(x3wS^sg{{@D$894p?w(@VO$jLDj(UNxfXL-+mr&>W5~x0QTHzD4Kw+h0?%DrH0upK#l2V1R#Umb}PW1 zUZ3WL!%?pvlEQv;ijwQD38)>uE#L9R)nOQi);`i$aI#hq7Jsa+8>C1f7~vMm{QUj# zNBoZf!9d&@ySG|0%t#cO(1n&>{Vj;i2q{qbHRMjk-i=4>SL|gHPWB(IoePF8(~ump zVyZQ;z)*?{ys2#ybVt7xpqe2*&Pl^X~A^Vj%`-qPz9)WKA15BjK78wL9iH zCaKp`cC?*VN-oEw-tgjt>#GPL(#zSU-%N4lPB$G2fqpEqF4 z!kg57=Qs|y(Fs13&pjO7uQ7S%bFa+QJXEy{tUsZgqnzcU00`K<8_+AC<)Zm6&iMV@ zZl)xNnd5iOR3rF9LLQ35Oi}?VO4h6|GyjZny+lqZKJhU`3n;J7K5m)*(cQOV9!*b2 z9pq}wZGou(X&}X4ysS%JqT6LYu`z%VWW|B_!jBjevF&!%zd>XY$erg&a2;if>ABt7D9mkNRm?PpTP}Qpt{Mgs(r;# zXCOv|5X&NR%}$`r%|arhGgP#VA4=9#vNN)Smd{m?cPj0td{+#TA4ep7Nj#j27h+GJ zGbMr0@he~H?AJPelw22b+-_LRD&F8L4dT(B7b{l~x(U|HpO$N}b>vIjUvC%Mm!J9n zxikL%mc)Ne-G8U_UkX$5rhk}BbMS(Tiq;3IoWgI$g;ao%f+&EC&Ic8Fxn)uUge_k% zz8ZCL>5IwbV25SC1AU~#NW^;2>drAvK2tT1|j zFC@hkpegd_2osB!hZw3;(T6yC63x}n?_g~s4x4i+m#>vm%UjuIAOWx78J*fUtc^_m z#;)}#hrkBmfvLNMj?J~0LtSpCGgg{6QgS+e#sM9u$0Jc%u|TGF@hvQt;a4@_Gl-$m z<)m+j8umkUbz948%JSdtFxg_a3m{MuSckBjBzT{^l`DX=C(oy1PEUJ~EsCyJ))MZS zbr^?A5#arE%vNFf&FH8@L6FHs=`ip7bLSgBGtCkV;@PILKB=us;AL8MDoZZ?${{#x z6gj*f7rvqz;`o_Dbq-NRYm4R?09L?00NMW#Q;0)IrSz=&NA5u50s0z__T;g;VO5Lw zL{yQmV!c~v9w5$RuhKzo#1nSkQrFk&rkXV?XOw5a$5WVF&QXBrwAc4qj#QL0kk z3%-nqYcc84xsiNJh7F|#%zy>0=DO5?ktX!5U~^H&a(k#>Klx>?5>Yf9U0-SCT54%g zGVD!dP(^<71RppsDY9P@I5y5VggG1*+apkmIee=^VUbwg3^M7{l{C_5X`rgB1>!j5 zKdBN%nA4`drh1K$C>Xeykf=Owh9m^f{cISIP0YH$3V>+mFxj3KpAXGbiQZ!o&?LY= z`u-Av$EJlne9{e5Z+zlSgXRuDI6QKE$(hzA{9BbJ4Hv>cKC*hFC+nvWqM*QSJKNDR zG!wt$7B8e?-fy%eAJOf)0NI2e5=N&G${`oZX}M1EJH}#6s&77g*YGiTn$xLWf$qTv zBtvPW<)m z;!T!z1#t6x`=$mX+q4x%!Ype24C8o#r`1gu0(H##h(ol%6!u7cw1qlY$~)Hp?(#SiVZP~B1ZvP7;{X5(J zXJtcidoweAn|~$m|JqEDuApirCy$^Wcsw>Gv1*(w;i_UJiaKf+FnA@keM5XV+=~Rb zas$)9x;ko=e7r_$TWIXg2h(rl6P)uM@H;m}Ft(B0Z(-`|Ug&2Ak5}EWU_!TT?3Rgh zDHwbl#^%?G+a=RV+l!6X+ud`^N&qE@(Z!c%XwUT5m&sg$q+ol3BnIP!(rsXUM$+3j zT8@!B(pur@?@aN zt1;i!hQzeMeh{tQaF|Q46{5lfYlMwHW#>mMX=;gQ}#9$5Gh59-qm$@12coVH|D58vkSuhVhzk^HA z1cAD40837rt;gA&E^=YR@^hKCgX)F<$0;Gw#iHQ7%$R^&vJy!~_nXX_!hte_n?yFp z2zzB%1UFZh421Wf^2gLF)1{D*SCt*X4XtrT1#2`E;?;QvOb?TjA8?4RGdk}xi@)2+WE&NJ(%n|2$Ln&nk8CD zsZ>k}e$t#Rwo62tZa)0FOT-O^2Q{>5AVarJGI>(Yns*uR``8hVYm<~vx{*$5a{mC1 zRGqNL=*%Q>v)n1C2vyzN7v_v!Q5)Hs}0Eo-a?H; zvj+4TF8%|-H3C_oX&0v{=Ojt08JCGEPb_)ONX-CCj&M&r0JVc^s$8YpnFJ$`6)y#h z`5)G(O<^+SVhQT}$>f~YXq>1`2(v!csB+-(H8&SLS25(V@x?d0hA=GwH|ey$d`%9( zd^Y8?c_72%kU~bIY#57c6yj?;$CdUKo9mLoC@Ji!&1=s3%;O^LRr*vh6q~&CBKoCob;SlOu_o zmb$bl_6PSz6ogu@6NQ(I=Ez0!^DidxYl}O`$&db_?$G#!OOVpDB z9}?Mc69ONhree+U*OLRkRj0Fl9gt&mi{!6cO(tb~(s#`ES+7kQw?%S2#9$mTNK)$3 zXiO`&ARsR|^0346rx418W^@ey<%=<}y#*s+?RSKt(Z$~ugzf~&wXOda;`;cQ3;Q-$jt*_c9wgH*FQ6UFGF(#LQs$s} zK5n~EnhkdVQX0yZssLg?ULA%7IDczCazS)y$W%WQ3M|GDi4T0ZBb!dUN3K7fji6vC z)Uhu*XZ{y7_;*St_KzstAIjMOo!0#Y11g<A*$6y-L-dvH*S81P+2qH=f6a-+eKU88SHzk6S$RY3_xqe#*qdsMy7vn7 z<9o+-@a5O1)x`SgyvsX^Hd8FiW3{Wtq2mO{p<4OpSC`uJ+ZFW&=mW53lf!=aglTt1 zCxe>jeI|T4tld^JNQ@JsSnZ(_`{a%-EJi;#`z!loMb*;}s?MPuQF0Bv^+YF!dQi;) zMcgOSj)6<}^#0MeJ9P36RQ6}+AkVfJg{x%G%JPoz%PJ@Ten(}u$bJTe&o7x|krRW@ z&np!`!K;=KCb>7M{zwE26cmh+u)~3Z38({F-R0o!VlmIpr)9BE7N8L?pZ0fxQk~NT zj%?(T03X-I4Qw>*W9-ok)Z~<*y@7U>SA$Z84Mx#~siD2w`I-z(8JO8ZvV5NT2aEV{ zAB)t`jB-NV=sCNE%AzMwbG>r6Wn#1hbyBjangsp0S8$hn9XSNMLy`UFx{j>F!*II} zIr12VmZH^L!CCoL^1Rvv^D)$Y>D}TI?fvkd>`LokJ&3$ihlhdUrHqSIvBHL&Ca3zU z+(zTrK#^YytsC!pWcthU1}SW%sZv|aA%r;^=uIY+Thu9J0ey8bSXUq(k`jy`NsP`= zge0b>G*hw<$601+1xosjbJ+_dk&Oxo6h}_|LBHG&*39Y-#Y4J|S&5~Wki%^V+(jx; zl8-~gqZ>@=1^Z=pW?MGKW_nVJi8cw)IU)|-^~k1Zez`%-5ED9%qcQ?{Ryn+Yp|Qp& z14+BoSg;LM-Xu@oesA8>T@{75HlUTiEU-7=ow&YOhBQvhTF)N8b-;FR`we4QK!xJG z5Od{bqQ_Y!MN1(PJG8amR{e_vm^46LU21Cet71GdR8+)IgfAD00IHwhMhP|Y&Mq)EqT;DED(F$V^X0AK8jznS}VFHH)2Oj z>Tz%}4e7;>YHLh%*mzu%y70+pkBv$pKkBSIwAW$d)M{`IQ#&;k zI7^;D-v+IYw%&?AL+%lwY2?I(HGd__p1n_7#g{iizWtPIz>~iqudKrW>h6LBh|f&RwA|qXJMiQWbd1?o(7q2j(MV+ zKT~Bv;p~zDo}~@g$c)v92+__ao_sUsxv@H3cG@MsCT-<5s95WxYwu^Ar$VeZVk<8# zUJtUEuTp}TFIb;ZYfpJ#<_|?un0N>g=@NyJ1!L7IesSU`Tx*+~%-{Yil{d&??=CtW zf#JTE|8T)%Gh>Nbe9)N3F-f3uk18V042oXe7Zd&Uhhy0i!EA=+WJ4uhYwI^ZRN0R= zR%K7pmsu&+nf2=3QWG1+6@>Jv)hon45(*O>JGkOiWTocO66g<2STlC9O#oqHq3Omh zZo8b&1L&E=ZY(tD9h}LQ?-Xl1#v482@?p@S*3e9HG@OKsgL_VD5p&|8g@R+Q)!5;4 zp%OC_KaCB4kZJ>{kV55iL*QmfiaS}@F-EHGA4?r z>h;obCVB-brtalS&1FQj0UPZZX3wn}sdzsmjN%YKP=UBccnGbat2OTa@-QOnYxm$Q zmFU9=AkY!m!-V-8U`4~VR%_qG(M*zd64)w3 zv=+$Z5B|Jeu>k7mAp2#6da>WKg;rcL01~i05zTpMVrv5A2&*UhO0l-?g;pgSP#HaQ zn!#h~0N;ta+reX*U_j_c0wgFjb4lBy>+5I)F}t)}AHtldEhndCOPWoImvEvYAR2P} zFa`F&P?lw{F28|C>XiIV5p)kJxh32k&>7}ZivL3c<_tc5^%(99ADalMTEZ>tWgUy= zwW(}c!i{H+cyeM^3^Af^q!B|9V_ak9D}_WJ#w2IbJd8vZE8vJ6C=yub;>7^rPQV^y zmEb?LK7v~gGC90d>j`F@f>z_-RTQo|1LK_mI#Ngz_r;asEq06wjG_(opx9`3nwEmPs-Y2Yc zyr!KfXil$UPIvug`hKTA@+qtO}v>4XbwQ||X=n&Ed9 z#~uyS@9^%9U~@h_7(Es$tWvGX{cy~=>0agsBh`b|=~L04b*gCPtI4e?S|vP_m{iBy zy3yO~kqTNg;!V*;-lRdy8D%r_B(ba{9UASH6eBA zX7(v=O4RJ=BN)=Wnfu`7%M6Le0|^_Z4H2V1vUsKU^Un^AKt^wj#upXFLjG@6u78GW z{yP7G&ueLJWv1`+pSY%8(bP=X?bv4UMf| zt15O%?NTFE^g;VUyGj@opK>YyCd=4q78p*96b&{Gg_tzDL?piC!^Gp>G5@1%rNk5d zCA~Ei2oxHiyq(R_U?Q2t_P~wq@FKJ08wxpL@XHl~4yRntoi<2sh?#Uw zep5MTTSyZee26Hi`iL(qwg~L4mMYE6(34a|*-sX1fogS@jckYk1XM-6!qg;A7}3vq*=FR3umQmvns78ZQHhO+o-f{+qP}nwpGbW)y?lG#~2dAQEoYL&52ra9Ll%;^UX>I#5UKXZ%AfY zV})rp5jbg)V|&aoxbyFvxE0G&zRNQs9lNzwkoUO&SWXc?*fGa^$|H+8$ z6D9)Jqp<%Lo;k!0NAOiaJE>Ehz3VYg8Y~)jC$}LE5#$cgoFeb*asa1L%aN#JjyJ3j zfzlqJIp1)=bax6wd|`&R&DLk^m{zh5ba?xadH6;X#zwVZX)}@LBIPq$=(Ks-Pq}v4zzVys1sp#o2wKla}@zzDc-wg$8f9KIYzFt0$Zpj$5Ry)U=Fq#6* zDE1x@QY6~c(Ux9W>091($51Z$btHYbuWm^!)6xAV^q^+Fqd#a6bf8ef1X8j5cvv$; zJwsH{-ob29wt{OqeEk~nRkZ2KC}rH|%IwuXXU#q1u#h~8SD!q{I8gKg zp!VoG3pmiAmJN?u<_6CzNC=-d)m48oqAqFs9iT`Emy$ROZlTNOM|T#xb!#mf*8K`b zOh)DMf<@@`>Xv(^2uDA!reL!y+2x2vFG}^-EaR#<2D?#4WnIJGQBDNi8kyEh=FTQq zj?M}mVTUR?$UoS3!cDSs7!xjyEs-aSm;=DMNJ+M(a9o#v(;ps(gr1|g#yTH7PL6k6 z-E1%`4AR3&USKp#i6Kw1yVUp~kaxf<`cRd7a{qucwK9H$O4Js0|6}}8le>R!aYEH2 zXgqjk<^-m-bRt*A2~z#~lWLQ5FMcfJPpL`)jc5VqZZ%It)zUXtYTLcJEcmT~nWzej zl5ehA*Xm3`jlwqMLU#j_Z~vo=D@oc$!VOs$jwJ#?Q;Xey1fVG=_i^lBEPG7zl-k<0$eeJm59F=p zcLEuhCG|_9cr8L(>g{5Qm77+oWDs>wkIiPG-d&IuPp%rV_M+qn<~ zgBjULKjrj;LuF!51c%v3290lMw6xYU)b&Sy0DK)#AF1iLROxHr^YqRY`8D0HnoHPSXbBT+Jfw=mKR2&M`!I`osG{5i!Hx=3y<}F<|@*W+Lvd-^G zD-e|Zi4)KcYeHZ#cQft0H*Zi)=plrkxtc3VZJ=4@3Y2CF96=Tq{%DnO@Hz@ST>LkH zGOe+l@X7h#HC#$(%I!PLb2P}al1@3(Bp@D1S7eB3RWsTBEkurHbfQ7XlZ;D9+6eOv z)d{%VAT{`zfs!jkj*o4WqxD{)_tA!VHm1a)-yR}3B=3$rc*)4@-8n-2Bq_Nga3|0mSGS*FFN;So%F9d{ zVxX8f^luy$t(T`6NB<4yo9aysafrfBoN^TDMM*Gj%JTFl>ib;Rq=*+7kr`n%j{GoN z^1i#nQ6y;~LG1kj%=?gy1lmh{>UF+Na_evW=47oTC8VvbL*V*Y<#|CHmW*{5mQs<) zIAgK>kVF4@V3do|v&vbUhxm*NIiCvuQ8da>tvvtM8!xaWhJXt!zXW#NA@B}<7D<0+ zY!kF9bPyc#Jwp}Gx-cy$#|+z8Y{t!SABQ5>JBl8`LNvMJ*XBo0~ z_t^2)?oddg{s*THtDpX|^+fGQ&2^|>-t#sO&%!`%mtdsE(ccS&(CSk7m!*{dKc%to z|4R#{U~KAar7xmy|Ll;AK@!UZ91jKOJ9Co$Y90ezBvdSsH-ysp0n7WwwG#seEO?(X| z0BHp%Yxv&(-ne+y)lISoH-(eh%|wM!$Xv1K9}y0oPbYXi;}GoAxMD!XnTys-b@-6m zoB`)Xvc1>g<7Bisyvv<1)Ls8=LVxuJH2`1@ceVbE_w?5HoYO-L3gg~2|I;H*%#R<(cj+cjziB{Z~9X4e$^6oGO z-lPH8d&Nt*AfnN~Xr`Q`N}D_J4fXY*IJ}vEQTWe2(uv8$I}5J$8d;-X;z1M0c}X7A zrxL?y_;FNOvdN^k5rm_p<|`W%J4Ono0#_YrJg&r&D(}d}hSyK93t5oS3u1w+b4)Pd7-3uFsJ>R2-_7 z*Q~!n+Tha5VAr%jn`av5s$#oWQy~`Nt%9Q7(s}v2(H&_)ick5cpQykXqt<@;dc>KFlLa28DjvjASOu7xVb$0)pcKufEm6 z&q=9f8qFn{b>Wt#@44gluY*j6PneK z^$l#Mdoa=8m7G`7`XDu{0iPBytri63NGdrMUFWqvDU$}Kd8}NtlGYLd{bBf9fYg{K z?aZAjX_}ViSNLN7*(8BP8arc$LSsak0Z)e&T6h^sk<~I~WJkk*(JCwT3QHQ}rkq1% zpHsUM-2xSKxA#C&k$)01o~QeUf*#8aa;wO_bha=j**vwQbhcrJdeEsBMT*O%*R=Q9 z)xvfgN_|$qWla`mw|lNnVPN990QdBUC5#Zt~w&_Sk8dM%^Z z_`i@GOT`rrGMeh6$Lcy00dxGH3;@(zw}N~)XPImrI!E)c-bn4nd3cOz=x6>tbb0h< zG^8UNe$;I*mt@$-gWn22tfSVE14dn9@YzghGJZJiW)Q*$#tOPZx+6&vPDhaEV)_Rt z08RYxLMTEUuXhH+5O`q$7kKHueDw=GF?tMX#q9s_P98{5P&oVi2TXHswTl2ZlY%2M znK7*)h2#j=GQnuKnt0jdK>_9WI}~FJL;YlLh7DH>VTIixJ|tzDZ>Ly3eM4+rGu};4 z%E50#CZ9fsOD&TPdEa4&%|%B)V%=1|O?sG&p;C5&j~(@m-jxkUs)Oa<@yg;jW1Vhq2prLF$Fk*TN0=h%zCvaf-)iUW&v7z2f> zg3!S|i?gI9UfJ^vB)laTuG%Z8WOPe=B3YKtxzrM!EnRS4L7MlIRNcMM zk|Y(vSnLC68vx3@^I+Et%Z$^!GGG2QJJ|3oo49K%yK7^9DG`-7chK3?PmY zyl&0AZ(!4JQL`RkyMs;7kQ1I}av>V%^z<05)!;U3xA))I)&xDH*gP8UHgK z68r(=m5F1;%i=xFqxZwr&e;HIK{SH_sJ3q~XOzelBOz3QIz*%yjLWIWR;CV}MnbzX zE`}w4#9XlJADG{y0g*3n(VN~m}YaZD1*(xv^ zR)JtkGv5StHD|SRmKqPD?|PjFd8o>naR z4TD0vWQ#FzW0~a2Z0<7*tZw@_xoeeuRnoVZc9EvsEoR5Pri#;PyfU80`T{F#N3NVeK=1p6V^d9K` zhMfO`W$?o8vWHPQoRa2PLpPygysb41=`&{4*+1Dn4%;>Sr&rg01jh}>b|2(xg0U`K z^9AlR%=HdzTXD-x_fcP)I}*+rdnGAqrvj!mFM9;yyyPXo1C4bF&8yTWB4)Mdvyf*n zXX)fcXsf^E-1bGPUiWH{<{GD8{@5D9m0(yR;u9ZPx(kzI#b2VkI?#fqU!7Hsfs6XPHS@mZ4mN0Sv5_Ue~#kP$=0DN z^%3WcB^r3s8I~Y4wOU}a%PA!9RL0E3zZfoPk<=Z-$ntT%f=OoKSg|T8iGOI@A9a4{ z`*%9E^$6cT`Vtq7g!yL`JX&W}u*t&@x?+E zB;LgA_M61*Gk2>B{nA+vPVVj_PuLl4H?d=ZwFfj*%Y!H``3zG~e9o$x` zQu`GmELRsQj5J?fB&!x_LwWoXM!Fv0tle3kViHDPootvA9gWXHuPfVmx_>QA; z)1)r-3Z(`xV2I56131W+*H=?8jo>YJiGu@~wd_*B$>n%s5|wr)Tk$S~`skh+j zK7d2nk8@;8;)i9G+HYab4A+ztbHWZQ_lOqLs(NLO3XUbKB|z1Bl7&mDK}r`z*P86l zZY1NTrSZGYV*M2`jG+VxzfkLd+KF%Rl*0#%vMxGj~2zia&IZ!BOq z$cHaAUB<&T5PnGoU8s@xWm$?guO&AXNCZSEKt=JSwy2`oEb(pka&?VSw76@g;mfBQ z1nnrktGpP)du2<0ucNLlIE<&}NCZT7gyWOaQbS{i3CYkC6V_lN^Mm+LLu22rQGvop zw>3#@<2x$FYu1RbRY@+Fqw%voQO=i$kpknq5vs`*=8onQMsuhM%<)n98>14nqPRkB zJ_geo+d^bz*@dKzhM+Ro9DAf0R$~-mb>K} z6?0Y8Z|TOr)veGjU<%ryFBe}bGIwN_*l=>I>0{td0M^`<@8MvVNT}PoY)>tx93|H1 zDg#ai_t`9y zMv{8|q5R%t^N$ z;Mp#LqW|_t^v#RK5o%aJKI=IaRGQa()QD?-#}{fZ@-Q-o!0HXpi9F*OmIqt~e4Wa(Xv zbpwiAh~70bcfh4VKa--a=gsCdNAhWbekT*1{E1>>W5C zt~7TUHlfsaxz+pQtB1hsSvE!jP=w3U`J8adD=mmWbITJ`^)RyS?2e;A-aZej$`Mt2 z;>oRb8PA3&UEmL3qV;qUWXX*ueyFbXN!EWXT~!!rH~W}uf)62xnQjlv^-O6W?(Wqtrb*PD*nP7ZSG})So!xTOKU6nZ$jj z&%kj_pZNL*IRqp4pwnj#&}5o^;~oQc4==i9XE{7s`>AX6&Dw6%3u@qn;d)s0R>uo% zGpLU<&lQMgNYQN(pqt(ABBIOogi^*32;tE`!Asv7HVQ=fu!<=`*Ek5#!kQZXK z=yb+F@P-oK`gCgH+;fykxhk0;7$8D=-{qUi!3vcc2{# z&Vw~SgO1oIRDLUv-h*3&CR#gk&&I)ebs!WzLGn9A_A!%8J|2brx98XkK8?~#vbiwt zeHcu#6=8zt^OUR?gujM;jJL*>*S}I|+CNR9eE(7k{fDO5ziY>4Me$nz^CJrTVmZgl z+x5b$BLdC7d;51({^-D#4LinCcZPCAtROA?sDeG(X}qD7%&Y++5-%Z-}+ethJ%~o zbfhP=yXY?0yv++l{(QHv$(wNmhCE1mMox)V7KR#X8fSY-TDyKS;OxKXf*Yc~^L)t( zAtqiK`ToHZe8y8Wr5IdY?bi7<6b}Je+PSIN`Lzyc|FnQ4{4cH4KUUh5oy@Hq{|&?s zsah*3p5XoACfLnK&l@|2MrUzrqmTVhtQ&Zh1W7D^KpY7?jHJ;1JkDL=71EEW^hs?e) z$3M^R*>AodAD=T_IUgro2tb?Rx@&sFAjtTQ`<$y(dp~fXZ)*d+Sy1=CEo`Tyr5Rj~ zeDiq=MT^<5GvJC2@N(-9zS$S&;Zlyg*)yl{&Y^wh>qls7H??v@pIN)*f?t!19$;~^ z6Y7UyQQ8&m-Xo#GJ6afle*T2nkGb(`v%AW9lEc?L(QA{a6XD4Vt`OoL`?c z&Wn%H6^!9Um%N-0?&re2_9r(m>cA$L<3Ldgu3Fo8lm|Cg$}+=IHEcvI+@ULSmUAV> zCeSzQApI6Q#LryhOonW3Fl5FwE$ZwqmZx)0?e|DYNb*!Tzm7?fvm2KlJjB*Fzyx<+ zM_d+FE;RiTieLYx0Dg_1VZ0ZxLUxn;Fna5VScPgeOZ5n?#!TXuBI>8xSF;Z!? z8@o4MvHQeQ9rk=cPTLxlA>K^PaQCBqEHcX2cKOhjh&(b8Ik%u7ZB9=^vRp(_Bc*3v zy=l3wkOg1bNWsU!O~ppl5naOp103q`PBKgHc`l|MP!NJyg#laP^?i(?aA@91kqH|Q zTT5V~yOW>B~0W?y(tTBD@4PY-ViQE=8=^nqC^+s+)8B1r8 zuChCy!uqMT9LCsy-q(Scv3zJ@O;D;Ihe2kSIH-4NX{c0q#To8;me9QVRXX^!M$k;5 z%9DH#fYq`)qBTYV#T$30XccRxF}%S>bU-~V_L3HvbAX3+Q772n!9e<38p7okq68gN zao=FPfqslFBmsFl!5;rcvbDE{z)rN-_+cMExCv%H6TT#2PK=}3(~(eE3V+1`*6l7Y zGR7`ml3)UJgoegjz!nsS64aLfrq}~HOoo{~zTz39eOz~3jEKmP%s}_(s$XXuJz3ns zua3i>LHK4RcpXK2oi7Hx={Z=#(_i~X@G#ZEZ{O0q2IB+OTK&(G-)XCjRgN^28El-` z_p(sF<`eg33mJ)PM3CnbZ<%?8uYw;SdwRK1d5_q*DX>RG8tcAm9mL*Hpbt$pfMN$w zU9F1td~Nvv7v`jGp_anHZTZJs@fEz^hf%L&&U3Jjbz$#}zD*|{<{iANYv`C}XHP9Q zRu@pg9A?*q&2BXWdufS*71|FX=TD$rSt(a$?S=B-$XIvB$N3LV(^{*jEHeuTA@mA~K?LM{d*&5hAef9z(2-sShOPX6!V1#lB4g{{u zualFi9+YMpe+A!^%J@c=#n>`W^LZQaV6QEvYCBaz&KcwX*+7>@)5`@l@!*d7Br9Oi zsH8R?Zc*NKqF0naZJ8_O<_Hn>_|WtzO+93xUnw%_X^&%rvF%|l+hx}q0Uj^a*bw+s zLmJ}MKL`9ui($izZG%VL5`L=T3D$x-L2MPJ5aeV$!ZL?R*py+9ca0pq#SboSyj-_l zY1kBOsAWMoCNOhKBjKoJHJsHLqeaaI34snWsjJT&vCpb^m#yOr&k&G8LjucLqLxluuH?<4A-XMd`I4VEl_a`xB#`7gu6y*^`ph( zAWasF>24IGwoe01xqwWjM4$IaD}cykq+!)fLLE86UpNm-n>vw~0dsIDX)Pn9RO%_4 zKf+D-r`oiwM#YG5g}%1)%`-q!6_0yyMvf?<=p&VH6@@zBi=-q7ffJ`LY4OuAD*b+- z7NWiS6Us@S)uR@|5Ogc#><`e>9{uIWf*a^eLU770Tl4``XAqe^xa{1-(n9M`)7u}} zLu71`x(AS-KQV5}IzxMQjo;B~c5mF!{uGy(+;ULmwg|u{52y*XKkLCQ_Y0$wjs`T@ z-TM#3phpwLYd}dziG6EC5^7zn77Qzd|3*SnMJA4{5Sw3Xz^>^R#bhc7a4bk5#(I<@ zon0P?c8)}Hx`5Kdxs?rX&Hlb6tYbskAp_jNZ>HarQRxtxZeEP5&+m_4KO4alAlcQZ zxvw3Nny-cqprlIo|Mir~bLS54ELjgr(T5)JgQRssPYmi+SZ&h`X$m!0fUW>T6D|P6 zsFr*rS2BHMH-$Y>E0v$dx&T(}KDAqvRl7Ed!Gqg)m|1p5jyT$9#9iqD=2AM}VO`k^ z^~md(I=M9*sw6>;xO?z9q`^2vDpHcPt?k_L{aBV&6y0B&6s^OL@IyZg_B5BzFmrpm~N7vJX*c zPUtvm>7;$kKyB;Tsa);YDgF&juba-;lX^UnXxw%$8TkRRc{wItc-SEX;#Mu5FSkfZ}_>5`?=prs&fsUWFJg!BH#C^nLTG-QLxLml&}sb!oVK&(#X z(%{>rzV+$^hh1#d2qSfi@$XrfjV!uk>(w%3xdfihlxIt z{HG$haCoQ(Et(rW(!2c^zYRKn>zjZ)cd{NWet(O&hRAm|u%z*sFX>eiCgj-%Kc3{5Yj0B4a1720g$LN;y^1`YzyV@Y3^>D}&0&we1x(IdE7mOH1a zS#-94r$GM*jeQ{M@0aHrfzC;sB-3Nb8t2$YA6peY+Lk@?0hL@UXpQ4e9_Wpx2H~W$ zpsNjNul3Pb3GX)Qi+Tw@6;WV8V16NGhdm`c&Or22+;? zQYZQ?vNBO|p#~$3l1ytc!fO^HFD?i0Kt1yiPl*85_QIv25NuOQNa=ZMnm!n{fT8Pq z2@E|VKdM9I))S`~NJ1z8NkKC?CDIT-IY(BdU%e43Qcd`%j0zj&_}BvirUJ)4?E^uU@r2yc~ zTdMlxH?G7;5xd?bIK$Gn6HGEpQZbZB(0MJ4WW%eZUU$#K;IUeOSqm>E zRzuZ2nElYNT(S0gClsHr4lM2I);u|TD zq9<$oHE>JNIX75=ScloTWw#t!)yH+VU}G$kaiwqUycXBddMUAsyDP za5JD_Mz>lcL8omHt&}fuIbLDe0Lr&9P6AxhAJWsRIQhC9RB+Dq z`F9z*x(h@b`D+uDzPOhEJ$+jG|79c0ZA@jH%w!$Dq}u*VVY*7qQ!aDq%fa@hZs*#> z9aQaI?}v!+514Pw@~Hd@dOy^UklY6c7lUa#boB=6BRVD~T$7d;Eti}0sjUw2vC%fLi%(*?b;pq%fd|sCee!DDu_JPZ|B<~G0K5Iba zb+Hk&o_aoJB>JebM z!PzN|M|_cBuA78DDYZy@-vl_23j5JeFt)L^dSq#kG*9+Ms3SyGT z&nS>L8j7V?Y91!!NfpUIuw$z7LIeT=nrqM-`V1(e>lZPjMvqh;B+S!i#I7inr9O`g z4Bqb(YYpyGz=4H0aE5gl%TI!pFeK(HWz_K3Z?HDg%fh;1SPlwJSVF$T$x9Mp8XXZY zM!tcGm-Zs_%l%>T@;2p0x4D6SgJNnPn!e{&l1j>D5wIO!QtUR31P!#!D2~1w3i?D!G zaV(ilQyO$Cybb=X!4m zcDy1Sqaqx(i`fenoM*_ST4ds?WT)ln%ErPx?lYb_@( z?(t_##*}!)vRhY){ckqvC>!U6T7D6O3#@V(I52gm@0iC`{LPbe(VHRq4~sFb?I#T| zDP)FzRSDIxNCe@?ALC=>Iv5cPT~RZHQamXMzOE);q|K%hlXQ;y_AW*S)W?h|eteke z&-E1T?mkQw+){oJTYTeE?(6E~Nvaw#(C@mHRLEzADcBNSzHkZfT)`u4)nvG>kdjPX zXT6H8t9};Si@WCATnD`}jcm8nw%G?$_nFU*m-Dq7e%z@Bt*1gig-j4qfcscizlLYw zJAZ1!Uml$69!jIqve)J)LfqDa)a)t*-^=Qys9?YK+cQd-*oKP`$#)A@1?zI$QoXPH zJ)SPzmV?ynvBC%5a@fK%P`?HH(|$?n>xu^t+wRIJNc;|lS3cA)<@~m>fM&_uZ^(rT zhebG4`0h3D+7uM>hkYUmnRZ6_{x?b~q&#rhuFf@@dghI3v*PIl;0|EHF5-``E*>Be%_Y&*@OuF#5Nom#8@KONh}P)Hewn5hjbs-$Vh8WuDj8 zVwf$%&%SD5^Jd96QLtg*(s0A;k?V}M5rG&1EVcO6zzvTTS z^0_;Kig^fj`r{X0ys&lYOtpj$U`|G9`Os&8{fj~Qx}uKBJrq2lqG$pIQ0=$a^_D3{ zXQ1Xdc25g0oL}MEe&d>Y1YD*vF zi*xbpFs_4_KDewp^mDd|a^NAIW?yC2YhY+92L-hJ3@VX5X+Ue^CP9jA=1_k|TxPn4h%5)2*6MSnV!k9-lL)^#|(_+0iN;j^;WkWflC z_UrYisJJqKAURItJQuIPmAL4OxM-YF z8P+|n*WeaRR+zw(1)oChpjxiKFWiYRiBbE?btEm?YOMu0= zS`Mnp_}cv+G6Jg#B@TOxPd_}FLvlS@DVG?7GC_*obQftOCR>oQyQ2`$SHVIjwK zRc8XEQ3wFe=RCbfRA>Y?ymJ=nJQlekDj9Djs7;Nmlf|TL%?fRgY@4eUZFaTU8qyd}P8OBw5r#^eMAmQja>kuAhhvB* zgFMZdDaDBwH)vDkiwDECMzH%**$g)zm`v!fxJu+z@C`Q}BI$$bGu+H6;pcoaMsBQX z@im?gxA?tz06UwiTFPXlBdhWeXA)(K=E~UH5|{`7{M(nEs(R@)Uz?nKE7}Qke)RX` zanvSs@}AU3nKsx5Nq@S&O$r*d z=x2qJvuuj?efk{gqYMQ=h393QwR4FvAk0~AhpSkXjJ5|95)`dI5i1|ee3#J$sqUkR zG-SOVM7_?7_ohO-*tkU|EtA*@QT^i1;z67}13LW#UjW;EH@Dw>Vq$JddHM)$DYi{q z-ow!L5HN@V|GkVFaa6YH;2Y6S%d5!Cg@UCUN zV0hx>)IHy_zrpI((%#uVp}{u{q$Xn~6iF3}nKDEu_2DW2BvY_gy~@JaizL;v8-v@3 zd8rbsO<)RLa(9jMKkIN4+P89Glmm~zpdK78e9n&wJN`@mPvC)){lm)g0#kHQYzF^ zyy!2IFIFYm!nA+TnpPZ6tYWuCRUP%kGRHn1pyF!^`(WqE;>bgE29LC+tcT5y zQNq;v@7v?A9m8tLBt}pZE80{F(X5$?TwBj)$9mF|JgZAg)3{S4s1SyD4{@My)oX(p zFH2~6roJyoYy29ku1Yjd=_T0`!0+-mfpLqK0k_NO%=~p@0nMZSOF>IKG0=PdL;N9A zBJ&jOjHWVA9Sx!=>IL4sZWnMyswJF=7E(y>l|s(B9T!}etipEd#}tacU$jSL4g#Cc za2s}5!l@qi`$g&8FXymcn6!Rg=UXaM{0nQR5Q{;?S@wpx%V3#`xy+QgJaA0zTp0zo z478LAPjx-JwTv}HI0mQn!$}^3@TE?;3JZd5rV6$&$FTK6!a~R}GYk8NfJalZhPXUU z4(&pdL0zCIiZrBesU@f4?;6~D$Z5p+RXQvm(34vEMa7;-x2j8zNEJGf8;N$nAT=I+QnzRzRa$PVp%K6R2)X|`dJ%X@ zt0KUOKfFw8N z%3)rNO2MrDKVEdiR(%xF6E3JUSOW$#NRi<_kzNz7rb>f=`~kH;5Pu=>5DIlYURWTY zf&WB_`$y!h@c)8bjExkG^{qtAjjjG0EV-m4FY|@PvxIZ~!@pZ}`dx*v4D(8e(R~y2 zr_Ve6Q*R|aB3q)31(_0Pf z2`Yh}g7MIeB#)$E?rFoPC%vQr3a$1#k;X888-@!>LdTT)fdU7KO`)mzM3bYd$g0=* zm>s@)8IKa8#3Mv;uCeWu71Xtr3J#ckp;?PkFb8F{RHMaGDwR`9ufQz$H&DaWtg-!@ z<(F&Acy2f()Ud_H+wo$N0qSaBNI2C>bg8Z4*p7P?SYwURnUWHNAHk{fk50~Q)&uJ( zFhFw#!h{VU8eA#XOTQ=9QeBMDo2$!vmSaqXlMUE$pL>&L*}G4m_?w2O7*RRQxyGxp z?Wj7J#`c3i&RsF!HWWX5FRp7Z{<$Z0ND38i1Q!%Nb=On|c*xyY9T-#rQC9-{k3%eY zZ>oEQx?F8{^b+bJ;>pSFFz$9>6$K5kn`d~$i&VEnZNlI$s=u~9e4LTi^$W0i{wLAC ze-s9i{eRi^|2tqM{@?zg2^)V+#s~kAo@b*E4pzubRLm z9b8wN_U@BM6~q#oLSx=}C@qvl9EewZV>;MnsXtnjP06_-jZsCey82p3wj!C7Mvq8W;`Tm^@Jh4chb)YCEu`;ni^K}tO43|3+5t||5o~bv z(8sR7c}fO-a3zxDCfmh0%dPj)gD4;tQtfwlTLaW5*;}J=U=NPbWPiDhSeEBvxTp~Q z*yvuC;A}PTKaO$}vC)stlexO}X&ks{8JJk#!)yBM=FPh58W;pK(*qZ#i`qRtG%$~W zyrij%sy|Wxiq|`K?=#2r^+*=|x$QCyI>p4K1=}~vEN(b&-RqOEwB`ji;!onJLOY(k z8jA{(=}~Y```nBbZ&?lZI}~%zoQDhOl7{8NOfCaIr+uVLpz`pf7A68oW-r|u^ql44 z7)Z7cDCfIXkLY!l`!51H^2Y7lTk-+Iy;&eY|2~jp;4;ueU=i$&0i8n5#X$#~1#^m%TBkSAI zMF|m5gj%CL{DJW*n{KgL|1KB|2AmedaXr0iWLl%$lK({QIe3UXwhPNkcf~{X#IyS< zl1*v5HX4~tN=X(cO-!3tl2BO2mmQ?jzDki&NIo9_|q zH9e||k|rH2YrYzj=N4Wb>+k5othiw4w#|JGhRvNukfnt@wFubBN@0O!%k&UhVeFxf zsm6tQ>pV-1LG#!#wbcWN%m^p&M1$joZ{9_TfFu*%((ye8zxR@< z+G~kG^88ikd_BdNkP_>A)0B_#o4EJK9zyBwsO1L3(q#=zAMhk`4??ojvD)$0G(?oV zKt)Va-5(xNT*AEzF?ymoSI?tejJls7&_T;MsQAWe#JJeG!fLpBVYAqJX|;)any`71 z@*aVLm?NmgV>7!f*YQ0elqzFyZjnE|;7i0s=0f!iG4t3&sbUz_nZoIRfn}0#3QrVs zZO9cp!2K1i8p@_<)L+qx`cI?vU$Ynd@~<|xu{HlsE)7+QlD7ZGF2c9b5|q?MC7%`e zArng%DhX3cNGwO4rhppSYO@(c?O=5%TId7W4MOmZGEd?!Zc&Hbad7Gun{pYSKPAtk zq3H=LXZDvT!}~i}FF=dd*6Zc<;G^W`hLSDho|IBeVc*|@mhvLr&lrRX_Q;bV@eEwB zui6n%0{9ZlgCQ-K zSVgxGY?-cg*(^Q{diOjB$qsG4b^jt4;f%=YcoWX+Gz#9B7^&G{hPPtf5+gB{L9N_x zR+ZRfL(VD z=ybjUNqA(hag++61Dj9sc$|r4F7K)S z0kd9nh-f^emrMuEnsUIED6i1=_?0XqMBSywEzP&rvZs$6(lhlVlCZ zRUx|9HHQ4+i7dFZwzx|(St$c7J%w81)mCLzRWceSkvqyeP8%pEV186mwmSHp{Vj1% zS^i5K=PL|X|7jTh&)l#6JMB(seJ2NVHxXwW!~ai~IxBYO%l!&=xX1jWdYRV^*$YJ2 z4$&6cUoJc(Jol74tJr${S}H9~`(cUe1&AjxmHUx6+%J&t*W0hSnVM$=APhG0I!%L` z!R|i0VR?=5`TD-8u`}Yqpd#ir5>1SAju#`#@d-)E?D7`kF&}VQu`*u~&1?FaM>{nT zZJ4e4ar^hXPQ)Lpa`u&XD*kEfh2wvenf~`O{yqCeOwaUx&Pqyu=O3SB9d->G1uFj= zgDMBWxOyoq)G#eBv2;16AL*d%gtK{y*7M|6)12=fFFh&w9myvUZ`zA*WCI53AOe1r z>)OWJTH8rlR$5jKFOSbRxq&U*VY@Hg1QUl^yD1?G1dx>x`C&M~78AW?Ka0FRW>g0Q zhIberfdt8cDD3lqT2COE8EXLNt0MBR35r-d~BEexa%Kg65%Iz)g-A>RVMxK2+W z$ys8S4#I@o>;^BVBD$fui>i|iZN8W=h5WkiC1|YH&H;kF`f8`d&`nQOq43JqMnZFV zxhOwDbz6T`?3*LkWJvAx9(>Xw67qr#6LvMJ$J3uXES-`zLW*)j3Tf1Z-7l$9q4&fP zqr(nS|L#rYbv@$>e0>gN z|I<};*{|9b0bl^o1n^c~Fgos2~t%#FnV&of(xf9n-S#Z1Wv z&?5%PB9-~`p2D;)MMbqMp%_+UMxFw@R0gl}jdkH!d4_eT!w~d_FrcIO!Ns{Snv(9Y zGwSXTF zs6H&zYeoqIu$9DmRRqd@fx~=cn0C0fmu@F+dyS0i z_PAHVBN-aDgK=pOBBr>1{26uF4uVv5JoiTKY0UXXIGl(HPPlG7r`?|}*-dvoK4WUA zfacxgg)vW1jg(&kua$ok$O`jLQ;AVx$|3dUh9lCDV=B;9>Inf82i`YZw-X6>DKSVQ zzkeiKCqWP|Ho0oWe~)1UQxrHTG|pJSv6L+Kl-H$nAmcd0^tg+^)-cfCN}QlVXBQ#E zb7e28xfl*lW5{e`9-%2(e)uIJE79_}?=nVNMBQQ4ejy`Is~Mez-5eQ3GBLWsg4ZG| zV73!>n6iQ4_)c@o@yXj|OdDgp8cg?#gU3_AKaor=2eAUI+QC40mo{~%UMAN~PiIvn zDB*-Akehb)-CGrS%z&bq<&h9Bf;hf~o4V(?tXHm;u5PtQ>2tBXyDS8$j|jP)zzy!+ z$E3`htR&@8qZoObfRNm@D$OO#Y@Bk=q;he8C}{*W@_%vmjzN}&+mdj1RaaG)ZFSkU zZQHhO+qP}nwzbQ)*=0_hbH5ui=f>RoO`IP)-q^AC&*xoFu3Wh?LvDdox912_ixSNE z*x`jC^$~=ledYKC70HwUmxqAK`Es*Fq66IQ*0pTAW%Bo|&;C3J8yU7{1!v2N)bF>7 z)@p!rHu!Tu)^*0Q+i}kBXz5=6meA{NoncOR~g2B4a zQHawd@m6Im=76I|v)FDWTX-j$2@ddgt%U zQQDL84Dm_$6(%k$txW%rUb*N4IkbFUgI5#`WKUcQ!lXv+86J+3s54cX7$ixWS9WU2 znin*`8m!8?RGS$!npTRkcouZtp`KVR_5BA2c?)rqroyGn>E^*k)d_oMoF|JuYpS)P zvcywrDnfug<=*6QQh884*=3or`rfo9B|?PGRPzwT_Rt>Yj#jI z^i~u+xTL=1kG_~+(<(N&S90eFdhz{F`7|bQ3_wZjqi0db??&}24ESCiN z&Lgk)ryWPb&?h@%8(*`87Z9L)4julkH(XfW-1Kdp=TZi3fSR+cDxtf3PR~CT^KaKD z0Q+wk>iq3b@!uCZ(SPIaQLz2)i;Vs+bxwK40Z9nylbxesz?wMY#=uW0-#;82Q%#wX z_jfEWg4!rey%?k5pM)_(`qkC6S{@*=r0iBV|N2hTBxPzvHT58z-$smysIZz=^Em#qRkfY66QTQOEMdrd0 z5^E)6+#q(Oc4Rf^6>CmoJ6iM_4H^sV5CM&; zf8RR|T89+B$g5jV$UTbhMcsF6jaG_Rt05JmoZ%+x+$u9D5z`H1Unc`z8?CU zIkDL{ICEv)2P_O%<`H~bX_GKJ8gRi-Ebbmq)rbQ2zr)O=tAr`VrWp>TVim{96|n9< zEVpbom0+MZ+1+O=@?=DKs70rLLaSj1pdpxgEJaFi-#LEpAQP~L zuHL-cjCw&IQPddCXEkbgfbHOjD0vvaU+hmYlGZ|;3Pyet3V48d$h^X8onLk;>Y-WS zNJTbXefE3@#+KPxYRa4lTt#sxn!>PNJj+PQm!BQgGA3(HT)<`{jez zM#=!F#q;PTTiDPhMRT~D&y7wyr;r?-RoX(E|E%m}%l-&9#~Rk|rfwF{1=AtI<91W3 z-5!z)m+32U*M;A+@F%}Wrpe}gCPuh;2nWg@`0EMbrd%qtKilC+v?zb?Vc%x-drT2JD`MLhz+TzTL80|)_}sG4}c zoIcq&ry0z;bnmesL|&vyW%&6w2|(8J54Zx@Z4+!(Q0V+ zqZId|#5J>iFEgBwcDNhmtHqq>^vVeCvs*c#6L3VIu$sUU;@fqRq1DQ)-{+TnL2M)jjp2ywvcC7gH05qOp2$X>{jqK4CR}#q~num|f1BYP* zQ3L1BbNeIg0f`Np?K)qgX&cCgEXu&vZMy3*g9-M18nuw&E} z&k~l0C5t$nzNl&w%Qteq`1s#y6#V%iR95&={rY^Ba;^NX6%v^ra}$C}tdv*#$Y(*b zq0UcDQP{QK(O13$;{HRotV5ro>RbLIpUr;zXWosJ}r z*{A>VUhS8$3odJ%+~BGM1?^!$b;%(&7&&+1{TUmM4V0cn8Bl#&%t z?|dNn2XS=>#t1?8-5$h$OECZYGOh4$lxaaTXEQ@1!~dia4E}EwTS-F&Qwix4CT)yY z^k9Aqu z6HTYn)1<$u*?G6#;&5`+B&Vy#i|6HG2G`~1K^>L=&sNMX5cTlQ&tm=1T>)U+q1=6W zsD)IzSj9;-;1uXd^i&pGA>C3kuXRV|qU}bmCu1`?UP|yx)te1t-S)on)9<{&?zYdj zmIX+k--0Gq%P>d3@DaZai23!^UydIt8)&_R?$(>YFA=iNct}#MG-d!T zkAK_ArmYt@kvSwUo6ag%>w#vV+80}}XBBTwu3G>3u$rL*Zcox^Tz8gQLb;5BK9yLG zFAA`j$$>xNK`Kd03Tql_8UoN&$`rbA zF?DDa;LB9^Uepn^pRQRY-Sb|F^z|chC_kuo6Gb$a4?IKub@QIE%&_YWhX+>KC*4B? z&KZ{Lm&dx^tL&Yhkf@~pi_XCiO;2vu8La@6l(L3xX@@K`O}FWOwf36a2;{ft!(^Ab zR8l9xZ@E69G(cD1bH)66=rfe^1}#v7Ijqzq6J&y!<`*PWOkLGX+azNvdRLSp$lM)&Hhvq{ec|3q`7&dsnt8 zZ8u8#)Km?k+s64ZNKc}pa(k3JRH0+KiL$CNAOIfVTO4#K@^fYJ)?LANCuW@#2GOK(ZCd8jsxxAA-~G45-Cd|(22+=Y8%3Gpb>@oi1G7DSgGLn@ z;iZW0*MJM>!%X>m5{{E=bm;5DNPX6_Je9LVpluGl6+OR}Z4A`;Rp6eSvb}K@VD>Zh zp?%r+8`Xkn=%7OAm`_?F9B!VUTBCrj^2J|K(rL$P3b2p#f^LyY?O+fAG7ZXP-UX43 zp-^N=MOCyczsnZ%l0oZ&EmMp1JpIJRg+i6Rw3CA&D34yc^pD1(Y+2^hE(q?qJo#wQ zJc`&5w;pHf?C!Q9neP50IxO|5N9gHWG7I!S!o&YJ+3dge!F(2GR(k&}MpV(T#Z*E6 zR9=gqoQT5~nSw~4=gnA4R!}mdQ;ILP+h>)#p{m;-rZcP8t}2Ww)Dlr=a~6Ok^2-|l zPTZZhKbO=kW|*XH_BSA*A9}?8%CPlJ4ULQ8Q$M3i9~!Sr%EcA zS3nvZ-;Uas1FEr!32uvo&03X*B?N@rr@XjhYRfb!E(&!lY(F3pA`^{;?QQuLmtauP z78hm*E-%f$&b?gb5xg&jkra$vOe*BxzV2*k6BB5w@>KZCEhnRea4^Jj1j9_xq;f5g zP65woKh^>xNvyy);)P!BQQTRJ-+HtP`5U+CC090{Dpvp!sxh=r`xp-;k%uMDQ{^dp$q0ta${tC8cI`Ku>n&e(;C#tcjl9ZXsZ!IE(HcMp&roT0 zXP)7dD_2`em7tL=^?AkmYBw9lZcb=90)|vxAq&h?(?&xoAC5Y!{4I4%Z?{3OMWUlq zTwN=jc%kkc#KidJi$<@%!Z#!9Fp9_^GYR!+On73kXFpr6WHp1~Vv(JcLVJ|q<}u)? z{43y005Vd^m2Z$tF}Kor_Op8FPzx(uSJ)0?cP;!|Z z$#MZ^uhU}_+zp^NYJp!UWrkr6_0_swnzocnrRj4_1+n|NFq{cL5MtXB7-Ca4p)OW< zFIpgfT7!&WGSiCx=PCe3KM+-97d{ubnIci?o2x)@g>(|YB)SgM##&*)0W zNL#XN3H4VMjy?xqOC2n;M+Pl3azo~+KEOcd33_bcinfXdYRB8Z^@PchcS;5x&_Y5I z)CfsuIpBo=vr%k4a`mS_vl>mBj*H!4jlRoi_04*>!tK#|wZ(ZSy_W8*df&a;AY*?i zE!b4YV*Yr}DHQF9Q>9E*Xx|vT)UnP*s+uMQGh0jStpzHAO@=3y&vEuJ!_u+VE$yE#2}j`Ad0DF-qHnd((M1CeFV)K99JVwuYk7_24hZ2*W?hiHGUFzYSx^`-HEne8i`j*F6uG~`~l(VcsF#SRGPrH(hr>%}*^JKH- z57BZ-*q$nKEnwiy5h5(4teX#)l`ApJLrh|DaNHXo+`+7O>)mt0z>ZwF21xr2aq)B= zu}%$l6uggFlNVZ%MG|h`7~4n?s8+D2JBqMyB2<=;t-T2|0&>e+?Z95mS~%k zE}L*SFSL=7h-hxZpCn_%Y8+06Tl~v0MpL#Z7 z34j1nA)b>w8-Erb-xE5Mpixk3ISBS5$y_eNtjT`?a&T|@0h-Yqb)xf9<)~M~g$ez6Lmfal; z&CUTZ2Y(vctYv##@pu@GBj_F%U%KZp4gH2CxJ2@EBbV^@V}rQ++}b&OMWX!<8Ex*xEO;jM>Nfmih8lw6 z#u^G5sj>FOsa6tk7`?5cb3dFIT+#^3d)CZ# z;C5XNl`TmRfiLz9f$OvVw-k(*6^?Vusva|cMQLhrdin;uBJ|#v?_BFn^)Wj35b}*u z;6SM1O-rs3{G8#(xYwi#pHJXLn81QrjTO*uVF-Z9W6>Qztau4=>G`V^$MB=lymL3XZKPjTjMtx5J~u!iYE zlqEHTbjs0p@{HOzcngZ;2NadSkh%qqh)i2K)oLiW z57S^aeu6h(o9@NtAAQo?uf8OvZ>+)u_doSX|8FUY|B6@s_p+6&k-eFX;lEP&|8*eP zOvUBSRrCkp7CBE`BNmtsz)Kq(5cn%L^d?AV{d}If?JC{_?-})-VR%sZK7gke*C>+< zJ_>x8@xzv(!J%R1YLc^IyW8glLKkKR@stUhlYJaJ70vUEonBM*=k#jfipiWgL5m%xr8O;(n z7Z#QPo`E(754XioG23Y61y;07A0Fr27qgKEW(7VE0DWqs`M!*Yovf2AK1>01P2L51 zP3=?DJ`=042;E0pOO~`Ez2*epz5C$HDUh*t+}FJ-aPD9-4G8%OH61LEuLI z*TAQd`Vf`Wq0Im7_QVi!?5cP@!8eq?OjtF+*y z#DlJqVp$@eFn(-oaLp;`7;NC~~!BLhd^)`j)Kw9Wq8$92(~ zgjs{Gu&M1jA{5jqS=g!Nc;9f8*^SH?Vd78KE)KfjhbJjUm`vFrMYf3G5E_>j2nIan zs{Ggu_#df6ai+M)t#&A{0JQv43&W~E5!~|wO=U2uR_y_jRcn0BkKk>vX7{vXoI=3h z)d`OB9%uw;LFgj-#6swmRH}iXkxSh83}XISc`=HQP%ksJ^{!v2J7y59@!DqhShK1v zr~ObaqtkKS61h+FSq7~+ufueHn1-wOEj*h6|I7?rltT8``yNb<{mZ=Yze)qu{tYrf z%FMvt#=+Lq$lgfS-p1VMpW1={lfwPabKaz=VT14;=?jX2(p)j5UQxB=-Y1^YtWmjF zB#av##RQO$)po^bMqDvo#p{5q;~5%M$%zUpz3s!@iJ{L{qeU~2mpU29WN@JWo3-w8 z^cGXI{UgzqCW5k>tgdp~+tqW&x>BV(WgCULgtQ>5S8M(ajK`_<+`{d-dA=yO|3o*q^e7ILE5H zk%>?&2CD=DiMokqG3nQUF2In+b}+gkU!5Dl;=}ie&FE#+g%iD8J+zeS$th8CqqjH= zJ(F2)FEA`2l{s#J46&irY!79e*t(!{KRQfkgJ=&+pcsk`Iq%Z0$B4(GoCE5x0Q>Tx zbM&$TM@YZqcw`ich8PEL0PqZ=^sc8Tn(K4&y3JoWObi+B1?qwYKhJ4BE4UP6V2EVq z?M6mM6GOrzzz8fj-U@@fM@&7JV=`+f$v1I`l=5R$Ly5$lrN zQ94e$HXNAN!pS$ViJ5mkeHnDNaz@lEbUTwMt(c`3Gn2q<_zh%o9|#~xy|?$fE?Dxy zVC*$iFitQ&SvbOr&%N|sX0-DQ_|XcAgT<5GU#Wu#B3oUUto$v-E~ru1#~tU`tR#MV znB^AnA65J}3EGzW_W_6hHa+^^Y}bDsh^zh^2mJq=zW&#~^IK*3pAwJ%7>s}KZQ3d> zqJL#|eCLrpiH!ycf&|&|*AoU;rY-W;^71ocgi0ZSmyH`g#cOIh4_twUsW)M~RohgA zLdgFTB7gSP?Hk2yVxaeGnRaCV_}WNSnQq*VeB?O3*rcolFe0}edmeKfzju$k zbYEv4PMYwf0nPfiNNGmdq?-=3KzXhQhCFT4B43ykWG--kqY};+)9X^gMOQbkA0xd9KS;@TgtxjUay9 z6(L5^=NWMoR6|0^NSi zSl-;4>u9cs@N;7L#ZjN;i5Ev^DOxyU2}>1CTUybvY@>Sv1>-!gdmJs8&IfjZhbqwiZ!<0FTlyz0| zF9ylCCm7)yi14y1@z}SSNVza#n}33+%Nm;r7}aJUh$a^+0l0;!$g~*J`0c$j$v#rG zUaAJqikQ#DCsVAGxd^inL!gIf#Dl?l@WqBySRSKYxqJPXpgZtLfn8h~iZGV^aq-v8 z+SO^ zrydf#e_b3ZgdtS`AR8~)`Y6Fc8}XI`Gubx5eLlHDjKjp`91IqD(&&h~20>2F~ghE==NNkbF-{y{1UU&8(~+UvZS(V{bro#e3K^nB{f2Gw+MI#=gUm9-Mr z)M9BDADu;Z@FKl7x*##L`clVO^>|S4GVjdJXX8Py1!W+^#iP@}!;vhprUer-PNajS zrD7>{@dvA60cUDeY&;f;Y=I@2jCK72T6!z*L_2HD5OS|nEX|F}Q^0{e4&6F?s{!Bl z+!oU2$|O{a*4L6nFk{(-12IUD%n)69T33POG;s{EX?koy)4s4VM}pgMXYmKj{)l2B zuq(6(kZKf@{%l`{bfuB%ThT9V%pGmj@=n2vVcT_=o(1; zSdU}45&mJbM-}`GRe6a`ac_M}z_U)o0F4E?!%EzCg80)Dqyp`=`#pRBE{*$OE3e8q zUjJ%bO;Igai6J~_vYj$Wm03W2b$#SQa-KQ@s;avqL&W(5BySi(y4?*suEL>hkQJm% z%p%_9{z%?A`Z@(fOQN^|Jp*+(INM=L1Fu0+akRqJ+nFW&K7Dq0k&yPl5TWhXTMoPs zPVUz@)z%YZ9isFAC}n<$ASPNDgQI33vMGr> z(dH3EbsilE!kiMPj^MW31(}hc44t%B?4xFg^_l}$)bMUm2ryhUwUuSLl0}pHCIk3m z`;RU^^#u1Fm_Skv_t17}>Jj!z)S75ocQGhLK$IYv|0{Xf9=sy1TzT$m*!(XiL^*bA z;x&m1##iRwMb>fRWdw{IAxNyqS%LMA3CXpG!js|D1)+4nm0(iyTS+`z4U(8CI zFxkjUouAI0A1}UdD7il+qsX<62IIPoMXrB;yU9b&w_`O+Y%#j%Pmrr|^iDcPJ8GXE z(aLt6g|IiVbjtIuJH*RBcGuTe#AJ^?^PZM1K~L5-U5Iq^&y!&|f()jcDm~5l9WO3p zm&EOJ^5;zbk>L zw2@to51pYNwYX3FM3OsyaQY@1&)}vy!+{++y7^f4$*}rnY>{whPi7qPy!;KGkw(&R zNme*Jr_OBSnf8z(_OX|u$sTDsOD6lsjJUNGPRW0m2$<^B}mGl&0EsL%4@2b3lNjkfNb2C!~Y~raiNWQ+6d4FTo#ugD*RgysC$k|Fh zi}D?~Lqz6^Mh84Ejk0!tiheiK`oK%mW z>BqJ1t%hQvieEnSP7gNimE6cEn#8V`M38F|D2=F8x{f2QpV#=8ZQNU>CSn7G)Y*^m z(@(X!=*2C8r&N0G5vhku))l_h%7QwykoS@xj#c>X3zV}B$g>aOCln@r-0D9!OGCH* z@)S_K&uI#NrOJ}7(;-y3G>FG6m0GK#`)f>MElgo47)PsAH$>`dqg!jEdnS*ZZbZ1L zs|i;QYZ!D#Nib$6Xj~{iuUe(fFc%~d&5p$Pr*q$YC7_e3G5B}7s@sLH7ybVJ$R}@- z*GrCgmWy#tKsCW9=uzOr&eA~Uw6 zW0N6|MA(Ymvf`_Xr;zYezO-WLkT5vzQKOCw4>T7TT8Ff@pNN2T*-6;Vho zeBwg|JbDw}!FU4WyyQbHXpjrmkiI&;LcMn4eJbxk;|dMVj$kIRcyIl3MLduSW!aV0 z`SKosqte$2m6hE0e0q+VlR~zj{ss9RJsUmO zW!N`~5h@23ZO$Z;)D!0xydw+(&ZPFVUmnjr*`hc6BnVmDaqZ~Bo~?lxulU!4K`v*6-WB)K_wP`# z1U*<;2_W_d?j#rDmdFVE{Q8=rmQ~GiEie-&Usz|6(=tU)x*#e*^t1SlQS(ntp@*|Lr{V z-!ugODUfYaQFFlhHWsfoK21}`Tn%3v6BQ3lfQw;<#o(~Vr>QHf^Y>?_6j4>yFJUql zqndJzF=;^J0Ea_INZ^ETRt$#&7CHSK8T&s8p7(`uRhNQx3$l#H104 zuUYd~+3S{rOwQk|!)y=h8Jo|S2&Nxdu2LfbuHwOV*s!}17}F=Iy=vHelEP!&>cJ-c zB*Z&kW~`_~Zk!YWMFl7d81op#P8Y#d1uzWwJQM?&pduk;sejq8P=FyvO-I91DFR3Y zq(um*O-08tQAr^7r1=Eo1jP6>E?mNeIBINdXD4QeD>IX_8xYNCG9EVg@hy;#VTg@M z_gWjmq?cFfJNr8Lx!Lt@yg6*#NmLR%s!e!X>?*`I@A zFXK=fm0Y}=S&$1zf8?e#)9)*9#W^LRQ%T@=rBNw+f|7LM4Xr{k=|J`zUidh%vM%BW;5$xs(xX8xITC*|JhS%h4Q+_Whw z>$g>aioYsECEOTkc9|uRWTrbZbU^pmKsmIdP^f<+FK^W9IAx>aLClf7^`T$1AEC2B z{F5-NW50mUZ!x~hFk>Q|=K@A-kNHAjx%nm4yQ9B4P708u$Lk}?fth|*(49Y~f?2EX zyeqkh_sx_$$#^G>3>lh#kw%EP^VZKw0LU)c%I!X96*erBNxUFmLPKJpv|Sr$ljStO zVV8|gbCgvA|5aYa=N+Fuykzt%LDnx3r>5w~ae;ub=p1qC%2%pt>SlS>p1QP+z?8f(MGS}kT0at}?L)BSu^M}l08O?N+8z8- zzX0tHcLvrOm;lx8QwqBZ_p8}g0^ZyabAA0<#X|<=&NC)djkz);5Koho@oxThnrpEf zc{JN-54nmR5jbpPw9z45wO-o-vU3z!I@HG?&3x>vt4tcRl-q7_<0mRt`>Lmyh(ps8 z*_`k&yfHx7z+vbP((>cMcNzb*>LNqVlGIP6>Lq&)Zb~RH01hA+fQYNh{!BOy0S!Jh z7ccsCWcz+`X`RbGL$&^*Ha7gaNswM}yH4hPaRHq~KlC82W(JN)G7}QH&0dTb&-K#T zG#Fg+#&RO+tv-*YUxV_&bqZA#C5e3D>DI+?)m&Ucf#u;2Fes~AU~tyq?(N2xFrNrQ zymJw_x>uBdczbU83&&ICUz(!LTdw_@&C{Z|T=mKRi)b^+08AxBRsiC6OR!4r7J*U# zFqYGFubwzh_%E^o{GgdT2Uu?Ycm)3&R-o?6r8PjKfBIJ-D_;=~uD*>>B?KOTkG=53 zzqRT;q^k$wjYY5&97#h3&eR>zsp7XZV^_>9L_bSL#re@$d($cVC5w(o;m-;-n9K&E^tL;H@2z4#q4Itbw1O2# zK9ChVMbgX28DjyzZ*YY)km}CIJisA}Y_sT7y=LTjiZ|y4t9PB~`vU{44B~MMhL5i`(tGrM<*4PBum$rB>$tS~*FS=Hnm+Bsq5B9IX@ld!`4f5%`#xTPM{fN~&&k=E*%fRUN3&w%;A*|r2b0!w z&~zZJ@8lugss2(627)YXV?s0YESA|$EWE)S13d)|q5Z($H*@|opYk1k9xArmEA_&D zPm{UmuT0!p3sp+9zqiGTMC&;)PUfYwb}$XT^h{w9tJvkwQaU1j_5y7|2gh+gx03wacp{K+4Cz9}qC>D^SRt^4f;|iQsXp2v2&|@ziw1kO=`wYi ziNlM+&gX3^`u0K|UUVRNdKe5*n&xg9g8lgGren36ZIA~VzFPc;k3BsEpcH~C~bJ8N8xV^Qk{ z?n=s>q&Bc=4kHI2GPI(ck+vx9CiuE;t|)6y%5qaZw@Ujoj36{O=O;T>d2gRqlzbgl z47?!_VUzB=dn$?CPg!7V5ozh-zGPih3t}!U0iC{aozlFDk?2`iT1GvZpJ{2J%RKza ze)3Z-ata#XO#GBzv0Sj*!vVTx)Wb%+A7!{-V+-b;3UnBq=alRTK(a^slhGbJ%<1-P zD)OkW47gTCY*Yw?ArtkGz}QalatRi9`4FH zzx|hqR*_ZRV7s(3#J(Y{8~}P_u<9MbY~#v&GH%)EZ`ol@WvB?k8E~AOzw__XU6EcapG=W3UZmz2 z795&hF1~z^OHV)r;r1UfWW&Le*GAe?v&2srJJHM~f}x{!sHC+ZBa??Mc`0F|ia4$3 zn6gucUqE(wg{qOSLoqKR@B4a|-%3aAs5AVkv#*M8iC)=LQXmyxqP3bzL>$F>bhL_k1rpVJT2ky$Y6X3xWL!b)o;DLS<+kU z;ph9xq~n3d&$sf<>HOLjbE`^1qQQcdM(tuvhb$FMnPC|?fS@q$rnv4`I{2nYXRj-Jf9l|P)**i-TzfIN@xu-TqhrMHb;aayg!MN?0c}I`Y@6CJ)4Rv} z;y=1IU3QaA$tO+OiBrZC1FjmkI7#_-qoOTLRC%B`y>>^Gx2UHobAM_iw+cU_!lJ>t zo?hy5JesjNLpYu}$C*yqvUO?CaX_v3={1PE{`PxrBy^U`c zVEkQsX(3uGRF}hN6vO8ngCL9v7JppyglD{D{by?_vXv)FKd@`8hbQq2qA8r#StOW_ zCwjN*NsvnI2ezxjEo5vFr0I=)X2@Ok)#JlMcXv_EnE%eQVc+a8frJ*>y<2_tIizXs z!~FOJ{?$yD?5VNz_$emSZcCklYSe|FRK0Ai)3YE1f6)3YbyO3W+ET6O(+6kkrRNR% z%n>S+Epsp=MG6y(%`FEK&Dw()?h&WwXH<)HY=gXql-i?cPGGEOwKnp%Nd;ZRiZ~hrtQEjMu3q2RIouGz zG<^(OqXnvaXBfG!OQ+e}dj&_Of>NeDn-w)zDkJz2xPCAvC- z1k$@igKa3iW}Gp<3jR#*u$^o`?^B|@7&+G_D<#&2$U#=`kX;;BhgYQba#su0>by(c zd=ni{)iCcM|F~;8DN2OMzSn>P|Hp~j|C`&)zv?Fbe;Vv66)nquHrOW4CN9p-RyGWH z-^mMv(3M@zE$4}OtUQ3zVLilku?s+yfjs+G*2@0HbnBbJMQIRsDvIeMs%a5_5id@t zded*XLEc`kQeJ!n8_qv{h@v<0gTM#~G`%h+EEX){ge`-Q8xB`(-y^q;hT}}N?e`fP z<{t+;=d^Ui1|-7;2gHn-^LhH317_HInR9euWYBETCQc{vpMix7>`eX#WZ6xN*F!m1{N?Ze=a<1v|FTXPDpQ+wNE&2YB`$&?RD}#$8vJw=N7&dg8)W8 z;t6Kij@+jO3+Rs(XVx5y#N!RT=cr}Yl~k@Y_?xrCcw9dXs6+bGtvix~=BWF7xXRm1f8=^c`Ue|z2At4bLSq3x_G|X3+rXZnLW)ic$++dG*o4wd zO|7f>>Vj2wSl!`LTvD-Va0_Wv@-!2;i@I5;#@OkIa`<#SpvEk9K^7_0eOkP0Cn*!z zPqtn5#GpDcoXW*o0Yj&peWH51w5bu`nCo~jpg1tc;VJ%_xLt~pC8wf%`{7bG9D;Ib z^ca)vg7$sS5cvTN2P!&{P1dT~EdAkU{+{#oum0v3DdcOm^!U3fl@S2S9nEFGYNd-R z4a_-Dw1{BhwmuRA^9ktP_v9D&AXGOD_!pI6rt*^av@}(mMRPa>n z4RtZ({}VL=gBqQ*K!1lW5^Z!pwfCUw+9fTb_nh0gj|)=^NGl`fv#d?1MDS-2Lp4IONHVgs9(N~-WC zmC49hv|`00xdwlU^zD3^`B<5_M>FLmiT~%O^j~X-&y%7@52>BGd*|3|)-K!^Qs++8 z5I2Et*o7DF>A%=5!wPRPHjEd$8g3-NxQ9u|j(==_>D^&LYI?MK{K7sUy;NDk^A@ZI z?$UIU{}Ta+GyHK7S&YK%2PR6?pN-N_%2ZUn)e{~4xych$9~ST1@06-T4TB#p@N<5; z*cnpHo}RiJ$jIR)GW85b{F*=%zu}gB4_FgF0CQXT0u+$u6u32I31zLxcMKh9Lf8Rw zxj8ulhrW}rS_|-lrZ5bad{_>3h6+KJU|>?{3XkJcz+9shP>D@UuF7Imt_($|``#s> zKxQToC?=kn6t%Xe!ms{#va!Hej>4Qh^O{WsX#tE7j{=sO5E9D54yDl;-UC5oZYO_p=h(C9lH zeu^C(flW!bS(UmLxE_Ay_%6C_ z!>&6yAqwyvI_Yv$)=QQSPvx(#Z9B+}v&z$PK)e?(3M=zNZ95(}ZcydzD6Tb5g+Uu-T#M zpp4ui+kwtRAe`bGNj#UgMxqX4Xd~6^SnM%*YI&k=!`bW--5PXKeolYzxP97qDm(_d z#|JllLt%dePlW^_0=qKg_&XQ8nf}@wjf>JV^3xvgU`R?j9qV|cLLWKj=(u1PT5ibXhV=R^ zn>B1EK4Qt4;LWc~CPrpgEI*)6wh^D)8nMXro&j-y?e^;I~dAf`+qpcVgv^6Px1 zPVIj8Pji>Xuw7x0n}&xZL#D)1R{&EzIvkpeYN~} zD>!Pu#Vd7f=O&8l5UV*^(M$e#{rk|kMYB!xY1&Q0-BqJxc1olhTIZO7R)9#?EnUAI>iDL?P`tPr!F8;^rqUNe0b zPkK!NH<;N~Au`^(30m7v6)ho>FtC`Qt_hc_Yx7%yYgZP?>akDaP51b|^ZGw$p+P+4Q%J-G!q%%yu|Bawq6P*-W=s z-Q~tU%MDZCUd>XU*%;X@w?Nv8p%~iqH%!1fEI0MNJe>~9v)yrBF4njh*xgL@olnGm zP>{+OqsDhZrp2{9>D0u(9)Y%>S023(Jw#ljB{$GlI~+XyFW^y?%>36tvh%Px9;09{ zQwhm(Mu`eeKf*M*)21#WWa~FBy3KaNOzt~`uizAAgcxoM#$0z}ds8N)k^crs;^)L5 zwerd$M-7FynOaKkpi3IZ2gQJE_DQ{gyhdAQD!&NFrwy9g8I#AYV`hmb$g{*p$>}7j zzi1Pm1qq0SuhYd(Nx6ua6x0cXU8y=72U9!G2ttOuwil$Cx>M&&x{xp^a%D(~KsL5` z5LQH%#n!j|^y6T~k|TC~#!~LxaHC94ReA@=HIVv-iv)lL!$R4p2WwZSP8gb?Rd_y8 zA#>7Y6bE#Kr==pu9KO~O%r)|I^zxoL41!XlwTfEYF|1aG=bx4q%7+la=M`hjI2c2e4r>vh8xJzPD z3p<3lhK*)9Q{=l3BQ|EuqzN)QXuOEEkGPT4V#%sqMHidEl3j|WBTY#$5K*x03U*)E z3hrcy4JOP@y5i?Vq9QBF*lX)zY0=8ktI+fiOszoK8|fc)MHG#DmAxDSSp< zsM)hsszn%2$NyVHUsukGc?@IYQ&Uv*ECR#ICZ8mRMG?sgzbN77l(Mg0Wjrj=D!e;q zd6X?kU2zva!7``SmQjstKc@PvVYRh&O<0>dQOuTeLN+!|yO1nZH7Cv5DuNNw=gfn$ zb?8dS5dn-9RRv5)_j{!sz&qJPM39;2W^+p!MzpEwtH@&)2R~tjPq~Q12vS)NjZj+h z#RUDlS3^@YrErFL-BxkX-#u`QL54H{8!1RT6+C1_cOB}lXf@nng52&k0#*V1eM$oG zz<9yBh8S(9noLY>3@sB~ax%VZpyb3i`a&0&{I4nI z;R_LTNmC-G?PerPfFlq0$TeNwzl08*ja1BZvK}B`9|Fc4+W`%k#S4#rrM8i$P!nIu z7iHK`!w1^>mB1P3QfLTWy-K6Wq3bRvuf6kjMw^;+|J*T%O5Zpxu7F(jum->V21HGP z>z(o@uU&Xo?hCacVzk$ygJR4@;rzb->O8uufnP4Dx% zifff-50FKtkxJNy_QVW{_+2Z2ikIhZN+ST zSUA517A&$ncPrKyN1M3VCkBzn^F|e=%~Q5J*5YM%g2}8S_|btxsaa0QVfqL}R!_u@ zHh9xQ(_)F73pn@ma<%ixCq>@kxQ0g0|03-jqce-vE#ZnQuGn@`Nh)?yv2DGvZQHhO z+qP}nw$(Z3c8@;ic7J#DxZj^W_8$8gYpox9?MHLXIl97(3Fe+z$Rj2!or4o)V}@JA zR#fs1v*Cuwa`z^Zf@6!lu1V+SG;qFQP=_Mdvs4qd%#U-*FlcL#h*i+{~GKpI7KcN;6SplH8Hz~|P_+ZMto94A;pw9bm<_6&QZOkI~h<-t>G z%u+ARLE{AQMC=qdPFA=kRMI?YUax|ku)?LT^kmSMi+-bc@p)sin?1lxn+LJv;%+P$T(ANw_x6-}bOJ5kybkqt z09O)L?lvt?8A=_*TsrjB(u?S9=~9|-0(I}0!|_=KJkU=t(t&h(ez~Cgta^5_XdJ;V zx%I(rR$sufys!g*0^A1d9dXV2CicxB>p@Mk_&SNEXR!ctC4&ycsz)+SoZJI_+gS`%p9UHjNOKY&iO+~sp;A@RbF$AcM z7o>!OX6!SBM_#YLRL^R6Q0cF066@T{kNCKmSFtWo+enxsv5smo=}OrhFc&th*IXEv z&)AxnnL4`TV4GIVE||gkdW59A2>~&+el<5jMA{DYgrUo2`Vm>x`|oX2@wuL;nRml1 zn3aQ+%HBuD{CW$V%*?i7>nEGl2I?9zixPurnjf3qNgTe^$Y&Q7!etf(wK`cBcNy;3 zsCv5(k#n4g=6I4fRG}A5A0;~KXG3O zST|EYceR{Jw{}`yxyN?kolid#j&8S-KX`gCo}GxV@kDlbYM}$Ny3B-Rb~#+;*+Dr zsRghXgn4&+6`oE$V=Jj4?r zR3cem{oBbdG~uU3T55Ez(d<|3gP;(R55Y|Ifz%j>%Q)it9xYh_F>%XixUA+{{KST> z?|0Ip<`SYom-}!F^)M8|Jj!uDRU_sZ&a{4kYuL}S?^t=_SFkaLS;l#5W@FyX7$c3P zwdw|H1@F#7*)_LcraQ#S_+?`QN&## zZl%fgs1ao4Qj6@1MpB`Gr|-_{HGLV6WnNG-!Kg?`oKbTeKWs$B9@;cZFX%^O4cGuV3X zZDd}vRjCYoAliKJTf*>fhC8I@t-<}63(T-`wPdD4Iy#vaPXybj3f3s-5F{(PrlZmD zirxgTX_ThD{;#2Q4|*5DRJ+HL$fYv3V9xv-s@ik4bk5Q`X3e6lh6dG_-6HtSxTu_0 z|3SouzQZad^GbOj6aeKu@I}Y4c2{ja3k%z0H!nm+SlXoa=9!9Nsnu%jV9G6%p(IwA z32`xH!P;9pExH7lDxpJ~7saR7XDXLxM$Rj#>At!O!Pa4nt6s<{()6@o zrYwvUd6Zd@bJfd(E$-7SzCrBHx)I+Jz_3!w){SvArNvs%)f);Fo}G&O;k$(i@e|@3 zD_-->bq@1yT<8C}<@f(ajQQ_n$bWJQix}8inArc{`hLpl_6kNQpP%Cg#0*6~z(_bh zEqE~z`7nQ?+W_Yfuz=h8LDmyk#Kon=?fbX*r!d4Q)KBv%mKsBMgya?$%v2s!6ig#y z6;~RR(QLIUX^s_jzRWkc&lJE9T=5v$^6>%7E8`t@U3z)FZN06%@!TCrZ>4}&V^qD# z_zI(N9`Xa>Qungoj}&S#r^15-zwYpl!{hit1-hdL=4c0LV8=}8tn`0~;8UcMu(&^yW=6{mk*q?pdC2j``4)kO z*851z59>2(YMZPDGZ!ivNfH4z4E4v^Err8#@(m5=*5St2Ha9mkm8CJdQZOy(>vI(3 z!l2{FlTIf>P~h_=7!r~b?k!nj1666aDXUn?w=E?Gf@||9L{4#5`n@wR7r}QmR2LIN zO>g|vR-^CMbJwt$>4Du=U`9~UxQ42q)G~^eESs|WCVJtZ z7;_9+1iL#^yY$kOlF00*He4CGOLC&AO4^b8?Su}hjf|F8Z~?b-rgn{+lV{C|*rk`) z=rehU6KJ9abFv)+(WsR8}f{z(DWDFCD(>Z5E^Nv*(7{$sK8nI;zL9!PD*3iEa)~Y+ro!2 z^E;GLNCj4CsXY0stlnIc)7DZ_rK6lrhaJLr&lCV3NVGE<*{R9p5tRDm6q_9uv1|92O|M1`)H*DH9f5U1e;sOi;x|L~JG!7O?B8^IY+OU42l%Ho@S z7-IQOkR>EffTjxR8AozOI!bo>U1-`N7Hd^HgOlC(knaVEhN!%swpQZ~RDWO@`Ed*I zlDhR299JFxl@)crX(P#X^@gYgye=eWHDa5wFcGtjVgu7HLr368A{&+ZN>+E0tTK=C1}UkjvDuYpo#6ThR4O<(fLm?aW?H zutbdow++l1fHPR?;UU{Y|O<~idCU*m?{5=gvbsmglO+2Fm=W20b2Bc@qPocAN?!oLcl zW!92ggAe@Fqwe&zfU$-yxl#1r9`F+FV6S{Bd0=hSg9t6Q3u`#rD}g){AfW8WoVQ!z zH{&LrXuLT$dEMcyq##Eikh8?H64>20CKYZg7F5X-VvIQ-6XZ&5Ijj|V{#j!#u2wuT zXytIN9&DA@h`2ClN|G2+y})a1^UIOrC$+#&`EKDbC2jb}TIi$d_X`qvFgT8-}HBaH9O1r7QC%(dDf->w{aY^-y&E^wXA} zzi1AWw<*&Nl(OS!P7B0)v zBaH@B#{W3cRKPzgx!fV+~+(%s&LD*>5~5xb)n!YW@>)Y_03sZD$ZqfaGoBInQ|T?YA*rFz6-{hD4an`vQeI0%{|8Si_eN z)l1oKmh&v7rl%>V6bcRS2x(A14QGE0 zmYc~`pORsEA5ZXxzyiwMtfmp)Ck}E)`f4z7AAWosqCK#D6`>=GD8GG^h4wat|1t*>qYP}X0Id9mV7O1 z{QFeDw^H|T8jABfnTm#qtjJ@`9&MsqcF&^#wUUF$r?(zY0miPce$k@uwoGxW3`3DY zqf0+I^Tcu~{aX(*2gm%m5`(?dh}@Zhyuse{5Bao%Hvjp`y{%45v8+8l@ys_o}XAY(M_lxRg+2lu_2c5@Qjpi)pUco>79 zcB(=>C98ml*>L&2^oC8f8eoir*tH)k983kPzE??Qg=dZ5KovyvA^(1TU@!@a@!b9g zP)lzU3=Wz-s3_KfucL1A`ZUONUNP<6=OOiMVUj*;$tvCPiuHzy>WTvH2si6rnS~W!ph9cj$ve&at&RisLw;fzK_s01*+t?cihPxgJ__(S zOU6pbM+|NWoYUUQ`9_bAUISy0kz%TGf#VX+s+`;*w&Rl%a-@WEK@Bv zGS!h-6KD(yvud)}gipM%6cYM+_*LAJwrLsh$OC7Eb6Mz6CiZx>Ez5FwvCiUJv=yl} zjRs^sSriUfJp)F6?>cmXZ{Xj!%jBM`Qa*e65czdzS3O<)br&Y^MSF>2N~j_n@zS08 zQDmLkA>$OFWRD8R{tN_P8=%?_OSWJnl&5iN>gHncl0u)Tq{XeCgAm%Nz?i9v9w8cj6Ln(I*|K8 zPjQkUHIUnqKR#8YiwP8;O?E)To+MX;qcrIj8`*W9Yetba>lE$0yt*rCo1Li~61F~W zU|E`Vb&8KSr=!t>9;nh^_y;J?BR~#C5VSdRN_D97FQgXY4pn4Vk3?J{{L6bJVMLO3 zqW(gRg_zt-opeSlK*%a?62dt^&VQy+nTZHXgoj*iCXBW!hbCEOEcS&;sepu*~=!kv!Li5Pee@5(*uH zfh?mQ<0W?x0q~~k+OpvCISr!D0lzHBu{RJUFt_nlw4M!+s0_t z(^mWeyr@vJuSAQQp*B$g8LaB54ECt?JIU0cNFmE96js?F91{&2$U#R(BfD%@;Ve@g z+o^0*v*>cep$ZaaD!y#Yq-YmeY27}jy-^75gsG^LKHgDG$|mn{VHT|z@Q~ihu|ke= z3TRdy507-HmCRO_jQ&0kk(0d~;Ko`0%ja1WYdkO0+gR8mf9-FGa zv0C2p=^Q2^o0&^@V9_RkKupzRV|sM*B+MnQxq$z2&FQR~OZ%=5=cesyzcnDJwy&u;lFyJQw>{w9g6tLWFs1=3s z)WsBi&rFO4NC*$-vU@`!rK%H)BG{rGzQZ%T>StW0<;$xT5|t$(NndY{@+9up%TG61 z-L}ks^VEWg2p0Lxi&u(q3i_(bR+4duWMeZgj5)%!paODQ<1yi3n~>A!246A^cJ*d&sf@4DtV^f? zmb*gWY%})nQQ^#Y@mpwYg`lI%cc;gkf0N{QL>uy%LYD|w8@J(aB`TuAKj-a69slz3 zr3MVq-GI;b_w5h$r?HZKhKk;x8V+pzq5X_Z+qL)|;v|E5rK|Z4B6)**8S->PbOQuH z`06*?)p}-F+RUA7+ueGW@tKbQ$Q3_97)l@$=!!+aFp$wtAfPKuM?Ff=q07-9FgT#- zqDWnivcw)Rf#L51a#T!=7jwZix<*bb4n_M|K<9Ly(~8hVywdhxDNY_pLnkTF!G-@L zMCqIM%#}%6aJRH%buB0tXkHQ&Axvq`DQC3O1%q*PBQfo(8;r|d;z+xB(}9PNdi8z@ ze{)<`eRuQ5TE01yhuMYN>XmT66sLYRqIq`nd@7R9!Do!#_2<^qh^A`5&Lz~=rDJV4 zVlZ}O0ikYG2VnRf$EcYYa58Zq~fG42$~bHBabFplH3h5C@T180wfdPKs)9& zj1T1yzY(mdr(6q9HI5G#f@4k6VC?g7P)GxIIy$-Lo!Nh6nYSRn6h~gTD{noc z6A?Q9_GlReSNs~{D~CA#XAmvV>sjgX4f@!D{nsG+KYP9Z4twVR)$0+{|4;IgZ&jLa z^qr?=Q)M|a^Hxw*aGWIw1#Q;f8xRk8800L#n)!)oyIZ;r;p@v#mv)D1Q=GZx3THdcgR&KuSnU9DxWX_UD&IJ zpoD&MKrL8aNW8q7ceP-_LR2|Xarvhdp;9$np ztFQZgLu{b+hRY6o!5~iMgcVBu$`&{QW8kt^aR_Io{VadSbMNDkO^W>{p*D~3M=UC@ z)$*z;B$St(jjuc#NZ%Js{4mt_Q$Fh3Dbq{EQ;4k7|4W6cm9dL$-fMy*wWTa{{J9!od)Pzse&!BqALsY}UIQ2z+F0-r=|83$eu zV^1AsBRLdq*u6MdU712rgKDOK3#~ia8Xzau7($`O8ImMGAseL!;$)1G+=G3&i`%BB zhx&BFP$Sh2aj(kBka6fW?D02|r;xsKhCZaMNc9@)9|_`E%i{b$NT`PXOAV|4H(Anu zFV+9gZ~K2|i2o-$kCK_Sh9b^a#zvdllTDo4+J2)6nf8hHiX~DaC=9G*4v7gtvan?K zuTir)x3zW0IxI&P5+LMq-UAYD8PJ5qNDwV{`GUkhsQkh)DeT;a=`%NZ;dt+(ED(a% zPLnHb8;Pj&3+9(>UqftPPhaVGYw%t*pxMw{;`n|hNCTjJwlpN#+N3@ZvQpW;r6ChG z8WAg?aJiH@K@#RMcj+N7phrPS#)CwNt_plw65Ha=OazjV4cr8yisHtE8rJFyBiz55r3?ud&_}HaO&)qk#>^)!fVlc{`{Q5;c$Wq=JhH3 zl&g`OKrL&l3s9vUABgm>@vzo!`s+NE2}EcIQ3vJ|?R$h`u4D-1IaBuY{%VCmf%57b z+*8{^K^sRUDJ>5$WLM875EiV-*-%Vzy;(M%r0zLMAmV8u`&WoK@}v{Vy@%VcrM;91ap;j zlG}2pXD^e&L&~c+TV^P_G6mMD_J<7Zd0(N(-Id<9#1kfy1oerDmE`bw;%-eG=OyE% z?Vhpc`k?JwuRIy+Hk7{HG!(fu;Z)nAQxd;MkLGAX#0CXPi|iwN9N}obyL%Amq&L_; z-tRy;nTMyVOaRFY`Vv({sok87g-K=Hjgd4}*PKPJbC~WYWlXNbfm~WQ<|`+I`oo~2 z>6`fGW{2nGQ|LnI`bY%**G#Q)3bnOEvxaN%8pe!@R;A1sfR&^!0iAXt(QZ>pi*zqk z8ftdotq!6N^|d?SUW@S+@XLQ(!~|b`V$qMV+5saC{N1EVg@Ex~d3a26;YoZ#I@Ni! zcg{I*!+b~8y|4FSxjY)cw*JHLw(zT_mwJCk)M84d8U9JV85)T+v+i2bT|C`{iW6m962ss__rZtX5<49>C*K$$FzQq7Z0oY zFbTEVSiX-MBt9V5pm1-ux9L|0pgUs9XOG3ij$cSt#4LXOy;h4oI=Ip7nI(wUs!-!r&mIDm`aU9n%%3V*eSw&TPhxd?$H z#JP3Pffza2UXo}F$w?0z$%N&S)Dwit9#L{9Ge6CKPk7))ie;r^e-KWu09m~+f163D z+axCahhq6~OSuRLl`9REYvKWE1cYn({S<;z1q~BP+vCG5@>;`2zpPD*nVk>6)T~46 zyuMveXk%d`3WTdV_K~C=;cr-C7xUg@dumug~MMlV!QH|QQRJd@-{$N#y@etEO zd496HqCiq6mcP^oRT}GrGo-nTs`aXN8JMPKl|ok5C)RPR z?obm*Crp=w=Yp(z(2dRyeNJex*iIi32`7@+QG^3GxSjczg5g0q0T9)=s`)W`qDQK^ zZZ#lpf57pa^muZB#gYf}l6&^tU8%1R9!zthWoQ_M!Oi%o|5Vj2d;V>C z&`O$)O!h}aO^zAcvhV1?FMRsf6BHOM5)_58za+NOG&uo3Z`)5nG2k$(f6&E;*=*9{pEJ)rl~b86;7w zcn7MUV#3y#N)K0N++(Pp1ps+!yS&g5RR)xtc`W6GUnh=v8y1G@?+)dhfT=gi6A(b* zW}m;;xZfE$*IP*FL&bf-B4`Z(WB)MZKUQbAltCGYaET*V6Dh|Rh%!6X(dImUL4d5x zjkUfqdWEZ$Ec1!G%U#kT?Sgvw`U!6x0esN(Eh-0iM&QoFmTy-A8ln`%<}+kq+zcIOTK5L@V3np?zD^=s`VR_+e&91}@J#l-fGj-$n{6aJFf z@8sQusLvT2)ik=sU!=~3dqoatv%ht#Hwc}xEbeJp&5swJy`Q$doFP2B4WEOZ*4~zB z_#Wuh!Wi|2>#)xcYi=O< zq0PCavpq(DiPW^IR>^Bo%&`0$b2D_+ZC*$qBf))_D0(iARL!(vW$t<}weT|^Z$SqW zsjvA^SMkt}1(K*`2i8N%vRT9wdu&tfx3P$6w_H%{DOx^&A6JjWBA8IU>Y7rZGb+eu6x=lQEM3QJ@!>x4~CR&CAYYrt7S*RIsC>f5_JQaC$mwPzb zHTi>+XTT9)Gc_O)CIvP8Cg(Dka}Hkhk=;aG8A}+L;-=*}9Or6>(%KE~VNeb|0t+}v zht7XB*#o|S{}IwnL_S=~f7krq{>z&G|BoWw{|@P_Z2uRNXodWmDH1RGry)F>gGFA& z>O*|-4C#puQW-vG`yZ2rUxG4(=vJg@4JoxN)NP`omL1n9$O2i}EWW(gx$xWkAzv^A zq0UCj8CIPy(svUlLsM5|KT3=9b#@E=nIH#X5XnhorF1h09Qr?cgS~mpSPJ)QFv-BV z5YQ-LI41tAIz1COxn=GJet4qyOJ%{kuED`K^F#`s2WxK&2IWja5W=Jf_2M}Cx3Mq; z&UjF&Ao-wkYCCJDiw`*Zb@F(T8(8a3auepiZ}Deg*6X&%y^*6 zNrKlc8^;6asu7q%4fO)Y@2t^VHY=lRmA~j#7J+zn>#sAqANo{4-=y2WwVg?8baar^ zQR!8xqXkC!)O^8$q?~BV^q;>r2z%Q4x)Y=VU$OP+e!oZNaJi|b15#!+24*2?(Y`vv z3s7(GR}t?)AIz03+5dXDuFi=@3+EZ`Aa8UC>Rypk@_Tf)a|2PWl|a_lW@P@QwK87~ zv{;4Yc!3>6OK1^D&X&mb`@N$#TBwme2$j98nkp`Tj!maobEguJlPo!|a1LDKuZtE! zQgTS5k!k8GPDfwbsPqXnQSA8~9GY93k-TyGCOw>BoK3a${YbH8l>Ay_!#UShtkB-0 ziM@^MUcgah-jH&MS&3h?s7Rz0+0I^B3bkaN;R*t_-c4TvBbY)7@gFi~=vyOM|B%qU z_%E}O{|;Bce}x&cMmj?ITvRhLaOr`=7bc8m_V;!Vs}bE;E(Bex)kD}a#qhI6tV>)p ztjTvMXlU_gCU%(hj}DA3ge5o$h>m4s$qtEVDWLT*DY96V;y4k;4a^|lOVOoKe-468&xgyMjI#cC*&06bD{4M z@xB?zNpXynS*w3;BiCxO5}PT;%_uXG#eyB1ISdJt8RNh~gIywv!JrK_n*s)-FvPCw zhaoOS^>|En4s41jHI2@|I==^Rjme3(iK-!C(^SKV2^{VjH5dRbjWl~17r$Mm@ zvB#na`+}JI`}tsurQdxLN{y!_{yHZ)DWVJ{;d8n*)rsgKXPTr>;xfQJot@d$;;VgR z0#p(E=x)5+eHv5ig<^bwtmM@xGB$>e@BYseH{>K8HMf`_j)!hmk&BiB9zx*shj59L zNK@TStnHLD<`R+YH`??YM60dg|$Eu-C6&u9=!hxHJ1ma7%3-?d_5z>ji8J`=E z%`7bcjUxKRdzwbJe2F^3J0P@9q~k&(%a|{>>KQ|=5TD0406wFT=L@MgaK~D>4TiGS z8wS-`vCH8sI$+aYz6%P_K}<`FS7;BtDt*T7q}Azzr7e^W(mjw88j;YZeD(>AbH2cA z$pCS?C%51TSPHn{sh?nvoTGfTjtYgiiT0=dqV=cT>`vo5Pa6jb+x0@>=~ai?RJw`u zzScy!+6fP>V8; z{ZrG*n_LZU5d{(;mO9n#n~X!+u`-HGj*u`S5)|u~OBi-K>fSEj+X4N9LNB{`x}IiH zx3Jj(aRJrT^w=A-|Npj7E};B$14`m2S-{P$4Ma8QO1-^j~Tfm z?=dzq8f>D*mkHsHPntr=%K>!d{L=({Da)TJP90k^p}j;p#3PpOIA{v-tQZkA60|l^ zZ&d!MIASwkmKfu!ozFF^PCsq=ZK*f2Tw|%l!lnaWBB?`g;5&R4om@X7)z;emA8v%A}b~4CZ`91SAHC>i4DyR3s^2f#@>Iz zmBKr|B3gmfi^z{Vn*F|hjp66Oz;&uBu5_h+(YX}wJNK2_pbRZ6g`+&G=B{}9Ftm~L z?z(B75a-W^4Tnke-T>`uETx>aPOj3ME~EC1Jc>uxU<5S7Q`LYu`#%FbF9^H@LQh-8r+`8=JF`H>dVm2*Z zI04u~4m^vNKC~02nAW*26Q#Ufn`WN~qDG}Jywo&i+gwJ!aFw4w7KNAa81KWHNSUNyl}_*;#6*O z@`N5r8zsx$UjPe7H&lQIG5fMW<8-mT%GbLyFu`k+{A-%Fpu7p?T0E z+eIR~dYxav2pR{OUA?_s)ylSngecnxYdm}RypRqSxnJw^)>t0ScpA+T0E?Y;u@aE^ z#bEbQ%Nk{_d9F+@*>JDykTNMXh5-B{jrt=8Mms4Ve%rfnZSaru1MlMvX^PklGr{2U zwNVo^D}X-)>sH_+jBq}>1BFJLfY7EIrIs9FWWh${=IFM4OqXQ3hgbc2f};0&NerEr7Cv;2~?vVJRXZX|*kI zQ^1fW@`sIJiTv-?_822sLn|i%n(@oaUo;>0A}=WzS)s>2GVw8`ZwjULVBr`Xvve47 z4Pm&&+oN{J-k}z)!*ShxI3jo0+K1tr^6rns8@pOVUeq#Ci`kEZ=-0$)G9mN&9{G_T zrSu}jRma1wnb~Iq&6lIUb>prDe zrSH7>$0m%1wvuO05*~|a_uBq zuX7?;u15*r3F!`Mv2Tgz=pioJm2O7y%2af9SN&jvjSBl}HXlLajURIQ6nrK!h$A22 z-LH-M+CWuIUtzRMa5vl*subUkT<$viC&t^hkh_KPJImli{@13+f5v$KcbX#qqF(T? zna2NYiYQuGVF~{7Ty(UZTp;Ps3DD)A&SWy`&D<;&#X`quHdztv6AL;n6k2RbJq3c3b}0-ui)-& zr7*s$4z^XI(u0E{yRLZM5o)rYkuz0h+fuaM355cW%&8F54G(n-wTN8KkPrPT^l4+` zR;6FQMEP)<2$*}i&jrkmtvP@j{z=zz3cyPyG)|U^5(YYeb ztB4Qe6^f-^t!?P)O>jjhvqXCZSLw=hV%3C?Nw(9#eVdU#}umLwKqZP2s66w z*(JA8GWDu&l3NDpQ{zM-KiNpGS&CHOy?IF%_MmU0WVg`FgIekeQw8(V@1{9|MYSQA z)g~tSsz?wba26Er2*#L{V>d-yLL-WHp=bw?r?l#<}VCtG? zg|m?E%j>|4HG4=Gg7t3BlHq||`)O?X`udnDQ{bd(@+9eRa`JJXtVAWMHr|B?i&6x< zMfDy-VD&%5<53D1Big4vM(RFx_oy1cctk1PWFno=X0^3qVo~U&R|Sw3Gwc?SA?o_e z?$Q$z*E`3KloLkrpnZ#9;CN>nUU^$t+hS1jti5C<`fv9Wrtq}>Ixe|X)X6?9Fs?!4mLLGmCh)3>h`*(?EX~R#@L<=KH*(lOdAIUxP(1guG>l0)k z3~lX3(@MCP@p9Btl@c7kCD|9RF+@Xr2)KuUFA()(eiIMVf)bLoC!P_-exlS31z+ZW z36w{bD3@&Ib9cl+IUFd`JOJNlyn-1DIWztn2N;1X|BWn&QA_y4Z zO-6!}YsEgKETAG5yapSYs~0vg*!Ozy-<^{AiKD_A*jk6I>A5o0a!ZHEAivFp6cxEigK#8n+{lEJw*J;dnSav zv_M~#h-I@LzK6;`URy8%8<^rtO@&!?XRByzu*PUHHY0JVgvQ9<1e&xe-xEPC>uAw3 z{6{Xz>lECP?e7cYu(15pEUr} zYl>-V0oEd8iNOT*Pv$<;f-gZsNv> zv<00&;suLBRoCAiQCxMz`wUV&F#KR`651N4r!5EJ&59Z9=;}*jvyP{V1cEbhRxYaL z=)K5^W7^n~vFhu_tgU$`iB$R<%+@J7Ji9UER{boR?M0mLk-!Uedup1dmm_toEb3!Xx*xdhE3xQ=tz=BLbtO2W-spOnlXA$VE-_h;7D}awP2d~$mk;R+Xhfq++c-Vh+ zg!H)}bWEP15_6ZVxP>duWS%$B$T0>}Bs)Y{xF<#k@qG8+T+i=Kx6ldn7$@K<6nfu6 z=;Y;7<-TmzqFNY~+%YXvg2FiE2oG^|IKX%m&Q1p8IUueyV&*hr&P)Z(Ujr`;YnLwY z6~))|$$9=1v7{fKv0801G`1bZ%H6cg<0`KQ|+ejGr&`>wEX{o988&u&}( zzp)|z7k%CT_Syfk8~E^af4(AxJ|Ko%{EfuW>A)L1?bvTD|#5 zZG5H1O6~68ub<-ad*h-%yW$?n>JUQfmDFiG?yNlYi;k=ep4oNO46zv8%*>37 z%#8GzSX{Aqli~0O!mF0pIHOYMSfiFH=p(V&%0N?vIWajmRLCNY=QzK71;zP(GWZ8-Hg-h7|srMiPe}!e(f$Nr$;H+5j3$le~ z={>VWX06?XJ=W@gH^FR<>%+&XPm}uLkdyfIh_2x7j)HRtQr%SMt=SRX&r3u?@8V8| zM_4f(Gy4ImyuVWOR@M<(v*>8ufewy;AO#l|8E9+cv;8GM$M-H~jTF>2Hg_^~HogXN zaaSk_)KcS491AyuH^;#k$3f9$B=F3L6=V#MW`j4XCh%>>NkN~|%$VBne3Nk`XQAg7 zIxUuzzQmY_kc83enw)tLy1^RyiO!f{CGWUwjc)|q66mGusmqwQMlX+tUV_4%V(Y=Pd@ZgJG<*YbPS>tkHYCu36- zLz~m+fsx74@hx&a8gC@(NI0;z&DKd`U#ONXtzm;&y(u=RL1Ja0|9RSa4R#p7#-7R+ zczGtAah{Wr=hq_Jni-eG!I6%~dsJ>IYDw$ax#??!J1iXxdWe$KgmmYM-3;zR}Ci_Sk4~~rUM`{aokTo6c$^ne^)uMaZGakJTU61If7x; zk^>?4g6TEtX%N0P>Xzhdk~~i2i;_H!;j5B7PT{}rNQrUAEt>$B(0;{XKQW`j4t@c6> znlZ&cyrNm4RFV^yiMP}`Um9s=I-vI}rz%eIbx_SoCvI(VpThihIki1N5}+PeRXt*4 zMoDE(S;zDOo%Y^Xc-vcOTP9jzyRnF4@*z(yPjum{&~SBC;^??k%w+nU|3?qP<(_gN-2v-5v@=o zH6JUWGDKR!{5As@@s|)toZC0JM#!>9o|IreaeT(2+Frn z?aFx&3D%M}Ce#QPJM<1$MT6Po-vf-|Rfk*v+e6ry)I52SC%_?BjO{^bUp1YDbsPML z0mM1qCqpy%*YD?T?w{Qs&90umX0N}`9uiFlm7Q8#vmRfAy8q;cc-y)A1Esi`1T7HFd*SzUtBY~l% zV6q031o0@V?O=_%J{Q(v0F)eiwaA;go8tYhEewD^1@&Lc3_@$kz1eP7V_@*5^9H8gSJgCo+8PF}K{2ho$fb&KT$mhTf@3XQn?&rph z>~qc@;5lYb_E~zU?pkk1{2FO!tJjOo^M@6yC)C%4!gkT5=`)@Y(R)=L^rr1&?^MRx z4%(#Vb>p4VGmjCf=LvR@Q@Yd6>Y=5e&1N2JhZUuX7F+v8ng7*W?lo*yVSOK5|2?J3 z!FX%uPmUdsY_=iIr=BW&PuR&ejVHoY_QuVNRtQUh${ClaGs|bieI>W8evB>4^py&m zOUI0WwChz@qpCBeW{j3%yS6ifWj|NCBbp_)X0R5NNTy2`9ooi4)>2N(XM9@(;kY*= zYpO;iDw8R!Ycuk)+!g%Q|H0ZjMoIo9>%v{#W!tuGb=kI^W!tuG+qP}nMpu`+?6>BB z&fGaO_r3FB?pTPrtWM?4YnJeREN06yA)ojh=BJbTzaK%4`lHN5>VsKKr1 zOikO@xLfecZ}vKUFa#$^oBW64z%Jk%J-fkiRA4zZps)ux!1%ir{s@PZ_~%dpxNW(J z51@PC_5?-4X8~NXP*nFiV3CBX5QdHouClP58FrnzS}WJks?Vg`{OD$_Ec}XTOz@`< zV4gn~4b=sttviHqbCcoROv?2fSc-!HX%Q6!li4crF0zbVjGR}o3 zY6ju&AR)(HUdVajn5&CU;z14i)A8MzVJyr>u?N&6j3?=oDzWmX*n`{|I$FuU?BTng zWQ{LfBLKc-%T*7Fb;5R6SO&Euo{hQ8{r2uxd4aOWxFZ#|eT{X1q>aeLdUb(#==X`&PN8Q&ylU zVO9Ial@G9I`38&YOQ0sl{j?8zrH5IeT7Tw=BCMY-M&GYdK`D;!c1N&k0dE?UL5@CW zHy%`ZGP#$xqIB)HCC1<;agy{jbklsJ;wVrUkuJ9mf zNvEJ!SpnJFk$3DtCDjp;nuPp-z`9f{GRp1;WN%o2$0nJl>&Z{4is~-~ygh-Bq&uc# z#ma$Hup`M`rR+g64jAQe#av2VAZa&D#BrwCD9409*jhnWD-<&kWb-#;s{CDhJe1K~ zJruJ`xfn9L4z6`Gyf>XjX;#O#)<|uL2@KW2KmDp;J6|ZDXl@R9pRAsUe_l!N0M*@i zEUejn=J?sfB$yl!WCnoQ9Y^88d3QeDfS8F$gDmyuYlsBpgxgboS5lHgC?pgTP7Rl! zEH4d}la~&X5QagKr!-JnRH*Y0=cN2yHd|_%Ye0fhQ5vc^Cnk)9Qc-4FYyg7-L8(zH zrZ6WV93I}JR9L1aDvX7aB0nc142F`WR9TWA5pGS%Drd)m!lPtan4c0Zt#l`E2ZE9j z@KVh~3rf$<hlnKqp_CpP(30$9LQ5w#G#T3|(rP32`ln|c>akTZDLPii<@HSW- zxX@MQKw9`(pu?{&kX)NSAT3ikXd0Vu1KA*=a)-;dMPk)ZL4;)c>}30Z@WXzv2C?eE z!sgx&bd7HEm-8RYd*pAXA7Y4s*emBkDW2xgDO2ls90nMoup1F6cu}LM?Dc?Tym;@^ z1Zjin1?o;j$(UHFXj1_+q!G?xX7N~7Ta9UYwqA&VJ;b!+7mXqQ*N!@ZzM(eG)rzpS0y4?d(u|(N zjR!9Q?l<$Z)xgh8U)D_%ivci3q*1I8YH8-Km0fQE*c5_NEW0q$N&JQZI1*^#!!w!VGll6Gc zO;!>57WqT`<)U)6FU6_;1Nqmyj369YXq1$@pyHlpOW+eJ#t!g7hMs2v)M1@e;S6Ki z_Z{Yg3Pov(IQJLL*JRw(`7u)T=|B}IjpL7d%r*uPA(H{6(M<|Jt2JUaQ-QCyH1nczLh%1 zvs~K$>z~)fSyFqASi6xddvfb${=w=rxlJ_)2Hfya1v z_7snWrJ?PXF0$F8_C)%=b6ALL(P>C`qfYA3&o=d?CULWbzVp=Cxq{v!@s=`1NZ9FK zCo_+tKi*51vxQ_aWwSS`H-j>E4EQMsm_R-lO;$gz8|yx9u{9cuh|_8S=M^_=jYqoy z(GmZilyMSB4%lKBRP&`MDl!K3l=(2zz1`qR>@JOX&9a}e8A$>5$`kNJitx3GzmZ1% zYvOPJsF4=&P8i8Nt*^W}|26StkC+x8h@Suh!PX&OI`DL|EC1t8zTHV{mpriuCYQkp zBp1+mUcD0jC(Yy1;jyn7Zz*5bk}J_f_DK2t3Th3Yo*(rip$hn zj(<#%wpTW&aj@wVj;Ep-f%{P&=+<(P$Fe+tf;4;56imFJrTZwhH=SUvL@);SvKj4f zP`*^XixT}W8BbcXO5W}OqQwiHQ`$Xt1(SB zNvM<==m)Y?sF&7Dz(5sLA{y$`R8;DH?Mru+xhH>6QY!UO=e693$#|m)crydNIaZ$b zQCf&**f?OU+@KoCKOj|=X$DD6)KU&~XKJg%E84>=O}8L8m1|>^XKl+vP1fC>KXgN! z&z6Lb#T$-7@9c5c2b*}Swfl^ijtCp|Bs6Lz)oK<08vpenf@XCH^}JCS8VQ3*%4m^3 z&Tilf{#F@-(-?w7+7qoX&Ksv>p^mJVhzx3~toIkkfjUzcK7hhZtu)GGc_6i{8yfs- zm1ur4Fu3R;bA0{qm`4Rj8D%o?Lp{`ic&zzTH0!0)q#8gKuld_G=N4~_94FE|q>lbF z?7u-HJgaJ|@$f%ZAINRHWEh5PKW&?tj$#TPe$tlq4*e;$qApV-L)Sp3&Ac>HV?0&$scq&nAa(XI0_l(SG20&$ThQE0Iy zk(gG_jwY9MjwS32H&LfGE=H(-PbAQTg9y1v=nt)mU5!{4!Af=Ji4%=L3t=X&YT-84 zPiUo)<~$8?&~m`5+|)Q#46eY5ZshxIkT`g803q0|nbdb+ykbAah@k!-MLTOY#&fCvUs z#_`m|P7|qydjKH?A78&ozq z3pHfa&}(uNfEv&Gg`T_!UxN|s2fK@&?AilyAjLjCx?MB9WD9EDUZg%_5w%0F&FOhv zSvBwykp439_ob(Mp|BA~^J_zaKC+;oE80I?q4yE@P^W~{7^z3~g1l>Hd$Zhf z=k93d(IaGiu~qfRWWj<7xvTHA>up7EG(LvrBMI|zOaWcKWTEQYLx0pW360%Or!Rtq z`PhfROCk_tnEK1yo-1ysP7z}O^}b{gQ8=2(Gq&w&Pu6pqArokJvVw0i>8{UIW_3Gn;DqP>OO$3=4%?uPPkAuxwxw zfCX7D%8acWoR!O_)|Inf9GP02>^7i1FqbJztm8b&A9$j+zn=69aCTpJKX2KEtXUIN zwKB0R`StAux`gEK&t5LgXck6AvN)7p%a0gqG%1ckXWB7eJbh@vRLsdbZl<-)(3c(X z4qnGjW9c%IHB9hILSptIz-3nD7)BS+<#^<1yP2>xgsw9_nw0fvUROIpHv}J}+kQ5; z@b=!bQF^7-I~O}$UX5F>sw1k>G!&KSLBDl8uo*x%3}I0;@qW2o9)@5wJfFR5n^~)3 zT3OEAa!+v|;;x4+3T6ado_WsC%!9G5^0(k$hORs2c2+n^bBgRC6KsmFL^A34ItZMK zIa|l97Gz25m062rGqz~eKf-s4WW16)YS+UYW^Dk^#M<_Hil-^A_9e! zQ6qKKRiBV3SbQ$s&jO(ur3$MR^=Q4(r1$UBBWwXdR6Z%c)16IEIDvg%!i!}+nDR_2 zxNu>^SjhJ=nZmiIZf8+Nu#@ABVsJO|8|4Npm}egjyJqMQ?u}@O&&lUs&E%Q1 z9vqOU-@d6>|GV6f%6|Yw|Buwqzd@tBR6V}hkG{mgr!Kd>HoNCZjgojNE{^AD8`Uxj z8wahS%n}+&nOUOXtXW&etX!_NuevfwOYt>8baVFuMDyeV$-%w&;)BH~^M_PygE4SS zu<>wA3cH8x-eT;AU$|V@YIrS~9G^}yuQG4DdUl?tyGlM^|B(A)-53M2>DBl<0`qd1 z5MEELMdE`~MFQ8`KNWuG@(0Imvqd>1O!dnKPuAB(?)uVOF#&e?Gm@ileG1MS&_S3Q zl1+X&Y;t5Pi=6XSl3%Nf>&ZXv#Srdc7vuk$ujWff@njDiagD;^$>LwL=gq;5Khs^k zi#5N_b~GKJ@S%y2{?c67O%!r9zDGduTt@KW5E zJtwWoSH&j1wVk?*E$RZ?p9T7eGr$NU)WyflL_kU3p&zqcKw@7VC&P>$ttsh;S}?J= znaSOK)_LFrlf0EQTdz^BDO*@6HO!bLB;wGaO2(`x`N$ERKrf}*(x9T@V8+BSHunc> z%!1j#A`91CrNyZV&yj|+l@4=Nns!)W(wW#FmV@OS;i2j7m7ISu?>(&=j9d zOtLYE*F~f*IwWQE z<(;qlkH)kF{gI7?Bgg)fyrer12)=dZWXQ=3;1YM2P4&8%Iv30i7bqoZF#YcY6iY^H z7?`%`N_q*W>t5eU6zw_|Hy%3iRlciFT=(W2;W*Q%N?t70cFWNFT_#VDtcqPnCte*D6&N4&y4NcR}*LG~%0XI$pHkigpwAAkTUj2ZFma97lRC?PG4y_lKoSi z67%a@MZvyuWa$%xj^d5to0KqQ7NyL-6UxsNuo7F1A-e0}-iL~;c8YDwvsJ-IkY%lH z2}9ZoOrH9>)|bHQ{8rD7?>8^*S1=JPCn@LinJ6_DHinASVPq3@=Xl?liivZ6*K@cx zux{ISM>L^bChE45)b45Xa$BMmZ=W5z0QipnOl5G~PlR}zXJs*#N4Pdc@XXncG$svC z(0v#n>$Xk=I$6jdO?kK#5%!$Y91qc9TJ$dCWQ`DL8#D{YI~1oLEH7evaQD$}ZI$1K zL2$Iet}Gk9yGU0!rN~}|DVoxM_A^i#JFJlu@sP1uL~o21P1=XN6^DArddt&F`v#U) zuzb?MU);$lsi6R>yb#^QV>nFbv)`oDF>;CuK4Ib zpDApo63=D5n~1WKJGPoR9T?ZbPD!}JhTfoBf&6_Ky^$xfr+d;3*3{ctk{jWcv>K*7 zUM+teyq?Jmx&N>x&;|=tEh89AXh0E!Pa?}x>Wcma?r9}R&MD9F5~}so25u|Q;tt;+ z0&kgc2%m_QBwRsir)tZ==_@z%<^cv@jm}>vT`vrli&_Pd3``{or>_YRw^fcpR3sf6 zN}LN%f#(c0DC?+=|IJZBl-gHCFj+|nvF(c85X{g4&h-c;{Mkmt%urG__%m=HX!2ev z@d-|!VCXnnPe+rQJ~W;n5%vI6m;Z25o(=+UzZHuiI)?G>hujVOXF>Mvbb{1{V(9IA zJH!mV-}|8#s^&Fz^8tuwq^t;9H2#3Hf};T9y5<|kKO9P4 zW{!-l)6{WNr4b2c(SRz@lLj?YM{PyZnw^k(8fEY&JDbhihCPEYP1|+^;oJKObE&eekhAMq6H> zNj`+aekQzH+2;)Pe5oM@^wcN&AOXE;C+^`H5PVQ1@9N^xgSv60Gz3ls2I4u`(O8eb zzSts@m>yk3$-Np}F-L-d1G!=5gK4jZ#mG(Lr>>8p5zp|R6VASM?meP4b_M_fEou52 zduF+!<_l1=yWzb>e~I%7e>Z~mEaa6Lz4@t2-AiUVFru~&UZ(NeBZ7B}pYmH&WfAv; z=7n#MUS0qyG4}f+{2|9r12KefVDs64t8g-)&5X?&KK?;|~85kB%-@^8u@v~zdpdmK1_FHhAq=U+xpwIL zhYQ+fYIPPVO+?ofkzqoHi+?L_;celM%z3M4e#~^3`SNAy9ydSU?(e~TN7TjzM8)Gc zkTAHJ<%QPxhWM8Fq$gDJF)viDVj9!kl zc34jEy_m$It?9sb1bF|NScUr0amg_deR6*9MQ7U*>{rk@1KxHCqVuMu*YZUkV63r) zCT0^DQq5-_(ws7&GlJ6@hm(_j#+66(?!|Gv_#u#{k_5rmyAJ!^rFL(E+`eoLS6Zd0 zq*B?0D+Ib&6*G!*gF>ba`6tq>Ob&Uy)Vz;m{(9B@nwtY1HY~QwgrZsUC(zCZ790Bu zlG%+~w%BqP2D>-Z+$Iz#v?~QA;=%f&WnlNQST)V z=PWh7=g(cIE1@k>PY9A)j`&1&y`+F)E*AK*@cd#&Y_@%PI=e{S7|UbKH+C18$v+GL zb`j7beG7S6b7D*8x`ABxU{XC%FLUX628a-GD=6vj_1v$l{77k zFOY-?H088j{qI61u91L)SwXZjhErJs@>wHLs!|JY{qGqLg*heKqsEAbNFfsyxHU&` zBq-aQHj9j|PZ&ceq#DSmgwpbi=5KWn?NA@b7Vg}9u@a^7Pa#;nfBbDbb1$sFDt*zZxzk20#M|S;S|fxZ7ur3)8*(+s<7U7uAA)643(r@Zqn&ffVu*-~xp$hKh}0 ziM^2zrrDWe2`Qn0Nb))uA8U0x9A~aQAI#{we2d(72Da-Y93=s%p-fdm5D*cDPf^yG zEN73Tf~+nd-AfM#*FmaR^p~Pam7k+%Hc@tru#*vnUI}`D;Xg*9E@cnQ_^J=pQN0HJ zf!>&D<=`?u&lBSTec{=4zPkBrK3#u)S#I#1jr$ho6fDq}`TVq#N!HibqbOqwIu`p9Vo`Sy#S zR+pJ#_<01j0OC3GY;!MI&5F-SE1ay}Ai4Eo4iqE-DXo#6=IOAuqOiuq@zHvDsfbi? z1X3C;oc1w1x~V^x_UpVTuavDar%7UKWk3EY)X`ycRS!kXG!;yVw`ZtpOjI9-Zr*ih zH+ViyA1#|{K+zl)hznU>af~1kb2hCfAOq@aKy+J%3GmqN9UTQ1{J0_VaQqE6rl{vt zxM!}^s&JAOZgE{n0sC=CRF&CYP;-j;Vy7gC7tN@}Q%aNzePt0I?lDABWTRlV^0FJO zHHySL($!za0Ky9MgB-k`e6$o_658aUX&f)x$$j|d1be1X@ZkQtoUP}cD*st#GLdQIiqRD~mbXJ~qrf?@Opidka&SVz! z-0HNS*W;M6WyL=_y?2W-+J*ayXts2uXK10qKIQDE-k)5~@`Pj>y{etnFLxZPPNp4y(%L22`KUt%9?GwTV8F(b3MNE1E1c(xH*K8O$p-XPB*J{|G&rjM|Q4 zK`Vx-SQjVvaPGY0vCZ}YRca5pnUAu2ond6>f$>RciQVyrhUp{`HC1509=WF;f?i|K zB`|l$#`wx$#*nojP~YKVM1~xUvkC-lQ}!!24iWLpwW2Q-#Nc)~wc6b2<}9mp%hHlFn~1e5O~)2>lJ(W0^l7_|FZm1q1-EG5%l*;I7uQpa-%CjS zBX#-!Y5fx!=?PlhGaAFwkHixK?J*s(L0xu|REOA&w2g^f61Uz}J=;6hku&tC2n9lz zSxFN5^Vzxe2uI`3(R2Fo^-G)651OEU5g#v|#QU<{^&??eaFV|>B6}p2_AGxAaU-Bhjm zn-hu66jC-WZBog>aAw>@#*LPlb8Sk@!{(L73Udws7dNvhGRJd~e!2y6u zHLKp<&_Q_HwbuMZC>6^NLn~1-v79;-we`@HGb`H87jlCU}VlA@ABkz$ ze^2;_d)GA)pV)`t$?-Jr&73*lPGGpUWNNER`Oa-FW`S}#^hUhyP`!Wm(;+(0x0Ffe zkmsO4k;yn3>+0jN$*l>5z!fkfp`fIdz;jk4seD3P8qHgP2Cl)3gS9QIM}u`aGN><; z0T7_)Y)tW>n?6)>lzpnnaQ)pQWPoIPbg~Cp0fE+E8j^AY)cr#HG)rz|PyZB(#j!B> zi|IpP??!9HNiL+k{LEI|BDS#G_@3rY;+=+ju&A(d3|fP$n%`Wek(l|}v|&Bp-2TJ! z!_%agbYUFN#RBp5%AEG$Of@SD*J!72$#?tc9DSNuw35U(hwxVKdS1c)85i>I%`X2;WHR_5S@1v8mFkybDYz&C+K-}u?01;B{ljBptSRB ztwI^CQac7g&9xFchEd+Vpzop5?NL_i!*q^dJ#(^$C0vDbtT_1_iy|&KUOW0EK11T7 zJM`YeW}-Xr&Gh@fsLD-u=2GOT*44EAaP^5fe$f+wxNQn?5uvbt(aJ?`wuZ9V1=Qe5^WRZkyx*>qwQ1%NQdn*4f!+Sf5L9- zs%>&qB>4PgqOvJVDE}rWoBU65vj18v{C{Jj{-=NUzo-NfBrTBSkw-q+(mF{O8db`1 za;ii!(s<+V%x>z;pi$Qe)%=MoPK``ONSOen6lQ3&T4B0;{C7XZzSsn8=bE1K1|4GZ z+ToF*2cCC!ye567c^;=*u5@L966>=05up^q6(khKDHYVD^eKV>es_6CM;^rA>qG#v zKlgbL7!2zd>osNOVAn5tW5TT}7Bna|x{q*#t(6?#qmgidvzP3C z^t58NJG;y@vCW7CT+?!FJ9xF+^5trxM*|A_We@23V&swJSpAEM=-ZE8re#{XP69iY zvqgyxH2tjHSg0HUKJ=xd-@*C#HtxL0Hm@tm?M)Bo@F&G5#s4T$#F1eDZvNZ} z{ZsAir8y0$6daez_pm}psZ(%$Hjg3L3f2RVTInNy+el(HPtD)q6#m)C$VwUmlB=ygG=-xQBY5l*5C!Mh<8f#Rf)&DU(CB6VlX{*7M?wu;4UG1hM~RG z(EflC7IW?x%`7g{>kyfMn}FrE$4&c93hi`*p;$bhJwc|BUb`PaoLUV}l2(malv<5Y zlva%dNG%RkDmKffUVtHts&5T@(^JJ8Rd!!AnUoEsIAXJ@8z4Vmo}=#Z4tWK2+UIT= zB{!sJ<4McS?oUAasSY~RElTK}pP6~_bEL!F4^wBKLdOnAYFqcc64q(6->O;>he^n; z_`AISsvaFu!=E?$5H~6KvPRx9n}fglS?+Hc6jQ&#pQ(SV{;u{PT-yIQ314ON|097x zEb`U4;wYr=sQ=#=xV*FlGC#am6H`Zm`iP}g&(H51;Kq-7NZgb<^}s(W{DXZ**6Y?T zW*539CqX-(QUrSOU9Z8O3I>16gyP>M3%c}_S3l|~Ki2I0^!~ouXN;%4ITg3BvwCUb zn!1OON55Q6dCGcm&_IVcXck_oN1Z%is=$MfjX?8qMqJ^ zBU<<)2j6*&K$c?xt^!ZC?^Ot_{u%Y>$G_jt#Zs&+RdgPvoZ9pyy<4bsxBKX!iA~Xs z`Cu|Xnk{h{~~<0?kSdJbz;W4T&!9=TRynIhBo z{qB}N{|b)nzOAsP0)6`i{?+mHf9`hr&*ZnA_3h2{9RZ^DW=8+mDt`}(qhu#!1Q_6X zgbN{gXW?wCu&|s?i3YV8i1VQ~>oCoKkUToqUXZ+4(7t{9Ij)APvj(5GHkmf&Ho5XR zLgveaEpaY(4%t{4F+9UwVhU^>9iskQ-}z6kccrO_yFub{z8;zqzny*FsQd@6rCf`% z%r>b`izBCobISLr4mK-eD0t!r;s=s-M6gr(-Fb_JCbxQy^3uoc?z?i}bJ-GRGQaK5 zOP{ucGz|*!Ssk(R%uO|(sA3UOzuTlg$86p1hmnNJSKwMT{NtATT4IVj!Hx?FB;F=8 ziYq1~aal`0ZZ$AVrs4;eI1vF1jNNG2X<#5nZo)R;;ET27@@T7kJbP1t>1O7922dMj z3sM=F8h^FA*#5{EMEF__%CGbKkJb3s+e_&`IIGImX8*k$asYcX8zVEr|9wfSR3sgc zm61O9?dOdQ1Fa_~sKZ#2KIgxHDFNziAU1#j1ArNT%v{&4om-tqb)O4D?J(|!d))r)Gil5i>hF=UK}f-fVxLZ}ustCh0u-ou0^oUlfg>5ccjA|-W^FiEAQ^fd<5kxu9h_qmOw zJEH^6hc2XrJyL`^bM=fo-YHjU7L;viY`W<=U6fZXQ~NH=+(5{3h?lzA&ON+;c|`LN z@K!?1phh`1xG~vVKUjiLARL2aSxo#HU>kR~o=U7g5@lYkPMh@FcbE3SP0CCGPa6r= zfWm2^m#U`&uT=InhW@>}A`%cDN!W*x`~dd3;~fq>wZx}n&ibl0g&ZNgwm+r(6I^mT z)k3_Ewg=LwB**Gih-Yh;2_1VksX4?&5o$lP6j?+3=Zt0vga^ezWSn)JBH9Hu+oj!a z+vCo2@uzXkr2(ca0|!lH0d@IZ&yF0$pojynX&HEABZ z$kCUz@dpBlUs7oNtTX~i-`Q-9l>ppaN#ml!b7Xh$AZj|oS|*Uq4!Hi$L*;Td_&ZSl z?y%fZpc9#%@tj1=&7?PxON&7py(_CyrspUp)A$oq-GC24Z=5mDN{iC!B(>JfEHRSq zh3N9R@}c(o#O$3`zvx6-6j~Ru1#`+Y*;8$!q;t;5o5o~`KTa!8WbO91SGq(AoQFm2 zD-sel8>i1o_4;IwZf2D(a-7)`+_^8`0yi&0Y^zI_o*qrJ!-|^1oKls-ik2E5V4MeS zm3pGGnA#e%wFj!{Fd@3oorcttFR`KMCkl1+`f2~jo+3u?GD4Z}As^F&W+;KEw$bVX z;SKba99AD-TGy*~`-kN09-wuO!Hmsjj00ml-4+sB3)Jj#|9$it>73& z`$sm@$Cxa|(=H<}6W%3f2IImelZvDqapv2~e zNTdw+hvg895DQ9-oKh|oJ#r#?B83aoTkb^cuX{}BGSgpyL6`#>&3MpKyvNJ4 ztTaB%f4XL|Z%kXQ?PEF`W+9|UBF^>BJGkvVXEyCC#dqo+hN}B?QP&)OY1VmQ@-7qT=^;kk4G_YdnHg%uqMOr94si08qfq*g z&ozw+pGmOnR6cSym zVsv;Ubv4|g6@sCtrPdMFK?DfIwLy)$dSX0nUYgpueN3u^3XN-Pv3_$+3HqQlyZewa zkZNm9Nm94ZUP8w9lq)`mE}ss8mKdkrNKcrOh)%hdK>5IOTfq(ah8v4uYuG+hABiI# z(eZ)hGM3m71fbz^Duip%D%#A<3Vy`9rnLTyADucPxG(f;OYI!P@(Nro5>Y~eZIyyD<_beOi9 z*?QE?=>cjD;}Ul~NPp0CeLE>;Ns=-6zEZ>xKO2_>=U^u#aT3g|XeY%)Tq$rW?^aN& zVyp)eoZWftAM3G)TGN6Z)T<4>o`2T1hbXv7u9lp%We|EKJf#1Nsy$oLn#CF0C*f+5 zf>92cwZ_J7C&`Y3D*XzW zMZSif*rl~g^Imv@$Yko55!#=vQbOXGmpb7uT*T6d%VXLA%r8*VIyBjai>mrfz_3I$ z+q+Nq5AuutFhfGVUxu{4OuA+(&A=^m43~?HIJWd2;xL8^R}f$}s(%L|n>}eAa;v?q zKcH5KHoyQ1b2(KXVCI?BTNI|?8YCjhl&v{KT)xO3MyNah`LM`b=NCbY_C zZ+e#1|1CC3oZ!xZ}>piKj8!aYT*BqQ}NHB{y)yh-$TGAHEmnP5tNSy z9rgZt;!iQEvzLsuI(}Q=cw<-h6}mA7MiR8sKiHh43EdV!O$!$ zvB*M-vfpE*NT+>5)AASjvq^Xk#lY_F^=)&_gGPiL#w{cbNJwjwN*h9iKbxCr;=~JM zq&XC=WJqmJNE=Rtw#SUuLG5Mi-3P@VWQ$KrJ<8}ZG|A+g6;pT-qXx8JTwGf#POCZW z84ET_n8b?&V+?|I(R%E>x87iH9iDIw*e0%Gdwaujf{iCg7{>3=xlEUdDqmcpV?3P;VK)iFsF$xWS(S1CQfp!9usX`RGTOk1vOrAO)1 z&9C{pn)dV-4CKJb7mYx^o5L14fK-wmOIXQXP$^luDKM}q3O|43>zP7asJ0iCHED>8 zcfrk&UWgwVjt4-%jjEdsXHU79D6pz_7uI!jghlAd5Gzekh`lFpcnpup$f7i9MQNCw zkx40&o45BeV7H|F`H)J z%HLwdxYk*mn!&tT0NPlDls4C#VYvJ(7Zu8P-aNO?_GGq^bs=$xB8`254kb1LMN@=V-7odapu#e#P zF|+Hc(7;iQU4y*p_BgHX7oPE4YjRkdHR;3oIt0BP=b-Ru=JTFanAmO5UIJRb_7Nt; z*+t#Px+5=Q?A|bWV;QX27$dcjR@gNexZT;gh-qVC&Usb1;SSMqXdh-Mg-PcWf8b$H z!BsNsfL9?|XV+5>i`@KJ(iVLAE3hJ6>hO;Y;TC{O<#sxX=(Akhtq8sN;NOJs3zB!bFl%H zQn+lWFPm-81d0|z+Y`4B71d7#wJ6!*1|(5Cn4$68t%PITMMG&T^h)e76nPusJIf}` zo5r&++5yRzs)Ng!!6p$;y-@p(@5s3p!B%;ZT^YusL=81ZhzWJd-7sp=E4BalepE4| z`S65Mnq!WjfFuBei`xW2XP!z7vYhucA={z#N+jg2$>pgEWgczeBD80Qa><~1E%h<% zc4a4v&d|+xd&2%VqY88zs@(cmt4>HuL#18dw=6 zlkS~z5_5v=J-LNNLiWQyTldWEE1-%5GvXUkGkga0{t?kc*U8OAn{_7%CzO`c!=Tj- zrkZpus#Fp&HY;RYRtF3RFqY;^2?1)mh>V5@7%TJFmIwzfaF$f~Kn)qO6OvSviIK~? zfpv3~y(=Qml{P7%?xsR8mg!Cc(hDV$Woe*_>@m7Agu}H!46~pG|Agq@HH)onBd{JI zV94A3T%{zsz)4mv+Z;=cRLc`%H#mhaw@zXR1mF5_)~W9-{lU>SX*C-eVkG9aCiz>i zPDVYIXUnni_gaRXqy}YmaB1T@mw9DwqrqaLzNAPw5zBgzaD&gXLl-BW!Sf$Rw4t!s zez2)>9X>a1sYc&$S0{Z1$4`-la^)Q1!WZ*N*Q!e8xVJ*}rSh6+vHK-W0-lM~N`Oe5 zeX!DsjxP&jG@>fnkZ|SE7|Fdm4c)I53pXeEY_0hcnM7hCfYYlfl*taE#k%N-rdf&d zeU!=Tu?5G*2+L4b`u-?D307D+UlXWev%HbAGFKT8gerG`ixmTwAXMSclpskt+Eg320j~ptMXA#2%3-twjWhg4KIi& z`k&~@Mv`KWCjI$fV1}M7p4!hya zkcMOaOs3D_hmi9gk@pxoewLR@jb?;{8ZSqS++mkn8}lp?5B3p@slO5h&LGlV;(xXdkMC!_KZq)QP^t_yKB z#ZfWmqGfdwNjr6GlGB16=yahQ6szdr2+G;~YU3_`|YIO?9~)*1EEW3rzOit@TX13`(*F zl~y9+$Gk)XZ!IlBtD_Lg4i{BQmrJK` zMT>%AzHSU=Z^8PBp52{cZ_i)7C7$VD0n`^e;p9J6UH-qoe*fWl{d08kUwN9p=V&G* zelQ^OV3b7TjI=DXwc5&4p$``A4=W&>d+irjI6_+)ky50|U)LZb_XXkYiiWW*$Abby<|67*^fC^Vva+H;1gumeamr~Ng+LdXcXT@q?BbYcRAk4 zg56(Z-Nw*QD@Uy(r*0ePC=sTDBeOd0ZrO%Y7PzTjN+n*1s1ahU~u65;yjAXLiJu|naBmy_2Wje z%wy&+Ht~gCGnx2@!jQ~jsKA7~?N5)5Nz(>YN%ZsEkB+wqkE@Qyp3grYb8OxZNl;(S z8nS_9G22LmJJ1QDzifiWM0;?Gck*^%7Ov(z0vrV)E{Y$6P9IOZ`n!Hg;eC7T!@odz z$;0HhzrzwLS@8_QI+T zpf0Xio>!C7-JD;Qib(=6plwh`4QW}{Gow1#6%;X~eYNHn%7UKCM|rMXZux|WYzv0G zsIxoS+bR*o?8{PZyW|k|jUg2f8McW>S@Synn(e*`^Uwg5g@(nMYJ!f!`^n48x@PZb z``grGVs~}-*XdZ?SaMul+2&x_&0Jqu+)Z8b2B}DJF~HiisOcpQRLQv4JFah*HGKtgDo3phf!Mx?#dU)x+Tx;F*QV< z9fG}{t~1vge4u=n2CX3*YE+O34URwhlb~BFwD!D89*%|wHSixP_VI8sGuJKVGo;)b zME0;`V2)%)Z>2y_8I~KYN-*;I6n%Vr((yzNCLGLvl9iCO#U#v+ZSD@v&UG0Mv?-Po zZ}?^`2cvTyVQwD;WXg|-Wu<110|lIoIEY3^LPs4A7n2qtuEe>(NF9=vh?cZY4?cCY zzKi?$(;%*MFq^;lwTM$=^Rn~uFeGj;5rSH3eCytbhRHq*?tgDXLTbzFE8C?18PCAO z%3{y$GBSDy?$O_5Xn3GFuJ3bo908zBb*G( zy07_Shp)u@8@pk`ToeIxTe3;O#*^1dFUB3Gh$ytEk5$*ZWx@O%8T#1`ybE7 zJWf7t%uqJ`%YWeQn&z|JcTnYhQ~hmiZ-zkaftoMA!!M4z^deSZF(!L9n96Oh6e>#D zK2pe*o|qM1mNT&<#CB`j5mS1|4pJH&lA(0VG0%v`Nu){Vm<*tE6uBP_P^wAc5nEb= zf>UtIidmTF%xSsk7gTc3=KgUq`dW#r|6YLnQ??suD2J$r{GGOFM*&o8+_wn2J&|7$ z!=6Ggxqh&Sx-L;ah0&5iQhQvXXp&pdugVkfY(C8`-4}uE9{&IF_6|U{e9QV^+qT`O zZQHhO+qR9{?^K@T$x`=X0-Ck z7!0Sdn&p;+8&2Mb+qE&3q&i@&7G|ZeoiXs#r1FU=Tq&X4xvCzcdY)H(^`3cqifn*( zpDR=(ZDSEegbb8x*^sA$nc#d@>3gMPk)28o0MxrGLaf&#gN4vvHhzJ*Rg zK_wrjL!hNZn4y!`RL*0r_17J4JKmnL?AD~?JNwAjopzMzx~l94tPKg*-LiyvR>yFWWXtQ5D);tuhqsF3Q zx~gKhR8u*WrlS_&FzIYwktMR~LltkeRfg1_qHeOPB6H%ZL#n#rlB{m@En58t(Yzw| zTV$1RwL^i&k;b9>dz9q5GfIb`?-5|XWo?^qU}Z=(oVVPN9jmczL~BTO{~Cs6-6gqg z`1?*t-*Pf3Uj^mNQ8jO@#NWe!wWqW#*HmUq{3SB|ErQlrgH+qn0h(cHGVij(`dgFD zQmls5w)L!{g!8;Z^1SJcvVQVg&Z=rVw4~#&TY-Py>VaSt$!*<5MXCGyDJ~nnAE{L* zbr`pKTCXI{<=_ql-@K-hN9@m0+5T?2<;Bfv#jLVLT<@!&86`WcUjVo~{FY!*^Z2y{ z{?YO&FiHV9g&_P5=bgdC0`ZbSoFX01$l$pKqkGFUTn@#yP;Nd&j&FA+?_|^l*>TW4 ziBAIW==$tp>M^u)PLH^sh+YZ$F~uvoXQ*xwU-8wv+Hu&u$}6N#jIS(u6TQyT{=G|e z#;3HFoL>#gqSLyor|yP~Upa1G@5*I?o%!goU6aMD)&D@NM9^%u^m|3qN6~qrs}3#M6a0BF0QUGVen(s3dpXB#gx|D`=XW1htKf( zj^v8&>Fv}L0;dkKr_=?TDHRXOcZH7Zc1fBuzmQA)8o?hl&Sc#()hSBMebwfXolzWd z`)~|LDw}k3bPdJ9UR+MT!`(sc{`;4vv}J7qhk}t@Q`!;xp=r=mwrTB(P@vf4qjCuO z;&nN(^lG9v`mkEhs*#pA{IIwtv?VIw6BfbkZ7sa=lA~!x;eo{ zL?s`fd;(b(T^z%38ji7)TtS}k26EY@6#+|3MN#V;mW+-%*RWCUu@$*CvW*4Glp*)= zDikpd#j3@M?VHJ#A5|2InxvkPtCk6x&Av&rjTOn`e=16HK4wy*LtOfhxWVt0ea#~&^f`Y)!htIN8dAWGUSA7b9QH3J6Ja#D?^{Q;{5Eu zwemULqk1GuI3i4AG)HtpQN!*G7(Q|5jzq5Br$@H;a@EJI{73TgM>RaRAmP>(w(o7U zp4a;k-!->I@5_%HiI`j=FRGB{jkQVJQq7psul4MvkeBLp!iSWNmy^kIU7l{eOS5h| zr$u+YL)i*l#NwEHTH2!nuj|(Z?}gN7j$dadCGL8)Q&x{&Ts|Fi+iocxgWh{fM-9lTROoYC-S7t7H)jRA5MxQU|xodXyF>i1dS7daf#qp1X z6?44O9gm2T=J>@)j|`{A9ZFvQH3wa-=DG5A#@Cs4MGqyY&apL56xgI?KYb&1h{tRm zE1n+4l{T)t5+fqyDBsNq$KqAsS9rCz4Q4P?R7_NRmKGCix+uo!}@zNm8CvB#ESxU@2iq zQl4BSo8XeLB-Nms5KMwiVi9j#NFpJ@D$$^kP)TBuWE@38A(25MA+?dWx1EB`dot2LlI)< zDH{h`?~P`R=H1xG2JDU8$JQ>r4Q=>BHs_ zQ)zFYIv#X`e>z2xr1&H=mr76Pp=iZ(MKzldw6J_aGmg;Y>U*S5KE#MBWPhZJ5W>$U zxS!7H^1^fC#F4tDBvfjM<0SFY)Qx;2w0w~&YSMAv%H`o~nSwaAV+TP$4XOtvQvV1Q zLa1*;t#`*mK{V|^G&&M!ID`#1MiT#lb{tp#qEMxC!JxSZanzP24i$X7YTr^kI?_Qk zf^UGi3o%K}!<)gQwFfa|Cg!+B`TE;bXxbHPFIn(3Uz@0)!72kRZF-G+8sJdlU1_4V zKp(rJx$vF(ctTc)4QL21K4;DPd8L-9$6_}VsE1-VQ};Xh^j{Ur5%(0R{t3-UJaDGw z)q@AxbK6$Quz_NGg2>_kDza3xC%iP2MJ^g6mF+NcDC{tZy0%gLR03$s#OVO`cg^B1 z0GZ~;AD&*oR)*VyL6`;Dqd}OZjOz(d$AN0}O`#}q6?vGJPPm!jmb0Sy8nxD`tY~>S z{{e+M0KhS*uHquq5T}-*J;m+}BJP-6k0_16v=25>#Tu6x-dV$~HKquD*{|AJ+e(up zrv~1Qx|OqNg`58EQMO4Q;EEnn1Aa3m z8fu67dKzUv6QF0D)T5Te7xf!NP(NG^%~^zcfMQZWGD3ZEyscbz=S zwo3u7W;%C&J&GMQ{>~EAZYEeyxuCaFA6qv`94N)3M!d-0*|+G848YFs=xwW-m#BC2 zp%D8-FI|LYxowdPkAMM8TeouYN+!1fEwW4LB2YtNu)btAI(hX%>FqB5y_j1nR0~i; zD>s%CK}~nzh%|@tdR8AurnTu%r;_q{`$OOu)(-MUMFut#VyLM*qF_PP=c5ZaO5^En zfe@NgAf2S%rRPkBES}XO1q4Er9tP|k(@8(ArLIa95Bo~asKo;BHkIja&D~+aJmjto zSe7qKkbT@x&csH{v?ygTipT_pq-Y^Zv7b=nR0<7HlDHxj`BefxHObH9jd8_!lFk%J z0-&(@vGR;NoiQmJiVQFbGXbeLN;c%@NkPvbB>Dkl%2Gu`Op~Va##G50%}ubAXv*AJ zPMZq^u_apy$6Up6<2e<&p&!<4c|s$(HPmIr;rHic#k=EO1I|;_htQ_f(az=3tkwQH z{(f@q56Y$A@2VCDSpNzWzHG%`P24&N~$I$u}Y90ul5cr#x( zUb`)$So~Wkk25@{_xRCX9KEBZ?Jf>qb|;tXRMtRaIs*_1>=}pz#wiwYo=!QaAv3ll_;SYVW50+IqZ+JrDd1KR{OfZC(` zK%$i6D)vtRD54h?&;=5q3g=-|k#Q5rN11ffnsnR#?fCl%t$Ho=%9-l}Izr{Bzq$|D z&?yT6s1<~Gay--uV!S26GEgt4e+OI<-o!&6U4Ys)zyg3t|N6kW#v@E$cMrW+Di1Jy zFS{}96M9&5Wn6%IH%!qnml4{^B!42V`@C71C zJtvu;$dl(cxs%RPEg24sL0NNy8t>xC&YB5-y$#}9+ohgd+f5Rj5?Ed84Kw{cv~x+CHSd zs$|^TbXn-plyAzYGkrI14&czb3Ck>u*lB;mqcig()&157Y$diFq);rtN5&k2&>rAd z&@7_R9`~abD^P?PfIVx%0S$sIjfCEe-UQlP^>`C*4eQG_LB81&!#|y%dbl+j{XDP_ zTo!xPdJ>rs&`m2jq6=wPP4yh$^6Wx>9&$LDl>mF_&871noa>8YSTi}I1LWawP-^Pd zmr7%ET3%QWBMXnrS&3t&&hpP4Pt2}W134pxZYpMc-7pFMj=NQ{_PV_oeucSB*sHlDv%^^^ZTzXW;!+1;ej5)^kAyl24y@-w`h#}rN?p#`=l20 zYgU%H7TDwN+@ft(euLO)fP8&%?L_yF@P%Hu*o8_gN9Y(0Iv*LEAEs?A;Y=0I`=(jt z^k0|5KX0>ZT@Q~^KSi3KkVayo_o8t%1~IuBLYZ8RqbC{U*uGe!IlhV7U9O#STUq7m z(v8Fh)ZeqVIGiq~er4O0ccvh?kT53!tkLg_P~^q%QwE`kjAKaB8j!g}D2%>)F%qGQ zWRsi|B_O+)@^!{=n~|y9W@Rt^nzcWw1%~P^p7BlL^5cpBqH$?8>DM*s$NSsy_Y+<9 zI&`#ihX+)I%2t2%5741ghHt!s{SEK1-*}()0K*{x`~wybMh?A#WLn!G=JVwF7u?JE z-hSCP`u);lL<)VA8aX!`x?9D3*-vBp+G z8~t*#9*sEoA-f@Aw&~fZ!!;an!7ghMxp6!HLuS@Ao43aLMIi7vU2^lyVvXR znBxP%^Ck`!05mItAhOWlofSxArWhhHEn*kLbdY|49Z!Jmkmz{W8zV0G#vFqT zgaCntBUUB1Dm^B28R3}IoXho2Ab{V~Sb>23M3pAsQ)8q4a78V(`c=ZIU37d!qt$Q) zZMuVIHFH4!u1W@fvC-Ct)UGByxly%ezow=`mbllFb@p;PGghN>tq$8`!$R|crPY+x zW_3KbY9slp+U^`Ruz9&gHZvR zOG;a3I>|U3x6;F!iQ^W*^#~&p0fW7D0Maj@9{d@qVmZXnm!92*G8?yj$9$^K^-hPN zOpzF1AU}K^(JN7PeP^;6Gfla)1Hdo)%qMi4v%pT;wsxB*ezkOOz9?fvDR6@w+P&Il z{ZSV1q!FtJ&gfg(vZp{u^q5$cHY4Th^`5C<1~vVJpUouY)NHM6edTi}Yk%?-EO%IN zL06sDtS*Ft-%&WpI;c5d)fug!R`1nn&5B&!BTAx8Hb$5HDyn=a(V4_2!>d@GjymT- zJXM~VU9D8rS-;C$@a6Gw<6M|N_-f?4;%W%rI&V>ES))0h1DxTW$7yv;KAO6Wnmbkr z??pnfK3Mw$=@)W=Q`iHf3?ukxk%MD7&wfw2B|Uc#Fg1c-PcxZMH<~X7Z`&2VZ6!aU zhUm`K*#AHkt|L@;exnk+J@byMqw(qZZo(QZ?>cxqVS{17Qsi2`=Y|M(es#H<0~hOT zZwD^M%V>yGIl?a*gBq#DbjqLK zrn6CDqelS;1}n3?M0;XFa+Fz~;mk~q>mtsrhvjpEQz^<_c^a}mQ-wu`g1jzEQ?H1# z0M?v;H@qc4T>fL3UMJG8LPE2MT{UJeD}xf{>G#r}AVc-V`~uamLiff~&5w4usZt;Z zePp#Jfv4c@#eCrfw&ZXJJ&SP3pIXV{<$~B@<;GSQ5rVlvPPa))tRmDBbvS+ z{P%E=zfo=2o}#wVJSyf!_EG}Kdd3HtXBONiZQPciRP8X|+)_{VEx1QA*JujySKn-- zcwLxYmBsGMV~>?WB(=77$X0H*R_vTMA_8k?we2LvOkZb*(Y9~K%{QO|I{>)3W zmV!Unc8kRwcY7-D6g(+7qw?4_zR#BR;PvF;;bOn171dakTOo4(qkk>)aPOuVXU>r(KbIl=&Nlrystw~^^l@6hv z@8ez}O6|+EWPvOgYP>@V6)D`*r}fpE@D3dj4f3Y+VYsOe+le0-_C6y>cuGX#?rRl^ zcZi37F}OJli70x9@GNamhz_N;g(V>z?C*#th7R%GKsILQ&C(@vJK>pWdFgS4!cc^s zO(3oi%z!=pyhWh;sXzE8O<@?_gsVr6e4Yi#I;56trcucLYJ$CK{WAfoD(%{wPU7ZR zSFx|~O?{96j%vpc-$p1+wWt51h<1wn%f#kjccz>GH=vq3QD9m$uHjqG?FQQcKELtZrSI;~JH%N_%|m~+XFRB@JD$HR)(fOZDd%^sD-z7VvsecIfyI)y zFflT5vv4x`7t)^pvS0tV-Na@!Eoh5hid2c6Q1}hMNn(`l1JGzP00fN4Y_i%wZxfry*Tu`X=4heF?frp1 zF6{i?wsu;~LXl`NASwW8!_&P?4`;I9GPovZzkCV-^$}`M+(AZJvgYQ090$kd<&n7r zgYXm+M@!)DjNEa`9z=)cxO$^1aq9MA2F#qYla+W4?{s&38!fLz0EIa8UbyAs3rNy$*OEJYPIi9)P5+Q;dYFXLpvGJ11~Q+D`u*jDG>rdWTRI=8^t z)&$0xF|aCzTB=&>o+z_}VVgWQ9rsof|3k+mR9a=UVy)4NHRNC_LYub#T+zBDS{f%L zSxys%2wfM4+5nu~yi#Fq3(yl6kZb++<)8_gC$VndUk*1qe1V zWT96qxBO@OP+{>F$|;9KAC(%TmvJO3J8f09)9ezHtJSQg+OrkZGGmql3Bt$?1<}?J z7Av)rM?#6qp3y2>MQwXtm}OTz&!N8#y`1%#m?9+3e^y1uFJK)d8+NmaZw_!Nhol!DX9w^#l#j z`iOD1&--+NB?nC`>fg z_yDVb4Uv~-7i!%uy+Xeul$L`6+_2*d`54&R=VS7?4fepu`4N_yn8=`su05Kjb^d{& z!;kFZ!i?{mkZc!&#v2TNpTpB6$rqz=YxHM7h4BqHpNuX);E}=zbILR6t-yoz<@mN4fuC;r(gf&p{qyje72v_8031;zGF!vQy7zQwboaY~p2<7fs zXZz5U(lZ1-;$qX} z{f}t|-_Gx}&iqNf%OQFC7ow7p=al+L&|6`>EE7`HBdw8^(p;(bS-4ANvp99a?t9O% z(ELt|paa~-+Uoqwt@SQZfx2-8EyIOw0kK|*lWxDR>N=T2I-plfKVm@J6o5Cr%DX=f z-w<|@-JV!mEdBxU%oiS?2r%CurJAsLO8P?B@mROBbMVo561n6j-1(qy0iy|ie5JD^ zRj?bzKs3xAZYcd=U-JPg3&)r}<}-?%gIIW{o%}1D`O+IP&JQT1w(N$W5=nIYCYfPBty%YHHKl|Zf zbUna3Nl~g1r{H@Yq_`=a1Zr%O<(b3+%1D~6Yr-)aF00m)LJ~2M}un>u+M*xh-NpMrj6S}p%?S-TY zhG-d}B%HzjqWjC#e*ThL+Wa=P;IRMB)XM$`ruJWq>VGSw|9fgyv$~bDwhHR!%#`uv z?-`keBAN7f1Uyy~MjvSlLQ)$G3oaUvgr@ietb<ahb!G#C8MI1#m@BSXEFDXd3w> zs1@*A`Sm8@jqhd{b^;0lKby6sRvljkcRKp)a?@o?np|9HCNrFKogO*7cDj2%*qPVZEm_S-S}Uv z!n3U=F9iX>P{~#oMTv529$NjUW5!wMr%l(yr(~qiL zyeV#rH?nN0dXl(2m-ZtwapRADZ!M`Vp1=0mcr3}3WVugbqTSQAy@zH>(S|Rgv%mAX zogCN_-5LsY*JnC)e{3@}Pr$gz@OXZwDx5g-)|E^Z1fB@tUmN|Qc%4rUx(rVoR}d6% zAqR21td3PTwv$`?MPt?I%BZ&{O|A@^&`g-@;z&WqQ>G8MHcm6BVMjeEVxOMra5sr6 zI3F7;OfUi zY9ve7WMu}%llTVP+$#>PLzl@j+jx6Y_YZx5wQNcx+eC4Uqprc9uWI>xD$hq8)H`n> zX6r%lpX5syGm2>nDM`353HYeGIY*E(3)oxvbC@+jWf%|UfWwZDW9I7`bW|ld zy?P*#Q@ZogrenW&Pfc(*@W$P7|Ag9IF9Z`N76F=?S{I2;M&NnLQwFkbk^h7=eRk%W zhUxfuVK(6+_Lhj??p2JUp;M_Ly-;|oyDe)+t!V|DBOh6kDH|8lhFRSg{)iqmO<4~O zN@Y&Uqp75HO}1y6T@Y%Y9tJ|3?s{I;5@I=pXGfjsywahVaFk8Uct?s#UDaO=MJ0=E zYv#3pxr})Ec+2xrl{r=FR`uj)yS;V#U7TdGn->C!gX9v1x<13d)lvW6L5Q|u-=2~x zJXvJ^5<9TZ#B@qxL`^*k1+5095ut*n3N4|ZJaAurua`c(&Q-)Px!7a1=h&pB{=*n{ z1&iHqk33dGyr1Qo2YP1|9;VBBFYNhe2>t;`n1VSIyHyQ3LVK|6 zenoPW8g}3tMWfwz_nYQhBanq=&%;df2Vbm3q19XxAp!9OuBTT3*c&+ReO<)l?qBy_l1Y zM&1naRRw(|kv9tEEJ(4Pou~*5i7#YgHBBtHneVPYmo@?AVS&37BEp*KLSi|Bm<5R+l=Rr8l{ZGuR?8z!|!5^#Ns1^oaPG9Y;xCu z-Xx}$SR+DXK}K`APo~Ufs?S5z2G=+j1lksWXEW6NOz-#cOwJn!xL{yC0AVW#$95Mq zHKOy|ResVDWLQpH2=X|6xAIo%OD>6MYsr z=Xn$*;|@rtqXp(OuSCK&hctK0Yp8`)DXL{~(lztn)<5YUC+H6O)fI%k zYePN4HPzO;Fwx6E;AeKz9YXS%|AA?eLf6NA%gT_8u5|b#2lg&&7@(%$@GiYJ;bOs8 zv3R#wy&;nsjRMV9F^n}t;P&0~P@Xlnr1 zD)2oqAzdMRtiz}oFWX6Y;048!4DpPL`Um|{nYfIht==M@@-#=d$0)rYACS`z1iGTz z8=Tr2T9YSbOSUttceau}zWW;;;Tyd5B>3(Lcr{RFPIQziDv$2;-oVw&^d_ycak5(X zVVJUl+y!LY8@kHNGF$ke*wvi`eW5z_fYiw<`9P^?u%O{pyvX1R{9i%h%t%P02Pwv4 zBnXhC8^CXfIBL;PlQEqj(K@SsL$NwMY{Y?KTH&EWNUF1jLIU91d)JF0orfCHV(Drn&z^gzT63T2*wiGBTvpilL zX~seyjWsMS&NfV{|O2l zN5jqkOL$m#Sy-lzJMlXO77xleHWmv=bm8V;A))Wlc8SlySgr$i)}hdr4a%sLDp7Xp zXFkk~5ufWj{mpAPd3*$Z$V|r-+#PC>8Va7Ptan zPQSqQo@SSPNYvzkGKKPo04s4=wkrb0l#`l@&O8~y+#`(MJQ$h2l=V0+qjn&okt zdCGRWe1BYp=L06!pYE$9KR%A>?+cEV0EWL#383I+&fB*MIxPsWm^yYZGEyDQ@?YEa zrnEQWxQ1VE+1YM5!&S={N=9$-Z|K%Rn#1$xSuOEl?$lvy1zGyDYowNEwRN`@BU^ad zvfWzgV(GaGJX&M-i$*SoE@|LE8##RK%JC=MFrH77TQ_jP@I#(T<9W%&c}EH|GnTL+ z%lYGFk;$9u$8#T79e3|VONPLftyh2@jfZUMcLN06ou5aT1CBs$W?^sn!E^>Gk|i)s zLljR&BRm=LlO(B!;M%c&ZrHh1pF_5+S1e582}U1Zj%XC^+QG9uGuh;VWG5Zec*c*n zK|`CV^nEWl@@{zE=3)CB&Mv zrxr~nv)^JY*JF)xxl_}B@grl*mkPLCRLqBTU|;D zkWu&IshT7{NSI0;zD9vn>CGm~nl>FW-uV1#K5Ieu#6oXeT{@a(yVGMv(s?YN;L)^S%Y$OVTJ0C$eaS_B5&>%>DO15sHkx3WvtavLDEK0b zs`uSjK_d9pBmqdhbfhgpAKL+S2Y-u`@`PJgh|0np*eT>~) zf*7tL@37|%hLJ@89wc<#!83kx*xQsXxs<1w`6vm`_;*>R2su6>>cxlgqvJ0`OH!xM zGDk3(Ki*&;=uBN~bXU{pmrUs&hRmpcD$e*$P>US23vCKdEk$k*SmPHoJ;&62d1WL#poSPi*f+#*8-@@a_MwJArXmU>BZ{lQ5R!>5 zB&5y?7fefoH$ignl=wgq!uVlA(Jdg+54FM|ND)c)UELd&UkC+_SwbF) zT&%0mIUPr6njg-wkSUg{-iPp~N*&IE`$rjXC?52l1qmTl^|*cN(k-Deq9l?oNfOwv zawxHs6KqpE2*pH&o%g?yC;p;&UD^1i##8&ZbfW(WdE)=m_R2rg1Dch!HN5ME5iVkW5(h8nn%rO}4@!_3eu;+d<>JwBG7ZO(z zkIwND;$liO4k?|Wf?b4k{=n!sDk4T3(A03B?6OWQvYTmc>mJ}K@4*(NDU-}K@R)g^ z{88&vNhv*9y{tXTX2o3=o3Xj~*h1%{#2IjXS~CrN!g**#L4Bk9YN)AcprI+{k_ljz z$yviTGxr^Vt6NbjCgLeJeBGQcQc8!!l{!JHYH1#~2~{r_e|H_SIzx;|O`39VH;L#_ ze02Hk5=}3iL)v1|US5F_{-Xpgag(+^-z);N9E$7x3Mj_Jpuc$Y=dfk8rOb)WoeT(*39%nt|1RLt$HFK>qXGN24rH_Agp z47VF69k9)_jdadwMf^x~tQoyXOX6J0U3LF=TVcdAwT z2$n1iBo=bR5esVzzhv}&D2O)EG(tb7r(t*=TgL?h9~U!u6#4UNlT0j0$EPrU3MZxVLgen)#pp?Bun!`4n|_rZUCz#mV{{~WvWQ#OnlvH|~9Yd$;Q3GTy^IeA4? zzc_@KCjw~oqLRN4PGlBoIkRJ#0cqYL?O zr^$a38kKRecK#=G;eUlm|2a8g;^d?T`4NV9R@RqS_?A1}y4%Xo1%!jusWEum&n>i5 zj3-UmNHPobri1YN;7MiSRsvC&N8fuCGwqXg5JuPzNQBoS6spB4KQITPn2_q^u>b zrD90oT<>!*C$l1-J5ig@F{=1f=5{fc3<7#m}D? z)*`H@5A3s&SrxhoOHdzTlLOHvoM&C*nDKwV#l{7D+Ih0vci>Vk)CW{IBw!A}`tm z?Tt!>Sj}5?>{QqGOve`*4OAB`M!y6~k)QLIzquOw6MF8!^075*@Hx6|cgM$Iy{(3u z-)L61Pd#g{s-AqbG_Dx__^i4Wf&)F=#ycWem}n6+W1VvX{gQdbd*Y%geUfhB)|{~e zYq@VRnN@j>U?}GN_T=05-em2T6Ag~%8W?bthdCZA95Q^+7AKlDLk>{HxFg{~ki_mt zbYeO4e`I5jyVT`b%K#ct9Y0x{ZK#WIzAfrCGYv zIltKEYI^`5t|Ns1exEgOSLa5VKYPwFlmz2KFy zK=eT3(ZcBgqma!hTJQ=suI8YhqFfyC9IgGHA)n747A0Tl37IOl;BDBiaQnRhTUT~+ z^nxR=fFMZTJlAv3TLv4DCsYnc$$E0Gw&s#_oJ(8f|1IthnN0H+mwKS=O zpau!N56ygoda#cTwa@iq2%b7Bm!S^K%lHOaU$P_68>S_eK~iGCYlzz8)?w;S`@kA1 zZNz1rF^wORjT}?mv?udE!@Cq=wKrtrH^paKWE=muzAjBo;LcwV_b;+~H2;S8=)WcK zV*g+H_WyL_Rh%uXok$q|f#z)GEm>p%l+TjRi-iVBk;<0HNVF~6c!7HY@KDSlLEdq(^i2dQ@9yplo`hKays zEaB8$dpJq*_|b{Gs)g*}^VK(fd4pHViU(dpCxpn%)?G&W-9so{ILQMUGdh#rVPr@{ zI&G}LQommqFAB_3a@#D8&j)@8GWpky$DDHx>mzsSX%%iKD+W;#S)oZ&R2G1Q zp;&b!fnyJexru!o51E8V2&@DWCsz*uQ!QYU^DbV0Q@_wp3RgZkFQ`+;u0GHOnPOtG z9g{NbL@@)1$CP&z^{q=})!e+-xe3ib01~j^;-vL8tM^&Dyxw6Je~gCVI6my+*f`&= z4>BKaY_C)D$4qJb!Xfn}OkADPg=R#S~YEU!X5b#Oh;MiA2S>~=}d2bHr{*yBsMDrAs85jgvvyT!ZQi&og?!rp$yEI zk3|*Bcm(dj=Fx{}Li=714kYw7PA z%|!OgGg+*UI6L_KvOl^viK2E%l$C8ob6!Px&How2jG# z6^afHqXBA$d#OkrtJe});n)q1$s1`dK9grqGm(Cqd#bX2P|zcLT>&02jFDLq0zg*s z(565_7;uJyJWMx~=zUt;ip8aHLh9Q&>a7_orb#Q&nNr6uT#E{G1@ry7=Mg#O&>TPb zfP7aWHwue0c7xESjF@DFAwCfSl|&VXg&<4T%xQ>nK^_!I+>VJl`$%BN1+_!>nDyVm zN9|t$lh=Ygm0%QM%eR_^ymrs<-crl(LH`lOy`i22J= zB(U+ci`vL?=Yhjou7tx+1ichCUBX77Ho;4gUrlN5M+G_`a1dpEe^bn|nVd-#3m9I42NIh#WIuGkM^Bfwh2=T0*%y?!NfYjA8)j+J}4SoFTqP-8kVItxMj)8%n}Udia>=$a^gB^sR_knV&rj_ zMGom@yF@dCIKj@K)kz`IWWpOB12scN+Ji0)Q^+nh;S1=Dwn^_Tg+ZpWe1xbjB+EZ( zv z^h}uBVRv@A9bXR~fVxOG4Du09ox}VHX&?)d!v*5r$e?P%BhZa{@CP|W zVn2a`20em@9}R-!kQ`GwsF!4{Fr^5d4XjGqq;NH|WNT5vi_O6FYcNX}YyYNr2jZT& zRK@Y7{anNXcmcALaZPeCk?k4E*lI;-DBvEYD2Y3))n^${uqo&h` z8**rewa?-PNxbndQ;&gykEGpAxljuXoAJO!KGK?tsGs_$Zps*B>B`+(Pn>TGX~-Fg_ZbK{NZI<~wyE*b+*=aplVx5u zRo91_+($@diu2jOLvjo$2KSC(v}7J#hHh$ofnIVM9`f4`ZpSsed-|wzZ4J2C1C8b~ z2OBZe+-D$2S75)0$IPky0u1y=yKGfxa5>zgzWJF{tlsH1Jxu32b9cI*{C*y`gIy>5 z)HOh?-D}kC&jk8)#HL&qj9iA+ie&`1o-rz6$}kz_7)cY<8&YscB-_a90A|L4K5R8j zWcG^w7oZN-be7M*9qZM9p~(NAD>TP{04R=sF3`owliyA>0*}&Y>|Gvg0Ka=`!UDTb z+X*z0e8{noC8|CkO_Z%YZfW~)J=I2p{>~TwX(*{6rJ%_?y#BPm-9s@781YoVAvM)p`^6qz`W7oc5)=D~Y!q4U(;T z#g@^`+W_)Bw?U0}o>2Orb>3TG_W+;|RU-=`=n{YNTkX<}Hy>+u#J5DKKZs z?z$^@gM3cBUVmxOkKq?nGl~${q(~9Op3a1*4bG$TxSYr*gOysQC;0LWpB?@D7iHD=Jz|gG{oJK})xRy1#gJe|cHhh7U;VuP&l^92|0`7g z_m^}T17}AI_kViVe}6}GiRG~bWfni63YaZ(kOMsE$^( zYFcRM$%w)s2xDAfb^Q}ya0rVZ_rjO^3E;geu`8f2kmh=x@FRS+!JTR{uoRfE_nc3HB) z%+1<{>WT|uHb{i?QS{RHNmFFt*7em@7TYzqzew}V{li(5AetUU2Es_1QH}}LDMjnI zPw)%qUn@Z={hZyNTt+vgI^I9Xn0!xuLbN3-b#C$fTacR_Y=}_dtbo&;0tDdVAw^;D=>cjIt z+sP?5HivSEv6+~kgmRhjD!k0RwD{R)RJorcaag+&!{f(<-0#4y5W#4s0yYCk>-oBH zDku$bAgXm(oC?QHb&rsL>7DBapb+?5=cM0w{Xgqn;D4`o0W(JvCua*GI~Qx~f7N)g z@`>zsC#O$Z`fSE%noN3#|BJG3j*fiYw(X8>+qRvKZ95g)M#py2v2As1+wRylI>yW1 z`<#34Id8mu?i-_O)TsLJSL0jjn{zJA9e;i3;o&@av}LS#G6)KB{|}qu*1&4#s2-_OBy-pRjBwhmvtk4F z0Hjo-o>6$ZC5FrPZR)fl& zy`ZjvTQx;2rK5*>bco>WWRo*VM8*iJ$Ky&x#-4?&&s~Q#?FhY2l0BQEohaf@`W{g78kQ4xDwwEV4CGZNABE zahXUCtrZG>+&&Npddcga-gX0Rp%ww0(|0DLCu?syLiOYzwo|``GGM0b4m92b@&BIvX)m8i)?j95}W2um~MY8iuP+Fps|u-7~O={Z3_b zjX3c5E~ie|w?hj|C$Z#MvbvPYD80rs7&H_jztUh$1zFzS<9z|qNIdGxvx(?Ad^K{PQyS(Kqr;7_ipK z3=Q%f6o}Y$-ecr>(zyYbc~8uJl+j5>gE@=jG?pJb>?Ntqh-$J3Q)cU8!6wFc1-YKQ zV&`To^*>c6Ng~|>F~S^X#Zkt{&8SS%@DAoE)=AgR40J@x1y;d0{kl!#Wu5_yRg z-wI&$A*L9EQIcW@*@7)W&+;jW+;zVd@P2cxqzJ>CJ+W93qH4-A@a`v`MG1d|iz#)a z8qmp=?od8MsC2_O$J$RRsOXr_ARYZBr|EywfEb{A!bD7C@HrLvN0eDrEuKAmMp*XW zGEwpWeU!=CI#>g&1nle_Y~9SQ0sm!=`(Np;@Q>QYCocv2MW;gzDoiU6y0<7|EFy2k z8ax(UAkiWm8#r|AvI4g*wZ6{w4E@OcOeBot<7@j)xVv14fCNm~3~xI5^l5|3>}cZi z_H>Qh4V1)Mz)%W+nhQhC@TM|hp+GFtR~3S54d;ZF;8D4j9&kjxg$Z+=P2BbjzR2jD zny$N00TF5?(WzZ<813EMHBOK1i8rCb`E^EKW;be8jHi0P{feypy z?Qda(2|943PL?!W%Fpe^DqtN)Dq3dbG{r5+#_1lLKu?HU+WWUP#bh-Z2pm z36BI}10+e0HX4H8aj2Uqw^gB)7~wb+}ieipzsS+ArQ znO=JvMZRz^cKWt&d+1E8F|Tq-M0JRqf=i=*0=F#=utZlkoUX5DzGRh7S9>^;z^u~dKQ zw*LKd-Nf;6ZeSbJMGt}Ud| z$v)5!&Jq6%55keSLEtxiD=m)rg20B5G-&)5UdbHXcjnOlGAcGTL0Xcw>7D8 zUcs|%iB@5K8Zfo7Tp_0h-=!&-=oqj~UgpOr=752jtp?_R<3zEZY$btLt8GZ62}AMY zJ;XtGNHOt3J&4~NOZ)QZE#IT>h%-LyNtTL*TF~;e4POmW_dP<5x|NB`zrXMvWa;NU zG1G;18T`Z?;}dP&h%EQw9E|AtTn4cD=Bq54L7+zJlqm^Pg~@mq#XC6Qp%i%=6avGM zRix-=?Y~e+r*Zeu6e06V=#@?O(fV7|qxH1Lur08y$ZIF=n)^BZAD3iW<9=Pmrw||x z{&!IHZ{^y5r2zkgpMTaN{zCl?s@6)_Dk$I4fS{$If^LX%MXVZvJ4Fi7Xg@v1pmkb} z4B7mE7Mp33Yn&5|*|3Z5uZ1wIlUe-P@ zw9m=^to6#IB@H zSAMP%JG_wI&6GsM0ADSgUV7u7h?|ZqRacry)X6Y`ihO(cTB0VMkT@23 zMfbTQbF>j7la2%wCcZK7+{%WDeFCQG>__xG?40(feMB(s=9*Kc7+Tm*3-r4=f06JR z%HyKlpZQ^QPy??N*3F`Eh@!kpFt9t z%t&Ow82QqSG)RpBxy$3D-5u&%8eD1^Bi%T%Kd2a8>{(^(aX(~UY~{X)mHUEQz6?u3I@lD5)X z-ow&z-(L0DnLI3Ik}-8*uVj7Gt6~dMHghV5tgM5JM|Y8wTAs`;!d9gD(iL{fWK%8H z6yN=$xg;MHhPCzlT7ZO+Gyqr&3O>r1DsmM$)}I#Bo)ni=$gJ9))%_rsNTy0RG|o4m zoIWTSSyCiMI?0rs<>b@tSX1Lj@g3N5`*WIH#n1Tu?Nu~NFFsd#=GJ)i+ll7}02 znX1l^#}To1sI&4ZnNZ#!CukqHV~ZCyU8fE)1nQ=oP?x@JM#PanZeXK)L%!}*iD91) zbtPuFROj7D5^awGzSXTBT3rc!Nbqg9c1w5Y8hW8V-)}eBle$wTq~jIS+5=s2B{+xk z?#YGo?-k;6vT&uifdN)=LRuVP>}07Am}{GvoXX1KUHN@{7^*xYbIUt}&M`NB_}0c5_PSNG{X7so<(TXciiHE?yII6OVOiQG^tTKAKk}dN zDdk7Xr)0$bFBb6sE`bRBe*hyZTRS^r2YF+FgQKm@KeORqiLg*v=MR3s3v7ihY5f&Z zOI_qCwvnRz8{u!{T*4j}!Co;zgS@%(Y1!oqw$*hkWPH}&iTqo()98%xkHD`AgKbh$ z7W08yeB*1Jj#HVAmut(P9Z=rjcJO0>J43EWtrW=0tvjVS7$JdC{8=iKzM}zaR9EHk z(rHXV_(Ib4A(-`%c|4)1G#wO}+V=W>$7)T4NjUnHK$v~&fOOBbxc64j`(|SeQ@8l0 z%=k&mH45nUnsSxZvQw3dB=o!1F&!PvDm$#T`6cN#RpiN}E!p)(Hq9&G;F4{Ki*UA2 zg0S{$xNs78sS(adK|S~=(j4@e9o|K}PJ(F}tWO_%?H)#G{?z{}#a?tOA~h z9JW2<(*VEFD<{d`qB6@4jS6Unk(cuGmF9L+>JmtH_i}AU2N1S;RCd}YbGt_EuzL! zE?j3pqk<*clzGnW_p>_Ed>~70zbG#;eF$RxQtobO$GebTz7Fx6IJlu`5k@=hdN>zg zn&?{qiqb15F(X_r6OKrk`*cw&v|`&RZBRyjv>rok&*~i6DQ6l+qfpfiLdp`xC#}FV zN8$r!UJ#qh7@@(FPt{%^TBVPNhIR!vCZNe$hDo|4xz;3V$4W7XxMSoDstS~URP+m< zK{QE_ygfuTN%FA05Gi_A7mHMTh+|-E>ocLCkb~1Q5Bf_*I*1}!TgYW`_r`? zqI*4H|C4US{Vm=2_P>uRwa=yoTN@=qTZeyB6f>1K9p^+5-s!?8PVN$L1-XBu zO5f$IzTLY#tafy~oL=(3gIs~KLDgJqe9hjquz{VM3e@tA%LS`KZ8qm@YGhzFUU5cd zhpM?M46By*vfe5BX2Tj9aM##v)o`z@ZzI%{=-YwWfAUUYQMy-a6(k&^fMec%ZYj(H$6ym; z{3R^@7?G$()tcp`VHa$D+Me93{MU!vxSQa+z#$`K$Q}h2kg2ZUMBHWhwmf3f8}Wk- ztLix22~aQ$IPXZAVWu!s1$Z9|q-H+LbZz(OYHGtr!%W9VFn!o(x7e$VqbUjUf(bY= zDJIiW-1jnMKgEJo0do0sq3{@zHxMWgZmJP=MabWdi4~^`<6nYi^sh9{PZV~_Jq27i zCO@2BP8xBfpiSjjwl&nhVy^R;v!bcmkM&zaZyHSW;;tcG$$FV#mOHaO?B$cx#3mjF zGhMX8Yp#yUfnMM+Z+IY_hUVXpG5TQ-MP85YN?-*h%$!hmeaMqBDY77p$bh9USy6@# z3C|BwU*$@;b(ix@vR>8B z6x>|eXg6FIZDCjG043*V)bL)dZS`&obRG3fwe>OJ?=J0Bb2`WbE&g@xSy;OF&@qr) zlf_ADTH6>i*M+C@Q~JGItm4S9aSQq8?Z>Q$b`R-_MaJsbue`=S)z?tV$J7`j)!+11 znAF@ATnQUu?z3U&>Uk{8aeVqQCYTT8Ug9JAcRCrSZ88Vb{kiG5Om_kRi6 ze>ZU8`Hw;C0I;$AT&6;=_}8a^m8q?Rxs#doUw5ERL@iYBAAY0d4Jzd59|Gw3M9t6x zD$})d%z;G>5+qUIGXnmwL(wju)&16Y`e1`h@XZ?{^wV~?FPmtx@E+6q zB3TtEyW9@j66?*BJ@W%ootgL<;VB;nBeR6Oe3Rj368+!YV1P4A3 zg0mk&ZSB9Jc#qw1Zmwb>mdP#Nrvr+4eqHv=;k}A~g%Wk9*o)D| zV9Ec)*nn@&6snjP>Ns~(Ou&di6{BUPsLAszG!>O4I_jJ9YBTbz)>XaDX?6uI^H%KG zTCass+l`HO6q+k0gPMbhqJ}0FEC#_zV1g5c4JOv!GzNpO6VzmsMnkEr%4!Sb_Sim= zYgj<gkIlcY^hE{{|A=McM1blq zqTqmzFrjXygJFL{WwHPw^syFOHSj6uDJVo?vh0mAv1`PH9B%743U2^0o4GM$Q>h>} z06VQvgUXh7BQinE*dLNiJ;Nik;zjI57U6uS==E?f93mD>LOkv$k#|}1LP?XWDiZ7A zu35$}mw}tFgN~4;@MIb;$yJL?#%C_(OWlok4tCvs9nE`6gre%!V_iyjYUMDRpf$zl zQn{6*@P+n3MH*#EsjTar`9|~2BS?U?@_?zXo)`@xX%QrkG0QHP+W=>^Z%sDA$|f`= zO1dCpW4R%ZHw%#ee3fF=0sc9^>gH3&&tyJIQVROsc*Vp&Au-90o`n(=E*r0b@)j#O za7trYuDaL|noUCJ8MKA1;X-q@Ko0Iz2vX#kig}iUikfN75-h~Xj1aDAK*uG)mR7ti z*4JbFU6g?S3z)WE7xa($Z!}rs8WJxHwZffcq^~lE)o}pqyO1W;f(7t2 zA)q9NaQKiJ{#3eWDWD#LfExUxmB>y*<084aCWXBE^;Ez@a6x^FV?2$In~O0yt%@+w z0hDJ)bJuTT4aUb0KUWg_(gf^)d)Tu|cvoSpHznZsMSb@8`Px0CTTQaY+-Kgp|TeP)zSgFqXseXFfOL(t?-L}__ew*75 zPyz6_wSN4e@0VM?ewKEXeyDCs0S_?kG4MQ()7|*jaegt^VSaMgseVF4J8~slY2jkm zAoQ7d5X|UJ&)9}ybq@5hY!Tu5jvPp#4fVLpfNXsVC63d_YOBTe*6@|lRA%)CXzKF9 zSZTVFE+Pa=t5iTEdMv9aP^`xPZI(~hKw+FVAD|41@@(gK4%2&JI9I8`bzr?n&-NC3n{DM6d+ zt!8&3LDHqJk~&(R+S7egQXDFG<-BMOvfi@rXg5pK+dQ$J|7#00WNVFL3hB&Zb?D$L zj4zAQodrx&bu9M29n8WTjrkHMq_qCS>?j|hD}Vy-rG59_{xWBT^6WCWAaX{`shy8= zA#$+bn>aGY1q7>x>ehL>I|utp%|PVhbMjDqsyUUKc$X3CeRbB^VjwB@deB@k^wN(~ z)CE=pN4bHsves~O6^^LQ#)Kz(54^S43=_h`5UZ*mE_}>|MW=@>FPZz9Q$0LW*uI9a zn@~zZ~=hfxa?zMZVG<7QYJ4J1o?= z>64j!P5T&N`w+2<$HT~ddWmno^fR?#SA2<^k;bGI7y1$~9j>H)WBEJlz;G-!^{BAE zo=afE-D@Lg0alS0=sd9vr;G&&Y(zq~pNYaYFlr;%_58Ld$iYC70bL;lG*c~m2 zmRNFS@tBPWpN*8Fqmkg9xVHatW16FtpOggUm)rP>R5Z2v0v~&9iTbd#4XN@CF?ws+ zSr&RiI{IAmEHs)l-SC#iEk#(69}gI7T1Y^OcRNB7gom<$YdpaR+x?TB{j1NUy4`Mz z{n4;j1c_4CogH!n-ocKNS+M?#Axx3@6-~Wv90fD(7r42)^75c4vKD zi-22DW@L(OTOgmC?2?n6cp4)oLp$_NiaBXsTs>)GlZhjLIkM#j9gg+1$mJj$5oWmM zfZWIufZT-uU3OnK&2pHMXAcYo1+ftWSxt?aO2B!EAQ~G-)k6U3+3XDY~)&y z5^l;a)q|0zWQmBFL}Lhd@%6Sv{D^EuCnWMyV`#f#z4#KaIQ^vaev#8I^au^BG5i#r z5q_sQ$71-_@!hnj<;yk|+G?;r`1by2icRFGb67&gibT2{*ii9N#hdhxVobgld#)^z zuiQNvZdrskKyR-^O53C~0Bp4WF^IbLlWuDD=%t!?*rnfYnYHg|7y5DyewlM7Y_jlM zI#xZNzXp>88D5X_Pm_sY^A73ZJn++y$Na{L{{($ySQTD09Ec zDmn1nK(BG^<`&Zx;MFMgnsJ_#38dGkCFazq1*aZ^SVe}rZsTz=LASRmV0&GIM|^g5 z>2y6l$TONgj4|%adFzrl?NE?ttrRN|t6Na!0kUA_FKA(uW+K}sQ%%{tEtO9tkAmXuak%x31mc+;<%r~o!ItQ-Sr zCv9Q;)}_tjX0?Y7o_*FXKGztM8I?4hGK44bMEU6zB-jf(K&VrMLz1Lp$nD|bj5&cDdZ4iyt7}9Lq?0{u0in+~>d?})W_3e8= z`{}ZzB%qG})76}OGHol)pHX(3j^=vAsr}~+!Z*oi@}Y!tT|c6^GtJ#C`u#Sfr#Tp;q_7>w8XRlhRPuZXGp3AoN<+81HZHo-?W&VRu~0m z&ZJTi^-^i4vH|ttw3;XtK$B*;H&y7{_;UbN;Dbuw0!a~XZD5j4*mVV>8j}_`V^Yr( zYVdCxu*QZ)c#->+?~#jmQpkEFJT9Sl%ncpz$57k)C0!HxF^EqL?E)9^IA2#!lPXm9 zEG5(nE&B;|_;IWRNjy|K^7c25Yt@T{n>0rr zwFde-vGV6xHFvMM=tRk{Vj8J)$7x=fA}n4@BgJa{xfOm_DETj}Xbtc}JCplZ?l4Bs zNhY6BH5lC4G&gEK?jOt_g**?E_)Q7A+dlS*m^&lS&QD11I%8BU8aB708ZMlNu_UPy zRf(GS!WOnha{m(3+RBvJl5!r2zO3BQjTx!l9We6S>@K#$H`J@SrX$`=P8N614@7m| zgUetRW5>2lwmJrW!_)juyz7iy_pYnyL+o|(4&p@5JlC2{L6+N(!TqAd7#`;i3;;PZ z8P;rJL?pIsaZuVJ&K0MIgZUNgh#zE$O~wZ`q^bi3603HqE2GYuv0j0>me-agJy~>x z4H}@h>?+WzrpW7i$=fr;7Y22E$2zvDB1J6Q5(Rp+04M%mohQOU^x;ACv-{ui6c zRJQz6%AB)lTUFErg;GYqFQFx%jtO6p{G~rbRw#^yh0PD^OdD}tW!^;c4)+oILpV~j z&(!C~^<)hrDH3v<%tb2mgY&_KmCyV0GjKOjmT1n_ca(@}6%rMmP@-s3KoV=D@JI_0 zkt%B> zRxP&h7xx6h+tw!0Z9`pKE!yA)<<=pj(V~|@0}Ps#XcY@~xQYWj{*t+9D$C1uW4Aae zylca%CC)-6DwUBU&r>w|Rux_P+alVu$4rzEcAD*%a_CG3Q|`v5$=GH=VM3iEtIO#k zNMY%=1H0<=0?D2qc4jRW>v9_>qZ8ccqE+a>Pc`hh*Ieo>td|8J?3z3koI*dXUb~H8 z}eQc5jW9}KG4B&1?>azqh0+4zmp_%;@g8jzC3?NiatAu`vDjiqtUf|$psKoRe zwSqTm99F8{mo0g;ShyI5bw+Y{n`}o(ValBPBg~)y-)*%&Lv6mYx$RU)u7aS4e3UjmA%u(L4xPn=sB#IYCm3Srz z3nDpAHX@)I$srLcBk5alHRyp`UkINS$ku>#p0-u(#f3>jZ3qC|qMYqbsmGI`kQCs5 zuDX|4V^TF|01JbCR6Jy$x8G*}vw(T5#uD@?HNyR^YVn`DeExaV|CPFvd=Ug)4{Esv!6fE{RMO5scl|qnkl*Dk=I1U^C#AXf`BkngP z0z#5eu{Z>DI&F>{TZFo3R8~szqn?fB<%f;&_6DCw4iz z1lAmz4^yjTwuLn-2?AZ?m!u9pjNW;3yRP-&{#aumpq%+h8 z-Uja6{R#}~n#gopPV0`ThtTxs8#z=@9^CjyzOU)k>jLXkGLnyXyzNqq&%Z6ZNf^S( zM&t1K3aX(Cy(kvj;1U?w;03aeTg*g3#==)5H#}>4Q92u9WTzc;! zd0^HE(98k3!#F4o(s2cJ- zE1OK!Qf+rRi_`$t0pRsd+37tT^hEUY>`wk|&+`9Xar?Kk`_CD`ADeQY6RksC=!2~j zRLCd@A_`ReuLAo`qwtv(eaCD+z7i7hX-oD&eKv%HD{RW#tqX6;gvJ;MhBCIF;v4gr z2Ec6i7QB6*Iy~5z^ZZ;b|FBu@{l(i2QHa|{bjDXpA)E_?6|@PHOQTi2Rl~!eIiQW_ zx9*R;mq;wJ4jQg8;3PiKH>hBc!TQ%E+?1e-wP_w7kp%2n8uhf}%4$y=1+8QOz&C0z zrfIL^s^yFDq=Xi)t+8%RcWU{%6f_Ke=V*;pD%AwxLFplvbA7>_#x_%30+wT1Eui0+ zs|^l?ze&fk6Q$sySd4g-xNc{gQsKc2-K+P~RYy(C#z%7Yq)dx$3N}<)C@B-R)1uW1 z{3=jU+KoZ`phT5<`iW6xnk#k~MO7jJ+Bu2IN6}7dcNxj_sX;%iImd!8Jv+l8v+e`; zDW!n&p|b3=Bv6w%Mpw^tjP`?8V3cmhtZp$#Ias0qzZr|yy%^?Hhvhg#f4}pH z`}1AKVaDOc#>LX5E&tcOD;hY=2V`}>DuT)_0U(JzH@6Z49)S@R-P$69_}$iUlp$DD zB^>9AhQ(8QZXLKA*`tgSxB+1ZTI_2N&n;tock$GsO4@gVF>8aFDUc z+{LdM2KrdYNMQ7|;WKH*e)BT1#*N%pIA3lJHv--K+-UP$rL%0fQR|qE(7Dy(e8!5u zGaqO)X-4<8W9nB9RU(vi#QE$VAP9=&r~;rN9fYnE?WyGfA47vpB0fn=_d0KA?V*)^ z$7An(c7_Qp4%m%N?j-VnON9obgRoJYZ#8DwY8;-cQpiC507HEKIy!rEhG{_l5lh|N z*RfkwGV)C%$zW-OTobbEWRq|yUUCoSgmTB9#7F=PbSBRq29gN}*+@86K_r&(H+Zdh z2%Lq?h5mGf2sZ|kWi6cOc-m}FiaXTt-eqIK2*vOqLelZ~pz-~hU|5s^s5aGPilOU` zKl>1Howg!;KF>JN-@+Ka|5$u6v~qU*9LD&g{vs@>BqSg!^w$r@{{Sx&>RL|7OQ`F_ z8dy?z4Dh?6?KeO)S}qwJ-xSjku(8oG4RKaexC&zh@b(C2#p6WV(>jsjBU=`PLtlalM_92D53Vq5CoxHJ;9lyN#ho^Tg}R*{M}ucxzo&M$Xa7k1 z+PeWNnjR@8S#bNdw?NI#m}KMEZ-elp%D;=9`fylOn3EH8gkgoooXF;_RCnjg3*8f2 zNgfkgXKcei$H!<}bJMj*AA5CXo&k`knWYLcg3i@8X5KA(0<_Epc+&DeE7(z$kozn| z(H+Iq0nx|87Uwd?I};X~QBmd-waQGXOg|?i7I4~{IHerZ48yb+=b2g&Z7){Xel5=| znM2o0rw6VWZ0#QNJO)6Et~0UBHzrQ^oDUgjuFSW@RSmK_wh{DTSCPYhm38HmmKUTm z0+$!$So2ip&0{;1=ABtfl_aT8`C?v9kMMA!kwB$svmrjjV*`behKJ9cGAjQNzns!p z4^a>}aXX0CkJz1GoglCD1qXF%{KxcpQ+J*J!%sfR5+}PBQNBD=XC-V@NX9yku&~RrY&KQgEqZO*WJn*KJ)@VkI*yf1Vb_p>R*;6=HbcABBCSVjPO z@+LBE&WZNJWO^-`=|zcW|Bg8ArIlb86_mfX9Oxh;53i80Ydam_ z3C0#THPS;nmK<;#=@gQNYxp+unChRs+a9S$(d^5P@`_|D`KuYh!nnO~%ep;(i~1M& zt`6vBu1fFv?EuoGjxvL<0BABp?v~oG@-1&|)hjnb%BE?7#{UUO!@{@}WtLW%Wlon$rv{Qup#e?`5w%gOsKa*Mt^be8&3JAHJL$A6oI(J_*65@ zTe&Nn3f^vl_;mx!X4m6-f8F2nt0f6cLPZ?IL_`!0b#wt}y4&Ws9w;f^`$gYdJ5)Y* z1?QHf8~*!)w$N*m-MFGj-y@DOb_5Afig}PKx~#+YUX#=oUYkTSo7Fa7uLQYxt^S_! z9u!qEB1WpP-4aWgo7yvxl6t@GNx1v~3Yrv0L<)wARC6$CWoJ>WEtC}RBkU`BmCqu= zjR;w7#RC3~9H0dRuwmKkh{Z}gOQKpo8U;(pxd;73ER#@@*^AEe%k%33NNP8&5`;Tv z$M?qTyi)~gwA*J8OkRnXY^0B(oVVhuFIfWISt2M?jL}m<1JDeN(fMwOayu+pgJWpW zz;{vu4$seDyd#lpsqskUXx&0zxQ7QVa0c0&G%1}&qwXl30Nk94R~)S^eL@ptoq@Qr zlU*7L6@yZf}dOijvRU|Eq6mOwGCy+C8En`0K;$cTBSK7Ik&{y3@T*AGrS&< z;mqK_9y!3Ui-RED%!t*LN2QVPQr_Dy-oIoSB@9Ac5f_>sleDjXN%U+P2UuWdav(~2 z3AMC5w{N(pKLM;oZ8f7Fw^wCWRpF_rRhO4fEs!$xMxXS(UjH682Yl>k@?Y}GR{my9 zTKvTu#EJ&_G-=2xWeL^fE?oa=Iw?>~HAR(kn$0%RZ&(=g%DwUd`LbMGalM%k!XN9$ zuZd&3e+%1;s@L$-2l8#g)F)=lDrTVAC<-J3FVEUBW!=mfIXeJg>Jc-h6f+?E-L$$* z>B@+?Hk-fGiBtMD!2w|V!eWCDIBgb^w>L#Z#Wrb3cgAZ6B4yhB$R;j){|I7yqdvJ} z*SvQfykK6rf?xXJTFkb1>iPjLwejJy^x=Y2P#w=2uCaixPmdp@y44j0c-g#orgyn- z=Js664AK7BT?51n=4d_ixy`Sn+i|(YKQQK z6wpOsA30!hvbQqAojV41C`Ap|5o?VO?8hf1M$DhNTK;6vP0~P!Zw8CTQzI>hJP$mF z^$+ilPy5`yoIH@<`rinO7>NnV0BoTM2OKHEGQ-E#9vL(rX0oh*eCOIDWJD=Le6bt1E*{B)nXyc5+GP2Q>|GS0Sf z0t5yXT!^mqn|8gbhBiT!q{-_z)A!-Jmu}TGe8kK%PchLb&(c2_3N|WL#ROYhOf1r@ zwsq3b2O^iV5N6Cy6-1bRCRI*3?EDOaWysgUN^9JFxjun>68QaxiOcXHr_H3rf|8Df zT@VWRg6P=dok~Cx+dcX-%o6b~6u%iG=9n9eUo*B&9H}7=C1w-jjGsWDu`q`)XC#62 z(DqK?5r>&cUmjZTb$`ooVxx=m1Yzm%MZ(qzEEY2`G`+TNJ*S1&emnK@k z`F8?~CHdsZUrW7$)Uo4vhOY1lx3~mmoIP~J?ptNEPw!r|O}{;hW);hT7m_v3lrOeh z-<7iJVFRBa2KLoq3U8BUh~OWXTSzH;V?r0q%+37hF0d?S7%vv5L4*pPt=0QOAZ;TY z-m3d#7E*t^Kjc4mIR6i3A>wRk^*P=Ru=$5HYHM!e^p`eTsA8*xErRnsY0p8T8Lhwf z8>)hqC6XDuWTka(J&GjsjhtDJ-~!&ZWD=ySTMNhRQsy;viEYNU%qD|j=1gNrUkQEY zwIjzaHNW5Q0C)pG^dZ>avJnKXGiImbp=`{Cr0eQ zGLqVvjXOhi?mtSYcA8n*+&5+R)p`0ro2^zkdHEHoTtvc3i9Hi%$W%rbCxhe}UbNCq zGtuIDHa0hyc(PYC@R+U?tQpIWCZHYQFin=G!cvbT|twS=F%67lQiy(H*g$p z-MLSh8*-icYy$Uegu%7 zdDisNi0`u0e_%)Nqw{(^F?ftpi^d?XpgLhKB&Pl^0cZ)gR2P)dPmeV+DmA3wcZe8#r>Z5EpwuM zF8l$q_CU5qv1_Ji-{Rm)V`MH4F%`RvEgZ|CdzJ4pc9mh?Ot%*cX~7fbh+*Obif)H0l(M}9^}>w-Iol#T zD$8(W$N?8+4ZmSvpiqzC17tgQ!dg_Uii-L(zEK#;oD4TaBwI(iJ-H6dRMOHLCle-= zX8T4p)`s|&H_apU6q%%}5&;kT%1}iZ8#P80A(hDEORVEjc84`v1>NloYphencTu5v)U7`=BUtp$tkO^Ez3+2h{C{_S z{yVDp&!waPks1GAsNx?|e8WH1#HXhx=&v9srX>++T8INdloRv=L$F36g{DcN77OIT z8}C*isYT;1%PMq*ntl_6kmvV}5gc#zYp<76A)UI&(3r~jy{z%^e!Gj(jfPiT8>mG| zQky|UPrn`RuL5Z^29W8&1wDnqXW7k1P01(AHmhQve+*0~&P}~=JLBqPJLow|JpkvK zmi9aW@2$(oZCpiJyMCY`sB~x~;Hl)w0wHHM1HpsuzX~LDkT(_YWU?Ns^kS2`{(1 zMriiPboPkZ{7xQAM>2n^aE3nKB;qTK#kzfX@l z1IO_&1bJvJYqZ*3j|P{eD)5C=Vu8YSLpkaKP`y@~td&UB*G5gOq;0Fuxd!K%nC5zn z|D@Ztae@_6`F0@N&{rc*?b>SlL2tBp+*^1A^ix`wE$xmXZ-;9FI#6491X$M#ock^D zJ$xAbNw|v;&C*BEiaik0|C&=7f=uu+byjH@fN8&1D`AZz_EqjW;{XD!)Q*Ve0~r&G z*hpawqJzd}7AIeOi%uiSKq8Du;u&+VrlsTN&#g>X9^lgGpVu_c-`0Zu)~fkWk^6rf z#(xt4N#y^yr^SWftWV)==HiR^}X_YM%l^Ei|`Q1+o zywL_U3;of0eRrlOexnFx-GTdj7!KD*Z_^Esv}jov0n43nN~vXpv7xzXbGAV3NoqJ` z^`i;%N6SHLtr8oiZs$3=(yGk&^#rYZ?hQ$wXAM&SGE67Iu_}(dglqmhbdZYRisoTM zto4gxs3Z)wXTK@{(iF>De`OU$e`v5mBm<1jMbbvdK3L~g^4NoP-Ue5FWvGYSdzTkR zl4lI*cZ-4Yswrc^fd&zeR;&(Jb8E>fF!2~DUMAWi5j;%u$X%?Xy^&TaO`6{zXUIs0 zv3&6Zc9}*@_tuK9Bt@;)W8(d7sf@!xQy3f}G)PFvNJSDB=zwOw)L(K5B%FvJ;Uv#r z3K{qvgZHlaXHnPC*6hinQ$@lbCtXtKOOR{PIt4c-sAe%0i^Ye6sfI*NKKpxTA$7KO zolf}%;%*-r{Eo?E9#mvmmq82kVGg?fmZ)SF9 zb|QBE*o%%nR~;P{RVTAD^L?L3cXwf?aCKJlAY=|u+t1eDts0v{HK}l-qr=7)w*T%l z_LYgcOXqV>OZ{I(?f?FQ75V?Uw*8;f^B-lM`KQkAKXcDYwN<-MnX&GWJI^ddFoly4 zc!)!77OPxFe1j~sY?idHlXX_;+MhH|W$!>fv_WH$mo;%ee}2^t6``arFkWBL13ZLx zcs#b?JaQ{o2zjb@rNZ`l54#@pyw6=H9v^=Bt${m0@}M*jV~9Z~ps*{W$QTzvsK?s% zs``A-SpI&nH`2jd^Qkzi0v)v3Fgw{wvU3D#AnpLat9@IMN-r!AF&(ElE^;L0qyAn6 zi!Yrf22w-t)}&8l`?#{7e#!B%bUd5N&fgRNJx=QI+P1_abNU+i+ z!=Qe0mUghX3bUo;QhSCqRE_ZQi;|pDP+cWfJaxUoR2{n|el!t3dG76y2=8+S80AS{ zfn~``(E!WWV(fyNdM{f>1uofF4hT`c4S|-|%~A=~P$h72g&3l)_stq?cz*bS*2oy?&4@@C03(pXTj`ruwm*qp}_lr3zJTJma;#1<*<22N>|() z&_=So-0Xpm61_t$IQ>On7}~IP2L9JT(~6%!Pn_$d?{?JKLUO&(H?Ti`s$a2hC{DrY ztu+mT!DPM&VB`VPQO=H{FYV4k_z8T+9XSm(Pi*V3%J`$e1iMyznkmaC@EV5e+g=u8 z|CUAJZT`6rD*rnM$5icW$Mfjn?Gwu4`Tk>W@0|A7y@5s@P)wtNwVnPFA}Ni3hNMTO z#@k<=55{n0CkMVm$LV4(!B}qvKSz+2mK-5yPR$2F=X@G3mwkR4oo zr?1pAEte=A@>?%Oy+axV=!KA?z1sMosX4-jBiTo6(wqnqghpg>Kl!y*GA@5^m(y+Fq ztW|0WohpGaAP{K-dqmBK;8Mt?bEzNFuG|OzKD;<2M)_z@_dhrD@N8to%Fl2=`akBM zV*fv{$NxwE`S0PrQ3J*&aX;-tAnj!|1r5@C51FZo7=?r|4*oaEHv)uh34bsp{CEbC z1arcKOi#Y{LWGv>x|UX%M@l7Lxf>P|0GhC(s;NSquZ*v0y|L27Id#hCo%*XCsg zLjW0}Lc*rctb$DxP$M*tKNB%>@vC?nn~Lcc?G0Gfk-*xcL6wg0bO@2Ou_ zPU6IFM(V_F`SN^(@CGqo(Y)ucgd@B-{l(!Ece=h1(u;82m!|wuj2VLG1^lA#NAqCz zC&GDTy2lIK+C*P1p4+vY9DIL&|B}tbC`io+K8dSx!o~K0cITnTrw6??fUMUi5ALzt zbL}B2`ILtG=3Lm%km#>#waqYp+Fc&5PaWFLens>s&vsuBpni>a=P|x{nJF9nk@9P| z{q32-e-Zq#@(UPCwv=XCYgV|;!U*J5sDX>Gy8FdWYZl*fW|HNIDJoa_n^Ay3f<$9c z`?q}rEQ$q6D=#O|L^`>bP3WItr3^?l273wf6>HS>@MOgDBJ%b5Bso*-Hq=&tvQ=HH zNLA5*S&mHOVrFxXR6$)N=O2E64y`g%CT`+hPMQq4b3MfNNN$9T9>vv!Y_nEie5lEY z)!DI@wP`w#ciU{|*SI`q)VJ|b&yiXccD_|# zHuh>W;?GM(swjbBl88tg-lvSIJgD^LV!`)}!-$0y2+jnrX$yZ^a!=J}?yOb@#QqeL z##uE>JZa7F(R`0UbfR2jxxAT!P4uDF5RLL^5t+KahJ3Wn{uNaTBtaNI`0M`+HPFHT zaTThCkt5S7D=x-6Z*~1;h92A0xk>Age03$&QmIvL0a6$$p#BVsCBwKDID$Iy6>mJ{9bZ-}g>+$flL>`4GO4jauu)rl zsi&5cJc%)Nh#He+2vTDOTC?vj*%X9;drG`>i5mXW^*SUzfrJYy36mA5LV1o@JaLDk zJz%9-uaBTX4@+B0t9@@pVJd9`)*+~a1q;!>kd)Ks7CKbGCON^iGL17z_Iz-(u|%M7 z6Gn=#dpcLT)!vUJ;j~8QJ0!+C6g=CcFD*!W$W+rMw)30m-hu^6*K%gN*)}wQmsg++ z{X4xB3y+q~IDA(tShJ5@uHzEnPKuH@DDK3xd>&+_R_|~gGAA{ES>z&LG?1R7LVwYM z;x$@oMY=dq-^QXQEhNm>7Tn0VY)UU}mVnMgnIv_11K~LKT@u{eEY$&ph)HQ@%wb@yY|R>7o~0UFWP1I7CvPM$ z&I9&q%Gc$7{i|OT{Cxpmo@E2&z?2Lk#5)4hNSzvQ)>Wbj3>+73T$I)G>SxdE!FE^% z7{0D31X8>srlhrCr_?AQ{jrmyNNCY0)KnJIu#X_tL)+}dMB^wQvR&%CxKXBJ;>gmn zXTqAo4BEp=HlogFXKbxp31D%R}{64O$mUN=ua%cCy1>r zib}XHlIi)X42Y}Q8YAt5z9#hOcQ3UJEX)}Vk#QI-W_$tb8cO3>LCbPxKIel?sCt?= zHJymBKg~#Aq|2x$<1co!W-RV;o|%qeA5_|tFOl;2Yv zUz!|MI5tG8GNH__1WPx~m&A{UmBpBc_zXRQB`s;9>bz#ySYa(w&*wB8t_k|<;P0|KbEm(F8on9D*#bq`?G{d-QxGc(=j~O zR7u=3L}a>pMcQgjLusoYDBWW>{dR$_BxiPs>@n5o0mjC%?3PC0)GoSG75FlzAfRqC z15(@1j=M+)LW-{s9bMN(!xnm>R#uX3MF}2Tsy7E-^=dfoL$)p+m*tTjOQURWo6Rwh z@Re4%Sl7vZz?zvSNDAA<1B1PebF%~t^Ww$V0D`^{EOR{_E-~+#I`&gbWfd62ZlS6>kYYL!L0|ymzD_i<}(_LPUmG&oe0-%iP0%Bkk{_;QR&vgnbxA3 zE7>wcCv&e-(n#4e#3YGI=b29L@JG?~$VFY8f0*`%C7+436iytScmFUFdF5CO?6aUc zh{Se%mlZrd|1g?sUT2dd6}w&rHUD_d#WNi?qFXQqV>iJ3k!Sg1z{m%O_PW`}4`R`P zw8|9CneRt&-=`a2RiD6)bxWjo^X_G%VRLSxb!2TA&*+p`DjhMr)DwG-oyJ&N(q3m` z71j2G)JYA#s7})Ssm#a+MVCK@%fdIGpxg4WM4`2S+uC&QnXRhPiy^F9F`gqoot|Yd zS#k+a*2d(-l)r8bu{kmAmtwR}PmR`-f<4o-dD%^Fn47j)DvOh<23dc@=ZZH?oQTQ6?+nI{mki=`^19tA4PlDxn{iGB|iPycxMBOQZnJB)=mMCzMo7o@|WYXtA|QvBKyp4WqLy>byB zm`#ZO47g9}^BiyM{=Ky``YWjOn=jK7+WVT3Fqcr?i0FQoi8p5G8a2De`Vr-l>&5Yl zyd+F^vJ)@q?p1|MKb%qsmMN^;Ftvv!sW&CKAA_qT3Oxnae(9m^3ENIj5hAiOyDOJs z1*4t>?^-UCodWPM&TQ;k>0!(@d5D`7y>Mt4Tg$1c7|?1bAr+LLl^Eovgt#KP&$?nw z_Q!ZoTH7a>P^>0~dD8&B+HGn>tgGoFxx9V<#IChXyXy1N8_%`*Zm#x^tCfSRQmw(L zeer8 zM-I;d8vG;R92mlZ0W0?1r3ivKhbK9{#?tC0$2%d`59Lz!D{hF70`}+2!IL z+f0DFhR8;t<%aQ6xBSDaT>GOBje0al#(U)THnl17G;ob48f3&2qbA}`Mfp5O+%TP6 z>O-TIJFegJu`iQ8!o@H37$GM*f};A`^wiYqLx0oQ+StC9sA&ssSMb%-z5(H=HN-k5 zkGQ!k%zT>1lB0-C?idIP)Usb{U&OoJcMkXvQT;7fiXh_{ttOZMBJ&hYPp$3II3cX6Z4rJipg?(qeY}_pAzdxaD z9V*-Si>@`jcrA=Xtw3QZb1l3(BT&xb%RiC7f*#trB@7Sw}|N}*ObA;+j8+Ctf?{l{i<(#@nyL;weL2g0{q^|WqSm<3$j1cWtzV^&jUahZ9QG!KUc;e8G1 zIe?-Q_3hz)LElUiOHFwFKCfyyVg<8};YO>F`iuBASQVKmv%J6%qA^?j8=6PD?;y=R zd~g>cyM>gg&~&2JCalG&wIdt&uyCY)ub*hh`g9$NzB$G1^z-R*cZC78s&vF#1nkXm zyg`=!n1K$>tp-Ea0Qw)WJC#TLbCq8P(&q~FxydzYs5W-zduF#a!$8Dk``cTBY>CBR zo*CRFDh>9ma*@(D77MFeW_&CM>eTd`s8#<2ke^-T@Z1SyJ-=0~j~jxCIV^FiUsJ(d|^rvxxMf+zh_<15q`et z%)gA7UX7@u#Ev?4*zBy7D^ThKHJ#YB_Hj-2PLJa3w?=Pdb$%>vOFdy$#nHE@*?n(l z-tl&VyGYb#Yxt2{uboviZD7}sF^D|6Y_!e_sj)RVEo-d6VY^9=E=0$aJTd9lw?k{E zwsFWF_5!Vxl+cH{&ZoJGa`pr3*3~-t1pe_}RJTDok=EyB6@(7fkmCs5jcI#HmI&IsBxwP%rPeKzbSS zCCaV&r8c*?wEFRyn46uEhc7O-;I<(wOCZWZgwa6W6Uoeysg)XFio>Xv#~ znLDH%VRHSBtDuOfqAx0kph7H)X9tul+u9$MU_DalmB@`K+L18i#Z~aNu9Q~?zIDDe z$6%`)ZYsEsEtc-%wC!jPPCL(?QjCWFctX$5T78pxw7N* zS(@|)$Zzm;=&P-;en8rz{+T^@Fe zQ$b~#d}^L-pme0|kk`6ynRC`aM_hCMGhg3<*=mKLHq9i^slAuTp;LB!;I!ho3rb+_ z^j)%fBk}%l)P*GA`;%b8W!6&ULgMA5 zxe53uLOwlua4zA+!lw#iX1xiU-~J6h7+DXwf{@AFpp*q=Sm<^0!(BoGQ?C1u_5b&^&r(_bwCcxxm&1ZJMW#a+8Su4?WTqRLL5(l!|29h%r}m1xC57wu?J~vw3#NjE5wf$e z#7}tx{_v7&I(TCgX&7FKEkm$Tcw;~fxxHG*xx}bXS0kv0kR>XSZdP$kMRnsW>~Zq- zWv_Zu;GGe^f!>nlH|nVOEBzvm6#HGBi%Ni@h4_MO6?cd1P)_xY4CWB zPSaW2#Oj&_^m>gJJ;|K54qLJdiCWwA87Df`c$?mhXxA!wFfut=pJqyt3Ld<5TK!kk za`@VK)qE}S(HV4k?n+%lbsZw%G8-ILbh&(DKE^>6VWr(j-&@7jgiimLbJD4#uIWBW zGYN-w?7ha7rgn@_k5z%+CqlMRky560lzcOcJX3D!i1n0tbiE2Fq9*#%cznVG?oh*fVkgc~`eVxg~lj)M3ZVKs5Dq)fl zI8Bvm5>e%jSBfmMRK)rF#B-6?=Chs|7%Ev|fj#sM=;7`lx_a<(@s~Bqh%P`C!Frfw z>|vF0y?ED`StfIVO4mQC{m!}bl$6C6(&dtw5-Qm@N^rH1s8^JXNv2LrAOcz} z*2$Xkt)sa3D3@KBFB%(^kV^6drn!ME6g=T_flSBY?Jsdbo5z5J!t?W$lq)Z_$US1_ zOV-A%NZU{UND+9joA^)S>sR?3keQc{x{y9M-5!nPVjr{K?6H`2t9;m`-{8-03~gtU zlg(nb2Oq}sLTb^FGoxi86;;(KcaV0F6{0iPS&k`p!V(-?IFW=&2TO^IH%sVwP9_oL%sjo!HBhm05yKL`N;mS3A6uxFzEl~ z!4PvYb#(oNhWv-b{IguGp|j}vKAEx41WeHQwj?3pA8dlnJ{tcMjI4I``_DST@1RKD zK&U9*u~<#?QQKq+N2TTPa(1WlrCMX^T1O+4Wk57LgVU}=8D6v8=?}}c0o!yJ`}iiu z=90sWhXW?s*lHM`P47?NtP9N#=Zn_c1$l-JNCVPyH)Fo4vPWAEbRE}RJp1tJ%a&`| zj>;YPbp=N@xNgdgOOsvg$2XhTuN&ioL_0D4yD_S-;TkVZ9T*b3XJfxL;{6J`EPd4Gkh=2ieTJfWm+Sb@oAS{g5GZ*R$9jkPsMygD zPX9O=M7k#BSlAv4JlpKw-5l5zsJlk%piS*!Xn2uldS*Bj-}wECrvE`d{4PH5(N>Ei zfI+la2P48u5&|n7qOcIe*qZW@ztIT_vV==Ph@IAU`$vB*VFbz#Ba?cc)#2(IVFJrd6O}tW$ zwM7E>T1t_%z-b9@7atuY&GbP@imDbU`Oc=SzQB~Ezeke`E5(1u=tu^_j6A&U(ja8HA4i*hXevsC9VGSx)2juI4 z3wJ_>J~n1*ULriU{7D7V(1lD-D1M0gK^7BPjSED@%D-~@TD$i%5+w_H<@7@WRqk@}vw zAqmouq`k+?5gh(3@g{nAmdy5D{d>r@XT!^sVe*uY>(2%_>eEyzu5pW5I4%x~I zXb@O<0|AZ*-NE_`!@~2p{Qj|0Y&-evW*K`cXkkZaUK07-ujyiUE~GD{C~~;A1sN@J z^e!DJZe~#hgrr7P;uPMT_h@>*v@J+z078*LQW>l(GTJSeWJA*VkX9;|{_M~-tc8*P$78l@F8;&Rn|_A-T1-QDC| z<@_IIQ&;7j6l9s-D^kTJwW;>_XhuS%)?wh(Agx_kE{n9kbrVK=T^EV9TSQ9v;@-{r zheA0!PGACBVNbF5l_rlq5EiAo>Z|v*IDH20N^TiqbXd7-s;O zpB7m6q)lqj{c#VQThgB{W{2QauD>d-voLbbu}@92c{mt6O!WfR-@I4stgSCkxj7qN z3>Lexdvmh`GLR6P@6OM0$yiPK(=p@Ft+_?x(D~&Z@>5L$GYhEmmvOHm&}&iR$qM-)ja87qbCCZtzt|5*Oa1ITdXkCrhFk0+DD}Q!)*zH@%A}BSMX=&rwL0Ir>CoYGxMzq z^z7s!6c0E4yTwePBR=rnFshhfp4rlOXE@rC>FB%fpR_Kivq3__P1vhN+hHtQ*k4Ga zmnf1$1PB61S28>{ykJgz=7QOg3iml7=cY^gv2)G0&Roi0d~5QFxUhQ&UJG%&9Vjor z$hw1M=pPA8xI;EQF}qLd9a7qpyHPb`P{5G+HhoJe!_Eg2yBF@Xu>qod8d^-gV-gsCWb;Y#?3fd2r9=5Do zL|;9O(g7^TBGN>nqw4K+>geNRVf&X&p%G_nxz(M(-a(9QMLQ&)1MfZ?nZH!`P|2 zWc54(kiWSA?wAYsq&~bX^H`^uMLet)d<5G^X9*UuFBF+BwZiN*L$6kvEvd+}WjMb1 z)T}u@108lq9Rrjqf0jbC03Uybr+tqhQR3?3W-(Euz6uLR3*hMmool*&aG_5c?(^=z zrwwfxksg}1(WluZU-f>23B2v3IAlMd`*LuTSY+-4rs=^6s2w#rGaB?(!X|3OriJV@ zpXaKO0zSfxJ(fmAT}m5`b+&B#Xbtc?-$=Ezf%M)WrTBkmo=8)r0j=2ofPNtBjA85L zGwMiZ;12+3shBB7Q@40WY_QV=YnfEfQiVO!IP45%6Lv`!&VQj`+^g66bys>J;vF~u zw=`9{-oa><`XP*h9Sy&AATGc10`({BH5sl>q?dXsP1z1=zzKxU%n!P5A@Owz$eFyM8RwSfX?`dlCN*bKuc$sj>1pPLV8eF14C#myTyhhMwC+Z z5{#4Jr-!y2Yui&Y)^F#dva$WpT##=1*-cKCTBZQ>4=YeJ@jqk;J&)b&B!|(+lkT?T zZ$IpqkQuqgByJ}&+ek9=<4^+a_P~Q^vj_x?a0Di(cDp!n!rgpE%I>tE=u4y0HAE$n zuhEjP{d7XywK1}*Ig5%`WqxplC*65QCMnY;@Bw52puw;$aNY+43b$9* zjLC*;;@KG2DzzZPMgt8r^(Q!KC1H@3Ki;HA3-Y0W!u`*ysE{rnK?y@ns=l4P;asFa;_9WDrlqJfa0m|)YO?_t zCU2#(n-Cc$TFwNMu_4Ux`XNVV;V~r*zBY+5xdErBE)b!L=XtzC zlS3nrEhFBJV;mP{UF4{`73`dZ{j#`zY39;OeoTnpS`;&aw9yyRDk0w|d6mDlS@2Kp z^q`^{Of9JLU~hLA^~U_ER+f=TT0R;(O}DtdsBMWlJV!*XwRj0+a8-wl$>e;V&))i9w2!eG+`lu+SHuAuMR<{Q^3&@x? z#P0?1FjbzKC;dp(8Sru}%PX2ofCKrPHe#o-O4KmxBG zoG|w&78IZ_96XsQ9dj+F<^pziLWjzmR`5_)bT$9)C%+cxQ1fIJ#`GCjSaW21yc}cJ*2tP?bK1O0w<@b!klg@Bdv4g!uFtCwhfNBOoqBcp&sjfvA%d+G z4@Dv(z9RQEaUmQM4aY9=KIU-%&(Z-dU{HN21hMP+aGPuS%bsIfRxYM!mfa zt0Ml+Mvwo@+6?B){n|{t zWWXk^f-TD+gdt+{T4$$8*D{mTxVfRSoI|T8c6pNcj+AU^X)FTyBYoO4V%7DKXTjCu zsmCn(OE7iQwDKD~{{5^EyZbG%EzkIGXZP;hKs8|XC{;ri<|dm`3ZbM)j=K1UauTIR z5@jyUr?S{79_30Dokm|M{Dw7u3+Mi@K9gF15OcqkQx%VXlkJA!7O(D3mp1Nu#E9u9 zSZR~47jmg45=n5+%#fuUiZj729xcbM?fu{E#{+K{_fL^Nr{O66r}EmrcEGT-Gc$Gi z2R+IlYiMVuZei(SXX>e{^2x{ik20Iuq&k{9`gO~_{kq`}$` zsFd~}H+{7TZYGf+zSy>){KUpG)w$Va7JJ1W(D-7C{jjSlGu(pePscA0 zxivKKrRYk}U%zO8k(9mbQutb5^9#`y@TR`d^l4c_5&1+DN9v1fDw?p?l3D+skroN}`^(;Hc!0Pk{4y zOPN+#oZ2oh!ca$Z%0^fhk4V{>9b6;ojQj6gi7j;#clSc0bOMv?cq@CLUSTeF1}qGv zUSECipH2wXK2S=ysE`Dklc%&SP1B4uuDYzWdg^x=ClhY2Ec9Bb@=rUx1oR{FspfRG z6r1R+3egqTnQuG93gQ^P)a6Q=imWd1c8pTK(q+0D*NVFzf-w9jsWqefu8#N=r3Z&~ z*X&FU(iR4tvrlxsfA<#tlCL&2{w;(d&oEEikK5b&^Ya#Pnl1<~tbx-|#<&u7Pd++^ ze8KDL>vFMQyR9-be*qRUy-udj4q{?i?${MLihD6A=6tRTxy2j)VG{Y=rFB z)U8+_L|Uq`SeZq7u6}fVS>k*PO7I0`N!_h=nG@a1{Ehw#|CcW*bh^eR(Md#t0A>!OGC5ZaWdS2xCGDmQ9%kBfKV{ei_cC?xgff)FnRq+$TvQlue%k7%Io#!lC? z>!w7WK6$1G?F-L}e!Va!NIiun|o8@+n2D zw-toE!DZfo??oVANT{c0InF&2y=F3;MUh`j%5 z-@;sI+f!FqH=pc31$XOJJqYx7wcGtw>`L~JIl84NyJ8}eK9$+EWqwS&-Z1mYG5nHa z4DXJw#v-GZ+Ag=viblDR@oJ{y$3pI>N+%wtPw*W3XOH}zD?8ywk%#|TJ2j}ks%JIv zbycd*yDl+7zqIsVjYtp4bFopmOKY?8t%M29sgeQzW&*ZL<%|RE-FT0hb0HljJGG6v z)N2y*gr~fvGqmV;O>D;6mp+>!2rzwb2ehlscrbQAyZk6KU z8*fj*ZHB8&w)|sW-UNLJ0{&5iUKT^|E|HAa}0onyr-~F9Og{n=AC+b@LZZKt&O0_6iBEy+kYM8{e2w}v+ zYPcL2%4jNa^P<^jk|tbgauY?YZ-2&&&i+?{am>8{b^X}mdmcYguuI+2G(VENCz*0K zK{6j-v`;O$vW7;AR17)N3yItX{*|yCch!wBfi&9+rsSXBkX1M>cH59PaHg4c4rpv} zIuA~ zzrw3&Q=`}h^8z5=0!OZ~yo12EDd8VJ#Iv@KyOZDcnInGlW){&`F5-D-p@s8NWH7j` znQg8wUpA-fh8|L4vbwM)M*Ln*oLWjHSiChmG5b)p-?X-G%SggVH%OpJS1mi7^{)sbdQ2GWC9|o*zMpaGybNDR*2rA zx!CzSfPWy_k_ze;4!Os#93wv*Xf*4kPP-^a1a z&e*LiiBTtjOjyP*CYX8f(7u+IX!Jwz#|kOdLSWF*+q%F-2Qnxq_BP+y`bIvAT!(CN zxtnpYaPY`BJpo_+o({&cyt|z*+$Z^*%|8`LbNOEsh6<2HwrZU$0w;sFq#o&d525+x zuOI@4V6wkIlJurPcgb9l^{PX6NnNo87DH!KJaYGPKzB)A(FfWm5{(!4CwWC1sE_stXI` z8JV?@2>M;(iZW0D?KNbp`r9PRYxLITw@IjNBJ^ux!AHu0fKND_eaCx-#q~4M$?rw1 zz$<;ofC;`Vyu2*c(ofY2aLu&ML0ljoHagif08V@3aMGR}JcV*c_0?#|phPPWADUw;+f|RQRnup`GNgLveg^Y6rvo zD>fg>Rr~g&8KIL>6I2`fVo2;)_l`N64br}B!^RrWXzBwpoO%u z^UrWmgz4vSIF1U|g(Q;Bz6oa%Ej1g2_~$CJZk61WU`mgeg_>k5bHZ*UkT{BM^pYYm zuYI2-7*C#HBb?p7&GE)$=m3v23>~5?lJc{aOAk$!v4#zTGYZ+OWOrG&nK!On@yA_! zcI|ZMF-wvgT@3t%?gRQs@B`m^TaC}qmq5J1e6VAo((EVQ&6AI5%>`Y10oDt)mV9Ut z=0?@Xby&V(v?}%MTzKz^vnerT6xZ+wwn{YI9BPdrEYrn-c0@WljZ=H^pjqWP@;lOD zMCJZZf_RMjAocnKvyFZS@A_}=9J>Nlfn>!>q5K88q>Vu-D+gwJ7}K4l>>x3n%kOfy zlSIL+%4{a@O2GR@sWm^+-+5kx3Ukr8=aD0?<<2er6h(E7jRK0RXBrRHjgbL7Y z&{s`46<@9JzSAPY1fqZK9{2%S0E7AsClEbAXiAh(!vBrE*9=AvO86UxL=Do01fz%p z+SjH|m<_sKKRCO%KR8-sYKYBJbRvuhb}0sM4N?wJ2s}R>icN{_3+{ zpqn~7sY4z}SJ9j??93rrJsr8hzH>fr)fKsNKFhha0J^p0@FBct4T@Zf@mHqk-W5rN z!UQwtHs!^97%oD0_--Rq;3|um_oiEvI{nP0nrBJ)MlY+(xvDn-@RSm*NltZ%Y1q4Q z5K@#Coho`kjXruZ(QoKcHNnZs?Z`43KnjRErQ~2988!B4`2yTeFj%U@^@`hOKL!cT zhbaOuS~-{P^&1y9uO8^1pJD{rsFH*reJukwB+uv zy^(vlskVJb<^AoiO*N^wk||-X1T(k<8|Pv45Zb@AG~&@iu6N`h>48`8H>i70J&Uf` z{#fC2h?b?zC!g8j0T!)CIbY4ba@yKrO2t5TtY^9twozg@ZHJyYfKDJV#9f?MC;9#g zMtNV)kbQ@&mMM|MQ9^DMJu8$_AOpykL?pCqvg|O&ak3cpCu8HD?Z+c|NbCKO@-s$> zSKmp^#FD=MIw=|4FL{>ZfQky4kx%KwE58SN7&Lw`) zQr2+0u@0FIj(r{4&r5yjm=2YV^qfQ-Ok0xso!F97jparO}^|t3E)3PAtd61LsO|iIYOZwGlfmy)d*Lw%bm8xZQi*#<1JA z7}+MklKY!!eTWzThYRA~3>{YSRi<=${u6;u#UEC^23nC7tcX0{Vd?86uXK6{t_;I?mXjU)d(M@5m1-ffX@5)ERfU&^s2d-2n~?UOMQLDhZi?{5#8gCjJ5S zPl{_0oQL7}sZE_F`JYl;mVY_d^IuZj|184|XgoRN4`95TxvLqU=Qfg)E0k#Jj6ROi+xn0 zv$7a*uDoe!q35vF$?}_5@1A+PBK>%(C`2uBc`V?#-pgq)jJ#53Vg$>WtCO{!?-OlW zn3|Tu4lBlQ*^dg7uW_RKXZ*yhSAx6*lN((C9cidkZO*w~bJq+4AS@k|1)J^^njMod zdrt<7?sdN5%W656EE70$6%neA;c+I3BMh{LT?lX8-424)@p5w$E6yd4$FD;nXk~V- zD~b>^oRFYyVL|Wqk55#T!ITNiVlmpCGr*LlXf^G~96b&(?&K{k?#tMWx3=qUfRTKS zN~({LBrUwfb6NuCN@v{6V0e|IZ*;uINohF{c(p{*;Y~jKj*)rv=-=m=UrSEal4KD)|#56Z* z_g1=6GGVf4*)-_jW^Md0%HBCfmoVJ&-EG_M-L`Gpwr$(CZQIsv+qP|+x6jPnoO36+ zGdand)c1c?>RYv*_54=p$wJ7a1LpR_zIWE#ttPEcXd~AR7$i??#G1(Xnw9Qf?P-j+ zge=*3W9j{R>pBXJ40~+7iTT!3a#DJJc4j40ihbTk!1T3s< z4g;d{a!2M(DxFy602|Gryf$$iG6m~Zs`<{tNns8nHQsgGWJ(_<1(6Di*BWIQ+9_z0 zMiC8OT_F|5fiPvv(xGH3&NHX9j}qIVmOA(v9FSM6 zR?eK#vxsQK5B!A8dMFP2h_hTgZKg(cdUZXvMZPbGv)5mpp~#PmrLO)Eo~hR9ZOW*w z^wu&nDbeyAfi?K7&`U0P{BI~+4nAVtM^7r!%Hm*^7W%3>tZWQC^n4v)uCYWU2j1b` zWBzmAiQ!{+Lb?WaT=c88dIR&LeO_Z?SRfpU0)b0_mo5r+H$O6c{3M%Ai(E!W3y>ND zo|Wl#hO{+>l&{kJ6yDUxJQ<@lrKRY}kjXWpTuH5OCDEFrEMddAm-rXePQBHq1qrAq z9pz|nH2DZ#f;-sZ(*p?Rq)67fevY<8o5B53e@`VeoO6zI7?v2gPvE;IC zm+9P6-*a?`foiT&pfkee2m+}C2L3#+VqgEI4O=6?!A^|>VvkrRc7Lt{rUF`#rN@KaXc zy9u&gnxIwuki`pE@B|-jBFuCb$*`5Cx=$<#Sn(69+)44QVy+KSMZ7Y*%eLZxCnW z->s_xYG$Yzc@omezAH8l1kI*(1SHFX`udb%OQ8ejg1cc%^QdYk32ph8BnP=17q5;I zMGJQ(5|w`2>c|`D{v&8@(9imbgcJ+a(8L->nT~0;7hNF@jcyJaukAQ2S*{Y%{qkulC zUKG3dyHZ9Kwk!xUfM{r5;%egDFs$l_n}8K+0qN4irEnk@nX^Iuz7WgMGL^Fz;R^FX zGd_llqPMhoT67ttE)!~eJJ{8pie4|o$xu&gx?C}18Trl`(1*FjNWD<&Izwbsyku&W zI*~{skE+8rd|sqD*E!%tZGjfP*1wu$DJY|;`D?@$U?4;*YL10v^(Jt0=qXG(#jn4i z7ZA)Z^XIluNa{prCQz=i=+&f_j$lqNpMq1gBJ^YYIT$AZRcF?mz9leZoxcxl zB_o29tnPr(a9JXnB_>eiD+9GQL(Jzb6s;meJ7G~qLLv+Vgc$XNXQVDb0XNKpv><`6 zG&)l6^wj8hEf~H6+!^JU^%#woXAZ+v-tomDmYrWHFg_}E{wP-9uNKH*veZwoO=aF~ zGFPIZm}nFwL98F}`A3J^$-?WSS>}>3t)Q2Ryh;r6|Ne9fq^^^OjLK5Y3;ao^yy3{` z1qaEL$q68BL&(hK4X&KgoA7tF^R@$EWtxlC7@Ib{0F%_+N)|TF7ta=!qlRFvCXfs% z%7`0Hjo?!)-xRoE99>^k?+fz~<_$T4Zox?ty$w87U!erg;t#tWm}`Uzo8<|c<)+dI z-WuPQixpJH^H=qTo;ruvzg5D4Ww$?9*{Mwz-Zr`On=<%dK;6$<4|_J%F)>vd4Qm0} zR7;(06gp)ma6-&nM4K(osUT?5MqG!L#HN~{{cJR-`S^kQ4@G;`8$V+It7x%s{!faQ z{lB4TWo?XA_1*bxY+dyK7i2|M(+O(`<9k@c@@VOuqza$do@SS+0Y}t@#>I$KCd!x; zvIW@-O6HFzb@h=nQFUP?(gLbR9+5N@Q!uKaxP+i)D-&@4kPMx)898LopxA!%i zP2ErNwIyibH74k09|8iFYfPJ$c;B<@CMt;em50?cLp67A9`5xdlpyCQjzoxybl)9; z*Wgd!W#rJJo28IA(IRl*BI3eG(sfZnQG|Ob>O#U4G>NJ)Uf^s+s8Yy2EOp7d;@n^6 z?LuhbvZ3XCuw=1Z#1%L01u`O0ru+JTg0Z1n<7J50@>~4em`jEbu1exDR?ehk5t@-O zmG;c2N?ZPE9&#A0`>gb8C^Stk~OJ^FPAg^fTu?RvY}q5r0gh?}#)D+;^(U+(|~ z`CCzA$j6kjpeN99v-HQn(qxAGr6}%01vLoT%?#QFw6G-XX|G*uRjS1Y)e%m>tzv?3 z_W^7b2@t;6jPs}qM3&STvejI|@?G_dbQ6~1GQfwKF~8EzuVsV_CA_js6Yb3Vgpg!q zePfWR7V7CS#m5RB|FwrTc^RY)CxIJ>6F^FE>GZ|9rcEF)i!eOMYZLb278q>@CF`#= zgh<#63=<_A!_1^A9Y`p|D%!d~W2)o7dq>LKy_J*yV)sOkx~7J>Y>DqEb;F}#X6crx z0!HK}`O!1(jtZwr&lHEv1(3?gmQFL-M4HiSkBAYuRt81}l!y?!=t!T6^3BDew9;EK z-b;Y-7|mgWVK@uJNEkp^O|PJlerVrmc`+1Pb0WZ&T%v95iPbGK*$pt5SE&qnuT$;} zyGHAtP+5pEc>CNjXzyfUd?*e~U)f*Wd&0yqdU|QiMKfe&p>nfe8PM(;qICBFSv`b@ zg}W&BnK4ptJEB-`Ndy-d8b}YQrN+{RjYHnEd=}TFw{XOWfd;fCsH&!|9|>wk-LM!5 zw&U+CwNUJ%Q*Ru)dgANBHq4i3`lQ>cSp5=F?xoeU0-sdcJ{n6dQO&j zcY!c`2f?7HCNjOR-v)+Cm|D>aBIpef#=|)2oPu7ZNSCX7%MDlSgNWV~=J82J(#%; z?*BUrF}_$*9R8<*eXt5N;N`b{xmSuZTISR}g;wYpVo|h_TAgW5dbCQwq=}B#qr+
9(D3_o9ZxzWG zsPr?^N~7UZv(uvjcCIgrg|CVfW4bdID=?ZaQHoRY4vtH^7talK^)&}3?ec=*Y_dBw zgAdojiga_e(tIS`oAQEQs@SL?wKp*Z0Ng)0tTSq;QFCIezd+wSn;}Nc=_Q3D~F&gM%|STsw8{+sDzPq2`wqI)KRcikijE(um8Iogi_ z)+~RnOP0AE|KOG)Kq#pc0Zj6png$X45P46Mmi~Q@v}CIwA3x@5AOIR0IDA83yDRgr zp|~=I)gHp`V8(Eg5m*Z79Cg7p6-Jf$E;?b;-1`S$sR??q5X7829<97oSt`HF+PiF5 z$Ba=IEl{smHU{uw%+TYf>^9`rNquDjdp!)TMbm6Z3xYf6yjcqt6RL41H73B%kJA?TgvU zd~EA*tjn*C3(FBK(zxK&ti!aVd5PNThTFhi3M=Iyy~v_M!;NF&hquxsrWL z$fwvIE8_m=MQ&y*DVZjL>aY}b>onhMS+2!HTsE(qhwq=a$hPQ-16RgaJq+9~zPNdR z4V@WJ#$SOBTfF8isV&d)o?KL+3|Lv?vW;De3^uUJN@&U)?$9MhyT=~b(hCNa3>rg} z<^-nbrIm_`Qn~94H-G{GzxMqp2n_>L3dCASFo z`fnxga_xpx*kwuB#zMMNdQPgC{k#zc8(I{Bz^NDm(fq>OvVV_7xWAuE0RyOy;E5}` z1k{ZKUW+t$E|ml4@clXck8VM7+!$+-vgbL7p>i_8Q}X+DXE_ZRR;R6Kshs1hOx+AK zYoT>1^G$$&j=lXV{lhBx0o4OGEx0@`V6craZhq}_qZ9~6%IGFbv#TURt0q|{&1?hb zbbT$eP!^OV<}f-&8+WLdy_{BH+I`%wY0Ue!R-`=oowwwc!=_fOJf@y%zr-Gps-?WX z9rFqoLuUJi&^8rmBeBMJXlqFzp+EsC_!BU3is4A3{MiVy;$~uluyrdoX-;w4wQ;co z)Yj(v^4ww+aSV<4q-|$Vb4~CBG$ijGp|CFSCQMp>;xVa<2ZALI^CjWabW{>Bd z9sz3=FA1K@q*@;RB1s|0yRxloke#mm?-B^0|*4M9clWTXHbHLR}CAPh!hycQifT^gO}c zNzbkE{^0hTn$@y191X_3M6BBg=3c!B06_rw&{~ZxgK`-JhUT>YLkPG}!)7nn`xi}v zo(O+00Ig7_YB&u_JnCW3uuFXHrQn+se~Q&Ki^(^Q6^X{lK8g?!*Yr;yX-!2!w=P1Z za{0I(UV`%4>XhCYj5M9vi)A8WAnV`Cd9~`S)W@haRk22bd=w#Lfkk5;8?tHdUVt*VKdkb-nE;v#Ai^8BFv4Y7>AoHCJSS>*M{tS%Sjvg7%ty0Np=T`xMFFDa*uhyYk>!8&w7L<7%kMS7E46Ahzrir zFMRylfeih)W#F{I4TCej<%87q)NSczPb(0PBM}MH_>*=Pq^0QB7tx`Jt=0Gz?;e?p zPx~yRmO6_41sYRSR^8iXj3V07@IbD9YB3?1>N4Nt#uBSlP4|xThjk?jfD}BIFGC{< zg?C~EXn2`nMEk#$Nkk|Z(Z&YlPBiHe!wQ4(oj*1|0J-}diyyYG4^VoyYWpfRneorG z{w0y;MJlkRlh=Mis_|xK?|NM0tTDg~q(+5um?)I|0^rLC0Wd*%;qZrt;M+u^w=vG~ z`A6u zPFx6vb|x`I=J3&TkfsDFGA9g#@$^;2s(u??jnqz*iodQ6PIQZcEE=;F)^T4qNj?ai z+(iK{cz;A}83@;tup2y_zwX7w+{PcbbX)|Qb0Dk^PXT}p;wEUePuQNXOAzqo-)W2P z7GOu{=c;8u%Ex2o4GU}7@^jp%h>;4gq0jSps;T7Ik(9fA*LJLb89V7w71 z-nxrB;wO`Wff%B2-YW~OGgx&mYNWLK#&-nbi@HsZP+MOyEdZvy*GM$^j=jx ztvyeZ?oMyn*|%?73&8*<=Kk3(TDe0UJfb68*RJnd&R zl0PfFFPyYAd6E0~8&hq7ED;v4{!Ys*p~}b_FZ)wP{{)l(P#h?YnhY_sm10)p{%(Uu z&%Z(&%*KyEN3ii{C_cL5=I(-cg`?4jrryHPA2P@o0@Ut9>I^7%#pK?B`t)VKqS)@S zc17>p!G8C4wuQW;!Q3!{@#tl<4RqMWRQJ2LV4_L&E0GwdCnmIH7msADYF!W zmFp+OfBZdgY|I9={ssk&|35*&|9x@&zcb(x{m%hcv8twB=I?+@WxiH7!FUZKp7216 zE(l*;203$A&3<&Kbuh-TvIU&2ByH#3R=mDy=X75SvWQQ^OhVE;pNL7?RIkLG)5#;9 zb8A;AQI;^+*P_Genj%MB5t;D^ONtM&x@0pFZQQyY~w62`S%6-1AjDixa$DoV)YY$ zUTSLYV-Z+)I7l)Nx==;jsuA;YcM;K^m_~;;M-JSVJY3mP69pO`@=V8ux314+MFkIy z5k|mi?=!28I^AAeXdE;l1Z)2v{5^gFTZ3uhLLD3jhKnV7y*iG zv@mG3cB8>GW<+wvggO(GDk~laLu7>)k$aFrcyZIx$*gqgwDR zyz^tSsUIGJG^P_W`(fjp9A+dCM}=M%l96Sh?a8U+;V(etw|yyDVd0n%3P_D&UN-tQ%EjdJueiDFS) zN=$ag2G1d<&=^|C*QB#p6l)ao@xuJB#8^q52=7Z)vI zgBCi4ti7&NUHan;N_}Gn23nlT233V0yUJ2Nu(kUqpWA(%V1nJHkW@-HSQ;)c_=23XgqZN5tj z^rNTn?)7+6fSt>F z??LH}Ds4U(v`~u@G=vyFvcm+C-u z{FU&H_h$kgHf!eoK$aWq0^LZ#lj)jjYG02j)YyzNu45lGt?7x!hY?pAb+xj`{ks(= zZj%@qWJRz?4#OBBBFxT+3zBk5K`xR=%@#hh*I)I}>~gno&*)w|zumXS{}(N>g$uw|g-y}f(OPi>ccJRJ|M*m;s& zu4p2D0aUNmiqa4jth;M#ea+}v7IgfZ!htj!17Tz3^F4y>0-!b$b{5UtKzmx<=<=y$ zvg_ILhH#$pu{{*vgZubLy|4_psVZMtau|dyS_zbsAoJuzaL#^n#JauqN4A&ot1x0A zR*!H4J^LMcSsxf+aBR^&;TB&TcSt5{H_!$e#|=IEl?s#$j!}@O7x)bxT1p=fgGjIM z5X%ZO_96R)15cB;#4DOIVN(6R2TQXqaM`Iwfc zt?Ul)`T&+wHAfVSIC@7`AC5SiOsa_x@(q+L;$PMSJoRqDuURnj^$SOtzeC7|1^WoO zxQ&Up-EU+bb60{}zBGem)eXGCv`CmZ96g~_{EObLSK=W6iLyys_9+T@~>})E_^oByA)N$7%>m38B#mxo(3D{fdSZ!0Q3-n)$}V z{&55ue}?=Yhe3kexzh1U?r&+bd=05gX4Ocs8wzz-Hm*h1!_!*{xu;1<8UwI(KMT3+B_Gw-k7BUaq z<6!L>AkM0Q{vp1&{M|$2ntp_Y{eAB>ZJp%bVkvQf;9190L0Y86`TWu++|Rl;GJN$W#Yign z%O>HD;@W}+s#RB%8|ctwWWx--`C}_8KHlA`V~&hDdYVI;0@Jg}BO8^hLceO;*p@n) zoP%uqY}K8$y=#$d?0M0A-Xpn*Cw7XpskK7nD!N`?G#ho}!lp~E^sbDn_;X9?CTAq2 z#3S3fpnRJ-wt5Uj+&jP=+W=eUj%*nsMhI|22$4U2|G^!TQy7%GzaN)AGLRtDCw^q0 zz^^N9K;1r~CrNL}mb9d0PmO)+bLbDzA6GH2LxAHz9B5qg4##M52pK4hyZ zYehOGaf@Qrwm~Z?;k8yxXP+YcC*X{88fkMN$R(?iLvd+l(b{ECJ0%y4{bbm4^)cVc z=777rbSYFVO~TdF|6%EpGZR@`Q(Vb~@vPpmjqn`yHV(5;S(Dbvnu$ius6nQ3 zft)_M9ZUZEdU{UDdoU zu^vY?Tp4we&DAPjHg*5O#J7(hs*%mC+czyk9`ek+5sz=(h!yX)=tG^^cb%{YKp>vP4$nj7BVWgX%dK_pi@ z9rek4jKSvfEatqW<%tx|8Oyp0MdBazyot|uS(c7S68RX7hmJd*)9yPDzX<-EmG7&b z9d(e|U|Xk=Re7@n|Dndvuf^&VExJmx4Fy9I50!_Ed@lO4bTmFdj{~4ZOB4cG!yBjhqqNB zv=(kMdEI(R<1z7AtdM9`0xJ0Q7MyEs^tMLFlWxP)CszXWIjj%cMz|+twg}_IBr8orYH>%M&;>J>64=PY5NlM#cA|*@qzk7PiF=4DRp6g z|5)}-iph)^_0hCDa>~?tw5$H0Wa>0V#3AuUHG-&zIT$1{=_KqzBNN&u>)E3sV^nTD z@rD{bfD&&b6cB`bQznyfJobG`P5N30Y1E!(GD)nS? zjxK4SvJf#;CX;UoL%V=elcFVAhGqJeEfjR6Kq#s!L;I{_H^%bH}T+~B!itd$i-B6pO1@YwBX-p2r_xGZqiSxQy zrc4-y1z9KQitd3-AXD#Idq&cxT@8bL)xW&s)cXhGP9x)MA;m-UBvYdR7Rkg|j|%NH z`mFS%MF!GY&!53bwV?#V;t7QrH{+k%4)T)HBOMf@f7=LeQAG--HKb(IW^OtIscDrE zotH+FgehHQnmir1c$~IW=o~JE*(i^6Xler}IJA1TA+#52{XQ6$u`$|Vkl1aud=D}x zLyAXQHnU?X4<`ACODVnE(QWGu7Ax#H>wXJ$Lx~Yh!&L+;430THLf-`;sZLr$6CAjr z0-|`Z=jgq8F}0(6m2Sc#m2PkRi##Ny_em>GUedVqz$Q1lAwmh>bn0B@8-)!V+>@By zH3wL)B~kCxIJtd^969}ofL}klyvSxr!3Z-LQm=Q9?u-NF*D(0TaO!m7arrC6CWP1{ zQA2+_wa5V-hqKgAwx4)gMYkUa#})_&;3$edT!dLd`o`k#`U(jfw22ZMAg;S?(M_1q zcny#x4ZV(H)Ba|rB06U#?YC)9oUov|YS78DxvYz6vR4YtX09-#P{oCw#f=77L5`TNi4}}(6~0{Rg@%i)NUK6t z-)yHdc9Pza`Tn@x!vTF{ckMJ;m^V7xMcrMYe>VB0JR65Sqby44hTd=_8Ncp?yd%{t z<^>vZdtr0t@6rd=g`(!Ea0_6ubo%DmL2qgsXkyW)AVQg7u9>UdX5F|ROKT&z34#V)@jJx z@=k)OBF9QSWqjJY5@&Vb%cKVlfGtW`yH85*f5j%ulgM@T$YBHlrw+Kqwo4$H7pel| zVGh}V;C7SjP{J|E-lFl`O#xA}ORULkYE_tQ^Wkzw4Qp?l7 zu10PUO?&lfb7}ZKzOFcH3-{6ntsqa8GUxVC>1}Z{z<8zl51Mq8{7AD?CsnzJtCd)@ zD@|d&s`(GbqRJ5{%gg(Pr;;uKJfsui_wuw{Ugh`GjlQCq_0z)iW0@oX;v0So#Y+(2 zczb*0lv%@oMN275Rfwf+!5ek#fer(Zj}X^NJp`{X<912egwzOiO^=`t<)AMVVOunj zk3ZvU@q{bt{f%qp1S>whr`Li`#{3eKwLzcq{9;s6rGGzT2>Qbx#kTBn&VWLpxFUg( zO*hk5X@{EUocRM;iRQ=eX)*@h(xg!Xfji>Q?jTGB!Exrtcf<@zxkF5XEJ!Vt9K~)p z?jmvKY2u~`zQ0%JH7h+(&SSJGN;01j6v3aWv_VOg&!HgiIR4)`eA`FXUqB0=xC?JQ zwsUyx-@m=u=|nvE#jX$^wKaSPn>ZzWg*5r_M;L|0@j^Y685H@R1=$63qS|vZ?TD{# z+YsC8?qGnAT>KNVLbC3Uw(a$P`C>&0dvRNZK`6dPGVCL*va4twi`x3c8&S(vYX8Ei zU1aq@G)slO2N($c@h4crgaEPDUG-zGjSqc-k^dlR-qH>N`tflPJe@#CV!0HFUnj%7iN>9>}AeABvEGtRJ7two_ObxO;XRQSmcUS$#({deS9Uf zrSp_HXu-=f2C-iFdqje3y*ccU>H+}>aqo#B~2 zbRZ|p8nFK-Lx`530M1j0_c?NajR-UzQPxdKag!E8VqOvVjJ&q3v|@<5+8nhic5qnh zFY@weSf*@`X7^K4zCyP(Tjb3Aha*kJ%+LR*@H1kyrq~Dj^T*|mqsWbR@t=5A-}WM=GW{=d5WivL%4AI-(GwNo$XJwqRw&>CNPm=`7iQb`;Y z{MjHpZ=B>mD`IWQ^_W55|16_^X+RH))OE3Skdd94aLifo{J3~&&HaN~|BJO;V}c|* zN1vll9sYA%?3OjCmysoFG$??mUOq+SpuoFSKN?r@Z->3Eg@pnOnzqtMj`aXuHz<;#;(jPR*ICe#-(kB5xQ@+oO;& zEt?RuQjYt$bknI_m9?78uFIo*mC>%|d}DL#z@PArBQIm*7yI)KK(tL6b0Sm;U8w!O zMsY3gvS?>ULq1WCq(_-2Q6Jz$q-xcg`1!11Gi1rE>Os^XkzGvPgR;8cOh|s%IZQ34 z1T=6T6@%^;LL7p|{TC~(*Ad9ou9Xm!-Uy#k7*-G(h}E58(0b*itS?^RZXMbMHZ~Xs zA^hk7Z*+w53+R#WkF@1J zHxk{NFE=x{i*Nsu_l)CuY};OUNQy8Vtin)T1RkkS?E?jPaB0y|uN`naN~4P(n+l*Etqq zgCvn)J#UaHDlV3oP~^{~w|TiuvSIaH@*#%TB~++~T!owuVwKOsK@os#9pI0QBOJ*H zJAHZ@6>|_3+w(bchvy`6>w3Ly)iTQm$}q;h^EU0;^YEc_!s-5yjW+{S*2k(;B`C$O z6%5l60fZhuP!<6U+u`zgb%n?MxiaTVj;^@JuQ2q4o~ktNJn`FXMn=b#*83O5+(^kN zUQs?koZMXvR8X5YnSKk=nE1zE^B7=3hd}sJ$%>EAx+`d9Y9r) zAbIo}z7CA?0|a|YL<^1VOseRyX7jZ!=QcGJsyHPW$6I0g}tWm?+pq-2a#HHH$ zx8ki>5)`lam~cG0Y>Vv151ij*r@#sm5)Bk!pI+6^8Il6GxfMA%dHU$q_44M0&C(u-7*x47?&QcC4Pq_#?bYP<_< zZWU%!cL$`+I;E4f1J*puwsW*QZ}5p1!#7OT_Ex%JhVtu=;43D}3n*=TpSX6SS4 zvlCpi^9yvd%hMAy_~!GR9IQ+Ci;tO>)F>`ZdtZ>4Ay6*C#U$%AB)Ge_r^;S=+ z5VB`>DZ?&ydhi7WnQTr7s+|fZ!jSyQov@N;_VG$l0JqN!xmCrp<=&Ye;=LuaAt8b- zAB-E&HhrZ2;IDmJ#cE7sD9=}Oc%3xNI0Lqb1|=h=4>Q8kRtHCE4+hwln6n`p3O)bX zS)ab*4HGgOCToaRa7wflh+cex1?E*%c{Wnfj5pGM18AJGg#oz^>I`~l5GPbq`+Lp9Ox8Izx9jkIxydy zq`ll^59d&jA($x0NfPi1o%I9HZ8XyxeqI|?l&8MyC*D)M$UZ~!>o51P9rMD!Ew4t0#n(M#M z1{V7D1}K0h3%I@iiB;pP8Pt&P_aCQEfV|vfAwSwgn2kD#m_+8;vywok0LeQktrBvo z7cXN6w_#=aM(v}bVX8hRZ~@JJ?PAmCWxdhN*yn@$V!EKFf6sMC8R@>$@(VYGPd0er zhFk|s3xs1op^%Es+cdh^U7JLClwN_Os+B?)pkm)*H~!LFEd={;-x`o zF`mGIDv#k~OHqg7qgWlN7I-tVZ!^{*#&%)#XSV8xLGH&;raQ3mjz(pHa|O!ZLSHbk zu27MUu9rENU^W=6P+%xc&A)2a?$?Gz*c*5#nn`4(9G7a9l|K+U)~9?}8o)YNX^M9^ zpv$Im*I5=19ZP)UQ3apDc2P`$Q|pRyxn3uG10-f;4qjPt#?s}?!!p3bxcxXs}Ml5 zdpZi1BTijPBRzm!Wq@ba|HRahG6zLz#|-~N^cArUvVu4A66;4 zV?FKwT_VuzD_;R@NWDYdFzoLHiH4wK!qvI(b^4mzl8>G+V?iadTt zyNTzG8k4ze3hz^>527vcJ|+VypZ-(C{fkv2H*|Wa>x6E-7W5-)z{Xe$c7USp?N<8N z-2UP$i_~P)N%@ndkU35(0xaHQKpn@BFkwABnbzT;Mi>GWw&9>jp>+$u_Aevmd@D3- zepXLH=zS!b3y3gg0LFpA_g^q%u?i_U(%%>6dtD=gGbbA#lCi32>cu3I^D1}NyF1R2 zwLMQv$SvG43>NdG6T`rrBLlC-t5wl%eNuys+iHh1`q_Wu{nssW*=Bs^bp{$jE{ zd3a<*G6~#IPI8D(#Md9h7>Dm4r-x|63_V7KVe(tPhXl+ur-!_P1t%xZFT4ySOe~Ka zt3C6yzO?kTqOI-x^R%w~;=1(jvG&~EJscihi~g(P!&z0;S6N$o$yVp}IzI4^9GL{p zY_K(E2o8ST6s#xReqKR#{gd1p$>n`Y~8Ni#a3giphg1_nBnpF0{ zP`g&v$Pfw5^vOOTn9H6?2~E?q2Q81pl`G!fC1FZ!)@|cmi~aJN_3MLuAD_`rJrd8V_c# zRsYys0I;m!SPQjLKCa{5z}L1A**crt#anW)tk|B}+f*&zbpW(|+A3M}il%9{uMX?X zdtUJ){}snO=*kmynjFX7hgU$w9)k@}dH~)2)b@AC7tiEKUB@R@Os|2}(3-^~Jij zs+R7Cs*3!W({^UbiVK7~#J~17M4Jc?!G@CF`7*ryv%$`HG{%z0)4FqXtt}1R1uYFF z86K&GZK%0KJIg9c$xEs<)n@;ZS1%W~Tc)O{B-l2NL{(L0qN=GT*JWtc`OB6gXqWV{ zQTQ#QJGmpYzvvQT=+E*q&nK!U{rfJ26*cHq^E2WTtJS#BJfQ@C>!$|!GAu!Osc2YF zq<}riNfro1T~b<6jcaRGW`?1n98*@*F6Fz=S_7A0+6<6WLkVv|eqHyDuKo@f7SqI% zR-HYLY?h%2d+(QyZwb(NV;jSJ7WJ+dOFC|nfeQkvPah=k{8RvTwkZmq6|aE|`dZ4i zw)~v)z#EH=Q$aC*3{H730I0!=wy0v}gUWC|bceWCwEn>$pzV2!Y4|FskSgSPFD8xA#enQSyD}*%bxRC z3wIez_f*KW8%B4~6PG)Lh6Tu^X=utM zfkK37jzA#gVs2=EEV9ljho#!6nv5km{PZX~rE)y1Koat~m!fvDZ&p;UDDltFt?H!N zDo-Gh(0wUt266)`mCNvjUtnuyGtt!>k-27gq{ZoksSsU`Kt zwSx*zR!q|?|5+trwVMPne9lsrb50>kqTMdX#{H8&krR-frS4T`X<1bqI&6JbbWJRX zxrsAFtrei9g?)rfPq?iy+WjLFv>xdn@p-B0TswjTHc`mWqm1ro*iAx_>mY zh|fbDg+!wn2f@dsYMKgKIL-E%guzl=CF;IMwT{0eF!cv$vlHpJLp?V_vK!#5EjONjG}A+Inv$*5LC z{VlN{oCqw$@-?pHfPk8ceT50`Fq<#R;JdxsjI1H;i@sJUf~)A}R+FhNFy&v~yqZFq z>~;%FOtKe%fTSgCRV^Hy?15O(TlGbhxs|oQojbNi^1gt>a)5U`W+a^1lk=w@nK&mA zuH-y9B1PKGg<183BU`ew+r^_lf9a;*JVmu7P(3>5Eymz|DQ*+ufC!JW`BE~JN=)rx zU_xWHeA&RjZ5V7%0GjhF=6A6ng3SD_Hx6$v9P?*l%+JIV@5L*EPt_hNhfhTAnHxn; z$)2v$C#6r#fr8dB^!A)RP0EFu|AW&jNLS6k%^n=4PyRvbE33^LvA`Vy$iqu}e?Z2x znlz)jUgVBbEarD^jPBl!^CxD{@7BK0ci?iwk5M-*!Q{7XAe4zn|YFDu7-yI7vUAD^lNGVE%I#bEdd8YTVwxZO6bY?>;8h2UtYPCGLKezXp;#ri*_ z76joKq>Km1+C}qT1TefL8=Ro0=Y;XX-M1k=GsXmB7f6Cmdqy$~vHpsij!G`@BNVz$ zeiUi(k&%yu;Z9VhIW!>!%4jw;RsDsL&@>_T&TXTI6(SsZQ6k`Q{YiM7z(r706t&S= z^tvVY>xr<-69w+R5hTM!<#-4gCU>mc~m>nJ%G}g$fbwo6AGpO<97S_Tcp zD-k4O<+~clvMa28Bo?K#zj}esS)2wxu?NP{3*}8>+1Hdq*GHSi`7zIr& zT!aeh3*Dy*aoLmJSzTJ}jS$sNN}-*jZKd&%!{W6pTBIaoxd?R0hqyRA+>V@3<=Kdk zDA=h!P6zh&hS2nku`Srb_raqM8j=KM)i}z+AwX1o3`52ZH_{zw(osQJ-ZPKm-`)+F z4n{MGpJ13DFpn3h%4uxND!Ix#9CVI08_wHNV3biLDJ#VGM0xsrgE&JM7$Emh+QA0~ z27-AyldTzW58M87cRJ|l7G`sV#wN7F(Lk4aFM!@gaGo1l=o3=%d~*^JexBbpH-{F* zP!tm+zQ19K2&mKSz`wEwOmN2t`6C^;1#r=Sv^COdM)Im4#0Za7IFiS3jN7r-5D+a$ z;)-z+qME_Y^%fM$cm{2bt|P0V#jW^R0#YA+i$E?44mX>JAPemeP`TyJ`QOljS(fg$ zi(|(1@sAxxyByM8*L8vYKa{;?Ol3i|CW^beyF=q{jk~)XpmBG1cXx-z-QC^Y-3~PF z&^XQG-Zw9EXI^F|ldPRo_OG4VE48XteNwQmRsSwrXfhEOzDIYmz+UF>%a{FkKdk6w zb^dyi=;-R;2Yt!F_;!@Ntft2DDoSwHIb6t!WJ8~DprGH#Ixp|qaN)h*n1nOuG*eZU zq}_%C>tEE>=R3H8hR(W*GYe?oFYuCyM7s$I`adJQCut)aV;xizp;#KO7!8NMac)0v z!5_?fK2EV>@h8!o1dCrW$k~X0IfibeSQ3}bl&CRPR9cnSR@l>2RaR+3bVhBKVE#djwx+APxWJ>UibaMt`J5?$8N)@7_sg0| z#m>Bh0gokw!XmPYY=(R}U$BRA95pO;Qem9yN_E1=ASml9A*Z@D_=Y#q{;)lhG0ty< zQ~}D4F5|#Hw4o$TFeL*Hf3>)UftNMi>?{AASxT2xyuqWeIAGA3(P#DpjR_N&A0giQ z#r;8W4HnW>LG=r7j#5M|-7kW|*L3_*J zP15lDQBV**j*LD)FX zo0EV>x}Gha4-NsG2caGGTIY^c@rdb3_}0QAJgojsO;^i>Tfp&Zk4`$FyZ;w_+bWZ9 zMb0y1eF8gYl4N)~38sD+f(N9;U==fzA7aNX{`oWB^1wwsoF6>m@^Sdy1SS`HTnTfW z#Ez^QVXS{9O|Fg^dUzL%uTE;DWYu>Bh9hb$G1w^b=7{**P(r90;?BGf7_x>nf8e!P zs!-SA^S-9--mYCAZwF^TAlV_MlxtaysQl1#4eI?Xfs>oP1~0wUpS%S>0YRFcHFmz> zMH+hfJ$mEoa&mfE@spYnpmEJ^<*K#R-a{6BYoH^;1wC690p+Djh@p!SfzOH17#Bs1 zT0qiw>33N!07Ey#rIL*~PX35dBZiv^IdDb`HS-v%k23R6)d?k3pfuSd!*J1p{UTSE zqT=7BqKg~kgMxb~N7n6#EmnUHen5#HW^uY!z7ss&=5)5pX5rd0B%Z^=oBC9ZG)Hc4 z#R0L8B$)KM2RW{wdQeODtQ-K`x+WVQAt(1wJYG-a09c(Y&#Hf0RSLB{ z1C^1nbW@GwXemGxQ&^`-h?2>?6t-a)$Ek&H9nVEN4LQ-xxrEz%a* zA(yVH&J9hYz0c2g#_Xw1bcyk6Gi3bddYdQb_@AX)OX#iFAdUKns!x06|`lH~I_FsdK^G(hjKGQ-wyR_N7mgZX_cwxN)l%%-MMGH z3Kt7o2>Fyof1*ZQPoAjikxT(&ykGLCkSXbLY1+2L8Yd%u7gW}`*IXNb7PCx1);$m{ zv|&cA4f&Y}xoL<7fclbE3u^AdhHl_9{fQv3%)UxIaQ)`iJG1^e{V)eL7cB+$&v9<~ zPI~PoAmmQLA$bbV4}?|YGT89Y+pv8RK66<{4LQc+8>W+ZSl5Tj?#fj@x%2b!!vmG# zU?k*&61@9fO*O5eltER#jvrHy46s4(kC2Z8)s<}`Q{>Kdk|cecDBj7ycwu!vsZ$GF zz(^0>W_>k}&5q;;DbhINhpCjj2wW&>eZit@pdW#iX{g00>r`QLAC!y#{!7TlGU$=@ ztcfXy(vK95Ye$bqE_~X#J@kRc3P~+jzpfS==uvb2Q58_n}MJ6aqqtf z1wl^sgX<%A-HqcR?5PR0WXJ#d$_P;oS~3#}lG8;JyhvG6O_-pVF0PcZs!@$|WlMNA zogLYQ^+{>YVRZ4S6aDp1m9QjN{Q%&Z(q-;oFYd?(w%k&F#O}@naJZn|m_fMOkx=wBQ5Dd=U4PWVhcA zFKv0WGfh5MMLWK(VOGDgVmdRT^4<2(YE-6vp5EjKJ8426{5w{k!+WSg@o0R^vwb=uG87QVnCQhi( zwv)Pkr2qrf^HeLwIytxf)HAV686DQ%lw|3n!-^<7Yc+9s9f}_O!#nvkmC}<*w=Q^f z1zg*kP4&RMD@Nx@-|I5`?$f#kk~$HCA0AX%1Tww8U&%1kQ6$*LFqrHhz>*B~c%ey# zLL^oyXi1EcYwB6YCn$;Er3lBG(`cPJ`oON4GjXYy|{LAz&TAs1xv`iZ}ewy#tnZfVETv@ zCM9UWycWVmjgZk4ok$xsL=KA$5ot-n%TZuuNHH)cX4sOkq^_POSmy{?yUfenlO_X& zaLewoD_-zw2oSLoyz-7}lrGhqwyox^XC~py+@O0nxjx~Ywr7!ZiQ;~9(N1J19m&hy z^CownDbP3urSD2~+kLZnQxiFDsWEf`xHT9j-b*{zY};qTZ++OM-nrN8ZA}ZZq3CAq zOF_+lsxi*pOi?)J9>#S^{(wyDByz^iE)ZpWw)4%vno_9G+s1mRT8uSf3>|HsN$<*) z*!POp#@IPw#Ih5AdtQ7SqBxpE?X+T1Pn#NPg&ZRzq5Q_CD@J%kNaAB2S?9{YQOFpZ zk8vrRe@PUko~FiuDU~t?&-AaBb1n zMJd&&Qo_3-Ah&pTepmDB{TIE|y;&kgso!yXgvHhM(Ahj~qem2jb5ylxnTL&%UP-%T zQccq&7CPAI*Xpm~+&>{Y!FI4RQA9LsE-FM}Hab1t}C%qAQT6Hai@uQ03Hb=3?;MC0p=<{ie!t^|inQ z<1>uKsFu#!KfwE7@wgF0>$XdMDi&+cTot8HS#L!nEGWsYg`6um1s|^X9l1oJ%s#)+ zoV6W|JQ~H3K>l%LrZaH{^(#qB_L>UDSqz3w44-F@nE@5m0^_P)BM0e141-hYy`vDF z5#wUts)5K3(|m}?5o!C!Y-kUVf1R3hpa|&Wp#uP6ieh|GvI$ch3B4s=h$Z1HP`4Qn zbA&aEkadh{Cx{+d;a0U7@dV;kW33tGwj-rST{woWhm}QKtuxs5N3^4^MP}b3IkN4N z+YOA3)VyHycq?p&)kSRG5jNoOVY&m~jgbAQ{NfBEyF&D~f2a%#7{#<}#-MwP)wUa8 zMEV+~c}PJF50Nntp_WC1lTi_2nn#QcQ#mTxpvFhjkDvp+?uy&B`6+u*6{By4*<_+T zG;qm?RQZ9BrYSF}Nlf}GR8i@vDtA$=lHHYRQ3muiKn_YWeNE2DJvzNdyXco(rxFj@ z4bt5-yZ5~u7h1D7(UgPg$S6K*dCw3Phh7;eHKG*QWK6*1PD;|AETezB6Cc&YMO4Ei zlFY(uCz)gil4^uZ;e$JUDOxHRdMZ6jY&m;IF(6Dd!bzmT36?ifCY)!oFh`#ERjJCT1uCFZ>4h&Ye@v zU{x_BS2!At!#Id4_9u$X0W^++E+1(@nVZ)SvQ%v;P!yD~ciulj2S7)N>>^XXv;7Sx z>a3Yq+X1NsuXhX0UQ9Wd$dUgmbnD1al41(R!AqKwmAVLipt5B*PT%s}GJ9$-&*b{p z()!$@vT5vzS6G;$LJ&SRz;o{+<3__oN*9lZmbJXXB~m$d?S#>R_9QGxXv$&sLu1Tx z_PNfL=S5-C)H9}#D15BI!^YK$I2{4m@ov3cEj#K-)ZAw}f7;Rvy(@%_QXk9l=XpzQ z+&LDWknuZ=pSfXVmI?I4v17a~aZUsAYE_$1+JfqtH~Uxv+XX+_mh>~DQxm}yqsg}ZT}^ES!QrlS3<<2mSoTp6p20qH?WL%D;L0HD4XOZI zmt%a9GCd%wMf(c{zi?HfeuYroF~NoP1v_IxGHR%`>ooMsM`2#8*wp8r$E&=n%FyxG z6%Wu)qIk$U4pKjUh)e|d(+x3;<+gkD3AKhXdX1S)-JTfURSWqSajo6*#$R4$_7)_VB6DKlejB zA@kFhUEZyG87}#n5%`nFP*F=dc8mOHGzI{kL}Vbb1{g}P=u&yhRnHI9Okp8XOi@bS zysUmoY9s1JA-B?4|EgMq={oI@gzX2P)bY@O9VCwUrxZDOA_Kjd;>;Wic!l}HKdr%; zSdkx(`3R7*rC#bXm1$!?yCBWvG|gj|fSwLKlUQ}2H3fAP?ak(_EoR1+kbYP>3&v`)5yk=EGJ7fUI=lKv1p)jd%KyLbCl0O>71>6n?3A3F*SGOHAH&N zR<4vXBWhvGdYYa4_|^_Kki2!Qh?jHPLoHpX74K3J&b$$2GWVDIQ-J&ie8r^izS?zo z!K5H-HS{kEaX83HQD)T*#jq7o#$N0+`uG4v9uPy3+8eMyEF;D?blDj82K2JY3(?YU z70ZevP=ET=V+i83NfU3H90`g3HmxB;NQGogByvMqg>=nMq<@x~1-<4xZUrX{)Bs=$ z!d^}Xk5XZ-RBD<_ENI8$JsO`T{^80LBa`(0duqxfgr_;pKnL~CuD_~4P@gajQ?R%v zq{|<5oYIf1puD{VDuW``cSJVgQrZ&vpyG9^(BfS#J0UY%Y+EDZxVOH;;&%LqX3cr4kgCGeu-c8Cf$QcV@?m?$u*mFD+l)}b)mis^`V-afq>oj~mL7Qp$S34U3RKM4yEhLtOitMUB` z@q(%_7l={inrGaA5kJplmKT6OE;knq^<2d&iav8OtaqObCUuVJ$$%6{@6hql&J4%ck9j|g z1AVeDb4Jj3Am@o@ff9uFf|f_hh?)^oWwMSED#9PiDGf$@q{ct9p3Z~@tzrKPx-LG| zYnzDnOmy9yGc5wg|2%Z%a$M;y8-It|Go8xh4DCHZya3dk;2|hgQZZ4rr!3l)F24#& z6pL5A3GlfWE;-L-&OPNh*DLjROnCPf&(ceiP6SXv{egnwgo{iw2Df#1qVC*i%u;f^ zwNH*seT`LI7)rq%@)WPlIVi(87DR9-VPAEFO?p}K!z^QgIUl09CEqVL4|^+rEfGt2 zGhmr*FueCBmO7VxMVue#)8s7eo^Wu|Pj|&PF}p3`vw66k0rh9PRM4Ct#UaK=_I3`L zOE{MextfA zB_$?%ziC2|CtZ1O!5BUm_;Ne#lG-P`yFrM2`ZJ+IWRy`$j_}RE%a(PEs1-iSf~I7H zp!T`XZ3|cv8atp9e7{-DGiQ6@9yUVIR8G85`IAcB2dv_}%!DmpsP+vzqxxTJ z&i;u~iJx%Sx$G&$o1E2Nu^;7vCH0iT?_ji&mbqZsbuzteh;p{gbKBcq=UkmNHuJcB z*?n;J2f-=ACXGU&AJ+A*Kwx?Z!c2<2jk9BG(8S9Kooe z^W#FeAnsK_leR-;eLFP3wV`t&;r?}$enSE~f-xwP;s{d&iCUC*sfG&rxavj+YC55o801hlr3RF>#iZ~TjPDE*o?UDyj zayIU${DXy6C#xI=C+?RdHQS~+C_q-93^q42KgqevS@`$w;Q>1UY8%X{J(=1$eMW$@ z1q@*sahvN_NN8{K`Uyge53$doU1G0N=(>XVWdaVe#m&2=R~oX$K^At}{X?i{lh955 zQO6BBh1OL>5sB0E=)p5*Ik}e@9z!4EAa7gBLA+5Qw~nW;REzG*9wPzu+0P?9%>Z+=|mZ&cU5=Rck@}+LyU2VBB^x z)~wO22&gAKRW@5acbi2&suoW!=W@I^H#qKN&fn{}d$hnYHbk<7iUx)m-1&B4`=Q^O z$-&tmWP17sl`94LRKistX zrOT_zpp0xBfpz=m5DZlN({1R1Q)59b$pOMadicS6Dx8wL%~Ppwq{9OZFOn7I$6^@C z8F6APj=l_0(oFj}CD9$Zjq1|O`WX^AoLEw$aGrQTrvFGvg93yn@^9`1`nNF6 ze^1K)S+nfNciP%JnKKzW7#drcG8x<3+S=PWGuaxtSg8Qu05B<#IEKyQGLfiSooPz2wpDu}@Dc;AfC z?hu#}a|n2T2q1R26J>N9u8&cLyB^$u!vYfF zKGSK%Ty(skVm~`N_QgPZtOm0ZsnjDNKMWI3d4%x!7ygF$X?kJK>Q~!8)kJ>_&*(QX zW8ipK4&FCv-~Lhq-Zx|n;AcF1X3g6VRGjpX5vHt7zk`OvZ~s>m6bty09-ylIs{S2z zQHHtf_=ydvyRMGJ^>0#G<&!Hd^1Kf|;lmaYY_=kPM08h3kz~EZE4bnMT8sVQ3W=gi z!yA1#taG}xU3NyXclDt96R^cw6qS&p8(YuCrtR;7;BC)m+( zT4`46xdtfGr>gIg*?BsiPb@$qm%4vZNmm@v+gm-luCk$1qrVduS7VTDQ^~U)T39TSydi;d}Rt6~9!#0gR}rZLO_UxvlM;`i)HDHn+1`wt8jqokP7a zq8RLw25wwfGCqx$yCa{t0pW!jq{&)%k(IIivmM7S-a27H-u9aoGs*(6uyxl`+AS0v zEUN7Hfc2sT3&nVT%IOu>FV~xD+FH^ZXs|^6RFdJ`Wfd!AD0L&*B~yOUDe)p7K_c^= zny^7-(4hEZv1JRI4e?xvKYNNpUciRg-Cs$9%8I@WV#A%Zyr7u{j~157$fp+~RE8J( zVCV-_Tu$Cb0zHW!$rfBtvO9sn09MG7F)g&L&18}L*XD`Lqdux`^LRYX7Eb~pIwexM z8nNG9)P-qyt90koV!8nNM~MhOtR{v0e7-@ho~7DAt8%P+&8$k8sYU4`2oo{myK5l| zA1V1z_36b;6(VhR9R##)D=6JEvt`aW>^f7V*cdk`U@pgbU_BMCGSM0NSFYbq#WxvW zowkHs&`C<3(;`>H7Cr$@81&)%843xaJ5h-Js3y+!83NcnH=c|mC@Q3XZp|cp^OthP zg9JBviEApaz0?0(UQ4pbOL{;s53K+PVpA_uA%6ZlBfYS25e8BS@Df^Fv^(ig1;2IfnM~8S`i+ z93kkBKh{kN?4kap2dFQBSjMbCB!L>2#`yEy5%Z71%<EBpFW8NT;4aqdad)lIf{kjs7wGQbFrt00U@pfEsdvY5!h2Vxvl8TnTwU3J{3VK%GxE#XK>n2i-|p5N)LI=jTVvmEWl6>6Fo0?`M0=G&vlfDJ`+4!lCv8EP}e zyK&mWaC(4G(?vAZN&;Tl7NBb=`}B@w?ux!PpE-!XbH{S0!lv8KD84jHV18pG&kI9q zn`67E2dnv0s7}pG;7EDv=iSx8EeB^?%XOudWyLv4y{#L|bv1FmV@rM0M~(WAny#$u zk6sP=ubQUdd>po-t#fO9t~R>@LUaXoC_L4`8=@uLU{^f#%WPO<=`#x4R zr8>Vi&v8Q>Vh~V4XKJMWxM_`_*)`@=2*VU6pCgp7i<0B~LR|Tf=RsOdUvU=S*E_z8l_|4g^e}^)2RzUFF5yqBkFC9gC@%$+<#Qt-oS1w$6^Zn$WJ_u^-joG=Cq*uzAjI zNToJ@e`Hu6omt}FnkjwMH~@B`m+@&w1u3E_|PcgUsuw4mvej;FI;J`j5q*Ub9R4r^mT ze|?{39S1BSka?AkllYq9np{)hidE-|L-Cl5a?a&k#nG-4u^MM{;cjhgFJWipVq-I{ zci-Kn%RA`{@*55?4jU3K*WCy}2V-GjBLDj5v2JYHHEY<>x+GJtVXvH`p z1BYlx`ZuTlz53A{ceqehC3EPH1FfVo(2+-qU(&LCJI{WitxNQyjY-RHqOAdwp^eZn zp)~&3Iovj1wu1u8i8gKaQHkz!UeqT}%#Vok4ifE6+$4%Aah=IH@r5oevd*yP1&TA$ zzEIc)o^PaWLHeo($fxu217nuggJXe^AdPg`P!Fb+k*Y!*?Hxr>JS{Y&100N5jACr*w~7Wp-G7yD^IFdC6b#yn~_)RUj=LVgH$=Sk%*N z5@^mrk&$J`2%Aqhz%Y5zBz^ku7<+x(VWOlsg>uzNtn^?GW8IEzSZjh*3b$TXVLFkO zCI1{!1u0Fc!$Fp@I_227MlFE1@}fjUKHx_}{fGW#kpJ&m}OBhwW;D> z*rus0a#&9LXo=}~krQrc^^jA=oF2t)DYAr?v`$5{F*S)MP0EU#a9{3bQAPXIak!5) z_AvT74{Z4GQw)rIY~iw(FI2*DXQG^Yo_AIMeUo2nqFs~}qyf5ON(QWQfVNlE`WCEC=6baD32 zT-}y=Qn5|fI(_~_pc6)K8PEP3$AD6z+xaalLb~Nplb5YR)GPgfMW;q|fAZ+^3eh$b9Q z}V{__7-YcA2Wc2G0N^_$gq z8b78GBC!;ehAcL1>M}%Z-Ug#3#n#GZ$N=H^4K#F?Lb{~ffu~&AjMi$|)VQcwwo0Y5 zRh}xLB$dbi?!%xGo}UuuT1uLKn7fXC@z%_}Urk)2fl*w=f6l)9o_Oa!|LZkp>iOD) z2%!4V851UEC%7k#X-971R#TuOl~qYg>BdR=qfcl_>@z-|l=>%ufrl{MHzWG}2#HJ5 zr+lAtB&+m;cQg>AG~4E6w^s4s zt-bnev(}QgA2R2KEDHdmzSLdI>-dM_PI^qX!>*a;AKoYP$%M^pc${-0(YvITiOgk{ z3zuK@cBnN&YX`l&41)*B4#&@UP-Y|llri+Uf0@c64MlOxb4Rqn?}n-55eXl1{y;B07YZ_2K>8I)^qPkA;ZYpfY#*ujdK^*pbMd z%%_5@JIj`I0zETi#+}}Bc%V-&>lVw~4k29h(MVo%)=WEGFS@L+4K*a1TvGobQylwh zyKO=xmZWXnFT>S_(yOv)Or1U*sFt-O)btvyw0C)wxuV#Dvs;e)L)oRkfIt~z!PHz# zw=UPDnLPy=vu?KQZPQjYuC_$avrZs^y{Us8(JDg%*zyw7oGL}w>Xv<%BaUb_&O6e8 zI9URX3&*!%KX#;{y*YUVR15u% zLId2oUL#E&N-&TLysCb)pRiqZmJ@$HRsk_vP$dyoB|1>UhGm}A;Q+tnIn9I4tvurp z>~`qF(vUDxTU5rUE4Mxgx5AKb$h~18ZbB36p5bH+L5Rkc87*EH+^m~JAc5Sd6{P4; z63Q>;B*S$i!gkMpKFZYfW4K?@5kMhOcW4gf7l#g|-ye;4j9t_-GmXFsgnIf_7nhEZ zGt7i=DJeI`g!lo+gx`*@$E$$L9m@ta3&aGk1Lg#xZp2MG5g9}24`Cs~NA*|!qO^34 z!S^7vKh0ov0L4b^j*Q0B5!{?M`d4{8TzdUilI$M91#W&UEA18G+qbee;lo@JmoB&T~5^;@48o^ zC||$4x&OFFPgPYYw!1WQ)v!5TAc41j>Rf%dpFKBT z8FXcL;SZK$GkrZX*D+B8Wy`S~ybyj7oeWC%Zn3Hns6tI9P=9T!GibZ`0JekhNq(&O{zn6UGP0d)k}GidTTj z<5fjYRHL=`1(a;F6D!x<7qzTwfsd=*g97 zX4QF@V?KBvPv&jMopD`=-4zp-zX){pXaGeH`3Jk9e*wNeVED>`^4*yysV$l2O5E85 zIf@UZ+j=-Sq13-~gSk-n!&wU+$@G781KI|HVJ7dS)f%LK2&E6!&OGp~i$v~bB`pG_ z&Pd9(D-j^z&u23$uNlYtX+<=!Na!80^^(H3FNKg$7iUgbOFX1pkRT+L8L?u9*04P= zca_!Tj3r`nKG}x~t&!*Nz-5k;_;rMjStU!Aj1r>R!!yWzQx~B!L|NWoVwNCrP0xMG zhp(LB?CeFmhKSu>dIo={z9yoX*#~A0Eg9}kY!%wHu(s<~6N;N!K&Xoscgqq}1JNmu z)v>3mMm0?JasSwm|4~6Biwjv5=^kZii&r_0{q;|cBfmqUx|LOUn0K~;Kc^Lu*E1k_ zAaZ`#IfF0mT#!_%F|JM~2U^V~7$J2BP913Nj?4rv287F&#Oy9)Yu5qltsH}Ke9 zx^&N}dD248#V3?{jFge)9@-}!6i!_R9&$70{&F?H{$LorsV7L+a_=+G(l@f}k-zys zrTu_K-kZV_7XG}7_f`PI}Y znX6Ex!?Sc;rbI?d`ButN87G}=kGwO!rX6-Ftc1vlbFjyOd=g;{1*4BC6Ia{w#?P~; zg`Q`w7+YYZM~{5bG#d+Bz8){X@1X!)ZrbEKUA!+%vpnbPyN(n7xsI`a7x{Z%5Dt(JRBw(W!ytlZC9djG zu(Y+(cNG}V3rE&xVv%pg^|LowH?`;Y^3`bUWJjMEc=yQG%gx)7MFa`ef=>rSa0)a4S=vzcrJ>2q zq8_rdsf`+pHD|7m(W3EJm>%Wu{9dKXiWoqCb9DFF$yt$ISMVUS2^r8p&DO|qtg;>j zP`)$i+VxZqo$8wHO%_M8m%fw0GH1>hv7`+v#z`}RFvpbZOG)CcwrRPUwPOrFP#L=W zM4|$3YoaNz`NbIxca4*gyqP9`Ls#CN=SGW@;KHy6YqbhIW~@^l`1=*uh3Va!8k6-L zyH17&RUb?4=4x4@(jfa}%4_U`LNL zn?8n}hrC~~Bq_)jAufMAgg3FZ(@>E=@NB^1&ooN?v)V|r_DQ_Af9M9n{=tByzb_<= zh=;b>>u8$eTKSIr(X+?DC*ar!9i{rVR?P7xca?WTjRwo+r zb7qcX``maBqx)yeaQf0YPth#b8|pGk8fe-^3}&lCYDu3MsCC95Zx24~Hf(Ez5U+#g zEu(SjuvffBSXIa~Ek_;`5L^dp&p=F&@`0-&=XV?h5}%<qwy@Kbm!wo;?J^GXRjTB*+-EeA(TVTyOnXX@E3mle~i}!adijo4Y9m7{Tf@m!8ED3iOi4lzFJMfUnY?T?%}YeMchV5@Qai4v z2Mo2}8)T7xKi~_Iy5xkm5m3fG;XBvPCuB+AE6$Cq^bibZ`#=zS}&@eyGC z(f~gy2Y1MtE)zdtN_q10-+$`a%}DPWJ%NLO%ztaz{jYDL{?G0?|8>3jpI4V$jU83| zHOw!)<|@odFwWNcOER0}(Gj$UAY*iJ7REHOBB+pPX4(V|{b4dJ4IND#R0m)wah#># zX1bth>5^Q=naL)vYZfe39QEvD0h8~P|Ga;J!P0EAyw~-PcoOJZ8nMewhx^>~Yp(O( zGA6+e_}|b!|B^>kNVxpUVq$~Se-s^b|8RL>G+_1Vc*J3!cA}fA;DPKUraR`bj@x6n zwTCLhdJU)aW5+!DT#u)P43*Gouip3e!%)62LgehDeVCKY(b2d?8_KJ0sm4UCNm!BO z=(4D0c8S*-0jPCVn_@p&tWKWPh|p%OU51twl`7A-7`Xt}PCPF%Y~H z29{iXl7yqQoq0v4U?PhrU$uL<3udxhmUxX!Ih>R5OPaiCH{c~A3!eX#%C?#9s#uHI-F_4!k;O z(tRqc^7=zr?009hn;EqkJDJM18VEanF1U90Udk3zQ93D5atnQ=Pqp@{-pJ)Ptek{| z3yDpXgfxl2;UdI3OXxGD&`coo{xHXZB2wDp=}Gy4r$b?5}T}=z1G8}!)j3v zgNk#!sq{{|2VSuKJ;|t|wC@)0QRB2Flj})n!WPp_l-(}!E&kD!!Z+AWqFO6YS)=+uSI-65{sf_aaDAJdZ+7GE&7> zr2ehQmcz6RkkKW zwYBN2m<)WcLWy_@UA6HuY|Y9c{!=n<6aixpP`-G27&=x}U zHy(vLo=Z!+2&2%THH!1J!UQo-X}45b8MePkFE;{Co<$xrP?9YKWG_hY9OH)j;_4P+ z&m#)p$1G3ihA0Nq^-1)RxiEUcE$JFzJABc1D9lEl(F@@XacVnm> zgW8M4ye;jAR0mb!tcTjl6G-x0U zxSjB05mK@oxEKB4{U+5`^zlt}G^NksD9=nUhv;DrtmHiiF}DakvaU0JR~|^aEK&Jz zw^%#y-9JO|{5$pyazT09>m|T8qriHz11su`!oi5LsKVv=y(=rNtQbBvP@KmRQkf zT6{zZkq#zw3;rcMTns`J*IhmC@^Vd&-Txm<&twgSo2$>B+h70MBE>Vsz;7Gm2xBJS zt@hwg)ohqY*%@D_BgSxr=NPWd9ed{Q({Q!erwk9Q;T2-wBxg(ktOHYDJewk|wO+T%s6y?GlU(+DZ`rKz6V) zC8GJAJm`ve7W5qYNS9+#(j}tEU^&ewl!_P!OqAw|Xx>hLM#d!_$7Gw71{ITks3Yjh zrZk(}6;RD*eFSr6){gEqFZ($y=c-OPr4AVS9dmyRD|-UJ4qaNlVlMB~E7owQ&36hG z8T;T3q;$qm%c@Dss;?B(MRnD8I6F5CX)a;1Hk2W>sTG=x2ixk63xK+HTax_1XbjKb z(-7%}!4@75VT-S)ukX?g4U;+hly3Z8#+^|9ccuLQERytJOS#f_kJb4bbn^e}vF2)8 zyQ^v9`nj3S=9u6}IcG8_NC)aOXG*gIL`WdP43nCTlVN8=QWD5=!N-zILXRv6QN3j03gO;CV>L16KC=lASgH03|< znEQS08O(sLM-guw^gH14M~sg}AT1%$E3Chw>4ho}A6*s`8b@46rI1FZ#5wX^a#Lb2 zIq{K0Hu1Vmu$YfQC|qzGOLELkraQNOj(;V~DoV#HN>eM!-YHJ4JvcqZ#KF7S^w-Ck zU#*9fx%x=FWj7x-z2p!g%f#c~=J@#N+xZBOVMEf9Rk&=%;BRQrZCINuHL!uj3RJi( zo5$cMDlcJ6|3`CmG@ZGzXv_CbYmt4iH^FlFVX+IcdZPCrCIALz{b@L!C%G3_dWF%GjXF9=6mEr(3gEYNRL%jjH6Th0nVOL7SCQrx26r6LK{D%eI^c?A5c9wWn{wn#UeRBodv; zl&M-uC$N8cpa3bpjKFk~Aoe>cQ>Wm#)9Hu_n1MX1R*v?rt!!xp$p<;xXzL9=0P<)E z-_Ph3oZr!nhaJ_P(I)ZLF@*HhD4w-orgAR3dm1APshQd>5kz2KpGws7C`wzIaW0$O z^h#u&c6_=XO=U9{o6{yKkJo(6_QI>!ag?KnX65ZdbJp0WYx(y~aUyKV8|=B3nOf`v zI#q?A-+p@TKrsfiL;bQ!p&z(1xwGR7`BBcz;i?@j!-Z>lYXwF%j}o5IBdcf zPJOg>Kjg<$GXuAMK97mOo5?Zd=82XYo?AG5SCSY%X#F9Kt`&j&=KkF-kYY9onqm)o zhM}Hu3sg+bo38njjTk7PBb(KBOcnUv7(B1O`#!YCP~eouQXnz#2ecnWgT7#AR|hTx zzq^55cguRh_@+_oxym8oniJEHoX~=|tyuXFJDBmq`1j>dTt4$Sm$F5SUx?~2?@+uV zfpNe4F0||={b?Mu_7ne9eIPw)9mVgJLhkD5?rwF3d)ZZkxZY@I+9z=J$nfRKQecB> zPma`z?3E)!m>_R;S6lz7-x?oZ<&o*iRJGKHUG-XdI}$R-67>t@Chrha5cz3HBv%#| zd!WUimisJR(P+eARU_;+wJ67efj^Sck|o6KQ{Kh5kL&{Z9`6d})fIFgM4ViqHO`(e zou!;Cua}>It-c3axnMFUj|QQ^B_RRlTi@H{Oq7#Ah9O$63uIh=7JJc>tbfSpt2TpMI{?S_ZrkEJ zwr$&XvSZt}Z6|xjwr$(CZQHh!oxJ?cJ?G;5-@Wghf4#2iRb9QRy4G4>_59`>bIdW| zjqYQEEbjV11Ra`?+RY@=tf*4Bp~K@GO36D_bD`)ZqKCO66^6VFTR^k>p;`PI(bW$I zl^^!{h=fS4ja_@ki5sc0(+klwXwR)XqQ=x$zjI6&GM-N4rk@D}f_q&&+-6Dg~GcU0Pa9zXf z8}96u%^2OK4to@4DsbhKonuAizCLFHSgHC!ZI`?qpwy z@GXQ9$p$UeD;DtC`PvW-S=Jr(HFT9E>ZV$tSA@? zBV3K?!L3@bpfLAPcp*O9kYhy4oYa@TS>lGv}ESv@l z$AsQJi!N%iY_brbvhU*yP=oeZl5a{uyd4h3TyfOvC}2kowWCPq-G#Dr z?XR^4VWpaeGZ}4%GVQSwiJ?OG)}rb0=t8Ad4rf*K-x^Bf6J*XNUs!>?;cR!}%y$A7 z0)b{j9=n46D}Jc8D3=CU@wWU*7e9lpOw&Me7($9m0;_WNIm)~PBR zR)8-C5-OoVN^1?b0@hQGG;!BU94vePhD4(vV9~r!KHTCqxU{)sNmz;nz`BPv8)53n zB>TC^4S-6Uj44jOTO27xxX-%2F=cuxuO>x3aoNx0X(EkGD{04R-=WOgB{QOEKZP|G_be}17Dk>ak zU?F7wj5%*HjGPi6XqztG)Yf}SX`UW2$q@dCr@JMvf%b(=?o^542 z@W~O(#m5=Pe|)AmuAlLAy8%WFS)$nI7>$gK#6~1WMnm?JRwl$}j1Z?KM}OH*&**iDh*HV=V>$j->m~!yC)s_1m=ptnH_N4&bhYFO`dM$V3C@D8XZp$I9TD*@0#_Tgzn2r?W^oY0G zcIZ~5?QQYGQcS2X-fO)fpM#&P_hTILY7bZN?)oR>Rep}1Fu3VwcDr9VdNJ(Gp(IDF zSh#FZ>^!)!+9f5bV7HGKS!sLWrb64mOn%tbtSZaLjdMiF>62nnId)gBb+EpYH6MjN z&)$LY_zX_FpZQrDBTKSRjgi8PY-dyO&<{`u={XAsgts3Y@qeI`Uj0VM)`aPWzR*v9 zTr)`dlBkWh{9*`k5uS)oy17aF_SkH_An=HSpKL4=e5jJ{3S@qTB_a-OB(6<5z#lOr zzah`_%|XZWXHQM4rjJt7?h}IN3Lb9=i&+A$(u=#OM&v|YfvPOs)=&(P22<9OtWqpu z(ytshA}afqj~9(`V1}J_wG(L#rH?c_x#Cpl^#Wo8azdpP@h1#<#Mk}+{;N`n>T8%S z{ieUqg8sj&R22Ww*>x_E5Q6D zjiA-`?X6DFF2^pjnqDougoh!=iTW%H-&+`)eIm2U6k$o#F=xFt3) zET<+=TNQrCDag4_jA=~SgIF*xGE8ae+6*bpFk2Z;r~Q zUlp7gRpj|0P50ZP(D0d4fD0+2frJj3kALH!2`&>Dh@B-l>NgG0>u(Dc3&N3Oi(|$* zNq#wrnG9%CI&ti!uwnBi(#6}X6f5%d)TC@xF&ed?o&hUZAT-3Ut?!VaY*E%kRPvd2 zR0#)9bOl1Q=w5rE8ealy6HpTd@OU%yDy-Ue#-Mre;^uJ}{S3%2q#%CQCZ?ItKt$PW z^&6G(vtQ<5v3;siRA%afZFQI0v!+)0(%YDU1107whmXj3#8L{3utHpQC$Kv?y{oJ|JlQJpJfJseI1xkN!N zQGZSr7(nW-y)9_#>r6w93OhwB2)7HFwp<{0%yEKamuAB;aL8uSfSGjrD*O&OYt&~Z z0Dp1Jn_4lo$Dk`4Qk_K24SkiO)ueZG zSbw10-$qBpBY01=!v=yvI7Zx@0)Kb`0UHuD0v}?v+L4J$%ixLNZ1qS+tc{J=gwMpx z;`UJ>R&0X2hjhF6Y^@uTycpyfzZllqa@;5sGXlJGm5hTA^pPwmBQ+BAFpSE+%SQtM zW)eQ+NVSziACp+S#)q94cMvYtCT=`r$5)Jb_HARKawOMG`*JHpH4XK}ddiUrkN``r zI4xFhe7sMW^G0$ZCV&!A`O_JF|=y%3NU6&gVP$9c&~ZEFzz(5p&`+ zpW!lIt>}P{YLI&FX;a<%4bwTpsXl)nlELCdbrYSfEB0KXDxJrMKb(5Y5z#z%B5~dF zp=k3|U*VFn>v`CFFk($+D&t5M&8W;;8iPJeSq@m>bo=?ybo(t4zu*lMnX2zOrM{AG zuV>8qEP!s`jeR$M-t(LwG1BJV0!$+62#6lUtd%jYAcQy6ku|s#aBY>jRPO|qQ~tSA z^EiGk`|NC>xdBo44h7XRtk))+7Pj~k){3@juxx%wGWrJ}8QwQ7ial@h6nEdK#1*QR4ZbT?CL%o+{oQxc9&SUp;X2Np0{(wl4SUdM8qD>50A+ zILd2RU4y4tD!Kl+Kg->hThIrpPVvE8ukYUgD#bXhsi5zPr^at4;D7X*{y8Q3*8r;j zO-l3+5+Ib_H$e3{HM!ZjI!U@}^n8_nsH`&yr1m?FW|suM1^_TojyOPtHeJ$Tv}*;7 zL{8(Ix$V`UQJOcWQN)_hw1h^IYi8js)wpkl(zsa0er7f-nmN0qk{Pz$>It!nGi2;= z?fZG3eeIihpE-X2NXw$(X8hhh#P-lZC__;;yjY8p3 z2j|!DNnHE!8Pqenh<;*ra0Wpv_QZN$eq|R){ol ztl+*jLH;BaOH#vpeq?YdRiw^{N4KZ5M?y1D7|_`H5es<1IF(j0$Ad+B8Cg+ta>K*W zGA?axF*P7|L+^l^!zIBYch~?uobH-YmmacKUVca=^^}$Ep08Z}846Oro%}!Ynk;$)^b zVB}V+4eu$j8A;$ZF8eTO01T_3ABoa_?*jqg%VhS1j?k=aWS;D3MYnbgTu_+pX8b1^JU{Y zn<`SM6;^SAG8w)TZ*`{8Yhw(^Hoa$;Lo!53%yXNyNm8-rN4gd219w%Jl2}6#N7`Lf z`XThC;iM)&-#!>7Awbse5hj56Tz)5 z;{85&SN#BSy^E|bb4H}Io;Jyn5zp^-e6Zi#(QvPqAH3wwOu(o*sAJse;uV8?pX1~E zHisO^Cm7;$!CW`EzeiQ8bKvm$f(xg?Mq^m^l=w%5b$`zg1uhQVeRL&S77mQ zhlaghfMLzqFZ#)DDe!nBiFmpFM5_~?)CAb4H`glHCxM^s_ZQO?&IYY3LcGNsisb31 zAH{O?FB%59Mo1rx7!q+$qr7cnv9+BmEAIerB2re`JjBrt3vv%n1*&AXm?|ruc=9iq zM$BeH2Jgn$}tb~a!w#rBiIm@Ge?fvYM@c4ipyxOe zo934Q#0@L70CPxjj+eR*es0t>Wx{PMDCJV0zvlO#Y_(A&DDzqg_Y3SCVwJ+n6Eibx zt`+thck*xE!Kader3UwKU#*IPqKcJ~L_0ZR-v z8~9_(2`r^;oLA&ai7c&7$yK<*9l7$VvOW1Z@~*4b`!`dL(+kR*DE8Su1EH7-3yGfF z2YOPk$J86!3gk-N9FAJyO>_OGd3~U+MPQzGI5!3_p7JnU4MDDYIiuM2bcoqa^|Ld_ zXc}xpfNe#Q6tSaUL-tKb5eBSNM8y+FBNob+OOuD%SRGYzv!%6|5*w3@)#&Fe7OR|$ z{i%QM<9l691vYx=DM?a_YAMYLmo9d2vx~AX8*z4Ig*!&}GX>!ZKZ+~4h}pv{Pcy^P zVOG0b;t4ow;e0v2q;DEar&UGrg;B^iS7iot=gTjfz~!2VoU(+hJ^4fyzAGW8qpsRMA0GA zAt1|}5?aW*38dtZ=lIo104E$ji-DMth9!Whn#hc~sjUZJXJPk{f5$VACfZnkn5@isLjT0!3 zS!tB^hE0aljO#M6-|`6#IIF>9G2Q%pZt&wi(>`Ut2K@Cgrpon_ZSND{FE4uEEOXz4 z(#u7ETArEuLJD@fB9=27SP{$g%~?IiN?bWt77)-WW{*7pTP?nIP}1HD)OGyHShIsY zi}Q*m-d}5SzYI!cSbqi#LeKBl=aUIoh%pHQFdZ=Xp`+btns8g4!`@-g!#z!f2lasw z%@RnBc*SznNnNQk;8Z3=+mZ41eM#^Rd3z>Iys9J4A#GFxaf`{uK=8>TzC(5^c0mFS zyNP89u*o_@`mcl%;0_|W!OPwo?h^9`SI;`6d}Z}E-%5A7VS`cDR)Dt4okjevrpsI>D?a8 zzJc*b2i4EA|DTw;|$1q2w`+D!dM1g zvTBpY$ES|mO$ANt^m@O2pMON)k;~|G9%NyD1g+d zCY!0N1Q~zO3fNe&3t*K)+avL`znS1v2qYh8ht($mSKSFaXOn;o>5#czszhdyfz3vA zVzeY4Ml0N$>OxYT`Ji#vnCkj`IUtv+Pa^-Cc>#Yb-H`P0t<%x_4aQuR(q&Bd<(+kC zdZG};-)mkJ{~m2pu^V3R{sQ=`FjuIfJ!SX?t%?!;rwonm{|H)%I2hYI8`~JV{{xXY2qX)!H>0x76G!eygZgHi4TS8hVI1-BqIVsi zfBv8sMf_HeK-$Y}RU1@SXV8yP=ham!U%w!)j-%HySH@61^Xl)S4+i({TUgN=iB|%F zGCo@~BeOUS546+qxOI#;28NGoT(U||bc(_u_>&?`;!NB0PDCY}@#>nx>CX z66kV*%1Pk4yLTgqC(&;E*Mo4WSs<(UzRj!e_kX0StCsd+-(URuOX>U5|2&{?WbA0@ zU~c!9xhEaJfuoayzM<2H(^Q{`D@cCndTJIoVkz? z{AE$vPrEj(P>!B8CpU&rH%TDSxHaBNo3*7~e?hd{q+)t4&z5)OWXH@qCn8EYJL5L` zR#t9$b6{}S5S+<-#c`Ua_4&i+IKxxs^W(kv{fCF%K+Ml>zuzKSeK~%)=!9+@peX7D zItY7p@Eim|f#~u#7SPoMbgcOT?TG#8LxW8@J7sbnP2QS#0}i=Y8eV#U~YquSu)Zc7D}ZE`bryb*$Nv zhasgkc7EX#^R%oVQKO?I{1k4P{JDy+9qeRu_j!l(HQbxEt%?tl0}IsEo#XUng;Bka z;8Atvj{U}F)DFIJo+#^Zbz;bvG{a7>l&&L$<{YtVEX>B%?WhY@V(H8#v(KpVN4Bca z>3vcbhHR0}g3U0+CA!*Oqte}c&Y7?YK-vjL+tr-umVIzuadLZ$XMf8*K+gLSrJo$SJ zPNgY>Sd>$QrFmG#N@ilEVnqFNZZ*}4y(}n>Ema1%Py+3_JJKlOY6`c^S^DU_yjuYD z&_r-Yg^bXPv9I=P$JXg+k$*r+s$EdF>mKza)UIz)2xY-eFtR7mNKJ~+>f_^AIfBB2 z`TB^sXW!fNaGsmc7606WJ;b6r^FDvn0F~BG;hu5ZaqK$G-+lX~mhq&yO10M+a18p% z!_#DrL$D!6`U}jsbI9nN!)MhS2(sN7s1X9u{jTOr(%9NqX zSC-iZYL}D%rXj`x+>d8hZ2t*%L#|8p@nQa}S2dN5uF{lsBu3zv=&B z$%!<%u`Sa7oI6b_Bn~^1DJf(`e&gNd(S4+8cIlQu&ncE{b_spcX5j|AO01zdpW5_f zO^#(IVY@Hnyewv6g+_yrks%5V72xF$r~?f@uM9_EU1R2rNl|^J zcd4qyd1AbS!W(4qTx!8aePle|nALrDx67@jzh}057OyCi4bm3Q*t2!m{rIn8{6ASa zDb8adQe;y*9CN^?GzUe291DHe7M_k`x^P+5Jngchq&kASq<>h9%&G3V7U=Lrn;EqY?0+((;o6rHWD^&Q+* z^sStY|KVn=qUorpjQlAR&rD_xX`WN~>nA{=xdsGUbs->4?#vo0a|3vuLmGCPqN90y zyv9vbSWXnv6#JA?N7o6vBJcq60*2@?o9~bPcs}7jOS}w~)?skmMwgG3oy$7g8lII* zuYaoXd_ilFl0R0$THtuGkr=2Aga+&pWJB3^hsC)s2Pyb^nS8jzkA=8s`rsKTn*z+l z5sL6k>5qiRqLo9=Yn&p&-#VfiDll-=zd4$uPEuzh;i~+>mHFgYiaH%TgAHh=EWl7E zTa0r=CS7`mb^YE9FdE%KZ$Pb9y{vUlA+fY+S$IoZFDFmg&0jM+Qz;@zrfxFXj3;T* zDFMu_j6)4#k`Dq5`MFKwW8X^6FkN=kOL*afYa(vFzqR6UslX~KIFu$L(q0XR%+iu( ze$w(2I*{3~o-`?{@C#buC*y@j5$;t!ocOMnZ0(;wP|xcxe{owz-`zc(Guynfj3NW(}kmiL6cu~cZ&BHOw{ zp}jz^PNB+gFYV~ta_!{(Fl?(2ye0x72&>j3(~LVx$XJP%S-RbRjnRf96L7&D{t;|* z`+m=nI65Z0Z-HCsDD&mIDLttKWq;5_<0(GdG&if0-&0znIOiYl?qDBm$cS6%>cW-A zhNQv|BQRqAr^|{^TdJ-{5Y%*}KR3DQIl$A?_)qqEKrcNCY>cK!Pc8wFo|IILCW})* zvdj4#MoGiVo81?VtKs;S0aJIfro6wWJzj@eu(erW5Ix@sityH^Rv-L<^!xXA-yS z@*Fq?o8L04Fl-)T*FRM7gBIDvJUY#K3F5dTg5CD$DegVEBSe1`LTF2y3#=3}=U&LC z#kg<>G|8F^Xqh>#jWy&O5xBY$ZudJj3Y4i}1S{?Qa?HV2i$AT{)2d%_Zz*$BRX$!D zoGLEkytkAaT=h1Nb<8Wf?<$M!3@3_Kb>7mo-%@s2I=yHE@vi+k0QBwL+ty}jv8=s! zTHN8efE<2ha|!LZH}X87a@(lC?CyJJ;I3MI(%r$jNb%?E+ooBV+yR&WMV=$aCeI_^ zDbOCOq7@d>5}3%eB7sc|UA8Hb2bu>O*l|_8>oTblQbnYEqj=g2(zGnxbWQ?%ON)7% zMYz2OU(s+%y#9)R%62F1X&!$8SDTs{Kzr{5vrN=04SPRxTJ_i~P4P|2FVO{8>8OVX zLGuFzo0#7$G1*~k|3qTmSA_jE#a^9$&C%6^*QFejh7DvqH`ulP*M3 zo0?s7HXvPr3(f-D6r6Tc6SSz|*uk?fA>1;lZ@pSKRl6{)@4e~}ZFoDa$;zJ8(_x%% zxXNs6Zchz!pEMaoqESC!4B8) z1)dG9V@;|Rn3Gq}J}AWlXUkMSs!Y{WK-lf>Zw+V2NU;*lZ*&z1>VFF8GXH-Ay0o*^ zcNY6^<3oQB?*EpodPh&n05ZT27l%-1hlO?hLTi~pkH#hN0b#a}&KhD=muRAKf$CMg z-vN4&8(J+?z0B=S9i902y8m7;r>ze(HVd081H(_+f;7Qw(VToyO4`qQ|R1$~1#pXFCG@4v6{B z_MhD;b1H@<2bhKMR|Ywf{IFS+c+r4w85^-o1DXq4a;qse5x)ZdlFuMyR$313dfcDBQGY$>nzF+|!SKJ=g9!0Q!)dCm+-%GI`cxE{g@CmQI@TQ;ETEt%}Ou|RQ$BGdxH9F z*L~Ap&ZhWQqTBv2YIOg+>ze*ci^Okg>R@d8J=OL1W%>7A_*?n*@2AXdO#eS8|84ae zm8NBp_>n)0+AjsPa{z_I@hkHhH1z~Keq%xe04v`9iaQC_=Q2-jXm4p34i){dUp5;k z57lakAt%QD7@XuAdogLI5XlSWXIoAE_RI9T_S~LYx83IR0;UIGf`CC=%iYUs5Mf3> zuo}rN(N7>agql8TB-wp!I^W33Hr89l;55-1hHF8hzSR&MK;VhU4OXShD!KVd4a!~f zr>Ds)h>B#nJjE+gQ(0fbrcHg`R$sdfbIl zR1f39eHdX&D)PMxfB6k6Zl0#oClKdTQ3kOvGI>1rV}Oy5N;14!ls3OQ0sa}YL&RwA zb&gW^*d&q*<^E`_tj4djPaD!sP;<%KC>x$ceoX$*hXqk;6zvEjF5ITSejtNp5aW&K z)jqT|AIgxEbEb5knGtgcbN_QLHt7 zg`h16C&}Lmrc(uQQn7ESMRt3VC)Fb^{ty2z0_ z8IYa~7*Jt z=u`4%ybwLC2&U0F^}{E|vN6W8zIid0@+0!4rUH-;{AtLn6e6)-S$Vgp_RhsGAZL~X ziJ5z*C2SG1-UH1sNf{!ioAFsiHiF778pv<4_>j{feU4@qAe^g`1uIkqt14ndSR`h% zDLv}Y@^8$uBXb%NR&ChQ0`a+U1qyKDrvr5eMbgxGN0KAnPox7&`75L@(8vAuDH6$H zitG5Y?s0tIX(|{vuY28i#W!_8|2xwC_i3xd|D!+9-^+1TODp7Ml+UWpbA8>H&MY}L zy|jj>s(w^6BvdT_TTp|#CIEk=_ESS{+$Dck*NjzlG@wvHJn{VkaXfKw;5Vi5?1DnX zPy%vm<>IgfKJzc7#5IY;yZp)NvdRT9<@M{SDjdNiw^;-8X&%R`)?=>Y4ae!u&q-h1 zFOFZ6FIj#Wcz{uOnIn?4bgdYCSAP3M&%)wSqoL~JQIZYNv$i27e`c z64OOjWBd@>XXy}nePNC$D3hu3V)rxP*9sZ@S$!Rc=r|{l2B)oCwz{j=?o;3r9u)IY zlJ#XX&9H+>G0blq@o|~K26O3bW`nlGQ9Ebqe2#ccLj^uo{R5}OC^I#NK1beg&$eKrQ$h2WZ7T3k>;;k;wy=Y2c*1A9EF^+hX0 zaMGP|!kv|>r*Q7*56t3Z#6}0ak7wL@7}|UekZluTWl*Ks* zz)*s**+EG(GATyfMxdMSsM1J$E!TjEJq0IBfC13gI!VdjZ+nl$&9e zew=5)MjUU>*At>}*}~=ukpwIyC|b(d4?3i z;ZpJRULtNtMQ1gSR*ljxLfnra0ML;DX_BX@Z{^#W+m;w|232w-O=|1r&g&*92g=rmNC_BlsVQ#l`+{!&q@C-gXVcM+VFtTU59tu36tLa9jEUkO66D)T!ll6 z@KITFj>W2|J~_Jn@ac7$R)T$mijwHNGPd4UJDgCen*cM(U7 zFtFJ|7GfQD(Yu9z6xet+Xu zKiL(2nkaWC5T7|i<;DQs)Q&YI*-j>>J&qkY18$G&rRwLN3UIH<6{?lSc#(nNzNmV& z6;jnmgF*k5e?PYld)m4UxEb|kbZxH}=cZ-xUEM9+b{aR)W#~Yc5aBK_qLZbE3&cU2 zf8S8gk#?Opi zhTBe8w6YhI^#F^C{dGsEZBNZtv+};;8GOkUFaHXIsK*S$$at4qODl+LanvJcASu~U{pnbii9 z?=vvW;2Ff;z%(g>z{Of`elF4M5X}yTU*|XH`%`hb5jbfD;}X7UIEA#KoTMks!WkBX_{6N)NOpxS z$)END@}?b>2+{37oeX|=O$fzmwn9So#xoS%Lvb<1X1FtYM2~8hr*p4 z##%pG6#28d2_n?Uiejr$syAo}B~uzXmy60$&~#!^zs6m-BwHG(xG=My3-vX><~5xu zoC6W-_6_`5`}n*rN${2gt$l#PERJidS}wk^E*5(z2V&7U>RulCWU2Bnfk&@|Vcwbt z3~Yjjd*+0(vxZ%69MW2$Zia;8oS^WWpmEvDUG$}#1k$Z1G+Yg$n^6$k7%e_#w=^N5 zQXU2_FA{utQCktXoa7c1ZRr~)>-7|iRdiGR!ihid>R8?i6sPUM{Dg{%gPP6f(+kt8 zRFn0EG&?PnaF%BpFHz6au<@3?f36u{eIY)`5B%!9mm1vp`kVGtGAD;|+xJ-1_Wwx4 zmHwA921R!pLo)|k8*>k1qyHwcu1r?9Ll#CK?k4p#PK^lx21bApje;5VBggOkf#_g^ zh);~3V93aIA(N5`!Bo${k8lep+W{|oBSJ&7GpMFPqI{#5DEoF)-t}5$%d6(IePP6O zdMT`Up#OF6o%!keC;jv)bxQWj>lx@rMIc?i99Xo7J_)zTtbN?DxJ(Q;zeC)CcwDhq z7O8vCfqI-Gaj|$7k$ctwNF18D4xxMM0rV&padljW$Q|b>7O|=L7BPqD9qQ;h@pVjx z?+(uT;|UA*o%;4%bE<#iK1A`hTex@NUT$XT%@F* zjF~W2F|Yf1(=N@zHV5$Kxhw}ydOi(2agrj1^mH89Vz<7!FSAft`vt>!4HF66hAbHlh;Hs0vIk-jQx87 zEe0?o$5iTsaTbjThhGPewADGx^{Wm%rUpq}4WL25$_K29IpP+z`<1vNS81Z%e;*}U zC{9M4sl^u(My&>?#`fLbhC+|$J7^_GDseA|xnd|eDL2)Gc`#F*v%e-bcG+|a_LuE3 zFJAV;7GcegQM_=$CL~=t*;MW_os3M2h?)QwmpKO2>uZ!%t+{mPM$Y}=wD9q>D=E1w z-(bl`9tMRqjG zFmV<+KjhQlCy;Ec=d9YOuYaaZTTIp%VXa5KJpJ(&<2XKHqiZ)l%iC;FE@Jz5$VO~d zuu092y(Ff`ui_^?L)>f9qU%>#Bkc#K*Z$oW;1bgiUlUss=M>`LK z4p`0LGi7Ga?nfrrSw947(;&ca*p`E`T<{dgqmc!UQ7hzy)7jw|$>0z_(tu7;{C1Ae zQUsIP?{#uph0S2^kNgGhVRJe9(iH_9%V)I4(xr1-rOl%5jzj~FTyouMZFvcpUBM?2 zZFxzUT_GopJ6jQlJbO&K|zy2jx;RAT&I|#!kZxnwS#OoTr%O+!o)_iAN1xawTPEJp^gV!4^z~rOY z*{oLo1xxvAdc)-5L*an-zC*CRey(59rW?`_Bl@Ns;`B43Aw={IhNl~ipHuCZlURro zR`f$Kyf`Wm%~9;9(6p{_Ob}!YGQk`o?x`(-f4UGI148m`E_A83ggwM$vyXk$FfMpSGCuPIQvlYGP#<$)q zOXi=_{g2`Bo5*G@UF>$wjaXo+y1LjM9v}!*dI-2s0KVfJ<-k-oYTz&7t;^WU4%lcZ zkN_^|s|xtF%u4hyl&kbgwL~*LPI#6?5gyU`2z=M`GEOM#F&-6qL0!K!e44A_aao5q zb%sAd{;G_xJ>W{LzX|pE$p5)A{%3Zjz`wN5sT!M`nmHL83A=pvasDQ|_-_@lbM&-C z|4;a#?$X9}6{syQkWTh*!At}N0`8yP9l_A_5Mg+*pxt!7 z?$p;8FHf+Vfj&JOJCPI%vaZA&V8=%3rcq~slxp2dTmhZL$X*V8R;4+o66><2rni`P zc8AxB)^We9rR@ZE`}$-V@Mh&pHCO{CV@(ucA$tM>O?xEb8yPIkV|(G^k7WLq6N-yM zr;mp^RV;AVFT}@V4W9_kN1e=<_qE2rq}`XXfS>5O&9fV99Ia$#+OivQ zFk%`-jWTF$VKRnsXg+|e=$0@0VxDhx#{3vb^4ouVA{dE95%ABKIn7Mgv3U8Mnhu|o z*gagvC(rx(NIl;5{PB+il4T%E3YDhwy;Coh@Y4klV9Jg%?hE=IJW&|EN+P4S0cJhx zgo4*V>U?Dn)f$a6%(cQQLw{|+^bXaU$G_24B>u4GGJP+UDDdm5T(W&G+Pk{&ys7GZ>8hSa-F$q?{aRh& zqL})W4tUdX%KJI%o$oly^Qx8ic|3U`xf=dMJ0? z*~W+B5961thd=dp+sR$Nu}5HA?Nj|9vV+}w+uW#d$xj?KkXh1d|wBhw_7kpuPE`tAyM-TBc6MJhj#(^ z>vS0WJ*6qWyTrH0z<6; z4vzw+6iEADBH8I$leP1Q_m6ZSue@>m(xYyopVu7+&Rj1I`7g1fF*=9^3CsjVs)%~K zVpi~5urS?^$6M-`k=bRGP+hRpL5KT2F{{+jnITc5C-gfdOgup7=!Tb=LO{Q5mg4e* zIjpFYi2TXu>E!uK5_F>WTe3o3(M8=5<`L-($B2g@qzeJa+_@g5#%%;;pHlLTuj@JF z`;Yw}Q9q>3Y|J{Oqygpenp1%d%k)gjdt--*3{X9EX>p7x21%9g0GrQ6ACd~PFfD35 zCi@K{&M-2yDRz(Od(v^Z+~lYqi-#T3Q`y`O`qYWoqDkWHiHMLMX61!~>92UBw zRwcD1zK2L$XF%mqmmN9B^D+8?PeMsnB~A23>Gy9^vJPmfDT8VaZ(O2I8zZr2wi-rt z&6@sXCQ6>v00lo@)Hri@s=$jcF*>M7xE+iQo+mxH)V9n(KbgZ z?fQ{VPo03Tr1mA%4aSYZhTxoGV@%>Cz6%B98L2J7BLMxm6-dUEjy5(BQ5CrRm zjM{;PIleKD)Hu+{Ft{RKzaAd!Dwn%HhHkh_Sv`O^})O+KG>Z)3-z z?06*^s)ECJo_wKdmU9o%%qJAeujVChcDrcTd@W};{ssB?T}iWZ1dD|`D)OaVuOr98R+8MCNLM%%he{kvkcbfYP7Lds|lkg zq8vyGI8wwMT%N5qtYqKDn{)LN3sXumdbj=rgp$;B9NSt=lG8^9z#RutH|>bQ zsl1ErNG@U|yHlz&fNK3|0z!ZH>7-M#KCUj+Mq} zd{G0hqn8EdgG!`U3eBmLo9y#K0HmhY)7O7UNtfxmcROK5y(}%w1op4|<7d8EZO`?K z(uT=umiA>8?$FAUWxX?nMt4eut$wq7_3Dwk4eDAL&IicT9_{_n=4pxNRrI^~$?n>DQ+U3GDr;B3piM}2m|J1UGs^Afx3KRX(EJBO@@X!b z99C9O+)NhQj)L>nieLKL3d4>?@A#t#NHS>R3;Wsax>;YoTK}^z7?&Oy8fmj#E8~Qr zg4PgrZ}CdY_Go(^qW49?wvpxYr5Pu=+{Mtrto%0-;UOcwW)8S&0}zv(nN4|cV*X||BD zqIQeTq2!K%Su=(npOpt~b@SRrS8|Ith9f&RD!q1u>Rpx`Js%$Oqx<{$tv;`d*O0t_ zbPX9WBN{hrm~s=uXN*t}ag~ov5QZ)#V}JH@Z~qiz2P|aQX~|AYJz%%L9~%w|_g)45 zPRP=gw#~TUg6!~T@1hsNBUl7Nx1a*2J3)w8KcB0x;=5M>!)kSi9p5LIW z9Ou}RaLX)) zJ|8BZ$R-^hj`yb^k-&!7Fxn=Ik8K6SeqdL z7J?Z|go2kX=}Wu(8qvdMK)ixjwe>eadby*+YsS zlO%9Lp0+PCM=kq2kk#;VSBqPe)kal=%3EYPLH~=jcZ{(u(6WW=lx_2rZQHhO+qP}n zwr!iIY}?j(b^G3zba(RIq`%k6PWF$TtRFjbO^h+-m}n{Dwr%AxePD9 zC_b}O76aZP{+-e?QRIy5^dp0WZ!qSWb~8*6ZCg}~n^(-sZ#Z#g)q97X(NmQ*eIAfi zy?q`~RT_FgES^!T_oh{Z=;UfW35BRmP+U!Tj%O-V1wd9$)@>H^3a`RF`BO* zzj1^DLZoDs9=t$4q-4YXw4M~^>{PdC^BQyxy(8_-E#4+&L-xj8<@$|!Q+#5!yx0+m zV_N18NXPDzNm>$xNuR+>S|bjXH02hnK)5Qd_b)7b90_gm249QT`yb(=dQR0M=3WpF zNtz13;YycFp4LkNLo3oerMn$Li5~BMUylJ3P`|=O4Uz zn=o260%;L{_Ou_+yfp@Dk8MrdQO%SeD!8{QPX%vDU*E2g3qi%BCcT!*7DnX+NXQ!E zW>Yy>8E@Aor_o&i?UAHArY9$)p7}JYWb8)_Iyh8%*8?B^oT$5Dew>w>%B7W<^7jhs znHr7&@owyvwIH+lg9QZASK*bv!k+0}KZas~TV~P2Y6jZH7<1c&)VB6(n_bkcHp%bA z+3$rq} zI{LM)|NNHfSIW`1F>*^lynBSb`xQ>u)dy^2@7Fqsu$?N=2gTMGN#ErL;bz#l+kQw} z*>dee17@^kd>?a<=L^_eTJQVgoZWnhg1vf>vQ55;njQ3Qp+E01ZdfDOWrirJeMay) z`C}uh>-FJ2!tS-EW5xOc(Pi z3DFs>%ZDoUeMQ|gy+-jTl{T8&8>fG66dM+zJ{HZ!={x|fo%lQbS>E`yHl3m{V9B=m z0+Jo5UwGxA9SPUAg_Lsj{84jH4SB}h@aYGpBKq1w3g*9wlrs9K=1Ie?Mb6(z={LFIwMX5l7(< z8p9>EHiITo{RJx>{6}b{IWdwG zG!wKn{MFJiVjLeD2mViZjDeNHI--U#Vey1EkruY#Z9bo@b0A?NF&2j~lxN2|D_3MaqQ3JR|&mecS%AS5x;$a8NWdo?`jd!M~BiU zvJ%X9NlFA8f=uWn5lC|K_*kMJ8Eg<1#yvPEJiuJVE#|GI=5tCCk&o?~(~DZns!7O9 zV8=+l|3lovKO{@f{DbBA{piyFzwsR2|CgBkzX%SLR@R^7zdN?LJ5#spzXsq*_`HBY zKmmu*D~LoO;29xe$0!rj#*JS6=m)3R9{7ixS-p!)Hhz|0y)iVan^o4$Dy3oM3=NwL zSiIX^tUEO|Ki020E4Qv}T01p8XR>2$Lm(jJGj?cSIA3PEPd;Z4avW(&zaLk{0bmLy z+@0a?bHSQlyRbNK%dkf2s|`ektH3CFcKwlJ?`BE4Rwoum?}T%5oEC3^6?F~H#Y=Jw z&L^d~rw6fRbMJQ5xki^%-L8_rbca{c{$RuDo;2Iu-b&-BHeYmB?75L%~c~6MAd6bm5|>De7&`J5Ac{~U9_O`fX9 z&?1 z@!B2n7tzlTHEQ_LNRlZ@;*1>SFZHgqBu0FF976c02PskqpO1vBh`_uLcX~l{k6xwU zDvh0vBv%Tmjk}39u_c| zGw@5hn>%o0J;QaOHhbmKrcf7IAfa^!{c66@V>OHv#A5wmJpNsd02%ks#o%2%J)(+i znaIjYELObPSIpFLbddUNf7jR4C`6+?Z&B&MxY$6L)alc>oR#mF3^&HI;gEW*S{bkX zY-F$jw+MsLDPbbuMXKKPB|&}s`;6SlC;t9khdCF~S|atBpGI0N+*Op+P;`=C11Z_= zCUUrN)HGmA#ktQfPf4#Zms+#fp~soKdT);g)~485w3gAq!x(t>;N#ABO*j7Vdc-*K0)PbU-p}>U#49#V+OYt z60916B4T~=&7$k0?EMI|TOu_|=FI4a&Z9ipO+`C}9#%u>#NE!@;tGo;N0Etnxo3V^ zX{6x}@T*1qV22T(^FF_GHf4Ln#^BdVLQji4rSKwx473L?st1u-S-4q*ur!~96yOr+ zGG04J$2AN+e2Gx6s8JVnfEL(iyRj2|MhoQHqg+f(U4nyG`Im zk(_{Psw#9;(xhofb5bxOW|X|LP=D6t#Zgzp&a{orj*S?Y*l+wSo+}fRuP{rn(w30s z<vjqkI2gIx6ZDH@OuqZu}F z!E_hx0YX=8$6P9OTw9$}D@du%gd+Z$uG?xOO5J4aPs=9_JyV&=wD?sq-;&F*>TOMOU2MXygcX07Oub)99~{3N|I2`KwmR9R(UX4jvpis<2z)7^0#vDuU$9a z6MH4)?Q!GHRT?c&JBexghufz;Vb&}A3DD+%kKQV8j+Qpj2ol`t=57K7wmjjdG5MY%sFC1iArdlh#m^ZuuyFz5%sD_l|tbmzI`7|UhsGew>q0Oki8@- zi73M47@|pc673|*VGre@Gtz5S#~>MPaiNhz8q!Mey!Q2NLP*I>yZl^5d$xBp{wN-wN(JyA_U3GIW@KL{|tU`9)MmD?p97%oOe8LiJ1#AJVq6HuGn~|Y09m+ADX&6OO=!<=O5z_ZOL}D zLs1P-w2dWPx-|}Hu*d~X@nGu^}$}tXkr>xan^RUv2$K0nQwF~2|W6Cao?rSgq zS>ar5cD9pL)it%8-EH=s&hGw6W&PjB&pj;uC5%|U5X)F-X~oPuG_@fVA6_=UyqCIL zPi%Id2^vRou;dKU=TNwn+6N19@`XU^%f%YY>DH9QSWvteDW)>z>u*hl5(Pi66K5eT#41x@ zZ{OG^8VR_T#P4|c#Vy?$cD#PtE>A~w`IIge&a-eN@o`I?vPDL&49Jmzd3!(>0(Z`e zvc#R~7eUaf=p3#ft^^A#N%Ta-H=7i6iAuyhX1Laiq+#;Z(%E<$%-Uw5C%FU_dwh#} z6u_0f;6JB)r1RRly-t@!?yMeF?zGb%4aZ+(hZRyz_^MWK#U9kYg%MP}N+oBSBBo{A zi|8flgjPboYWNU_psjKfIYSR~V~{a-Ku~T%WRg<0L-nHo5=P0c^l-QA0{_Z2a>%(u zKO5R*`8n=I4W@@DyGyx(MTs?NnORU>Ubil#3`+Dku zx-&P<0WvSL-LQ3iYTIMKeNwZ<2z=LMiO5eE-f{!s`C9$LP2*sX+y_9YERj#(NBwQp zM=EwsDn1Do7fYVBtJnr0DleSej0=~Kkt+-zYlOdJgTE6)CXaDw$fUq(OwgN4by#GJ zLkOpoaOlSdyTh^2Z+p_;zg}gi{OO`Hbn~0pVV+x@E0@617ej~Zr*;oga0%jirx2X5 zEA3ONg(@O$85@x&nB-S7UQHm6hDs}7PW?^#8jPU3f!h+krpZvjC~ z@B4+cYNCHZzuK45zt}ov>J`F5y8Xj=Sll;iPD2<#1Kp7!_5pVv;HHM)SU$ zRh2Q40qyGUE5xH!z$ekhw@=nYgsjnlETJwDQ>E!(WNy{%*9B$i-~{iizPvyMkwMHq zsGGjLfZDuVT~fu1$cyHUL>2i&QIEFw3AY0y8@}avvPH(}4+R#pSAf_7ZfV_EHilQA z4~oVs?}N5PpmlH8{-smKYzzZe%C5xB&c0resnq*$sBO213L7Q5_r&>S5uRN(U=Gai zKDI&VF=o+ChTv@mzoH+A-iKlU#}au_FAQxEx*BPNkicPESS9L4osE<-13@W(STZA3 zUwpO7FaNO8G%Jo_5Az+;P@Q3nu={&k;$w~A%S6v}nu@%+!kujN`-h=<(NODB2#H(b zLZ#J48M$|9Kfoag6=aa@MQTldY18>0#wdsJ zRBiyf;V(byn9!O9p@=n9K9)djK-}lPjo7dccf+$7!cj*nT2`oWiH8!n!BF&nGO2gS z<+}nPUT}^*B(o=yglHXKl7`-vo=WQ{VN7h7$&0zv`71Q@R;Zq*^~#Bq1m)ZNyK#lu zz?8F>dy#Hf`OtNyC)ARSlZ($aibwjHTnc+IbL{zT(X5Pd?Jsk`L%>N8qok zf|#5d+TMb?)`)55F&ax6)St6p^{#Z&Vy4XDBWaf!5>+XA=cZ!}Lgt^?Lt1%ZVW4)!pj=QrVYaEs|yV|hD9jS4XM(T_x$LGY-DE~~@wMoH(oW|p(?%4x7fmT3DgEHrdCuBOdX zWFz_lD0gKgBR&)piA}^sBPt#!l!WH)lKcf554L%?iTk9rRj`hx$*sKPQF>L*t;`4w zQMcj%R1G(Tq+!3|IYd;f?LJgx{2j4&u#duURcW-olb_O)8nL6fMig7|fJ2n^unP*c z{*Mn5rlNcYAd7f+E*V(1dMMl+M6#bRJRU>g!-{ioeM0wutk2 zvm!}F^07|FtC9rzu#f0S+(+42fI(O<~FT;G-q(QQua>Quz|(Re@2TO_V%DcOn@p`-28Hegsw%`((3Y ziscE_%8dNtWX+$m^-^QxU3o8HJYrRfPghDtl2P-KUvf4iaa=ae93{KS)v}`0uH4P+ z^`%Sw#Y=>`=6v-IdgXb%>$WjD7yyWnghL%5|y-h0-hb`@WVMi?di%jV1I z#vi>-GSeM<7#%xwd%WMFcPUa9P6v~jsHD!IbP=MN?udtFDVYjsujlCOru$$(y;V9G zvP{X4&u3prTCuNLs-NakZ5kCmk|}sh!f4%L`s1o4RX1;1a>4&1`0m3yHeIi6x=(qR zf8t`mX)@@IQGw-KJ;-@n7pCIuPiI^}`i}4M|2D&ce(E@3rQY6ikyLA0vGKIgn~z^^ zLJ8t(!X&8kUV}I)sq?z#X~hNKLA4>np?^1goIisUw6c^Ce=i0O339?Rh_uSrpj5$7 z3nfwCLipiw;uQ_WT8cGOtuZLZT3zy2#f3nokXb6Qnk}wgDmsa#JJ4E|g9$I^9w;f& zd&aYCD%e{1bvg)HyXn+Wx(d-JDxJABq(HkFp^^T^`NeQ&Py>lJ2Df|c9dM_yVHfQc>%_jxxo0iVYAXIoo(9U3G00Dtz+LT`AiTtqbk z1qH_=jbYgX2QBi5p>l2A&m_A0&U^}1c z%l*s+Hto}!N?s^r?mfqZ)Uk|boQ1ECY)NbQi_~6%oPa5SD|^lkp)@=)ap8eYP>fVc zdu#C_rYEH0aN%|6h=AD2hLAoDeVJE)7K?jkJEVTHI3y}RDO+&iLw$|TVVxYg$*bs6 zU&+{9Rz18yH!LZcP9nnqp+m@{37ot+96UPS1&3WhyGS{(i)jR+*z80o>4AY{e1vdo z)GVhcnMZ4M-Xh|8K}~9(G7OhHj7j$f?0!{j_F0e^guCDv1%ho@_XKbau)rHp``H6R+{a)vp+Ws3#8`!QxNafGD`#QEA%~)) z{9A(>&}}RPFadLni1nTG=27a9_Hhl3g>pi=!=m#Di0NpT(lrx3LQE#jd^zr|(!9Z4 z=;He$xpU##L>esp4^2Z>XkCF~~Shb?FQlhD9vlM)?5RBOw3;givZ2N*D-UUykf9EBuO#d2k1R6XEn!yXo~o z)XDotZS4*Kl|Ftbbj|4`Z!W2z?l=7}cCBG%pcR-+y}27n;=<6M?EMvRV>fwJVOuTg zuk@wzLiT6XXl~s{mJZpfd}uMgl{f&V=LnI}`UBRL)%~}jXYNvgKQzXDr9KfiuDGss z7dE1;OEMz=#*seRDK>P=6_|Gi{LvhiXK00D$*(mc`*N$jdAgqNVZP(y)Q6Pp6Xbf2jO%H|$ ze7u{%%?{pzf>LB=vdk70MKKMWf_WG ze@*E99gSV|+NPvO**iMpQ9NR41GxfxIH7xzY*6p-V_#K$GaSLa2?FSM+x_^0bm16| z2jqOPv;b5_$A?C!OUBjGq2VHBQnaF-eWpFf4}EtjQt<}1K*R-PkCYjb@@+XGtpaU< ziU!Sq<5y|wUthc>I+T{WdA%X=JA%b3%j0grQpT=u!QryjoI1R?VPlF2MLYdcy`xg^ zf&|Aj<|PbZ2J39G4pb>~AX-J>NH27PSt6D=jX_QZl;X>hZBm^nV$=&!UyNl1bK?uF z1@#I2(hc%cpP>Ipp{KzT_%uJU>ilnGmGghzz(^Y#{hTTNXITDGkyJ$DhyMl@0362z z@7XCR^Y@D+=#fJfpA!o+gTE_a4k8Zi}gwg5pmKBjW zkd`*lSbJnuO)+LktGS4rJaA>Bc&twxg$3pu$hgRn(!}tP-kWRAaNdW{S=;a|lMZJc z9@7m5+Xa?HSXLTOMlrSb@5XXVLM;$j;?;b>n}Uzr#}E;%XZrBS8a20>LwZi_zIFXx zxLLmPkXSX>=U9N>N?skT{7r6YZt_SZTY{a*N$|sOCjz?9k!D#*pc7oFwP0DwDG56o zKCChVOWDvc7@}MK#vX9%5=zH!hnd~=B|SQGNNEM!B>9DT?f28gXZACDA$ zh86qQAd9d{YD$j74Z~Z3TV+-y6gg^VR}K~WNLe=dA$aBH2S$ypiUm4Nt^Y7l^+5r25_Bz3q8oZH(3s-XxNU%+-KxR=VY%6JFs45@iR{QEpJ=vL79D@ zT3p%lLS>5O1jK$@c$$}>{Fsn_m@A=!i3#dQ&6PQIcgKUcRUpvh2QwiL#1yDN@K3`o zMD4*(b2GWjd%g#z%H1q@!bSfYrdn9(^-Hlh1&&Unak7AlYOc+<5!#?w3+3jiPLe=1oiASkzBpM3u+S)%wgqVkkW zFa^!bIgF!@v+XO6Ul%X2xd6*^H3LHmC@@-$c3T55Aq$4(M$bw8&R?uvxt{o{g0_^B zMVKxhq~*`Bf$a!zz<~#n#5&Ri+VNHoTXAXbys&Od3AwMk+u0y!lC+kyQr2S%rN^l%~rQ2S&N%IET9r~auXTo0fGFo^6khdsB5HP2lu z1Q05z*t!^o#?YIm;b>*!%JB=hA4t%M?Z1lbcNQsbu_ z#!4C0wjxN4-ldL<*+(HZXMb8LC4Tf$qXz|}LN_@91i2JQ!Hy6r-N*96$gJV?z*rQN(5;#qwklBXDgd$yJ9G?~(+ zhTg(kj1=#%;FLo9c6+-p_ELRVSPjqqR6^3sBt0)beJ`Q$*CHG|1%o2z!_$2(nnMhP z4zV|Mr`lZxdy=>9A;5e@d)20Mf|>=Z^92hgROgz>v-8-Db-ksp zX+b|HeZ1}Ho8{Q^knL#mywdCY3ekt#mBP;%QxZQSc7N5I=i}f^HK@-NNDw1=78FCz zjyJt)oK)nb09$$}w@hDCNKi-I1T^YYdiC4M%eF!Z8J-kmUBsI?n^h9Vx7#!K*!^($?TX0+xcj5 zQ?1cV4W^qQz>i5EIqEc3Da&mdHJ@sco!|_N=^ILTL8UgcP?cS+@GRj@__S>S{mnaA z2<#~vA=v_{H-ANEu0@nFY~R5K_uvW+8K@$hS;)(bE8(D2>WPhg0>Kuo4QMy5=0XV0 zs?PX`G+?vM@-h%}$+ZMbMguDkmlidOajbzoRRZM*mXQsH$*rL*Y4A;F>srj|MSuP8$=>^tKL5+U5jSyA`o3TogeG}~#C%;is&r+Y{Fg+yU|)uNppE81y9q~B<7A;{ zq8m2-L$xUL!~CdfTSCTifE+ucvtn@17h}hHrdu)>^wkhpppAL!U4Rg$EM_`?ai9}A z;<}eTj2|8EE=m@w-7iK^le-EgFS)$?-4>DK0W!Mk)4yd1r%C+C*u8Y+m}~Bp^BRFK zPlh|xuL8x_9fbVNG?m?Jpn#&de9l=H2^Z_ij@(e1$RsO|6~P6%s&0rfYV?%RIT`WU zwH8D+h&GQqE9Tq|T1U1KfSseeD3n0q)xh^oHM;kR%)|Q(w)Z*o-34JsZm?u0wvU_Lf4Z%ST^DDWX;X_Zdb0jC6 zbGE;eFGwFZgEP&>)1r*6;SY?81yE<^9@ms>J~C=PZlP!2=JI>T=i}1~ThcIv7uUmP z1WjYn)6|EhH4`(bKn)B*EXEsyfWNF4#T2YFDwB|;kFf7A$XdM`McjR~k4*2hvXXPf z{b>|u$U>U5dQ49k6j-FJX>XtfIjk@--E{OcjdudWR6f&W?hn`4KCo+ZHXwo@&~E)T^183kPve zXma>o(bPH$pm1m`r>v#HlS!`&`*c{XgL+%i_31E4molG{df5nknAKLQ>{8aoLpnig z<`iCiPaN+%Jo4(1yrIJ)Pk61pK|#CoPz?zJsN)!#}I>w3??AwlT`z z>8a}(6PJV%^8}O30DjGewI(ZtbpUtd^`Hg5jF6)05)l0kPVo>MlSS_!6-<^FQ<1oY6D^mFG8e# z5n(xW`yNKm=^R!FEEglYateILxSFLHF&Bd!;$Sq2c!lGJcyq4VCFP?Vg&G9;q`*!t z!~22w)_PozH}Kly z_<>GIKsb-FytEh%Rc+3{t&8sUsYh3FTFgPHaAq6@Vv;8xWUX+3H<8KG+%F(c%MzLj z7haUv#1=AZ_)PJGQ8f8;nyrN`hy-$+qcUL3JOE(&^O8u8rvdcv_GnvEv=Ly?`JZG=sCzGjRCC`C!jYPGPVWN zY;qrPwB@4EAFHB-Sl8?rhY@rYR>kMdh&-@4U59H-Eb8Oi=H%BDrjb^Ke~DEM@C2-h zX1F^w7$yZY63jU#v;5@k40iPOjt>g%EGvDP2<_;7=`ee%*}dO>Z8>7X;e(t-#37fa z{L2Nvg+tEN1`iNyTmGyDGo{(bViaqsL^*q?EbRsIZlqP+e&>pGNEg9|`rbj&@o{%R z7_y0+1M_L(36nt159DXkBd3;w*jdy1iWrJep-(~v!h(W1`xf`-rQ z(Oy@NCNQ=(G+8i^uN}spasa?uN&r`w)omAKz;S+(Rhv3w#Y6SXTv^kDKWy|eGrYUx z9`<6tI5o`nkj@Q--q%<^PiQ?{-3jc{!Q&T35ogr%~UpETDTKVgS*R-~j-(>~&_tD9EAvyv{{=;LNmigiAi@sSrO z<5uxEu@ggX%jE%%g}Rtz-q6s-dXZq#ylt7d73{zEbl-@x~2A|q}I5*`HJompDQ7g)y5WXb|@iZddDy`O9 zhOW+%4Rlvp-c}aUG|3*@*J=)mRK_9<%#>gFd(Jk~`81cKKOigc5)F6)LCPGehD|BR zAJ1g90Z*~cYbB-*zPHlQx^lYeCIH=(=&B`&=&_m@#id|HS3b+XnKxyU=tnz(n@8&D zw71tI>+rFbA7dIlLR2!^VzNpHHgl8fHw_$bP~WPxN5O`oRK_6jQgVbtA{2_+dnOYm z4UZBRha}XmW4(H{Lfke&cyndk7t`j$Mw5`5V5?_1?bC78-ACGmVHs0(@paUgC#x+> zmqv*+GX?b@VC@jqhtEE+-NZNhXV+7V@R4wiz3w`CHmNO^Iq=z&!oB5|r)ZsFzt8ja zFjVxJouN(VX>Aek-wUZss>z$xA2>{H9F85U-WanWs@wl$OtNigd^}XI$z~<3LAVoM z)%ZoK^iAwCCG8U4KFJDZ3(!+bnzfrj7WeDfogkyi=3kZ(mt>Dfw3)Z#(b!{04qens zbwN-LWzO@PR=|WoQQuKnB@$jP#>ojeGDAE7TbAxZE=%i+*G+H--|HoF1xHkc8Q;#` z(;(WjMhtn%5#S26yU~Vs%px|XDDyQFhNz+;NY|-kniH#6&Oq-BHzh!1PNWsi2sa_U z{bfEkmBXkiV+?Pb>%ObiH75}7{G%B9XK{yjct1esF18j#kTf?491b#>N=jj1B zMFmTes0H%q0ipn_EUjY#lhbc_h2Gq6WY=>5l^Rij#00$Q#ZJO|aKGu!QB?u1lBp9!D6frDWO^mqFsjL)j)RJAC(7O&)VQ zj(qoYPL^Y;_w__pr$?socisRuF3+rFr9tl~EpLzo#I(d*t&%(5fCI!Q)92J_#)vr> zLiPPScg;wD!XwHMNp5B_U9!-e(q3mneXDwNd4qH^jzzt$bN0}gliVh2ARN3^x$YC% zEM@ZmH%vT;Da=kZag$eIz-6r(%{Pqne&#B{HxTEr?>^?8wN%*O0sOliHkzJ5Qlek8 z;siR$L|w$~Aj%2B#tEuri4j30dnFQ9B^kQVu?~U1L z`pm`16{t=L>Iys(Kg>;r>+nSC7=!IB{CRddsVW?Pp5N~(yxdxetNon~Azu+p1(GM> ztVRJsZlIFSuMs`1Kv(chSyK` z7DR1AaQsTNPgHii@F?kU#NBwm?E{CE*Q)E1gm-iG!l8 zL0Z4Su(@!Dk+o)uC7Z!t-E4?OV_)iOC826Eib_3u*%jk$3V(V*`@}|ayaj!3LRoe~ zX0{5M;&DgswJBe>MsAR!_r(-p;!SNcNnZfA!Xfgwi=+h&agz9O;I>0MQ(6X<9<9g? z^VWSJH%$RTTs6zVcB1YtB_7(DQCR9{Z)z|o{j-9l$8*yMtzcPX_XW4StlVB{1nK|Q zzwBt3v_hwK!NkL}Fk|E8h3<-phu5RW%+u8o6NDNM(-TI^E}$6}`gWvub)?wN?pyQh zFaq8{91{IztaSqrT*YdI#h-yU5(C`|BZ%hI*bpb)!6H#lN1kWG={xCSD zvOnT(V`qRbc<3#4@=<+9vXHwNAQrrbE*vOO{Y($~7w#XB`JLl<`|lsC-d3!C$N7u= z&#?))|K6JavnOv>b63;)gYuUg$JY$S54cb1O9)dpT7d~tx)jYk*JG#zp zx_-!1SO1W9r<%28^SXtCbv4#{2eAZz{Yr*KqAM(3LE`_s?uWN0KltX{Pq z+wIPmAJ59SY{yv#JlgM*c~XF?Ax)p9eIy;Pg;*}H3ILQg72Most!I`h-gNDgHTY&z z9W7nI*k)#pxWFX_my?M(z7mYOCBAt5vslLAYI1{q8@pw7Zcy zn+p4uN=JbP`81xGzXtZRv ztI&{L>NES#GmM=V9GD*G8ycLQ=Ng^JWYdtxe@Kzc6(!R$o83faODi`aVc}SrmYqdA zJlYDIE7=$3kZew^uFb$5;e3b9xsA>4rjsm*khZ1;whwt6Y|k>eZL{o<Eu@cMqr?o2c=ETrRikUG7IfOT|Fc!l?hcFqC zoiM*3rl*S9x|~MtIXrP!5Wn*67#6WsR%%XA@v@VC!?{kCUQD&<5a2FL6%wO$y23^r&(({Iw=;LW~X)P_*25ytWT+WH^|C~Lrm zIo`zYnEDkcz=F$Q1E?H=d9&uX z&2S*3h&jd{)Uy5Xl-AyIjtx~Mf&n7Z!ED}QvTuJ*v^LnzEgq5F*fJ3#L{$ujNRB|{ z7&~K1!a1E3f2t~nST?a{so1{qr#7=X1t*g&oH*2lVpZtJyj86pSO z3J6Z9)l?M+WrD8Ke6S75iC$!c<9vbMA5Mw|*P%yzhyyvz5aay7>t(DGGaWDOVbWo%f~4CnIp7&P*C+Fr84yr4>6@YXtBx+J`Eb$fEuO7vkt5!r2W z!pPJ*pK`;od`7ipZYclgwCCRxyG97O8TFJtrSiPd@#OCuKLfC(Hr9>L3NH=D=6_{g zN~zBK%b@fQ)por$cli#w9A7$~!-i7O^ueO^4qrg7Z=b{|*^{?ayy9%j-FbfU4<8u} zC*Qvkei!Y}zD5R=2&!cKalzeIvPYm%v0LSQ6jVvc$UtFc9{5lNsRpa_n`)gGAdi_fJ8@IA2vR~=d>&iSll6vl}xlw0d0N%ov=U?s=ycx^~CeR zgx+kS>8dKLX(%hIeQ^c@x!mRW^^RAd*3mVX0Bx;VY#dT)qN*M8m#Lav|NP595W_lb zsvwaa!L3&BFlzaDtbrCAOc;T+W39be<>TC8MoB>P{z8G=nzZ`})(T=0q~Np1qDb+`*dx*A%9XR=CEALAXS?k)zOAP+~DMsZWM7hO-Z2jZ#oQ_ekL6T$w9LVg$Wi ze|l*>F=UevxKT@^g~OcX0Jz~LbU&R5q!iSI(I)+1f-#kC8z}+8``DToYD2JfXP zR?WvoHq)DfR|#`5)adACkKBu?HNZETV_X(79^Rof>RY}ZLxO&KvVQSHVQ<4RykN?* zr~w=*e^cb12}I;gCrU_)NShuIlti+q>tGG`827gWGK%X1L+FQGXh=;5}GA#ef2J%<%&5u25 zO#Xc6m%ZCc7I(Y{kq1i70vd$~&VuWTn6l8pdrOYxw#lsnH7{LMVGLuSl{xx!7R%NEo$s8-xHpG%i|T$%A1f`Wlq4t zclXmjvV{g{GnGD&DAj<^?#R@wIyz|9PJb$ww*Pk|Mh_&MP!) z!NQNDU?~r-2R5PYF5^wc{2ppvsiB;w2b^a+op$KF->G`Ql=g6#_OynVJVm#D##bH& zIs4ifk@;DGU`aM(rc@ zQUTgVDl)rmUSsFb52SBifDd;}aPJt{p{DiNv-Bu0j2OB_YqaxYsg42ep38k#=q<3C z@ssI>%f(Jb2F2ONqDKP~F9+a44=)7~Nrcb%s~FB}NV!rY@?UcU2PeDrgwE~5al%?g z?UyL$ZYY1;s7c8Q){1uj{OLz*(3+`B>g(a995O`Eon5<}u{my@TJyqs8`^vpR}xD9 zyFX(+H4}!D99eP1?T-TagwRImqP`Thu)sTs9kz61J1(jdm`QJDgTLsN}i)A9Jz*1QJ{OrqbK z7-7bxV`D{-EgZW^3enXm14{w zC~=&l1{Mwz&2kiF714MiEhN~=Q5HnaA4a?O5<8saz)GQ!x0?tOAtq*_#so8&-x)~l z4~N)Hm5pXH4s*z3s+cRl)9EtA6j?*$^LoV$A%75y-WCytrm|2~%$iNr2s_ignLNQ8 zTu^shF22?5aRi?#timW{!mbC)7uEGl56;;ImPTh-Q3@uhg8I6|tHNotI76J_3N2z$ zj1~nn$nPyAf84|Y%57~(BtaZUM6XcFUdps8^(5~b<(2EKCVh1&?KnRF{)asslf|dG z7bE~c4C;UGcmFrIIDNN&cDUI;`Vj0NE{^6=3NDcZJ_tCz3^-X|gfT$~kR$<~gdZ`D z3p~v)#XQ61bk0d}iyOJa9!VD}6?KF{TdlZEIVDy?Orp|hZw7A{&i+W^>pFXeFHX(B z{M>Wa`(ISt^o{S|M<~A^DozAQW;q`=aJ=pnCPIIvQ15YGEkYDyHc|Kz=17nW`;)~Q9;dr&#vaa9HCl_3g zz=)C#i43%)v79+bFyKoj9i$*l_`WHmFoiLuXp>NkE_Q2K_U(&I=bBE23m7YRC8*Qv z`F-*7yktky!iyP=4=KHMd^>L-j2WC+q#s&Hk_0#53dOg9uix|T6m67 z`aMwTp<4-M98b5^T9<$_&I!ml_74{avJnYRs~FchO!Y4=uAxxUMa_i}g&tzAO;HJI zA*F$s*<@(-amq>GNN5`#wiiL6*vzntd2v&EYBi`&d*xYT9-EpfZIXj#uHcBahkP#c zY#W1i{5L3DFJXX-gayOnq(5=v1m&ZTi{|SnA#a^FCp0OSskn-`QS3tul1R*O8fdGr zl_l1hJ;-eop(L&FDp+l%WQo7%yonxd2K1$1rN7SOMVr|!;s}h^NKjw?6=Q+nLLX(D z!7fD!wA6vJ`D+>9-JUhfOpv^u#{6G-!a1tIF-{*JE#`&?mEz`i+|$t>)!R3NHD|Cu z1$7nAW*A@@uAp=D6~Y?J)TwGJCJL#Vv*de_-l|)otU5DPN^WLiPTfCZn?#$Z9(jun zhiwx(z#uNM{glgI^RYx;{wY(Z9jyM`@55TtE2U~HabO#hO4tUg#}@wcfh9RkKz_$g{EvPb~2KM?U&j_E7eyeg16=? zb{aib6ARlDSE~t09ApsKc~$n;hcC!EG5DHdWLVkSYnozJUJ)MbJHb9km{w1_Fc3bMsTj8c|Goi5B$}uuS*ndWs$TC<&oj^D|hx(R4ZO$t< zjplH$CKV-fh>1>bDnt@27B};<$|y|ZHw4;`H>4*VH7R%_Pxh-mB_N&B9Yp49jUBH( zR^mFsd$c@ddzZH}t;AbydY{=D+Ea|+);@u&t22^Rc?2tzHG^r;zSg6Q)V@w)RjhG7 zeigB8=PkOb1>ZCrZx=qiVBCYD=V|qYLaqb&UlV2pMiG`<+~8gey5;-@3rc`3Co6VJ zQ=qQS89+D|s!SP#`g{c+&dQ36tll$S((Vp?G-DYJnDp)?=fy)fgk-$G3u$5<`r+b= zWtFwEy;ux;u+PUeaj15++24#;^s4fCNY_ju#@Ow3E1SyOdVWvPnmZ*|-=oC)PLI5r z1a82x$P-_~wk&uDZ?lO3j8?9p+PAFKd2;7Sv^4&mZc*?t51mK?TdGF-3;2(LKcUIv z|M2z>+?BT5wrC}(*tTukwvCEy8x=dL*tTukwr$(V&G)Uf+CF>TcJ^)iw0&-ybN+$% z?a!EfJY)3U*Z#j}aWek{4L{L8W^oSxD2pBHkd8JWd4FyvU=2ssk&b8n@_Anl)4v#+TEni-qUmsUKCb#=OIIdvbSnr%6CC^%LM$ew$ zk)3e;sCL}Zok&8&o#PYG>+8dwIy;AD1UQf|4earO^$@NfnJaJYLXo`78A--i620dQ1r0>W^?l?)>zN=Q{P zQ_53hD#Dn-LmYk%Qi&JUCT7;EoQK6W6*7ha$sVl1vOWgJ=F&3>jan{rvaSvBMlVam0!B$}G*)wNz$aNqFgnRWeDxZ{~RZf7aCUPc3?7LXefa;d>!$oeL$b;JIOpcD%ut`n3Cq+!w2$B4F}v~dhxco1y<)Jrf51I&n`)ECu}K;{X5+EStHIr*_ripiOjCr{we zDS(@(WyBdXqpLF-5J9Mbl6NDpNC3uR+fLL2X+_K&SBDhIX5P`em;NS#d;Q@Z+uMo zwCo-_^pyP_R_0PQ%2~2gN*F3rdk8cjWR!Vv%vOdeRlOy#0CGTj4G-H0>TT z2LoY~@IV=cchr*F20wDw^fkv{77l3Dt|tLAZawe zNTIK`e?j{UdSHC|b(OM}@7R5PN+9qi#UIjce)qxE}R^3d~mH;G()JC zJqHK*?CJno4MheC+RZ7hhzTfv-n$Hs4zHVUg(?QING>u|n3bhm#s{3WbT_|`s%Zi| zl<)B>{alg{9ImfU4=OX|JGAIWxFSB&a7f=4?a(+r27O@DL76j|DnzoS)2g?qbVXK! zx7lp3b68$^&(9=XLY=x(qo=09%)C9B9Z%IHhmhqBQZ%dDosCK)N}WU3&+cX;UtFyz zZDDUDYOHrU2x_e3NUT)rs5cYz&@6W{8VXW73yK;TThmO0NOyDO{R~E6@I05RA5ch~ znXvhBYFtUV+Iq~AUDkB~2BYD833}dlEb*emQjW>pJOrE5M3f&#im4YZW1ffqCU_fIBLIr<>4JewcdfKY>N?sG5Z5&$(Aa+e>ZM=74a$1@!Smt@y5oxk8N-gtpE#InV^)MQ(x@>bma-Z@ValJ4^%o&yxaO>h@e9Vtwqv z5J)-l#l3IW=gEBUnCTkr{u*U8wxs8xKPSq`fhhJ;dZg7@R<{O|1*W7$fsPMc<|_-3 zBg(WsfnoE3pz;jA@hl$2Cit~!74n%cB#h0qwc#kI`EOn85z0b5m?N2kYXOh$+9K}r z;trMO);I(bJmo26+acg{8u8Xode9F(;f-=|$AQRi&YVEovi=SW zCiF+s-0^`+_+BiZ4*`hC8{&#^y%bIG148S9T{tj0xHlCLEt2KAMd2y!1#jrM(KwyG zuUmPKonTG3%AHU#s4I>g(CHS4wp2f8u+v->N@K=TU(hR$6W=y`dA3H~G!N4ZsUSm5 z%8}5DV&9b*M_hx<=Ai-z!lLg6JYWleG&SG`mcvby>+^Nzo}uXnA&osNG0FTPx`bD_ zeh`$9b+XG*GLeXA%c8PPa6I{H5t7zKv8#?&(uN3d)w}U5x3LGd!0lJUnp=ALqp-2| zJg(r~4ALTqNh(O9*V>Q3Spb<;5V1+uuQ>s(16r>}(md+VJ;rQT43oz`7p@k3f6SjA zj38f{Q{dK_z2$}x@U>L2iyu7eXg4yq+DK^KjvUpD$1VznxaLpIiOXVFzB=oYrdI=O z^kRwUw0y0D3z|TR1Q$ihX+*PrTZvd5bp_Y~+WlRyJKTiRp5;HJy9niXo@h-TG-b3` zNE{@r`Xw2xo52^HwTrR)$C=@2xmO~c8sM`&s^@e1%?l*NZ^TE<8sM2_ZzM+}R>gjk zbB5+hjIwc-E$5~PIZREXFe~u!a{*_$rv7#dB6wDpLY&e|bj5KPfHXy-%~fv?aK2$! z3{kC?Zx55+W!~@SA7!nQbSX1RTsZ`6hBgDw?zKsc+M_fZ)KcyQ#&<#;CCu>(DPO@S z6YXS;KcR4w9KeT2WF;HJ&b4x%Tga9RvyLH8&u{jXxT=T>`e{XP0T%4pgb$~1)gACr zdo__p7;htmnbI&Z4SB* z3GBl7Q`D2pY9Iv)&!(mW1oIyRa3%s zut|Fc`>QN&49Hr(lxB?^&{^7~p1E#N3)3$@!}W%r@QYQT*eW zCEP069V?640N-t%U44^$^UaMy2_5?HW|L?8n(hvskO5(}fui&|sm%U)`i@yVv*-Gn}4ZjC^3|Rl`1;_u@ z<#(okF#L*t`K@hSS}&~<d0EfdhU$dsv<*{0+UX#nr!ny(7VxF&V@v}l`Q=F|%f14*S-c&vAgIo2G zLCR{8j9|23uiU0sJyc6#%<2aniBCyUe8>_|CXwG{&-R-WrKmOPo%*+2v|2nFbV_>rI`3wJ0> zskD4_Fy?te26rfDvIJVe67=*8Qvs@a&@kOGKOdD1_hO*8O5U-VrT|nP29hxbX&tjI*^$bw{ z{8{9##mmOObBEp@Cvcdgd$fiwOgWb4E+S7n%V`FYKe0;_vm(SS%Hx0Ufj-HV;d@?R z3vt2DQ6nd~LTOy0J242jl3eQp^j8Bqi|Z#q_`MBp_n)@m{~e(JCk^QT&JpmR@KiN( z#8gH86d^PdiR)1*tT79T=SHnR!+ou8^ zT@~=HjhkjEIOjAgUt~a*?vs(!Y^?30{j~cH1Ud=uY1@1?F>i-ZL?rZTceUVk<>lh$ za=7Vs$t#-yG##=a(1h(j=*iUww9yqJN2uW#s4(gUM!ZR^uO8mJ!qBw$aIwC?3{RsKIR(UJ_ni`#up|c`;OvOvI*9BPVe!qNP zYF)x;JZG;i=tsj6Q>3LTN9GthI{@5v5k@{bbVe=dNWL0q7u~!_f6(i^;{j%V!jY?!DbNF+op)c240c zCE+Z!fRe!b!aUh;$c&2(S{TYoWcJ-YV8z?<0E{SW+d3m_7V%!FG|)sdGc=?myl=j0 zr%{ry^dPv1FG154xzspxjZVojqup|-4L>KZk;+_r%3nrQaMQaoHdY?cBT_mpAHq_& z@p|X$tpj{a7z0AybB#iO$q8H1SL(f^(C!XL@Xp^IdJYZ9Dt$)RMyS3BLy0s1H%QzO ze!Wxq+Q%yxId)Sg-8rK0_SKPiMrM4l0PoU!ZyMjfQj)?i*aa(8UiW8JAS6>&dr*Qu z%N1eBWYb<6xjAjMY;Oe$C?W_0I$#>|kZzV2)^W3QdxEf0p3%|P+JxnZD*UxWIInaJy!`0n4{55tY5Hv2Vo=a?xa&G>{2&1x)^Tp* zabVm`npwAu8Q_;HWuj)|0@|vs3Z?CYSTJcV3o>u+x_2lzdQs(>xq?OFI|z`_NL2X7 zprXT*(P;=_Z$AoX))9uv5`5^daT-8hLmF2AZKx;sbv^C+m3g!A(dV^MbK~Ea;U(BH zlWE5T0@=Jb`h79Qr?~rpntn04|DvQOj2@v~T3As=d+aVfCRSTg#4+9GS(R5bVZ5!; zp-*^nt6xKUP&WHhwAH4NHpA5O8uq!v$Wq>7N&|NAxk2I_FMYBu1QM^a~fV2xRW=k>wh`_7>PiOEvKNWl)*s5nh zl~7vya&rxX5JWCK67&EH{n#vt){XL;xO3x9eUzKRDHO9a&Hba0jL^7ukWk&-*Qm#ND^^VYmxxayOvCZD%R#w-*!7s@D!6HHbB z_a%h$mBRH2sS@rppmAeUjQADx`x%xg{7b0lnO11P=g!oaoN|9jfhkYSAjrf5iG+b` zQGWFSBoREec39qyZbTr{{=6VOD^EGp7G|5Q;%+YO^rcc5fWO-CS*Ct5-xSx2ki{Oe~7LA{9pbee#rN#V{q zptUKR>X~|XD&&pDIm|AH23US9I7}IchA+r>I}#yVcJJR>-f_pmfAE$VYk`wn3Dr9U#H*t3Q2RWH9sTNeM5q!oAL+$!cPd6iw}V0V(y zo}S`}dr7K=e%0HSA<&sX_``=RM`LL*OhX#J0l1t}ucOk+)}o4LcM#B;B1dM)`q8ur z$<6}cf!K1sVXb}jLii^HSR&kP1Bm#Vl2G&S31T5ftMGDWl$wU$g$Sum6$4ibjmR|} zzZVf!9WP+I@-N78JAP*npU*ZdJsVZzg-ilECruYvY2@B8yv@;ef4VZB3BM#+ z?DzrC8ivrT4|lOEbB+pXC&pwa)DBD9KXmcV}O_75+UhNm`D6MJ*&>BCv2;mxQw6I znKsFK$PnF&8wB`$q`S}UdjiF*sXE)*b3VAZT z!(pw~Y_@~q{~|_Fl0`Rfe#z-QjGa|hSyx6_(i*vFR=R0S*Vr4So9tYGKnvQ_8S?nt zDLWp4>Ar4rCr0v_%;YFL2o-ptHul>By|m-WYxj=2K&bxUjt!+A24o33ud?rL{S15v z(jQN$Mi9T_O{ToXnSydIIsIy&5-oJG3_c#LzIAK1?0ilJ_SJiFfTvideoM+JSObYW zfn)9Ek-lClNSE8<+`;SjcNo*0$?Nm>dnzi%ztp0P?Xw!IyaR|M#%y9~{RBBY(L%2z z6CA(327OHQOw)6ECzPdTuVN#>Q&B8W$Ek9L`Y{db#wf#GR#dBLPZF`bq*wjMEu`Q( z(}Rq@tv8TIb_tCCrNM;7q>F^T(?)hFbJWQ}$JpJNR;VLtKe-Mj!TcO z9?K(?N)TNDT0QdOkW3h_Y)dDrrJw)| z86c%!RahEM7RNk`Nj9yOjf^PSJUw36x?E3g3{JM{^S73{vmwoo9ek=UFt@>mkS3K$xAaDQo;v2x{*OvAt!z)F;_G))qy8kS-%ly*jmzkWAA zg|PXu{cQ@f5~h)(4Oda{Fd6kUF}^z0<^A;xt_xJb;8-3nKLm|fMq8ZsNn(is=@>Z)kvD)$_f4?+&=aMq>s`*eAI&zZPb_<=gtue zF6hK5ZZxcjUa|peuuJJxAk>b0O$2|B1(k_9Aea>0!i!Le8~E)BlO!P$y-svc!U-3O zJ7z}#8;I%PwB3nVL#spqH1n+4ag*OCmt1KQBZKXmL$<&tW#;Vup%U#IX*O;7QviAn zp86H4K#oE-h+zURYf{gRH1*GkWD52K5BN1*9lo*V3xE8d3Cx(NTz+8Tb(WdpZJ0}j zcAhSvR8xj_4q9$R82{%c6t+Iq)#0}yXM&Y*61TWyBBsNd;V$ti;i|5WEgGl{Mxygd z!MrY_HVCFLx?)CYfwTa|%~ltm1AsS>N9HYsT#rWJRT8RR)msKgBP9oTNEY*!ePOEc z0-jllGKce5D)TevHB*|CE%|4tI`@EqLg{BjiH8;V@z-*<>x1PI35n@ey85H)deoLZ z0|*g~p(q#{J$gx@V}^qnvMp*YVws|kGBpB2I1g&oUxQAm5AUYP7-MdW%v#6lDX7!b z@(&ntlplY)!ECxusKWohq|EsC)&W%dZ(n_-~t{#c!LUO!gz~sfVU5old~x z>|cJN2MFfP);mFgX;6Wp3M2R6f@KFCJ8$dI%@{43W>gEstZd>9E@emEWpqyNZ>RhA~j#P*sCXD}pJUC0o46XTRFAz2U2r@V;ub&8chazC5gJLU}Nj4jk9NF{WKC7F>JQ#C*M z+orlnm`rJY3PjG*0|N!=lO>P}rWpU3I;^fomL9n;8J8%-BDLlHhNR-(kc5nh%F{!4 zE7vGavcrT9I{HgnPtsTSt*xKdhx=LtEMhB&y39JQG2~4>{YzWlYw)eD-}=_pe|&4} zH~-Ss3r2m$o->&4%V+K1$y`A|+tNeSo?o+!-!_HEL{@6p zcl$=3K>S!$+?DZ0%*dzhN#a#O8xY^+}E#qlLj58NnEtXbb1Aoe{{h(X$m zr$4g<1%zE7G~4=#usM?P(ovVnS|pSCT&lK#a=y)F8cyI#rYuf+Mi`PDbI9puYbmJJ z+WpjF^3K1ko99FNG;UhEq&X8%lb5?j)${p%djwla z03KM~iiQZr`d!jSF2$OxR%v=judzJ=XhT)uXgz;q^;*#0uVU_<@Zm`?QPihoI&_|R zZm}~KeLR1Bfc{V{HjWXY4@Ve%jgysAML~`jcy9Iu2a1DwB|I55&CF3N@7m{FcWho` zTFT{XoiM*(Qd-rWM(GIBJ+72g<+`eG5~`kT!V+*l%bdu7#u;Yg0cKCgioRZU1+JP7d$N<(GSqNU8$$rh|Z)8}`Bw2>c5dT&Yz# z0`}@~R_MmK5SqyW{8`?f#Ab%aHr><0n+EyW17a-< zY?F^YoAQ77qB1!;{Q6C_@V*fAZfd#Qk;OrPwTLL7y_j6Y7P7@i*RrzaMD9Sv+I?eu z!Ygx@^49JvJ6y)oBUcb~{z!Q$pBp6ze9?RG(#+|OVs<0XipNeWhcUI5C`Ti4Q;gzi zlBo_#5Y2G$mC`b2UkPr#6-3xbm}(QNv7u0GV^mV+09tPsQq=y|B#Kwkrpi>RMR&e`4+9 zpURK_wEa;a-y;J^kCYB^PC!6_r?U+}!!nqMiWm|a3W9)e75!SFwp?3D`V9C(J6$JHVHnRFhSwT<#@*OPRolQXDy`=o>^431dlz z!CPf2TT7HNvSL3lx&=wZj;ekMe41C}+TPY6Qsba_%fuR3NinBpR(m%PS9EVD|O*yV>6K7DE5d4_*0BVXy!Grz-Y8@oxV4 zXIc>X{W|!eg1!K2t7DrhXE4jXax&8zRo&JH2p^m3Ba6 z0j>m(#$TlJu#2pP^uqPr)wZwOk0-tpi3`8rX%amk^B(fa+@b};8`thwdY%`TNCjH} z9?5u4-QsOLW!Ty2%0HcC1A1Sa#wZkNuI21qew;6?hx(<&{PK70N07-u>iK>sWdG%3 z)<$e0oD<`(H*g{jwC zqiHqS&UI50T4UM`_5OmygaVa$%82-o50}L%2!_eB^&!I2i5#McNT-h$ZIeN|Tb|+a zr0mO?JG`(iccTirLPr?F5j^aMH6+_Zg&I+48T!Ma1l04#W>l`eXs>fxv>o@4NkfSz z&V6%Y5bC6ss&oS_#w_1w0v=}sxU@PtDB_O%|H&#+u03 zNCq5+@-#Ts?VV|>vdei~=6o;^r;3Een_(^w%YMXov_~_oCrd3C`btjRCFZ?WAov#z z8GUxdO7x9iEQd;H-MSunWcPaAd169PfkqcHUqa9HeRmE?y2bCD&NrBsI$hsBp}OYo zE0hV*XD$Syt zsd*Vjfw?cD2KfHr%|aZq_WosZ%LnbG6!Sdz2@KL(Ql*{B(hC|`^lr72T#~?kj0OdW)Pdgr=XgjC& z>8Q{!7y6Jfel74_3c)18Z^t=cJK>NF^9^f5;*>sH8hvhc*6r#KfK&ySYA zX^m}*cDxPfUL$lsGcyU7)E?ZiLDXTx@?72HadE|UiloEks4l#KVx&gvPUBuxC_F+e0jNf(^5&` zF=$cH32N3UbdFkkCX7BFXG_VNOP+yJYgyZa;0ok91U0p3($=ZhenR#iOC0eleW9}7Bl%uM})cXlee!Y=gBBg(|7`W3WE(m{96eCGcN5w%W~H?X_HJ&xOF(EQm%K`(&ouQII(gbM;M z!1<#0s{cIgi^Gh2%ltaiOg1aINig7PxP~a$rW=|Qecf@#=XKAO-@S^WQEvifHU*#4 z_6d=G{$tzCUnx;9gc(j_CWJzo=muP47szw1KY2aS2h{t*Dv~Z6!j$$b zgn&60EU2UlV#b?FBOJSE8N6yKZhz*mY+ln)c`9_@1&W9_FOWafwOFZLWLl99*-Lo_ zk*%0C-?iRKsDU-JFh-&vweY9R9#oC6nG$_Jct;hDyke1DXlg6bLb0of-DI5s+pZn` z>LxLk$T90*!@;5&@;Z-WHfX(EH*8z#_4>$pP>FAy>^G1 zNH*o;o-8wC7(5Z!@8He$Ib}i?7O6m_mogB!&{mnFG#?eA#~euKE2HIJb4)BaS~GGX zPlJc61C&-YT7s2gRb$BrgK`;fe^}FcnB(~-p?G3scWT*muEZP~) za6$EeIkL~6Rkm^XP1SXWtLO7lb zEZ3kj(xD!to?hTD1j_rU4nF1`w=O=5IkV|yTX+*l5K_3PqPee%7=WEB%vgB(r z$V%bdS$V08nlvk!N0PPmHgJ2DKUz^4&1GgEor|NoflGiRSCt^vj*g$+#0S_#P|Ekz zMkdxH&v}B@{`#QUo?ewYH!(}z=L81Begp}U{9yxthev;BO9+u?)1|}3qBgT9YcXLy zd$Wy#k>w(O@dqShq5@%y{~&h1;_0YZi^kcdnXh)n5^2OO3O_F~Vph#MuStq`&D6z@ zGy~QvfW~2N;B}6XACvPELQ0Z`pwb>M=ZVAHyplqgSs&4Z>sfOed;i#fKqJ0z`)l_h z?Y}g``tPO7{j0>u+1nU88T^wh6ewH$WeUjS;$mFXhP|wyPPI(%5O@j6P|-fzC|7O? z8CcsMkCGE6Rg`owy^>*U+!z8u6ttz=t12ue7Lh83pL#t5JJ^4WdmS15`GdD)s)O@a zVgp>Z)!`a?jsUR=bg=jBQv;|TYbGbLgku*f-Hp7Psz7;bWc z?yO^}*2PKN!$@=z1Gr~7odRkA0z-sB+eH{Q6hl}cV_ZbM*CkXZ(a<>rt;*QkI;Wlt z=X8B^3rcS?SkRMP$UDecn#fx8acjmug1Y0jTes&g-P+qh zI@C$hSGjic4ko24bls+O9e^$|4&i4j#BKT<5eR)(nplZ^)5lgKc5V7@?c)T$ryhqQgbV#VIwDw4>E@Jju7~H8A50{ zr4j<0Vr!EF*V!gl85Pfv_xnG^b~*d56|8hu>B%4)I*w&@4V%hx)a6PHw*Q$MNQid~ zEP}t=C^ZQ^{7r1n{;ZTg2(+{Z^YjrK)`6Ewy}egm^U>YdZF^kOoj4>GG4@l`a;C>U z`E~K`(62<1)aj%?Q-Q-O8`W`D+QW%MT2bFkG|$C}L-6XvP%cycGi5A)Mm<9+b#WvY zJ%cR+G3Jquf`@&7x*pfH5Sgn|J7N(+CFlZU?>4rYw>a|Rk~G>ufrT;)y;2$wBz&e) zwDqpwgfUEc2>n(&#jySfTnl#3Yu?UvL<@!=+)%Y)*o`ZLJ@O7JShCa7+wix! zF6Us#2`C_L9M6?@_i`bm{SObED-tadJY7?#WHkq2RyZj1f?0#w!6^0b;I6`{J6i~Z zW?2YhU7Vw%{)sqvmw>}1M*^xt@7Pwmq^caShB*f$;h~BGBzlct+yF4{XwXP9qkDo! z<>#Q!{#JOKzH8m(xE0R++M6|`5fU54dyA86f<cg5x#dHu;W_L?OCie;G9-Uqq zJe{E6-&j33@LeK+3`rf5qd@fwV5EK&)nRkqq4kx<*aYAw$YK%Nf#tee5kC|V^bQ17niVTNgywDK?u;~6PtMw(9s=Wq`) zS~)-Ek~GeZd+3d-M!ozdd}+?oR6tpP_m*f8FLSt1nV})!4{}mBa7%l0D;Mhz0Bx3z0B_xp?cwMHE7Jwi%B z+#?F`2s0vTwaW;1%MSNw0jQMQ;t?KidRcm9gp+2j0e)Vl(%I6l8_p^IHM#2Qvm7*QmBm8mPx^D@-=5&?|&%M2sE;A|=%z4btayypi^1DM^#u&QIX?4xtD%65g%SdHZ_4NTMWtp4nk6z^ftV zl`Hgj9&WNBc365TptoVqm7}Qux9L%b{_#_d38L5KR)Ya<+fm~ZVb3gk|geHE1pV{tUJ21p21b3i)DxV zJ>E9>P@a2$*626iuUVK)O&^=AEN8)9NGj0_o@{HZr9pY7gepu&`d*72&=3cakSg#j zfPh#?4Hexj5Nq_aoFzpaJ1aFdF-&+@072c$G9k4;RoB(rY6r<58e%+dh4_ZSSK8$+ z*KaQ65(uHdO}_UEE20KyuHwadh0zFfI`KtnOV#Yo_Y7R~`7_tRY9tDxpUaAhw^~Yt z-Calb%^?4cAkazHoCDbYatTTn7QNF!cm_`w|g5y!iP%)p|wnq zHrd)^u`1PAP4Oh8<~@#<$up19TCVANuC*pcA+G9wRgwb=XOQ-iik=@nFCUAGMbC3T6GpMltLr7-F2 zp0;Q*RP}2JaVLs(uW;9_me#CJ3oE!X68K+|`N?3aYZ8q8*izc5mwOq^+(lg2ts54e z93nJ{oV=0L**c_tbhS{vDk?3aN6HY{@FtZnDeA9=VYh$cTTsr)6p?j=SgV(`zp@Bo z$u@Slz&?dB=joXV0%-WiU(9WANqKlOTC z1U)YqoByTPk)(dIKo_W|GCR7rBwkAbq%v}mCvB6gi<`N#q(=52ABI>1Iu+~Q;66_J zeBBwE%!bG;zZYHnt20W8C(VHHptB<~5?0x~Dr2ziphO0njLlILMi8t-s7(d{5e0_}oFs}rUDQXz-tZdBh0D)?`+~3Mc2P~Ft z;q5N5?PQ1mW4jyAcE zTqdv99cVn?mXcgTinFv~6etTY$;AvjF<|xGS*{#Qy50WpE3wAw8sAHJOOj+@aTK)%%C z#ng|2|J1;y(}fp$ND%l?WyXo&P*-eAj>W4RuGs6PtQ_4NL6TZ25(8N~vh{6p#&0Ok z#h99w8XhrwNwcb?7{@~ZKQBVGwsBQ=ylcixBk;KVKTb`k@3k;jc6Hrt2K zAwnw1B+JgjjhidTL^Lz=t3bE_RiK_P9A6_BRnRe0d-phm$m7eFa4gE=Ea*+=C8juo zab`T0g*0`mUBPT<$KzE`^CHJ+ERk9NXsn&JRGM(+0$@yD2>m8Bkk<(&U-E`M?B0=RQBdD1(O^ z)l5MWM4dnFktji&xlGf8zgcMhJgU@l6VY&ki06K%#;av@yT-z}17r~k>k1)2X2o?4 z@l|Wx0y}-%rkbXH(eslSn_~%=MiI>WM{Kv`p$%}mLUW`i$NqRFRc`*xHoicoS~`vx zzuvR_WS4RCf*t8m#%ed)7D{3VuuE}zLWidPqrekdNfG%J4*Sts7s#DrvC~;W!Jc4c zhTJCBJ)^akyv2YH4&2eP^A?~%_`r~8+9rSB0^lUC>nmh*%@Y>vjk4PfDDZ&<;+SG` zQ=qr9cZ#$3iyUq(e0R1O7NK1kaV_}kM^wo1tLcwE()=R2cRs0E`TSp%n^)N(Uc=#D zh-%R7yRPRF1S@OkG4Nh}P8?`5RvRymE7V1*h^Xn{R-?@#14dH9d*b+9En@m0^BhO5DaQ=O0Q#kh)prvAmpiofRz8 zmTrp*y&&@Wh-|$3t$#usZ<((<=UG!=wVm8=cx`g{{m86*jNN~jC26p{D<;5ori1rW z=3B@2Fyg9(RkrhM*x(0EzBXy&t|iUtO)fSqdrU#H&hkwyB74{iET^^|fhv7h{hq4K zao9@(c9)%gt-f}{UXu(G#Uby7>qMx2JI(mjxocnO$#VytPxW3`dU7CZpqpgaSK@B8 z!h1B5PwcK0`KM}_OTO#U$bg6QyZY%KAUZQ6GPF>4zZn==yu-SV+e28J z_0@(iqfa!VWB4pqq;n0_(+A+Z0Hf~)%O$dCYVYD^!Bw!MW4)np3Gw2^7P>5C(eZ^~ zv$~7+bnB?>g!y&8zJN?kU^uMb9X!b}JDBs{y?1H8e!#t@D{^I6yZ83SOs%WT%4Qt# zQTV4sRhEgXJV;n?=5}VP(`WX~N}Uf^2KQTw0}P=#j1wXa?iE#YlT^><1!TpYn_tRG z-~BiR?$S*47A1z7x^q5;JN+_qBb5hnf|IS3UD;b^UjXK8e*xtiGNlBUaMw>{+q8{%t<9^xF z!2J5!2tUUtN%Q$^IR*55ns|@l8JW(XUYn`Us^=sQ+q~rK;-HihVg$$exd0UXe})#7 zjV+tGekMFHG+SlqhqC5d;#3S&lUzx$o16L{*uV^oo*p$vmp0QP;9qI~%CuGOu)*cb zh#7+jhZsx4@!3MVa}0d(S9KbRdaimvr-^bV0&GlffzIhv>z4ZykNT(%2E5Fn{sn^H z76Qen&uy1a)@)v3F9pV_&*&s1XtmBY{Kf~r=G0`8RYbB4?z}`+5@1P&QW1W!dH{)N z9APepdI#F-si)r3sjJH8H!cu7fqCuL>=PBu+W7;Byi&@n(fi0ci?ubsG!8QW$~_|RV0f)V1`fjsegF1T-0 zYdZ$MT+z+dHC)U{2`=9g-I#{*fi)vq+a^p`z$R z3tz9=P|*!Kw*38#2xrc|uqae}4i(N)XvN-D_uIhtTCIkomcIpfIKz~h<2(1K9u_zE zo6~pJ>j97#U}#uW^bRg#YP)h!Z)UzbHtvuUIy*kGFg!FgN97PeuhHJ5tdL}06y~)o z2am7pDI3`UKDl-LuA%}~;w}lfb>go2dxRWoOxzqB!%D2ET~$<-m>q0q@g6`9PW-M; z!821u?VNc=s%?>sg>6;F;_1B9ndACUR!QI@Vqv6R)HTZG{)EpwL+OGUkk$SNkJ=eR zZNe0iOcv4{NrZ_{g{0A;!jV`l(a)^V!Z$66{5`hI10&9K0r9-u{g+dTQ75dp#JGiv zz5*`1-C$v@Zo(FUHZAxD3L$Cv{&4`UUwz`gnXZx!?h#8p`gwe?1>6+=c#2OwdEft=88geA+;4O6AEu@ zvGMX**1kY{e!|%#+Yj99lp(B3@^+tV>ic$w*}6z^r6;=uiC-L-#bBXQGRW)E+=}?H zAu!XH<>pyqafqzD3X5ACd3~h5x)ZKgy`LGgT!-Ik^SH%k z_t)>q2@%#dY^AZ+?t6B48b?n;DnY$^QM5Wqo+nH)zhrfAkCFlc6Y}oHX3Q)YC^LSw z9Ij`bO+C1Mwj9;?%D)nd6eE?6H6rA`6R_F9IZ{G~$hI5ZYtH~=5g&j&mTdk?iFR{+sR9Tp6ZLL=SKcu~5kgQ?0 zEWFz`cH6dXyLa2RZSA&g+qP}nwrzhsbLZSUcYfT6bH4gjRZ&q2>&) zG*qONuAZ*0Y-MAiGrP60v^CINu~yrEK^xIuG$yNF%TBZm(QcQo-W_hcC5Ah4OnfYp zQyCop*l|D+9_~*xBT~1D7&a!4v+u1(H7s=}d%m21K3t0>%Htr_&^=)&OG1V?&9i?> zn16{qoH5M47&W^lIR_vh{Y?e|-bY{{0y@oXLQ*3uB3#l2%qCD~OsZ=2bknw?1S-(XQ;s-U# zWOGi4iiYSTS5N!aWb{R_7*jKi>gxAX6ebG@qgv&U2jvKyys>D0j_CBVXL)QAg;}Vg zsSAwzWXbL_SSWDl3h!9Sm1KK&>RErV?Pq&7%oB8}%VzxsS3(XiiW*lUWWKJ4S)BV| zSsIcf>%w97hAY8$tev+$FBLnwr!~WGzXC;(_ZM$fF~)J;HJG#7 z-QkZ(saJgUX{x^|)o*^`9M+&v$|xlK+N?7vSD`Sh0S7U=k*tc&gF}I!O*uf z4){>w&po1|nP1%`ZclIv&2Pr7U~vHw9_0|}#2Ny8Dx`i&y;SlId%(2${@S<(59(>u zh{e%Zr2*&Eaph9Oa4P-q1%@Zkjlf4w$*Y0ivw;B}%^~4iH&$jjV!p0`WDVNAJL|63k{iDb~er7@MRLlvg z<}X2oLHS7-W7N!CMy0vDxw*+e(iu8(0m9|PDfTw4NQ?ot46(HMEFs~_&;3c=?%wjR zQp#{25uCii;;vbhpAK7h(|OR{Vzu6Z?7A#I?b{7s$%ul@>4MY$NS_($0g ze~;~ti6i8IiL9=r)RslpYhw3VY4pH zosbu7EDQ?%d8}^UvLfH#4*?S{1q1sdhoX_b-j12ujy?Hi&Y+9F&~EA;nA0e>L&wEv zoD7s)YK2OM-MIt#Sihj@@S_Z^2cTjk9#0HtMJXzf5#JCWl^|A2Nm!s1H4PfFCWk*gIGQHzhd6R*a^KBltfinn3V&cJr?gH9KguF>Th}Rao5D+zBXXao5E=#^Pz|i5J2if1pX2AQWf=>2LVeouLaUbFG1K2PxgzdT>Li`={6x8(5ShFaJ?XKAs5TBy}D zvpxS^BIxGZ8#-JDCjpIvB{YnnIr1R@L9=gx?hros398b;hkdC8YBGH#>bz7Nn@;PM zLF$El;rN%-8wm0QiL6Mr=;hjW?}Rg=+F`6$#YIL2#~}6P+73E3-fL}R?+GQLM9pfe z)=`;XT$W>B#)v{86{J+^F;~%AkD{I}u~c5lUU{*D{;&1n2)Ey$Fg7-IDof&wmBMC?hqn>lI9l5x%L*~bO6mdhGqv>{iz|&@JZeoET z=lG1ap($-7z~v6vKb}642!6tpG?k5lnM{Pe)CzjS5q!T#n}Ln=d-9Sry`Rf5W05rF zMZ;X{U@~2UHnd=jEuX{yT8qrj;WmP(WWrWYC2lB2no*ZF4eXzhAQnHm^pZr>$A^Qw zL=18z7wmvmXjnr|34}-q95QktnlPc#ODgQIs1JCxG0>=?+VsPQwqfjVw}*zp!2!A4 zrp`?)7F^eZxC}NBq?8RtH8Q0SYO;YgW&Qa$gp#Hxr!zd}5SPOSg5_etPijF=>_N`s zXfxI_{zaqPIZ~JDF9Auhhw6pmh}`c?9L-!2<#o7&OVnxv*aJ;X@hxw+4|+Do_}6@; z&MITTV-tD`mp4@2=4*PD?1`hrvr}$MPe*`uMJeN&u` znhp+!aK+}RYqE>=0G;E_*VxvtrNDiH8J-gkj`jr?pTaU>8VsH>><`}_webdR+@q{`y(n=cWN=b zAvkWN2nuOdN3i&$u)*g0y1oYR-lH7@bjImn_!D6UQRa-nAP%6l8e0kjP{x?_d_Vk- zGy+r@C_5{cFPB}^YEgjfB-@>0Iv45z3_(o96xfdO9T9C9KWu>l*%Hn!8FwVc<+*AZ zcNobfeS<}`LHQHR#avhD=NeKA|2wSpQdhV~1L^JGCm?8Z*vtI&C4JCNhe?7T6n`BkI*DjT7~>4NUH^J@%2WXdFxB1FthH$^Ty>9l1mpyArJqz zM&6nJwe*LQCsZ$;cS7#+&rt29t)gv<>lw~9k5Rni`b+jk(^Plw1&yicNc66o?|;nK zpcmmPoZx@`%BKEzj$_rr?jOSE|9zAExo2Z!XW*!0ZRV_JZ>HyH^uOtje{FFnSt%f?AbZoS8ve+W z_Mn<1)GxzfLYb8mD>_V>_*D#Y#Q6ZMH2a9DEbAQWa~_%<-%1%j_oQ@+K#H1HY%))E zP9CZq-LH(*^#7u2@E&YA$V_=B2Z6kTV5K!syfA>|xDE9K41?rP7+|1Df&h8G<)eycC^D2{ zB!d~Qd$kmCaSVz&g%&iODZ!kg6U5u%?8Vz`FlHAtnJT&eu(t|YC-xdD7}?EGnw^B$ zWC^$iAvW1ErP~-&b7n52Jxz4WDpPGtQ?e;AZ)4m}HfL*#PdkhZv!Y@jf|M;Z!HB9< z$+&H+CFsG@E+mU|`R& zh4aOQlL^3THb3*ATp!+7F`+6!PaqR-WT}!X#-3rYJdTUKVYNVyM6eqW;Cs?HC{a zJc_F!oyUe256~hPXQHhy|3Ue-KNQiCsEu(fX(lIYGV^D!)%NMyl+QBgg%%-EZO8q^Mr+#xfft)IGr?0nX%+@V&hO6 znpSKbBFmB1>u=`wRgwcPVP%(y_SdT~S&40rp`%hzrfH~7f$KvXX8|7ZlEtU<$e{h{ z59jd92wqTdG1AS*l{T@-d6}~~QWgGQq9R~hMa&1F(>utO=8OQvx3HJc*L&R8wo!GQ zro3rlU!bX8FvP7vQ91}O2y-k+dq(+62Yj7sdrgh161G~IrvUy&y?pz;Oxue(kVBY+$ z*s;I4bwXkUa!sc}7o4zM5$*-S475u~pV(SoQDnG8Ndw_xC4Gok&0?2k9|;iN)ku2d zxbxb6VRLj;Zn6uRQOg1B7iQ#cV&=V*PB+eOG)27)(GKFc<~Kt|3eXBQ z#H$I)e>Rh~uG(E;F?8U`n#-wbnh;Ia@kv(cmc@hcgR+X{(RAc~n{!<-IDjDT8_iPH z1=^fmOM9skuB@3xeOiQkHxG0vA$EP^&N93669C_1C%F`8*hSQ`BzYA=$R^uE66PY% z)5-;-YLwG{B*R5a;!}t-35`qR+?skdfhyi}px`O?1E}NBq};Wmpz+{5&KXuCu7JOk zOTJgNB_)s7oZB@{lf`%x&*w2)AdPe{=tHCi)4?dfPu6>}`3DsDt7uyOgKi%Fe@Y$x zdlEG(8!IDgM_T27z_7J}(ZAqV<=jQ_Ck-Z()8%MtBXxqvw-;0V4={0RDD15->>o=p zK0y36;Jm*er19r;bg7|?ta7E%>bD?yUN2#?j(Vr&jVpP%iA&z*?Q4x^cMiOdg6(a} z-+ta^m)98{4yn*NT#y!1o5zjMUzgiF?-?Jj-PzutIbheREvWGbRJ}lTrDH|LJ@g0z z1*2052}OjKIMCc*HYGlF&oNj&sw`m8o}_-FHzmHqQbac`8&6uRT=VE=&mB(t!F=bpoM~U>{KvZw1tGA+H^O0zSmGp%NOSKDj1FBjrxTh zUO75^mZ+v@^Yq5at=&eT*N{CG@qsWszKJ(vE8=J@gH6Nk@hsh&pq zewYkM>?YUJ=+=%5`_9xl)G{1{W}N$1qY*2w5^kR5XB7w`$m6e-SuC{*cybk$v`6M% ziROz_oKI|#mDEY$Qyjj0Cd(y%w^Y!ZTdiwUn}Ul-hAz&UHdI3iEBzC>=np~yylnos zJfT_uTF`9C7M5f*pYFd+jR%l_F8w&ea%OTCZY;Onf9Ke361N=Y$3gZbn%DlJI+g%D z3JShsQIYo_7hiN{pXGc%l;W##RW&pKtuaOL2{v~wzCu-T%U+39+Q%jNuRDt1~;QTO7lCT z^TAx*9VxevU1P}KxwdAxwDn1Axi6u^Os=3vlZRJ0($~%-txYj{1EeHDt5vy*Y0=q6 zqlAUou2~VoS@aN%uucJ+x)?t9gvl-Swh`ptjtXyzD4nQ1%Y+YmfJc6-#?LF`987WunyK7`Z*u1pLG_qA8r<<-~3^)2Ek>Z27(o0!&&?C zX~TB{S~^jpbFnXB;TTr|h&ODPxMKo3zRN_S)gIsBc!lREVc=E*8VD_H_eTL@J5HQQ zS*jPjKu1_8x4JRYGp@Xu#pyB;gTqjTJK_ZT*pVNQ1GqR;?F zEvrGMED+qX8U(ruta<9Y+^D1oHH zjP113S=LowbtbQEr!6Sa8L{FFIq);2`}oQYBdpiPTXnOxAhF5(%818ox=wacT&7W5 zv$#reIgZe_>}6Z#4lnei(1L7wBB8}#oSv71VPKE zbgS5tnotVXu*2-0Q(R(fjK*N{PR9yP8pjgZ2hfNM2K)n{@sxcDK9 zexGf39qh!C=7l+_8qI^U>1}z#gjs1L z=MTh5-|f6ZWObip39z~BN&VhX&`qD?ET5Q1pQYN_tNPig3A73W&+L{q z`0$D>iDs7x{at8l@kxT!TwGzIti|a4HrP+Jq^uzVoL)-h;57mB%tU5+v+)>x4dvzs zM(;vhMCD)n2ton@HGF6_LTHjgz~cd-)(C?X2!hpOWZA6r9GhZ$G8@7^%J^Y6^!`MZ zpFC0Ca6gX1^m%`t823fd{PAY3j$u0i4oiaXY!-~hK9b1%OC4QA<+BG98C41GNSuC~ z-muLjMDMP#7l@?qR%&IyIHaQ}XFgfZK(gd@W}14;5-bstztyNd7?iI3MbRh3{p+Gz zxe@?SE1ZjMOi+0so?r^IluZ)IQZcoSwZ@NoiFb7*t1wq1KuH{`L3+iBe5DI?<-xU) z&PKSL{-AXzGmKuXZg%xWDQ;61S_~&q%a5M*V ze#TBpo+rrb){-rYd4E+^UI#^X=y2|RtDpJQu%oy>hPkrFNd4%`lf`n7iZMG9J0g5v z=ZhKLlLXVH+|OvVbj6!en_Sgy3Aog=w}T&6Ete6VH9t|NOF&m#ma2vUr9A#Vffk*{Ovt;Y3t{=1y!nFN# zS(0IRbN!-(BdLb_-ReLu>eRPIl&5uL+LH#vT}I3SX57cy&$ls@$`?_W#rF|>;1jAm zv^oczWQvhw0Z=jHSkQo1wJe~TkA5=WhqgqpGWpelD#&lqmw-BK@PV_SZmViBC})Mw zGe?E8;?Gsj-2rGwKva`$q9#G@xy4;9Ptcck(;yK_hU+3*mS8I2i$5hNF*5U3knteS zewzIdAC~nuE=Wm2Oq@hC%|&OZ{oOAv9}XkJvaAIm+6;q>1KFM6Q=Z97RR7NvTcgqdU=)z z!s~I%Pk@`$r5mP2iJ3+Sb((y&a@|^% zP@^>??Rww59{c{<=4JVnF(4@py`v6D z|3T*K|5DqKC0^&I+%IeBLk$5WImcjBU(qX(CkX4Z(}qPZX(6oceDUOy`xO_^h97J# z@ki88*-&9|$6R&sM!{F8w@R(Zrd37yJR4Mu)m_$HfCxg#$`?azF1?pPx??Sxh=+n6>Q7Z+D^cgcJ_f?MA12%5yA~ zc>RWCBTc9=sns>M#R5Ph-k`SLdGTo)s=-7A6_^0&s!sUZ_@YdyOeLveEq*AjKXwa! znWz(Z$Ab>-R>e|ezqa#LCYmr+c$6o8wV6z!W#BF;JDDN;J>1HA(AhJ(4n=pPa@DBa zoDFbvRHLYoqLd4US!CEzB^wECJmP|VrZ(+x5nE@cu+w}CEZHDSqdJu#x+N`bZwaG* z<%T`as0t-)5W(0@Dr%H***Vfi&TqLz5t)5ob+N9yFBvl150r-Dw*7P6L|nGVk71(i zTDzOZRxRp+a`>W)fQDs{#1b`Uk;pw3FnpX>9rUQtWP$!Kcf-T;N#4A)}6an*{=!*Mft;RC21cBfZWD=G+X` zVK1oG_+&&^Xjt&22^RPHoQ))1lt0G7!(K^HYZ$}3Xdg9e{+7#|#`X=9PUZH@e;vEuI|xZP&*)0r@iO%MHh#zk4tiF{j2hdo94gz_{d@<(CJ>+_BZvYyI;qR|5&rX`@89$$Af;Rp!QA?9cT5<>a68!!8R__r!BNG;_ok!^6 z6fS4d(7|x56Iu&Waq45H(^eJv_tqtNrD$K`%Ph$Igg>c{dQ`!;Y(ooIFa}si=8trc4QsEH z08;v45-g9Jf84#%PRJFag)r9^>Z7W{S2sp(Hv>O{i?0ZYiOOY+95AdPSEUFu0g1dk zpuFgFx&_=rXVWK*oE>mV&d|TO&s_LY%j-BP#ZLQeBTt z^Bfuou{q-#}fo($xi^u?U?*0B8z7Q$s9h*ZeKRoLT6 z82FX7_s+NnFJ*@o#g^AsJLaPoUH=m;DpHuDCYv*0j$lGhwad^St6Q0Jq%32Htp(eE z6sULKSL4RNQb24Wqo~GUVK5e_R&E7#hLi$RCZL@tgh%mwUA^uibC7oBZ|aIW5%}Eu zx^pnBe%3u^)=Nk%!-{>ZdLl$s@hYqD4Tc}vtPzm0E;l0Js%HtY>dns-ASE{vs1-2M zuHYD5o1xVyI>Pa$9zYlJ3>kV)WU1XwXbvjY8UEmLVj}JX_uQGkV2%A$4~$v-*Z`!Z9*%wE1CiETxU~tpBCj zj@MAYG(sExwuvI5LPgN0E^SDZh#RcpgQo&!4=~U8V# z+pPp5zEi3sL71D9n-aCkVqMJ7RML*B^s|vIXUF{fAl^@{mL zv7!zWoD`8w%PR~UrRS06m`*{b;5#3j%-2yU-Ol0qYx( zz&0KhO@SybUgA5(?t?*qH7$4zh-Zlz zH}@m>?R@H;n10eTyL-0D^bwtZId{=4lGH1X0#5P`VCaxrlx_5#Pim`U*a4{HKF{Ry zt^IEiSr=QJ+-ngqk?%Uu_`Kh`AYQ6QgiB}+iE>LGM59PV`vBs&*GN2}f9f#@bc&+> z;C#M3Bgk?E6iw-g$av0%qun>Me1NMD6Wma)U~}I*(KITt^!pox$M)^0wiRi5g&#QM zd#&6v4`ldCn{OH7G`m(mjF@4*z&Lb}d|HdJTO)b1_%U}Q4z&FqNEmC4p&d3kS$-$f1m_hh zMA`ftl86Y$HK)5oHpFIWNMc?nk3QDk`6wgR#<(lh;Q-9%`;GH2g5o`!Z|y{6u-KP9 z9UYAZ5`pv>1Myjd*s)P6!lM9cy&Hu=-Nd0C!hPLmR|#&2BYAir6)FlS0d`xH%A(!@ z=+{~yJ4j>B3@he~oaMXS;u8jk*VEPtZu9rYd76OiCp5KbVydkdYnD8lJVqHsfw4bK z<)4z4E^X_DWv3SNYL5+eZ3wKr^$3B^&eSm0O)~_wzGBBsh;iWKVKpz8gxgivqgtmZ~4G;gB%GRz+@&j7$Q&V*$;_xtm zsmIJe;l%MYlc9}kf5bSmngnr{9X*9bVQ6Js@u1DX-Ra-STLD_^goB9tpsO!q}<&m(xr z-`@=mRO0-OwNjT2+F#kcHn(bFxS|z6vj!aqsL@qLW_yg}ej;pca>Z~*_4g9`3{|k{ z=pvfyTJ&{6%JV8l?bmwNT}Acs(s{_Zh!0h*dqVCITXdSMPFjKF9=lZr)U92&q*N`y z{~Ygue{M#K*pGXqa2AOmpW^ZX&;4q0$u>Rvq_Q46?`z^zTt5BCq(={%-`5=u=Da=Lyr0b z2we|hG%pMBEiLE`R1t~ilch`;sO{S>2RacR+ZpxGA^CJpgZWIFpWw*e2SGP4@(q#G8FKbX6>~D)i&e zvpQXkq{&tf1Vp>DRgh3tE!v3Y!~w?#N~WxL^Uj3fM_$MwYVbS0b*;_0)Fj<{m8_u; z)CQizx$oX883aC#4JlM{`=S_}bp0Xu*f@&m!5(bR7I1Kc(f52NUCPn1D+9OL-|_c! zQ#d?#bX(j7jE4@Piyr^WrmTD{bfohKE#m*L{jdK-i~rG7NYcsP(Z<2-zt&$>)*UvK z(Z9_)DKCXBIQ0}*egjF*8+K~6IjKuDoB3s0YOdcF4us~?&y3Y|C@WL4$1RCtNI*%i z#T6aSLBU);0B|$_Q77wP@PQhmW&QO9(tI1|R#@MfW#48$e)m3Z zm;BoF@xG<}#qG)*X+2R?gIVM^Z`KeP?w;mPoCNb)>x2J-M9GOTXDVrT7@{Y`b8}7V z&Dr!)+zi~0-ulBtjdZHUI)G#q_s9}PtI;zlU>zy2g*)iGkwo6R3SC`lCb36DL3WW1 zjC_%G5tR%N+_dz(*X4BO?LdJ1CU$fWvM^r?*mW;5$i}LWhzTMxjAm;(wrJwbRg)&H zeSTbZ@lartL_7$Zr?b@QD-ObLR$e+{@>(K0m&xb%wHLfMxu#N>p_RqVx=M5CVz)^U zOttTxcl=z9)wSaj7;AWp1()U!K6#f~e}EG=rF4`P3&FK3f`P#9FS3eY!BhzH5J<0U zsdrkLEv*&lY>i^s|Ef3@XRGn9jFKZCX5=<^Y^f2?57??5(n5r_`c+yO!Y9sArN(GA z85hIjF2gz^4h)hk(A_F>((IZ`(Nbu}1FcnN{4xwvZT9N>vvF&sKMAF?%CVVHA(|{E zc9N9a8jv$#+B4Nc8tDeAc|Tf)Oj7Re4-hnJVkXDEuT7&z~61V%y5y$E2*g$=SM1j zIr+J$iHFuVHE8~On^#C>V&SIEVtjakCC+NMry?f-enUJKm6dS zP#oxW4yb`i$c;m`ViR^YPIK=4Zf2#eVE3CRSDzPc!#|yZ48VB@?wu|4^7t z^&yze+G36Bq(_rY^Iy5P(E**;5OWXGoCxmcXmX8M;U(=OY}Uf1jlL^M~a-GBOYkG-|g zoxqwdNS$+~p!C<&85js*Z^jEgi00TYwr*Pe7Hm7Y7Bu?P=jh7;Ny>cOD(@TvD};u zC3H-gNzbJH$?uL!0H`{M!Gf;|7dwt|+hx{-F9$K~FXgtbM+;k76agTeLFK4L8Pt@})7qWdPC!UInCET{&9qIjYC_jj&enlwKj1ig( z-}r=oPC|>2=ull-Yz%?Z8BEu@JAb)yI#2^%zfNo(@9mAcyaRNm(Nz&%rJ>C`$Ka6{ zZ&YDuznZchzdCb&;ao|bPG~anxRam`j@IsUd4t~5>7%~Tdv-buMueos$dF9A|l=Q^yJ{q+FRM8SjLb;`1+6O9Vdx6E$ zl^z>t4cLz;5@>)zBTXbYV$Z-!#Fs}QeKibK=>aZ<%`3V^m)8jJ&_JmTn3e}4&yl%} zQstA5Gta-eu2B~DSF0MGzTdTIUM$XYw#RNqPtgbpCsy`49cDe4x<;Sp{gcRBH7g-> z%8ixaCE-~pR5=j#_qpaLNhP$nB}C(QZ8LJwA`c5S|IkXWGJ_M?Cg4YESeN8RH{CCv zL75Mj=AG+u>n;D%kq7RX@9tg4C%NF$krsPJGze`iReEx%{VXN33~*_PfJhj~_$-JP z^Y4F#BAE{Fe_a1`;W%*r-iiO`ab4nn!g(wI*Ku9Y=ARn4|0BLo()#fSLi08@F)r2u zH7yTMv?AXDyS!S<9aQF7gM1KFU-#2cH-mziKV8XmZdWid!TkB7M8>^I(?R~$$BTuc zpA7&NQeeLAbKOr&);_)dlg-#}87h%5U^zAXp5?H0-!c83v5M={-3XWifrL=ezh!^2 zLfZD3caE%;9CQWVcM`foj-~3a{UCh9^d`)jqxUBQj2Ub0CL$m#fRbmcV`Di`Z0_(=A7*=suRMb@H=j6?SOu6kWehpUXt$4CS~ zJ7Mq4E5DG`#tUx5v0|*MFi(i;|NiXx1jd@F*@FPM){^xbULqT_TF`3VY+DR-9r+}S~bev9G25lYV-aIzOAw25ayaqHWB1020m|&zPBePkc$`a0`CPE-z zO(SSk*-dW3h9i?6Nt^p2b&B6W?U8#mQE2LpLbd$EKzZvS64;Bbe+1sO<{ND8EgUzi zrvAq7rzO(J(E=7TL7%ck=)n+jWDO#~Idc5|M4kdlLI zqnLKa7-ywKcx9Pn5iuOHlg1-x47K}F_txj6FhylV>Ot``o%fJJCmvSv5g#jk&;;7z ziY8^s6L#D5>~pR8F;jUmXX(~tu8j39+8H_E6Ae@I(XEe>fG`4(47~Qc2IT*} zff`Ez)g@NmTSicC4JfOI$Dvkd&G8~^9>;DBO&nh#*K8C`M{JZ&ztxPemQX>Lx^{)D4G%5>ERKo$^P3mBF5VL*t4VJK?<9b zZ4lN)_@OB~R|bWsJUdZt)ZHYGT}zk z7sxiufxEaIf-;&i`S}WPEErZ0|0O0)?)GvjbQsabvpQP2DgyE;l;dy=v$jSw<8QOO zdqmMn)$uR7SU5qhC$d%3A+m6uAlL}T{``?0G#OpM@P_0QpJZt8D)|Z8etlk%qVW+2 zo1Qcg>uBJLKy))dOV+q<)GQQD2!squ2K1qH;n@>cnDy6aN}>4(Y~f7|Uziet%V~+2 zeqTl;z8NUYFaYAD>O$9+?BuXU7!bSoTqjlpgpE);B_bs%tQZ66Y{dido<8hY)&zoP z`R~9HTqIw3Asu0@^f_%gm3SJ(+79{GQ;NRCvFTwOkHJof!K3-=Eb7*SbX5fg0beU$a|0+Hr%mvJ}XHB1Tjzr&I;pl_-=RT~6Hf7$mcE6ZIU1w*=K zf=?m-(0{Biz3$ZBUL&zY1RqcyfW`N-b zu=qA5h+<)KwCv8##SBSfn4Y!7Br7U`lf;KRtlvs8F~VA@Dc1O-gjBWds}Ti|Axa~N zef(Ogc*PC@*=t``AeB}S3MI~VIGS?vJmx%}vhn%;p!~})buiiI|^L{;x33zwyqV&U*c(VyO8iV1>q#^p_8tz z({$81ouTpO9T(R}<5lvukTk|L!EC19K)4EusFS>M&R|SomQ5ClP?9V2L8X9CR>`ey z$&zYZw^!TQZBFG88?`|#Y5G==L0u`g$8{0zEUD9&vwY6}L&Tq~A_%)ON?iy^jgr9; zuo1P?$&C3U=z+jO9Yl}G;=%whvG3|91tHTr=WMKA%XecmJgR^(-teZ3PuWcduaOl0 zcTq#LDn9;}10eZuqBCE1Tf~v!iX)*Qh?&G)ficdA<=pKu4TKc3i1WGyM@YHms?mIV zF%|aPWY4Ta0VBfXhKkF5EUuVJ&~9Gw(xbMJeHITzM1p~_JMXCTRBSryui`}QrY-6l zxXk9|ORk_BQyid^@qL7gQG;q!e|1$hD!L|2KL%IoXoZx~eWo(EiM*nEdp+}SZVMy! z2*CBwuSjxV@68{9mBrSEnNzD%bJRwCR7dBga^-1TV$RmW-*rw}I?w4D;{r{Kq$2{D ztqm@%3@B#axl~{r8buhi<)^cy)WiEZGir$_6}_>j3-;HjE`GveS8fKq^9Yp^+b9=E zuovGmfa3t<;2XR*Q{Dj^O~6mFGxAxPGk)|=)+K+D(e26`c+cxrr^I zyp`yvbg@Rown7Hpl!JFNu-GEc%+oEr5O#qSlU$H4jREhj(dIdXz5Szl&H(?2g~Fmz zB#gf_N)%rKQ{dR=QV!~nWc`t;B ztL4ixY8OjZ8HWZ_OJ1`trbTR0nPulwrUjy&EX7{(o?~p#D+7-3nF-|s`61VUqYiFc zd;mDG{lj(@=ow(pPoXSR5bhWFWnL3>0+L9YmPlP_NIZ_|$I?^RBpy8t4>SxdV*0dp zL&@xapPS&hk&{u#c2ipd22DR@o)g}>GO4U!c~=lK%)xlW1v!C9yVg-ZcB6Vb%I$7W zT?e?k@jRYT?HBb!4QMu3SdL{!E{ae37O5SsLg$_8R_jt7lzr6qHr=xA*2*Uu-Es=P z2Vo9aXO!mXMst?P=SrQ@6wNbR{l}Nsc=yjdWzL~!u9C5)RH)vW!JIR>J?lYa(DQHE z#$CUr8qX`?SD>uggrt^1+iWcJEgr1fq;A5$8B?Alht5ZM{{cT9909LzKNde{KdD&% zhY(}-NcGqhW9L+Ni zJG7aY+8@`EEbilsPcM(``f1kJ{qAjVuo~RwxRb#{;5J+0pmOns9ftH)qR5GQm&nOr zOCJ4u`t)=06jj}6{rVA+y4K#J9^=qR?0yCygac{hRmxiO`;7iA3Fu~hTM!Pe(=}r| z<+iNL1d}0qKz+>|rvY-0F106N{WV8uRYkZ5Ul%=={ zb(vBj{MEQqTI><|l5DMntiv_Ru1<=2;$ot4Z)asNI7p%Bb)$7&@|n1^Y!vWlw(x+} ztmbk1I(hY&D`JOSF+z>|DB)K-yw3C9nr=f6z}Dkw-Lx=urp>_&%|_{Li6X@yh4h}- zBn9n^KeYaud?ieHwr3!|z*E*F$)x6c0eevvzc1?4kj1iEtwvF@ZuN7#po))Nh1)M- z){9v8TB;g6#fvGAfJNjTX!SS|omcINyBV~if`O6#_yj`DWh)-bL?-1VhtHKGdoc^l zBb1X#pG~xA7H%h0xTs`8$aZ6nxv|Ykks1Veva=egR&i zQv=(=`P)n=nbqTQ5PaIIGYietnXtt?ke0wuyn0lcV1b!n{|n5CJeVms6g(5SrqkEp z8e>md%u>2eN|zO7v`XETuTCqzW|;FgL3V@KJj|@QcDC5IsHrSU=rFK&Vr4j6N81Gw zfUV!!PRUr7qI5qDnJeCutrC$B^h}=lhm2PJfWI+5|H5ss<42PEM-mvFxB1_fGFW}d zUv@twyPu*EFK}tduZtggn?>4RQT2J=Y*QB0z_85JB5wHEDP12pU4JGDcA0r5q;Jwp z(;APbktJ}wxjyWPWaJsezO9LY&w763BD1$-&#GVTP90-q%8VuaChy@w(X#Z))}ocXOCkWaJ%O;AcDkF>hP*!z=WIg5-># zW30LJ@jSYG&crl;DdsZy32%WZe>pg7Y&M(IQ9>MUQVEnhWwpf)k9SW%XX7 zROOAza;X3uZXTW${CY?!6m}kFXI^nsB^>Sv!<(&L=ZX_F!gT`;S@|=ofFmbPvfTQH z)aH?h`Dyu%WI8m7k4R4B*zdzl^#r@8@&czcGNpL6~bh}d?){(gM2>kwo zVtsHo>PXT9Xq^ls?&paw8TIo{rGqPT##3&`8P8r*9$C)@Pv_lTZ6LaYG-s;*`{a(g z^8Mo+Y38)mCs^8v)zzcBKYl(662h%|W+`)eJ1tljN8vsKpQDvX_N7FHaY1J63ZuQ^ zJf41H_I|#I#1qje%3$OE9qH0xDVBJ!2 zSk75>iH6_Wu0a5UCS5I*SSg=O>Rx|tind`<+90nqLE|0z3yHaRDcDmKQRZCpSgbDO zHG+1FB-<>XggwKGThR{&14yb?SxF?uVdK>Kmtj&Mwjv#mrMT-!#XnK`n*|j}o@ZiV z;3Q%6?J`Ow=BR69_%M;Bf3<$NHcEXx^iWN=JheDzi|kvYqQ@`#a;-TEljf*@!ol2;)9cpAzin9d8$(z0y93ecZ}iNsSn8G!Od9m`Fs@kR2`TB` z*CEdJ)UV(p7#BA9h||H?&Djq1sAVwP;@F_MBH4($(2nfp^sIajV^M+T+NkgP2utS( z&ZWC_e6*a6PQ9wzXaJ6iDy6O{v|A)rLE4;i|9_;tQ;;Oknl9R9ciFaW+qP}n>auOy zwr$(CZT6|zXYS1G9rw_B#Q$qWwBow|qQf2BZljN}h_?_I5%c5;GD-!z=%u8TRaCAj1DOv3~Ou1UgaHkvxMeH@Uyi%J}8Sx;ij< z5!V+g zzW<=vjE?9fg9aNh%Ot<1o5-&y=B?nhV8-iq)F9+O6?@bKlO-;H06aa4vNoilepmHi=VQ88&SIdrJivtP1j4Rzk#`m%hNuT|xz4!MpkjBR%L6tNJ*p+ctl&8r$_*HS`|l#Ek4 z_-h)op3P|H0g{D%CkH4qZ71gMj|Ee`JG;Z?>)wE-Xj)&vz_mO zxI3j~e2m_hVeq{2`_k|?NHErL;n^o+U8mZ;3i7A$r8ZgcrzQs6MYoRkU zI$aUMQ^zD6qaGea8HTc>+8rI$fx(4h`XE5hHzEl}0$2*t_{6?ILeU-Yw;s=_V2<}= z)A~+&CX z-fRfkG`P%Bz%keD&3{_5V2IO8wT01fwTtPGQWBTzdj3%hC3{y@FZ=_gWB${&`d6Cz zeq{%VZcO#QOX)4~2~Wvre=`Gh41CamK1JPav%c0>5Rm zVw7RjV#R{p2PGnE+p6?9{x^5J)Y)nHhe)Y$+pAKIp6P%vkGKMfN?ZHk`!Zj+ZeG~m z4svpQLF`a&M(&V`310q++(zJsow1EY+BFE!K)DN!BFAM#M84Qe=tM=9w3xn)x;4@x zj=94?0Wu?xFn5wut{AtM=H=>(=e3x)H_NNnb*5i&OsEzkFJ=m?Bwj3f4cw_lN^C*O zX8%YzzP~qeAhDP9CFCd=EI6Bai)Yius>uS2H<=~#NNqWn1-jZT+$D!Cf+$7rtHr$n zG}vruf#D3kZ@D$i^-l~YHJHeA^EnVG#dt8e}ao)R!ur^d@m zEEL}bu(c}HcQqyZf`!ZXF=(4&9`Kn=uIo(M@=tQZ3-!5jR~Rf=Ohk8)H(hIjjIT29 zu;i?kbkXkz;Vm{aGtKU0rJ-rDvP1#P>^T9>>=^;p7!dg(W6ADPr*%^w2FIq*r}j$k zZNuL~%1~-qRX{RrO6+QHq7>agxJ&CdW$xFF_bwluf1Tn4!?QJSBY|0&@NIY zLDZhm9k$ z7H!+1@po34Tq5l*bel}|%mZ(q_&AIq;K``@ChmUaUZ>0z!gKBGo%BSiSgo6>s7}8$ zu>^*93>NMd>4+=(ou|`J#;ikS;ZTN}Y6koD8^{=@=IO)FO`~XO>}q4|`2VPBR5t#N=KCw%k#g1wjeX~B`pswOE92|FCWZ%~7Kt=pEwFc)Rk*6K)kyy;?l1rdOtd^p)Bf**%hcwkt`beZdSQO61Z(zc zlQzyqgCX$WIiGhQ)de5f%5W5G!~+hPON05);Ftpc(r3V^hiV=(i5jO ziNR6#EY_`JGKMu(3wlu|jyH@z*QIAeSx<+h_gX5CW#ItVl50oKkqYF7$R1yPY zBG%PA!INyCri4t|%h6(Jq@4_-B~-R?!M5C-U!TFphmVznAP@^SAXRp|g}jrE=28$_ z%sX}UGZU>CCjb*7Bb39KRGXkCfrh|%NZZWS-d~e7aYjm@g@~O!>v-&}ZPQmEg^c@n z{hlTfZkV(gt)nzf`@LOAtw}RphQC6CDQsZfB9*4Tg0_#nU@xtWayRrR3zLw82xikN zd^uct-RBC&T1wF#rdoN2wztv1qf0Sl099&l(&<2L+=K${_<)c3pTLrIQf<3mU%0n2&6O zxlzj#0XZuA{nb9zFIuG`=7_ba^aDtux&Dvw@6vM=M-7!uUQ@QGjp-Ody5@x4Ksk3| z+Q*G*I~jgQ&zeYC`G)&7zdi2YYnWX!QLUC^i-2L9ye7fPq}qc!HvLky&2_c}b_Va| z0|y^rRQ^8XQetOfl!Wf^oMVi}JHm-?JZw1Xe&r+djo=$9*A22fyQ~}@AmXY_5or!P zjHWXPU>nW=yq6pCOk%GYzgOqlFtLi)id;;4lzT3#;}|H|Br>(&BdwrdzwL4`PEwLs5zoVScW9gU2e1>m-!LSL1z)Bj@ z764h+{=ziRw=*7P^`y5fo?y)ooMZJwj}tz=@Z#LAK8Fh;UCB$`dVaa6+(`FSfm6xqNFer#NXal&S5#)lgDNYmaHrIndqPn5uB0`ygd0I# z^YtYtVRZpjHFD);sdw0#6*1%(maIH>T$tFyw2+y2A5|t)PQRqK>&uF~d zABV)5V#b{5-nIq zU&jM9Wo)hA;s`E-V&N_F_bnp656LHOe6;dZ2jyDAs=h%VE@LqID3fe*#9ld)6!E96 zjws^ZojQ7D-%UGjWF^~LMWyKn_h?{XEyz7aj+W|(#!Z!}wNSC(cz+UQ{r)`Y&QU%s zjg|}0pf?p+fx3xDZ^7nFm19dBtELbt-pW@wo!*GnsZ?HRYO$(TB@;i=j)<0OKX6q< zgJ7}J)hD>|ARgFcs)DgrvuTpJ5m|y}5rGzgM-#r%%o&=r!J-g-zWr+7a~MsimMN0RYm^Xkm&Xp^9S^(FQTiEC;-ErE zE6AK~{Ysm9tI?p0R7YE(G4}ALFYs(j?V5om2UL$#=@=UZOVpTV=ts z@UTqa&))^RK#}`Vu?K0Pwf4iIingIY+BQZw>P~D4bKOm~h#fh!71(YGlB%W{*`aDb zwDnoPlX|MDq@jnsm!ReoL=?tB53M2+QMh8%NM_(!=s)k7Yc1MhN?0 z${Iv5Ac8K_Lq^0Kq>BDz^J-AWFlXw|AwQLrdB&&3D4bBWkrfTFtxS&Q;+7Q!qP~pC{k_SP#i$Ko_E~v3%Zmrv3hY|H)PJEB)7}}b^Rfx`#(MwO zjrxo&TI+}R>a2*{l5Ul0HfORjO4*c|+H(tW$zPgj6GLRA?(Gtc=O9esZYO=@Sq5kw znB^thKY4rt@wg+7cweH)`C{9l^5CVp#Lmtp_wa2~wpgNiiec+ckSbUt{7da@#FModi~|=Y z1VZBnZveX~xzv~eLIpIsb*x;Cq_=yja zxH)dA+bEp6Hu)h63c3MQ^9c2h3rIjRqQB>Za)ZhNbFkL-6Gd>Fp@!yWt=5RW@RXgD zujPE{Td{4T`_%m<_RjWE@BxR`tB4<`%iN=tqMFwsl6yLSd+n!5S)bbX!00miV%&bh z=edF3-jE0sI$?)N6V1kG$&<=H#e+>6qtl^vU&^^mm}kwDLeh3Az}`K{K!=mh#wK%A zIXQ($-;0%e+Oj4Yewr(F14dwI8-ES>!XCpjEb|nBCDcZa@hP{cx{WriLR*jVLakcZ z?@~S0z_S(Zu=L;g8bKe@sKklOXS@0873;l4sEJK;z};l$GR?-^GYW`z{+cgT-;2px zF3hCS;u|03m9?q&++$QbgQE|1YGKK%P_e$Y z67o_6zrkR}wwx`<1LJbfL91BpEAVIWDANYgVC8oH5=%3QL$U7WiwW8y)y!(XMfwKS zCr1V+5)S@`hwWq`Msm}5#caz1YM-zi2WafaU;RFtlsW7X@b4PJi`s7)g%$zw#LRM7 zPps0z!gloT`N!6FQcKlq`04Kj|0hS;zfwg)|C3*fsPT`P%*nyr@IN`DDwUld^zEk( zJKbdCN`Nw`T<$!^LLAXp87}Ug^2ZIrQn=1Eq)}+ooZ>V=g6YDFEXQ}$hyGJUKZHKg z!v~B_tt8@oyAnzJzWaBtLN@xuCOI~^QBKmt;byDj#OH)_hx_I7>ucx6=hrPk_2}tv zU|?kAFA@#-{z55fmHxz2(sesP+fWk?Cfo7UzOmUO-`%glMa_J6Vk=YQP8jJ(hy1yr z2zL7Pf-J!Y81KIXPjls&HV2@k_rA%4^)}NFps&aaMi-6* zqBjyWrVG=k$t6jf0smxwjpcIM!etd);9U#HJoJX8ED( zrymp&0T7=>jYYV->Ij5+!I`ZOAda2er4SUp#s?vU@igPatw>41hg>f5*^bvZF}Kqo z-#CI-Td{rMh&%^lRajl@tHrTjrAg_%r{xKZ6;*~+QEm_GkE74@)$U=RA_Ke7nnk4h zo6e2U)%r21&PJFbbq3N04`40`^{a!>8s_)|2P1Wc10h&}{MG^iI#slT3qdNJBh9PS zgTEnT3weN~+12L%Gykw#4*Z(6pNms+QfPkPX#!d1)?_8-Cfg^hl`lcvC@)==sygBb zrR7SjrE<%|1LxsQ=5?hn#_LvFmwB+BeqEiE2(8Io6I^7{c@t=#r{M6y%O`bKZ$5nK zrEaDX6|y(_erWcG?$b^NOK_*0&v=DyNq@>71hJg)Q>#p2wUp#a!!t=Ot_UEBZith^ zd;(d4&I+pJ{H0bwzqFKyNi}1)Bq+g0{*|bNL6kUFqM+6TZj2jnn{>Xl_e6}80T1U( zu};Z_j1g0kC>Wt3KycsyQLy3e?$OSHh%-(qX3~VjFkx)ch+*1J@9DuCm)EJ0btj6} z82JGySaoWIyn6c9%-7=R!mmlv+0d2XFQ^FyL|DnG!2(QhmQ%rcG!7U40qI#YQZ6fi zJiOVajH8lH>6Wl;fLT8LEPNXTN?TO#qcoFu#IEXgIbBo67+@&ASo2kAK~8q!IED~h zkie&!`rZf;o4huhGdBF9xo~^fvI>JM!mzmqCWBS!1H7m5kZ=DP7Z4Ak z^*^S`D$?-pVal_fXZzx~it?0Rlk~U^Un~Mhor&Q>Va|^t*tg`3v)GP^jTpNwxUC=v z&mN6wWQja>nag2G)^WCQn@y3)B%8*Rp1(k!pqT$yD;Hb4fqZcDmACNhip#>|5&TM- zlVFXg$T1W>5;rN8@wM6#*m$avt6l-IPxi=o-mY335_3icD_57lqjGx2V{PzE)g_9e zUCJF*MtaA1ZKD(P3RrZ7Of-9$Hf{u~dmxO_LZ&&S?m6cdrZ`rH=dec;?R?2%lORXC z6$xOnC?^ri{C?EF54$1Gz}PPwYT}U1VJ6~^j01((oTD4+#_L%j`=nJBuQPO-ye6?j z{YpT4dMoR$o$}v_;;@ipUQGAyRk?$BDLeAA;C8CS2@Cf%g3wH!MXwU-NYV${q7eY_ zA;92O4F485c~UKh?pd0><{vNF5G5CmiviRc1{|qa+Q-J>6M~V46GsNUG z)!^~<549OTB_(#pkFFr~pZ?U#5hy1vuZg8@2*)3~x<;^?ufW{3Ud@oL4@=ksIZ z=GQLzD;tEhU05%P9k>=?j9#{$UoR;*xPU)FA3X2qO^SAOwK)S2kwgJPc`} zwo={NMT^b0dh2u0AGeqz4gH!wY7~r1JovfYI}_vpn4(mwQOH^9M>$CiEY(&RcTz~n zWHIjUbv#sRet+)ZXJ$%{I+>s-tUaOwmgb|Op|s5_F^U~2=)5g?8c~!vIxf>eb{wlF zC|ETb?W2eUlc+hOA5$7ycOV5Opxfu(i9ct+S1mxkbj))s%MFtUCts4#%dxg|5N7cl z+vXGI9Hn4q9S2bgI&CmCW3jXtkds9pL@u|x2D z(v=Z7eH&Ndr@L19-FLn*LNS&r;X(A&n^*=Arl-vI(CdVFEALc4>r@L@hS|q$ZfM6U zBXZM_39KyMUq&TL+hZ|f5pSnbP&{r=b<)@6&QL1BB4ipOBkhhqi?V#uL{&NNe_q*F z7C2U^`Y6q8G$(bc^?cY_>yFrdeB?})t8=xX!0WQIfqB(|@s z%K`77Ki0QsT+u6}bQJ-l`l!RN8t@zT#6TCfuy}KI-XoBqHIf+|a0zZ8t6=t@&RY?4 z*JhYpAhJM-`7&Y!;KCnvve?N30sgA-S3{I{2iTsfxiYHUzv$W26s)6Ml$8!{vAAN& zY4x;XR=!HZNo%Z<&*g{IMj$Ic$_X%Nsh^X8qs#==YolbWg0xieS9az{N7Nazor)bU zn?-o0;yu+Jv`A&^4+*K*^Ab$e9B?IVX2(F1y%LF8&kx;`BN6}LlRDocNaE;G)~t-F zs@>yBvN+wtBy$bMXE@!HQlXP#32x^m@EVV?p-&uEQ{0Pu1-wD?2G6JiWR@HI2`=Sm zHGDgJsUJ9E2GMu!hy2_EQof$b3fs3=R=pbn1m z;72?^^Z}h`>WVd-6nSflN!%4PoE3TTPfjq3bqu7Wf1Y<%?5Qm-c30GNQtTl(Y595H zL@LWvnma$^J&W1dkF`me^$E=3yHfugd3X`p(jvp=oOU_!P}+J$DhzEI} zeLXJ?LAtUG%l2G;ONlalU11>6KuX(4`f5@7%1HXiU9rPS(Q{U*Jh-giyBJuF_T=|uh`$LSwXVz5u?3IWy z9wYn9w&Tp(*3V5oGvV`XrRziJ5z?DTG2DT{S!D=;_JK>E2Z8AVkcNlnYJuHPVO z$Qk9PR!wpq#szGcqiZ7l#qG@}o+p;<2=b@iR(Y>A*t&{pQi4c3zSMfSSxdH|Q+bLi zf=!t>UMMW$Cma+Jfw=@sg*bd_RTy91bGlZjyR!>F({eo+LRxfs8K43H>w*vcfdxi2 zzbNx6QOR0#fiBN=B%XWJC#zH&rU9F&$l>7mRg0!6!Q?JPRy!}9#}2L}?&es$iju4v zMZ_qAHzZ9}m-3Q>L2eHT^-E27ieJvfFJ$*U<5o=nK|-C9WAJsl8k4R{jL0db8p0m{DquNFL+j#6EhE ziJ49wv@tRUiE^G}C1&0OWS0mk5=PMqGKL|&3@Wlm00~mM(GGcfve_M)U}7OmkP`(1 zVIN=^oBQDHC#L^v$z7?W8f|JZnfY;|BE?UO4;$P;ZY^XkG^u)^Vfrz8MA5zteK8S;ZxEJW^>GH=mPM~%JnxB&u9avXhw_VuSzdfn>)PWT6f`XPhR^rDuobE@R_M=(_SV^)_y z*=P@9APzDsx(2~TonCMAQ0Eg_zso-!h5tP0kc`e zB1jcJg}_a!5J5ENf}65W_Juj&L^$~nTzYZNqf^%$YsKW;D~`S;h?zEygP%0t2u|k+ zbI6LQ_J-Xqc>m6!#Q^?0B?t0oHxr$^h|@ijB_?4u>i1y4SN6p!QKfwPQvoFmVSGWi zgz=uPajI!iaP#}t5_VUEOx)22#y)Ba%=HV>5b%Ibq8=y}JFTfGWUc8_kY{%+@5@#U zCj#cmbqELg{o!@jNAf(m%amxa`TUm zDD4N3)^))<4%RM*lr2adR&fh%)ypE18Z8&fM9!HKTe3HNUE(b8s>R(uus_6X=ef`y z>`w&xzZ1Ux-*FKCao*`${d)uF|BlBoj^>sDqK6aV4Kap+;3bc31!PhSO=igF0}M|( z1*>UFGqV=eF$GaA_}Ti9^q8A_{kGkAlL31+pup{@Bv=T8W+f#5>)2+~+4q^U;)Fx59;#0Edx<+I!vN#e@i z@AqrWExwWyCW}@Ta5!L3`dTqaa?w$NV}>DH8GZOI4HCYu40D;ja z4K9kuG)`T|OY0FDH#Wn)wzOG-IDs39>I?X6*SxSuiw2arSMlyyJ5#4=f7!27@$e6woKFKlD#6d!f%XH}{ioOG zU!gkT|EnGU-|Y1%bttdIpI+IVH1Y1VF;M{lw_s7YxY%FtaET>>Mu0$LM0EIQaszY^ z#F0`a{a%cF^2oSHQL~UwP1=|3%VwIIO(cJiW}97>mb@3YY&12uY;Y|)Y`3a3Tjm{m zZcI!V-u!`|UoQ4(ceqbBJ!igl9H+TovhSK?b=bi4Sg>6UQF!d~5OFD9X<08x9(Evo zE<~!wyb5=HH|^3UZ;-q$gDn{TR_wmmAf--{LejL#8_@v=jYh?h7%Gll|A;T_$r2Al z!p06M3R~&tj4~nHHdCz_Y*>Bo(csGbF-Umc{Hft`_VyJ^<>CYgwUnd?kui>jp)sfr z4F^~2Izgi*w!YvaeFc>Ei|?5DXohw~vxr{v6vBTVFrFmc+KrxvYPr}Ek$wMiGJ5cl68wP{l^ku-8=1z0i6;xMBc z)$)jKUhn)8k~z*qNX*j`%7r>M#g`10F#6mwl_*n@Wi-e&Y7$h!ewwPz9a7vEI?7$+ zXT)Lrt(@jD=Bkk)KLK451THp1!<94Iz;Ij5xwnWsH15rStd&kpf^6`S+`OA~a$3d~ z+P5z%%++M^X!X^csme(K=Y$;b;ukMbUvc$YtA_^s#2Qdm2I@{ZY++)wlN$662y3*Q zKi*%!4L`Gsmzgihy`;A}WG%Z&%#8)5D{9KO1twu&i~3>}+90 z1?#T9Z)u|RRxHZFSC)qMuaf+x`RpQ8&?B9l=px6X`3xpD$BhWE%CsuZ_O$(`;HyZI z4{epXa8}3CGqE-B&aX}*;cT$9fNaU+(dQraxHi+kUCom&^7pEL*^=kIwNX}*_VcT# ztX2SkJoIPR;du&}8R%Ef$_7LO3=16--ht&oFZjR^MNOTX01x!#j+#EQf9r_$2`m44?vUi2RO7 zucsWwL$Mp)-+Q)Wf|Ea0IR?y&g^vcz2Kdwd8k2&FzQSRkt>G;tTe%bndq|hje2{-U z`_7`QKGVsHFt-jASMKInAK+Z*GI@-Kyuv}~x7&*h3sgnd9e5g&3f~0JdwqWW| zWy0;K4Ny}rgs7iuy)SU)Py2Y{djhtVPQq+UT|fXlHQWhRZ~jx7X`@y9D2#`1*~BV( zh9K&5D$S=Zp3~4i1a;#1Y}ygq{%=_!#AoJ!NU)Pynmw{Q4a0M2h?^-AscA8+?o?j% zO@$ib=0Sn9?K*Qua8+aI%LgO6(dScM2O52o;nCJ*lsW$}i62%IHW6(JDHJLaJt6dl z$&|pPnA$~t&8fnu*(vm=*HU{zYZzIQB$;$$or&dh6@ZdTHkc5fnkKp!1;)O36vD|x zR$wO!*T54W|v!p%$uzD;4x8^>J zY^c$r)G!wVI=8o!eve)fgLiHv-hol^%1pdbVen(>H$u~m)AJVfms-nO#&DVeR-YQF zsQ6Q?7yD{eEau9iQ6P}L3 zJuBPQB>H=V;1G9f3f;|o%Pc%1d5ywgQTU7j>`4T^>^15Z#WN%|RB&Yx?W6J~A|&X} z*DsJeJ|{}kT5O7E-Q`KT03JG_+2P5@GzI(HdzUTOT_vn`E)ee$`Jp|0kC+`7Y`@oO z37&Wu>u>9^U$_LwFA&s%;JMJ$6w!Jy;kJ7K@WZebuQ1=r!mu977Q!tO8MnkqfNp_RPPc6G?gHs?#Q`{ z=B?QZ_L*{&*Cp_S2q>K8l#0-9vN-HzhSW0^%`(DKgYb3wTa?rBn{i3EI=x=&h;k4? z%%PX!{!~*Y%8`p}Q&^W^3*5*Axs*Mkw`b9vDdJ#LZ1LkKT@U`iV6vXBrHz`axdz}h z(LUf*))n*GPAzmB+<|ieTqv(+`^PO6#u!?q^IebXKJ&t;$&m2{^dXYyCbyk*pIwcr zVt|~1hZ%0+j#Z^~z%PZnTAu{eFy`6TO=*CWaq3Zdq9~K1k z*Xr~$TdL|1V~(9nIwP1AR|SHf#h7O6e)t@2vAXNR`Lp^-*9C-L(Wj*XIfy4`V5kwF z02YevtK!G>M<<~G+*lQln9L3CL2x#$fe(k0B9+hTqen4b95qqG1jCw(S;=<=^hnDA zTC9Z;NNYv9>+QqNri)3Rm9R_0`&@rYD7u4})5}R{rcrgq5mywTdazY=56ASlHPx)< zhTAU}^|d~UJscP{x#FbEfPRvxB47+=nNfSzEP*@(4r%T_w@AVhyyQ`dIpvFPR$e(hkOpZF<3*1?nEV`^-9Ma00Bwa%}-R3ud=BQ~OA?nnWS3kdgm6Zj50f}dwL|>c! zEvCL(eg3m)lV%+9;Bo7`P_b43KxJaH7Y+K@Y`3G#3OIIplKrOP{p2UK=fBX7?G%7wn?zh9V(gh?6@zxAr4u1Z@a>b`meV(l zWM}&(F4tBC)_l)c+mabr0LCtL%ux2&J60GW?h1RKs+5Mc9NaQmrLz=3K7)aGb8;ha_`up%Tp9pn zDHlm1)$fsL2z0!MLN!2ADFQcTCiqKV=(Xo6w5~6nZJ1HnQIaj1){e6ITE+(>8)f?hhm8=?u(i`kPIrs%o+dG!Us1HA73 z>e?wK=JYeK_1*0ntL@?cjt&8Xh~_n>z{Vndy^;44KMo?KYJmDk;f2k(lGjq*jxhJ% zcKn2YUV0c!TaKvDXlIXB#MT`oTchvFkR}{^q#+U5yE(AipFj&EWs`Mr%=SWnYQ?DB zpC^cNaECl{_(aEH{CqsgY>?u$j`QQxq1rnYc4rk?%<79wKA~IiL1~c5zyE9yfwUut z3E0;1Msj%Fn5bW%;)alSN!|@wET`CbwHF~dj!L61`;*J8jU9WVj zYzcx$h16+VwrfcavVyq*7>vGW%^Sv!BEd5$$3Rtdc$OId8{JJYg5I?#lzQb35sea@ z74c1Kk~8RyvLh~`$3a8mjqRtCH=ESA--1>T=^{spMJg{7+EgkDii7RBo95sgv#coN zaQreXbT1*L>W{1}tCPp)TZ3bw!0PIljxbt#$s1b@Y;cyxa@ zOX_Kk8o|^Tnh3ar196@XmG}Uw4E)d@33gE;!T@QI}r2(D0#?>6bsvcCzz(uEpMn$zTgqwF8rngBbE9dArLeuB`>79MD z^1BF1>FC=uLbcWXQ8W@!rsm1Zq4Web&+g63!`)^>=$#s7HRDF>Qr7h^v)GU9Arhc0 zlbW7C^iC+sj~EuG!q4xLW(7C-Svtc$9w1<+%3gjtte1}187l+okH%gxPc4j3sBS@J zK$kPBcjOep7srin+6g#(vlj|W5ta`dJ-%p#QgZ=pg94}Jo>DVUdX~% zXG<-q4gF{8Eot#pWCb~T_+LoQk1RGt zuCwC2BRKEKn6Ic-ySn>qT@j?G+?fOq?bN0NSbAXG)3Cqv7aQhFWn{{Hqk8t3A6|W4 zHLHIKDSYs3H-O4eJ)i6xfT5I)r+J6csuh-xy@Gwp$>>nnA115b zF0fN7u5XUk9U1=`lLi=L9@hal6iw#4um7_ePVM)(iXo=M5~~2p;0}l9NgUfk<#%Wb zMBV~?k7$Yaw#Ii%ANv;YYmLtTrvZnK6f{tjzerwyOWT5K`m^D`}vFd^#!iDIGrX8Um# z#HQNQ=|o{y3|<0bozsLnN6C%oiRP=XkbyFENg{lw>{we{SF}QXRJ;0lZ&D1-O#Nx{m_C}R`b1r*Oy9MbE{Wa z!=b;00l^`m&kHAKeAO4Q|Avd%QYh{t{6zF$|5NGhzf$0$|3?tU!PwN{$MN$cAEf;U z>uqOcEM;zEtnZ-kA20lGn9)0CN&<);DMu<%>4{$K?=PH9m zDN)DO3Gp{lh+hjK)et62w_SBo^B<^^9)v-bq)o-hNl?p0mYSwr(Ge)B>tK)?KJH(- zas6z{XTergrZti@19JTOf1K{Az5&qT7)R`~hGsgWvYeymv7)xzU~6As{%ySdd7ZfD zKf{aoC)n{{$NPVdRs1jGm6cNb?ayNc=K}o;(hb5y@US!TC?;0yVvKF!(YdX%O5z~io_H=EupJ2HWN-! zX2yJUBIXS|T_1v-)+i4I1c^D3AhaK)o{SSUkj>M)(#l8+G5B*3ylCAOdoOh7IyVu{l8& zBSOSwTgv3hV2&m!L3kjGH0{;Y>aOEaE3fhPuN^EN?B#b@IMbdz8FXKIm4z z!l+FY3B$vq1X+O4Wm+k;n9R3cA(JtS+_1Vg>x!Jy5~&zwBz~vQWHhT~9CF0QR&s5;2@ikU6xC!{=}>ZL)DCm8vVC>R<{u)$N;k} zT6O<+_O>gu@j4SEV(^7pidiYg%*Z}t*=&#SoG=fuhOyFpquDNYQ3&=(tCt>=^-q{p ziTL5y>t&?}qj84_z9M-xM@pLUZbccGq4-m+5U$4J;-vQq~>=-24uj6$&w_4sx~{<;8{Bj84T2_(plKy-!!_z&xG3aCB$y5OkL5qhik8&_t2r zH7`YeZn>#=zTzV(K_8IAOkT<(E4ShOf;Yu9z*iR>-F~*`Zpb_Hch-Ghzq>0AJX7ax zy|HWdz%Z)MU-7HSp|{%X9ZlFT)Gn)t8PyvjOva>5PWj1M_r7NDII7QH;Z2;hMq-?$ z_UW-p0zZLkPE!%COJ380b1q&%e98_$w@V3S$`&&A69+Rme1hnM=KhWp%A?g_nz&V8 za)>N^<+%{-3xJ5LyrM*!ksdHUkt5kT+sikSw%mPsf zqUvr4W)kopQxdiK>(|7>)ThSxbE0j}|D@hc{7bTP^6g#YYx>}iu*e2hdq|RS#pE^)w zP5_KGvBh0N%8V@}Yt%CwvD;1A9*hTz?7Ejuuzl)4WK{fAl>V4f1y-&)%ydRUegN_@ zv8TB@FN$`U$CljzaW0J}-FZci3`c|iL(g!4j}7IzJ-ja%fVw#DEF#Eo-7<8jKT8!p zigmaj%s_+58{4C|rKra2{JrO|6S36$N4J|9%!WF#rCW^uNVoix?XRjr*@bFTxPuoT z(&}8y8G6|nMx%+xOAwPs;mKPdqv)QKHr;*KfI)oeGX8BY5m{yrw!nkK{{0_24hdHf zB3j8`dZaseT9&NH!vY#%bhl9R5Q{3uB)5ZAw; zFPp7l*o+mSV4Rez?uLrP)pPkP>KrSU;hwHdt)vwkBAuXs8sJND=Z0_2Hhgc~_b5{u zW#p&Hzl!6ki{tJfJ<1{3dbQ6 z?;&_WvE}`?l5Vb_W7Oy;+&%Gq2NssGr)Wcm*9U?$o_r|3(r7+|K6TZ{d@JlP-Si}& z81G6~%JAP-p(8n@4~|s0=32r(F3i$<7zO_B_T>Gol!vcjk>0$Jm$wfdI;vnpBI?|- zjRYg=vUJn6?(zUoDku4K0faXQ5ATG*Yx9MITMoK!H){!lotMdFxw;h^mf>bs?2CM( z%m0Gmfh2Ri_Ry0)2$j(e2HzAg7HXKYuFeP^3WcgEpOVNMaXOI;?3dpF_rJeO{hxQX%>Se$QnEGtMb259{P!1kk=%rIKOYiz0Ux~F z?U#B+Vicm2**;+z30kjUK4b^RL{lP^)dI|*jl&+;tK6_e02zref{DXPrpI*Jh?j?t z8;ETvH)IA%Gw`@p(z1X+m`ELbYKsLdAbXA^CD01sMEOFSnl`uN?A@&rD~gU7J=2Ch*IhA#87Zbs{)318MBt=uV<72KW9Yy%XO)4A_1JItHf- zL>h4gk?+PF8GVa}nk(s^MYIS$vn8{V2oQjP4rtVrBLN~XyXhkM6)54GI=j}<7GY^Z zi9U1^s?&|giX&Noq{+4Mb`=Vn7zIwk4y&*K$p=W7tG?;}7Go#>pGU|4b94Vk1(}qM zp^>G6t&xG5v6;bt$bv$y21d63Ta+e#N*d`OQqW8gItNsbzb^)A?LTiQWc^J#V18pF z^sG4$2FNwp1x@#G#ov*f70`Mk$tJpEkhKJMdqB6c!y7>D2>Ov3?Y!(K$DCqY->=Wu zy&TypbfIg1900Q6Nf@1lH&{9*3&*?*q;p>a>(tW?wMo0Htfr5m1|lYCX=@PrXN$!m zcL+RH&5LQ|+e-#$D(IpN>`GNXt}%y7@LxJN71~&pnHOX=9Ev%UE5N1@zmzB|5=6bu zGi^^RCan0&l5yzu^34#wQ%A6!b0FFE%5AJI{1V^1)$X+t;GJeyEmBIhXc+5!ecYT$}@)v3m2`>1Aij-a!wL!YAAYDGhC|NBGzTa9}t9AW=t9ut*F74WI4M+i}-Af$`u@(b}bJ`$u^ zgM$=0Sz&$W$Q!J_e6&vf?%8R(!)(l4 zwPSal^TpwI?)1^4UC9qRv^`;WXh&dg{Ufy#+i=HEBp5hoVi2`I|I$vJj@-Kn4T#Y$ z|NX%D6g2jx7*zmtSHh_=`(MQvX;%~UWte` z_>h5^Knwp?FwV@?w)pNIw=k2HIwZ)kGoorX)4*7xo>0_WBcM?Z;7qeBL-KZYFS2Tf zh~K(C3_1jg6CBnU5h!$p3T~uBasEJLyl9L5eO8X*0%2XEf5(XmLDKR9{sdZcq#}he ziNI7qS!0pNLROk92MY!(hb3`G7WASVHp{#RawTMC7e~q8YMVW_5z>`G`8fTWS@_3^ zCUQb<19j+2L@=!cCYYyF@bc~Q5~pB-*&Pg+iE#Va9y%X-Yn*yiiFXZl>GS}{cuw|W z4NuAtc4X!Q2E#+GuX+(oW&?t7`>`Drs$MAoep*P62vjb=@6B+|wh?3HkqpLx$i-Bg z7`bk_&NfAslV*>N;UNN!jMVY7DeB|YK^F8Wpm9q+9C#-b+l)f+ zVV-7QY3P1E#a=;U;wJXVn+z4Z6M*%jecL#{A8!>S=2iV&Z?EAZi@V@u+F!+EIY@%L zY!Cn&)hg6?>=rSaI-Mg+gc!rBF_0D*C&{T+wEGOgr(pmb29Z^Vw31HxB>WcN3=7f|U2-SfQX)QPX}U7&lAl7&2# zT!d?FdBp;YERES$Ps0z{j{<|~_e5c;8EP_x{`~h|3fkuFmSvi()c^o$(UAx%26N#3 z2>*VsWk2IhAajMcztS78Ktp)?lHilMesS`I=pg~;m?&;jsHO}Q*4oUA{pS!vBrV}7OlNG)G1TR2*#l*beV*hCMTz;xWF016yY~LK zSPIQIKylUEe$ApQ*B#Cz(FEiK-F;$0V1;@izH+awO2 zKoxoMHjpCSo6?p;EZs_*(N}KCa69$K)jnX=Em(jt+-+rlFP(c`cBk2U&n<78*?YNc zY7Jm)$1WOrs~r3_*m8huPORzY6nwt0f?ePi%or7qosZBBiK>zMtW0O@$Zc{H*>>e` z5ff$lw^#vY6zMb?G`D!|5s(vR-|ux0$+F7TzA2O?^DA$lIyveuF`t<8*J|k z#B`cC{K6Y#A+Ohfcyq`>>7`Dh=eR>si9_UKz~F}mLU-Xku|?=2MeJgK5EWcA3rKH~ zevEixNbe{_OkR0rny8}pVq8&th8>zKU}wW<3qW1;NPnV9Y+=z|=9?TV556T{DXyCX z+{6B@n}MAm2s98%1`+&>4%FpCZWbU<%LRq*p9}&#d5|fbws|mwlaPyC(J_tf!la3R=Q2 zXYlu{18MvS@kOt-@KX)?|I`o2zSd0{u<(Dr%D860${#NM||+ zqGjU}apqz6MDGv%nJF#wJ3xXz>yZ1QYFdJ2*#$o2To%R5JOf@BI~t?4`2jIWdScLJ zR;n zA5%TN&Q7W@JI!3Un8z5&wtV#=XZA1_CX728gPMDql=3hO+n;6H5>w}#{*o8Dg?k`O zwZCL)4Le)`9(7LE-Hs27ca<1BF-@2~2W`FrO&Y&e!_f8z~%DmZj_&#yF$-@0U zs{{W78RXa>^O0qHpmD^sJ~Fjq`(S0=Jun5d>6wxN*5($P@dblLHZs6=+Dj;n)n6dp zYMbg7#rXD@b?4yBU=!=;*bcLi7v+Q5XHi(1%MZLm+WGzxt;VyyR^HDeJfr6*#%H9U zr0uQS>#5~tm)C&HW7y9`Z5KB4)#Gy(oHpBG7dJCC#^-Q`x4wov6mOo_?qLSzGu7oY z0#V}5lik}N)%7R>rt`2j6p`|l;lX{#FXz5qCCju=59cc~Bc~yB#dY8UrgN{C7VEW$ z&xs~ZYG__7%#tPveI4r-JTwY0$to>RlZPeoCcH=lp&6AEg_XDVGE4=yvMsL9T3z76 zlIwC=lzY8V{2#{IIsxl2g2I4s!lqY!aAcJKRRJ0(@NO#=d+@;u8{{xhGjVP$o>YR)ZOGR z-ai|R$fFioYXanZsWm}{jL|xGskp^mTMl@Zzm#EOUbGU`($GT-gkRu@JR+4nJE#*Q zqDAgGF{o?JL;G(*?meQt^F09>S%r|$z)#Psx3>DFI=MyPw0uMLMAUG$#)tuFzay6h zw0oQ?`tju-dHGg9khKuflHXnEtk-2&>=2)2ao?PohLM_77W(=vDoA{ap^YXr4y-30 zkNANWM;5@3x(o?$6>;)=ZJ|sMzsg**p-(LEl#_WFLL-t>sYE2a%86l9=1N347$v{c z#|Ps2Mvn;T_4j9t8P(#sf=aW}JgKZa^*;qKSrCiOJOnn@>(ex?6<8K{5oQp*K<6To z8E9&3Z=6xDA{5i-XfdlWJ%&paxw6Vg#BbS@MMcEC7wuw z_th^WhvyC3Roz`V-G-NP#*Z4xy5Xn5C3tyACLuF8yo%9>OpzzVi9_T!iTC;se-Ogqd0r0M(<1ML?DpZJ8^PQDuF1JiueESZk^S@Sm^TW9@p zA@QwQ>>TJ>^{fg0w$6?fOl>;qMflznKAq>DCq_e&?vKM?ViBHTy(U5agdZr1p-C!m zuq0YSJZU9|o?yE!1hw3<7<@EA(m%G{!bEr6(y*FkYe&qq+Cn?C-(sSELw9Jp!uB}r zao~7G_iXh}eQ<3}6>x8QqIUq(ysF-Y0XF_l58`R0mh?pc)kOWq9>IRa2KwLz`ry;O zBL^n6`GQ5Y*5~rkb^RI3Macp#)eVkF2cN}V!`OPI1^eCz`q8`544C;_$@Wxg;QVvZ z|Fb6pSRn%_4>kpK=171p(PErH7!a1%3BD5&DC3Kn7Yh*q=@V50!IWd4hgvGv7eCG< zv`C-XF3-6JNIGTzK$itjmS+e?o=I@*X+Ka}S>v z-6HxEm_WvgP3XHir$)gA|DLI>!-%>M8-_aS7Si(vpjB3$t)TAph`zk&@{qk73@t@z z9gmWM0q3JfPz-GLM1v!mR2c9w7|;cvRaGC0Pvh3kkxh=Gv}YPTGWNphp%pE0f>E&a z6a$I!de%iD*?GHi4GmODNwDzQcd98SI+mCMQ#8q`=XJzW(R>-#(!1Fm;(~=ll}02( z_`1SE(B7g~Jtd1#nYTrm9EzFN32940r+GW>9CWFRLGQ`KQ#oZGbrR&Te|oZG9D5Bj zmi1NG^ZNk)y_BujNpNX+@bfbn<^1|K&iX#7$@KEF5MbALX-~)0&5N92le0*N`heeZ z)0H)F?kJMOXv2Z7Q~*$iuiH$+a-;tWZ)<>Fw9W$B_pvY{Ya_-O3- z9`rnG>=?pk249u?DEl5D#sF`c1EKG_>{jsRA}ygP zCQsU~s)CZi(vEneqcV|6D;>w+Ggf(BdM?r@P>)Dc@SZh?_oE;*lQ&ZI8Z zSn3n~zjpT#zx_BlhrghPkh08dXwC_~WdZ!hJ@Wu$qxn{A)snhyN zVR!Xz-rKe?13G4eJ84FkJLN{OJLg7_JJ^~bu6NB6A#YuZ!lqmq$@VbYYfs7 z>^^DF7_4u!>k+y44>oUK(px~1TL$(Iw(P;1TO_U6Y!n(#oykE)eVS|~Yn!}6n-Vzv z7LC#=iWZG96Zy6+=}cNVYgz+VluhXZ01P{h;wVS1!jglJ^oHL)ml^hY9)Y&ZB$wyI z0X>y!s@KpAl!Vks*Ipi!B*}vXh4{iOm8nQ?J~0@yhJ&#JG%F!FSB&sqg0MdciCa~Q zJc4Uj=QBh39faFeN$E(1s&9@Sdy%?td?9L0!qqlj$G87BY)|3h7qWFx%GlOn3D_;k z+XFRMRLh-#dqC&74BRJZPtgge2c@KTsu_`4S6m@vB$1Xi(OK1@h84Ekpy1*VJ+lU@hx306?W2_A)&Oz#$9nk%qU98N`4hn*ts z1A-Jy;c)vco%Dtk{0EO`xoNUG1mWK>20fvsT0K890mvz@{<6jNs_E3GLRDcUuO5Jv z7(GpCxCW+X`I!^NXz9Pu*G+}(N$*EdGqNyJk$HLy(n4Ec6^pa#5vE7|?)_?lY(a0K zXJn|1vx4CDl8YFlp*?;k>}fWFX*O*PIYtQea+-Pgh$n~)ET3J0ecU(bY?!3SQkzji z7~SL?-6ngnAEijA%b6uJCsIhh>Kcb2%Vx^XLRJS%7x^Z#eb{E^3Dg}`hDQe`k$TO; zPUXW*ifRD^P_#EmkS9_LnS&cUH0is5(^}&f6ml}t?6?+#o|Z^br|^)qNyGGYXyA3g zE8$12a!dx1?;eBV1>uc*l1F@$*wPJ;@aVmCTV00j6G>;+#0ycei_A!FoMiS#M1;lU z7)=!;bZN0uyecunYeDS{2J)>-rM4agi)pBPOmoo1x- z6$+9^ptj4TI_}~6GekK8j{PJo1LWW(`xTpDL?GHrFLiSk_J31F6k&741pe!FG~1xfvtg=FcgrClLN^Ks0rT z3qwl9vNg<>@)ar&m|7gw%akD8uTEjq?M~)Qde*cOByNdT*I&e^J^K7Q2Dvx=CeTYk zdG13l5-dAz{7W^=zC?<{ zV8&JI(>^>h{s}z@e3I&ae+IXDe@oaiqdt1`*nb1K`y2pw^X}U_$L$-V`xkZ z2N}VXQ=Oz6($E`v&k-$@-;WQZvdTJ4!)JEXO-tb$*|h2#2#67>(fCf)LnS32rJ9=! zJ5Goz7$bAp6qL*?Q8ZATC3b7iRAQ32MXz*-ZMtEet40}Si2*%1HaNx>=APvpvb3fw z5aN|GoJ)YtNIZr+6=vHPwoNZm02USv!6FP!s#s5m#T zrAy$794d}4zh+JTGRy`-QUs%)xc`fyHaus{t`FfWUC`(}-w~;`D6I0Kaf`eFFnVgk z9O(vMi*Md{^f0u0*Pp+Zqz*grjZ)y+9wl zVAn94Msut^luvT9=|XA4-H;XxQPb(#4Gna13z_Qnu;c_M34R0AmC2k1Q)!^4$zQc1 zFfVqkId*eUajkE^Fr~J>a!nKB*AVTgqhxN!hvR@(PKcUPvh`^%B#E&F)JTIh`Y%_u z&?AqV{;1{=Z0>ld6|C#Jdh~%`iZwu2r$bi*wCVV8MwPR+CNI0mqhL5J9Z2Uw%;3x(jB8pM%O4N(=6t;o?&QhfZ#;+h>eCT7hp~hfp=f{8>VH$slMUXd7k%i zwe^b5F1v)j`JC%gXn81Lx4>DIIT%`b3sikMc%!Oa@@jH1aB?A#DVr};k$;f{WDPCL zlyI)eXPstXizWR!tv+`ckix-tp*G?`|TiqcM0`GB1r3G7i2@ z+ZrWhoF*HH&Vsq!ZT4x?H`60i4g6sEL zfBrKCNk%zYu>IGnSxfZa$wdD%tEQQyrIG#r>rVLp$wltqx{6CnKkP5vYK&=>F_Ni* zNV4^DXt_Xouy90Z2+;5#m1D8!{F0-(2rL`s6=qv4)?^eE^7%>?rGF{(HJa2dwyM-W znwFG5-qcoTtdW0u9Ck9mRj+z>RP3&~Z@N8Zx?ZSy9In0G9(%bz!b+1dyG*?Kj(hN? z3RMCUrD{OaK-Q9kZ>jLV99yn_W68yi~uE$@hF%7HLnH?)v}KAJWoXUBK;$;KNJ!Tzr+h+ zCmn6eBo*rBLJ>{jce9Y77Y`>OC+KffEuH%pZ679EB#%Whgocaz8`;Mjdi}e{th^eT zziaIHfq^_2^%&~?w{YjP8;=tHnZ>ov=6VNl*v zf?Wd^A0Vl$W1a-11{DniH0J%NPj|1U+i})Qc^kMrozT+KK^vz@S~+{Ywa7EOwF07s zo(*FKU8&Q7ej^K=2};mN!ZW+dntFL7Sq%iHW531cVp9&wZS4Hw1Uo%UF)^N^xB00^ zFqXKmxRqk5-Q%oO-$UJ9j!OL|RW|KEW$V-cv!+O|#ubqPCEx z-odiOD%-%q(`sx#)vN1STgfO%n0Hy+B)_zxYaRvOofIn;i9hzj>@JVR)2!M5jXXHLb+PAcK)ng zzVXUI1w`DH%?9D37ObfZO!HO&oa-zqqp-@WpcBr#04bwmC^S9;ROra{2v-&J2Deg% z$nZ^<98;R}IiG1xt*PM=~d4(M1)DM(H1v4yh zBK=LVuI>BKj6pQm_@6iT$Wsa4X%ih$9sX%OqQ%Npz3LVX=DoF~vr84c2exE*V&W>Z z@v1M%r22(oLZDd=)E3@E!+XcaY+r;m9XS2%zsuQCD}j0+ytC16xj_~P3Jw_Bj)SfT zg|Dx%?Z#Pdx&tZMu%InTdt6q|m{dil2tb7ku$3y*?k@|lb%lyLjUD0EfIO!4S*_0j z^e*%QZda#yG1s*g0FURIa9E-Z>@_RZjP+Qid4`Gm%Ij-fxHtX<0uNFDl!K7EY(Xm> z`+~&;Nh_yn1`iy%B=OO61l2lq%0+efsdXoUlBF+l$#PJI*yr*h?yZY;d4*_{tm5Se zy$AI)8b9ijCsJtZ*6MhKM!()#20yIRZ4V#aQ*M z=#ZY55+sN~Rbr?GC;Yz}5?~i!lyw@nj{rvhx_p#b<*f@)85Tn;Qxi^YXRQWY(__S+ z`uD}xVAoLTd}s3HkkUAmkW*E2h&cpv7`X@}t9w^KW_s$^7kG5voeoE>`UVdtmlC^H zsNi>3{?LimOmY?DnzN`Er=`Y94(2uXP$65PP~(M6IO>G56M3)DV=;Q2a1ePW(Yn}Z zaJdRui6T{^Av;IUQ0YPvT$SKfh=}7b&Fh16xRu*Eo@(ejqHL`Eh0>i71^!Rs=pa{$ zln~c+Bqy@c3~A^&bjRYDk`PzWna8_IxEW!>nPYbR>!|jr++-At*y;$tk{a1 z^v>p!my2STP(Q|gLQp#oSL=VSOz#TODKmI1Vi|$UNImgs2liUMRofbTbO!7sFf-I+ z;jorhJ1e`(?EbmSL{U#&Q9mTJG}2VqSR}%@5h{p*E)l=(Zou7W=C9l z)tsND!qiyrF0?y~e{X(^SWjW0VXrO&P~gviJl{C4+dWQhehxlPMvPW7R9{DJZfs`F zsWsFVu<)4Ze?CyhL}8k?VWi+a*SWFM^W@u~#t2M$r9kABJhgi^bT4$Vt_p6-@NMod zG+*vDi^oK2Y-((zEwj<~4$Tu=W%MKCs-G)PH0%H|ihx!2XW|EHizSh7M2^6WOD=jV z3G5MJ+nckt)Sk7K_fYV}G zKdj=o^%KZN)!(f$9PaJO?2y6QtO=_jA9av(M0O?G0MipxFq%S*10T{s-lq%bo#y{Z zkLL3zn%z_tp9fZ#qE{DKfDb^Cg?;QmNk0qNmXAH-IOpHw$a*&m1wGZrD4a0kwkm;k zWV9;mFh%@IWmzydy~8?BIjwkP@QTtdVLY>X51yMrI=u&&T=je7&WBb};2)YB4pt9h zPs-!agT=5Qsl-U@oHL!DBinYpmA)iUx93dqjMmZ&_0l#x=H5I@OQTLrqduK>zQvlr z0~vWXmzAJ}cfJ0#l4viyZUsnAC(yUigwk@W8i9IPzfJB|@VL+s^mKHzjF}KQHcxgY z@h5!9DPFg56dqw<+@zY9ffcuFs$B0#givc)k8$P=x?-ceAt&A2OG>Zd zaCoK;|Hgm2&y0;<@zyz0Pkity$9s5yU7V=&S$>nlePPWqHbvf^I@7=TZdlqGKJgVt$(% zrB324uw9xVQ*G-p|6yhtTYFG-nSo7^flVOodZBn}Gxt#kO!{ak)^gWeFQR-R63w;$ ziEacQ!KL`;mV;AclA?UQ1A|&km8Gbp?tzNUUbtsxQ^h<@dDTR?;g~|+ z74k$~1cGut;W73xKi9EX$Ym&P{E|Wn;@#3(+~sXDrK!CT5odgWFkSToqaqQf5^9*> z^E|LCQ7;)LwG08{*mIjS0VT`0EQpR0)^=fdXdKSn}@c=1i} zRUpkR$|R;v$6VuP{gY=dXpwG^g|NqF*es-Dh-6h__0nUY)0Dul zst+<*LMq(CioAn~)3uU?xIA~g2~}tf5l;Jlgd4ZvEmp;j$aI2?bpm>Rz?<(-s1B@l zFF6&ZZU~Bhy%Rqmb}u%eWj8=xyuGckdH}dUeBS_IufXm+e~`WsyFq>@pQTmn3vsUH zW3CCb)TLbO@?IVM`SK5VMEY&LvGQ5jGaT4MB-mm`Y<*)60kP~L+(vlAC_Nscsty-?H|7+v>bM6QP%kFLHoRCyT@sMZWlnwnrQ`^BHI11SKWXic-Y7~u=e2k z+sh2uZMTa+4MLulCB}JmZwujorT&$-=HM*wYU9N$wo!Cv!~MG7fncLYsV5ow3OU)+a)VyTa$k zL$#R(X1*Dwh_rb%b`5cxWVhN-7H75v_vqD~iCA{n?6;1h<1x(>b?2s8Ad3#Q=A2Q< z*cl;Qc>UVta4opskFW%2R=u^VE6g!m7=*dt#20SoeN6HG#B$hAA%WNZQ-_IRyD1$WSk|KsVUq?%#+oLfSJ`_!ub7 z0CFUwK8-lCW%80XrOB^zYka>!Yx?&*iM=uq8-o(iJs|L0&ggh%g%QuNWO)pYq8zK^ z7VmDe9wJvJ`K~>?&%nUj<{#!;qCnJLV;*`i<#EAea#oj4j@pbHI88GbG|vPFPfv=G zzN_e>xD}DNPArz`Db0zA7?n6rErj85QPHF}uv}NS!0W`r!76M|Yt&+atJR@~ZFdN1K=OChs0VTkyi? z)4RinVHE^&Bbe+JH@Da{Te_RU@BQV(O6m=fZIi=k+|Av_YMzlBs2CW?u&OjnI zArFT#M|ucg9b5@aMktL!7g4c-yvB)>v*HPB6Mda$nW5t#?p?a!ieZDbjEQE9h7;h8 zAOaW<&fU(!8J(y#rv4POVx&8i4%p8Zz^oOi)Sh1Y0P8HcCt=nk>l_Bx%bitYw#(eg zn=?nqP42|2bi2RH0K;{@hpnzx;LChMuFfF&qfvK?_KDXc%#O&-gZHv0ugBX6S9Fa) zq4%unn7ML3k8fJnsACX~%jw3!F`SnHqw?X+5f9g&%T5O&n$z6VLO z{i{rnr=5Qv~3|(fx;YOZX-!)&=%;0iE)MgYqJw zr5sbf@|5&>PND;_I!JtvQGXpP|FH6cvwA>SKQjTpLk+#E{k=Cc-_@DZ_vUesj38i^ zCLJ1ShkU}TW19(-B6dlw4yzf82Qj@k^hEwTcBujV+34qUm}uVp78?Gl8uKly&zv5{ zhZKHjuS66jzIe&hSxzc%$d`Kw@e^8u8z2r^23SZs>c1 z=R|wJyk6V&F37@$+|X;(F<9?6#jFo-ZXKAG9t3o5#_mqOw}*NRvQThR8&FieYyz65 z*ks{^T9~PG=q*~d9Ro-)C6eG+&cDS}J6U6IDw}Sv%=-iT=0*m_>7KtzYH&rTY-!>m zSRZ>zXaK$OU5d>j*6BkQ>21e}HsoH2&z2Y!Y&O&lkJX8$hI^NzcV|Pe;g-?=34?ss zQJem9Dmt6=$(laoBO>XOqy7q{-iJF+@eM}&hUnT0z!Ak;^h8(1h`it?KIf8HT#+Qi znHXZN!sE^date-Ih^mCrRZ)LdLm_!naD|vO5k!$QLUv5JM8=a2Ybz-fNv|3CNe;_G zJ*>OO#5{DE%kId0KRxjeB$nBVl?8h^BWD&l_j6R=N3WAu1Bx)gXu0hbUHG|qX>dYq zw7!O^&JO0ASLJip8}+$yT6&PxOzEQo&M8uVga zGw@@{Nu2uwx2aH<>SF!a1G3U#g=UU;`z1NWT#{K+CE)`lcBKl4^co7Yu=4zaB|&qA zCCB{oyg-h0`SN6z3Nc5&bbi!=s}2g`m9jEfPvS4xr8#PIjxBJWmtQni*#+KclA?)X z8c2;a8VIPJ<~0K#>?~U85mteCC@bQh8)gc90WC{is=sVpE4zX$U!!P&AWW@eseWMO z=g`7d_G|W981$73eNITv?s;T*>9*Fg`OzP=VKBp;x1W8fGiE_QA6wr1U|1Ym1mzP^ zTux-RjI7Xx~Ob^ zHnY<$kQ|kQO!OPCp8u@0=rAZ7A+P+e6cNGGhxrpA*x{&@Otfkj1rPYch8sd4^uT3= z{jWWp{Up)A)5n6z51aAQQF3?O0PmglPDc@JaAFV+YT+9)(pDPTksSv}zW@C77q^m?0Xbz-!9=bNoe#?SZvnCgs-HGy5hl58H3 z{Nc`u?}lFUcZ-|leHj}eR7S0@f~Oy(A`F3qO^21RJ?4aeK#rbNk@XnmQgY5C>!o2@ z)@$Bd!w>*l(P8p>eT6@VYSy&Hjz|REgMo+b^h0> z$XrgPLb)-kuv)I`T%EaadZgzf>gETC&4E;kWn1g-&!zpB3#z9lrzdl0;gMqi7zkFL z_(F{@?Vnp6*zsc<0xj0yCE;Ao6fl*fsn;Br4P2e@ufMSA&X_C#3ho!~4CtouzM7*YBsRcy-WWKD@>n$?II zb{VCM)l<_kXFh?--f-k(LBzVbfkeuY3P5Da$mHEMnouF9%0Zes5gV1Bh5|x*VrZ#q z4R+`{x#mBTadlIsSNjkz;xh^~B4^Yp3eJNDrBr zk6}%Eda{UgMI4p!;3g|96UDYAqGcWkK4zkBp^Z{}Ov=o=~@>)igC5`v>%~a zt^hkqs1Y6jVG=#qfvCzaRDl57N=gB)+JV?21p_TA^$fQ%c1CLMJoO5$n5x{`&V0j~ zK6sy^a<-G!5n0(3iDazBtave!)Ax=KR6C*|ePI28ie7S6leAGLLlzhyb;uG+ctjxUS6B2W2iCK_) z@N%h1nao!>OX*2meYfb2a!)bkl7wT%JM>nbw*;?BPeIAj&DqMik-Jcrf8rCYsM=4c zbmv`E>{-tSKj?>xt^)aDN1iKRyI=GOd)#z(4aBuVMlJh#LO5yB^z6tQ-E8P~U9l&~L#&ZA$NY?hh z7fzMQ)vSp7T<=RwO8@t;F>H%Poy{+4`J2{{C3mQ=#B}(Aa7Pqw-{!g64Bokb-2B>X z-g$vsak_Vt$661lSlC$mq-CYHo%U$^EE`8<5ixzRWOs+LO9b|Cj_w`Z&cX6%x5=R* zPpR^H?xg0HcXf)Us(Ea-n*4R3&_zx4ww^+uvZC%aO>1t0>1vOsQLxc9Hn6yCaS(Tm zHFu6=t^nbSG$!epdmdz_2_5kEm1Kq%VX!d;ArQY{PNgD z-u-P(C!_gmn#_)9dNY?4@M?&B?r0ol0DC5CyBXt1#ubBV(Q06owlJUEe$RI8{ZT`( zv48K&5D!=Ni(mJr)X(Rc%i>y>PCUFY2`%>RfoM?*4!Nt4@a%TPv2Ef|qDbTA^+0-t zb(Dut+#8v(M;xlsa(-8e+VFMdm%3NNtn|q#FSX%^!-jq!bRllOn2d)wSnvD5H&eDK8r!$2KQW|RGY~R!3)ew2L@x`? znRdcgMFk@FvJZahId-#P=03+jPmFA6oVcZ=9Xc&Q$1;f5`Rg+bY&UqI04aTaxNbRl zCs@kwY=x4wCfg}(qv$T9sA^{05(&vPE%|33Cq5t9?yyRGtZfACA;na2kK(1YV?j>u zu;ju6)51z@DnlA$SOrteb)qmCaHkK^g2!48fE9&;nX$t*9B!0 zPlH7a9V2XASZGI;Bqn#7T_MF=%1t_z-ua0BKYx zsT}7bJS5D(x`6Yj*(kq2-3*LmqFHdiW$KQ}b*S_B@@}@V%}}>bTU+F_4OnvQHvc~_ zcBRt_)A;Um^(UuBNt+U6cQB{Zti)N?*|PVLM&%vB5}=jfM`}ly(}+i!cEueSkv1S{ zd(y33mjx-;?V^`?t#|A9tnL`?rH?b{F9Ua#pFo~DUZWas--o9FtR>hxRj!n?9NQ-E zM2n{bE&<-YhsT7?!kqo0cQft0oIRW`ESu$-2Q|~4KVCEoJuJ!ZWd6PFlUE-ua41tQ zsHrw-eWQ3^NyQn>e`@?BzQxyF88?^nlKYRc!I1Ys)lG#1-Ef*xXVZohb^)-Dwa=9v z-TT;%F>Oasr@R(A_-1v0%)T@sTfD~XY<~B+XI-R+9=|d`ruc{9+KU1qpZZv$SKT_V z3N(cFh~k}^KlOys`J7Epu3kG_FAVc<@}NA zWrjGKzScu)U7~~&NaDvWdEUxUC0SV|SsgrZK-Z|uJPwxgo)pC;#j;@RR#|Xxuv@pm zPJK^H-pr$X2?j!@ks4oP-unaWO(6C-JdAD}oz!^KXW#qv$8qA1@2pNb&9oKICpI7e z4-kMh3-0?LfKVatjT=|fGCN71C&5oBm{(x1PkY;1JJ$-9Y5lh8eY>ookG5%fOYpz1 zMG(@kXfrvX%#*YBSELKOd6SYUL1+GO;`pEJs+MbNzJP!HvX=B|KC+p8Z*}WLUO}4v z@I_|A{SPLxF(U8q)PS)6FfJj}&vK>Ln14*-Ju!hiwvW7oy<@vBz482C|ap?f{Z>N+>*e^!oQKkiUEF_JRFP z#GU8(g7^GE1Re!)?D|f0&i^u&Sg=YKa#6);AGx0oNRGj2_NlvA$AN60VLyvVHuXODfAg{h6b5>W%L$ zmZ`iK(x+}T9A15yRop7wna9&>hBcte*VC(t)ftzlEaJqPyGGNM@q?UrY&TE5H=gi7 zs^~)X@P&B7y z!nlrwYI-B4W$4PW{3NeWtzz+@I)J0Ry&>Sm;mP{ye$dX8x>0x~kBkXW1= zB_KMJ@pkFk|59Q#rqj;^q|rU=R|m2{bGR-~U;<>cs}I#cb38+K7jPq!KJWf3j{~s^ zKKzLH=T8pne`mD#A29+%{;$v`<^P%hY%Tg1T!K8Vn0j7Z$YK>(-cMa)or2hR@mAjz zKD=2g9=Vxh&9MRevEaRr_dwEVIQXB*=XoUW_+4Aa1j+wH**ivA0&Q8kkzw1mZQHhO z+sv?SJ2GtBwr!gkj_A0zsz+Dd9@X!@zvtgMWAA^t$GlX*kJo zO6d9ex`G41+sBXi<&8OHA}w{tAAv!^s5lwIfF^?efI!QeXh;whs^EO!L{Yz`KA6DW zNDWdxR7l@E@FI!ds6Fq-;;+2i=(?aOGI4Wu)~P|6 zeq`BRwC06$R-mxVLY2MHv|nJVHQbl7rd_354?o(`2BVZZ;l$4IX?t4dnW- z=~PCH=D}sESs@LQ1#Q*;2Vd%EH6i(vapH zE2Rj}Mcl+ItK$X5#e0Qj_;8fz!%{oaM!L<3oFft)FyICTC0J1hO_TX{rIh3m_uAu} z*RWm(0w+?A)2MU9Qb)xG854a9I)@ghS6Y~NRq5Irkd9#^mcG!;M#&I>{}D*U6ifZO zwwCTHGC0tC9>I$;<5Eo?kun~ydt+IcJ0tnYAmAHYj{=E!#35}E&L(W+G`_$ohUerA+ zD2jGp9{-z+Lj46sc1VQAkB2ky7bK*!H_~u*0MDj;TuOg$G<^=miz;mdIR&|qwtsj; zzzI6sfTDbGRbEJYfX^Zb4{R>| ziX~J@W|+*XkQaxd1sEg=W-Qulb}1wASnv+3CF=SV5Zk6X)E^YPi?N982N>HjUEOC1 ztYcrd;>L;G{iJW(c_OOKALH}>NUhd*>&yhcfn^;+}Tde|Wh*E4BDnq`-n_R%{&Kpz<} zw*%q3=4x4H=z_9%;{?_7-jKXP=LCav({)x!+0!KvZWJib03mm{xqvqZ?I+&9VS!(< zm6gUo0Vzd7Gc55-OGL4tCFa(mIC@KaN0M4zL43hZ7=qca6SjH4#9WL#*cIOaAi%uf zi5fw%X(VI{9A!PJQ(6<6)84rHwZ?>;y99+%YT#`Qa|_|8fJXm?UWa{-d&4v@DP-^%ABTm#gLLXxTW*CX;LI z8}VFlm~FY|!>M2rkSVP^l+SV)@@P?pTUF87k_lUdZ*|%%w$~;EA&z)0s5-t~lo$xQ z4+W7rAhH+VMlAm_=j{Rc#TDQk>-#YanESX_(;)u`d^t9fddce%x%Ec)Hcq?m(R)Rrp&Dp}=D;uwNE6xaZSHmY4*G&JgarX|g@0g26{d<1 zSWgbHmxpa7l^3AiwE!A{p~hs-*DqT5lq*h%r7BGlbjsBs=P>QVV0kc^sNfkqtW66m zFO4Y*O;v$g0|8y6i73BaX$qr8~$U>C|98p$>hA z%qiT2rA-^+^&+s~ED3lnrEWTuJR9QBL~%-=+|){q793aGYXbnRns3Z8d_ zl_tw(lPzRL{w*jR>6z=T=*WUB@6~ z4bSv6nLCj_ai824=tz@EdoVR!mo&a?*&F|X;MvO(5&b4;~KqC{m}o?Xn(;C<&(!c5F?n6aPmYkEsZ4cC<0;$gQDTU^$o9bmE@W!0Me31s9+4Bh2X)(!b+FToyU&F}2 zWPti1LE8Y)1>I_R%fj+v^s|S+WI^sdxX<-U5p+f^K*D+3J0@->yAFH+NpoMJ&elt~o7>VyldpmyhQb6ckFNZNepsT_@G86&%@pPtX9!eNFR*O7#j zVEukBdd?&fLrm@PtvqeDmDn6$`=IUaS73IEG2l6Zxqmbydg`!x^eVM0pSvmk%E$a1 zSY%r{#mnCguP(%+4~rtJ7wbXiV4b-a*nEI(NA1BT}z# z$umU1ZxFqb`)^f(XZ*`P-A|<^D7bd~MXyb*fi)_8LK?F=rtTw5K|s@s`R7?_=Ix&Z z4fl(AkWGYdSZ`#aJ=}~Uxsauy=WlO>sXLl=?cX(MSy#M$I6u#1ys7_={T9A!J6lu! z5$3Wm;7Of=vR=_E^|C9oD>}}wb;nI(b{Dvx*g@E(2Uo@;_N=5^2OT22Np|y72Hz#^ zIr^5XEAhPd&vFD)zvskGwn?i=?%L(((9u;4scle0L$%eAVG4n&B$q!d&s&^<1=&v& z5Ox}&RQ=^G@&tRJ&qw9yN$MZ~Bs(xx;YWr$;K-@MVfjE^6rCZ0nLXgneup#A%)yBJ zFTZ|@qduv28Zz~dC*w;Y?1A|p$v|Pm5DFR|=@^g3##rlnONp1Gg#>!qykcF%zFEcG zk|1#jNf}K zyk0V@mBQGD+U6yYBQ?8l{{1c$o=TDOzH?0Xz}IdKp{HfaC9n#O?mlV_CTPFk)P-{u z=29-YLWkIVGV8Nn;~vcNSFO|v<-b|;{SUZ+owL{I7~ZiazrZ%%37kF=V0Xzd54SL1 z?3)k=k|i%oMt(Il5kFt{&4c z&^q5@GTVkDJd8@f+1<>vR3bZdz=QM<|JAEY>p32~xySf~$sO5Y4BeSKeinWQEAUD+ z|1Nz9Lz?OG)(2@oyLg#|NG_fLO5W5wV=F4Fbe9RCs(PW-B0xd^{?c6X*e6Xv0*hydFb8p)oK=`OAp*mQqj=Hc;N)dI|ZPJlAurH?SLMaKM z(z(-~SEt>YR5}XH2Q*iPVc~{R^LYC)im_#Fx~@GiNe*N#;s5%?Zd_)6ub7VAyNhsg z8(Oo^ZJB6kwX1YsE58;izka@W3|n<^!&|$oQgB@qwkQ+DsDSJ5fD|sL4J&-w0;<@= ztGM_Q_Hp~BeAd=^mRoXTQ*Gl@TKSaVR=LV4cdfabr)cV~q7{5ypxG( zg_>!zr-><*nrPo5ne+$PKf-erf1et`g988z|2GKazXGEEzjF~p9ZeiuOl*xjh-D3& zT^tRph3stX4IB-e?HvCjlQ>&hMhQs(-lySp6&?`+oLrd1Hv!%l;w8O^oB>s(f`S{q z4ekP&x@m1_Y8dbnEQN2N5RFdLvzGgzklKqi6FnhW5LQA?*R98QYa#t$htC&~d`|(< z0Xb1#0b2w)lJZ*8SYoI?A|V0=r2;xV#a_nN2CBt`^DosW29VcuTs4R5#6fe*R8?~r zj-R{cvQh3e!(c^;ji(iKythFnfu@r#R7hRBMdXyLlUOTEw-ExPf*W+fk+5tJ5dHa8 zI!(x(%ypBF?NZk9FSoXnR%nW?=3uP`_X-m7B1N}NooGCJBRTVs1?vRtsCDFoq(arKbA>opvi}w$j6>8fXO96b9vYX^8D&Q~HP$HxQM(0R1w+9} zPq}CXj^NSGvd)3^5mQHXdHp8=e8Z{ZB{?IlgRBc$UvLmWa>3B~-lE!MrF+Tc)a;i| zq<1m1k$c8>O4D^0wdpKl3LJfto^Zn!O z(?kYL$Nps1@q+$W<^8WYg{=QCf?msj% z-x;g%#EO4T84owMAn*?tCcU7uiCfFa<8km+U0U>a<46)YsPb&dd7@}lZq3}uHCNN zo^!meUp;QxK3)P(a=_pR^}HBx*u3naY@hU5yA{K1TBiopj<~3&u5{5~GQzKP-R(n} z_0ayprhmemT_c~%T3ja_XU>15r)JuDIIvwKSpKPORV#g$zP#@rwmsXtF|dq%hh+cm zbO(Twe29bQwKl8)i`CCXi#6;C2h!CJ3uL^vvFIj35)h|GIHum-M#spGjz#Rw>4mtJZePzOa!aH0Qrxtc zT!jOr7LwZJhDa_=ZYfIw#uRUCs#0V}er))v1KhxuAVJnlP1d?xX)*Ss#)uLv>}9CK z?I@u|iDMTAE#5jZ^AfJ@Jhe*vAry0xSFRyWuuLaLAi`q&tS@=_ft0G7e7BzY@7 zJ3w#^$x$|p5(vlX?{sQjc+_63E65QhO^Go^+&86R7}Pb3-XKFhnxg7J8mpfE64%o^ znSDzUCeD!*eban5{H!Csv0V((vgDA5VwYSMtfuY_I#DkF3WdjZe}OAyW!KBo`i{)L4b;MXbLBz<_=edqA_Q=OA7vT zcM?RGCDZU%x!&nOo*2hzzrjU{nH8V5x>I=0}l) zyAYELw!s1ng}oYTYhW!S@J#B?h(uJ?$Qob5DXaO;m|RVFATo&5oC^aC_?b0cf&Qpi z9p)s7M;2*qDsaYbn$(+Am`=YE$anE({Fq_$P13t`d>oYIvJz)82}X za-h|Sh1c_g%jzqJ%Y+FA0wz-v>uOD|+H33Eo9(W5{q|Z^k=YM-CmfOd&C+MatD%YM z>e~DBo5W3H^|t*UEPLzCv6H(dD?R}TGo58gfKCs_93}&sEH-~mvYl8S#hQ%+!-=9< zA8tTtK@G9f5K*r)Qc_UEWz_r#!!5KYWlki=2VcPrVAV{V+Wr{ejssVx(INpTaf8x4 z=_Gx!R@kNY)|BHBjE*3t&_6*siw8G1+d?ZpGdC)wptoAe^CSF|O|Tsw5dt-x6KhYO`l^k{^ds zu5V&#kFv6=XZ*C$sxywi8Bt`9+7bNJbq4)r z>8QeC_yj`!J6EGaWb@%+6-lXoM8Bql0r>c|nzT^y#?tY93(hk0;^R7lA#2C@O{T{S zuiPYfXY15W4-5KqCXaEQ;gWZVO0=pOyQj_RwYE8jTV=B|TM+z}9h30i&72zMYV%zDvX6iVFsdp4+7YrL5j z8ry<=#0|65FxeFEPDz#xD=)7?!rG{J6UOu8ShZy~l@}_?=RzmN!ie2L(DD(dD%}o! z!wE=U1+i))uZNccZM#mR)&Nmi9EWiIo_Bs#M-f#Gs+v@~w*ER5vFgO+%i9MMJk^A? z{Fu{yxNzF9u+x3-xuL{@$Qk^%+1hs?2cGqd!DnBhyjX+vpBUf5qKmxU!QhJAVG$CY zgO{iaur%I~8C*BNoh+ri60k@9K6F~!d+`~jxm%I;)W*FAyKxJ-_w(eQ7meckS%q zdj{QZt#Ccyc1U1$h~QuqAYd1mvGXxL8neUyn8W6jkZ4B_-$BDT`GF0e>0%duy2t1a zGQ5FZ_e38&a&_|G9Eemwk~PA|SV7$;G=uXkYTng11J{^S-IcrY$XZ%-=GzRlBm1D5FlVyp4$bNaxb0(pA)T+hBna)XVCuIgC%*EuOG?teh!;*^0BI=* zE}Q~Z8k9o|J#r4HP?7zm^$ZZGK+)Z014MsnxtJ;dN#bu#a*@$3Qvc)~2WQ$aQd%zCtNqtXgJ(g1mtH#QX=}3^LP>JG*YUBcHYyV_}$0r zf!2g=m%0y^7W}_7TKk+w5D=BHhoQjm+9MG)W_BnHGE0F zHZ@h6=I(l+@R}$y3LFM)+rkTeGiTV^DO(N9I%sbHp;G5TR>q&0@wKBGz|;twSGAdTIYZ@) z2IxZ(1QbGk)bcWLm_wno@!F_y2ObrCS>Mgx9W4vUzX?;LNczSccx0uReEZnGk#i?{ zr-C0?Izet{Oj&yiKO{K|&~F_{md4*bRmx&ir8$OC@@i%Kg9GW>Rf0SEm6_LruuJ)h zcha4~*+_T7TS#|<$~{PO(lGSJ6y+Nd_$67DD~C@f!l>E$8YG>MI)4k?d+rrJtft@l z;@+LCH8ybIQ0Nutg4pspUJ7piG8WQaOE0aA9V**qchjO@fuDMAlQ+0G>A<&iIp8`f zPSe*5;dI{djx~QtU{IE-hdnSThdqT*Z}X;3h8VlKmRzMk;BC)o>^IOP&vk2yVr9)K zeGD6m(uq=R7}9E`Q7Mb=QZVB!nE$dogRIO8J}ne!4c4TWu3DXL88Jd0rZcD5&UgI? zNjYd~1neREV~Ml7VGZe99k(?F|BMv84-y4HM-l7s>Z=(g5d7Z5&%qe*zVDAs*;yf< zg^c3XIhyn`T}X@^?O%P|oi@T$)Nt z%6l}1AiP;!wH-12bE4hx*%P{QPvDIth)B#&5k>JdSvlzPH{2dOI7;l2c$0fWy;AzT zjgrK-0=FN7j7AbHtn9WR)&3JJ$%Mj}mb-n#O?=-(|uES`fRNMGC z1Y%6#3$T)2>PU5JL}iwNRi;!@+BuzL4c15{P^$=yBGve-zCdu!QyXunU$<;=+b^T7 zB3W6zALM#n*KJVZ%2GB(4up!Wa^Db$Q=8Iy%85l`#2B|t))z*j11M=z`ss<)!L8%E z^k~MSsN|B(fC%&b*CeG;cElx+22of`G_4*OSVY}*o~JU0G#iu2SQ#6c|Ciq(j?BgD z5SB^pjUdMm`t3oQEKiyUM36a9b&;;NkPmvEuXl8Uc2sd~DC<5zaa$+$AUez*u}%Ms zIaA;l%nON)$!-q<-mJ`FL1tNmt;x$bq)$xqoQX5m)Snv0TR0^wn?F{ku$Vi6C@01E)HhV@^|8Cm5WFlhg?C2rkZ1P|FM8zswcE~Eo-&@yP*=NrBsi*=J z_~J`j8kdW{zXdh?n@=SzqK8Ot53eqZxs2UR)6;FvBY$4EKsrn1eKEtsAv8SvIvYbI z59Yh?-5vhv>}=Xh5hPUI>mOjalV8sRi`!S*_lX{W?hw}}`e2ejK^DC|VhzQU3(Ozr zA_q;11xt>?#RP$Qte^j>6erAStkqy7OjBs%rB8uL%d`c1fq_iuvIs3ReG||r3sC<@ z!jQ)-G!Q)cG?SUcK53btd}xf}lTZC6RG2;G;;WaZ_M2c=9pNR2j$=z_3)Ls0B%oY76GQ!s3^Ok%V{zGk7J^NEL_kxA zB%`SVAG(Ed2jJ+`NPc%>Pfjn(@H$Yh|3Dc zL+5m=DEot3^UA#UCz>cM4^W_+ljE^rQo5xAl};5kz8fm zEB@|}y9DG_d`exHlNFfqw^Z|<&(<>&wV2)z^KE$rkq|Pbe3`5#HKccd z50%CqE)8jsPP%IjH>-^`s8pi`x$g}BWY;%Tr$J+|+b8L?-cJzJ=_MS957nS~k&^kt zsg~&Sro8@SnD(h>*mhv7NBGG@XU&S~3qLk)D1;IQyG~CTL@0E2RuWCHvW15ECWbYj z&%=w*1zN$F;X-jmFPkPBf(w%!HBqo^JvD1RA#W>_irXxbLx+~)khGmcFl+9gDEwJ4 zQYDwnyB)feGf_63kVAlX4()+QaAh?AW=^Lu1Ve8H<)i9=R0d;jg>^q#1X`J5xEbydGw+Fx+3WN80Q&b9i+vCX**%N`cMn=`0P4^Pk&R&=UAHK^ zBKQ38UcvuTI=vRb`9@@$GXhjkV6H`aRL^o|XbFFKsP3y1_9wve3AO%6$8YKcKv z$b@Frx)WEl$tKt|XTZb)y~=yc5#dg`eU5c73CV?>ziaNAa)!Vk|IF5%WbzfP0RjMs z{{g!E&l7CUf8&Ap-?)c=JQOkp&W;xD#4P{WK31}^`e`5g{&gH<85;_+tXeNuDI{H4 zeZUb$XtW@Ri)ci=Jvgps)uL@Nd8R#|L8LCg`}p-m?(i49^d+AZtcB@)bCPLh^6Km5 z^@{7aSF4gJ0+wr=ssO}FMXP^FXeO>LgS!$gn@S3!^P41I$VZx(5rU{Cqe3_Y88;3e zxKTQI^?*;`0Z)$Q>mG#=1&-80=fv&pVkeqVq9tyz-w9u0xO6U)aFq!7F~SBeed~rL zG5WdB+Z$yjbg=J0CW#M$egEPhb(sY0~iMJqOVxjnsU{JVu;w9gCyNFR6By!9Q7VYZ3+O80py8 z;m(z!xVG=+`B#Ne5pZx)yyf8B)^Df!!C%XSZy35cDa$A~?x^4KPnu9fk4Z@|)+dro zo4Gx#Lg{gX*i=GJtCmeCTt&etI4-x}9MDptMO+f)e1?Ix(&4so3+Af=fW{W(sQE3B zxiMnVon(!4aaCZMWcmUpz_Pa>!EzqE7@AVZ;ATObudLyMbG;g?4=%7&Oc^c8)#A;l z-XRU$%U_T!VLQYqT1)Y_*@ao;zpVnzgqOKum$EuTpbk0O+z?X5wSHM~%y7~sx;TKS z)nz%=cM|jT{F5cKQFFKa_`?*T{c%YApR@I^JzDO6<7_EAS_oShnAzDHSpQ$0+H4go zYo!&O@9e?pr-OCb`Brw8kg8&42HI+!@$*|+e^%oBA&*89>!acB@a)y@u_hqot73|G zM$juwi_$Gk3v-zLMNsR$tMg9r&^sMwP68MXT%ez(vlAF6I6>805$4+x)$LC?F z*942zyG9G-x9Es$zFOH{6{N~V7idW4s+rXLUVn9R9l4r#C!O^p!vQzDlWX@|u| zu;{q}=<=Cy^k9R5=?Sl^Ifbz!jEzsWMn?0Kj)&n^6-LOwW(CSv4cEEGGe0GTHB@+! zFV9lP%}RQh3NB7NS_D~&kyVkL9*AQuz4ejA$=6a1hO`H5x|_rz>4}O)p}(LWuy-G` zBbF(wBc;uSN+{LI)Ss1Gg2)l4`0Xny$hXkyOs>P5IjKM70KU`;vM8UB7?jll1L+ZV$I6Ll z#?}Q&80i`GW(}ExW*`iw@`M&i&ikM0l%fw3*%`S`R}5XsMYvXa#1VqmU+%nBCxDB1 zHHwDwT0mP2!T}~FhCcy%M#Kh@FZ!_ z$`qPr8*YhEY@=5}e~feVv+J|7Yiv`CjW!;C(#G-fheb-Lnp?+UEaO*{?yis<`PHEv z$W4g$k%id3-FA?WLOP+!pVcb=le$9`X5Q(@Ko2gMAA*#*XOrg+JjpV!Y#)k_rzjVQ zn{ycv6G3;jQ7sPKuD};x5bvWt z+8+Fy1elThc0Q6qQ(tIZM14TxQrMoYtc$R3x;|kS| zZaLSXT14oJ1iB~|uF~*hx&2gHT!W&@WM%8_QKBfx8#gUd+jKQtsGgXVkl$+j7P^Bs z6xyNHV7!bghhe-iah$E2FydF?%w9481+F6Ey~(^J#|50Kq*5n=Og!URn9+@<+bj-m z2njLpRsy^;8Ry?7+Z)>vLBDL5$;h0U^%KVL{=oD*Yl zSbRqOql%$QJ`aS6=y-93;rRMPL$q3qUK`bNnl*G$VI4=~_&y_0q(!634Tkgq`9+2S z<;ZI2LD7+VHuth&fJ^p|IpL5JF~vUaC32G|ls=kh@fQ1e#w}bk$<*nBA3Z0+v;uv12e zHI^*;Yigmz4eA~s< zY%4?mq-}yp@=d%j=RKk3(Neq)xtC`AG-v(DY$drD3Q2s9jq&!(lH*n4xn8?zNVnh( z+}ujd{KP=kC(+|6h35C?+q1?jK`+IH{VS8MIN=H88-n)`xFFwY9)jE-2VfbV8` ze{_e&2kY{Mv5okQc{%Z96MH3T(nA>}Q7FNc9LEv6xj?i?N3>8LiDGpe(;;LVyYRF| z^pksTR!kT65n6s|mQ$0`5D?IeAg-Hh=`l`|rE)*zYB8wKcNhv-*2wGCc zigBb~vk6GQCBC-sSS@zM(9DoTbLj^=%TI{f1Gep+BKQH>hxJs$o1J}@-}o}mjH@3I z*DX`p3rFfWoqS)-9mq$B&>d;aJ`MH&NOj7N!p;VJpxfvtt#A0w!(XuK6gT$co4p

H~ z(`dDKYT&X+EZ%N{gTpAHC5T1i+BDoYrf=2^1LNzmV2|tEx5?#UVw3?^8Sh(bI^F;a z_->}QouhtN|G?+GtDwZrgv??NVxB%gyS!VI+e2cvWxxAXRB|$v+osAFx{ui^+&5OX49G`to=SJNwh!u3^nO zMMgJ)r0B&z15R?2L`NFF9NroY$h<(Ex4iSm_aepmzJCph^kH6CS0Hj>CQ$jibjWoP zq2jl`k<|#{TWHmS>-u^+Y?V#+T+c@#&YzgSZade2Cg<=UMmIb+IZnPOn_j%vTWowh z+#vW7WS{1PqI{+Xc>#-gnA9xLuMAO9ctoS;wV$^J%Hcm0+Y>PoP-Ls-*eOoairCE0R*;tSRv8-KiC8S#3)($JBhxUAnT4i~^jkTN zVxpJU-9CfV(9?D^@H>-DdRrUWq(+O=S|AhC(-eR-$jTb8$*#>a?gKca8hrgsJ#-J1KU4=e91t}BV9 zfd)Pp*czit7;Bm{)TaxxcV8`qq!?Wt)e(F^lt|L70=R8D8!wyc%b2qt?HjaH3GPFr z5_0xTG(fn#vy&;IDGQ32y9U_za&sD)jEFRjRYZCKPa9bOER_citN3(EdrVE9=8erl z7eR$nBT>rrc}$tP;BsCg^V?gLu}^a*7ecAD_wCiLv>$8R!KP$-5Hx=+4Mf zj=#}S74OU{XBnJKM#s@wIjP9njn|vXAXmF9?M1O-f2S?i_d_}by9K~SZp?)^xYwS} zV%NYJ{}STFh1~^fW&3?)x#}+lxEe0z@_rsNMwdnC(C#2vg6i?Wdu^S)|Cm9r%@~W zh1a709uI0XUon-uTCDX|&yIpc2HjQ?*S}f}_H?fFt@xbH=&5qt)yF=?fGbP%t zJ+FD?n8`YoqBYHjIvrtV$+e4AJ7J&W*QDH3x@J7a^r{TOfGmIsVRmr5A!SO!=C5j z7z}h^xaygh^t?Jg)(=vPI@RD&0<^*e7>hVkVLH&2#f;v}+(qUA#KRtu0lmOu;{}bzNXid3Rz>+7bbkiH5nXUoHC(A|f@7 z(gSsOrZuY_cl-laO57uxSyNM*XlA34SE_iy!s3z9v{u-S=#p6R?&7-$k;7nHAxB

(7ge%xRH?;Jf!4KrC;8M4p47aTpg z%v~k3V=R%8GWs_e%3T+*j*NavY4uka>W36vYWBnG(O|A`T%1&YoowG z55cmE6>zltcqwL7F0;FA(eT=6)ZVsum4P&70cwFrhaUx=N;a3S-6EF2k$biR-jy}J zw@;;23D>qcGb&E51@rtJW+B7+Y+iZAoI_{M0al{GvU+ZLi(D#>z$YdsdqKl0rY!14 zPnuyIS9*w6`fs;%|xy)mbMH)(C4xRbSJ&$(8Drbd!DVoh&~CvQ`dV zUW+@0-r(-3IB3O=fINhF6O8WbI?o&@w5lXhL<+MqSl1KSWWu+`JKZ_0L=z zPS5SL^d{8XS=@71CInHl{dejsRn9_8K)<=%xEAN@L!47s4(sbfCTXm80dm|lMOk7D z*{buj!R2<-78nEW3GHGD$H_=KMPI|*^$N8Ey`?*Al-x=>#k7|+&rP6Q2?WYBeCn=;ic;O4gp`#bsI*i;dzm{Ve4cZO5sZDHTY*@8c<2s{RWFrrIlq;!pcCx2kV3k`^-qs0(VfBy4 zl9rIQzD^%6_!SyY^})FpFQn+LEOfg7y{l}Tv|t7Q=9cU@>`VTc3}*|0V@ujb=d~v9 zV(_NVW(z5Ji!Ta+q5z|rlG5$+)Aq*k3B5t#TXqs1eb)PjNQA|(CF+0x0NDBo$^M`F zank>Wfc}sEu8OmTwG*+Rg_-C-Fuy-C`aeDvva|hBj6Z{+|IpM`%35+r0_Z#qUDh32 zko!2du$qv?jtKH`z)--5okiwIyB6l5^`;$GB^w2N!)QM9Xno}9GEsEhFNIM%vS{;h z_+|NHuG8M{Q?Ju*rmnu#~%{VcqUwM9pp4?9IKVk=8+Qmw4JdDoLFmAL5^st+v>B9=sX;hj3aG} z_c@oWgS|3|G%_t6({1RvpQ$_6otW>4g^JD{&KL%jBG3OkO1VXr*NT94ovt@U2sNZh zPIhQ5R@+NL5-U^xQ49;{e`i;0DMy`)LA;tXWCPS#BMndN4v15Bi2$?Std3V%LoFM< ztH1rbLBrB+mL~p$W3?NV^zn2{-IR{DX|UM3^jq=hunaQj|P%WGi_-MjB%a}d~5 zCaa$Zi8O)qI&eAaE0&LU0$HepB%HK*uRR6~`hm=;6vL5BpVJ)69Z z<*gJd`arVfmkz9F#C4d;w~ZeZOaj%H2{66+S2ujbtP`XSvIQBlsDr2x^(TZi+&ZiQ z%%8KJJcM%o&{NNP7Fe1;X3Zdpx0~*-1tjIo{vpE75N;m zkfzeFu`T`zJGEmn!;Y{U>;m@%;W|4Na34ylXkQlC-K_JdZs`JUr~|rxT&kUX1M7_+ zBXaP6Ga~uG4s67UFjZ)WAOcqadFV~5C)_Kl@JgFn22%u z;`k8$0H`68@S+Ln&ZYtSRyui_n=9?k3Vr43=j)*GP_1eg^CDNKI^~OBmhaz7mZ?1x z-`Vde=|R63PiyW|-mg2Jvu?b9hOF0E-d{VhxP%25`y;gLM3J{O#;DrYnHtG1gb0ecADYe)uOhtq& zyF_MWq%Jo?W~{+SyQF}60^(!}7URraUz-!_uH%SXXQ-^B!~_A>%^%C>Sy|vCK-uXa zNAHbs3&fP$6K9p87NN@6AQ@Lgg9-(Nugu#|A%}++A_x@VKDY^YcyLmI1Ka`lxV<_gtzF1=s$*S669b!Ew4=LOHlm4{ zb-D!t3(Koww}Kk7R4P~~=!6&sXb_+CgZd;Dcj<)N%dN0Z&f4fi(3eC%3qp7mad_%x z%{0x?X4%A}+D>1G2PfFAdlj4n8&XUAl%zcgGn|HnI00z^7VG$nn_2h}Bb-AI-AY5q zAu=oaEoOqdB`=c+*6|aL&j`ce+JK7z*4a!Ej3UB`Ao>R}chr}t%G(lSYT!hOq>3CE z1pdlNinlbZ>unCP&pNZdfVBqkV}=F{o~<*MG38``WCMvlmwU0{AwBasE2)+&bY=-z z;1mjP=O^s7&TTh^p$3^D^@5jqs>H#x7I@W8mTU7P@>Y5yx^{BtAxGVUj|lQQcmra~ z(DY~4GQ>7Y%)GSzQkI7uHFpMOfK9E>htQm7w zbmLw`ITsHK;DktKxjZ$^)T_$`7eEW%H#va`ja35&Z>T$kiV07HVj$ zW8%b&&yY8i)&=t-%ycLA8SIhLc?=MkyyC7m-ZA9vX1_O+!BLjO;i1UWFqB_Gw&Gtl z=_9sjZjZclq1php+M{n`#ZGE;zaH$8$I?!p5N4BTw=~gG-ya{N4o(FoPCp18X!nTQR3PVKU$^8^RoY*SkfT1<(0+)D7d zbjsGc3_3gZnKcxVb3@eZB*qnFGf2B9LkANg=S=Hj^QjK-)I0P6QP!}r^IViZ{^_Lj zq0VrHob?1i_=#T$0x-=Bb==r3EWtT%Chjr)fV0V5!>sUQya#guyH+all}`dJua0)&I!vG~##m`4X<2V2WGT7&R3hN# zedr;jr1>6;fj0abZdZ0OW!-1I8F$z|Hjw?yM`={V@nQnh0Iy=v(z2b^3!NQfTeMN_K z((YqauAw7w@`Xb!+x^Zg@4%LPEp3A8#X%KY2bQiq)Ri!+J*W|48(RmQuHXpLhXB)g z=#YI+HXlj6>~#R9tw*)DQ5su#w)?#jB`g!v$U7I@bD+WQM3}rDW19cP*gMB~5`F95 zZDXcw+qQe!w#{$bc2C>3ZQGuY!x zbG4FafoXqV2F;YQ-4z7>`UknCeaLzbTO0>cgncSiY2{NU%XHfz!ZzYEbU5&*GlCVi zK7?yyU(yOnxhSz{*iEV?!`>y$Z=m1;_%W^97`i${*|wjjHb--f@RWrw zI4*WQEzRvmrX90skB_$4>#(U)^O~l;LPu;J3Uq2A!|R9F&fF?Ne7X6J|J5HN_bVV8 zIiK~mR*Q$IyCw|3RRsTYllCd>)5cyv`v@&2JkSPazAfEtg4Txuq3zUmW4D$gKWt=k z5Bj!Hi-$DZCBkg5A^jyzi-$a$KQ1gLqL)B-ZwmgdzD$fB2RsQr07|AStT<{?o*T0r zOa(qT$l}Z6K31`YHszAemfwBg#HUlVVLLis z6x-J7YuDWgVvhuSZ0>ZvqKynU7T(6Twi&o4wp4RTK22;vv>q8mA6QMZkHKjfQP;+( zZ&>4HZpHGK8w4~55kj>M=HFQ6J&HGa#Qfjk;w9(tbj>rZ^L4aptyT*SrTzY4Rl%f@ zly4HF{$EnEK+10|?t%Kc9_NRrm{9Yrd{DA~k=LcKj!E)i4~|08tlZy}1|$<4Ae-~B zWdFp`4_iENjjFOFJxgWo{yilsnCP_L$sWHk((02vkcrBxg5JW6FZlxKG4;TRA&IW( z@4!b7>^xb&xwMt0rlYq;rFb1l@YgO3B|v3djmD z_RqwRsP$!g{t;rk>zNBA)a_DQc3ZKK6gH)^oh4T;x8UuIRyu-tcoc4sij0Vk7=fDB zLu6&2y8hlGXQE?T;}s_cPl?u!suy*xRIp*Xk+cmw8Vg6Oh?Q~oQ)}>-^#((Wy7>_+ z<{P~mD-LVod%N*ZE;vO3O2LS_>kKt;#fp3b4&g+u6%*SxyEY>ti@NDHFprv2X_rm0 zqM5(?=)BEYsS6pUi0t*|_FUXzoR}s+D;e$kl9bOny{mg+ODvD^zi4kdq)-_nt z&JGjz9}J=>U#VoFDTh(chLVJ|3Mp!_zB0wM;QhCV$N?NJuOIJuiujyI`?)IbFkRjU zm5pU4E-_tpKU7c?gqVSjh~k5F9+#Mbkr2MIyZcw5Hsv!8fmN5a-Cxfi$7v?X~9(gkJU4lQ%an!qxe0Lm+^Qk}B~3`Lnit#yJ9&~(+A*Vg)m z!sKY{2humDMtcQN9Rg>ZaQp56YE+{fLG-<{$+?V67X^>5%^Z>IDZ!I2gm_51CSW8N zfo6gS1i|a5Saz_kz?t`rZ?P`=Vkx+%FO+?5d%g^nYSW}~E54eMVaatFosu$>bg_HC zD5LwlVzK*MU`;v3$V$PhO&;`39^0r9juMJCGe=oE@II3MMCNvqc4gc7`X{9v@lURO2Qi#Qtl~3vFDAl^A zEuc^>A1HGyGNp_RX~s-D)(_K37^R3MuxxE8>~8D^jM<)~9&je8<0Px|q=t*Ia)?o! zTspD3xxvF1Smqr%J7MX_i8z5ibj6v@%bYwr-#n6OO0^KAZvk0Vi}Ab_51JEi(Ui=e zGMQfpU2{IL?(CBA?`1@>qP$zVbMf$wFe4un-+r3sm6G_Q2OLRX|DgnO9jWvRM3+eqcigzo` zg#c3VHbU@&gG4t(i4o@hxv=42Tj9GSpl^t-diCUp@~Z211ZK8kMpf*1(SW#nCvLmN z4mVyG1W0Bm7GpOb%+RIl?%7XFW!XbU(Q_WygIV`6!2?SUXnQNS&Kap)5vX@h(9u5E zkJxB^3*V`7-QiNjY#S!v>2J&I-y2wd8Np7m$Rb6d0bbZ!9Z5y63hI)kyyW*-1Y73* zbYqd9Kt|OTK5Y=RCO0p|+lPa82j2>@Ju_i#H+8Svncv)Ry}j^n#R^ z{j+47a{#v5n*__VTwGw>%*$A%h#TF|YgK+^dLrpq(_@X=NdL~Q$9(tFrX2KTrgJJSM9)BBZF zAYv&VJJ)C{jY)2++C@li6dd1ExjVN2xS(sGz=9tcU83Bzf%PkBtS@3cZjt1hd_D`d zBbp-KFO#0p5|DP}3$@){pRjnME)g+fsHKEWr<4i*Zedq!hZHHjUZrip^o8h+qX)k9 zk6xgVH%CbumO%{J8D0QnT7MwQuIo+a!Kg~h3p^G%sCoPqJ$V#+lltluhq7U8_^C8epRRG{W`}n6SsN2$S6NFvj-`{HRM1ul5 zBD)^ciBvAc-XQhc5V)b1+{NMg*N>t1(d&DBDn2l0Y$*gqd+xO-g;C)2;+gXJLcD=j zcm*+py3pY8A-hvk$`(2N(Rh0hUg;QdO!8g>{5a?lD9RYBL;JlC(7)G^GbJ%km=TMo zv7zV_m&uec*5|MR0^6oq*N1*4Vkhkh!3XP$X(2pobXeZ8lIyeO?7hF<&EE{P(&qOc zI9z6x)kn)*CmOiM&Su9nUVzP(NOVmNLjv#|ExEv^UMAl*YYng4VA^&V@N};s z=F|;r?>h-75+K%HDoDU03$U4&f!*W+=PvKufwxOUASU(Qe}-I) ze8S($b;mx$Ddbd-8-G%GHQ*;ODy&>;+pyT5>9v!&@x<|4@!_W5N4*qC{4oMA%7*z| z3K??Gp6`H@IVoZX0?QS~?F`xd? zNXMy(k#uCK6T3(b^1Fhmv|tHXl;!Y4Q|m_V?rbhAwkXm?xE92YfY?U=af zOiN~CE<(s;MU!ynw8Wuj{OQ$@kv86k;6RJu#K$U)Aioa-ePbHmRx1fllB~(u{ zJ*mWe$pWxsVLq%TCx{QuMaOuzd*INAaOdRVseJlqn^)Dt%fp6xLB|os>jOKw?RQ|? zk7wJ5XFKqpe4V|3Cr0CW!Q;=HEn$mD*_Yqc?p~pp0^fudCS-M2Bhf? z<@o{q^aAztg7IJZpzw(!ei)B?eq~?7xVqh@vti&X$lOV^12HuxEI-dwK!)fmPBGy? z{r(W+NlxUF(_;(6y~bbD87AW0++QuYdCmoU`=R85LPEo3P!l=l8FB{{_yWeNgn~s| z0noWekdv>#Idz{z1Dhl9k4(m^oYuX9wp*3B##eBUnVVKmkB5)X8E~WE5FI!jXLRFE z$;$^(p?EX9TlY93Rx%TIg9+`$(`$xug9-0743q=1!wm7_CKo;($MRCRKRy0{EF6Iy zHP)9BSrZfkNM;_l$RjAye6h>Lr`{*L1rz6qb4Zk6(d5h`+tDsW(U?OJcD9y0Zzz1! zuy@Y(CciarKIgnFBkZ#r+%wJzXg14E1me65`o6Y|zzU)VQ{Nw$QKFzA6rLLYQ6 zPpOtBsB3~IqiQ-2mpPuqB=u%bIXB%@m}6;gPxpz##Jn^==Wv_!pnhI=k5T#9>dsS1 zO?b;At_@y!40>*%&x^0VoQZNyjJCur=l57~TF16xZ7?an{$^Cg{Qjbz13ro_eCMIx z1*XmpbY9fk4y?|e^|KvND?4(&e1abQLAWz?=PCc^q9ll8kDq|M36zK|Xngmt7JxLQ zK0uVpno=clBz?;$ZH*XQ;b4&-FamVr<9s*DUXtboPo@_!Iz6g?r-#q{YJ1{bfU^}` z<{o)#)kwu_L`AcMiiJ9r@1i%##{~=SV8P2CUZeuTFbk1d8W>C|$R!h22*tAXD-`xC z3nEEW>r}qF?gQpaCzEiP=e5tz97C!%e?u_+60g3@6LN6NP11x%q>qv9a3Fn=*%29J^)f47Ds z9WD!s8~TE7Uh>z+-s$S30aVcHR!sqIaUZGFETvufw)CJ9)PqquXxTQ%^US)of_}pB z<${ki!s%I>CNIKAsQ{Xu#EiTnTKRj`mu+kLTP+sZS2h_Hn-arAgi?3%te|^E6ZWQj z?p_5(cvNPDui?>powePV|8ub5Ff1F<9)PjxPWomT z1w7(Li6MU51HIS32W$As6`y8>O!#S45#$^0D69wDq}(I-%(shink`BjcEux2&}hke z1{DjK4czg@=TlJPjc;60BY99tY3hgapyu4OCU8XgKvC0d zB|!XSOr_vlMgQ)zxGZjNkxRMV*b@&qIr2oEnu+9Xrl?0@1gE4_A8RY_xc?dtdf_6bgwx zC4MgdtglpeRna%&OLP1e4WTgxACtb@Z=>72#t#k#7E*(oGzJv$Lm3)`8K%Sum$tZJ ziynxkl#+7V6j~L+j`Dn@rdfOe%{hC8a}(+?Sy~SIl;luw5b- znfo4nOY43J?PnngqLK+#-kbBLqG1LCdS4B8l;kfRo7Thy-J6M^UksE=1jLLAM*+g1 zWS*vJ6}KfZ=@cG^j2!0?HVNehMks2(Wh1AaFOf zGLF1iFQF+&xQ1Qms$D2&XPBgk1?NtxR8*_2$h(E}mc)MVt11phyaCP&%Ra{r>%Kr< zB&bU@(B-h|QSM%EntTU@1-;)|lY9q)1^pkK(!jMQ{k}aP`yDT81e{R@1g~@e&drJE zp1!k5-Up+9Bxt%eE+@hc6)D0^7AmA}l9Ml&H;y`lNlM@qEsKgZ_@){GLZjepQmrlZ z#d-io?b~1b+?86!Z)t&TrdOW*-jcLoe-e2<yE{a#TZWFZ`mWg_poJ`h!(^rDYrRLC!jA%DqzH6#RlrjjFIJ)=eQF`tZq^mPNE z>3y$6o6KbYeUfPIsgYq02ulF6riN0>bdAxrSQV&PNADeKwbTOYGJb&mxd8McSjb5UEdeUBzu4*Z6|#w3rj4=W<+ z9_WXq+y24Nv0`25v(AW7O4kLPXRc-1pLkhiTZr2pKz&DoYkuc4<`JdaEj|M(QYF}J zE~K>#mWO!b#k@jLTLiZ=Sg$|!k*&=doUcs8uCKsNSlZ)l?6_SEifDD*r zwcF8-?y(74YH0?q4+8d#o=n>@++qIX)yAy}mS<#}auS%DQPQK;01~vfe2-A&M+O@2 zzrm$3^Wu-tRPs565@$-v`Fv3#kCb4W>8lIIx;9xg9Ff_e(bpjzF@P;xNptvXX)QAC%HwMAGOw3=fpxq`K0|n z8+U(mK{{O(Akb6_ZuugQezKd7ZL^8ZNGpQXScYSO=$YW%U!OntnqnLq?(+EM*M%OF#gYm@&60CO3=ZXM+BBzGS+!I}6~0!!65eb+ z6cnmlt7-YHVqN77s8X>!pOdM2+WvOE?r=PwjAuZe`SQ6rqJ7@Q0ok_GscfrSG<~g$Ivu2B)GH& z(X>`E+3Fh93}|{9XRGQ+pW=%qybJqhp$_ zVHwuSVDB>)u-lnNMpeUZTJF?{+v~$2s2OZN6l|BOM@)CxSwFo}LBkWmTj@3!8 z?#nuCntkn6l_5D7hZ*-)G`+LWtEIun zAl|%w9HuR)FzZ+&MXN4OuV6je1F?C&d~79;BlRxQxjNpML_IplPYe>b71xnh6b?=w z8=c)E);!wVXSz$rkuOs9lrQh!)+;`?=xkkUBNaRnY{gp0SMYE4u9A;TGbLB2G8oc5 z0%T{LmY~xU3kHhJQ#7y6pTJX?(&K#dWntNRW0QCLXPcD95TF@3E=*$OJI$R4I9aZt>a1&R+a&Du8ZNzqh=x zgi9^GaFFcvTWjzhp8a+8)LnkR-q|H+jt|OcK36RJ zps{M=b%VzFvWEP|gt@;F_R7i9%589v;dcMfoV}$3LN9M^m`ElcD%Dg17kpC9V2@Mp zoxiyZ6$R+xh3axL=&>)pN(5$j%Shk=*$>_`u!+sHoB|dK=lj41dMmt=COI4&MTAYL zr_ZE8YNaRZyM32T=%ME^ABBQI6`EV`+R_y@A;#5qsy6~Fh?$T`_HXlIM#LxNs0R@O5#Rk{fPj7Tr0F)zCtkIwX!rD!mzP`!I}~bC$qi_uZn%{fBFhe zuKRm}&!Aw2r}UmERAJVReK5-zoy1kloM&<#;a5gNB|?0o%=xJpbX8MRUTc<>1?zZkpD@<9lGY?l)b5$O**)5$-XSHz;47 zvg&(Y#RewpCWXa#2-`9?l92*#G&M-KzE}$Ti6wJ{^7-i#)=>ewNv3NCyOlOqv{0~m z9DO86Uz%R*i&3aD3tELlMrY4#gn`v1Zyz%#@8#!)#6VoS_JJt95hF~A3s@h8v<+v| zEUJmlYpC$pjhSt339^|Wnff1>JBUOv{%mb1N^q~^`$rG*FV|gP*M4ehXWIa3>H=>h zfKA~mivz**NW2^|uie#1isU}Q-n^HJD?@F>h_%e#ne^=~BpZ*9C0y64`-kD<+$K3n z$szi}PI*bo@_N*u)vYtOOzb6G2Ik~s4W>LuIbl zP<0x8+H&~n;bpq&wEDs3SziZTC3J*~mm{XQbB;*b)Hh?V_l_L?^B#ijiCoF> zMF@v{vhHT0KEJ#%uXGN5ag#pWwmM~Fptqalvp8nc)UdvC>Ee;GRX3mUfNlhLRRB8R zk73x~$Sm4(#J)Yi9`XVK$}1_yFot_2=$EB&;=yA4uCPo}NV@fy)EWhF@rcjv4Zdt? z;C?x>wEB7J&8e${#H47iT{APt6+Uj>Nl)M4>|Zvov|Z+Au612r*Y4b(soC}O*QfBJ zu*eRJonyn-UG7Nb+&7#I(*9P&wtoAgAdh-c#ND^0;PAcZ_?rT|G{6I zJ~O1p3B;M3&9`Cm=YK=F(@N;8s|+l>zS&h(5pQ4)X8}x}*V3}Q$EU6eU@xsuxQ)%2 zSERY;HDI=l)mJ}Thw*^ywgk+KUQBt2)sV`1r|MV1xW|iJ<AijMl_Wi;@YOvPo znck*5pW5Bh3Hm7j4rUNUl8|sAI#=30zkYsf`eb77O^DWdJcU*1#$ zPurx!r;x$Z89Iw}ehN_?nV9}IR^AY0X6NMt-aw83yss2Tf`@rigKH80T5qiS`PPoA z5>*AiNJz=r#8zdauBWxyo?rer5nP;pln$>lP=gk%AWq}!HIvt%2?C3F%QJ8z9j=ad zhiHpL?-7#iDyM$Oq?z)f#tn_V;9bs>@elKgRZNCgysFgN+KQv1DZd@_LTz~gdt{(z zhWE!(u$?7}Y#v~o7j-}wMK;T3K`eUthvRt2ccGo*DQsUBYaG_Vc|(MC<+>Q};(1RR z)}wZ3`OFCrIEY}NR&Zb26gDqKnUt&mq{|9qHdf&WjH2HQc z`L-W~?1@hXU1WtxceTIfa+q@3cx zH@t{T`ab*)NPMEmViPZj!50z(umlwk{24en``yZTVNfXS2=Fp60yQncv_Xx2bvwf4Qzb^K`A_w%-ILJj4 z(uE_?xQ-s`-k3KHy%gkH7!K_=xMB-*wK%j!yU^(rGR12eMrsd8Xi42OoXK2+6W3?3 zHijLeYJ1W{r(atyhIU`2;)W`vO$C^~%!Pe#d)Ofrc&lWcwuvDp(wj5L+auDO0;Y?~ zZlmj8vcGAAvwuWkN}K=OxLfg?{{A>>cZiXX4oZJgU-AF$MuY#1Ir&hz_=I*Gv-JDo znk-^xXy`&Xu`S1#5Hr3?vP#dg1KnH91e#>96~Jl0fZis_-K5F8m7c!NKniwAC4)ZG ze=~3xlneM4NcsLd`yD{DEllLT%>pf_a3tdo-3N7FOmY9xfRV{6xe9bo1vFP5yp;sP( zLBW$;fWKaDm@ALmryJ@On^h12I!i?Klw}89cdBm=fsroZ!WL1#ddd=VI8Sv{h<22Z zJ0SyFIg<$LLKSlPm)ZuUdIef-18T-mK72FCDmRaXy11jx?7;6P3-oNt`@cfg*^K-u z^5_-2KWaO2{C>ead%V}t9fZe~WYFpoifdE2_B7eJow$t$ z*My;Nai<F9efIi5*7{~0HE;tkxdoao=rl*J z*dz)R3~ZH)GzxA4L@q94;zbMYgbJwsVFmFET?)^IK8zSN;{2&Isf?z!8@!g@1-8ox z=oOAw;qB+?m=#E0#W2s-$k=?RvUJ!{=GLp;~7klr~P7U1IHwEdj%);#oJ9dYu$ z&hbn!<`&rheDJWocTo1sFxgrYt;X8G0iwW;^>@*d)FYV=b~G($*e00|k+g||JZ9z; zjRxA3{Rdm3`X!1nhTOs?{`w3}Jojshd9sO&Tj=!ScYR#}OS(69*uH{8gHfslzDOy5 zaq-G2MfY>~ojZ)G!w9%7n`TH~H*qT?xxd}#Xp?p0H3}7bh>tO;Ch_K7tKB&A9BohR zn9Z-Gl!bT5>LwK=oW zPmWXrw&3qY@pYh__BGnVEEK8m^;{EqNV^D*4DA24V9`t?zxcItZTLM(=)8kdhM+BR zzQf6}+cML4Kht-e8;JfBdH=~N-{f3wcMB)INwo-HFzB7&xSjC0ouL28AD74rea|P9 z&@ZiE+Keo+A^n(?kNj}Jv+8f1A*9pq2m1K(gg(a&h^U=)EHZr+@;6kqINeaiQGGBh zSh_(0BU+cLReQW7uY6CwxjQytZm}sI(x1Q}H zN{&_F;RsbB_oxA0VFaCS<7zI)QXTsm?*no1yON1;Qdm)Sg$Vj-R}SFl}(MriDiT~<`5VriH&=Pj=xPH`DceHHS8422x=@1 ziP^wM#^h68=`9(rK#Dg&@<-eNFY~KE0I*WO;5SxGnn?RxR%wCs))629buAm~0YSeVAxgmg_YxN!6r0 zk0eD(+n_w_k!e|1sfs$xbS*l0bwz9bVKc|0*MbkQp zt4J}(hZ>>SY|So3K|cd$G26t0;eJ__VACjj!Wpr4LWTAK>rG)ohY`_I4C5f_UWIk#?uxZd=Dun%XPQS_8 z9K8CiO!hgC`7En0z^e3VGOck#W?-zjNT{s{K3=Onwf4*te;IoYAM0Z=_pHbK94vY! zay|}zS*1JoJ zDD_0qjmGe$QoA%^%-Sa*jdks3&seL`5 zg*mX_T-t&ai2+lpFlUM|O#EEYsxzySf=45R2H>{~S_MMq_PdH@gr*5)EzH31Ng|dM zeH-s?iJcf9Y7ifBZOBFtbyBvTOm1|ffgAQFNhC{>%p!q6ZRgF(d6;VXd23ie_cP8YpCa8Dp;U#Li4 z#JLaBxDr^K)av0Y`%51TBO|2ZqpC?yR0xyE|GsO% z4N^A%PL-}+SvQ$aTuM@@F@B+Pfv1qSYB1eoa_%{Snw*rHb({)>1QpmYih??NMltJ2 zJujx@x$v%?iky^9Ix=l9CU(36DuF+5%L^WS>AaMETfqL&?4XMs0PC}EchS&E+BqAF zhX%Ar9UF_96s%xel<%`4?Tb>MEVl<`g5%*SkT)%{DBwsEBa;@W_7oR8vAyRr1P*i}*m;EIJ!}8+y7Z zv^M~h7SoaQjpzoU7!N- zinODM#e{Yo)w{_9ono-T9Vy3n9+$B(O-GIF#EREGR^efw@^5P6+tq9~i1P{QdVtX) z)vRcmq{}F2f*puEI`kleb%Hd(@H$*dEeVoM^=KX&Yc?&J!ODUg+o%zTL}vtQBjXnE z>#$8+d4SU^TKSY4C@NJ{{Sc1*#3IX|Q<`i?^Lg`1wya_RbE!ZEz+=5x9J4+2iwsT7 z2%sumRWF`4@t-5etqMt3^gHWIFm9W(YN9KsM?uTq!-`bz3|{f@Ha4v-aPTaM1(p*} zdx}qBU(&h6D7HK+dZWsN+hy>B4|UXn&eTK+$0Bu-1wCpW22ig0$FcF1MUA@nbxm8d za3B$rMO2b|S~EDzP`p60|r4kU{7J`qncu z?s=v(PdyVHlSrA{rVwAe3@aXD%(9B|>o!%GnzW)Bte>_3t}1ibTx!uc%l~}CZc3n- ziAM=DTjE;G+dsX`ZEu;VN8r=%i+1%@yk6Yeh>tYXPWItx+X0IuORgjksSWie=T5-cJ;>Ncyi3vCH69tl&|k4&c^qv`X%N z{q>GN>sx4hl}x<~!j4|lmlxRpnphQkuSB>b4W^L{LUYDoO$=fKYXZoi(6S^9X->Oq za+H?aAEqJzhY|M&Q6#7j#{BQAC{64)vcMO$bE}Byx6^Gg-yXNwZB}q|)LbK*(wL;0 zX(6mmnv!Ze7LU$}WHHSbLdy4${)fuw*@{Y7GjW+p*wlBWJkmVXtuaRw6|{&WOFmG3 z>GWR;VZyOci8o9bh2dYM?=oI)#S&KQCT}?u@m2e(V?2_q*inIknvOhY)DD+KC*JHb zGkliyX8AuM&UvKalHW*f1-|cVMK0DORbId1p1MS5e`wLh6;Q8APJ=4HVcd3?=^j#c z1+{2NvIOqypMZrSLW|HyO)1g=!+B((?gBsAYwPb)b=vj`*2F=f+KkqqY#Jm&d0+@o z(A!3*roU4?l|*MV@D47#GHAP_w!h22kVc1$%OJm)K9nH8Mo9N#&1RNT!*DBiC*}+0 z{+$B(OWT#O^eXt%RUz(4Ch4MKX6zpphMWOK9L7tw4j&qgK|y}^F|C5RBuTn_JwG{$ z@dXP3c9q*Ifk@gII_i1;kk7)PcX>Uj%Gw;hy|sW&#KWHXp-7K5OYu()g`k7cqcJC= zn^;1rposDS0OPI+cgJEPxK{hmnN5_a2U6`-9F`bm6-DuY#4LNxxFJ|yhu-)Vi(>Pa z)M-TQp;YYQcwcN{15;V1rJl6UN9% z6Ae7l@#0#V`&@|xCQ>B2DYZS~SMdKbtop#eUV}0Qw{kC`DSpGQxgV*n5W~jV<`%IJlr0QWy0ai%o6qpQ9Kzk z49TRwIu!yJIdxnW!+mBRQNUb&NrguZ3$0UV+Z>V)Oly*1$7pW2=dW=}XV~m52U+RO zAua(RXHO~8MJ?r1q)T9KJ3!n$qBKJjiJlX#hC_pl7b7Ty>5CQKgs>`7W|X~u%PdQk z$_tepz^9R?Vi&YkCL8|C82uG>`o>WK&RPwghGnqcc8BygyqZIbu*SY1}T+ z3~NID-nVE|^#oFTA+}UIDm5GDT;h7JE826%Rvki?Kc1wPu|FupDNc?UkNP-=qCfdl zR=ylpy__Iyn~V8EJF{G7I0{7Y{DXAs8n>NgXAaMu*$*; z?EoZ--ytI1P67n`J?~O>oJEl>LVD1e#)QM8X*N(zBhNG9%^l*B8GlqvLjw?yQB@^dG3gs-#$+|8fnYW5S@bO0YQ?w&E zfKF1kRd{8TbR_NoaFv6_|8@Y+xX5#$o zrL@>r0ou*tbFBNyMJjRCWm7VQ35{coOXjna1G+|i#ye7yqS7mRth{5sTXm&qaE5Em z@GZs?)6C+!YwSH)T*`%u3}X4iaUz~$uuhswXIwR1Q z6%u9N8LCe-s-%Z2JmR|Yc>Xei>DsWF)}pgMnzvH%d~Jj%A9yg$!7Y;~lM+r+XZ%x4j*@AD!Mznox!=8HS2Zf4*aLRt zne9q1;aqWtq8-IuZXmK(Wr7LrGNm{1d`t`Ukn?!HBuN2d8LXO^e#XC0fIJ$iGbS>a zGq_BcpE8)3YCC}RGO54mkTqQ)xbIW{JE#$q#Xc1TGEh=xqKTgc4ok*avt2}}#HMwwq&e#I8O0vttjC|va_2;`E7upkdQH$Xk;8%m5Hl;q zDRzty?-RcccD*SS3SyZTr%sjZ>jYWkMWuQX=5>o2pB3&by6^g1CVF^YlZuU@I7IZ1 zWTA6CPx6w|-hiRp$9~&-z~<-s?Ip&no}+gU!H1wGtTj=65XFeFd7JVJp&_=QB>gX3 zrPJG*-$$+lFYG5r+k0T&2<|?JpC6uZ_xN`H+asuJH3{AQzJpl4eq7rE;UD}3mZrai z*meKln9U0Ju#CRh*HdB-kGq8>%aXSKRTIZnQX8&NrU2VGFEjymjj!JYeul8m^HU0f zh1{U*kNDN>&u))}_1Y;?7pS<$^GYel`;6T9fwqT(sF@N;<@Ti&Yxmr&LERZm<4~xk z|H|8&KOOj4N3PBUbS|QYT=^^0AIg8|>N?<++3)u{gbc>p6@+X@R?{Zu$73h+Qc ztqmBYD6+^!M3MU(mpX%_cE4+W^CA=M zT5K#d;V*(T2_^$Z0Y3o(XcE&plH7k43?!hK2@`+QB-9tE#+39n&s5>%QU54WqiTy+ z!k%eaZML+lSyt>dL_Au%q&$C5@j99@fx*2#j?n)Y&L96^7Pi0F>8E`^R~U)XX;q8l z$+`d<^^eWnIzv5}W&>xm*sL?_A78lCU6#buT_X|CuPu5vcc9tc{~B7{o}}>j_6}>@ zo-DDwrE_jBl(2D+kw;FMu|LVZr>=dBinj0WUA;!HUuV!eKR~Cu8)p|E^msnl5x)nn zzfwZJ_Yc)NuVZ*V!b14(Z_x3+#s zz(8+>s(3eQO#?UduM5;zX?b;-w$gU}?#J1p47O(aS%sP!TXku0uS&phH55euZ(D-; zrS;W)sK%PVtp>6iJ$!qYSLT~W(JgKRl5=k#`&8{t!E4kj zQi{bp@FORAS&g!C_u<`9_$s_<%&FzU)QST%yBUinw+~@!F9IgOn^Zn*eEKLTBrWpM ziGsWgC@KGqrnqcB*<9Q#Bl-%`U0kPM=pi=q&^3b!MEtd(_%;2dClBULL$qeWQ_s~Hq&;CJ1?xEp`b)B zZ7F{4Qf-^s%9$+;%Ydr{9fOM7YGvf!PfJHKqvUybR@88VSO%EMqA&1K)ry%+k5=_v z;nL0#g27@NqR9CCg|GNGGF=B$@1)#&BnG`h=lKuY9M(mpx%sWXb!hK$__zM~C!`T~ zW@i61n>Op%fd1T|05sRR6NC#EQggHZL8g3dRS7GTrddGBdb!sopq=JKEQFr**=o-A zAT(H>h01>NOCZCR`vMxKIUJMguv~rO&xWV~KCzyIF5s|t`RF{-ZJNUnDA^bl#O35R z?H+Y&VLEzN_UtYogT+S+dj-eS_CBQU$apV7x(|H#Z80KUA5p7h72oE8tzWyNb2AAC z=Hji8bmiiFBXWFT`0(lG*NY^q#Wc$kseb^T`x4V(woF`X3hnR`Xmq|)RcEY39|}}( z`wbCNC0tOa;)l=_#OUP>A1`Hkhp?Z{H2n;73BR5i`%-t6cr^p6m|$iVi*@_26dFUE zTKdRKi9Q*02O?eoqBtb+Wp`|~sD{l8F*iy04gqVXysvSuJqbJ}&0fBcWP`6%FZL<) zYo#GsC>70l@Mg~o9MEJ+BAUuhbo_6(%U|!0ktE7+oC;h-dYD+qolHnaDapw&XD^T= zAM@ng*4)*NtdO2URoz(pY9g5A3iJjqmri_DE%Oi-#|8yiUt!&}=3C~~CLl2@ryv$} z^E!?AQj8JX;BHW>r$}$nIw+w+x;70kDLSpE8r(X6(6vP3vaa$xtMXUqB>#@kNkV6{ zzefT$%ojOl^}IweC5t|}d%tv| zMP3nDzjR{8ZHx$-`1hg2v=>36hmcaNo^@)byA+df9 z@cCFQ|J>GL#ETX@!X?EQdclU=gU?ap8lA&w7PRnw-x zlhd)7qFi1$M&G9lZ(Q+YMIO7}#?W@Cfgv1f;|+eXJu2Vc~&ZKH#ez0W=O+_P`hy}N4G zs#&XQ{h4#jQLDx~=KJ*bpV^%+oyW7(4hRpQBZbaBRThQCTr=dn+a-1C_WJ8GgAvGa znia!ety?Rjc#K&vl=vpHR6>KST;0Ar+zSC-y1|1OHSb-lBhE~n79aHGe; z%IW^X+tvm)sw_*;+^I>LE}TJ$SpK@2d>lfT>R>bAT1_+ZV{S0-6e_Z1$9&=GmRXUL5pK65e#4N_Del;76r5;ITPizrk z6`=m*FlaTDT#=Ln;Au6nSm9E|d%ZCu&BjQSMV=>5yx5Ie3>sfek`Di^g0j1c=}1N1 z=`JyYbSm#@(G4|mF)1jExw3C&kj^VTAtloR7q2RN5sY9LzERo0fP5D+8;K>sjzn^>2knnDk*Mc&{Z&QS5&@KP#qqxwQmYoqZ8%M<4P>%B zM&lNV`n(aMXAotkIu(P)g4Z1 zN-qo9v06@DAThd+?1Vas1v~$ zn4SSAv)4AjM$HDmVSt=F$i-^ng4L*l-N?7|VU`}FkH^Z1TL>laILexNW3aBHca~$Y zx{--kU?ya;3GXXG&+tXfy<%}S)U1mM4v=3R-=hM2cIgno9CZ+D4p zzQN3}g=x&|QBfAbD6quKa< zz22wDF)5SuN)vj+!u&=E@dORO%i6Uk9KLFBt>6!hi*#<%2#2U99#C|wbK)u{zmblD z*$7D`8-2ulz1!^YwAVC~-yo?R;-E#1&wr#g4-}rf{5NiWMx_QUgpkc272(}7lD168 z5oQYA&NzZ(l|fNRbo?<#{>+xLD&?O34={;eP(#K@?dlx6a0`_8hhF#+D4oXwIh*R} zF2nXvP#L^VVuk6_-|`Ogr(0u=aSiVUx;oMgu?Vl)e>f>ewGOXF6z~bp_&1ppH=~?4 zzUAfkzZcC;Dmdd|_8|Upc1Z&SmOad)`XAjfw@xRSyK6&H*Z*pYCa`9S3&`5y6@L9l znRM`)s79Mb9}{ORZp7{jAE%d%$aa78?WyhkRUkEc!U zfW6ixG5@7@#0z^w{KrZenFCV}z3FzGVURgB*TmFGeN-vhgjLbvDl}v?8o@bI<^VmD zUBhgiKan8aa1!Ba3jNu1mt?v*+$xF6OEKx)p!}s<>{g3qvBrWh>W(k*RiSEp_Y`!J zeln52%Vnp{$k_vRRJuWs*XSm(+y)6j}w79m)<=~@5R^u{0B zGhNez^;(RdY~=>Q9ga(hSTy1x{+Ht3m*~wl=qDeIoa+D|SPD~cLs#uLyss%NuGnP6 z4fC$?isV-Ry3~)B+S%=oNaIkdfH32+Anq4;=Zb*1#Eev>XM${==xgWvV)(W;{xPu^ z?rqUDI%3EXeRE1xWPT?<@fi>O>OVlz&>k~Efoo{T1?Q&-5=i}+jvLQK*04Kk3_%L1 zyJ}fS#@#T*0qV9$e>b{yS8Q68fjR?YxwjK!Em}9Axg+U)kCtq1i7Zwe+#mu}9Qs38 zqliEifLl>oQg?-(dp4>0v!l z>>FIqg(fc~=xULRWUCC9^(SP;{Kdo=zc{{Ea={ao0y83(NrIA2LMSdp-q+;zM+CJOkdVi&3QqSJX)*qRK7#6!UzK6( z5idpgRH$soF^t>cjUa)(`k{Yc%GPv}mhHh+Rgmg1{`*HgdTA4eAG0NJf^}8zhD+xI z?i8`~p~@;DJ{O^zaw?S0oCD1v7aAE_Qk{BQa5`)-C!?fE85v0g7(t`J4;F%p?NsQ9 zv{`LmtI}R3n{QNbn}gXcp}7ZU5W$TpC9qVGR~5@7o2yW@-4G4%9Mg1iTBKFAiOUjA zMShipW!YqahvkG%`3e6AGV^G8Ekg&JN_Iaw-gCiGn$&kuH32Y?tkj2()oX)HC*1=v zY$)mM1vzo3F^O4E@{LaBe}`f~7m{l6LSuZv zUX7zX+Ux8>BX(;;_Y^NXHU~_Wh}CK47i-9^uFhnLfx`!#jbvM-;k4Clb=vrpL`mTXzH*u=jFv*Y^8JN%cFU)+HD{{)b ziJY124B56>$)f0=Nq$Px}nEtgSuLz!cmJI zi%L(bIV!2uN4kVN^yWwVi36Cx)%NDWqDjz6V1RkeqkBRh%jrC(9bEH3((>neK5+*Kj`*O%I1vn72vI5<=^6^z|trIr*vy|v?ZJ@p!d_wHl3#syUhmfq=Vpg{W%O#X)G^qq zdHEEzLBD}}U!G;N`MSB*!reWgyl`XMv@Sv1(oDGXIUsylm_k=g-{6uZ;|9AmREkyy z5A`omNd&s-wnl8~Nv!$M9_3jn+6_%oE!54#mNxpfrElK&3hqrSX1E8Vxy|uBJ%3E= zJ)&4PGPGLMfboBfhlE0WLHS?QVO|&!$p~Skoz4~#IPFY!2 z4a^fp#!2%>L~)!O58+iuD>#ox@^vB-A{vNVjvUh*4Th@DJV>nyM_@l0%AGQMBplLj zv$WP9+mkHY8^H2g6Lmb!aGgdUSs=}@dwFt3=SzcRUTJ`h@G zkS%iOt(NiPES8wfALbMN=e5cEtmqY8!>0PL89na~BR#vN@Nc2!7EasiQi!}GN0}S& zh0;3EbR{owGZtD?iVU!%{9{QS!u{*;f%yz0+r)P22iNMK28eeU)%wgSErM4_X+=WX zX%FNYKY(}T;hbEGnpAz!Ph8ExKq@6)e6~7({-+gJNTXgswO(QQI`z-)+znl#;4{K1 z;M2&faqGYZtG9ZV_V4+JvE~mnZ+V?piL)3DlI$0><+s8KBT_1Gu9dkQ6wU8Qt>xQ| z32n=-!POV*#&Zuq-rXhaFb=?%3yY?p6Yo^@pH>)}unG;>up%@B<*=7qE;(l8WY~4E z`~{3YJnfu$>gjo?OxJgM9Hr<wqNvHCF7 zg3gj41SFKs2cs|xrUx%wI-uBZ39~ozCEpP=` zlEy^U%3%LRyG=Y^eo$>O;G%L_RCTZzT)I~d-BQW3#B!=omd%3Z9~W+5(P;R<23=wd zM`@vu85RT9@Yt1nk|$f*D@A=Gs#-lzn6|(Tuhpub;O_uLs@+d=XUl>`c5C$~q?ao# za{n^ymjnyfTlQO|{!LeuXYFpzD#z5svo0cV;|TWt`b_;qq~;Ag>zg`J4SGTOhzu=8)41_WAMeDPaWss!)`F`H6VHd(6{$ zJn|qbo}G?fsLjML%n_BJxH&45P2Em&iGIKe!pyO8NY9Fc{ z#UL1b0y8|gJM_@Rt6x<`6JwL1YRygQ_!hLQv=V>uU>J%)5V(5QvXpv>U(mHc&^}61 zAm|df*gC}K{4|c;iJ65=WmDu&UY>la;cb_pL{If`J*@oxQ!DHd&-tCl1j7;y&Dn*L zWA~MTUu)ls1L6}a$15*>0p9E_;6IA9-h)5}ZVV6*TGs!s;_QEiA}9f{G`IghC7%DA z%_3s|&1RA4Tc4XluUvJT3g#$o*$50?lvt8b`i8Tx&JTyM1`WB*gF8}(qR46fZK`$f z6CzRy_yVDocRt{O6TQWI?%i)ilK0em%{ojrxNv8A9gxawe=>rtr*jg~QVqDD8@7wb z8YF#cZR9)0<@5$h$domU-5UpEwe@z6{GkPdNoGR1N*^d2j#4(v%P=bC6v|H96!z@P zH&9G{547R87S#w(oIy}p%Ws8yoRdi1XZw%U86>x9X!|ZqBmN(7mj5b*eP0Lt|1DjM zn_C#W*}DF3#G7S@8ahT3F0+2QY|m@yTE|%8 zEh2PoRde6;IZzHTZ>oy6TD9B&RCU1bYq+Yb3_l91u41*vT50de&!k@L#MSsHvyD_u zzCHxa`=A+!R^HJku~$7wa12RG8TqWRsA=eIV+2CLP#SN7M9wu0PC#ns(wI=qWD3Dq z%l1;{Oxz~wfn{e)XThySHqq~298${2b|NBXd!#bEaZbB=JcExKU9(2PrhNKfaG_sD z0Vn9naBFG%HQHCPl3qAi*pe*?qD1vz9iI#6oT@)tvRyBCVFd{%3v~&+GFOxgl??5G>*ZZeyj1;$k*wr)tm{!l6ATZ&j%@jWD>{`OnQSdVZxT+>)PAfKhh zmB90K=4$=6Pyi@%*dcxwbE4Fbc=2Rb`3dISF$4?q4hNH&;hrdH1RbWe)!1ho?KqO- zQ4zY>HeHh41S0i);a%Ichva#g@YPmrcKpxqZiQK=edgHWVOX!V949cL@AliYa~ax> zYTDB+Lr``Csp@QO3U)VMV;MMe0ZS2*tK>&FxwSyQmCry@lyUTK^snaAN(= zX~%M-$pA%Iwnq0V!o4BCwKA^@`7Bm*g&>pZl%7ZfR=v?EkZw^awoMx4@k%u_rdH5j zYBp54S0v?pM#TvT-9|CU*>cE~!s;Zr%|3a}6}ecci#4j3O-(qAFzkBM{pR19%V(u> zezEw!vKg^=}ir@4CLS9xN&)Xy`ke}mevQar<3#eZn zAQYYA7c@tIX=ydRzCUL4L}eyel@){DoC5AU1R^1~%May*b2ni);F!J3z@EX5c?tS) zgPpbMgJ1x)pHoTQjT$s@(%6jfmRY8qpRd`bL(vs&Q>BKo0&9-mB_gd>k)2RC2SXxO zm>pUI)a&po8&~$h`1gqNa0e@(lf>?8MI_?$Oen?)8uIxDE1y&ek#9qg(mE}UbUuhY zWgL6RGDBawqPanHc%~QkX{rikS!vuY*h)#bSuq#0RKhMm6&8|ZKjqLir+6=x0!vBO? zOL&@^JN^gP;C~8)xvC0sdfx}fw5Y!9mTZ3c4OSHXY_PBcpil`>jp~OhW5Q{WGBI_- z%6hGkF^%T55En3R4~Ovq`XRNMvQ+{{3L(V#yye34Je|vS|L?lq2IRVtIaa3U?uIu+ zMBdAD-#E*-hpZO0i_uOh^QGb;Ea;Lo);6nSU;N@sl*;)=>7F(H%U^JW`9Wr6($7Mg zfnfy)m|aGLGwO>m6+&(;t%ruFklW(`mV`mB_)?bX&ah-m{W2P^-y$)W#LuiEZh0%+ zv5dP?LPlR-#Vy~`aM;!|h|}$cJKk0d36GFjC1Xq6uA${r$mH^ zAH#icINFGykIBR`dvm*5&20OSo7ztPTdAX@6(NlA+iJ(`;)>eWGgNdh#p0{?Ynvi)vXvs9Z-3w!w=-oHS?*RJ-5#nY=|%-?U%xeW9xjgjmhtbxW* zVmH)%#O#5_RoFcFrQD*qZY339O>{#2s#@4DQHv74cw||`a6IMSJ+RN4K3!Pi^_BRx zO%>n&Gja9}MHXayC(ixvK=|K@^S=hcf5%io)Yie&=08mp{wK}ifA0OEAFQv&QtR`Y zWrs^rc0#hFLU2)}BN_y_A+snl7|b}iF*5Wx#j_|FNf7z8Y!wu|hEsuCO_5VSC{kqezX1DJ@vHaE$0>fJ0uh!?^RO!gXi7U^&*UznoIeyQpmPj@qD*?3vIS(Ta zd4Cne%Olgl*fr&!)P83SrdRrAj;1$*cgP>BQN1W?TR~MQ_VjK2h1Fw1wa7dFn*FA~i4OCvhmF>4q?Ya-HmR@J&!OEjj*6s5W>-ygEheAa2%!pt!@CNgdBUrh1*gHtq^s8kSfO6|yETDdt~EBHGt z#1(UWf2dpk5~QV1Ma}FDT#Rl$(op2~s3B$%QI?bt^HX!_`R%3IWA6nF?fC}-$3=l> zv+vfN6sORN_{c^TE3z8(w6!G`arl#_3DWCmg+ram9(D1n=bn;-oe>}VCvJV6%#Rv- z?IwsNM153;IvjpSeY++`mNv#ta-D78F5&?5%fUC#`@7K+;(tB&7SqCcOMe?smprTS z&eE7Fr6!qd@)%vjSPc@r4{!|iey-~?o(%g-S=~RtqP@+E9%3NEwxn`Ywh8i>zb3s- zjN;tBx{Xg{E-J^(kFZF-FK24HC@|>K2)J&#RZwklJF-8^wz2VSZD@DH4K-lhD2a>_ zRGJ3g{jl|U1gifN>)yO^jBLQy$ny-en{Qo z-nOb4eYI^oSCNR#>fbjABpY|TVEDiHOWJR4#dqJ7&9uobu%>8O>z*{$YLp?%lvKA` z$ySYx;+gfvXbz^8i_d?5V0>Z-PNEp0x*%d zN(rJ2m;s9D3ZS#eW-YsU9Hv;BT~W8e-Ok7wIlEAaPkk9K=RRzY@27F-s!a3dWr;S_ z6trzit+y&{P(WE|vW@}b@;L`U#aF`D$e_o6w?DeeQ%y~xr*id>rp_v=0Cdy#eH?!) zN*mKvj`*zBf#Qpi-8CVG$5|}blVTQ?;h}WXp|N_OFGcB&gCT!=1G_%F=tIHL^LA7v zwo6Bf)i~Y0JBCZ$Up2jQEaic@g-C6yUB$Qz7kF^!_NP_u+-T%Cg}v%x;b+-lV6Byz zR)Wbn@5p-$$Gs2kBlxUIErpFjQzNKDkUIb4TcH+Dv?>?JUj;-FYvU%J*SpYJN}L2>l9* zCz8fE(i|L`Q@d{oj)%+Iwe#5GtP12W9GdW~Y>&ejk=_|^r*iD29l6PsZwa>bOl*&I zkEqX*VAIKS(&zKPNJ=HkP&dw%7eGPyI?s1?trw?`rwFxgM@I#1Lnpj9Vs-U{;jQtq z*L+&2&C6p-a=oz>fGjymX=*1`3K&(XVebl;er$N=QD^9TxXJLU91s*$`axy>m1Vtq zlo|POeGdi38q}Fpp2~gp*(pSft!;`*HrD3VI5a1Q;tn_+8Q#}iH4OHWZ!pXk5WtLI!?puSMpL3CLm_BuX zn709x{v`;t{qA&Xy*S)$@pojRdPwhm;ONvS$d5=o9{A87kdtW2M{^Yd&rqATnp=9c zIcK@u+p|*oqevATq)L*+c&LM{b@xQ3SmU6(HaBdm!BzNMw-WFMipJFZ^9wd3y=za} z=fF-o%XXMuY3_lsd(QquqbA{<-f~RUaiBDA;%S`8#k}W-c<`2@ojf^9j#>K=3I<2U z>*6v~j>ft=on7U5mVTij3j4biE;{=ewV@KuK}Ru83#SszM%ZSRm9A+M&1%P<-bDTT z2`;L-lR8ETIoIb2R1RbJTCwOB3fSroAX^&Zpg9dA+AqV$CIC<9h*ah06`~0+AmU=3 zFTc9N=nQzYM$u}M1gii;`!2`uQ`ZsAi1nv+E?;Y4I$X}eau1}z#wA4)*$=D5cS;^6 zA?i>Sc$QW~aJs{_fJ@wXBCn;6CSxyCH)nkYsbs~mn`1M7I`QVy9ApjP3-X_xDf!>i zds8E>GLdD#7Gw@pwDfAksO%9Wu{}(uYAsvXsP*AX5*E!^_^4ZxoC1`HivZSEYWBIq z&xuwAPfdgUI;=v_`J>WS5~qlc1-dJ^sO}L>`+dUt4leR5v}dxxGy71iB05+W@7-O@ zDp8Yc&we^Wgeb#3?H*!6R9BPq2h1Y9ld=R)ZT`R%Pik?G3HW1yV1B12>>Z4Cu|281 znFMMSaM3-LTkS~0;+0+#Dd`LJZe%ex5i2!ZZb?_Z3yfb8!)SXlX@Av7ZrNi1?SIjV z>QR0GS00o^Eb(QOW%(mkMomc?v6kSNsxS=eo+9tkr(OW_cv|=J()@IJ@KJfBsHixk zY~<10sdTKpd)uNW`JRI0hR8xcqVglLdiToT_dP{I`odWHWBJ%1M98|y&8A)OY^t-* zHBB}3*7dtdPi4VXY_O~|x_Z3Mf=@wo-eQKjfh`+5S##{gg@w*CJ#~zikH!Yxy><5L z`-6uF6D?X|6B?IbsIHn^Pjc}+7^5OJbuTYN4CdvN&wOT4hksh#5XNw$2n=Vl`g+pwInoA@DZH#-%;T@eiarD%QZT88D1 z<1ra~^H{5O^f5d75|W#^p&r5YOV7%#c}<$iY^qJYfa+xh z;h8yTz3#!#jUq2Am?i1Jg0~LZOCTb=e{*x<%vly-vg)vo1sY=?7gr@vYg+P81{dI> zViM=ROc95#-sG$#Gr1gwSH8tD6jw>8r_lAYEf&R-_$cXx)^OoKg{(@(PU(3z53X(eLP5K176E2e^TfKnNL{Qb>8+gBf6 ze==fm-Uw4sul&mE<^w;NNm6_AGmN;a0;2~Ne(#hETvM#DCsio3-c;Xt z(2i`D^;j=_BrHJjS;hXUOeTxjKYXG-pd=a;xBIF67@nIiA5FCdyhL8fO%6Dlhw2ld zJtJ1VCqXvRRY6YgVsXrX;rDnVH>``I4efqd?oV-gt5H$K z@u0F~#mE>lZX9aWaS7I3c`7oLsp!9oa}!mo5^kWlFV0Nyy zixV_%tfal14dUcS}Q=IuuXE=29#5;l=;h)WKe+t|1K7iYc%1Tp95FON_U_mt8H z$LiwOb21N%51)kN2Y$Fw+oq?cb3iK3W3`hrHthZ5gnK3c#z(a7$x2J2znIoH)yCq@ zV`oPwD3r+x>mw+yLTbXxCuzVbj+v5)kC6qU#|A)>dsNPp{ypDR68 z>i#?j+rQ%ZaB8i*AzQ+#{3YJPlgBzQ3t1~k3vY*5$kBqC<&TO!JU$-2yCORsHaF$w zN}}rDvm%Z~f+76tocu?K@EiwfgrH<_31r$d5&I9n2fnx={0HAM@;Xv)J=9uAuMIlb znQ(RcB=XCkZ%Beq>TMMbd*B{=oI)bY5-0g+7n0H)m z(LgKSiwuE4{xSH!e_VQEX^4uI27bV}`bKH@$3lYA_A?$qbV^6gmm5Jt@D_^Gqcz-% z2La{ddSsC$ZIEH!U_n~lzAjO^38eOkT~KwjN5VifaJz=<5QHt|OrE5*(yz+)rpen)VNN(u`z-z#1O{+G#q?NZ`vkK*FB|_lYg7X*jbXKdK?Wxk6pO$eAT|27SRQi#yvQ<}?L8Rh`OW4wogF5w+PW zBts#4gy$h4Lu@^9E39YJgi#>G9aA4Tt(KuR%B*6_O2WiQ&Rn3B|oa=y}~)rNSx7Mw{g zW3gvhye8#Y!8gGVVX$2dtjl_!n~@@95{akUW97)D8vI*{b&Q;R-`Sgw|9yB%pj`vh zLL90**J)s!&k+7k4{8_%&Z!vL6cPCy9~A%&w3Tmr%#uN)^{{B-J}IVZ+dhN2rT$u- z59R33mMnb3)E2y%i3FS|%BB(L=tzx4shTp>#_;gSR(5@Tm`g)(7bm5iRZ^$M#bwtA z4|3n#)}%gJtBl1&$Ww$Q-X;L|V~CJGd=yq-$g<4mAdErgvIwiKC&~?hjR=c0&o^>O zcjG^YnYiY$Z2Ea*x7)CaloZbw@~PerK+70yvA|V8?flcXr_Lr!@dsh-lPvb72J@PY zaZ9#w%XY-PAyVrWNO3QUqz_u`lLhuAl5tCWzm-GSynWF87F2OBfn+zNqz_%}lRft3 z^M8Ky{1sr`((Y>Ck}GmT9oOc875n6beVNR>w#mFEz`WMWyk=?CGAr6WJ7AR`Hh&d9 z|NG`EXMRgo&(%>UFpFE9_xgsEa9(8?Xi{ngPoj%77E?NMsXq?&P>FuN#oqXI7}e~F zBQiXTEZ!qY6}5sw@ms`vPa!MThvM!y(xZf1C$cmn#E_1}8&$kum?z=eMEl4XGXZta zs}6Z~DE84EfdwnU7K>C&eQADgc|cU%VRVygeS=HKRo2LZ_NAn;$%3eb}FX^Uvm;INcBF0~Yn)uYOear@RSBQ9^?ZAF%ePOpbB^ArPO6 zAtNgp5g*BtF(2%p^n&XkG}xF7thTzQFDI&G(poqqU0dS?KC$xND3#tx3NeS3P8Cn zcC$5Ee7H^lzS5m);<3u9-FTzwn&G7TOa|V&NH?;Zq2)HIs)pfeIqiyj2oQf?m$J{^ zC+-k0a>|9o$*Q1wN_hljLIE7KS1U}5K>X9n+?t>8Bsc1=B6-5Wta3!!+%mJFnb`+G)vRstl8|UOxW*6c@39MZyeH48!OhTR zWU}J1pr4&^dAEC*4{Y+K!fH#yis|1{u8GqneNAMhXH2>jmqlXcoN22%0C&CHv263l zJUPge5`uU4)J)r6TM+fHpv7G63Lx+(ii_63GFr)f024Sm>U_ygM4*cJN|n4@w-c0V zIU4BsWpfF7zcpKU!sWw_{zx)E`8~rb;R)|XX-RaVT^&`9#vZDucjA5I3SX#{78pW<+8&yqa$zx=nDMB12?^?@{Z^u(JI#xSnF~z;)m?^`GJAKGf zk-5fWJHZ;2e_PCu=wr25xQ=rf*53z1;W~;QkxaE>-`le`{oOGk9SI#*;yGM_&KC#R z1MJh^<}_;aJH(ccNHZC{e3jcI5c$7%-e5$}!;-MgR&%4j)qBH|jc zj5<+s?F^e^hcYm((3r`vCk!Onc;-r>U@r`5ty5x^i6X=%44GOg}~*Ff+dsZ$n$`kvt5MT~1C03+z!(14Fc=Uwt2dVh(%Xc{S5z~*Dt zJUe1jE_Ho_^SYq$6OaVx38 zeh1DEK4$=$U}t{X1FAg1`1S_cqg41MJu~XXlr|6!cxhr&$VX<)!8+y$&SmAw#HSyM~Z{le^j36q**b-fREk6n^@Xg)LxtbsqeO=dvr_=Q1yY?Ing3UCY+jo#h5M- zwzzPEAAKM2ZFNn?hsr=r?_5K$C^Ygf3=+0_vN75b@-clCvd7|Lzzs01Hw^fRQvR`H z&`OWrSW4!Z`b^+?O>^*K5nDfAE+|Yq0J)+u(Phk4!C>q~R zyFmrYI12{vJn7`@P^v_5tl9OWw8KZIv8N(bLXoCB(2*$qsJ}#qazj&H2rPLBcBk-^ z`woZJ74>qq(+>UAco1;1GVf_Wc%dx593t90gh3-4nc|MkwJ|NWPZw!b%Qa40nm}Dh70}9uvT|UR2Y|2hx zy@oz*6d&GJ6h-=C>ALu!{a;M(qCK=n5MEQv>f@!X$Ppu~2dsZ1 zE`5faQLVEMI2a~bSu)uKT!T+bgUWs>a(uAk_eo`oczl&1JM@r1#>RInOv8D;wmQ$K ziU_UXL1H|l9gV;ZpX?u^1jBhty=s+gQMAhGi(F3}GAj1gdtA_-fYXR7`cX@qlOL=A z@fYgcl9=Co7STO2ESH%nsxFe(*rLdmYWmP6ItQQemo(m?OOCBh-u@*av6T$Fh{Tcc z@UfR7@np<`T`OQ5(Ul}tFqOYBQgWiJmE(RB3(#{8n%BxsAeHM z&SKYQ9eFzo*iFkH1qMgL-ZS{(LL5qkD}PkIXYu9xSR&@G{}cvK8TUZ?VqJeIPT2V%xCa+*KV=GL;Sf>u=?sbTj&!FYB@v*ng|UNOnuvmZSu4tx;?>K&`H{XRoAMZUIJ3 z1jUy+m)}a`7e*CO*mtI}nP2#Ue3u`Mc~KxzNjxIUkniNGYS=$uNm{nzFZ%#gc*Ds^ ztH=wTY;CRJ3qt4zGUJ3g5tsEOEB=DOpSoS?-{DU>>|mTOF>||OONOV)0DmRCw=FdV zZr|UdA2#t0OA!wa^uJnONC1-;Q9tnl+msGS&p3&x91f6??~gCRdL&Ny$lFqp z1{k!$)t+N&uT&Z4`BvP?XH-s%(dlk~3BTFAm2W}x;d)R$Zdi##>A&-t(?OQ)j49Ik ziKEsNnJO?CO$b=HfWH3Gh0BDe8LBBHJR*Je)q(P!jG>p`>%6LPd92`hL^P-e2ehu| zoT~~5b&J%8H$xL#Jb4N|YbQva1nkl%rEjIc9CoUD!BQ$L+o2El{+!2j&MO&k;rqI5TkEgqU3&w862n z)4H=AQ!(6w9%)y)@aIwZ(wu$rol$|E3#1b-XyaNX#EYkvy&eSmr%d*=f@`uDh8q2wyp^!WztlD>5U%#WQqWc-p;+yRn?NptVjI3&uxzd=fkyN+JodDZuG$X!bG#^XjlAdT zAA?ZbKVjC*>&G6|z2Qyw7avMF&WWF*F&p!cAR&i;9?MXhSyM~t8!HufP^L?t!}9s-jaCiWiR`=QmTU+q*R z=->jH3ZOuW&^~XmZttktB+W%jUXV=B(WQXM$YDe$tX!i$Ghoo*3&f>R@Y-?3C0Fn| zW!EJJR2j5ZX_T%pFe=zBvX@SltFH%@y)0yk&8ttBRu)DSRZ& zXT9A~1EODIh!96+Z&UWq4N#+dYRCXp(hDg|L1oc3idM8|+OaBr>MACSdb&qkUK(1) z5APLdMzK&!)^SC2I|>dZH%DVeV_3J{#E)9lq%c0aymEAhf}?U7srH)z zK71GxZUpz{Mh_Uu^VJ1KE5Z^EA<P|&f3~IVY=dK$t!gYl;4M#+1L!z3U#ofDWMels7`3#z zzgy^?0Vg863+yG4F@O`&C|$!xm5M`+d`TH;!z^LMqy%3WG)!sHyY32uN)Ljk(3~hy?=uK4bOfXIBpCw7L!-2h;3@(PiJ9U|r;PEj% zH8AKs^Xnizjp?-P=L&42pDJbtPSzOM-o@FNV2ThlP)ZPh2H`Ju+mjiE9#YLUgQu^a&PQN($` z*}8dnTTT&IE9T0OupO966`}8Km6p~?!Am8dPjFV|liE1)lI&rCe~>e?FgR^A$J1+= zZJ|>y3lC!2j4Swa^gNwx`ef1lsqNu)@WCj|r!_SxS2ZyYb$QSmy_Fs4u;dSw8&jpkYJG75k0q6u z57q=?F-||j-%~Z2XnvPsFS_z->Nm<91hZtv{WkY4!5sq3|ObXBr(oZ>+kW6QT%Q;*vodt-qX7z z74*U$#_Ei8m_O$~Ul>%wx)LF89RVvCk`e(ZqzKU z7*`Niun1NEmw(G1viQ}vsug`w8;Z^<6oY*LPIC}W^ZU7g3_oAgimB;Hl51`teyn$H z6|^K;?f5g|UGp5(Bgi68Qx;j}(5Mn!DAcvbu!?4=hx*ZOVqgn~W`%M2tm6(syeOu{ zV0zx^5V@8R$>cAM_m33S*;ieGAojkJGrLoEc_a8!iuk2G0MnYW3B6W|It&BG36h*P z1&}vI&>Ak)Uw9QTJd>^N4&a;qwYye>m~bH}{p8GDPdDCJ7ph*LhDxVZ+nGe|fm5VE zIUI7B6B>VCI)ix05A@MC^LQ!~Zl%wxHt{bha8 z;{ducc#a9ap+mmsS} zoLW?mDIG?afKn%{xCn+L)450P5vOW*sNPky%d5>^rA|ectSbHSSt`o=+lAyZFu`3^ z`j?orlCZRrsI-!pv=4Df?0 zmdIo;V7tyRV28zDse7E4@R*B_Z^i-NHz%Ou&59Mi&k>$)K)WsZPsG2NhuzNxeG|t) zUv2u0EC!^-JIy1PO0*C7gQ!m&@HK!93Q=nFlZeQym1-lk#W*W!NFUxohJlT$3nW6Ge=%{5%`Pzb-JZux*pt@(Qz zl6Io@dA}RDNb{x3E0uruvr;GlVdDPtEF~bteqP0q$(!2EbwXgwVIcDdjBz_ ziuV=0Yq!~11@7DdIuOuRo_sbPzx2@Tbb*UNWb+5!@kgVD?>xb)3Qwr zdG!{d^Z=q-A&1;6M1d4>3=q^)5D(g;nJn+`UDW0T+ArU|Q_pdhVh*cT3thcu2X)N9TCFjEqhp5Jc+PN+InNpe*ki2-Wg2x zp;5DCPC%yJJneeflr557OYeim`z_r8~nyS?8*Y#9X)A)N{?8U38jGylWa4*aoa7OK#;x!k<8HDg84%hdku&k zgqk5;oE@hLJI6gv#LlxQK$|V}CvItkNq?mYKzMSqMIl=404MUdNy(2%Xw$C$!P+~= zi1Kw=!`-)e+qP}nwr$(C`?hWSwr$(CZQK6(H#2WC?@Zn&&mUiMDpjeZl1kM+Is5Fj z_F9!wzg14j#2>4mI~BR(NJ#zxGa6d{8BPueaIXSTGW;72uLIn=i|@(C26Y};NC-&wirB~V0^pGy8(5=)|}2gTRq5rBi^vdsW(t}jlA zFFt(gO$qoh`=)i!6;U^}uXKK?^MKPM&O{52FbuzZh-$MPW07wNtG%3J(T(=wVzeb- zq;?Um_%ManGi)bM&A?Xcz-n)nK6z>F>u$Q|#9Z3hZ;DMwM+4P$#T;9z|MruD9mbiJ(e5?nHb zoqu`iMW~z@4aU;%@|nCeh3C9(ten>%*7_D8(jkHuQr^i4`2eAbWqI_J@nYj~%;4BM+6bDp8No z9L-xaU{b)%F#{NLcEbk2xDmqvh(qgG&Ix3=dp=M!K!#-WfIZfqpx}oeD zM`5vGUdek?UuiS5=C)KSL`XYrt>JW>;0 zwy?c^Q%Y;JX2$qF$l(%*5)%Azh2ic(JI>u6BJ!}?nOg?TBZRXpnZpP2+K;YuD$Rz^ z<2LC_NU}bf=tCdz8}Gshb>AI^Q~@}a`XIyzcT~9cdL(F!<9EV52ZA3Ls)4QqV0)6s z>bZHYH~QekwL)vBKgl}gDb~BE-{9ebkuJaG1?8!NC!%#zwE(yaGq;7Vpy!3QhL=@%oODWQ=@9v6r;s;SsY(!BSZY@igV-a-!OX&@Z!qiIN&L*9K73Ha1{ zvHxQd7o+Le0_4~|-s3*d6OdBQLXOMpSkQ`Ux)=;cF{OxjOVpAbX7%pVq5clbn_dg| zrgDol2b#_JH;5gjSO`W!tjO9ig84b|T(bDzBv&H*poVq-1{SzarLM6JJ-j&UxP5e;Bke>V>aE;&%m-?jdFpAuY3N-Jch2&|>h z%yl`%Jst9kVP5>)L^ap7VBkbEN9J2YV^w%9b+l~*WX z6{BjUipei#(>bm5nvnD%m5aQ9BUR`?5(6QLOjg~gAX2iK$@y~1C2?Pw^MTMgHwQ3b zeXM_;8GX{hu;CTlzcl?R@MCo>b<59fi84Rk1580SOo^abego&-LZ*`Qz+OKh06ai# zhCJgo={j>SOR(~k7AO{m2ZqWl;L7UZ7Jaz|#Kbcx*tRY7WN1rTNSf3>X_2;X13|lX zgK^MYuIFUYAh}q~oeHy#fh0fK`YJ(M%o`V%Uu1y|k{WKj9Jp8RT!zHRYJupw0E4JH zYxfdgLePk*(lGMlAxGEPY>S;fp_HyGV~_HkJ{`|oYR+7)&s=iOT(-|#dd^(F&s>7d zT!zeC(&nzm{EWPH*%OI(#Wsx7^Vny>_ml>Z!|T5H=k;#!`ODfW8?e^4tfMoRhVpd= z)n-BMO&UAr_PIst%JTJb?M)k3=XUK3ciOiv{x)hy=l0FT%csEnc>3?Nk^u!>cwnt< zyH>8_B#=(fg>9hvmzh&Owy+++u3bOdL!diN_neOg02)&y*<3`KSl*Al`I0NEtV-U9 zf_OSDVHHyO-@e2(ns4F3{ldh)e$_98JGZ1S;k^B-ULd-+s4wB&3Q3==J$u&+df%v( zb>IA$7uBaC?>TgjwmXzh^Ehy~m^l6=M!fm)z62Dnl=<%bI1-T zT0n!9$us7;B&WOrev<^BA*U?4A!o4jo1v*cHkU-+pbOn6zFZXYm(3%#er*^@k*}(v z#9+Obb>E;Z(7a3=5OaAhd`bw(?SPRDNBu&?*;Ej2eGB6W(m>qoNcRu94ze`TPi#tu zqXihUJj`w$a}=_FSlpuXFu6gTii=}$9+3deJ5P|OYacM?Yze;wJMPiXUMq|L>m4I> z9!>vJyT++p6HuQLSQkY!(9_ISImA8jq9&C*A^)fa7cG3;8@4=Xn}z{nn{}1&o!7s$|&SgGeut# zO^uiC&kVx}5O58k#VCU~N6J)^7}I5IN=o`G)Y3D7&J}St{BE!@%>Mu~$Y6=G4)DJI z{M;iV24BJLdj7iNKIWNX&vC5Q{eC$h2e5z8EExdhWyx1Y&Y-dyLRoAZ3Q=!SK^9kT zD9zVK#x7g2sBMu!Ud~{f?t@+_VrtG<(f?uc8{7Ig5v^z7ju=5|)}I=5(Gl2LZ*Ni2 zfhxA*^QT$7i`1Qd$dM?oP}0qpI@z+!@F+^q+AiPrBJYJlv-swkQJicak@mo1PZ*da^=PK(W>qwtEt3BDpb6 zMYFM`*Qx$R9&gKRVh~Yn8mX?!P#0Qh{8F@$Hfe8FvCew3CKhIy?L-t^3k#X_@8hg?*;C$JUcuDqyCBlE|k5EXoryn>HQEyN|@|bRsUu;S_J_=jrx5 zjLO7_*&)Q(gDQo0Nma*ZZBp)1%lDaW8p|lY%%K7|$W2=TkTy%$kHh#8IihKL#FQy| z%F++Oks<}zIX1oYZfE^N5l8f?6;Y8E?&pVSUS%~(yVYShCg(rqsYo2rJM|u`uT&Xw zQx3#XLs7Wpt)t~FY0NEfmbGY;El|1z6CBYxlhx2>^1m@NW~T1EEOabv5g_dVb2U*F zblH|cwf;o3N)VfBj3h^VQr3i02ktkP)Wd2tf${(Ys;l`TbuAN(jX7EbQD{RKtJJZ` zR+d$ zVny{`CZE`A0;osPL2Cv&#g4O?0q13NAioPC&?$+A8!5ucU)*^!;b0tb#r%{~yb%2d zecCsBQqUU!&{|wUHzfB=J#UEi8_UQYShBrsJZv;LSPx>qP6o(#q5w@JK%04;?il&{ zXv(Ge3=*89^oUi69oL8Q&9&*(6g~35H=K6kW)+`!U zbdCy7nyeBbv^rVg2soIlnbq?RigK%KI|9!i`$}2+6cG_lE88EnpKx7>oPeKj0p_sw zcXOD?1;ee@E!!+KSnxQ)nz`DIyDn_+65rnxUAsPR!tFV9i#79#5M7U{WKuwt*4SCW z;Svb+Z3bTRYV)jR5si&@m=JMYGbzujr!CaiI=dn6*HZaKEz(apW8!G|wLI`9H3JoJ zlny*;8EC@NYH49LW6=d}24*#bws%}t#E;p;Ur^gFnR{Dcg1{6GN&@&k?$lE>Q~1H0 zM58&KcZMy!*!+0)W|BWvU13k795XL1JEJB$*C88MR*W7tO$VA&7!e&`X88Avtkff0 zDeEt#j$UN9SeZ^fqwH)LZ9>`nf*bnuF7gKyZ*TPt#Z;Y74#SW5qo^A;?*8%KP=-RZ z?v&V~S4bf%I|u(F3loRZAy%0P8UdmbHkCYa;mwO#07Vri|KciwayPmBBT4^Ek%bF+ zhHnzWlQWXxWFkQG-Pzw(uC{yY&QCvTIR%?OWJa=#V~TFhg1d0^q|RdsU$%lfi3*3r z>I3^lH8rqy#B)UauL1UiPs=eQebYLI$Lu;%$4v=L)fpaI8PefK3Jpgg97?6>S-GcJ9R$WV0p_xaz36a8Wz^%&tSOzve|Kh|X6{-O52klTlM7o+}&Q2&rh z;T82AC=byVO=KA?oH%+O;8RN+tEud+;*0QJ!6_^PX2s2>gepSKtI-w*yfmcA$*ruo zG1D0_(nIo@DaJdiU{o|bam4Qj5m91{g{i!$h~H_N&7G#)@SLsP3*dDb_7uV1+L8~# zdEUjoYI5F3&pux;(|;X?<(|O=32IeRAXGs75wxelP$-6o4r*Ch6{Fj$M?FX@3a8YU z!FD=GXnIM_IV3csLH~Yv8%>#}Gy+fnjcJji0lmgWgugZLf2sLlWz=;BxGK~Gzw*{& zssFwespuiI?O*?k(43Iq>F$XgOV>60w9kM_>Mr@ER(2CS(XVOs9ad**%)_%Y`KsCq z@SOxXNQ^2jM-#hRCzm`*V4kRQ-U16JW=#VpTn9DR` zSdmk-K~H}GB7WlL9Wy;fJOQpsPn-JJ%YOLcNG=4$*VK)y2eg0|5mS9%&XHp>gPYyv4!+RL&e?XwQb_4cwk zk)47d=I*g25xrR5<<#mhPrCYeUE#7-z$f=US+e%f?l|r^^T%&TmL0u9>a)^b&C8E! zD*xkDwpPtsDBB5-aSZXQq%Fp22cv@-VJnn#FUk$Q<%(Vrtct!j&y&DvlhLjv!(pDy zXr{<{<_#mg;_eUc8X6Rs^T=Cyg&p10VE~2Ery)Of-IqC@%s>C+!u98$v;?2cnl=8q zdDfUdu`;_Wy|;6xv`VUrEUb&nDZUf^cvDIqV^Ho&lQmwY(-;jkHbu?hNHWeD>ymsY z`AtO}E+?o6Qd+h%sG$s>MRY4AREVwXL=iHdm>3RPN1(BH8#zS}YmT!{>i$7)OE7}r z;Y01cC52NhqO`Q{WzL^v)#I=lO46jt*k=PjnT_vO#_6CdXly z`q-isvL9JH?*Qb}`_`Q3scF;4IT!X!90Xek`MvAw5o7c>!1wf6ta;$CC{2ovIx%}| zIxtD0E{72xhjA>oU|qkC4Y>Fqu)%xdxhRyd_mhM>I|Ow!vG z?W1$7RmP}F$OXVQuI)|E2G$hTKBhsX2^YootQ1DWBmZP+2FexH?5k7Q)I2eVZ1TxR zo?x+F=acdH_kRc@xCYck3_}0_+#&w=eEI(;F%hQ!qlutxi}0g~&|fE~r&%Lh-t>rw z+|;NfA@va&)`THmLcee`hZ7ftCxw#U$Nq%a13$Z9vMQ<$QIyE}f8@`~= zNT7nMP%ZA=N(xf#(^C_=g8g)i1SZsDkiAUXbioVk2eM_@C^oN|CviDY) z!C+?#v0F{Q;UO+}-dnNH$?!B9PD(L89&{3mpo63fNSKwvUIu?R;R5H@Z!(7ML>$;P ztyd4;-z1GDpmc0ebVwGIJMu(icXklJ3pt#BtgX=)4ujnzNr*)U(w-s%|0ob#V7M{@ z%Xl}2_#7x2hf_#XCeM+RUteT`0nJT}oL^L7k;!)4IU`2+N~-hj2+GiOKy~to__TBr z?qy#T)$Yy!EMQF-O!31+2Xe7sPvGt2ML>Oan7^60-B#CG-}=J_@Rn^+!2f0@vbNrA zR)T8$?#|F(N(dQl51cyXv5d@-3RJFYun!dBlupPI5@3}e%ku<*0I~LejmJf5KA9}w z+qd(dAsl0bcXft3s)~xU>+XFs06#L9=8u^IL;>f-P_&1Sn7MaCS0!P>CD+uwZlN?J z+KhNYdtx8X>Mp%3#CDl$RyTmjM)$nIqM3& zOvc0PrO=5JwJS3&)w8RKE|CqZ39~9oL_|vyZ*E9iN_keO{6I zP`4oU7^jpA(2s=+-sv&;g18Y;Ee!#mpk^Z@Oav-OEMouQr`yj;g_{pl#4Ga~3xM}!rkEpf&rLW9&U73*n^H_l+ zi?-X6CXJrl)KDbzyXXhU3@OgehFHCVZs zh-QxLy2ds|hH9d2#|dNQpEyN2H$+erao4KPCxziLqHl2!Y~#+-ohyeY)V*a*lrCW% zKyNE56PVgIQ{)Q>;R4G)Mr6ixKFMCo;{f#!7cF&t32AOJRTL|=GK@?N#xwP{BC>~R zr#inB<%F>=MkJy#)T=@SImeZ1i#u2$ILiL!Y6f$c=0=E(J#MI8ae{0^BL+A6n#Z{b za=Onc+mHTMct1Nz897I7FD!9pvTyiH!20)|oH9*%k|UXN__4*fPN}R&+ZIq``iOcT z9-UY}(yZud091v&KLUScgTQjE*41fkZ1$6(4mdjPRV&k&Ji2cP)57WbFHb@Fihpc) z`%IAm=bD?^_5gH&0pt}@vWF5^ps8|Zk36!dP(9G}tG)Oj{eV)WUQYP&Z9q7xup@@4 zQpcZh3Y{TJE}Z4U2;Ay2H|Xm3+u(54+vM=(pdi;9nuMwgM+txnReRwV-L%&+h4tSq zJzb?uRVwU3?Pb16_a;f#0P=H}#)+T_iR*icQX6I_6FV&gMAd;F?AEFg^?Sr1_N9sP z*gDxh5KSS$!Z1OK9wr1{ZccNd_g?Mx68z_9F6!2Q?AAuoAXtKv8|Av4qLod#(v}rJ zx>g#nBIh@H1Q#>mLkJ<|d*f!>rca#D<&@ce+mUv^v)l_VM1aae>v7l}^s+>&YhSR2 z{@Qm0T2^z?S|6Qd{BV1?L0?!q&NJJxya^pD*A^WFFZNoNdrfF4ueJUYW6ipb13VMK z@i2SMZI)s=2jh|l6x+E8KCfyzs*%#}(i~B%NpNNl*C{K6?A2s(*_-VC(wN(`PzPFs z|6&h7fzwCL7K$Q7OfuPYU|``)7p6nIcr&7d>$ydcSxGasgpm0xmiY-YMH%gorSXnc z_ELSsiw6+V)k8HzbCDy@9+Peyi_6a)ogXH;fHDwzMqDtNfZqVmW)s&tV&#y^V87Fc3x@7P<#6~SqPZF} z4@|5O7SM~iJhQ_~v``S4;Va||^eOXKY+je$0C;-VPRsAwYE&FB7BNrnqENGifL5}z z#b~}$jFdPi4q~ymQ0XOrb?4dlkdDyqun0%mJWuAGQk+4)+wi^;pI!K?we24e>{pf; za1NFfjc`wfkJlVYi4cu4`qqjiJ^IsXr-eBEPEmW z(=#2FN+F_7}P~Ad8r%!WPQ_E1<+WBhP-;7@QdoLg8KFq z?bxlh9+~I)j{NCGNW-UjU~ybn$%|F)mfZyT)_g~9M8O!aqLfS$&5Tnq6+gnr;;@U= z{E%AY?UF!2nx>S5wd_ZeAGMP;DVAfZ6>&WNj*9rPmqR>@iuFi3~t-jnFj>`*hTnP>*l}X z!1Z6kgW^vAC}Wws7)zPk80$Oyr}>t!i?NNo_&l#*ZmhRpF9rl82nf;-lVHAyw;88x1WLc@ z-|i+^@4b&FRvGK>AJ;=<0fy|jgGHd2^8x!AB1h;b0^tV_(Fo8Y_9T$@p(>4c(>FAb zZC0Hwl3t;J+WTj?E?10W*0(5{DFjFrYHnwckeAVd>!aKCZxE)D|HL_l3!gEEZ%{^J zCYwWEVMq!n9B~b2;f0Rpwm0pgkf(fTLd9toS$iZvRV%DY>l_9TUP2q%TPN@#-Vg77 zt9GXKDuY_DjY0+|QzfBN3^MO-?OUQ$Hkf8%H9FiyAARK?Ax|*$Kg6vY4RBPeZFP`p zU8O0n{J$4*txxuEdG;$31S<){%XufYmtOOo2C?(BhA`;z@c20?7R8} z=w4runZbOR28DI{Sn@y}4WkuB=)c6KVPuw&hfRvk(2Y#nAyw|4?9nARVUIk$Qz$jnuj@hX8b{5;2sO{CxhcY~O>;Xa`6~QEz_+-i zo$P5Q0$57EL%LmN9tV9djUS=@q-YH577_C?E14GFxKqiH;=CW-ATCV_K_zXWtW>IO zQJLgXByp_1Ys~sAxns1SA`PK*8U8hPj}YNCwIpW-jF*^PD=bs#(Fl(LJyZ&mAi;m+ z=d$$g>B4G^V;56k8?l0HcgPn@ES!AAxkbBMW$$+ME*H(qjyi58UdDLjvD6=0uJqEZ<1{r2H zh?AFX9*hS$JeT+(a2K3H_1ZZ>I7?Y1E_%g$tB3vCCrAsh!j8>mSGV@}g#6B7tDfF1 zu)HjE+ICl{j=c0Yeqms@inus^{XCHaHoaShdeyLoGt^k#13f&rW3{?aFlcOKL@;4T z^0*ZCD?NswIHV_%3ex9@<^kGSQY3SZ=?0aRVJg4C&o%}n!Igw>rp1Xh*9}IS4r_~? ze+M)*c+5fwA-CtIl~&=~1k9LX~K#slkWawJ<>i#L*3q}c=Zh7RvNhOHU@ zxdSP6(l)LTj-=c#Ju+dDU&XR4=Pjr!#ZL<@q$~(io9|Q8Y}4;o3RqUQ8aJRCRT!_I zA9vTVmSncqn#YKTwq^uRDl9fIgEBOCRA|I9+WM8P-B9H&P0-2IR20Vk3aN0bHh-tq z#viFoGHH^4I@W{v(hoDE@x_EN(e&n&-^jB#P-_`gtAe6}A)LIIZ+`eNLrk@ZwO-T0 z-qGUzt9O3vMWCWFNLfQOy?=w)sJMY4KYk~8>4uc%&p9Ry{Lz_ONoAKme{mMm0&y#) zN|GMBPG)dZuu{BZ1?xBw9Z@x`J&9O_vnR!*%A%3h0ZSSR$|`4}aEn@snc=K`p`na5 zJ-2{uX~FdPimsElgg7NOp#ud`GAG2idhhgS=7LA}^sD8K*bCzb)!e2$ z_Bg9UteVa>HO!hn~Es(RC7ZV6AZVh zq3N5BsDk`gcAc7A0v!awBAp>gP@URaNFggFLW3RUAHG2f%Teywkk{-4@?_yJx9nV> zpk?UYUd)%qsCwXH?96#{-PG`bV7L6A6#BG6*7-g3Cqbd!x&QQ81BX>K8nn?H+ zy>2%ScuUEHBNDB#*{nT&)HDB5i_pcwcy7CWNm=wsL|X}B_CpXaqepF&rI@J{>Qa+v1(Jz@m8yKh11f-57M(uIAYSQN0w?! z3rjQewn)3)Qf|pCjUT3cU zu%hD-;6X%r+^LuS>!?ri4+VARQx^ysbnRjRGP6;Px%%haw5pj-_G z3B^iO#@G`-x+efd4lP(NJO_P~)Om1-D90`UR9_#1X&L4ggJ=V$393k9X|$Gz&}6un zetm@%?SyEQ4IH8ly&EWxaU32)AbC0=;~=3>%d&9wBE*%CS^|`^T=v>$4XOL0xXBC@ z20v{KM-nRVW*DcMUw{c71{3LP08ide{VU|OVfQZA_LuAXZj8%I$$5RVmXF@KwVE0Z z)1Z;wy34`yoW*qz+X|pMx{IkI%z|h1+nAjW*BiUFbz`}$%bsR*^CWwbp?~Ng$p?S8 zp@G>51?(HCSV-%A5avF7dH=M^)^GL8s+>|Dj_8vyJC$a79A_s8ZvGslyC7`cb!=3T zqhRI|f#5@vk+^rDad*yB1khOXN$3JGx{<*t|m9sd!wn7h*R>*N$T@CH#B?gf!KLVW;7wMh#4S>3Q53j1e`CyfD8!Hn`|3 zsgC!XZsSQ9RwMz50rlZJEbs=(V0@_Zn@@yS{a`lhIbA zMJ8p|2QLlfoh|M%!#ldi1$>En4^pfRb?c3oduK}L%X6TgvVxqwRudWb+dkJ`=Ptm# z@0)v0PlxT`IDu-8mhmhl+>Sy>b*Dz)GhaZTG+Yp5k7;Dz41<_RG4BH^gwkHmF1KE8 zHdd|79}%sZUTG)RAj6^U-B|P&HDzKBC6e>2RjVN$?ZYRwdu9xX_FAQZGZQPG{ee)=VK-i)ZX7h9Lh`wCI?GzgXq@XuO>Wrb089pPo60({{mlpxS!7tk1$U)&4f`a?+^l~z{hey!R zwx%9rvd}TbsTf3dVB#CQw_@}OK~Zt=9UKJ#1%KMJ9`s7sm;|V#e@y zwv@bRm(N^?H!D$U;|ZVFAW0=S9Si_Z;^>!C7s;hb&vWOjZ-vV8httwoxYKhlqLOT_ z8zXJmfg%617Z-m)rnIz0sFeQm#lS9%L|e(mX+uZoX#`I%YYofT&P~+YIdk@Hxz7Gv z3LVJ7L`Raajk$|l47{fG7&RuV810vhK$qu}mQ@IuM+-INtBS$8M&?(^T4oABAd9x2 zFg3^i@)DY~KcO;h_cT-Ab+K=-l8YhTawbuDn_O%jSbKsn?D%tXkXN#3so&{+?ydk-kHjB4c#%DW$bJeR+3?%; z84RE4uzjtCIw5R?5>X837EnujAPjrP_?0lED^W<8Jq4^@4z8F-H|)!o(D&{DT_Jn+ z)s}#8JL050if}t##O0aQmS~mSz%zSpZGX%YiVd-hnm88+U)V0e_S!U@Vd)2q=kDIh z2f%TkQ0j;66_K1>mcbb7F#s!7P{R}lj4K6-+0uz4AD%0fsX^{B;g>jt7|$e^jbbOe zZunC;zgIMYN3cXX|C$6(1Nq)8%JkU9i{7j$updee4cRK64BfAHwqoqm|f^c z!4Hj3$mg7$=8w6jHj^D{YTWMm;9cv=U&9TzZlW2{+m^=;zBpU+7Pnn4@AKAJJJ@=Rx z7w$RXPOwpPU~*wPVg--*OlrJYV~@2;c_HQIO#>(vh$CfOoF^(^$-0&rsx97Z}UvDz9D6gymPB>!%op(Rk;&yTDiX$IQS^q?nh#@@$%XrP(~IJB3uoH@y=$W!REj z-ed`LdNVhSH)memRp!fVd%We@LT+BRM_k=r7U90aD5hMyw=F-@Y?_un7>*awQ0A~` z;(N?c6opj8H7sMuZmK|E)~n3;SW-VzKa?!Wgj7mDq&g#V>suERs{E*sT^1Er^glE_ za&a4ehG#cM&pR#+bA4fAHzL2aV&|e>2zbom2-2=1x^boX=*t$WUZOvwb7ySTl%F)a zMEaO6&#${cV%K-`cQ;oTyIxK{@Sxll=yT_g6Vih-t4)wjMxafSj!3Tznyt(JW zxx_2ypKvraL`UL*^$9AJN;_-6s27sg6xty-zd@3_L#Fn^!yYc-y5HReh%0Vo1I}-+y`a zWWTra#`Yw30($FI-|C`rCSkeLu!D&lWYgV)X0ozM!T5}X%h@?*OtOU@l1NjR^duf5yB0B~G}Umc2~qVXR&?JY9JA;uBsjVDRu8+=M(zc; z&KTqBswDvTh@n)hNiXH!ib=Zl3KW(z^GFit8YUoP2n?TWRtFZGj5WB+Lg}^JYUfSJ zM!ARK>0{LbCafrFPxd+gok?EGwI0ZbHMTY;4{`mOZTN=K%8=}{GQVr2<+VOsu1@;p z?N{odbh|$1<=NGaI`;(E#fy6Xrez5Bf}%a)dJWw)<$CJmW>^16o}M~aJO4&oRgp$# z*ZqjIUB|eqY|F&$wd|1P;ZurxfT_Ab6Q;YGX^Sa8+UdrKxP1rhL*_WjnEC?iA2Tpy z^!(TF94{;D#>Fsn=MeyOpdHuySKwFluQyW|JAITE zYDlfiU$6$T`qQ_8nQj5AF}s^+By8S#$Uva9(p?6JJuqW^Rr?B#dfi8$lsQ{Cz2>sH zEwUpLbYOjB0u4EIy29Q`vYh%|ESYq=#qF;cyGQ3vz2}%}=wK`;AY(0vN9PP$R{)F| ziai~cLV7Wia-`<`)@G!c&s5Z0={fq7Fw$O>@C!D>v4Uu=2CO1cTQLa7v$4OeaYcBi zH167UVL4SizztPy=D&CnOZlbCl|w8V!RS@Lac<^FnM4~}Ui-c)6jW=7Q~I>yQ+?GsT>o{kC5E2RkW=r8QAz0 z&}baj@?@StD(3((<3T!W!z3;N9R{$Ku z=teIy$|k-y-&ik45O+ZJ_0xyQwF-bff)7Pd9L3o6w?hUGRcr1I`@>!K|LM{+a+FCm z#8Uk1_|UQ2|NVseD1Y>s(caC{=3^6o=}IU5^*5hx0G*2bOJ3sZ^FMgV(Xo77PCuNA zFXDey;S>2cDt!OT&PUKp-^TQRoB3#4&dZ_sOqtJHZEiSaY|B(Ks6|jgRSUt_3TG+> zk$3V=8hDDt6Bds)`4a0ucie!z6bz7F8^ncO^zm&yyLV?l6TaTwue$=YyRC=-Jqv8W z&i=mT%X^$SYI3WZS-FZvO80h+C98n3&hDVBx8LJUx0je+n;9g*Mz^JGcVUSr%_8r> z;@}ONFh!J2AahYax>HX~Gk9Z@7&Y`_65~l@pngJ3=wc3PCjBfOC1uHpyqG|l;#CGW z3AzpH+k499Vu*4bK2Y_9(7%{t7&oUD+w0;yx)Jxm(-Zgd7RLwK?6$X4a@M0T2ipXE zeo#Q4-Y21M4KEX@NDzc;=53i99;MX0Y;~Uf;0!q$p(5my+#USJ5!`hUMlF00xgHJ? zpLosD8hDfCaLRq1b(j7El(vu&N1qEXL3Ws%qI41ci?N1}j3?Ve;dzaE= z-&8*624RzXd81T7QZ@uAhdJ^RP@h1^3(jE3E6#Ap~(}&I?uCKlpD0YA8IXA zpROUoa9@|%cV3m*7yKNE%?AX{_QgluLe)l%iQeHJPLQws#uZ2N;-rO=R*_C)Akzj6Ffccj$_u7G3V z6olheR-U!8-nHM?a=N`=fb}pjAzS>JVOcX$`>A1@xi|FHX#Oe-kj|lu9nki{0C|qp zxar;Xg>4WEq&Q6Zem53PPj}Hx@XEJ3v_m~ks`SmU(GADzmlivqC#{OD`J%03AfK?b+wPN(G{-}<~h1O5h|J*R^Bi@`G^5x zxX=!b>z4XpKb5m&NAcK>9+x`0V(r_Pgp(*{%8AnKj2qTA9OYBo3f(hXiHYgsPX+Fm znSm~_gM-@lv1{QCg++Iv@d@tkF@Kn5`EG1``*oSp$xFIrL+s`U`YG8^4eUZ)av6_8<~Xe>3r1jh5b*E z^zl*ERQ?1B{J#tmfqx@N1kG%%j2$iA|8M`a|3vBj3o}rWwo+0?`nu|PKAP-!%|pUz zQuzA2=On>7g#@;Kw+)yHp*+qjeCzDi1T^n%WC9_qN)kmsa55D{Lqx?yPlGp$V)YSb zUqDZzRRZbkj}aL_b7QMtvE9jt#DoDsbJcmgbb#DzI4yBnI0gZB2 zOD|@g5QJkSW!0po7m;bjY@ZVZP>27p=d)^^u<3&6jY2T@0LVqgkHb*gKOlqH4*U_6 zg<7d6E*EII}>;W<~m-BM!b=O(v2pX*XKP z|3!v;mhl34<1P*nJ!M_A)1fQ=Ieb#N#l~N(YvUN%^&mp903_r^qr$k`Pd@qm*SjI> zz_qKp39IU@#3nUs0Ttezl{%nqUP=~JvTbC1E*?xhG(<&*_yBxUtvaq}yCV7Fu!;Lc zIs-OV9N1xNqkwJWb&_|JYtwKRKSMaTj(&n4^MOj8@KM1;Z1b?q85fBdIe10NLz^%I zQ9CiMx1sAe4f%}wI9ta!jBP`rWAg#AyX_AU`P4r}PZ|l*BJJYYmkPT+utoRezo7Y^ z)3sTf>8bRKh~X8!S*@snTlYxE#_fKQI*bi&2#|{^wq=%@C0SxB%n~@hDJGQ-ZKz-c zH<+-U{{UEJ5`rx0^f_90JTgpBzr~Fz(%6iZo~Y*Nn@icB1HDP8mmG!|2aRh25z=V` z{MJ@X)n8@Xz(v^}Pkyi7H=#oH;7O_t>DP87{J05my!x%uiQ16?b(zKxD8swyWdVj+ zvcj9*MYW^iG;&wvY}}r6L=jgw#UyB_xN9Zrox)>Hc|2{+63c-^m7;y&@dbXf+Ni3G z7B@dZa_1<8!!$K9pyX>~>9J$ZunH|MOt+EG%YosZ1dypF+r53mUc$|w=C+?pG9xa= zs%T#AHxdVrAY9JA%M^-IV=Y_+AhEboGCNgXGsTevGimtO8dS1wrB^9k-{K}lFy8)k ziAFf;%PW+_<>t%z%$CkN2VmzZ@q%>kO7VgC%XXgLlezikQihCSy;8%YQp&8!IaqvD za3yJ{&)BF;cjb9Z5s-_Y1+=xx4qx35BEok!BKPga*TL|)*)ru*CeBOLt0N@BzW`9Z zi>9&GAg#$8C2ZX!jwD!`svs*bcDer1A_YLL7EUR}}MqWWmmHJay`PPg2`odZ_VFRe^9t!zrEYKm~68wN(-pGI2} zv#Hl9vJ@Pnl*YGUnEO-Fu;Xr6)xF5Z0;tX;oELQ@4G>Y>9ad@pZR&NvHOf8w=mE} zt`%m5UmUp&Mq=5bpGBr1BfVECr7$vZjO}kBp^K1v^96V(*o9afK2fJ=qHEaAR|~&Q zW~P9VZUIl&39}8?cm*HbT3-l9o_^SkVG!Lc4OImSz7?Fl6*Bxo7}--OyB!-$SSwkC z2N%uJt~fm|X;2g@TlU`Dc!Q@j)xaOKK2HO99=M3xFtq?$HXXQeJMj&FN(1&H;d<~; zPGO+oK?C&nAOf1ba8=#gAl`vwy(j9(0&#J9E*Y4ONtC_>uTyacvPgI*3LW(ozhR{B zj}-}&;+F9ooeSb+l^br-+dq5h{xKFK{97&ISiQ&$G6b5bBo1KKf-flN$PRGVw;AaQ zUS9w}5VU^vZ1VktK-CT@3RvYtuEL&C?UZQMo@C~cB{@`0qb~kTD$8dJ7H1<8NMV#1 zIsKWx7qVVGM-i}>lPbg()w8GqwV7j~8jaH)hBZm?r@jhyyeleFRG3Y&({O)$JtWMb zm&y=2WYnvM38EhpkLsM5=*gZPgtT{P|5>rhL>@*3et0DzQ2#vx{-4ZZ{(ob|`VS_i zl=A<3!Rl1Cv`bt>_u0BQT=!}x!z&j-;G>N7q~r73fD?>e{1d@X0h}aVM}%wRvadrR zM_HnF2GYAk*%Y3;SBYFnG%%s&<6M+wUzFvtcG|EnwSJn2dztf9&ufw6*k#-O$I@l? z)W~7#b;{lL*gNN$`}*swJI4of2gS?6fTxZGMXx2bJY=Cp61sh{X1K={ska}r3v+;Q z#ZoUP3=fC-CN<0)jpdf@3A05Jn+JY?%1ag+49ZJ)QZ}9LCK2PQZ1*=a7xn-nTS>4f z@;yEf^Vxol|FP7>AZ)-3ezs~k>cUfm#QP8CNN+dLQ~qlkh7#o(apGL8=Pj2ZjqGc?(dcymfaVno*UxsyQ4>BUx0vf}5aYC<;DbYVsIX_AFo zyAH-liE2rbwhcYEF-o)_7;qHXsy(u2)Wkaa(ImdKC_JE~lq$(9^p+HBAb&19ugOTO zhR)W=-2=H33PF)uFyQWk{`Bz)Yl08-8S|6}YOgCq;nZQ<^+U0t?q zGt0JZ+eVjd+qP}nRb95-Wqma>_kQQxiF0pEMrK4t#{QFgzgX{j)>=;`u!>2Gp13}t z6%)+6*pEJc+rLfi^<+EAq{<@^E;I@QG!~_*0|qSAh}1m_Wxq$#*;rVQOuH|Wm&G5P zyk}&NgcW`M%*=UTWtg~pdo#CIF(td=NzfXaR48Ee8IntPM+g!N2m>t^1LZ=530&-) zM)L*kIRceeiOIV*p!Ii}5OhZ5A3;-4@Foyfs+v#Am{qe>(oMU7tFeuruqquD*HS%; zt;uB=_thXqZcQL;cP|lScCrw*hPbRw@4~eqt|_92+;m~_(4WO2_=e^Xc$Eh1GnE|p zkf^67f*vZ=Q%Ol8<6r9hbAoOlWy)gW5Jc=X+FT?282}3_W?mo*GosjtzD2Rf%v$Qz zC(U8vYRbJ>lgsf*lS6^O`WUaMVuTV)?#x!nuKZdZR)Z++I zH_?hIBnhj`WsMXP<<)W9q`pb$1SlAjeGE%-nQqWSG^py<(rTw>vV`z*y_dI2eaVMo z9L1D*ZtHn(Yv--0o#l5TQ=;@9k`ta zCY7#1R+8T1bOR}U?#JwUEMKNp0?yOUe(qY?rF`>qMeiON4KeqyNd@HPm7Jim#t#&3 zRF*P*su+*izrTpGJ!W&wc1#=OplTBH)Q)y2(;_U5a3u~zsP|uxG?9`EAZMx88JiSX zQBRZVhYM84ap}_AvX3vQMI$EE4;_}{7rLdXo>cZ!qQ@U0Oof@M?vS5jdT+A*R_^^R zt95b4y{t7xNu8uDc}+#jP?B%gtx`~|$xQt;p(!h-d(ila#IVT##2cwoD0Yc9}DQrrf*DM`pLDsToO37syV z#=>eovx&@9K^~$$YiByT`XI12%8!!sKF=lJ50s$eBlS%XhwY>hr}b1;d;$b~N`#|Q z+}{#wRqcD?iw@0MzqR1a9N0X#MZ_0W{1diMZ{3`?OLg|>nv1BCo!RnQo(gXaeg>aw zKHL6C9yQ?zWyK*D4BBUQ0n`FPi-vL3!w%}fF6zGZ zHr~YkFwk1wfVbi3j%s8c!e8W8CSlCeu85aJpW_bO(;Vf(RzP-#Kvug{!@w}bTiS6E zncsR<@qR%2o96iRfz-;1A~?&GOf-QkT5RQICA#j&2rLkJRnn( zvVj}s4aw7B8W6Q?11|8|_U{2I8tkJIU$*!QKd3lPNuA)UO9Gnv={6z8S%WWhfX;n3 z$k!pOd6~svsEomv9lJGM_ITZYFof*`Fb3~4W9+U=3vaRuZ=uI_9LJEf2A*S#)WsC` zQg~=fRdN@9E&wLGgIco_}I&8Tob7}Kx?p-H9oInB3iJwKpH_s{GudF5lKZ2|Q zvj@7@`SjG$|k_A0Gn4i7Z!r42F54+T$71%I!U*8>?KGT%N%qPw8stv&x zF)Dnx7laZsf(O=QwQw|u#J{%eGYpdjB?lZmq5i8>pQ-$z^XT{eY+w=`GnTgCL}K1q zPxqkR&x)##3{rVFWff4fup@XgpM?bk81N?Lq21h9RTX>snFh+zDup`{=2XS~R4#dj zW9c8SEWA6hU4etVzhC4hlSbAtOMlI*l}`-1MEC5I3`GcPk6UsUGPIB!d+1*s<2RvbpGWNbH*h!)Xf>|)8_BdA~R_YZ}9m z%Ecsm2u5(aYK>c7Ygs+nG61&KU!PVSX^*OQ#&WY=FOI5~#xhH=7LTwLho`A)T5dOA zpXlO!?Y9~C5qwjoYLY0iZumWoUXdxFY6>UWU>dVm?3@i|yUO*3Zn6~ER*E~&(z$v~ za`&mO&h$HjESFUjtKUUNWVInm;g7k}I696!rZnT#qb(cL#(0-b(UyH~PJu(l4rY31 zKs0TC6pSig)>+zOPnAQpxuUgQnTMN&uA?5O+7zzcYm4^cNI6(TeR=w0i~y;Jbcg%B zWrv0}WlIe+qU);!a)6AkIpOZ#B+~fy8l?&XZZRC>%j{FN)CRI4{4x$fhzhv2Q16Ec zn2NFHU1L3uoqr0Xt7}?1G`=lzJXrr7$o@M&NBtiFSw(kiYbp7Ekt|E9ns(Srh&%;d z^OY_m^(2yYXd}r|VzDF>mM?%%D=8H5LBe|CMiBrZ0mh|{IFX6#;6-I^B=8`d9{y1h z$opu3sb4ArS6@7|>LJkq75wL2TFwDmQa;jM5+%u|tIED`C9Y&r`Q*sfWp>-9_toi@ z=k>e()#f&k+0Y?Gvq2#etk_+wfwBmFI0Mc;qFQQbE)Wr-hpR0J>pZuSnzLJKC=c?O?HoMhaCT>=%nquq{5T+`FQ=<8EAAwlY=w1V6oqCYi z$dhm&Q@>?vOnv%Gl6pl=oedSRNV=Y56M(nAU!$5NQm{{6#)`@2M9zKZ8 zW{wfl6Wf*AMkXDFG}~$3TmVNlW9#{eO|j#)LoJB?jq@ zbggdxN|Pl6kap0vE|DhHsPOyA3rWi8yFwfqd`Tk0olh|DOiV$hY~svaw*ST{bLu8B zvcQ==cUu{}t($NF=b9{L`;xj}DAH;&TqQ3%z*jS7TxHC>!=LadNh})>nPty^fj08xBdT zZGC9@pg2BzbpdiFtuTsZ_h6&2b81hJ?QCSd?+Fyx^Cr_@d(~QxOhf&{KN=7788LeW zK^Km{<2-#qRkdm#6u88GxECSVIg`Z>j*s;Q`F*i><|f}i<)%Jb6{a(M1?C;QW{yH0 ziUa1_8Q8Y=A>%nH`0=ok>##Jfp=&6N(JuS8J4mJp50C*NPU;V%~Mmi_}0 zJQKFZFEkb}edAshCu+93?Idxsg!<==gtC0O)Arp1=uD*Zs18Q1t5u42S80m9Q`&v# zD*r~wfvE_QRd-q+}EtiA@h8weJ(o& z++@&s>vbGeCf&gRvx}pMv#WTzRx9WIdDalI&IFKlA*?fx?Q=IRSj;m_=x&l%5z^A^ z!~yLh+YzVhW6yfSk=X1`LxX9&BnSxYxcw>T;#PeDz%DVe{9=L zG?0uN|32|PfFsvf^2Bx4f|2V=+BdDbPDRgCle1cjfX*qamct-d!>W*;N^E@_+4x+g z?|3)TzQPZam*ox}93}q*IQsAns|L5@Gg(402|lPud(`X~zlnewElV6qY1#{K&&$MB zpX*fR%Wul@%nNI_W*t`N*f#u;pGXQR%4lYUa!Bz-GuOU_JJ97@^xA>i zWO$1D($y(DN}RKU)vnZr@DHQ)xtV@rst40`T(r+h0nV1MYFvg?ndee*jMQ1m75Q9x zPH>f3E?(|F=Z4=*z_jK3xE;}H6zD7Kd1Tr^fwYwObd-WW1Bc~sF-3`u^tH`^*cR?deWESA zAg%r4ANBd#jKc(zD8d4uQSXvtf~>NG)CdolgSaIK@N#2EenGnbXrV=_$J7<^0U1KP-#3!_D~W3nMClM>e*0@PQLl5Y}2Zpg^4 z$P0VH@~{W${LRC2B{u_hH!FeANc}uV6IeiH?vk;hrUSZ)0lAU|xtf9606+m~f$ScB zw!Z$*^2WuMgcPQe3<F% zkoE~5XwVu0z7+%lE4h|&pix#oszPgd>En_8RKcqU?vlO05XM?PeHm&bxk{aT!Lyr; zFmT{%xP^UJzoXxKLdcJqf^AfF7)ENfN`?tOxc%_{~0*5 zEIhMU?KQgxx70cHt~bG$w>0U&H~qDxWsl7zzK*gSLCK}!DZ#RsFJ=9LRtzO;1 zjOPmW7Ov`{AurKl2VD6l&AVs^o}ktUu)U(dH*>kL`I3zQjP9!U z^yf?q#wb6Q9S@;T_P7eBpP722QR?_-T z4(4vejQ>J3S&Ejji~J}&4V#;^l4#3h-Kg4jE#yJQpvaM7`XuqxX0x$3_RUf*5!T=( zG|x4WVM6=hzJ7e;Zly(Ae`>aQeSgx&gbz-OVN?=FpsS_iWx@p%GK|cginH82<35G--y5ThvELGA!=ZK3hk~kZCHTZsUX^70 z4msym?prr5_eB{5yr$}xxnurb{v~KHd<7AFi)(CcB(Gbl+KH!dU?uy?y|G6*d(N%4 z_#2~lr*f!Hj*37Q2@p4=_}8}4JWwItA&D`Pd1ca=nZlhv(<-X((KuC@p^B2!UJ-Y8 zm2iteZ*fpX3QAt?8JzYKT%5nrIRDZ@Mlwy}%Pl7a1J+0$wkv~%GwMt-?Yj*%n8$qB z_QUkmowtk%Pt=DTDS%rI?Nsh+)r?Dxe*l150Eg{_twe9I?;jvcJ-3@Zj2YZ+a~#Bt z>o)V&(O+Vo{59m%e2rMOT`Qb$CV4blPX@GSt5?Lsk5ma=`>1R2Wqhe7;Xf_PHqW`E*X`mna4 zCo)YYQ+jHg)QamrM)sf-A%(-Ym1^q$Y5V_A0^j~e-{QZ9_LPdXBDOGs&k?&?J+&){ zRDPJ*4GG6p5D5YhBmzn7$>}BlUyqzcd4SQ`YGa+m)6?ztknRNS<3e|q5|l~_gYT_? z+SBAInh2@CXq=L7!)iwAX+hR?=I@5CFW(DrFY3k$gP%RDs`DVdJ=8~Qu_2NoXZ3zC zb}`H3$;ohKbcUPkz#FFreTBY^C>`m+9!*x|QBh;=ZgVgfj7CsLC$(4b-0$NQ>F%j2 z8hs6&qP;fdhW>ym`-Weu(P{93Gr;SP5qU$*f-8}ifBK|@-6;7wMRMG273qngo2ew4 z#)EIJZ(&1JUZJyxvRJOx9dK!e186$N>0i8h;CAhLcHKo$7QKcXT@v56plaCE5s@aC zB1`_j3L>r8uF%v~=`nlpBgWP}3?V(a3&-;6`})Gz2sx_Tkr}nN(s;Xl{tdHQ4qU3P zKA2=5SV|!fF2;gcb9rYNJS%_!Hb&&m;0vx>w0jdRX`rkaz1j55UNIcSK_#!Se2(26 z`>NQw9MUU2INBr$(M&Y-9;$drZZ(|Hbp0G%XTFQQwgWZ=sG1da8Awz(g6Z^Oz~W&% zql3Z<1Cvl=s`V2NM4{Q!xnGSJU_J>G#Z0Y}*IiqvvDOmCndC$eWBxk&t&M1-Jl{~! zXll*UhdznMkaq9=`HY_gcBQ}6OD+X$`5dUfSEPX|m?KqlYS&^#Yr{=!6#tCLB>u;DV z^ejs_@DK(+ktR*QTTLj8lWOrBRy9`<%FH&~aq@tt?uuD`4dQWn4}PX= zL?5tZCY=Qs2BS2b2*MqkyRb6%gLcA^nNc5>DI29k6?c= z=-5g<*`1l2ptWaKRAoO5JHZbxSdm-KsTfkWz^RqwiJDU(o(qo-+rzoqr(JEMtJp(7 znY-fT>@%TG4aMSY^>t9DgSQH`ONmp&8&Fo;%wy))g}4NdiK<~M8l#}h)P#O*6wVg? zVngjjq!b!6P%5@cOcfQ9Cv}q}HOA{=R0=1NA185%lQOMu)BcO&7rgWwK3r2azAZQ0 zqYO7sAl85xK#5dbC>idHr%WrV5E3p#_CX(yC_EB*;)OXUezYhayCsW9m|Ic*#V^6v z%r3)KNrO=Y!G-u*E@i6p-6DPA341veGzCeK0hb2#lE0s)?28Z7@) z>@?+7=^kAtOgg0)Z0xoGW4Rlgxx8eK6mCuOyklywIj+%IqlY z2=l3({nzt6SQ3z&$v`eXF`tE@=%}4_L{{M`%On1Q=;BMFei_^$HbP%%)wdXW2@PMV z0IAhIU8})^^KL}tG2DKvkwQ1 zuJifzX`cJXe$Hur83FD49$2>NjQEpFPq_4roj8KoPGu8$g0VG9O9R+s9PCvA5I9hr zb45GcwB)U!ycka?lesazTJrQ0L*A2PZn=86;u!E4q?niH!3Z(@EG$$Nv_)*C&gdeT zBQ!TC@zH9pVWzqO|gP z?_m;fL$)FdkkdRRt51_n-PXZ%mh9@Mv5;!G2u=z{K0vf1@rf;f&Ol$4?W!V%P3B8w z&6+~GvlmighV_i#6^PrRb%~pyzoO~ch3k=h;_<|N1gLnCAE70`V8I_q^KFA(DRk_hotnQRil`6@YFvVV&oU1o?A$B ziyR!0@4L%MG!o-r+%BV8SpWWM3ensu?&>tby|+Ftg>{(_v0<(jWZH7OP$y%4Xjp>| zS|lJ7wJE7ozSu69(I-kIP{Ze+Lb=rh!VUOu{gc`^ko~Wz_wOK<;Xjyq|Ewtg3%&kp zgRfFO)mRrn>5}MWgp(9lpfO)y)sD?TX&~ljAjqSRQtUh28de0@NGHQ zg$;RA&Rt);ppeB;ITUaiXngdl zZ<^@?XWVmO65AgAg1H={km;=Ah=R=&356R(DV5<3ZzL~96Wk=~BV$+8>3{De`yi=1 zIR^)8PiMTYZgI86(XZn_$kA9|LDgLTvU@z)$F*n^C6+wBD1%!tIxmJx!frg-Jz7R3 z2+X8Rirv=3=<}>&{LY0@!zh!Ja!2hQ-LT0!ld80nCug9ZrJgCHdZe_ou-4_dGVR&h zZGxd%-BI}ZwW3XN-9C}-5ArHmYM9uA^pG;JP+zW?hT+>${O#;?VQ#3%7-Z5KQiPzp z7u*)~a3KSop{{Wa^RFSs&V(wHO#4jJ2j+rwkD<9-yRH!&b`kfyd7@d9f3jz*;J!>dzRYwli2 z3C}SNZq|d%SdDk&M`$I25w@ zdzAjKXy>ZC@n5j7uvq!kB@=vv*Hz3?n$`#fMk>x-`QhP6`87qkDb^JmoI|2m(H-&Q zb@$@&_c|?1`sZU zPWD>SJHm~y?W&j^aSLw=9Jo;5v34Sxbw=zzfel|jFcGd*)NKS8VIrtTQHha1;%>h=fx@D4putwk3&7Tow9K`YN3@_F>OIuTma zYXQ*{kjgYLfJgAjKH4{CLy*{qSs8*o1HKAopgU5}imWEQ8m`9!Fv7|fsm~^8MxJ;j z^>2dqM6C1{g4P%z>4{QC za7XlxQfK1p5~oWT+ukv~&+cl-LASfoJ7;_K{G|6D!u3l~S+lq4Tpt!Kfv}F$z=%Hu z<|LkXQ%96pODcR2dvn>(#*)7!DR(`5VJOFSDLDF#uIHaiWgmYM@#Hs3F+~0EOXZrS zz1a8a`2WB7zQ5Tzn9}Ln=^L6E(;3=YTie<=(pl>}nK98>{WHCV?!V6Y|D*2QIfe(S zpC2J;+ro#L(hbPcT5E7z1Cd%tPKd55rn+LF( z9*QA?AvwZwb|%`1tZS7CMMFq6OGD_INi*UJrK5fhtG7eFYf4!aZBp++Y3W9S>uVeB z=)s=@^9IY!cL{hTHT4w9c6k-@w6*g3;$+kp0}4rN6pj}*e!UH$(fBg%%o@u3I6r>y zsP>=R0Y7#y2`wxmab=%TAK~Kh{&8#!#YApt{QmnF-=F{cUc&Mp+@OC0asS#+l2k0M zG)*ylc;8k>Tx4lsd7=WknrB_uWfWGn(swJ-mOZQm*PWafB3Ul~ARiOE7`_#b$Sg1n z*1&*BA;0UVBZxt#;1kcb{sq(i0SF7`7kDTC&6j|Hg_KKRPa$YVHS_c`XihbojOWv{ z{?@f}{1WZ^`S^tPv+&jlB#RvrfD#kL!PN}rj-6tl7LKeCIT|oR^bC<5+mN6TDPb=W zzM#NOQI#3DSGm~WWEH9h1KP$^JrLbH7#J;%BmAwigFp{hD!;s<(rilCMuxz39Y?cL z?e*QNQjCs10s*qAHj;*VJ`kW&3(Dv5k;;9l-Ipn@G;fnZ&6F4_TUJ1=(DA}ord76{ zkUq4o@ER=dD2jlG4(yB=kj8pBy2#~k)p5Gin4^e+hIoa%qE?oC*aRvYw0L)lfiQc^ zwAakNq?Zjbp)_pfvWiM-Td-fHP&-7Npc!jwDO-vlG0FB3r5m~9$N*oEsZyfjP%cKP zBrgG4S4B0H0i&RNhrLrZzS_^$4@Q=%JyIZ$qfo|iA>_60K#tbrIGJ3uQpa1LT1PhS zzz@&^MGn{kmDd~4GEHV(?evyOW39Y%n%i>$R10kI&eLPIvkN7R%s5iIRZIVIb}`h< z_jKlYXxlRGC-@F!4$EwB8LJL=d`C3r#Sl*QoOt#)(Qa+8*ocbwi@|X<*$V3EE6!@W z$s@hyGTp9+A*R=XatyN(1AmgrC?_(+uM7q52`jbV>Hk&>2(io!ZugH`HQMoZ>+zpb zu!=LNK!G<1@ejEH05i4b8ZP$=a~to-U!b1ol9)6z*T>d*CyweITKl`C>6BY3lPQXh zOd|pfURnr>H3&n7r5tqFvWyWU?oA#^pmt~|*3ClfuJ?HhSQjgF?UQS{R#{Z}n`S|A zND2_fo~X=>eSEE4OLZy9T((#^d(g}SW8l}o!b!+#Nb`tm5UxlQ@m!;L5#1m+iaE5P zX|0#9yOJiVaBJdhxQ=rbv~5`AgwvRJOMs6~*?1u;eLQM>f^|L9Tnl;elnM;`aiB z8SKC0s~TJbSl?us?K9~+MD{7$Tjj&z@%&xrt~Be!kk3T4&ZU#)MS;!P>ww4$GNpSO zW)!Sar&-2h4)Bh+KRIIxIIYB8%J)#pp)_i0!~f{nLX&La{USk^zocBAro}HLUBjP1 z4-*b}F{^!eL9^?obD_k6l{qr}v-TN_aaPo~&}Bl-gkUozV(<}c?iAF97A4Z&UmSO} zZ)?GbmBv&UV@8Zwm_u<)t6U~l5EpFIoyUompQ%eRF5VB}mQFE^$Ujqikb|GiCw{;? z@XISa>Wvw0M;&JO9=%U>b-bqDTXz8Em)%d@l4T&?0Nb0t8E%N%{gT*pir1Xo1>syH z2F^(B>KY3iTcYen5M$+ROg93KDupQ_Yti&oc>OY4p$H1UTyB|(CAX|5C(6|Yri>!I zBEK+QDpbz?_Jp{yjK}N?W`dTzKsY?^9Ve z<(Dr2EkR)cp@F4pe>S^@c&ww1$5yVf_??_$X&1^_@1YH2J%#iqVQfOJWb3E6+f`NI zdU@oAQEN{h=etUf0W&QdEML2oT4%qAaO)Fg6uM-qyR7|w)E+BTg~dDJGHdyIva0ag zy>^nXjIzoE3`lZPJ5Xi4k<`#4@%`RCd83IlZNEusgqji=Jd+8#^i=IZC@-3cq)x<{ z&Q~I+g7KkDr+t9doGDfdl)LjOe0aaElK)bt4JKnl(p_X(%hwb2jOE4P`9&X|`Ujia zqpHgx?B1vC!OZrH)mMP;=9l<~=KI1O9WS5l9>sgchC6c3fbWfQr|?myGNUk{71s=vZlg*KiLjmeSLJ(YA=~(T@EPM%K(;pn!O+4qvevqFw;+`KC2N zcJi%5L0F3L#na85MMD*My4wr1wfHnjn%6nf^tc#q8aETL4Y0nc7OvZgQ!mk?UC19#s;X=njHD@$6u z-Y;-eMb>)C0G%VEsmYM^G`!xBuE~h0N%&p6d&^3y+6+Fwmp~~1*i4SDR^Mw9{UI`N z-3OdYYBmF28TlbX58E9UaSwAAzh@|BmJ{B~KQ+pxF9C)H-x*vqaQ__z{5zS${2!oz z|J^I(|2R~tS-N2>WBABEGLE@8nvWG*vubJpTh~)qCFt~Strv>Xn-iE*i9<84NhO%G zap}9THOe8@x`~1a(dhI-R1rdv6H`!F%ijV)guBM^jqlUl-rlz4Uvn^}Z5Gq4J>MA4 za5x@iUVHaUymWu}=jNKp0-B9v6KsWXO(6)330d_L;Pqh)l-*q*@B+(Os?`|aAxPY_ zfz3&vx=NZl7HoxonwSH2_zSwmO^(;Y4zAk|T>nxZ+*Qw4zMF?&af8}+R8jwuuJ!D^ z#!a0e%IrlHnCgW-#CAAY;IL#!fIaY?wF9-g?#3N>y%UDe9dR8b7ejVfUSf3L7P!J~n#WSBE`#3jI9Ms=(;X?z6p8;7K^HXjGS!g!W!rR+_1!cmFCWQlpXkbSHH zn22ig2kOC*UTd?lnUTaT%|d&_2zadaZ$o0-wticn8?UH9OU=4x%gL$muV@}9KqdgA=)#ovJ8;6=71ij`e^tJFa8)11Y*&W6T z^SZk1MOd{(ekRmfZ_X!^DW)|lwBHL<_VIS*9K2zgSZ1c_PuCUGzhDs( zS5fAww^?CnSLzGoGAEo*{PAF%*p;JAVhK@HDt0wd0d1dDu#Y>KDTZIrUZ%lVYtf*1 z{8MZFa7>K6jf>$qVM?ZgMW3j_$c~xx0}s{sr1f5Vm=|L>>Q0*CxVfm|k)SP=fBU#o2z zlu(lwH^&omU$w9=(GU!qQFji~nolDFas;z3a%_duv>po*?v&V(3Kd-%_Z`UD8MiIT z;?O*2xtiSA&X{ddESefvDldr`a+pc3BTn%pN;(GjN5o`SVoa(JQCif+qOy=ZJ~ft{#!_cu(` zw+i*9bHm)^nU>?knC&QT&753aiy(srQwL%{+Js^j6O%fcbS%zyp*>N9Be8G+XJ`H_FNUb9dzsY4j8~Q{vs>u#nQ(f zzSQ3c>j0@v4ZBr}WdCl-K|IFC6l$u}N>`v@xfKkw#2AlMoOGfhywpSY#B7!G2!Mt4W{3s2@ezZq(v6=$NTa>oLP&XwTm%OlQ z{@Nx9VvV*VH&ts{N*p(!gMD$yL$QPI%%r)S0~Mlzfc)PqCxKV> ziLQ5Lj+XBJ6e=UwEN#dP0`!`usKV34vs`;enG{4MD>F;Wlp&+jj_WRo86#u*2~9oS zVG2Oywekysb%VpWe|o#!#VVO#XBB;L7HA;{8{bOyG$t@uQ`N3@*M6outqnOhnGBe= z>s4g<&oXFeqGWy_&^r1&kR~xb(2=QkHF5y-(U`^PEzoowoc)yquQo8AD8Dc_CQeAG zsI0|I{(*VZ@rOh9wSN+XgDb~V&7opc1MqpRj!&3f<4-IKXXFu|#|+f|U(HDR2@$zN z8Sncyhr%I?e@Vl)wD48#2Q5}5`11mr+MS;2QUcHR_HWpv@eyjc!taV1KxX*4rpp>e zXNYiiIGeTK;Vwi_xKQT}M1w<=jtR%)v6}6l5-C-0pMGjx=5LR3v^fGAuk;gT^Bc)D z*rMwf5+ELCJsh*sO`07u`$Xu{mnVzMWQX!C9T0uo)Ry4^L8+rLB@=>c$LazWxkcJX9? z-52*!(%ph|gP5dv=yn7zYv+04xYD%$p;s1M&oG`<`x+;~KPUR?^r%y(v&RHP8$ z9X1-kKT>KI@n{yAS71RYq&H4PJ=c2TUhidU^(eJFdNWh9T>rI>6c&~5;$B8dC?8Jm zh<+|zU7xsrU5tmlVNB};a*ybSsF^FN*+c5Ab{nB+`t5EPVj%KDoAU$t&6!d)kYb;- zo@O_7#XUt(2TvZcnl!ft8-e0FkrVTwP)3?8Rd!}_ z^_M`IFO8TfOZJ$BUh8RPu(^jJ010Qu7NI!8)KLaER3nU;4mYb;0CZ*58N29q*naT{ z*)2-r#kJWM`3tXfn6D1u>n@T+nlniEe0Qb&*`W~+eB&lL%-Js*P0U@(;c7QhoHmX- zrE4l`40`^BZT%~Dnk!YdkyBoQpX_KZ%-zWVHw!&@T9E8=jzOC<&b*i)3s`$$JUunQ z4}yqzT%Lv!np}t*3Nc1tumHjTP(Jkzwg<4uudxdj&skZL&CV4sIx;NB5OmVuk01eU32Mu(cRZb3T9CO2CG(6CEC2Fpr>Dmj#TWojuwPDNh#S+S>daGLNfW4e588Cu5+Gg(TDVFRFb!_oN6$sjMTfu`Skj zQJAwymB5U}m!>_~^GWi{@cyJE%GPNcWm=AlC4+%(MtBjV$m*;fqCx1Ehd+~6$WE{8 zb}y53nfUxMb`RT5{m(T?T^#J9qPX)Y;uFGsa;X*^vsgX;I>smXNHChWFyOz(ru_s5 zFJI-)CA$Afuj<#gcI|xMA}z$Oc7wXMG3be;piz-3*QGoXl-) z{+FamVS*OqyK@SQ35;RqwyjEVQ1oi3Dj}};#3aPG|6M|MDACC^>db<)yZ5>_PVM;z zp58Uypuz@j;1mL@x9leG@kWN?!;Ob4ydK>C)QO-klsybFL+T)cpeTOhfsOnLKjl~N zmY&`^Ox5`~Jj|1HTt}W*CwKQvMahF2lU1 zmpaL;>Pm;v)C8Wa?;sGxq5A|0UUgOH9keOI3gJjp z^3qf}5oIu|R{j{8#tT_v$3qm#lYr{U<$Z z+k5hs<{neL&(w1|pTu*6qnfi5nUs7}KXK;S3Ly00Sbm}<;w%F*LLt?FU$4bw2_!1O zON*1Rt2d)G1}iK&mWu^YQh68{jfm-PrujHH{IJgX5nhCg(&QqoCB;|X!2jTncYebv zCx1Wvy>IE!|9u27{s*(@zvj>X7Sc7TuDLE6q4b>mtHNs943&vB>(6-{+l!jtex9))f0ag9pi-5<)^-}oyk>hnI?0ttF^JKzk z{+iYZc|4oF@zVU(aqil4-SPMOCE`adI;{u+9Nlm(7~JiR0*t^n%MlXRIXOVZu(PXt z);Tej1?t zgW?`juFp(|+Nmr{p*kes0-ZBFJQZuvn5RxX?oGUrpa~@@lAuDuP?|nR=|L?Lo4SMB zAA2wzoKeA_)65CNnqO@#mKjmlP7bHWe3RrcA}pWa7>U9XdyPFU;Pgsysi2Efjodvs zL?5O*3FKT`E#tS_#-O>Dw9j>-C+Zxz1$qZ;^_dRojj{(|(TT#Cizrhby3|vfTQ60> zfOVp;Sy-=++fZ+OA6 z)||>Dh64ecnuh#UlIkp}`1nVC8{TE}6kSmf;wSmzxTT@`(rRhh8etfm+Rxc|F_9(v z-yyc_JDwy3+DmunDeP0ib=&Q&%#8kjD2hxAQxcs8l^9F=g&a4184iR~xVzIyRK!U16NceNntzZ+W zhQNe7-nmkQhKNPn>3bS;zlvxRjA(k2R5Vg+i!|fwV&#wRer=#dfPkMzuR!MCMIlPG zClFH6Z4+U-Ur^;HVr$Vr$}E|+6FonqYX$t2{Y5acelCNWS|jN36oRbs zgEb+a`b7abA)b=f2aU3(ugVyKZ&3Bh5IzNv^QVgiizN>e6Y>aoKsupuJJrHO2bB)Izca%H#x)><0JYdbP|7mo@^SDNu$nCb9hTCnon7*~X|N>a z2IJ3r{Cuuzf)2?Grx%1X^bIb*p@Z8f`(=YVy$$Dze}*}MSQJOxoG#s^QQI^vX@Ej9 zEER^V7Ur8j*h8mDm`pgK4O=`lsv1vDzg3=j1)-mWBT#9OJY3m9R{w*EXJa#5ods!t z_5BYIpvC}j{0cTiX-Osm@kKKWDo7s&8s+J?1)Cv7=1jOKwiVoY-|SE(x|JN8>Arqg zwq>N!m9$^lvex23)4g>5sALOOp>xiDwz;p__5H*8UfGtCN>|qR6-zB19bOeJQ%rd! zb!V54S+narfRct>;BLTe^X^ZN2XQc`9NXEf?A#^l6MuUE(Ra7fCw=&9L6^&NyX9(2 zwZ(wyCaTLJUz!Qu)g-?CA-;e^zP<6B2d4>V>R$Qn?qqI&X?^a9SHPp&?`Z>o>@(O9 zbOq=*HqT1Ksps&Jw=uCqAaATSF%<%?=Hni^Sfl*y=Y_pztH1JD2m|cl$*-%UhBQI? zjE6N6cydsskQu1wORy;*>%Q$9^yE(qgJ}v>dQp2yeFe!8MrDR^j{&w<+Z6w3I;5wH z;mm!Q*X!zaP&_8wy0*BeDZKqblbBj+xSs(k{n)wj;hwl6||W_;@2}a-4SCA*$#X3QR-}5vcX7)r<@l z)8B+^KL~pji*-vMn41Mm&N2S_9+px*SJFgO{nW+C%$8SnE~Fkc?30 zS8YyErzYsttB=6Kb1JUyL# z`qV|Y{X7&gUDeJBaVpf$apBC;@dFP%?IHBLUx_@o?K)uDoVquuF(Y#0dGbI^|S zdeu2*T_;TwHqOn_)AjLkV~bYMLFLbUhM^o27|$AGK)fp}sGup}k3pOKI>Hs@b}hsy z1v{y@qXqxDx7=-c{j^=rPAh7bt$hQf(?Z!&X^zgmjXbRF?W06NDhD4EWkb+v)g0Bj_K)0^bx zo{KP>m8?==g+4YiCTFf?>R@89xfH|3+jc-vjALaWgt$kYzWbdlq3fqW;jXwOycVHu z*c8bK2~ZkQmmUgQisbOPgL#)(V)%WRuAz=Kyt@O`6Fa0ty+%vq0bgz5|W-%;wn zE9U-_43>YKQ@-7+#@~hy!~gN9Qlz*pgDj7tUDA^0ti<0dDGw0lDqw`r=`9azjE!t2 z$y*ik!XL1+3Yi2gVG8x}_uc7`9RGVUYmYGx7&x8^Hl>>f-z&LNt47@@ zz%Mx$E*g#{cZ2P72E=26R|uKxn2W9o#`OQ)4+?ug}_Q z;t?$v&O8EvNt7<_4WnD(X7kXtf79DCSr2e=c33)?`1v80UA*E>Pc%5}2sI|Hs9{Et zOp(2bDE%WotIQ+M_Krf*?Bq@Qx{t(gD3+dh!5n@8GF+(vwxwE{j@q6nmY#5*(?+b7 z;++O#6Fq4z8V)0?A6pPj@RRQ|TK}D&bsNZB$l|1V>O7cdcSSIyqpupSz;})ShFUX1 z#i(m1LNQzR#~&$G<90^fEUFYTQ`5iwUhcm)h=SL_=`P@D%r$ZTKg!-QND?($8|^N1 zm+dawwr$&8wry9IZQJUyZQHhOf3;`MxpQXjcTemakr|PZKUch3&w9X7RNVT#%07!v z9X`qW1zbQzT1C7Q_l5_{YZ@}|bT)(HV!$d9`~~;1>ZQ+djEDMs-CDaOCu>6%u%Q7| zWCKQj)Gv$D3%^23mAWHceL6JTLO>`c0K2>!-yRS^_>6ZCta<{eXMcUhzBAt}XuTIZ z!j3R6BU-x5ls~t@BwAVnXn35CM>KH9?*MQ^>H1jZhU$(8+r*ZVOXY3kQ$Y&GO!ei8 z7KaMOOd%JU(MUHcn(l#;mv{+&-NMC+ikM;QqiH_M<^YD**n;-GYtLb0v3C@<1}Q7| z#vsmSnr0sUjMaba0vpfAjij$#@cc!H`d6>^pHn`;ztO9GxhYyn>Dv5{mhHd(5wdcy zbNy$}UZA*aHTxxlLTt6&NhP$L1=6K}`!X~mv0ToC}7)nYGO~dhaB)ai}bkoVa@09BKXF zGNs1Q+jWsT`PyU3-krE=(|ca&((^u{utD?D*E$*v#oq8cpV<5paIzA)r41rHPXlt< z5Qv<#S&PN7qyr|QKPNNPu|}N0ypGi!Z7COJtZS{|qLFTgZlqBu6wzcn>WQhiZz|TG zJVHQnwL#Cx$$h^=3UnO3g3OoZEO3$&KLQQ$)a#>eCR(WQ>Q7}3HIp_G>4I3mf_|4| zb)>daO{GTtHf^=fw0ZcWW(Yl*Z`~&{+}EDeM3w0ez!7+{x_BGlo7U9-hi=)Iam}b0 zE09he6Os*i@{#1F66#>u2*Wl8snP2UIPPGrCP3z(D(3xh;M&@i5;#sPo{NvZB1%E3 z|D6`MLSh`isJ{Q1&?D4hKjQ#TL`#7MvS&A=fFyUEl0({yd9EIxGnHPZ2-`*ewOSPu zVY5Ag&2AZu_S}X1EAyk3W|E7RfZFpgQf0nRi$93M9hf5N?aiCO=9A;(VDfwN2uhAL z#fC(O^GS#I+59jL8k-AN%RE^&mW0-cl?a;Be%C9KAQs2AA9(|-eT!Dh^vbvm7_#{u zCSYU{uXeL;JqF>en}{p4?*dL@LJe1I+R|+(9eQyW*T)oLPMh=bj}@)LeX+0ewW7a& z`D^`uujs#%bt+(OW#(wC>tHBir)ywp_}>|A^Iwiyzf_PvDyh^O+G@-=BI}%JK_Oy( z%cbVmC1&tPXXw~i=>G}|DEyPS@UTKrQLEl;l`RD>YXVGF1&F^B%5mhd4C-ODGhrX+ z1@MlTqiKTzREoN;@+7^l;*PJ@6V7Z;o^oKGeYxBnFV^iRoF|$O)7>8f7c)JvyXIZi zq8hh)k(&@$hPJcQH;zc|;n_UqV4?H82&3cusf+YuF&_1SgqN39wm*go#Bd7t+-IXG zqGJ`+VG=P5iF)yHEO_{bhPuf_7NXGC6eHE1Z;aS56WefZw|BYM@MSl6rns8So4jSS z3!UZDrgIAuv7=zv8e*_7;lTPT90sOmCW4KO9DQqIE}BNqr6i9+$iCb9ILNbLML3|M zvq#izYs%oy%sOV93U(nj#>PWEV3@Ykq+!gT>srpu5oIS#jlqvI@3s9ovLy}=?|RT4 z#f~zY#n8}pN>C}w1`Tb%UhPiU{1kW#Pp1+AcE#P7d2N{v53lBP1TRi`f?)H zL{w8#TA&*{%I(sos)#ss64|i$P0oY7q+Sm6-TTpkKg+4&YFioLs_DG*?2{mzibhYQ zpTgiK07zVNqg{+75Tw5W3 zQXEzly_e4Dj@nc5Ah%=dbth9cg+{jk%X0xfxT0MCH{8(WZLS9=4aNKtqHf#^0ly2P%asF-W*G7Lcb0}P6~ZqL%)*Pc*`6kP7gS-aS4@5o6|}SnOf=O zRN@3v4kQ^z-r;qS0sYE4!!voTH1yI-IIM_A(|C{!ZB|fudB&9UuNpxXYKnHMnyLB=&sL`Q(*2Y>w;<34A?4#e3M^-h&^X+N z3gg7=*4G2OGAKU?HvJqPT_hrID!QO!Dl12iTy;zl4A-=_GENN)hP7(E z9b(t8xRNN6!nV(2!BH?6EVSE~$e3nX&(trl(JjVKt>B((<;_-c>!DAbMnq|p3R-X> z&jcckI4s1Toj>yTp_Y{C)3ylJHTCER-*4!fZ9I=PscIKGy2=lEoAN1PIhAd;%XI7w zo*R2_prWVcNg3m@w2DV6VsdBr&A^c4-Ip+C#_4ev)s5 zHu7zePl(G-KCdQ?v0QIw1Uf{tbu}TJ37Tv#jif}%yF6>GuhGIzW3mOt9lRS6?$tWP$XdBIubsf&pfBP7LcxelFcHlx)TVrMGh zTH~!&1aR^Xtt$Jh`I;;Hco=stnm5~Ftw4SVKT|xnk56Xb4GVSAJ72?~3JxKo;`?CsEhcHI!t|D#i+^jg`6CU&;Lz(}3AmI5)H`l7pv6D)X90ER&_!TdPvu zlSMDHkfX4d)f3mS0R}3K6`)0t1&+-VhnDT&T6z%}0o9wgCq=A2VQA9xuANh=c$v4W zC&x?|kt!FyFJ)qz1Nd*(AU-O@aI9x5b85|NpW;`Mt1P-KBljGR(fl>}^xYEe^^U1=dj4!fDfux6Uv`m&BFKyuw3QOYYI- z$EQ!vw{M463Xz@Nu5IBs+sK+-o!3Ag{y2~{Uic%|3~~`!VNy?lCIdA6%x~fjTZ_3r zJCXfen1d2KWNnn0-J5;(Ppzy$-odv| zMUqx>12A}ye-Js;P^)M&ss>x(@IQXE{c43H=J%2!lJ=^|Oza4Kq=j*;+eLe~<_|9R zKf*5<@l!1pm0w??f()L+mM5aV*Un97QG_LfE$u^Zv}-p(`Wi9L$pgyz2wZqJ6Z53j zg0$t4m+&sSwdK7Wf?KCVN)c>rIr2K=3|DAi^nDb+5#am7Mwj;R>CRLVgU}IKQM$M) zo^`_kmX)yKsGe{)7h2Z&@ILDAJV9Qs@K)M3#{s~fpnvs!HuPwstzRg|#=m8{{%7C! zcV>M5qW=q9+kF8X|9s=NtAKl?8KQskjAwY5)<#;5qFJn2u2fo3fUeN3+@oQw^EFml z1nMq$STfA!6CW=vMVr$KcH@OwY|WKO?%R-Z3G3pL;*;-uC&dpYA;osdJvz8;+e~5< zQ~2{X_uJdE^U-tT&?}2V2HSOu)(3RYafd*9?W9j+z3GdgLOP($lDOrBdU+AOuU~T( zx4&EC!JjBIQnMNH#dWLk7>MAoD2BRr^Yr?^Tii@Qq${5on zQFdu=ZDwk^;URYZe4MHR6(Mw$`DY_Y8Gg5k^?a%UC+2wtfy*!bX+e54sY*!UANNqD zOjuMulpv-$O6}8?h-m}WVnHpm*QYlAI4N=HDno2El~(BYkBm{g@@ig!TklKh{SmR$ zyk06Olgd6@Otz7Fc;ThRmK@j#$h}ZC_`{R>z520l=e?USjA2ajL?cd#;^!;N@imHL z@4yObP~P?)f?q+M1y=V88f5jbkmYuZWL@rV7o}G0@N%#k|HeX491Zpq`CO55hn>;4OI&>0 z#ZRRjjb-k36&Yp=Z~(!M!M;;QhNiswf}t!lac>Mc@PwBGofA2GBpKBx>XctB48}%d z)L@*e5|ud$Z4hyqWJ9=Rr1lC;TN!F+G|X3bws>~x_K{=_*Hm(r50CCww5 z!O#Olk!_*I;>ryeWeimTq?IH;2r!FINyaZZ9Teuq`bmMSi?OAQ8j%Qo^`Xb8TKH(S z`)=uU)&(MlACHFf18BARo(v{-pj^!5RoDidQ;|+=XlF2>kKg3A6W2GZg5*=u*^A_t zjWZcyxq#z)Qg!`^^PldZ)@+ND609YcN2<)BLF4!$0hN`++Rw3UMl7M0z$Heuc9G3t zBNQ|-cmA`+?r344W~9yvRxOB0_-x88xklcrDKTbRmw0&B__{y^Ph zOvDu^CGOXx(@3OIQv8|m#W8ci=9&3}{R`8DuQ%#C7Xar5RwPr8AM%tWNWb`o{>%_T zYaa`R*pd}24G>ix16{usdn+%;vS-MZ@$4QDx$yl=yp>1w*^nx^~G>s0~21l(X&Z z5@<7!4>;0jz5o7&)pNWc`5z#O_Fe`yy_~mA!A1RSq_Ws)!gvfqyZ!l7d+|zyZeQl9 z7SOp>g&DYOU3EnGjqwfI+T^Jf?E$u}WIO9A2|%FtEH|B9I_ z(;4l|&;;7m{*O3eX*;%|ikP6f@>iua=F|1`hJ-lv;^eYBouZSHA8h{aI&m9_d*t!U zSPItMIhJ;)(nrIF*GpU92KhwzVQn)LtfGgzl2#j7PX?Qf?>^5alw%rwrB~`I3M%l& zQo_-5hD;|RsOH^!Xp4Kp-Q%Kxp9m8$emYKX}uo0dn5sA4{7z1DLP56~Ou~jt~ z4&%ZpjH`~4!mW2d6joN$2l~YrjJ6AxvdM*WW(tQfuQt!BrI|j_?$sSa2lZ`lJ=C#{ z>y3Oc2)YGxt={Gtt_-dYPR5|snR0BmRyse}E)gx|SZuwK)pNw;y3_|Wp5z3O z5&fRbgitwl+7`6`9yW3X`2oR}=P7&+?eN6fJ>{Y_gP+fQFq{9*vRTWD*+I_QhGk@~oR zDF5B;QhuaO{vrV6njp#oDhp7t4$T~8JH_yiwyEjdJZ$ia8=dEv7Zz<4&V8!|$IQ?LNv+V(3`8+LH`!o8REK4_bG^CX9PIo^ z_j}C4WYL4Sl5eQ{ML*l1SY%luy(*v4P{3{};kc4$HjAMgC#W0 zcb}hIpv7msUk{0zlB{&1`|a1Seb!{=A>Q>Qc&r8o2hH@Pr4$JdW9^*?*AT7dzQ+Ti z4nmr0jwBaWn(NjZ1b4d-*h3|kM4rB3%2&EOYxpkv zDD1Y&$FqL@+>*Ej(Zc&tB1Mv>n%NnVQ%9D>Qq&E?E4PVV5gEO315OVoWM3n4LLO_5 zeNhGsrl-2>njijIdCvQf7!h0!%W#_@%nZA7w8rAVGEkSEhHdDHa~8I=s4Z3Oav5EL zLquIV_BlpT3R(o`D5mPxO==q|Or&dPCTy1Fl!@t@l+=y9W5Gw_aoTss~-$`KlNF^-IOI zpLAsOUHL=tEHDBlGAFjz%BzB-{#w<%4#5%@@Rli1jDOY-N*ptbdva5|Hv5=eyml#C zODCrZv;^F_Ni_!vF_mKEzIC*oh;jbyfK;)QtG_q%pj$pl+nQGXJ9B7Yy>{oL?b91} z=c11Dw_2(8hpvLBW{SvP1NiJNTP7On`j<@}3UnIkp_`VmMPQ(^QZ8V|b7qMcRhZ^r z^?@Hf0;~#fD#I6)Jp`<+4MSB4F7HC2JA8u}5)oB>#@LVgnVQr{ydjrxW{}CbR%l_X z&M&M#GdGX-@3A|XL+uHrDaoa^`%>O=Z`G=2-srb>A^zkx$+1VlQ9hgb@ zs8&qC*^e}(0d99w@=&q_KT5z=WErdq4VwbhZGTY>da>g;EBpeOfC`%;!_2C43S+qd z*sn1iw?SLLXlDCeBA9m^TR=oehj@focUBKzbuOq96&9zDUS78LY=1O9e}k2+)YTZ_AY6)M1o9ExkMMsT)YDmUYR0qMz6Iq zZ~V}<@7fVC)`w`t6mZVF*wQUj@`Bx5s9ON59yxukC(WFc`Rkm-bGNFpBCRf}#fKiJ*2$Hk+3yTG)dq#R_c;m*1|Dj&pC|y<5z#Y8jIgPul^|sb^rr4 z{sZ~#8^Ql-WBPY6!~d6Y$v>NdFU_kxq9Kx3gP2pAgL}>&G|^EZ39-1TDP`boa%M%p zcHWV8T#Go%TE;K_Ur)d78~%i7|Frc`cpigCHzYZ^?A1&Z`)<}%Ue+7r$*mRt$T(Sw z^yaARB-^F^gzH4>^KMoa%D21j2VJ&U?sDFl(Rr_GHvy<#J&v7T(t%W)Z$AUI#mfi! zZA77hJX!tn^c*F-ZFL>^O{AWtLgOH$$y^k=O~IqHi6KFIvB!@4bLHZ3qcoat0aSdc z2~)H&@!9$J4hut=(QxPuXUE0d6c5vN36mOM%C4%U8sO=4HChLbRQkKMVC|amu+?L; zAT?TvRzgAld$b44m@Vu&dO*N}Zf0cSZ5+T;G;2(5hTEdxehq$|xxa(lA*qHq2bR)P z;zWmB_sV2}Je6pc94y}TP#rw&ls^TIw!NU-5~)_1y4QoKX;Lu*F&;BL*(RPa?sF{f zG+k>)v?L%>tv9pg?2WrjlQE!Ow^t5`@r~B z&=w)Vu@gjQgHn}JeO14dfW3Dn6Nv~C-QVu9PEJqC-Jk1TNeSV}By9$g;SNFajWYg;U!mD)}oSwo`0y4Y6X5UHgbD#DOk2ZH##yqF>=0=flhHUzh*yU z4Y?#;dVjcIdMGCZIprU@hK2FAN(g0Sce;GNvZm}WIrQE9dB}Tx{I~)N@ck~)ZjXeT zlBivi!GY>-L!IRjk$wzkZh!1B`!R}}m*q`~N&Ewf_yf_j*KqzUpWh)FH<4ZqHQ`vB z94R}S4JfGnDjAN0$@7rhuRwtYCR3y_yM%=~qgKaHnpArKNSK(3zSsixU$OZp*Ea}C z(Jh?Ma7H}+jwCxTGn2EmZaJ9}C*C}*FHf5KTs%}1Pvd4=IIF{I)lsYzZ(R<0(1Z1B z=YTYlct8);ZFGk-(xUAh+YX3G_^i_T> z9XrPstH#eohKvv;7H0WXs+Z1_2mJa#FK5!WtFTLI&B_d{91a_*HQuyj4)y_R7EzYZ zcMhb?AouHq`8HVAP+?4c=16<*@EhqcF_)D`0Dw=dv2N5QAJdYV(LgkFsza3M>1`|fLdtPU&?lfPaxI1fp z$LVK|(i=jil3cO=#v# zu7JKM+~!N{B$ceYmC_7Dhq8&h)$%|Fg}O2I$T%b*)x#t@$P1rkl^KPcYYJ|(0l(a_ z)a>Sv1{9)I53E=i0ov}KAiRMs4I(haAYzzOuzQXUvFOiLb__3&V)E394^0rA$T<%8 z6tAv5`;PjB@-KBEWwMApL02GJ|tIG8ySHsB#ZE(Dq(Q|e*Yy3A~k<~kbl z?!RMj*`Qq|!EII+7)AgeKn$`m?g9g~i8pu+*=P%}i4FCp?ScUxC;21NvPc!My4I~(8A$3M8O8cV;H`o9`k@Q){PWyIR%3vGMB&rXx5j-(`VL-O&a$^9k^ep2r2&bez2#9Tqgi}CA1L}0s z=^%;oWAjFuI3kM3xKiQm!n5UY18u`li^5@&iWjZ!u1C((fNP1;#mUOD@cde$xe|KW za#`p109Vu;@|+W!juB~5+`B0yZ`@CvZ^1voys>pj5qm`Ig04~j0@sMsso873hQ&u; z-+z_oKf$%X<2d-=UYh^Ij);)%zo*E*zj#A%pOzZx#X*XFBRt6U;_iVcgco*YB|Pu+~HHQry~e0&7K*jVsb9QB?WbeIMd z33$_c0AZ|z4RqkV$`B3Rq9d0zaInX|oOQcq2*P2pP$?ZdyzIwD;yY=~+pgouqO}97 zQ6~+ij4+bMp=su3acno=y1vW`NT$~!c8|TH^cJ1Pddx|ZpRfG&?M6W6KgNeBfSq;F z&;|p1^NHg~(On{-&2D2ZGIS3+1{&}aKEEmQ-+&ppI-{4cN1_fIK^g0BY_tX@xz}B(9H_uSl$}A zV;p>jw`qw@#(+OVwh?0Ik#I`5e_4)}K+5d=V|^b&x#K#24VNGOSJDvM-=ItUo4eir zOc?x2BLYkZ=UK8^sa$q{AhV>6k^d7`TM2HCAC>bCMPRAWAdW~Z>4O>eop{N zjwP+Q?K8_*VJ5nH5vI<130Lxo;4s`G@3CL=#JQc`7Q26P*WE#0=T1`%f# znJ#uh_{8r>Cp?C`szrGwIYf#JU~w?|2Skkm#21MR^Fb$TCR%dK^9{Ugi~S=(si z^{akNUse9s3G$zW6t2Hf;s1M>k}U6Jv(fwG-XqkO?S3sHc~F(C9_714aQU?0#ItOg?EoDtzE>& zaee!t-}u{Md=*ZmCep#j??l`Y+23C}^fka>KYLgjfp~i9CW!FN0L^3Q)cL=~ly-8& zn38_}bsUno~GfOhp+? zX9^v1;)nB1!76;GW{9OAq{LQY17?)@tVkM%qlYEao588T`d3=2i@|D!mHV=5kWAy^ zYeGZ)AWzt^orSpE-nOrkUL%Ft-z2`7UE2d6?nX!H zV`BdLHG3@v9Aw)^fC!w`Qv~gDo$@X8O3jqJXjd7SZ;d!^b^ij3{=F@d22JxhmoW%x zEre$HM(amq&-#pqTB^Ijqc-|FN#1LLEAOC6z?eV1tEd$>=GSCNaZnC;)JBx}apZ`O z?W&mZH}XuB#4VF4Am5eW%1bNNdML(P{5GFa=GaAjkbynYlvI4RBpG?rv}mTaMI3gVGfG5+GYH~i(@+0hCOb4*tgx*JuKnEwDx7u^r|X~ zNN?f?bcc<%<^f5k861G053>7CaNbBTg|`J^-$h{5p*lWzYnYZ+}CEd~0@?xi*!vqz3Ku~U~s z_MpQqCB?hP5;|~^xc8ro9;BLVEYEplt9EA%Q1y_Y-E8pW7Y!MOB_r-V35*ScCnqyg z3?xd2gkdB^(eAl^E?#5R3W;%&$4@B6R4M38)?$QbiVADuMg6bL6T`2{2FEdF3nH1r z-$e%P4dStvPV>u)^SaqoK77VvXu}U5!RW+tBEPj_c$X5mB)n<$fsH0 zob}#qUlubT)k4HP>Q2#G{bQ+EjZm)dRt!q|pYG`e;1t|YEEU~_YtnXxO)f!J*drN~ zMYrs7k|(>Rlcc=J7uMs{3J$G|5ZI%|aFMz$0o9R+P^MOmG7vX!4i|n|sHsHQ&@V2= z^tBklL}<#KGN-5pbYmM!B1LeY48^>kKKc~sNcw=06ZC*&j0THvc{RbN@g77{HCDHiqe>rNA!4p3=m-Nlh{GdwhmGAT`9 z_r%n~?SOjw5Z0UTr-5tla(%n~Lr!5F*rrJ9V#Mi*xLEE?xoGoZX z>zyECFT(MtYeYor?IL0?VkwFhNsC@5-FG=?)btR!-HkeNiQTp%0ppgrY3qWShdv4- z2!Lu$p#ax+J(i{dhh51xqGN|>(YX+ur5MS<^rfw)QIn=UE<;^tXycjwd0fjQ|AFlwZE@o2d92!Gx0_ZTN*p#c{SC9uKJrIk)mc?_#-1P6nVIo~n(v~(c zj@tRg`qh^cO&i9^j$6no!Jgs^b$cF=;lIU@?raKUe|k`FMUC^9cdK79jcjId&gH1q za1HjyUMWqsjeBuV{^`0J6P^HU2TgRa)fDT2tmG1;kw z3anb zrA9jx(iYuVqX~F~(%WL3bDGfG3X@4eTPlLtK3)Xk)Ww*JGoOHEe*op;wRw?$Tqvu; zLMRJ+;&!PjI6RwH-VyVAOniF`a^kKZ{8$>HbxEu)$K{1j2!*VlQ@TG4(eDxo8j?*2 z%?bD{k=RcL%|%(}7*-nyq1NH&a(%WLulj0<82WVqbotb|$Z+(A==z{`Jdi$weg!fI zG6;!v1vcGqOjY3@<-=WnfQ$so%J?a+RI!GQ! zliBTQ9d~+1i~{fSqHOkh2)}8KN6mBO74>UdO++cS`{n9VvM->NV07zAN0Qmxkm(5t zukkzHDOauu-&s#C4{nXrhsJ|wCC%`=8oluWt-Vu!hL&b45vTYHuP2s>>L%D^FG45kZ2g$N7_$Ss(lDLBQWs()2mKW(JD8UxY%PEwM7A=yd2a?1{dk!zD>OmC*dd`+u`Yzuk ztuiKznSj1EYy_9q1=o6hTC$w)VH3alSi~)@c%TgZL6)&Lmk^pZE-Q_Ea}t^=4I)6L zc&&`J>jO9IPtcPe^3@A`{?4c_Vhyee^A*{u6mKJ~_q`2OR-+2RfSeEGgyGwK+;1j4 z6cf-rLbv7vJmWB*0q}zE;GvfJ7|bgX;--WE&nzIWR7Xn7;Ii8$=b1oPv_tLOwlG|Y z#O1{PC5;Ouv`sS462|>|?qig>W4!f#)=jLtMNm#h;h|zyh_X<)Uj(XZs7NZ%ph319 zo=cioBhD)0W@=19@YJ`4umSFQ_n?NLfsboZxo1xMm3U+JB!);NHK%|0D7ZKoQL3;X zH=GI$w@?EPlR$P=RDFIEgm1z%Y}OFIMGEaajsd)NJ<@dEL%QBmc;LLdv7Ww| z+M7qa-h;DiJdxg4jYnA{szGYXKh!7@LDu$$3qU&4%opi-9w~q?vOiZw1kF?Y`r^6m zII<;6;*2}#4Y}EzDHMK)?qVB?SMg>sEDTG=qqzvDutc$ADqZiS=<$Ah7|{1JrHsg; zs4<3?iuRK#hm0#WYl|^v4R7xrDPlv zR-k-(4w`j;)`br>#%0gVuGq#<^sf;if}+NuM$ssS&JRM~@DBqphE2H9QgMV*BMsHR z9h&p?bLK`@j2|nd&6Y9eC589NXNqB5OoFqG)O$QYBibm%&V@{X#tQW&OuKof{B|{S zl5#EOAiI@GbZwrRoyZ;Qk9Xw`tw*4o=2tCA(2Gz8M6C2^8WC-#pFy)N|FWxLnQ9e$ z&?^kVPH;}5RWOblYT{-Ylg`>$KCO*^q0HkREtzDSGX}k9OL|Ec@gz6SnT%kVB9ZxM zVZe4#D@6Kkg8iW^#m zj_=&>!TYa=u+pbHNB);$|Hr>+mj3f0%=tIk1#w+{Yduq0J41bID+ANNbmoS3|BX0g zC~EwrRQf2aSg)x>nGPo1D6^6b}ce4cy`b7m!n<8gEOlpPX0 z-G{RkMW2a|0pe$R+&huZ#&O88**t#9!{hZGZBP^E#YT$;^cS<0YLn?Mismn&cnbsC z+$clHMyhan)-+DizF%_kF>MpFm8HcO*Nzt~0f%Kq3W3#&dt&-CkOrhKdsN`ql#o1f z)0hIxrbA7%1GMYY7vPUdQXRnoRXt28qR0^bHopP%u3flm8@Q4DO-*CbDJtfEc)tre zC)LMOgSD^Kc~gB$Z;pwh^0^xm(6MlVN#!8%n$uuiFd=8g?)n;NrSUY(v;;Zv?h+>G zE)BiwR{l668EO$qoLCAm3!xzb1L`z1vsJ}-s{E80)^10=O4MU$uqCjbrgZN_Hm{_l zi=+5?WUHZ0!|+XunIJR$>B2c!edAyvdu^i!LHrj(u6jv#EL>+@!vi);#5X4CSIj)hj@@x%CR z&S7Q9KOQ?5Dg=LQ;D-$Oq&CUS2?|+>bHTAW*Vm}ifvF*=Fv16|7&P+P1a2UuZ6qst zcUIEzav-NOqQBf66_K$C%}~mVnoF4)K$a_R@R!y_+@V^Aepjz`fM4n|RmUPYwEf{f zrSAkIV3}M5l9uavMM7UC(y^_2Od((ADZ<KxgB@_<#djEwdZj?3hwheCvq37)(K$r3l)Ky=!f67mUo zIT@{mow!E}zlW8l(pIDqTEb#@qvH(T0rR}n0qfYkL(tPILyKi|yp3lD0*CwpO?^R^NJVhz6cTwkh3tc0;$+A%1?^EvAF+qDWSRNA zpOXl|y|~V+^56hy64tXyAOJ{&BmH3@(qV~uUoTa!wX6pKVT~-iI#-2|r9)g%)2tQ| ztu%nO#!}&TO&5;JW-hk~(PpB9mLohBD!~y^K&7gQoJ!t?I3uNBTYT3JfrEqwzaDKv zhxFy2shEln=W0lMc3!Ko04LHpZi07e!GaCnCm2knQEW)NjYh1g!00y z)Ya2zEj@2KO-<(v>k$8k@*$?0KT>NA`weM{U#4Yw>!?Bq<+dks9dY7xpB&gdwV`6A zoreU{4A_>kif+v!Bn0J=&W-x-5{-nMb2{Hyj&lw5p9kEAi@4*k+I+0`8vPq%r;eDZ zrK%da6>LwHVP+(b+8(;qv^2$_SY$X|_GG*wF-|4RVzmhEgyCmy!jr{qz=yijtC0jsr zN#)Npj6Ou)3p|TsD_61>RJ6xNk!Q*ZGApE+Nk>GNhDPZ{H@lMO{%zQj^F#QDMr;dF ziN;CZU!TMl!xD{)JPqknTDOR4Jk@9Lzb-eNhtJH)FH?VNsQ-zD{U@5v`!~*lf1v39 z%d{avcGRqw7b;y!uT|{#FzQ{)MUKSrIE=461}%tq$hGGw<--s6#_|jgP1tuIFU8_? zUf4h%Q2rTF280(j4^Lp1KFTgjA2R>Nx|w7iKa03KVfYznl%&?|-OTc1Z}k=$Gq zQ|Ir#uzBT+g5rF#zSTkH{fq?zOJ`~o39V^0XAyB>tW$0A)Y-zJmMGQ7Fa2U}?JBut zyu(f#Q19KRSC+4?&jf(r1w{Cp5G?oh_Z(nNS+0S-st!UPLzO1(fwbR$Raq|4#nbKdLOL^l#Aaf1SNwnxXi4bT8?L8%w98XknBVV#pXj3lvcu-#Oy% zVc?<`)bWIMgz{>!QGax4bZNG8N$YbOR+QTmp-|uo8OB)Kc`4}0unOu&!e^z8-v~l` zX+*r~+Ls?>L|)qtS1k}?V*?`h(jPf4U9BfwX-+w^-VYqVQP{3T*g3dQ0nc_(FS{Eq zp97%fa$X>+zqtp5f+Hsp;Yr9RdZ|5(#Ksbx^Zif*2F8xp$)bD}`uv^)gW<9i;p!sj zfE61S)pCsn^GnrgYt;(ms>$~f4UN%8@H@oDfMAd0{2=~uU5c_z1Cc(kk$87Ch1q}` z(nwlt$wsNDcfR`5uu@)X{3St^t&Q<=J0!rtla_o&74t>Dyozq!zq$7i18kOzw!^ItTVjW z+O#37;Q{B=l7}xQq>OlK?0U@7f+#upX0w0>d2G|2Pj*`4?!bYByNTb|gkP6ma z3^-vS3j4vIUfJG+F0BcO%Pmm~0L_IjM=q43K^j~P z%kWYCc0u)YyP7p>1-h`xqP9ra`Q2m5B`%EcVpnZD%1%~phBA|?Vj_R|1vEty2%vMV zTC}75S7QrH?>~c{z<}-@&zYEJA%_vv7UxjWgBAPnLpDkmGCYkM15T_Yj1<-n28s>h zy=yQ_kjQ9CueE?>T&}r1es5=%q+91Sy4S|Uo3^h2-q(#fNpE+=IQRQu4N3-J+rLsy zAN1%h9(G7GuXBO$XcBdslk5r3`pwi9hU7!YX_T`^x@xsKgASK1ijZ4Sc?KZ0G2`}y zpj>S+X=pc#ZoECok=fv^bU4uC+;?sywBJBT+E_ylp>1#Do8;X&>KljLq~%`dN4K05 zNs%_+^3T{C_s7H+^kv1}j-f(h0#T(jF3bDbLX2ufgVhD%w~Fe+IE}f!d@#AuM+Xq~ zRU>uu^OoXo)=i|=0u>TVps>g;M2Y#W{Ta~nZmm71eYHnQJKh!r2fd)H{ZIfBYGp}jrO*H zd%i4q)32IheD&W@*>h@$dTUpD)9{>qOtszoact(1a>wQ4iFZay*!!ymtlj|)G*nA} zgJ`MYx_2V~7eHVeKiyh&ZUxR+U>iu29~ojFCgFX-^Lu7=%eN}ZS_8703dr~jKHDQD z7a-pSzBKmN=S}_x$YiV)8Wa50i8!16-ng zukjP6G2GqiyL1-(f(HR680>B&5R|^OZ-LHKcETg+USlIPyXYso>^Ybsho^MQOj$wt zHb$?ts=5}pN|(IZlV+m)BB8jJqC*0`VyZnQ+yuu5hKGR7%u;sTBEaLz&yh5qHEfb0 zQDKRPTCfNvaH4#~R1b-1f|E*+cVb1Dw6j*~=RHaH^kH#1GbMko`f@2t)-(n_-7729 ztJ;#KUp0zx{DhCE$i!YQrWq4;CqD@1nhnc_bJDuWc4aJe94#UXn^^na|q_5^=T9PE*HmhDF`hRclda5a=H$c zB)Uf}|C;%c2S3btxHS~G3E==9nQciM zx5VZFMT#7m${DPsPP^#!sFS4vF49>0@opiTMQm@{-E@xdG^H%G`5)nkC!XnwINR|p z-E?}Mz4-jRq+@4PU%z`}ym9@m?^$`RowAGq2=~X3g7=1rH zwE)ogVeuF}!sp1RNRNoNCZ%$Vj?wU3yjI^k26n0LhHsieViTRETxC*^Lkv4Z9x2Pl zDeXs5n%N+!Tp`PDGV&7Uj6Bv)evOQ`!ekmJD{N3K^;SHwx)Eaiu7cF+X|s%dC@4U^ z7GefnU8$L2SR#E^L9wb}~$op+D>hZA8%^@*iJ(!&#_7uWRRa<%>t;K{=>oX?N z!AGXt0lSN%Jg0-j6Qi9{761y z=>h#KZ!Q0Kg->b=W3Kql=r+~T#QeL$19?6#W9l-2eu zCmVMyrAMjVQ#?3#0Sb35@lKwvi;7DgZ@|_9nP$M|^!p}aFbjAe&e4Si)Se~#8w#)& z;$|O5oZlZ@*q#wiFlbk}2AOZVeAof!h`dXwKerM1qB&;9LMykvLk7GI^O4r@s!}@d z-*Xuz#2t18+37RhJ(uHbaRIy%q&p|4cyx{ykFI_?oVCC-Y6dkB;;2h;*EP`PxZaZN z0>AvwRbbD4Z63vndV0hVr^&OJgD*1j%!O7j!f;$Uw)HuijaXH>~xgHYiUOR9+4Z-$Zkj4U_9rB6a8A{7Ro1LHyqytNj1}9;;t)jJ=_qlc|-lvZ=l4|Kp<=5j`s2 z%Zmi~JSM8XSH|hq%H6`fSdl&I;m^*VihfVVo*^3!mz?2Dhx~FvN07m9B2{IlO=sJ@ z`aHb3f4>Ibf@k5b^ppevC{<`uZGqZi29fy-tE6^&!c~=z7PzS_CmI-y&ZLSbmTqtl z7ZmEB40m_09W7*8_!-rbx>u2sz&_d(GUumr9^lck zopmF^9p!Mnf42q(_SuEQw$Cz!HBOJB{TQ8m{^+2#S?({x`K!<)lcHnKUuCTOxA*FQ zA_RZOnEiivHPHXJ!Crxqxy-CAniovnsWLf~Vw+DftK%=xW>-)WFo7aq1bBoe<%V75 zntF*<_%|7^EYe3eB@2p_;#Rs(#m$uvb9 zfR_gKlWR0)4#A(%5S2|pBa_zt{)F6lBa|17{l>}n3b6YV1&nB$wO6MJ3Vbl3W_#iq zIx2@PMIDcL^fTH&J&IUCmlgH~)7E8P`;eOqG|z|yqU|6Bq+kuP0LP*KkNC^m2?ifH zf(ETb;`Tfie?>YoD}l`JHrMEs@QI(6Gla(gQiwSRBRU*MG@&^%d4sunf!amFc`m@z zfJsv*2{77}oAZkdF!ouWtCKQ4y_AJZ0j)x9C!LX^L^Z_ zy=d31xm6f(VAD)23Q~(r7e`<1Q)l?tWc0!DsL`9v&ob#B!3vB`oh(2N?gu?h_&>0@ zx&-lOa!w~7dyCKtO012l33Y5YI!1z63E&dhmk_OGpHfLDsd1#1G$?A}Vxwy9PR{W= z_>SB;?P93iPm#+s>NAXU9d}Uuari_@o#8N%zT{Vz_6Az@Z3`R{sWIts#867bJI_&i z5o`6mP$Zse3egTWk547j!7flcQp`1dfePFf@F&7&oT(y!GV}K>#i8B%Kb(D2kS)=c z?J3)~ZQJ%K+qP}nu2Z&c+x98jw(Hfsw$Lo$8FCz0J_upPCGuD`M4vcD?w1*MY z&mbDV#H_L|S~r599@&qOH_N8uhO?Awg3A$T$OmYgOJ z>JsuOSs;s%kIw9K`;6Sj8|F+1=RG-O7OtIAk6rr7UePYz2uB0zY2y6Wi02JJ?9(C)HM^$(C#DE%Zr$`exOUGx1*6xt%c}_L<}Av$t3I}K@5h{ z7D2?@pv9z0&?XdtZ%N1`OrA0KLLUfqN=2WTp&V)@jwcwt*AGxMYA4q;y45G_Nxnqn zND0#7m6k+I970Y_i|{naSn_U{nuKS1rH_Pjr;VqBOb8Nl%gUdnh(H{&lE26oWC$fm zVi%#vIp!SV_F>!>Dawz!rrsG4OjRQWZ;o_GRijQ}A5uU|j)Y{bPS8~wuA(d{HCbv^ zqqTT(u}&yOqI&r~6AIehk^oonGMh%6@nW86b`-nKfoDc zSFM;yMqV|82l?W${3_(_uVF4cyhLf6Ne<*XO2Vq$gmPk8Ww}(9GTX zdthF>9=IGTRK4@dn|DA|^zUOe#1ohYRdB|8sO8f3TBA-ne1dy7Z<6ZXhXr- zjgNqaAFJ9G|Ccpx&TU>Oo+oV<#``oJf1EJW!B>7bz)fS8N>jkoUY+%Iya1M~kS!fw zGxyk zAWp;&FjkjvuWSDO8@ob{AhJTuH7hF(C3Lf@8_Pd@-P*TLXP~aj%$@0ory$uStZWw- zjd(|Y59`{c?S*iCfsXP5A}{q!T}Klopx z93pqXFl0@yf_WJ1k1w94wT`=bPcS>l!krsx23^^MmmyoSOYWhzEzUKhy^fw-@9v>J zq29dePZ1k($~;7_8#e~N;_LOhK(NX_ZDT8VkQc)zVb(7IbtgEdlSLh*zgi=-vv>NI zCri^C^I8UaJRkYL&!*3I_-(~m6kUJed$qY6}3Q(p))B5nV-|% znD8sVyGRv21@b<{cAMxnIDuEc0D6PNRcq-tQkmmEHGOd3%6=#i?M!;o>l<63e`_sp&| zbmg@SZ=VXSY2uve38h4nLND8K;H-gotbn`$?rt1y7;A%TymcEvl>7MVVH#!B63qp> zIS8k54SBSN8b4bIZ^BX|a3&q16v#JsViDmOKATaFu6`8|^EP)FpT6R?D#F~BEEtzO ztExiFGkF3#AI)+%7IukMF>6=#`Ty?dq3vZ^ZcU3zn<6+Xo@yMD!P}b(hq0-X&%7>_ zvAHFvlbG$-UwRvmXm54TEh(W~Wa%}RDX|HIZ!{9_a^GB^ZDB>XdI)a+K!7l4(6mB; zma}q>aA8v^@+moSilpV-E4H0)*?0iw89#ZJupTOy1haVqadvo?wYf|Yb&d2>v~rBR ze5llXpa*gk)%0&4g5^i*f_7kHK(J{K;N30eI#DSBZ$G7|OJoap`8qy@lC}5O3>uVe zIT`TBMf{Xy*cs-05-eH0EWUPZ&)^ME$5}c8UrpiB#3#=nI?I__TQ|YJ~=aCi#@qA{}MA%X5mD*xcLSgJkOxq~ib)y_T^r($o?GVEaTM zqN+A|t(iObdI?n23N+o*=zd|s+p=GXd`S3Xlc%}q#HM{%?D=Bn2dBD+UyZavgh?{t zuV-JekqUXygeq7Nm9dP|ot;h2CLT#$P&i=N-Q*1F;ZaG0qfWTG?is*+2wMgDK+HqB zw)ys{&5got%+b)E*y4r>i7Dp}w0Tzm1qijXr+7Uo6W3U(VI-&9lVj(>3TB9mUKkaj zfWqOi-cVQ{IVBczY0V6KOq!4;XNR6x1%1X#l=F&Z2Jaohz6oY@$Goy^t$2Mk| z9hN(R%j#zGsJZxTEoG|WoOOkDnRSV^#(Hx@qo=*9&cxCA@`$BE6Kk2ZvI3>?E)Z~7 zQoBA^m6tQ3Y+?^$V5tnVpu7upL|be1zUr5;*hoA6^+U|GZ1u+C@B~m3R`lb^-n0CT z1}wS$sxeHAvuavCKbNf|4d*$cqILd?+B-B%*Y0MZdqMf~qAOsAq+wYCa8tYlk~vOR z+Kie5xak!~Ac-elNnzrFnr~)iteXSuZ$@Sk z{ssMd_fRt|IT!4X+^Ro_z2cbga$sv=#!QXN7?M;i0gXtAwEXKKT(IH9g>f4o>66OF z)QH!5vR5gA%)7)S)nezsZJmMat1*i6MA=$n9c-cLY>skqT!0Rkxd@m3vt4G|z;S4b zq}qbP4+t4jsr^H|lmMR8O_+8?pjr~%^s{j^xVVaft~)V-h$JsQEc}(hQ_~HgX20_p zQ;*!h;1oa&CvK0Da0?DnK10|)wy+T5kO(49kWPF^Ixi@rzLxZEC^JM>ELatPdGZ5{ zEzsZpa!kdXfZC$Po5(-2X@>njy6*iwWFGJUZ>Z(RuSFGZPl@h znCRD5?4N9a!S~H1{6;U**yuq$$NvVhf6jA8HsSWWb&E5Z7h(oGX5=g$!3UG;H>~9! z(Dn1*hO!glc_RdAMErd5E*XK!Um%RozI!5a`uMEUY1r zUg)g7MURe;KRbwIFWZF>_egNqC5*??$+OVFW2 z@QzAs|7%G~S5E{b*e-za4;kA4Dpc%3pt{LSt?4SP!q56m)!I@_)=C}M4shs%>t%w} z5P86&`$pfs!DQ~Y*!dq*@-)<6K^r2p=qIwIdE0NIz(4Zvrm_-)Cw1Js-Mk#i%jr*;zJi2*;AE)s2gf{c# zK9V+mBRq8mH-3__ziZk(wUni7%{?6`q%@bvt}B9hK1q6>Et(M<9P~dWiTrg;uRmr@ zPLNFIIYkK$9DtM4*SbiAM-cuFIPewP_9ai>DuQ^xokISoLC$l8ZZs<_%6L`4-z1Jl zB`+KUzXhM4*e6VmN#X_mQ55c~rHG3F{uL(V2#!n;L6m{F$skSeXEs(V{KKqpv5P;VBICLT=41!)uys$M97O2L_BM*(Go z$Y_p!fRZ*r9e01glCUX(*|9YMaZ@VV3lTk-RN6jOblyzG@ILlI(Y(up`*Pl;TT%yR z7W^!a3FVjp2}Z@;He!YiHO(W7ao9|ab(Ok4#V8g6yCts>m|^XaHM7BNumuC4GrB(ty1z$MFJx4&WE4M3Q3^f?J#8&{D1SwB+FQs>S)?D%xNjdE)`CXMGG4(*^3Cs zF9YY{lVGFNPWuojHhDAWBXgbbl5~KJQh$EZCQ`t}mOb?$?}CP@N=>wn(rfv zhqV#pd_kV?lMx4FBf`Pv=WGQz-BCG1ZkYpN*CoG-6V8kU$MnX0iPIoX69;Ng!u-XP zF(_r20)>6{>~-S=xm#-?G_e8hHL4C z*Eyb+Ei=uW5+O%@q%;#mpr>;^$SzkXVc~HHVovj47X;VYuBN6(5cHcW5{pKqG zyp`(uJsR@h=^viuim9^j$4G=7!qTD|T=C|kR6}%9B@AZOv1gnV&McE{-+K6zhi4io zslB0(_(p&fnS;ZQf!X#VJ$fjl5kr%J&PtxyCPoQne4_06BaP{@0TsI#* zz4zacGv8R;-`6)EzQ4;}$dU`Xq(A;x40SXrbc#iT-#>=r`svStnCY6WI-yboYmX2M zAtA``zK}26GHAkPNB}%$XQ>bssA0)Pmo{CcdRFL(ip_Mh&pB!_sh5I!{RG1eounC= z!Z30C98Gd*!|1RuY#h->k}L}31L8#xqL@?k!@tYoWe?5hn17_wE+kxKhU3!Oz# zoiUNh&@O$5j-j!qm#{rhLbEakM5pwDxalT$X{UCpe+c)p*wgaZS553%E}XC>!~5`c zMs+V%TBs!>rU+fsxW4v~u}r=D(l_i-+(-T+UN>sLaCsVmFD(kD{m)RR+n9AXzH)J~eKH%HlZ>4P1^R*zDvQy;E4Y^kvEGh9LrTOlnEN<2Lj&|PF@={n)D2+p`N=iwTapex(gDNTHn7= zjC1f)!|_n)IcSMZvBkxBEj7!hfw*hbNWmn8Ku%(O&*>^Y)Ys&ldTC57jjl#H}Q zhK85IiY?8`?6azgA{jt0c$NSo?Jtf4 zQI4u19iGW^t(QPI$)>*ydMt)X9;<*)1XGOPv8OqA3dcg!`!0x>Id3C1Gj5^Cu#l3z zSGo!&S)-Uyd2(8~G`lF~XiS$RR_i~mVe?9VJ_XP#RZ!Ww=JWwJk$Xe@&z9+-C@bO>DCnG#a z80uSba(8#-`vUrLh&vMR&4!n|O6Dyk@04s|O8y4j99V`;2%lHa%s1S;b zJ_`tT0W`wg_2jL-O$*-0O21gY;7SZSB(H(*9-{gwmh)Bh=PU=*kTq3mcVtQ2sw6w_ zB3JdEvY3yElWSUNV;1(r47!Oiee;C(YsfRcaEquon|!TD8wW`y=}y%}`cdvYX%o;R zZ69E1S*RT3wTwI*rBMGe%6C$8@Vl%dSPJz=Noz7H$OI0jlOCqAW&}M!FO+F}WM+ak zPXM#1(`E)`vR)^aO@V}Rl{YtrT}YZBs;={JZ6Ghl=hlr z;z2P$U07yi2&b+7j$!??5Ia@W( zm``+xLBO;+;tfpvVcYvE8N*MrM{%9T#seemQt0C?xt2B_&^8h3in>GkX-VCMY9*D6 zTOC&CXjIZ`lyD^7G)uA>&4}Y=af`6x))Y=LJ#;Q6mE<{2B!);%`R2s1Mbh@s{v1ty zy`zX<$^?oett!c;x`?_V+9dtF6z~}Ho?An|x`fmb$eNx_fp6M#N+u!Hqt!k}W1PLu zoT3X7&3P8H$x5HK0Bu@7<;gtdX-NN+#X~##_V5g9P_TlQY3bvGo<^*#j88JEbqAfd1=aXn{k6(7CesWByQI+TZDJ^HZBmfq;$s|E+A6iIIWq zr-u*LwXi;iqs$g$1HA>#2d5RD&FZKNVl9$jw*G9(fP&k}8(a)#k9^&k^19Kv9zp6w z-h{t|#|aTfeRmX5p=TD|2NL2#IGol>Re;bIFX(yA&_B5g9-}Jymc8sMv!YgEboH^V zzQ&@g>Xcz@haXs74O$4_Q@U9tH+JenNj{A_R)DJiAft!22tF=E>gF*aqy+*6g?nW7 zQU&DQSrxu9R$K5Ew(&Ic{`vc0;DH*G<^M3&`1^DJ=W_gaoy)&ttnvSp#s6z2nWds_ zr#Xc3wVdEgb2`r27jZ~T%O_Dwy#US;jl;#aqvk?gFesoREhCs^`8wSFlx(D{&1H`S z3F3;5t|w{k@BhQM^+!X`UDyE@nxtRQ4=It=<;>!BTH}4Fs^Lz)xsv6wLgysGI>fr zDKZhj;*LJYds$A2Xpx(6gdqU-NP)tK^nltgEIYwK1b(35B1SR>vcfEkUI}T7G)O%p zYM2E~6XsPw_*uo^fYXOH(K4eHV6OoY&ps#M<{v?}XH0Q}VS2Zd94pH_8!NZR$!}d& zCe9R`(FYhf=%PfxfS%vBb-x{=1Go%U?~8k%CQ^97LPF=o8oUj~LP8XS#Eom}AOHR> z+{FaUHXLbPbP%-}&lHE+_(RK?Xm6-ez29cQEBE2HWmn=dY+a#;Da&n$`9v__T)E&0 zY(W{KE_l@hnbM()kK2V2wTu8@Yil2Ha6Z4m!<~c2mQ~4Mqu4;8J&ExYwyWl#E$^{O z5jl6(S)IC7mj5&MMNK4aF^wddXo>(ycsfkB^dFRAkRc^mq4bOs1f4Q00WHFoW`K3y zcbacB79L{urErfERQs43SG*F+oGQb3%uv=Vmg=SMBv;(|8!0fq^*ORg*?Qo;6i8kPflF1o)9vp4@5c0 zi>@NlRTbIbARkG+6ⅈ#R=>o>jHWVJj@(c$I94g&4R?=A|qE3n{FTtrNtbrc8tO~vKH&vXOlM`rJ)W6PXDr1_Uh>E81~oGrjlkMsCXfl5|c> zc#qRUEURPr2_^g4{ysfR{n7N~Y9V>i+Nbqd%Xp=!5=FWiR`D5WwpSjigIHgw;`ylS zTFk^L9!|sb=3WT#r0|_oPB^EG@u;i<$Op(aR`Si4z0QR$?V=7q7szagK5S@>-F7Hd z=VAyJ+)x*-^oYc}Tz~l)!qN<^xBz7ITAFDIOp&AcWOw@c^)d!j96E>64Tsa(!RDp0 zhiXuqapP#HLA`H@5|E0s{)S?OPEyI&9<{DoBw=kbMz_`Tu$v(Ix|gwlww#Hm zBPHBf)9oLE!W>m@tQP5(ilCDWRm2_}ozBTZ#p-4;(&Q+-_Qr3Oh`fJg!uV#Hd zSLct^CU-t(fjh2=hWR~B==@MOAJhrk@#gw@+7%+xLyx2eAa2znldeqnIm#=1gO>7d z-UrpQZ-FH)ex&;!o5eH3I=MMF00i}zCWYr)jTg(mO1)f8ue9Ih-6ev#snJxxK_8+@ zeu^kNq5+HEGSuq7j^_r~QZn%ReWX|A&}SUa^{`g-z`#{Qydyrmu{F;?x!?bg91XS9 zsmDxRPKDFjN)2M&PESHpyQ^`1TfLf1O_3TufvEn&b~V5^oQr)srY30uU1)I>9PfMRRi;H(+dBE1pY@_;nWYU5Psx)y@vU* zf;XT=cu=IXDQ`9qBrkt<_B{jkG{uPMkM+%8?w4P@N$gmCfw@k4=~;LmCMM7O_m?=m zFw;PpAm~sJmL-));05ojdn^s2D;a-L8jOt{%XE~QNz#>#)zdXn#;t7+1r_Vss7i_V zi*=w>IoZZ9X&|80Wfo9f$E<+&$a!l~W?~IoK#n9h)3HrRQX5XK+Wv!8=(Qz(f7@Q3ws^8CO$ z0mytur-w^(p+DdpJSpMbyZ7cAmiQyr^G}HJuq1Q#_5&~4{tK`0{|91-8#_80+ZY%- zm?}Bw+c=v1xZ@lDM*?=1vUU{G3d+}&2lvyO;eZV~qtVJoL(q^K(y)dXm*4fMa~3gN z$j*SrnDLsvK_D>}$zS5JIN|| z<|FC0qE5vuI|t_$4WygPwPXV43TJ=TF;E8=oAEJQgcB_Lir_*XqUW(pP1=rRje4t< z5*0G3p$J3OMD-Ec=(R_S+i)=80GT0=iQzauUbRZ(b4!qfTg|#0EDfW zsT8uTvsNDUJ&EJ6KMhhyE=}amQ$kg|%0}$Zn~M{1iWM9v8dOoLmy*^!nlxO>yt;H$ zD}ecvwrQwPvRUeCDA#RG++jc;5g(8rX}{(3s>%%XBOtQtKtATLT1|5>5V>23-|>dV zINvF7uH{iIYIJ>RDo|2i5$>9YrRm>hRa~1h99dBhk7B+t_sW5u_M82UTlxGTfMN|g zdOz8qtR}0hc-Spfap>A%JJ)&8KJQ#O+#c?-=ZUGZ&J3kCeFt&-W;AWG_zZ2 zID40w=%!|+EUh^xb=Nf7R~KLI#CV7W3$O}j>SJ_`$-X185@6sq*>H$zYeZCwXqJ^C zi=|hZg6v*Mhmu_T8-RjvCit%7SyDUb7F|DEFgDD44_F_6rdi$lCrd;vAixp?X(wIi zOi@q4Oi}TKT4K;kVI7sLZqar~{duqxBY1?$yb0&9eSrrgK!Hvzh+qAIoPn6K`L-<1OeJUsX%QF9~spZW8w8- zFQAMvXP#J{ZNKe@#8Vw}i_hZiMd|Mvcr`mj4d(Tm$ix+1TeCvntK~Zd5iWnl`84F^ zMlVW_19Be$n;hnaPr!Efzcz2lVcSUN84OLu;v5;vZ4em(HU=rx%mHP|CUIYi3vG>C z;0n79N6{$`$6QXwRGyq2iZnzEZIvaJUc3vl)mfda8EWpRP(~bSk*OLYrSK5FDmOEO zgjPaeq+v;y(%Z1b_GA(i;9b>) zl`$m@3yU}d73CM0+deQ74gm;W;kM-DYAWmVfG;Fe_9pOupXd6mV4*0MeI_;P?g!r(p_ z9B+|$@93G{p_$&O8|;%{oTH+hk}$X?IlmA))EO`a*hSkkXrSMg3llcnbHqOZjj%IY9nQAI-W*w&W z6yU~@v8)5wTr}oWr^G0(o_9jcYHM7c{dv@Qptj*6b*ay4Hx?R{&E2*HDnd}gOgS>q z+?=yO{A+L#)p8&Z#p8t?Qj{~4FGPl*B+Yq3F{Gek*B z0wU5ufh{Ns-PCoo%t;uWB_}|QI=jDR)SP}$e@VmvkY^>Rhc_i#TXFIl8%>+%H%M1xnoLg1l_Ezl36%s)lyGIMS&IUdm;r8z7e@R| z7N{^KtFXt8CAINkneQyIG>LXIKf6WQ?2N^3B zDGT_6eVr6iy_D0Au-%jyyT5zmTT4hwGSgbm!kA8@)>mpoS=15><%K_qDC}X3$cut# z$yb>R6_cLAiKe1gb6CPGMk29ODWC3p1N_$0#RUxBn2Vhq$_9aZ##)Z*M0r{BNP0#K zj4rMR)x2`dllf=^=2Fr0{ZH++I`Q@y4O;8d&#eGMNR=Te5ClZYNPfsFVEHY!VPeskXlyXaoOgk$ z#c~C_H-OL5a?=%3@Ip%Y@W!nMCN9V6$-%GB<72vCHM>diVogEVR!EVgI_YYNqrP{0 z;(B=qLpWl%5-sN(HjC#X`rD^tg&liVZ#uQ#v^O3)X_XL3Pam@6i2@f82N^ON5iEQU ziOvA)m`qYlB6}W4RS*9;zWYd>4%$-8sSxAT!!V>^z)?f7?CYFg5F|GYk+)IiWsr68v zn;>0BNdf`Z6-iUeCFOX;7yy+mKPo|}qCd1OtE*$sl3g6T?8#$`kZR|qL!a`FNiB)M zSUdy|yUgG_wu);=`S=`aCnSYHjHy+B2T|18AAU#lJ{i`FynGOh@_^3pktQ@h9(XwN#+tL1^Emb7+UN2oipSQU z!OH)x?Am%Qz%FKKPDsh|HWkFzeD|hHv{Wmz5@Su23D1-r<8%h098$tJK=biFBA)TdSA97q% z>NXhq=Z3t&J2|w0vinE~C?;k1+%2ldE3nL#@wp}KjTJ7og8g^^lY3VPr@LUU0}#df z5{HJXVqdvQS}K`G%%Z8Gd(Rl3bNXG$|&Q!dgi zq{>KI4rk7WQVc73O z7&?e)kO=!u7WVZj+asunt5(UsZ2gKn28EiirzS~owA%W!eV=`AJnCh0jTkVdJqv#& z!@1B(g8Mv5p!HLKn5;GI!P1(6{aH>| zBy>24ouOXlRip^@2Z=say79AswIL!Ispv~&0N9KrBR)2+;*P($9B9T0eOgB)vXfXc z4xlMhBOFsA1RjuW>VD6QM~hMjspq3O>41tbI|u~3JI zn6)YA?fxahvxX6it`ybXNgkY6PoF%6T+)U(x6sZ%md)y)u_twFN9f8>okq}N&KfdR zII%*;v#nnrSsUYB5}8s$~(QPtocF*1^va6N);6$Xor&6WTN< zBr@vWT*oIT6mJIuWyZn{cE++b2+!gLL5F-^DG3cT1YyArV+Lx2@fahjj)17|V%NGc z1#-a1`ZFGJ2cV4OUQ)3phxHhXXtnd=Z&x#>5a;sw{%-j~ zE-Yr7g9o?KU`LgTv2f&#lcbJ?GpG!$+oJ80Rn4OdQ_0#y&nhs{LfaU2Hu_W`M#@u0f(iv0j z>UulT@?63Lb(idoFsZoVHw`tGChn4HTS~l`lH;AJAIJH*^uDH_RuF{>`>+ zIHq~pFqm1yHq+tfEG?K_6{wK0Ljq9>Di>CkNVY^A2i}kq$7+$%B4O@^IdtQS_DeYw zC95J}+0?hRAd;D^_?v-={cypL;Zc;GL0wZ7N+C*CI83X#|I1v-j24Q8nUw=*UFx2< zj6TVDii$e%3L(J&ELl84`yfHI`L8H$9uC{oR33zzAk6-6q3Hdakc?q@OpDQ8HrXev z!^+@{11(%g^8M1ZVFxBjb7qJ>f&49ztMGhG25JFpw*LI@9EdkM@0P(fR!f@L29AGT ze}~7AJ46Vo7U!%7rAXLvr49NxFo1`5;&tH`R)uV)9YTtP09;SF7aiSO)t3uEZk>+z z|DKayWKno+$hXeOw>lNy2*vb&uAbs+F(|$i2HH{Z*n?W_o?Bg)CYELnvM}K|X)tb^ zGu0%H@t+m{Wfs@TOfs6#zMk<}c zkL%k@f15@-@U`ZJv7kuaCYX`2CDpulbmEsyxgu2sm2y*C8;zgT`|D?!wWmtXQ^OO; z*>gwFyhU-C1=^F)=X}9Qn{fyrR&b@k&YWLRR6EiPv~3_L49GxLui5J;na zV1A|J`zF~O)^FNei5+Cr!?uZr4ct_twmV6mf`G7OEN*}q5+%?izhl6D5_EPb-TiuK zm2gMX8t&}lr90BU{TBWui!e4ToUz+TcDmew#sF;c5jjrGsk2NTGN6{8vF_xxH8OcN z^gE=wTm9V*61q5rCIBDN+)u8M7ks0x--W>MXe@tx6K%f&S=_Qd96=UC?K*zXl5DIJ zaIaD+o%Bbx&c-1gqN703lcMg0-R!rP_5~U+$cB-y)1(+=9#Pm=J$&ojJ?PxoWnOW@ z70K~!y1FJlCbkNYMuvK4#!i!PaY~CAIc+?Y;7fSX3ciplh%0Kz>Y<3*hdo`@P0)3) ziFyWHaZE>genb7EF})q4ZM^fNcP~Z$-wFhgf1^N6$O4I?|H#gP2lG1-8q!PNBC&?QQOY$VtemOIO@8Ebh$+HfpIbYbFa-MTk&GA9OL2)hk}q(IC0iq#fhApg15xoBvYJ|La|- zQit$TT3X_J-g;(CA2UKskakn&cNqmF03ZYkqXq~U^drdigB&oD4xt804;tFUth?$6 z!-{C0v)H8k2?NosNM2U4s#vyYTGn`PYPvigfBumnr$a;ne(~a8XM0|^{dCQ*+KxYL z-CqBUxFE?FfxDX#eh$k#K8S)|7O}nFYqEXD_+00;oLFbOjRel%rFpCfDL;srxW|rc z9na*v+ynUXKFsEv5~0x;F88>d7`}y-^|YS|W`6~7`R>n@P`_PMANjVv!+m`uj(iO* znwpPPZMB{T#N$2R@<;nJt^2xt^hkfw#d=@m(VY;%d5`7npHiWDU*;jcMTd6hd9O;s z`vSiN8%eeW?dHw(JB2eh|B6t7K=YmF>7NqpM!-!SwS%e|eE`oHbqKeDi$?RFFOK^h zA#tcp9(4}qhLbUdPz>g~d~ro;c*V`2c)J_fD+5GTKS30su3r@*3-|f0^!rZkJEMK-P!A&G-$ z8TA^x$(b6m$w`!c9aBSfz0b=a1HXU;*&2yBHDCcJHptK#ChzGnfRS@e$oiJa;Ie9x z!^fqvtB$ad64@p~Daf#@3SNB<^UMrWaSqWsGH8wJY`uVG?zdqj&7wk%28aA_6;I+t zMxr%zbIpNwp_xiE%ToIu1Y6-}!rd4(u6AW9xQ@-mr>EIBd}6x!$l6${$qkrD;AA`( z7P?HNGqc!gDVm_q)0i;WG`wg!we2-b06Fv@gmEn!(JaD63RRA7&wMA98^^%2{AEK^gKe`)7wl0O4Pw*q@SK(5%;j0iM-Z(Nxwx6-sa3|dwW4tOc8kt%X779?U{xB zd|A29t&s@Ra^S2{rHVf6wPmDpQ0CN~X$^E0gmPoh8YY#3p+9Ji=pA<$GQ0*M$JLOupx)su%fvpTdwa1RA?4s1@7 z@bV>EmxVCI9ub&UACS-{x_m$9BZpZ`iG`HKg>e(uRwyqRO#dJBKk@CP*r82gCaQN4 zwP6|H)jpPuFt7ZUuqg8yf>l(Qg1;#iw|IeNqzYl8qxKT#X8-UZ0isr3K{ts7)S zcejLHyqvjcwu!`mTpfUGwSo38_xjuDTpg4e#_s%nf|BYZFvkwo31sp=+TVO8 zK+V*XosnrAqxHHE!U36#n64>8UxzbU)-ilnhe0sOO{9$6KAe$`rkI3Q{;J4?0TIvQ zc7Aj5s0hC5CPKckkBV~8jP5hc=c34ZalfeK#5}Bk)epa>6j@n^Gb_bDH08b|dHPX- zh{c^k(9~@Rone`3_-8&M;!Zso8H2Llwb-k~FMSgcZjg|wVxWQz#>=3NeO(U{L19py zn_=s0P8@$o1s@^h6h6Uo()D{DmY4)iEHn2I$P z8Q}U!EFMvFWx_svLDgM&`jwHeq6+l3wFZT@CZzkJM$t^#Nmar~P{Dyb_L7TuOu_>B zx(a)A=skq35edUe2q&S)xtYcX^5P$u^@8OjCM%HGM=Da%d{)0Xktc6pL-GF~%HAGe|(s^2mcG-3KgGqdOQj#tt28j%OcEnDU^!#pF0V zFpgPX9{q_FH}z$vVgWX5^oeLfb|wF10J3kN9?^|q)Sk-hW4Bd^Ie=`oB%9Y@bG)>^ z#=N@?xl{XN_=`zKPPfSNg8Ox(n($S}B8%Hd>qdKYQNv;VPxfv>+d1o;Zzculae0HNX7=&~@Qwz0M=<2mbH$SSYaj&~jg>@U%A3^?qDu`V7SEu4+3w zhuHk2-n^q7t1=%#-C1YIKPw);_r3=HXfZF<3jx@$B%W9j!n;+*PosX(ipnoAz51b=Q8F81`lB%B-9j=RrmYDJ;>qW+TVSBhKgy!SjyD789 znaeRqK}X}=^H#s;huBkk++GdaJqXkk05_*fS>VQ$KC#5k7Hhh&&6GG>5ax(ivGxV{ zVznsapgb1ARg=lq1n`0&RT3IQ9@Y(&2P7mln_dVunKm&DQ7>u~RVS0-HH)YZom)T3 zfl4r{EBR&;=T$Jn$NQxob7;>&T1b12Io}=O?trOdt-mMJOT#{Etg%h{CcfL0WG~#? zCRa^#D>bBSns$-DT)g1C9sLqk&GK#9L7Svx_%ut|nTB%9DD>JXTTj|f{$5UwxT%RH zw=bgU#BFHG2wlLvUC&`jZ0#@l128doL7ty2z+VJ8|Jy1T>U)3)d;)lTU%E(ATe+Y> z&fMonif7KI1Ii0*Ha>-LDR>s7b~OyH(e+O??eD(Fo8+G#;9a%yx~CXO-JDF>oIJ7_ zLFv-MT^JBJiw&v^CgH2T``y(`uKhd1}NV7-)_0g@AIwyWJo< zPb#^U8#HP&VP&K82*P@|OtCHZ)vA<`sS+&rv!zWjZmU>A9~ZkO2Wr34iH3@bIdyf1 z%Q8MJ3A+(@p*H!a9m~_v6%xZ0U%ogROU%xDCqVILzqJn{Xgf^Mukh>v9ya*Pw{yZ@%S*%f^sYD z7!HM$k{%O}#6})TP4@Yi*y;;Jw=)ZIlNlrQ<(N%fTXONfhLC%)_nAq7bqDGikJQ;X zKiu4fb-pd|M54e&-XQRNT(Zo>in`wq*a_wf21AT4$WC#A+L0E>E)3&gw_R(J(Zo2g zq=UC;x~X7FcKb%&*C;a#D}z~-#^fn9*98mY8e3akI!%tuEFB@CPTD#iMiDoq8%o}$ zBcvM@H0Ab_S*8+5&QfiP9=LqOJ z5Kk0BIMQNKPZmw0m&5TDYTDz^MbMX{VAo$Y8QOn&{IKPiK$pvO<-`$PVyvf`6~#Je z)h;g=LpHf;I6_c_WX6X~E)-Muqb;Fqz(!pbl@Ka)8!1nA=dgG(Zp;Xd+!1(|Gnt0P zIY+hwyKVmFwmU~H5Kffq!+ss!CXVLSoEs?NuCQXHdc#nWg>Z{L3baZ(P*6}tr3j;r z%@)+-OnRS0wusMOrhW$}FS4&!J}3Q=n%bU!A~C8%c>4B4xjHAG;D^9Iyv)^Ew@SOEW_ROwi020SwGm`ZGXQ6GULogX?xE`%1(+IJ$0KD1 zxG&{E!H2ew4LUETO#$`St8oAhv|m<}jcYnU!|sjN-kD+QeiURaeZ~&%&_x+cjF-p1 z52D^H@zNl)UZ9m%@hs>Cs%7CcN6YdJ>#cgT*MQwt3g*G0-}uEqnYegJGv4UQ7H&vz z4FT_#w7nsX9w%5yZ`wGglI|9rfX{033rtl@r$3LN#wM%M2E4D26Q{XLP0on}dnjh0 z79{(swzk`6Ylp|)L-R!DN|^7}XyZt7OE-0lF~E2)whsRo1FY;sh&POc2{Atej)qfJM!T#7U$jeHsNAyeeUkxMQNz?4ZQ%LH^Qq`}J+nU|!f zS-7@X-IV!DtaTyJ6#EO-_$SfvUCM2quS3mb+|?+YM>#slJmT(DKJ_FL^PWeMd=4G< zUI;+ZC6d-Hp+n0a9&>L5Af`v`OHGUDxp%tb_6Tv;)+6OhRgaoGWZlR1sCk^cFsbd< z!y~qjH@z3rq-39ra7xN1vrl!sN9z#Trb?UIFe%!kIk<=O2pFV4$LkQ^ruL)uBl;n^Nz$MCP|fXDN1d!%0(#5GBE?rqxkq%({>-RMh^s_C zVq?`GU7omSY|*(^fpto=N{Op_a%x*A$Wut0BwuztwNIQY=RRyY2Y$;wPnfGBKY~6d zeJfn2)>pbI{2~17N2IUpm*%zfGpUbtcCRj$yJ?Iv$sQfxRHsO_!$LN-gT*X3muipw zbdPJ?@EOz~)N9Q$#gAnT$R*xkukBxTy$7vTFv2ppMaYN$2tX^L%ya_GAthsgtZv6J zT_@BXc>IAMg&Hno6)@S& zt$hWa?QCC00+Ow1dM`6hn8HXbCKAx@{%e~pHFnCyHH5b^-;kb8>aq*r!=^3VA|CY~GNw+`Zt9&h@gbpF((D>9H5| zfKr<&<|E)IZTsXtn)Fjh_#}r-%>!7x*=JJ!NKYM|EK&94J0GUGbbUtp67`klP1v7O zcEss{5p95OvnMZbP=+^IfIY6y=8jN%2k`RVR#;sXXGDdiJ>%Ad8tKA83xM0a=tvC}62En88@ zIh*Sqao5JTH7lX}`;`HtbZcAIDQlF&--M;g-ZYt)f%<4}BwEY=g68Pi!QVESSA{5m zNAm7m`SA7jJ>6BFceLRAmU8s%T`i;nrlb4zdA&U7tlTGltLYH{GllB#C(6ao&Q;DR zm%UU`4NtvAhxXs|sA;)3`hDq@=+o7DxBAq|gmeCOwAp9|ER9{FDx)|vizf%V)mY;_ zwPhn1X9kq6kw3qd&tP%nJTqf3?#hkI8E7k8EyQs0u&w5_+4HyY(OrzjVrrh1EAMIA zezcD!921B;V02Xxh#M{4U!I_RDlmxedJ-(Yqe?pm=w`>IDzotG${n8pcYiX&K}2|S zSY*e-VEpj*?)$l(cQ~}}igiPFQOZYB(ps4*9WZ%a(1Glv90b;}VWFo)^l}V=Jm@{3 zVv+74GJ)7aCuUfZRFsEh%Xb3`146HAsI{Jl&A$Tthq z3BLY)qfZTnm(!KQtbF5>QKLGF)9>Zf zds&KW-fOw%jx@s$KL@Lez=7Dx&bgkqfq%Ign-SVgIe`H}&zgqJ-*+RJAwhJ{=*~QX zMh$vFRYk0Ht#yc}wMN5p+TJm}dK)PnbstlN6C~mS`+R+IAAbNS#r&!{M|1b)_x)~K z{Snm0#XIUpb3y`UoWL1?lo1EbICCw`0XqE7xTZrN_|$h;Y>^Mx{8Jh6cQh<>Xf_OS z^Y(yjRZJ8nhSavsh&%iC3y{IL3GRh zWEqxHa9`!PW6^ti`y!=sFCzfO@3POv84PPGm!zqrOr zo1*#WtI}s!RzR|tL+6;X{K-6O=5*wqJa=TA;|^kI9y~1a%`qiO=P}Clf$kvh(|>^9 zjk|NreTBSOo|~rQSe)3)$3OjjD-gA&yF-0T5Vg8IN_?Z*D;B$D4yIrpFuCN4-lp|_ z-pI~eeeC^Y$uD;9B(;8DQE=yo74e4f{QRF;wTWH-e9|$1fR6r&HUAqA`Jee3{~J8y zKOU+wmUgCwPX9MZ_Fs5NijuB83L^^dAGg&2FkoO*egOFZ0(Jm90DWoLB;}VQvOB>U z+>D)LX-;!ff82fuIg;$-7QSis!+;b6*)>UyvzOO#_M)5b_xn3;KQxb>A{m!GT!O`Xf{y;NS6;EYzb^8IqKo?18mpG!brqhk(#yRGU1Goh#`zA0LV*P~c{{)Q2S;Ik; z3|&Pkb0#m-UaMxx>Sdh_s0WU4JzC*%S!C-jemIdjDqJ95r#5-@{a4@>>ipP$Bq!eg zFQVoD6#6p#FW|EOw%Gljxou{DHfXQ3CPh_#iHcaFoBVULrvJ@qIY^2~7(kxtCX{CL zCu@s#pzk1xp3lIDFhOMdi=BjwFCAl!rUWHCqGiIxY&QFbdnd!$tncUh9kw5%kygS; z<}+pt5DD3ksdC2<`x`G}#<;<=aNiP#HeKP4CiWNEz6(={k=BSaDm_NJD6x1Dvq+=d zZjbrAQ|wTW=EkGXHFNY_*LJF5>Wp^+wnv+a6YdU0hM?nMJ#AQ4?py+LXHaGTqC zkxcrdJBwU>v1z#1OeI(doFSSe={#Mc$>KfAo82IOF~hacX>i7b>w!NF?a6&&YmX4q z6mjnQ*n_kF_vE}}^2TwjC*3p zlr**zbCoYzVD$5zZ<)OZ61p}ZEP13+59I%F(+W>l9(2lO?cw07PFS4Rgp)$o_!1`CFi#pTsw(eJ6ns;Sy7R34}c&w~dz~5(0MFt_66ee6{j| z(}|Kftcj^YLLY%E?-3(EE95Xx;TGz^3tPDmmm9^J1=mM1e8rYzlPc=~zPf7!6CdG_ zQ`>}Ef8h}LE5$9!ctXyDr{}4qPt#IDEj)SGePED;M6l~7VsVKCb=CnMEl!QV_*Hw0 zEGUg6O3cOF%8R!1G~Gn+e6^Rl67TH+WJ*Pf67jcKgAN@0{Sp?e43SlaOh|87rzF}) zdpGd^;VNWI4WRw{*Iy?8gmnM?3jUuxCiwrW$NoPwbUt!jP=f*p*{VsezxW53EO~|( z)Phwah2B}|?npY4q^HL;Ux9s--S0p*jY2cFFrU9XdV#7Lq8K6=NPoEw)e;6fW|m4G z$EdBWV+&^6ac`kJ-(iqz55Ah<)1~Fmh17FErDYt(xI&P(w5w$iT@3!EwclhiG}bM6 zoqbbPv8$TQ)KcBlS*ctSTdm+n4faqklwu26&$IugB0=yxE#<%EHw1ErL-^(xoVWi? z9LF2o_n!(;{Pi+y`gi}A|JMJm(Ent_GX5_r^j{QjRToPe=l}XTwP-;a;Fv!7*_$;s zt=TNFh$qb`da|#P!1fSYf)YafS_~$$l-9CbCEGCBn6X>iYDN)3uo4wi5GcqG^j8Bu zS}0{*-ybNT2=fQgqo9a{aM%C+v-2`@d1;er+~#-6_%OqM<8|Y6axQ8_A{;db(y_;rx(uXVWrjY6RteZCJ!$ZKlFUst} zEeArEB`(YbF8mFbPOG1Lgn}X*CQ4f3q&}+KJJo&lXdjw`h)yxbn6B~&QP8BV{Sq+^ zy2+g${=z#!z^Nf>XDqGVg0xRxCTw`KgiD|78s9;YSD#KyJ$#DK@hyM$Lw9K$f8k9E zofQ(`y(&t(N%ee-$k-`$Ql+~@7Q8sB-tk)G9TQb|6c+&)8#(1d*Pmk#pCS*g=Re!W zej`K2-_061Ld)SVc_`CumNZx$&I7!u<=7!7_R=QtPqkfmhZ!8oq1zr^ft;NT*Yejr z2%sPz{w7Uu7}+uM8CXUo^#-kt-67WZWoENvYuxR9@YaqH9#G?u&85MpWH3krI9W@f6LHdC6uevJ84HNO*n~aXZ;3d2Z3JeIt36+Rha!3;gt_Bl zG;ApUlT1rY#`IML=wC&fV#{B(-qJv%n*&FGP-wqBY9KmH7 z;OBq+`8g2AdU}nVhLP&|P}kX#333~Bd6;H0;8+){O(w3kP}8;tE&tY@omJQa1x{c0 z8;ql4M;Od3TYH|LmujvcJ;HwoGa7pgxn!~TFC+_Ox0Il2x3ZK~wE^o-LwF5Ik*QCG ze0}Q!ZO9 z#9-7`VQQ%zJyrghs{8I6oyWO_4HbSC$Y>qngpk3JiM-|PvKlMeNp1vRSiXIfB*OH4 zzhn#81tH&UBtLIxrD+B1;6sZqD8@Dv@^KoD0J;yP>dSk&?it62kCN;s$-BpLPhHz> zn`D463rZaj6#M!Er6<>$qR+@O)~+yg#2Vv>&k|Jy5^%X7<$Vd(d;Yku#+7}yB2ZDD z{gy6s*g5bi_i#Qk6N%jGhYOB1V_XmTJ>~8MlVxHi_9>`OQ@^o;4EIjltH56@q0wkCnym|genTq{E?_Vr2T)-3 z%cx>e6EFySQHYQ_TFe#eWTBY~t{UtpbVQKsAY6~P7R%B~+bfT@W&_gck&-kg_TVwk zD5YmvGq}fxUA(i=B4};3Ng!v?BWMr=F-fb@9>az?{G+(f;RjPbK|^il!ui=osy2x_ zW<~=7{OhYqZ*S?+bE_%67War@6(;QF`*^|AqJDvgInYN;ahbW%xbaQ?^YVZk1?dV5 z@ZEWRA>Bw?&(5vi8v0taAIzmLjgyN>2)Dm!JT6usfx7q>`LmoT2j66nNCwMM7QTsG zoH!A1a9-b|82_Kuut{MLH+W!uO%CnepQ#6CsP@|3gP7n7NMOTOa>Nv_Oc zNO&UtbxIHv5S2(3`%;YdGy{_F^Utfjjt!yqYO@uTIfuAGm$=~?L+Pac(P7LE+16?% zP*tsbkD*X$P31J<6M+mG;uG2KAR5Zpb{-vzMSW$%%%2zm3un$(nKy6($k>I2bh~ScpF#8$({733&b?;NpS35--~p({b0%(w^1DhCWQp5pWO_&e)Yq zq##b+w6k-ex?N=ZV?DGO*E?%uAks^DbY5qz2elMV2GcZRjY#m)0~A&o*XShzP55n; z`wX+|AG7$AZKwS_a56%?|t zC1pP@*teI!UDW_@nJ#ai758Pc(NKbsyIp{Hr30N+(-Omxx<4 zcAwx{BP~ZFN(k#W#pI*K8eU`qj7TtS zV&LK;#?~X|g7;nf_q^;r*|m#rj_iJUe)$i`cD{*uMq24gMVH5AZ-=IH$8NdCNjB{l{H2aLP15hu1hehPa;w)duKBvX0N9vp% z1Fe)n-vk=&wm*WyzSw?#$7wF#QCUBee#qlL*T;UpeX1oV^hV0kS}o)`HhC|h!EH5u zEG6#s?Y`UM5B-LZ`ao{ZDp1#E?u_?b11R)f;Qy)YWJ_BpZ`nDKN=yIbCpbO)ywbAw z)gUNea4+(lLUo~r=r5x#*H}n_Uy3`nqv|@IOOr?)rZc0fi9b~mtBy7(-P&=l2a53%G*373d(aNFfyu&M{Q9|oVfwFU; zPTAjAt=yDqQ94jdrD(C!n<_h-oUk*kXq>L0K~GMV(H{Pncm^8MNECv=P1hAk^A@PB zSyAn@7m!ur>kjilI_=7X!Pyy(CH)JN?;^szB4IK5uQE^k^n83yr#+&)=%) zJ4{(#o?R~P1eCAr-CU85vi$qd%o9`zjpTHl4e2-BIC*ipipj4E8G()Q93&r{mR4Q_ zn81ukNHiRNVv%|~t#`^QlO~>wU;&xEnX2?cl$e*EMJ#!pYO@JdD${h7 z;!m7dJg5F!+;Eq@(bUr1+1g%L>`t%uS)@KWi_0@>d&^;Eb8%^XX|Jiy)L6XXhKaY# zP_eJ2ncLy25%u?X$YvV14Za?^MMX>Bh0rXn4fg7b^mT_a1I^qRa>C2=&0!W$v!Ki_ z&O1$wnsSky+%S&=leK55)%3GTrX?0;+RXJYEgwL-gJAxXEwZl?K!=h)<#iZSP_)Ur zQs!+K6BoYy+WNx6jx)`&l-4WM=vxpVa^5A{dcHZ!BJEAU4+p{ppOX%BB`(m2AZ;lY zzGYiZH|u7pEv_xEZQP|Gpl@s~FRiX`tsQnZ?Xul9mcvrn;doA_>;}G1#@1!J#mU>_ zvvu20nwxseCw=S_qpKU!BftdL-#fq&t%vwyp;SMHzPW~W{_A3B@QaHWR7f?*61OrJ z84*IZOHsrIhCn!qIX9XA27A;d**gNxv66!Gslr<7jovr%4BRmbK1Iei9~@#MXmAEz z88z3)8@4juE|pZDB}_b8Uqf}A<~-x^Q{G$g=>wdEC=FvoeXt`7mOqvCmywK;XG+rQ zZnUHFZ(JkvZ{H>R-+5x06%`!cHjPe^Nq-Cfk;+VqL>QoU{5$w9E2&B|(ByrfY@qux z_Fs!8*oojmE3c|NLy7iy#Za;x)G#j4n2l+3x$*~KK0wV_F70e=&$L&-!zQ*i7navn zHWvU9V`3(>m;@z>!S6Nlar;U6kCBhDkxH*nR{Tdug$OD$&MnK781KU;zEkoBn9Z2s zk+JJEFC{a!p_qZh7bdQfP&A}JTBfV77VYXwNylTNrP&l91YA%Ty0)U7We$b&EPgBs zij;od$FXFT)08wr;l_*Uq2tbGHP@;5T#5xz#AKy|kTM#7Z34<2BY_pm20fgNL9d&N z6%O!`)rv_~FUIorAU|KXvMM$uoX?;#g+-t|M65#+#92hz=?6E(PpKZI)ekH=uPt&Z zhPb7?`*dyi3&PLVMNT806*+mImW{?(Bmn+r@q0@oOv zo;@X|MaB5VmyAwW@EL)@R>X`HlGBW6i?S{PiRsi44LFcSP+K-v@&a3dA7vy>d8r?t z(G#Kg?!Ts;Ziti5RMU8+G>s3>aZ9R=w~O5QtQgXW-QYDl;Uix%G0e!HbBQxLaQ3&v zJ(_pO){k7Mw?aS6?{*+5&{+W>lwlipBp9nnOrUUrtl~_&C_|W#6Bsa?P>*?Fpnsx` zci}eefZD+LJcppiHsk32a zxVCE_@CtZJ!zlElp$^N3w6#3bq3{beT{AnWiWrI>-KZWcLNKS!aqz^S45{uppqQ;X zUrhab)QeYnGP$HiARTEz7z^!358B zk!iS(Z~4z6SIv?Ps-HjPGOQxE>32LN6`T3by|X6=Dj(l|Z6P@H+aWvD7e!t1{D2;tfMjg zt#T#>OutDMlLrP4KcEGJsU2^Xb<;YDQ>SPk#c8Di_Q;_y(5huq+fFMMD&?zzi!j@R zK!6ARat723+5()uSV&LAv^yQ`KyN4|QI&oi#gJLZM<~0+fts)rQ{mEhK@zG$WIc&V zE_)}$7IWWw(4^HBr>TTJilH3{M3+MwCV8DjAg$%{ec5)5}=xgm_}(h&B! zKJ~sM!0h2nWhSOMdoCY*Gpl25eF|wqPpcu#>qt*6%c~;Qi_^*sdx!!oSt0W7dbQn$ z4Cc{mk*Z9kiMmWDM~qWTvx#H|Ws#7n2iIZ=9s1w>o z3h{p~AdE7l3Dj#ff)~aZo{)kZ=12$VNF+a-A{jZrNsR3OIwiyjPhOCd?rwQ9yomu8 z!qo5^oFpHrR8^}WRFQP(iRTD{!Y{hJ=dMDrlB;x^I7z9%joX%bdVW^_h{7d2Opcxm zSG-)SMA?=8m?_%PtU)iE(>>iP($#Td_=tg4v-@FmZk}dWTvcU*T1}{u9Q2J3;?ON` z+BWa+bpy>V%&@@z*Wn?&pq083q8~3m7e!C<77M^iZMDD!QoIn+Vq)m5HN8}d!RC5(-0^sa# z%=wOp6fNVFb55cyoZ9)gh=;m zX;{tPXt5_s)j&F2SS^yrO1M}%+yxpicY0C^Q9GtfFnLduO7oD4TY3aJYofO+P7#Dp ziq3CF&EI4o+!rs=WTM*d^q4rUGgvFKtqCdASFE2A3_?J^T0z+p(kN}nN{tckJZ3?P zV~!eLH!7xv{jd%cTI4d>a97PE%=w9vz3;K{ZAGJIC8Kr;)6K&PTDFc+-o)r|jsnvS z1Fi=QS|>NyFFnS13-z^bvU{NrTc6WJt4L2RY(s%nnWK=MJ~5GE-O;=<&y0i zyY9ca-03VUI=iHpg~SeK4n~t!;e;c{$2~r;RFa2j*a?vQ0{AmXNMTw^adxC6QK)AK zk4*AVsUHhtKv#%qij+~LEETv{K)lRIv0f=zS+HN$U)`o$^9 zf?YGc7oms|XU_3YDAYqE&`Y+zXgQo{JA9$x{4#<3MDoOSpb@t>C?-i^6zcXX?MoMP zZb0DzScaObOkCI|o3C1?bZ<-j8)6MB{`Gp*;eB`|%%d9(O7cx9Elc^?c1;J1r*&jO zWq=(9sZ~c}jrWhP86|Fwb0FypWwSGUH0hHp-VYG&3hfYU)~EF{v5Gg2PHoH31qkys zv!bs4!Y%`xEwcG9@~^4ljkqpMr3fzW<;uF z4=oD*tZ&&LMr-e)QPi7n>AT}ES%mK$k>Cx1R~zoVmuPZt;@>;J1|i5uKmR%g@5CaH zijXl=lkG|SE20QG_k@-E*s87(B9Y2voW}MXg_R#5xK4tcJO!sqi}aOsOJPphPn3Md zno-p$LS8#3^J_dsZ`i~i0l=%OCHLlzV9+3GL7%d7leO6bD9Oz;87;7nMPMRT@C%)> zCi`l$z8FEwb5G+KdwQkCBKae(#o0!VTrpRL&<~esJI${Up4@Tta_Fd%N2XI06Do9b!RM{<-*y0f!qgLIxVipFL2EneV<&(k zA~3p?ari9_os>$H4vp!}9?~KK9ylCet_?$VU#keuCO%bBm2O%XC6*yx)G-A`m9Qa0 zG@k*zAZ_Pr(ZPq&kfo7AZ9`IhMKKo2urf!bI#<|v`RP!#i=g)jVTW_6+AhA(5(pXE zz-mqckX%^t9T?qjFkR`VCF8uHD2IKV9F+J*M=8{0n4%Tx+DEfLUnVhxl%}fXQSi)Q zt9Z_&qPT0spMr-{F?H_Zn$k2+iKLP%PVa)nc7oE zvvuK^9exD60B7kDbUJ*H+J>3~S7E4uhm_$7j9QLJrC!u55HoNurocUHL3^CJ6jiR= z6YRMxT_N8C^Y4>C$UzQUuLC3UD9zUn57G& zKqPzva=@z{=D94$sRgCG+@&?+Z$`+Hdzy+Eu#I9ilo>)YM-r_$(g(h3aV&fup zO^39tn`e({*^0KC=U1?s)@+lksveLilq%nuPcT#^UV+Y#UO~vSwq=0~O5ET&oKorA zp!))tzXW!uF7}Oy+1)c1d<6LTBM>njc=yqfSY8ookwuk<|7_Qp^1g-%HB=tofyUvd z@t`nQWXo+uY~{U?hJPK75AyWy-^Z$`TzB%_;xz{>@mDy%qMIx8rWm}G2aQdLiwk*_ zZu}$RiR!(92M+D-D_-W~-$^6O^+UOCO5!SC7GusqA2FW<-wWSS-_fq)fR7A62{nEx+MHBt@6BcK>?nyX zsf;e(bTUmg2ZTBu%_6Ih`71ym$dtskm2hq63gF5M;mQl*&I#ep{o4xT()Um41&4hF z(<%Ew)xC4#D)L@TaBI{Qntis& zg^~Zypot$NwEu_X3Au72Nyqjx4KWKFOgtUpg^{lGGc6W*;ozkOkPd~C${S4}Yuxj` zfk+3G?Q+n7fu{<^P3c@xCbxk=;RzCzb!z6?ByrA7AF_)Q@g}FlBxMpOr?9kn z-zBI_)}lIvs1HIjL(5u_bqi7*g48F>ElI0oGkZ}j9^Lv`b9qZ>w@Rm9>3d8ANwGmDRIh!}}~0ZUMU+VH9oeaItIbqOG3ok)q}@(2&uPgkcb z$IK}HqcF>xAQu3J?q=3YZ@2XQc3fZDu`ZhwzI!|!I$^5qj*I#@p6;I6T21pjgyY;$ z7F%cFGjJ)`%h%yM|9_B6w@kQYZ5$w=XzBkaa``{8U55V!a{1rXd+-t_0B>rZb-hKxiZb)SB3$4l1^?}^{+ zTi!#?&HW=eJinO8!>}j%Oz}>8dDM4M7`wZBQdpad=Z2`9r+C>P=QCc<9nrp$oeqjH zzWFoZ+&6jjj0#8FJ|I6kjm#_x2H)h)5p`nrpfC}{F0XR8NVRt$$oKT1P!q*Tr!`f1(pjDaw(^_H zSl5ps_jg@1*+CcRgac1{^axl7D8PcFw~#$uA{aRk=e~ge>Ch%tgm|JP&}O?5Ht>?# zXvd;NyUV_dnYHd_ta1(04Gx%~`%)5ph(0uAxR+)cUyp3*cGg+tIMcjLZX?w8@eE@d{cr21zy+}=>_2s=J_S8Xe*G- zV+^#}%3E#OU3=^e{KIgo|KCJXp@tm+Bkh;&l8^+E@_4(=W`C`8GsK1|4%;ba0)%5bAUyA@vT21`=4_%q{LsQ`V6fiOc>%AwoJaQ z*An<*!?;L5b#^!uW|D>d7qjjhjPuYLTEB*hSvP{XgIGZ)B^PojO1#LR_9GIk5ai{8F$GO7S z-#UUrLlP7DqePP4B489YaCBdh^jkqN!W($#u3{r z1!VKFj-+A3*m5GOLe8vAL)_D~OZPAyI-O=N;SwdcdK4bfp|a>T$c4E5J8B_9cc#Qg ztGrlJ{$m4Vq58@fSGbHOGfLbgfYQTXVrIjt(?ijE0PpA|*zZ=JnzA{dQgN^wnv{Lr zD04BPAp+5M!niJ z2(a;FXi!#oK`cdWa3q~Z4X!=|+uJNe4H8RD`6D*FbnHG!wSN}B9*uQbIz^FT+eMo+ z0>$jRS!ZZd2Q7^-x2{Veey8e-Q?NOU*RfVissxRSpqqDzMrmA^mYq?uZ;7=*Tj2zC ztg?G*?I-+8tL4Ci)Qr|8JO`53k9}0=da2xCmoZQeh^ra*E(8cmY1i}j%s^%GuX8(@*H~Xg z>t_1OqMr~-4`a1i6bZ6lnPaEL2GMH5#b=ZGEAzrpK5&Fyb)Gsb;)dhkmYKUW{FPOY zq;D4`Ke<(%9;RPJwc`>b_jnDV`@5HMx}TNi;jXH1fw9)Ymx*zD6E~7n-uV@c1&=Z} z3W19oZGSlhMvEieTSO=>oD+Qsqpd)THI&tuk}!t2t*BNo1V#21jACK0>jB(of4I&U z34?MRaW)JslC)>5GvKuPh9O0CdhwhGma#yb<5s7tB-LG~{b_%p^b)JsA>pLZVB zLbIu(>ELsQwyIOj%}x*X-+UWP_wj9DZFoH@v@O{I`MLS|mhRfQ=-xcBjp|}MY*F}J zCP4ZDMUmNaMv~R-q5%DlZWU`y75&OC!XBHU*Cw0px77H(q3!+|pHlRKo}Jd(T0=)q zQIqVvN8aoax|t>3?(Q1#WFnFp7_y|CV>_4QKYE&G^L>~-6 z87xL#;_F2sX2!ZBZrh=FWJ1-WB~E1NHS=Q@xZ448giQb#?e`LI?we%IvM-q{K;~`4 z857d3gF!F6%k!TFG?#anBu;;bn0|7eC~LH=Nt=C1l*17l8bE*EjHqjuO!m9bb|}e? zr|Ezlg86i>n)!7j6jPS!f`HsC;@$@@?*zeed!De-lxhpal(51De9gU~Kt=CKK?G!? z?5Y{GswUE_LSE>+r2I2Ru@7=MA|-8{)ltf%Uv|M?rzgpeF{*d^*G8cJXwt<4KG6rE zlL<%<`rj?`068`^s{D>-Y;{XfIm%Zi=+2j z73W|bw$Hoj9&Ge5$~lk{fl6#9kiKnh!%uA~ z{2+e0r$L?ZQWd;Z1o}dc_Z6AF15JDuuozM%t1D3I%C7Wd;ExXh93-&HrmYw?&k92x zS#>PqHN^cS^}~Amn4CA$JN~jP5hUdIshRZ}WUg7Ib4HZn6fXRbOY;M7D<{MEp+i1` z2^Fmkia7`8q(VZ_qRW|{*_fW;M3vM`E~qUoc$-=R7^I^bwccS-;ENdO29UF4{DvFv z5oEXO+()1#WpD_eUh3wa;L72t3&EN*gDMReZxsuU<+>r$mrV z4^fU-G-cW>C={`zU|`ENIrxx%_~B=j%-ro*hm?tjlo57qtm`+ha7JQ{KJ=)b-c5de zI&C6C>0BXv$o1^`NC2mY@{lTu!zs#hyc1zTTSQvqOMT8FMv>&dH7+GD#+2?@qcmeJ z-f&e8<7wtUBn0c^UJ7@A+Je1mAv@s4%fSOZK90E2drhbs(YL>`QDGHhj^8rd#w|<_ zsW?VoWggKs+=Q1f%A27Wu`)nV$Y+a_a^R>&!bw}LPzJk_2|=VgCyAtoHQwUttf^XY zTY_hQ=sIjG4KO-C%wv9T6<+Rkk1Ki*;_@e)*&hez)lC;WBoDqNees|XLv5gO_mIva zkry`HEIn)!yZjXveh|`unsOt=>Ozc}LWr5F5V|aQ+m~LV>5blOH_`xeAQ0nJ=o%Vd zHuNY6+NyY^N%k;Q_b{B+$wF+{ICV>!hH$KFB8OIkm;AuQwB+|_C~6#5++Ri1>bY66 zP7%IL4AImP&wM4j?93$#wdyXB@($JGDpo<|d3FePzB))4Wxe0*#%w8U3D`WN{$oeFk~u1@fi$-}yf{d#B(| z!gyVGV%xTDCllM|#I|i`V%yflww?TA+qRRPwbnVc&fXWhR-LM^`l9dp>*}uVr+)AA zLhL*jDqI#)-|~raA()%^hZ2J|Nh!qyOksn&qy&1V{wydLIq(IG)ja%sDSsayObrE@ zygEejUr&_1{4#n>6277XjLRO1R`Aap3(9zFI_3Ja@u18=z`ow92bW^- zRpM})1^%YMAg9rhmcP+9yhvJ+>G`5wvr5s zt!3C>fdWFN_e)t!?&nAA;*TldLu;sxmShJ@QWo{>$)=Y06-(n~ax`HrB?HDuv>5MRa+HUQ`-FQ69R!P-FBYm0Z8v9Yk#{XwK=7>AM%hFEuUmjW|^jhM^sYJ z(wIrJF=u2`B=5znWyG!io`Cdweo#J=m+f(pVu3$ie$6PYSC``5KhH! zhLEi*!+I4c63X-*E7y~U)>Sz$O9t-pjtinpdMt(4XxWP)xeKNRKs0DLTm(1@fb5#_ z7a1~D+6Y7E71szo3YKk!mi!`8s z)=EQhU;5*5YOqOKf#l!*)W4P6GA!H%YQ4&TcZ5kbd0Di(5R!~q5WvIw2-An8efD5fL=m`zYAuRd`cKh6tWo8+5lY2wGQGToC7-3gklZ$m%{n%yRcfKrY7}C z=hf9s`Luc!rCEX=IpcT*J=PLgRo^4Xtg1Yt`Kg-b9sP6iWJ|X2m9MMjPY%T;-tXrL z=no>qywKZogRb^xKY>-vDQMr!s6OW#PW%#ltjZ&5OLei@QEi> zKcglLuT6)xa-wFRzA-Dr>+(>%z66nWD;8*=cKJ>gK_8_9SgyCNDkBHs)_4_ zt>!~ztGxLXt7q~d=($?P#sdqMUAHH?I=jasZVq>-v)4#+4M|xa;$}~mkB`|fpO;LHXtcpQL+?jpP zsB64PC$?2dzx)hHc1(t1`1~zAC{3!R@mBq2^mvY#iF{#wDN__5#Yqv?kEMpKb!jDW z+}h;ns<06`qPY5M{i&D?+qDA1g)2>LefLZK`v+q zIkiEG6O*P(tnb)=`j8;g(oFglwK@*^(b;JuGC>@>N6ovo_@Hq3KydhAaQGw)zQ=3$ zEwgztbNT_mUBB}F#Iu$)&F-kqBY6>}TFhn%2HgW#DIp+eWf&Eiv3#@f4x!?9Nk?yp zM{k@EcSW`Iy~cz>u_9ropiLSg5^9xdZ14kM8O%t8y-XpuvEyND(~RBOc(Ayc$$WT; zvGlM|u)dP@SlHMy!=1n_=sdR=aB(Wey4M0%D^9mhTqc^^(EYw+NOFl9U8W=hM2f6#N+yN=ef3dr4 zrFGl+ADcYRF#tR@REcud5h1SC29|EGxD1#~v?=LkwxBaOHM)UR42MChR{4cGc)@=V zgrHZP$W%5CnpZ_7#mv;qb$a^H`}_70$6x&BSaA@K=1NPEt}xikWTXER89zzEs7$7{ zid-miHoPx@TME;$%YS!I(ocEJ8CSW?Tuf2PXY{7E`eF9?+MN^Gw`|x5jp8dUbFP`8 zP{aOG;F?10eij#!o@e9abm>k&Pua1jZl zunld%TI~rwm8xr+Qiorq9DXQjG^OE=!F-=C*Z$0m0lrwOzlk9 zifgiiQoGI{4kOci7JnK5G|(^)(AtBOKa8k43Lg=!sIuZw&oDUu{!;=58^R^?-V>|c zWL;QVvx@-F#U>rVCA1b5{q;Msgl<7w{WjC5_*i7*6GP1z#Og5KNsGzfxjZwI z-s!<{z2bzCkj81G!Gy#hphcikE5DH9pbI$DWfBa?Sqx132W+c5v@6w$ZCk3ra`ijv z(5w{6_3H{&QmW72>o#3m)XH=(+pViRqGF-1xSrpcMIwPW$zG?pj`^p5%#>bw+sY%p zFPQ$|mOrZGCv*cOe6$-9pjeN8GhrjQ!3gvhsp%A89~!;#-Y-<}kdFw!zT`VpK;M+O z@-UBo{mp!S1lV3Tfe42yG&`aUdUv}foqIz99=A>mU#nq%c2e;_q7YQ;i=~=BD#Krs z{nbS$Yr#6n2ZDs~kZ*8+YNI~3p&#vlw-9ei{I|!B{4j1(V84ZX4G4n1QE$Aky6GzY z;&yqMKNx_%>2~};aglCn{GUNP8FoP09tlGBg@MEmZ;XKX9cO%vqdsgN5xvvo4~Py2 zfNhiFKLcvFJT2 z(+io>bxpEDnuP33x$0OGZlg%*_%h%ORla`q=zkCT|*5oVVSWeOjiDS&E%9{SmjoC8A=&O zO>&XV?>Sp)(ylU<`q*&ijKk>|ZVj7PQDDfIu2AQgb0|79PC9knx`!bNFkYNeo-K+QFLp{^O9L*2`d z7+0TK^J4rVu!?k%&=`_4$V-1h3``g~18s1}2eGqV|un1|>x5Ir=!t2~lM)&&(aGz@2nXT;g{Dy>KUa+)7%pgoa6Ao0FA1dIv ziDM${crEQ=k+661KY4nCJcv|m^MPYn(z&yI!ysT4!#w4ZLgp@^UK4Y+vZPSV)?g~y z_-YeyxMIiti*F-t=CZ)hIxxUfU|1-QF#vK}>AYze4lJ_r4^nA@Msw6ec^EYuwqzls z>^H&O6oVz6p#oaA(QF&*+V74H*Cw4WUTmWsN30s;xP-R*@{L|>EIq0`?cW)2;zkx( zg8SubzjZEJ<$5vfqXTMp$U!ulDZwlP1EyXo0-EaA$U14jbcphVe~b010uwuGNo-vJ z-TL|0KUUA$2N;zb{uwc=WbB5Ao0OyiY zZdZ5voAXF)ED4bxc)jen2d)N~z{p7jeCEE0B)T;7?L)J3L>LE^raU&oxi1vy-={Az zo4M+WouRB_jZ>n>n$k_sOIRd{+yelw-BnBbT>Y zI20E?l3rcw!&Eq>mtGGm@5`&4Mzv;-uRvdivoQUhCGZ1dxl_Gl`I~tPviQ_0nPDU< zsbMUQ7&XZ*pZ3?G6bN=@{psS0qt1uBFpK#9r8Nj!T6)jN2En)1DQ~?vgtcnKn84mtzg)KS@4J282Huv0}^W z>`kge#51<|Fv%M2wj)wj;1M<_)Lz)BPkF2Z_*rLt(!{ohh93B6^WIm1dH!YK_hNf0 zXdALwZTUyM5Z4^y$OyB2LHoh=oW%6Z$&oIkt{@jtdAJvspEtVjUX1@SmF9fCP2KY> z*(e+I-snxj;JA~ca7t;gu6a#ySrNot%TV=F9BSb=L)yOB7;;&PJ|7pG2(fxbt6`Uc zm5c3{77$|M3w2xzi+^ZU6EKFNF4GFhY^u;xxkQRUJXaZ!ZMq^5NH3EZHoeFz$UtS9fg-cevY%BZrlS` zxeILzdd5}8c&f8tH5iFLDm=#CiWr+7d7Kv6q^s%zW+b^fDGDI?6fcY^R9hJ18&xhd zQ^WzSs5nCH7qp1#ms6#hDq%rewxyxa6~AAoIwD@!9W1T9hi3Z}S^mb2Ot3v@v*eH>$ayXxM-*=6ryuWca?8yGx;GyzH{Pe6|c|Uz9TL}%`)5^#~MvjOI z0S0}25)@C#8_kEebvFM5gBh00lBRK9NxvO-$q1~*@!RW0>f6mKP>m+VF+hFR_>>UH zG+xtFXYy-5Hl>e}eYNA_^SbW1XC~(xsNz%@{-Q8VZiF$GUx=n>1dTU_dirHNBFS-= z`*7Iwu#a6e_&o`MCz&9Y8U#XxNpJVIvI5nvjL2O)dAAH(N>5d;P=zX5vBWjh*SEq$ zXRf3Wzi zWq?a(@)+%WOd9l!iD@vnf#A_Y1{vVs4->^U58;97&@I`1#yWaZia9~~4@?!r>ci^a zDfm_kM4~XreAe!L89D^?KLG>@tCb*_2V5R~#qi3Fq->>`5=d<}uhJoaLIGYa0Y>v^ zUTOb^rj#V{_~;9&*0l`36*1^jZEr%o-leM81y?FCeCS>14+Mc9p6 zQ^OX^K_g3a2ssq^au0XuspC9N5&Wh!U`r?nIU3bUY4ZXtsc1{CDdkjvV^d&_LT({_ zQ$jtpP_DX-b9E#Dt|Hr3mFX??EU&sE@k&ki0R*kIQ%hRD4D?gRW&WO8G)yG}zS89( zW*mT&Op}Bv37+!4El=m#<`o4CAE!onw_{_S>L~;C0snlq1JncsF&+l-(PUZL=dhBArlGggHvvy3%Y7y5|O{#=Lwn66D%L+o? z6NUF!&RGhsYzO~$*oN7lA9<&&ADXvcx}shWeI%QX*?OyGlv~aZAb)t(`DZ>I`4mKRhJ#(V;#40@kg;oj}HohSexg_CTVbbr1GM^D1;PUI7-xxI% zVy@$oy>u6%df}R^Tw}(R;*#9Jh?B)|idmYS?C3p`+v0T3ASe)vHRrBJZJ&n*wobW& zAe=23a_Y@*lhc2Be{=cfX-6UE^vP{%P4<(t-`?CqJTBkH*?KkCk-$mB>=|^h)tb@% z5lIk_azm{-PLUjW)uJ0%Q+OHOa8Wv=I7v2g0vkb%g&np2hJ$;8}`F|6AL| z|Euvyj+Xs#iok~a`KVOuqv!R9S%x1Xc>$ppSwQ(~WKJ`Wb*h4J+z;YT$+S0}4JGNm zdpL3L;`d8}DI8HW9O}0356wVjKeIvOI>XA#-JY-_#+K~NTM5)aF^ifS{knbjyK*o; z(W7d~gJ@<}a#qq7nCcmKE|oUtQu3RDtP(I}P?M9+R5g462+^yzf?9`+O{^I^o8Tvu z+;E`H4vws3xMe<-^TcT5lhlh&o!_BwxZ$^h6zA9 z9T9UD*Wi<$K8}A66oA_!EFluRg}=r2LFR}SSSa=W_}L2xNGY6DhvuKXf%xC{=KmJ~ zb#yfFU=~rbbNg=w`d?IPNYlevdolgHrkP^w4qZGVTY?A*(RyO2E>PCmh+JKSrc}-vvPtR}^k@mq&K@r`B4k9On_g zWuT|kBHCdFX*Mz8&#{?k2`+L7(-{}mzrd~--B zur-l-ZSG89_gNzrmgOwqGb4F_`p$drpNL-+mi55M*H4Xmv>1y%YxFSV?UBVGk2;(9 z@j@DXe+Z@L7(63THK&aI`CDO3f)x#BghND`q|VsTCr>!8RZGFZi3A^ax;x#gho4BY_clOO${FxBAUtumbA#SN$7iFd5*mw zE{hX)BGM?NFmg_`q_ig`J8@Y)OFDKH+%>FtXhBo_!3`tmGW^eg42|VJCq-6;jdXFp z*9TtTL5)5u?lp9&a^2=sU{!L!FKL(Jgbr@QfjLkR|0f`GM9E>6fru>4xm8ss z1-s5F>hiOWOIKO5CBN$b5elZNO*`gt@%}=L7>^Y{XbZ^>@MDnxce_9kH0@`mwVO63 z-;B>j83?@CDd$Ua#IJtBqzJdNOoz5cR1_MI=h|7y2Wh>^#Zg3&k5bYST|Y92aO?B9OfFFfn9U@n5eDW4N2TFu*Mbl z>thp-bev&CHKN#~bDZYxodKdGNv?{a3=B8>QO-)UXe8pP?I&<=$x*(tc9sw50t;%r0#-F#Zq;~HWKVmbzPo^ zdTb<7CBmGf2{G4g)v$MPO!74a^P4LfE8!E_#nlcOlAhvJfD#a>UAZx<^LRKG%Lved2VO(>AQ*!%$UvspLW1i zS{`p8jsNIa^_|k`94{#YY;Cr6TV)e&Pfph3QvgqU(?(sG<6wr@Wj!6-Oxtsl;}yAq zcS#t=&Ph%hQdxEXmV(3D>}T!Mdj*t5)=9X(y^C6b2$6vUJ$Dhy)I9~at=)-%*2^K742>qX9eb5B{>;Nm+X8zgH_X;+=jJ0UYm zqA0enXPP`n$Rfn&5`b}3Kf=gJ{EK zfa0I7fb>p`K#z;HWc&ii*?K324;|E!ElpyIMMPK#m~lAuy!H!_16MxShya;SuLuyWwoy)xFV^w~GgrZ>ZLbx91WiFZ6YtxU$Hs0IfS z%CQ~s#HeAX%9l+gjQqD9+Cr7G)0PNblqAf$;}rlMlThuJ)o9cmp?0mS;+%BR6&r7q zl{MmR`YjSPWTV&s#%pEquf2LJsBz)A`Hf;D1%&mOvduHP)Pb6p-4rd1-?MU!Bc!fL zKfwG~hDiRl>pyl8Cn_=gHK6sOQz7h7w!~RC3fNoCv)}S_q86AWL5n0BbvO-PWFXbQ z?lGDT|wdctXDCOqRpAoyuyZQgN7vYgyQwjB=5i9IEgUHNq8H$aWZ&ebVs;L_htRb^!}20C+HQ9XYb87hXW_mQB;2+s(O zhE^HP+FwXyJAlI*gBrKMus!!^{<(MLx$hI?-%Zd>Mc57#!hkk@fz|ELOl2BqqpstA zzI+e?gxa#<(4zldsR?So#K1I683YMWy?j_>cCrC=icupziMOl*flVAO#yq(@{kl89 zTnGA>nd0R0o}IEUV8c%o0B$C+#^lchgq9Nkm=W4M{=Igew@V7?4mA4*)PezMFv|ZH zSHkP?JGyZyveApM9MbN}2yi3`@Rq@5S=MJNYiOqvSa5F7V08-Gw1JT1A=S2>5X=}+ zVN&*O>5@A>(|tuYu1zrJ`H-D17zTC{&hLnG`)PGm;oJ;yS<%pFApvMGs)fs5t7sfz z9fG|PQ4C+S`U)f4W=p+*JMO=Mhrh7t_dxa9864T%0j?1rOMmb45Z>q_zEcdFQ`}hi!QfJ{Lgcb?WABeJP8?=7 zRUDFz3M-Peb4nuh8jd09AfxB|jr1Oe3wv%&w|iGRyUWQO>J^A(O3}wHw}aO+s`262 zTcXM2af`rn*F%*oR6~^c9d-}$HQRHh8m6vYv}0!rm~c8z4~U#0_+#C&=-r(wI3f%I zB2Z}IN?OF@Cx%R^8AH5UWJk&!l%Rs$}i)#G5$RDV=OIC5`gK&D~f{COPX0mqJY=HAzE?>(DUTMS^s)(DA^D?bS zsT>Mlps8%^yeWyC^rOQ3WY{RZ&v%~%6V7DBsuEfQmdmWxDj1T7`?I9u?bOAxyz?1C zX|{*WbUMDv5#=TG-S2WmJCelWC5~Ob-uNhutQ$vMPX!K@T^ps4mNLbOrL{XpSv4(! zF9j&p^w;lEur?i-@kp<$#AX_k1)3SBqD# zVT4)#NeeuufDAjmO~^mkQ!-#^+c^1@0M%oTX2sj~zzu(aPgJ@ZH3{o$Aq{Mq;5DZJ z227T`*YZi#0fn;-D{DgtX0Ter9;dYxPiF&&-WCF*1>kwhmfVsa=EH2a{OkL%*HE-t zkE*Rs!fgERAK2#Lwgf&q00S03@S!CEV%R$<;I#$(DB7&odye$zu+)HlX2`29nRG)y zsBg=lw*L?_ZZA5EawP0&86GN$BZPvZJSe zQmQtL|J|7dC0Cmn92Q8beRyb4&6ou1_R$L{q{XS1b_B|e&J!8~2jfBzQT!fdAw1A* z?PakK*dP5x;RJb0DTGcVbcRNx{j=aWb`(?Msw4k%c|f&!ET#WqQplwvpHN{EeEs*b z@glY>xFpC)(e2PIb7K@dOtW*K8a!;JalX80tP25ujbENiDKd42pU`%UwE$SlDfMPVCw zVf)wFdL#C8llv8F>4LoA#NWZ09ZR&b_N% z2Fn-B5e`n|&d^}9T$!5;R+^62iP!zF?SOl}*4KARXM#MO7ew2yT*hMv#^d+!_ir`Z zE$g(Ts4QEh=#+xd%XgZQ&nfCFKLn@`j}@<{)?DLa@`*@wWCMjlKo2?GjPZwc`)+DI z;VnkoEfO6wR0VVTs2%gX)&|clF6*jFQ!Ufq>6=uVmo8}E+Q>USupafkYt z?-NzHR#zt&DCU&_G8ji6=GN*DE2qt!0@&O1@~!*d|A{Vm$YJS~5r6%fCi}l(o&O2! zQnoj6bTSdMFtIjPGco#U{QWO((WUht<*set(;MkB%veOfkxA1bfdh<9g&-vc5esO6 zz#D!+>HiKPVu|ZBCYK{eau62%(vzXxT=MgO0QO} ztLOIiJ>B&@nVn9XNO(OG%X7Tt)$P=M{e5|Sr2XyvAxT_;#L-dqdqt;F)7%4d^>xoa z5*LFjIML40LkNGn{l(BJ!h82<4(r1Z`49PhaW7TL&3-w(XHVL2s!%uTZE@Nknd6D{ zS61Ok`$%MRs>7%-29wuD(SzGV+U`*dmir-E2lkoVsZ_2HYx+Oq*@k*KX$;gl1xoI^ ztnx2uqchi}9%z5i89mry(eH{wmo)~JKji9GM5BhdyfypfE$@fg-pr}wlT+_sny1N9 zB0MQ{k5MOd7YMQ4*Y7=?1C*p%ZwCmE2VY~icWNta-_jZ|sZ zQX$1qv;#Lk4aA>Wo@cJUCpw})xm?BjH;DurG7N9|7W=mJ&D2}lS(fI5UKjcLM3(o? z*m#Z7^E#VHbIcj%2oPYX35+~_yx!}un9nVPSBnkv)vm)zAYe2J}RO=8aDL6z6 zc2mA`ba&mo?A1APWNac`fR6}!hr4cPb50_EFAR~?ZbZ8T-kvpY>31^FwyYvw$qer8 zG;z8N(RfX%rpEYjDSt)Q1usz47ded#lJw5s3B~8wC)r3Vn7CF-w>yca^AJ-eD8c@= zy0y<$G57>csk2w)Z;o@!;pwc!Xxxpn<=mnLOK!x7X&ZTBB4>3C3vdvs7-H&$r!n_U zVGV4Y=vN13l7uj-8g=DR5Q4_Mb$#8p+*roClKnmBBUh&yC%^-nmiAhc9p0U8zZ%Ro zxlqHmD^iH%I9*+qr9WGqi&=c?s>K)_*KQ?*_*XI!o2`*k+A@~3-=VZsLc#V|A>meE z_)!2OV#r&JMBYO__)+$g6X`>sxX*pJXsm=T-Tk3#SN~Gp@)!h z_UaV;%nY4nhRq}_b~&O@)5}${D)0L{`YTC5;uTh?xD_6En%jDKkWMebrR0JK7yCrw z<~2;7#(JB$H*gT#z~e!8Me~w)rdAdRWb=SmkWZuXI5m-?hmi%-Nn8C_ad08k+#m|Q zDiQ|?9a$j8>IEyyM2J$XM9yf^YkxmcauLrdxDzy>&W0R^ES-p6T+A(4rPSSzWEodv zzuKN}7w^-Rl@K#x=MIFKVR>1ONS7C=%l~r&J4SBdH;-)!>2MR?ZCyl*SyPFgYLP(; zhd)ulOq;oP$ZU+FO5r(&mBKr!6ne_XuIjNqxmQsjP5jIY1aA3gJ(bUT+M=s@N`(-2;r!OiE2}Ensxsa&a@it>b zoy?UnWQ`W|w=5lSp^3$3u9q67)e=DB=& zyTALk@nYdzfrMjVM%+w{k07K-kLad{KARZcC1m$JX%;V6lZ1!nNpXB44Z8nJTzH12 zOhOKjs=5l>P^yP?0e*RQb46HSVa1CYivRp~B84L_9AN~4c#bbieMFs&6T&$`5$40X z8Mmo-#t;bQ%%zmPy{RT5i#W2-bdwc#xd+1<;%`QgLQ90&!wg^i=Wd(<+OET8T?I_? zLa=qgmr65I;~wg$ERBW}b%B2Q>TaR&Lh{-))hK>q}28y__}%7Z?S8qd8>zn%&QWwIKz=_ zkqu%>*EZ2o$Trb5&F)Z+cBu>3D87OTI^u`C%rD*FvWJ>feX;^2xs3Zhwr`M|XC*WD zz#XULrLB{6?V_>TB13vD;k!Z%fKS^uu&&@Q`@x}sBSl>o80boU(dX77w3U?Z!InR}6EL*X?s))dTJ(MBQ3}R4YM&{p z8s~W*=RsNd3DHxtpAmSv8f5iC>oK9Mr7w~5D_O?*BG$=IHd}}4@cR>P&<<<;c=6|e z?kA0^YKoQ3Y#mwLS&VkQ**jWvrHCFbK$u&$u3GmAS{l&i87fEXX>jWt9ejNTK~VPW z#K)D3XApxO_mHgnNXaXA*Hr3u$7!s!l3#ugG_}ODENbe$y&P%oE-s3Xf*PlbTW$FD zsTqxGLNvGoIz?FES^Wyu(R>pzzNGVGFiO1K#FiFVs-d)a#8hF{0rTm{9F)iY6y`&^ z387B70VWZnkzjQT0rzT}PhYMJ_;@tsBz@WnRO4gkQUvJ&@>XgbCUHJzP=0`ZBg-U# zZT&G-4-2|1D9Kzm%xeQM#-xVS`he_w=k71;AFVpuo9P?YVzWIj_5dl?)ABl)Tfsl&L8i9F9wK-G;)t^18OV;w~HU_4cJH*-E!6>y5hn zCc0Vt6#(bi$OzNZuNmb8$KUe1d|4IQcMUSr~U>3gR4BCak0 zDT~n&jYE>3tpVd%}C(nWOTs{}p`yiWEqoj)oa&^ zY9q%1J)?ol-uBRKrEA0=dLS-&?}<;=@yyA^?Jb;iPsx=igPI7kY#P_7fZqflUHjF> zAr)$RIzbsK1sCe>%thLysX?P!m0a=TfXaW2pm|yu(;SLF5Dw)DBvtG=wYh9V~?Y zDq>sct_=cZyT3jt zX}HPaZ>I5Ou1A6N607R`$?pTCj9mt86|-mHje4x7!h5JH@6I-CR-wXWGd=kCcD*Yx6dc%?xJj5B#^z^)TTF&dEEi+I{a6FqC>>){gSr|- zU9m^Abm$aWm85A_8p`tH9c7-Wjrp0k1bEqftI)h=T)2N;N;8_QT_!7vfW zaH&kL8&V=#6UfiMM7{Ob#+YREwOaO6@$H<@>R1KDp0M=xu)8M?Hy@%=@5|JhR&bg# zzo^@*MD4SRs>WUw*#s(%#239&W~rCO;o9^Vh5EI&Q_FT3+q(GEh86F4Pk6*kPDqMd z@kiGR7T2OKa!8!jl3Bsu<^IHfVrH8J{bFI`HWxQ{FQ%qCu`bJ*4dwyT1$sL^ePCm} zb7A~|<0j~devm~&Iog}LRN9@-Z;lOYsCYP`Vs}2dR@^Q zb$gyn00KU0|Vb(u0fkb@Z{=C7WXh1i0mu`8&WV0tD3H;m2J@qhbg z2xQUt0q@KAAGoaMayYsWQguMtHwcJcK_AZ2Iw*Y^v5JHBCeD~Ze&IlVkt6Tg<=?jK zK-vkvxalWdYk?wA_JM@%%mwCz9Wb zb?zH>?i+aN3%cYBeC`{5?i*-M{;Mb4c99E)Km5Q@exh33!ZrgZqO;2J+>8|FZ7)}} z8Bk8pTe~x_r8A${`Wes|O>WW@zr&&;Y=B|FQbS1YAstqh)m4v5#YyFF4LQi_7%n7D z$1F+28-Xvxik6~Fj@6Oo&W1_M_xBd#B;LRhi4Lz8YrjkspRBo_s1Ut;IK`TrX-1dz zk#p+YJ?+Q~zc7-h!doi!-$KJYe*fH}PcMH1;B0UFzsUEoh&1}M_Qe=%9L7%1tu*N>XHvgimSG8(PJBvT#>RB|J ze7gKc8lDD}#xD?Q_EsgFX2R_Z@*x57fcfOEW72RL>T}?v2$B1=MyabEMHd=hyE4VW ztoEPpnh_7n)(dA|lK2#>2|nu!@!5}^ZNU|Uxirrh9t zOKwR%(BHU*$r~cQ&UeOgH5n5(!!)GZ4Dn>qfi$i>E6`phjU?p@N_A-Kdi zBg4X(v`b;eHQgdjB3M21E%BFT95olE{+}6>m1XpmWwnalYv8$j6)Rx`kB;497#2<) zPUtZCSaa#c^k(N%uQP`~8R2A8_=^eL29iV?N|-5)I4KK{Ioe9?h=1^rdP34)9y?24 zd_--!mO0gEZndm*ZxoF3nkcgqTSF3&ha@GzDaaxd6BIdLskI2x_2Tt$nSCw}#gO@y z4Aak7cH*z6Etr(EvtxDhb{9W*rczUW`7i^i-F672gL|lu-s=H=rNHKV?Cy+>&{5d~ z%@RAHNrhIHYv>5G3^lR-(GmA`@J|Upw`gk(P>aN&qO~occW5{pPwf@#rdP%wu`sM# zK9R?>r{TLqo7j58S+OD4rGy))X?OIA7PgEo(+cuZ%f9nNJtR^%JMmF2c%}pCve^mE zoTyaxT3R!n$w13NZq*7CsiqgNbV28u+e%SKZzqf zpc*eLkZGP2=sm$&{BbwnrYBQ$fD;e|&>qV8>DA+Li@B(oEm_TbAw^s_w8pd5Qlw8! zo^$gIaInr4pm8A7G#PW$LdTEk#m-dmZOQQrqL@PsnwclO(4y_Ni16kG{((oUxEoko z|C4-lxfJt7eR|1lCD4B|@_+);^a*Yia+jx?eC-QAE}8S-{K)A327DMHju=PK1iCLY zB$`jn07E9QL~eB2tMRD1? z&UyDrfcRT*V$j!v#=A|?`ZXcDH^$}gGooD&g17JQA!XMo)uk8FXCP{v#_gQ+hL|?W(stb+&=AFjdyn^`PP>c@cQTC<}{I zal68OzsB>Cu0P-BN`VJUcH%&8vI`!vPa(fo|JeY{kR2($wFO6i14efaJwUP8ujIBG zfM5?(Qm{67WiZlUld(3c+{c5k@F!s9f1K1Lte>3KgX^jvYBfwEm2`olB-YwMT-M6w z2{zPIEok{VbS3^a;7u!1=Bd?_j#Z20!RJLNVlw}Wv3HElv|F}7JGPy4Y}>YN+qRRA zZQHifv2EM7ozBg-_c{0Mz3)9|d}FNl&-3#gt5(gLHEY&+qIEY6svCJ{xk386TMBZj zpAJOaQLv-V(VnW-4?Kwz)))T?l7P*Av{VlN5OMe_&YK#J zbW%HiOoW*Y;z8|GBzb)vVfuo=D3CS=iJWHd#?%SMPBdH>SG4A*Xu1Ua;(zGDFUld9 zV3_ZCWK5<3ijhGlR;hA=wM=jE8Ja7q;|QTywY`0yE=r*mVNL4~>msl6ZXl+biY;&( zrFT31M-`+X?Ng)1v0jU%mD{Zu2oQkTxN3F=RT0Yt)?b9)Q87!6L18w3CHgQKcaksDJw++(VPGxc`Z}M9R zq8T`{i*V9GKUkece($Doo1AYuiQr@F$AkFAq=|ZtNiwx~1J(VQnt?_!J_Ocr*e>xa zSL8iE`mrG0RET~m9DXR50sWNv7~6Rg(PJGn1f+n28hQTJK)n8zdWU-I4{?%GFO`7j`i=a=J9CLV2U z@?HU%Yk0ri+!EJZ(x)#uQ#={F3(j??*DWr&D!?5lJpyA@DtAsIeKYk$Fj!eTPde~o^e@Y#Nth6y^4 zsk&f?e1Ba$i)h>7bzCw=b=}W4?pi*7XJWsAvpf4>V{Zgwb7eWdYyW(C;-#)77P(7!Qy&#^p%ihTnCOZ^?;!mw;C5MBYRV=$6sFG z5`Oz6w8-Se2mOFi9@via|MGiykfjKjr(FW3o@Hv|Yxv$YB!1qcwN`pKYceU!+33|K z<)|3L66Vn~+9*qzd)`RyRKSvCGg~~XUln_`5PoW7-Nqrl=9hkGdnfzLhTm#dv`1R~ zu=Bz74NQ(YU-LAlep($)SK{*>);kKw;`_iX#mZnPCx#diS8JY$v$)nn@Z%Ek6v99F zR6YYBegXa^2Bnal&AR;F4~r`Ce|1y@{)T*5(cH$=*-GC*Mc>NV`2SZ)T%`EVv3Sel zxi*@xH9P4%5I`cEAS^e)a>%$}$Z;w~!tSF`nx^8Y)*Xv$upg+1D4}3HzhVR?G~(U@ zDG(&L(y%8pv(gyv->0W_f2^&jiy&w|wVvk%dg5H|_+Uga;LuS`wpv8GjbUu;){e_b zkTRHmkF`HGVT61{iXtJ1cyKJ*Bg(jQxMNaaK-u&mVZ<;FPX4NpasqkHJQXTd7^Vd` zl^tT(G<93l0uFVsfI)}E=0=20;sN<-GOwt=b+0I#+|(7_ifKo9>1{)`f{EU<^Sq~) z8oeh@FjC*mM-j!Mteh#{Cht6{Ln}MM{Kg1$9!EY$kukJ1JQN?-cA9lEA+#6OXm0%n z>*JP`hY*sYW?w9h90xblDPPo>>){q$8h8B0E3xjt5QG{RpgAm0I2_-A2I@LIhD-6Z zZs+V*iHHw70|A1GNGZ@ds5N@_moF@Ig<+h_!$drq=t6Gos>1l)xivdq{F^QHLrqUfuLkiY#-?_BlHU7IsulJSB(IQn zX4eh@)3Ber9l}9QSVGmM2G}kPmaQBiuY5kj@l88enQsYEsNzpRK^~g8x_a(U_Q&Ao zQ|&)#`Fe*YZYy12mhV|DTKUrxELrU%6rALz?OE(HjQpN_ku2Fs#&wIYY5%%;R3252 zkl#b`G{FDY%@h9{H}88HrlGBkk-3w(t&OpfxRbGizLU9&@jsUpE81GQ82?vyZ&7tq z21^wA&k(w8$7X5{lX;n@!dfFbmKvg1`j0&OSMg0uK|EoBGvN?pV9BL+r_SO7;&>Gc zS`Xz%n0Ot&M6swuvCb3coPrp+#|gJidT_w#@Wi#PG)Bf_uj33xQ{@N7-uv!0lsRj;RVz^eckg?)5QUlBPS`d3a1GhCkJfj; zY0z50e!C;P8w)*76C=8D?Jf~E2TYCMOM2)QOPTyRTg?N-d%61Ic})Zm3?H9}6uVq# zz^)bv>FbHD*}N_WERuZ|DlIh_#^JoC=75fJtXWES9p|ukPz}6H7K9KfZFN8s~F5lN-z&?4h0ekT={zG@WKnB6Jp81|q4a zS0?DErg~wz24S4`BB|yuO`tahjxixYyLwVUr5@-~MeWDldAi^IQ-kyU)Dxj6^tbqU zZ7|gM!t@`=a^sI_d^8WcO2KG3?WOS5nHO6P}mLnL={?US8;>OkbZ0Rjbm%l>x!ov_b;eGq-Se;3_JTS()H z=;FmmU;A?tkq0*@ot3*nSD_EH$4@Ob-k@%&kU==@V)wj zYj=o>Z4wQa@yJfUpFqejk5(t0O;x`THX1p80%_l3&(u8j^1yA!;;7K zYG7aDtqqYcnQJcF$Q{|v;}NAFUy>s**+git86*{1BcF?(fZa=gdiBD-Gsl(Vm%oAw z7f)(z#^h=d&0Z&*zRWWvf5bUa&+Y-rJJv1JB{*#OJkXr}^s{6@edxG_n&R@S)3UwV zdr(w2Jr^uH^l(J8menN^V`ZYamM7RCZP`}bh7&p!h2ACI=$VFjxDRJabiyypi8(pO zI?2gz6VVN}rX$jYNg(gE#Sq(=b}{Gl|4M*M1s4)uFx?J=>pE%p3b@@+IAWlys}sNOgfy$0I5bAqwhvfCteOx;C(zQUtxps7Q- zOs%*;*{Ox8I0+`d6cGy5H;&t zy}G_4H!COVsY=C2rvTg$)@x(R4b*g;^y=dCseXk zwF7dIJ@X%6wU;LIn_Ij1<@|+`BlFAJnKR@phhbzw=Y{O1Nz4h2N6S~;c}zolguhau z!?4BT>FRqBZ&GBzLN6w(iCTd94V^ttM@oSjkxll zLAm3@OGe7wf{&pad_nFDUM%k)I;}XGEEemvb<`@u)#CHB@ps3i+W>kg!tj?e87LO_ z*$vU51tw-p7UDKVgXX=gMFF?i<>SkIMPreKuS_NZx9=c1BmqlkVi8vlAgkpJBjmBp zg(!`a?jQ#Y@^w1W!b3DnL$`Fa2r76q4ohj9=QdI>R{$hou5yW+LY5YI3Kti?GeMvW zypJR*b*of?0AnGLlbEhKs~oE_U{u9Ph*_?Z2#;gBNuFY8@gcWSFspNN?TpwqCVC1|%eg565 zsY>Zu28kd3>$2$~w^Je@97RsPq7m${$KnGIpB^PX-9QS@%f(ZBo$-5l=yi1;=gSYD znGm`-^v@lj7rCKTK?LO2`PA{tiOGwJYgWeg=gaq$njgvbzR-lJ^OEcl&=l+|sjPK+ z`D1#pt-A5{19H|9i}r3g?b^Go^~(wTCl785RqS18;MJMVvM-k~IOMj+2!bSM9{T2C zyS-(8F`D{?tyrINdV^3MW=Xr!?xoOQuo5m+ulc0@CxO<(iOQ=cV#~&wbdjv1pHx>( zfoprzIaEl}rw+aul(N2GOvTPv=skMO{(Plv)BSR>hr4vbNfry}h9PYnu0wa|Br$Vq zmtXlT$N|EWcuh^h=OaB(+#DECha&rtR!(0E5?v;GFzL0FpRH&oQXAiko>z*OA>5ED z=S0aVdrv}3N)WvXbnaGoC+>eE=E(uko>*BXD^$tVD;s2OCe}F&wv}kgaaH%Jdi9uh zS^Axi$0AyVmQt>hpi;A`)zbx6f*=*3I;gSOPYb{(I!%S7lL~(FA`i=90cK&!6ysft z$9n80QXY5gJwc$|*VIkt5VA`1BF}2TmuXMT#gGf~QWVI|NP~&Z0XGJ1{iJHsaG%qe zaZNYs&E5uTsPLq_2$B`^#?ypEGn<@|LARxsc{4)P&OIiGHA}Hevq}*4Qib&ruBX=; zL>7-iMM@SKU&qy-kW%F(%o?&St(4L42r%xD-MRRj1haFOG8CD|zr-{b$=4=@EE7b& z14C}C5$nPdUu{UV)@={d4C{zO9A&!Np&>!^YEu#?^7)5kEzXteP5T?>o`C%8E&k6* zM3KL7ixs|gYWn}Iu>{R*t&ANl-T$r3`lo`eNJZ01Nf}xD*agS+YJ(^9Nv341LPCFS z51R3W4=Q=NQ4Kg;5eJZ`HA`nLkI`{_A`vhw)r=Q9jI7Iz3{k!k-GE5K%}j|WbQX@_ zc79+0SNdb-#niyR+Ob4B3ObeHxClq=i7ef zH`O!2)gUAcPUS+ZP)STG4NS#N?m`=}Nz=E#f8Dp4OYLQRPY1J$KAr_^#wkB#db1-t zr*7oY#N3X*8B0RTgaDIq+G>+YS?p?qnn&6zKEN#Xj(Ys4sRTCQ?2QszI%}M9(WWhg zQqAsZTbx#o@`~P*u{lI#-MooQg8InFXW*`61?;7? zh7j!fpcJ{`F-AA(u@HW)^Od+}|D43xtKt|QxgtCU0C9g2fg%-nY0-wAYu7eGLx{x~ z&f#ry;lKrv8<_6~c-eSlcsrz*r!7hMIt8-19BE_guXZ*I*pfm*b8Yo?oZ@K}^Xarz zsv_-^7B`}~4$q7Zfrr_2a@}exLu23=O0Y_Wa16OX?OlA(8UQ|EhuNGrq3nP+QD*oB*uB<>#xIS33-=D`u z6`Y6Y(k2eydW@T~XX$j}geE9fPUnZfgiRUS$yeEa|tg?M<9J7$$oMNs~S z<@;MZHssHcMJ+{5XIum7VCV_;-uH8cx~P|5n>c>s2eoZ^&r%fLm$d08sO&Z~0n zutg1rT!~8&rSM{{WZHn2HvPt})jd^>p3uvr8tp9vd6?z99AW98v?xucQYibr9|8@O zyNq6i*hUNAz+mJuZZ*_jNoOC9*wd}@V{ZV@vvFFk+9ftov&!$dL z>Br@PyEcuKWp%<(&+nBM*US3Wrd)bV6j1MTnr{ns|$xkewMM;>i3K+U+ah4q~>-;;kFAM5M=dnuV zCTIA@^dT|%3GEOsjUYu3AB}~)sff(|3&UVw8iPnG^I{7tNr{{4@B+FSPpbkI4gyX|R^A6v1U7oYdx} z`g1u5%O$?fII{P{fh~|rCm<>TeaQTxFNACd(Pf`O#6Ic7wib?8kJo2Vu`jA*5c&eG z;kMGO*U&{Wh+5NEb9aN$m7i4#VG(tz2J?vzyF+GaNe^X zPk$}C*9BqZnB%a;V43@+sg={7hfKy9A; zxb9)QE8c+UU;yqN+xK8Nj%XB0l>NyS&Mi9&m_KW6PA;kryj0`9Aay*|!_@jzbeXn* zyFApI9=VeY9Zs-b;;nyq7Ka*DUp4^a((+7}4CFVQolpJ?x(eAPuhUj6M|X&tLYzP#0ji7L(}5W=+Y;Dn_My?h51HD;MrKYB@f8ck1Me`k z@s(!!%1_6H(EF9OB*)R1Cbmc2a*f%{=L9j988KKHFd~SSUW$OI&VPlM=~~SBWf*Pu zT_(QKt5Ya$y#{WC7(T=>dFONH%uVColKB%|Vq-$IMG$jq@&f#Iwb4MUyNtf!(bE43 zkGTE@Jd#rWH#9`_uf$)LimsKWDasf2yN>SHroh@diFAEZl_pY2)On%(TA_K%BDI^O z!V$}9ypwfJR)nMC@RL=EB_CI=ut2%nFEk<+YcbDL5{gFrH9E))Ci(&1+h6dAa|1wT z2DDsKdk{op*Y6iZMIYh}>Tg|+)2~z4neSQK?91IB$1z(Vu>(zXF8WlFo9J-z>2l*3 zOTI|o$kW1fQ5a1V8Y=})P^j5(1t@6!t%2i^t97w0 zbfFX57aUl&#ydMX_ihaAcc82q(INsyAlB^0q3{5z?tcW1*Oc{bTulM@e85RnOo z>;hbDM@buDMT41|+{Xvu3ysl9_cHclWgch0%b3pYb)v*f#|JBD^b67yMys-^IGWNW zKjZ2gnquuJWPG-y55^-R4i%{DP8N>A5QX5cPKWETn)umMx^=NiX%_~1da~JHOyG3VEWml(BII@1b*BFC< zwSrSXRrl8tUc~P_yco{%SZr?|yvPV~?ovHgyk3qOcehU=N2x&3EIc z7OtI#wS_3@nWS}0KKTO`{#MvrQTqyR z1WnvvA%CdEAKufvwu9w)8t@2W2IQQ&m@-0Eh#gWa@^DVmUd=k)1qOGTE;eocS!h4_ zb8KL@Y8$B}36te;&fpZM2zDGV`HUXB$hCni3OvENW~6L0xu#8KQ#p>&(WdNbF=d%S zjPCOiCQ91eef!gpme-`69e-`-7%UoQxW=^NjJ>nrvK4Gc@!JM3=TI?D7W6smR{3SG zvt=g+w-tnN%Ngouec}BEd|8{0-OZ&pb`xA23n$j)B9_}NvDvL3_q`T(CO(`}Lm|#v zL!s_-!KI)C!#%W}10~|?$I*CgBo^HV>#`tdqCCzVetuNIBs>+D2NvEPkN*b%F5-Zj zYvVHuVAeMOIJVlnhK}$JchHx$&=nq2XZVe07H>1j2YEjWhpy;4|N4n?b@Qw%R@_B6 zKI@fFhY5Bev-?6L%)Y}|J+(y}?AlV0QHD5LxAo(^S5d5X-O0E8!&`-np$vPsKa)2t z(IdNH7Nseco==bw))(BFEalK9maDG=*z9S*ALW59jqZd9Dw+d%U?W_~8*~mMUYt0a zfg&{Txe$Eu9j0e`jGn@uLzU3^c;sGb@2X|*>5)4b4$w8@WLvTOFI|~E)2(0WZ`)(y z-peRLFCi5`V0N)V&SHr?5~wD(Y=~?^1ev`E*>X$Q^`J24Se4TKZ_b%E8tO^T3SOZ; z(6uH2A2=cAkF(dF=t2?+1l6NG9&dkoEqHody}Hz=U0<^Ggf*Rov1GrBiW|Ae*tS+5 z0W`e&gL#eDNXD5LY*tLZ?D$kyE+p0eD9ymS)LmTyaITCC0B`r2evDKDD{rbwRd=g7 z@+>@jkDpTK*XP_LyxgXjuAmH z2idd7kh{aC7-14$IiGbCq20!7^*R5Jv<(YTB@SUFmQ|SC^}gaQ`NPU}&#B&ndkD!B zPrwr={GlyjaKo#uMp3V*6AN25=2JF`Up9`kA*;wcHDdO40n8)Zz@PKPk# z1*;_U4o18q3^5^^L?Sh6i7!kHnv_Wb95-)9=r!;| z&`+?{W>T_O_hHXfaL*OGK2~=JZ;rS0d3o19xVn3mZ`Z+$Xxh(XCo2FXX;yv{@G&9y z$Y-1rji3(iobIwuIM%7kXAAg}bRez~9UJHyJf0G;)_9&6XnSurjRNle-?=Ip4CnkOkVJLK%ooQGYYoR6%dP^chBgz$~rcGHsAJ)zGV{R7YGcge+$ zlMe`!piDyq$Rr^f!wp}ZGfc=&)f`;NO?E7vpOFCI_0h}HHcAXO2!cXS!m znSLv4*Sck`XG;-u8Z22Iz4|A%lMZDbXH2wkjUtM8k+hBr_cvM|=Eg^-niGGjBUaY1 zb(P)-Gn&;z3vSYV#51S*kw0LV^?L(>)`Q~wT8jLVvSYOe^1?f29tgmH^AS0-zRM?$x+)%?-LJCF<=2B9jZi#!t*` zfw}y4tz_bN2^v!RgOuo9+8(H!nO7r2sDzuo#z#6CH3MgA&wuB<>3DRzyMx56VdOQj6`IY$`-zz)0D zF%daMB%dAd2kb9k+HZ)|8wj? zSXX9V&@+{3w2&0~gBkY&;1Ag_w|It0YB5Vz9_{4Ox-ISYRkQD(KW{KUD(rIkbo{&l zM=6lrGciyA@6Y!94waZK6g!8QHp`c(8}b&*N~_GXr&0Zs;#8$6v_cTnUTF2-4~#6) z)CJp&brEOU5TI=s&R#kY=YtOM?749Yl5AsDYV&d|Dy{4-v8HrSCQyHFBEJajFsX2K zFLbp@vTW4bmC}F{oh?j_=}2nFd*a`LRxm0KTqyWW1G6YeZKxI%__&j*#9@>Gi_B1g zHpvE8)(+=cg4R+;*T_LnmHFvwgXx8@1Xa>Od1b;H)P?e z16vf{xC3soHc|0HwjHuf?kU$eQ86D5_#=Ubor1dIxNq_1)Jfy#}y9tjl!uGK)!_!KG<9rEcs^mHon1Q^3oD2TpJY zgsMNYa12|hgf>o!^giMmF|}^)Ss3|$_52u_-hiipfX?#R;-RWyU^2j_{( zr~VvDACVRsB8-Dbg~nHuK0qaCA&ldU8*w6XU`70m7B&Ga2H0Jq#}c^t-InIlUPCYy zgq##6fFnflK*nR3SL=yiF?91+OnW9d==O%3=8^@RrbqTetDV8G4j(Z{X_c(~DfL9W zR-;FZENn?ogPD-D6S;3$w*s2W_BPyNUk>OVED9 z6M6@5NkzdA2m_ifi>p8VKJ^LoS9IEM&ZP5x_l7c|{xv%PGua9Mjp!7&vii zUk6#jWU5r!CPcz20Z)MHmiw+?DOz|g+)l;|;@+w-Ka|E`2KzB5?>4*R)a%D%Kk1KU zJ9F6K+OwV32qd;s1JshAnJ#w0`t}r&2j#RAN@oxHJB+oS(D&9^GSsrxITcb$Ivtf8 zZtrKWXu+%N3`tM0g1@g=--y;c$k0&*(!y<$p#x8E{RqYtN)7i82V`E_>#T+y#%3U! zFxBwMj{pOJ6v_CX}%!353A$mt_V`s^yCkIkt_ewT?W(Z80dTdZs@ zrG*U!Pe@kc#(FrXT-$@0RGmas~t>vKG`~eX(DY^@f8#gs*&4U4%DO3%h+b|c^<~;$CZ`r>Vg5%Jv z(rFyDJAamB`_=q9zT%aI((e3prx=z^M>TIA_zpy7-teb}_`brN2ln~8boIm#2BppL z*Q_`vn~+2F47Ao9`lU_wR=?3Ik!_gKXLmQDFNAgS$ zfjK2e^)9%&oEh^^>d=&k%%p$x7~Aff5Ej3E5HADP zokqYpQ%h^@-QAt}-k`nUE_jpB=j$Pl--alXx_<*1Vt(`(yFGRU zYwPGyXsSMFmqbKsc|{Xm#6~zZdw)x1hRbR-*)=8NM8l!UHORG_1b->H5{P&GBW)5bkn5X{X-kDB}v%|OzxUV>3d z6&)wcakedSF0QdVa~-i7AN!2E3Ojs|bda=WN92>u1S;DyHM>!7=tj#@RpH`}9@Fnz z;*{46XzjI(tT{(E)Mzc}W++pg+LEB6vjQT40$kA9$k0~>a-1OOuy~t>-nuvhs9N>w z4d7k%_d|{px6+CWw~A8%B1>7s*;zBk+!Zr2)$cy6MzYhb9p1X^+3Dm%4Fv_Z_8ZAj8G z=WLgka`$LmZijBw=9-f)2UKp#6g>@A?;qDrYDU6yYjs8;*80QRl5fzx9ld`{xsQ*Q z?&_>GIqN|@4f4~|K(B6QyJ*i`!wfkO!#u_zX>RYAU|vTp5>g^6Osd_N*}8^WM9lQs$Yb3OYWcnQ{M0zg;$N{8;!5;6Qo@*`2m$eq!uv=*^S!EPa=3 zd~ONZyVOd_rM?JBEcr$~$gD+qft_-S?LT=n{bdHlAWXr-1|``j`Qso@T7Vi&-U5s> zJyq^4{kML&nyqSQ_Ht|WfOn!7$r?6thn=IBFpb^AQo04I2kul#K2p$1)~7?*UX8~bzeIr)r zi$KXv=@R4&!1Q{;ZL5@BmiJo-FH8VvJ;ZXr>Q~--rLa#S;^Gr6j+{cADuJ6x3VTel z-^I0umV7XQc4^?zv)c*jV7+XBN2S$+`t^b)o%LX(at5@~B#|m2yz&X4BhIr=l6o zwsu)}YX=o{+|)a25L+D2Y2x>>6{@n9tQ_q!f}o=Nv|_9xw52jiNK;8|xmGGC8>)n5 zUkYRq=dh_!6A#xm2TTHxAW#ctO$Q{6Uq)E7w1!Sb1lOUgGw=V9JcA=V?*8R}d-MJK zA7uZZ*g^Vl{7K(v;kz)l`xhD4e|`ClySL}))zNv2 zYz{!=o;u|keLlY5cUg?S9NWw6?xH;i14F+NKV}V+l^Po(j-qI9#N43p~6Oirrb9WN?_cc_`?o`M5p|sAC3V&*{CdKb)+hjL6bXH0~ zZ6>twzESqxde7~uO0+@2E41tzhdZ!s-~bC{E?G9ea4_gub<&$Hy2#J;W;0HI&m+g) z2+BT!Xd@Issk&Uf_fdr4Ti$$QHRNG{ut3?hXlx^l>XP&xxJtQRlMR^O86H^?sHC~J zn`Cz4$r<`<4Wm(R&9hy7q2TcuYzOM3-^URF0>_we1h0w|>idAtXancJ_{Cu=<19qxu;t_C&9@6RiOGCK&h*45IbV1hEtjKRMO9s^R+za_8I$^sw$bwET2_TfTNguJ{~J{2@^PjL^ZQ6Iui7?X?qK{4OJ`hXFZ{2?5J3iExS z{C2q(1Yg-;>XWK?ksriSD#q~IWAO1~bnIYG`NRwl_~P-S5U|)$afz<>;w=G7EzH%a zT&hE7H@BGCpsWMiu(xkKI)n(ms{1oWh+{CNW0M>>okNU22oFZ(%n!1fLz)+1z0rod zeuf*BNAs_nib*LFoyPV;6NX`Ovi-S&XHy4@4!%NxR;dc6(@G*~6MvG2;3Utaspk$- z&m`&08goiBiad}O>iP%D_ksEBrTs=`8Q}j{r1JfZNR_d*QM7l~cQF260DhK&w5%dO zGPk0Jge4^|$_#3i4YKx)!3sPd()V&O1x;(o79+RLJi#qb#iPmn^WhtymEPciAW75@ z(7i7^!;Tt@zT#U$#&44+vF6Ps?|KY%;bV;B?qJP|}VCAUOT`8`TvBH}fYBuX4B zW!4a()_xzwumY4o>q$C7Wf}9f$KzU38w=cssg)JKFyp#K ziwU2(rY07e#{1$A-M=W)8of~#AT@U!$ydAVI-!~?2i!Nz7an8l|nVe>LA`A15 zenmE}DamMIs%6_pdE#PWU)&cm`$2GE#9Ee-##*0`v??jvm)w~J6#=;u&66G0{wiTN zx|Py<`~pLCV~v;Uj>x1wRD}2Z;1BXTdb++<{o{|Te#kB;xrp&tzGer&scy!E)qW|< ziB&abb8lGGG;7}c!cy@089>n9-u6;+@nXHacl`?ueSaGS967F!ZJ6mAF;#B>E)cBa zh)wahoIZM$RTaJ{$dZUA#QBwN7{M(JT4xu(;Fy<^K8##1w3xo1gPwv;g3gD@X!_4T z%-j$mulGnnV459bY=s!l}`FX5596}}x165XMp(U17ev8k{Fa1z~^zuZ< zBXw6%ADdn&16@IGL9r~gKYpr}-dmLBWr(Ufb<|JAI|)_BZb9S98Ux3>(=Wc^#KWov zuRvN6_lQ|SJ|61z@XL_?M z#glocYWlv&9xkw7EJe$0e|u36f`nYgAWU8a^C&%u@;G@H#Mn4fQ> z<7}vypXXz<>eiTLC6oHnu+)9^=hYVFHF<$qiN;o;FvpAG3L^@}(r&lLs?<_lK1Mvuif&O~^5ffU%|0s)vh9YfVnMip*Lfzso~oJe+tj%8?>@A&fqEb~AK$p&9stPr2c{x@2?#A54>in{@#{9C? zek9jM0r@|1kt*_wEz{Nezq%8oRM{LMnVP7~Z7NF#3jL*PE5nECs1EXe?{_C0+>`=V zD_m9=H!m=gsx0x}gM`d)`)GrxxWQF$h;@{K^Z}puN@;a0ud38-)IsVNIQF+}D5K{d zSGZbyHa{Y}7vbwb931ItY+7Yhr&+ECs|Sr^v=SbJ-bj|#d6+{L6QlW%b*M{-Byph~ zLB`CscALXQp*Li6{z`L5lMZUoRG~wuE>+W{K+9Eb%v@QiEo|eNoipM!P+4YWHP{mo zHr%J@nmzN#Yy?ih2b0404>4(>vWIbHgMMyLtG10ILw_Y zcphsR6NDc}Ym9C?d!rx^ESf?EHHolj$t1X7TK6Ox(J^qb&IiQ|Z{Bvy5dC?*+jvuz znDVwL(#?UEMPDU02`z80aW%TH4sYy$*kxl;nfMGWcLTbicFIQ*X)vc|$K0F7U+y`K z73MwP39ZEZyRk>Og%^4KUDCN`BgBmf5JNX9AWLlC#{=1RC%VHpjCwp>$WYM}ZCvYt z7U|(VMcTeYgl}!tL##ClagJQlw%SqRI8-TbAc z*_CUb7JOw|siT&wfKKw>Ton+1vgBL@=y5VO!fC^YN+V|zVTqEH-jd-S^gGHZ(0!F1 zq&a*LHHK^KALHuyxpa;##`CP!VbqbIAc)XZ#pC9%2f^saf>;w+&99jtM z++m?AoYOejF?T~VJkHODmq;#_UQa^A`B-@R5($dCXxP%fe=n|C;kLHc{n=q>sdFgKJmmBh`!9k9C z=c$KJ3E?-Z0Nt-e47uI56|o7?woZ~3MQuMX5&yLsO`V&*w>r-fOa*6P z)+JD;I0)elKssVZ+$(iD1jOsxr8{CqD;+J*!(zvU8G)H^kbpvW@W)~RY~fne3KZ9R zcDh+#=a>d<>hpYh=vpDm`=UF7b5~nW4NYWe#KIu_JHlHscoQPdIFHiVj%td~LeUvR zcNzTa;%vUVd}MI^hGxXB3<-K%7?w z_(dA7R@=riHi9#$>pRLnPE~x;N82W&J*}(o0<5#E(5o_@z;=&#Ii1AV&K&odPInt^ z{*@}6&_aNPsSvkN>FOYwIRZz-RP@YgBYr*=jkmaO_{^}^iX^W=oo(cdu@ifR0pYpb zeqP}ztetqmfy(6?Sh?_RSg`+UeR{l_?J)l^cCrb)3=0WG#`zMyn-mkNimE4p5;AWj zPH_v9Y)u--3^6a;o1G4|C7rRfBPOOvO=)R`q=(mlKDUl4YqPyM6z4&q=;T;iut&4g zjA1*slx{ur8!*-br`a_1WLTSj7#)Tficv+4*a9a%AQ}7G*5ZY;^yDHX+n!PBN(6k} z2GF+hl6aEP?su7T`5PTBzx~Qg<@ZkrC;wyBwORvXVMl=l&aZWKN2^bc5U`kB@)&xT z7vzf45@`G8ga=o26*W2k5gZlaN|-SpwTgymtlbeJaW zb~FPYU|xl=lRMITHkH`8FoA`hvXF@u^^S>+i_VAUh(ngf=QW;FN)NtsBA7D+eJo64 z8gI{zN(Psao7y=Mo+4#Gew}jn%ZwRj1b4WZAaCV}af%0dQB!%cQK+j75sNV974o2> zdkZ_Gs9 zx50hqR*H5ZD#9J{Y8@b4yrGKoOP9dVPh#v7H_8`6jyk*?pO1Jtyv+O6mEnJB3pe@+ zlPF?3lF_z$*~uzgh8ZtE*A4fqkjc8RVk>tphc(c-8A1y*-kRJtXuv7onJ}@2s|bF# zBICEhm-*OQHtd}oW7{HcJaKnfZ1-~!fU;+Dz0@k#81=H@gPyWBgP@63;ix~6!S`!y zGx3eAyOyrGcKv3;h3v#7u-O&wYQ>NAN@UWd4er@>_LE>D2wob5uNk=$ z>}G(fTzC|Yj^xG`a|@)`J%8(x+_|MdiH5p=-HDvKgrn4rp{l3bT+XUq!vCk*I>oGn z9WBuFR@fyLcEH@QTRPe80z508*?8ooWkG=f6-ToBQ&i$u{e($g2@i$Cn{~8tZFsmk zwa13-tK*tk!eI<-m2pyTcO^G+6j)U*N@;k=gWC$E=FElx<%BeW3b1tjZ}IRX1L5+$ zGL;dDD(?Z^%w%(ou8GD~4=xLky;GGo6sv+Qddkj`aHC>%c}i!vqWdx~9Bb)exvk(a zjeasK%g6mzmidn9`7MuBgjvSeg@)J%$JDR;nJwB<-cF%_6XVoTN~fRIq%$>m?YjLR zx*_6Upz*#y3f>9nCoSM~+X6Q)EZS1t0W8}^Sf|`4uRtfyf@|Wqv-=OC9lL@Lccc$b znh$pz*)LK|pU}>Oo^$3!W=(L|k`+Rtu8O)ALgd)ovcsCi^1z=lB_@dqH_7x1{t6UZ z%!w-Vn5nzid_T`w!_Ou7WzY+>B77tBI5spx6yUuV!P5npLZ;A|=%YFak0fIIHDS{M z(Tk#rp(8U-r9zCdkp&oUzEA|bNr)WC3)!U2MvCK+J3zv)B&<#-r^gFk=u@u}7X3Yz!zz z{%h1Kx0V^$xtk2MoqOI)^-U-=3Hc*)uC#)IOfzjk^Oa2XwTus>R1L(u5^~lEr8td3 z018D)xJV&DqCjM!MtB{jJc8_oK+1;1OC$l@3*W6)Jy97VsWG&ENKjZ(cn3s@m>UFWEwB$+bb}Dk~r_k1nEGj0xW1Qh>PuO$Er% zI;>qMGcA=LD{z!kcnNu!w5P`9>yh8^CP;opH@?WPewL2v^>aR_8#8YcGyxhk)}sFL zldRfcpRd@rpmYV-5fWhBXu_}h7yDJ9K3aXA1yGzP3f0;FL)te5X99HF1{2$MGO=yj zp4hf+dt%$3BwuXX{$fpR`^gw*=UA1@jUTYcF5TC$?E=!1O zaOIhoYN14uE;^K&Le``V@NLR&$Zok+Zm&T_ADy}uQrPmv4dZuvHt); znoL|oJqzN-R8hhJ?GvSz9|qk{bOq3q30tH0>4=n`ab*?7m#o^ma*6=Ds0Inb0)kdR-6Lwe6K=7{!kqC3WiP!J7ARH{N<@Ff~J zp8#Toqg~T~Vh)aN12KdFa>xV98v^8rUWN{^E&c_y4WyG$hQ89GF%(R*M_wEJu?IRU zio_#VD8Fl4kWW;21X1)z$rmUfj5TnR0yQaI^c_R6_6^<*$;Eaicdq)Fl;ew+eejZ_ zsy4OvBY&Fj-L|t@4qTq4pUVFQFTkh_392H7f6S+rCm!jzHN*qCOxl_`vnrTQUEEKN zeXS%MvbvN_WLbm+hN?L2@4>dQ5-FS~CL}lPl|>Vi2!q&wF}o!b0&+tZ8(5b!jEuk; zqK-Zz$1F-dZ8&UXP``sP1|653V34l2QpkxBp4i{-5XgpyPFyiKcw=^WV|sXFe)xS? z>>)_(AsnX2CX#O#L*&}IehKWMcBV+80b-7RVva%LnGoR|q>wfcNGC#gV^;Wm)c+oh zz!XXQ)yozs%gY%Vul=q6Z{j&fr+?iV*h800k-Ub;9s|Tz!NM1TB3I!o?tR4e5yG3_ zy~fDt^GERq-diYRISO=rERetj>^)!(rLT677dDv?VA^thL zR2hNZ8O}>&ONyV^d&2@Ccgk6j_vlNrDhZRDltv@sQjC}F&x5^06R~i}E_O*c9>Vz6 zq96xP=6q02YpEIP=tkiP7-1(jXWt`y=|tXnf}?!-gM9g;dRA%a6Oa3=CmJ9K{9~$#LacDKBLwnq!vcTQ-GXzDa*xHYzYF4KPHOJ;PIt zN>fHV1IaqI^)ksQ%i;kw08bBEvhBe$BR5d>r#~#JwS>eIR~nim6Gy3JwJTRu%}}al z=4;UmbQeaT(aOs}40Ruh`}Pj@U=s)zOOP<%J*6fz#O~PmpqFish#nY3KREn1ULKil z+0lw;!^VJuy)(b80s%3$50u=JFX*q2P>ssj6W2#9V8xe=W@Ya@!kG)O>`TF;lJSJ( zk)rLM=pp4TI#2n#1Z%1HWc6(4A?htlK=c(3;kLCbrSPjzn7{we169^NR)hRvV-UDyh_%d_~iEi80WxwV;ldKYS<+r=6DnM_D&vDZKZOQ9N?y zUWllKTnW1$Hui2w<&R*^Y5*${uwmOC1ei5*>Ab9dz(#1cVo^S{0aX9yGn_#La^N;Y zAOiSUJ@@IWV~Mv-SUY9k?h4GG_r-r&a71Cc{g4;TG9KKzM{W3ZZ=J}JRso2LD3QGQ zb)(Gjd6sT}zxtlIbm@5Vm1{AzAP=TZ9epZV?0E7MtHO_U{3U28HG-UZp&0+Akt-UF z!bEN;G!%YbXQU1wl>p(5M0p|R6ikqeN)M&Oh%l51KsX^5dpNw&DVt!ec;~jl(C+HI zHwOZOIDlC^joHf(FD?6-eV&>I>Uh&v^9V4$2?J9VsakD0F%s>%hPq*swCw|~G{N>^ zvz5?J;zwilwfyk^S`RWedfStE?TZE6TbVG*E!dI;+NX6gQD_NT77<#K>$K?`(&6zF zB#9e8@q#T(fbVY>ay|w-8HfA8-6E-T;j)!vI{JtXo9>GGl?Y>?GMmV`>_M}MWwblp z^vc^jSgoMCC9{krc%?X=Sh)>^Ya&O6{Ss`YJZ({DGYLQkPv#w9^Z>vtw`ksbDB=j# zpO;v`({4DcO|2+yK2Yo7&_I|Usf^OD%qo;uf&)aIq1$CtEk&chX&?Zjs+7;GSFF32 zAniKV=6Z$VW(Nk=ojc}Z`ZDa~>p{{v3sYcnTK9I?)|TyoBpgd&Pb5!m!WU;8-nzC_ z;LNk5#-f!c2b{*DR)6v>hA1TG2UU$lPt~AG9ME*KgT?B^YfM|t6Q2m({1H3 zXb2qkBB_F6voC2xikGk(Xa$Ft*cxct{7P8PhX%Y!{T0?`gmX`|W-{wGG$#pKcL;7< z2nfk_7VQ9AS}B&I_0(-H2DVs7yWjeXDh_tAK9VCG_3}#^al(eC^*{6S2cJy;Xn8#y zGT7i4i~mWyHXDOPIE+f;IM7c&-+ViQy@PMT#mPhr#|8ea;nG|#F%(+6JCP2dMmVE%ic}jB? zZurF`ss_dpH0tLdNCvc)yhdLY`Vjc(g%SQTcovHg*w0VW{%L#Mt{2iiKD9{C>W1_v ztqob{m>wkFC6L_;Kc^;ywK8}>rXm?GrhJjoT&+VP#SGQcb%iS0aw9ewkxVtKypks8^9Iu4!Yj$dTh9O2i9@E2@3muYMcb zhjvIC!;(dsk7C2UGmF7fV9kLzl!mU;kPTlz0yb-AGl0@=QkK$rmSWE9K(BNy!3zzTQdSxss#Ev6L z6NUT=M2pB9D{vq8bq=iFVvz)=4$tO_^)N4+=L&VxoM2hdKh$g){bVj#C*Z98rQsfL zc2Q`uc5ZH=j&qcj7(#~c(2zMCvoC#+o{v zQ-VpLjAkJQ5+iE*EQLR9G4$0c5y6C!t$9ak8JQ*5N;`zhpN?Dkt;Rz_9zYfF`o43% zBqn}s$qS$HTD#Q4lJv76aWM|y)Cp90=Rp(;-*TdR@1C^T>$c~u-8-GW@bxB55}i`I z^2j-K=P64Tcp}2Dmns=}odxl__Xw?r`WYa+7HyaSphsV7QHfuHOzz2qv~2CGaVRwc zUV@wvuqk&Ym)UrbpsxuZ0k@#RuZov}pRQ$3AbJJ-Qks@X^BQ(oQl6Y5LER65PfYwp z{37-LLPa%yk;kPxjRU~((vM4swzu?U2w?qkDbQgF^Ae$1(?_Sfu)BJD;j19=siDk< z7f|pNg*ksU#{!t`VtPXf9Y+Fx*;>NHwMpM~uSW|}EM7hnfypj*E#r~Yb>h)0SQ*0# zgYOVwpG%;iTdS%7lc8S>+9 z>r|gZ`o?Gx>TdbC#84Mlvm_ zjS%gnSBwu$!Q?S2yRsr{FozXSlYe-=vl%eVD}ibNod zvK@;f(L1y%rG`3nte~G0{VX(tD4nZVItyt^CuHg&Y)sWsbuc4rx0n-Fe+M~yn>YD7 zKI=ZQ?B*PP5MWaij4nHqT-5Dmq!(`2m@W181F2m$ z0SM0)%fAtK=rR`2zZqID!ksE~M?Rg1o;vwq^T!6oE#B-D5b0VY?gFgG45WNA|!`gFMraF8ZWX zhtn(p505!%9e}GpXm1V05(q@|*YVt&HB8@OW&{}xp;$YCG}mH;M-gA>88(XK_~CsG zeQ_m5^WnoB&JPIM#t`TLA&DBqm4ezJU>CFIy(ghR_ziX3Co zuoF_beNmyeqMHaJlC$K8!YOC)mvd_7-}1lvBnfRo=SEo#9|fbOedPk2)8^|X1yMG4 z&?bSRUik3XSGY8ipcMc9#MOp#6Ea^LVb#=fx*+!8eX@o5sFV{C8ilww!UFP-z;XJu z2U_PUrhc3K>et4OQ*4WPw`NauJ>FVucfw#r%RlJ3Tw;A~C*J9=d%$-1+LM|TpHF3An7W1~X<7vbYI3puN$4$*toe;$jnRrwJRwP?v_CCUAFh;`Sen^6~vj`4}8uIvh7OlW^+BI-l2%p zk2P*#wixx(7q{9#DESf2D$gHI3nMKt;0_B1Yh0q~?vt=UuM#*)fp#2=x>dGvYSEzpUqFt$%p1?o#<P{kpV!cc+`1bmP@FEA&& zw+^Kt&q%^hL!EmB6>5Rp&~O_bMrK!ttU|5>Py2%shqQ7LOsqKP1Vx?yxX6e9Ua| z>0`A>MwHj|O{@)mG-!I(GJ#Y7#(4-l)KtI7p%dfVumyWUmW4jTW?vwrXhDttbn`$Ph0 z1?1N)2^QEqB%ClTZ6$DYJ_>sA+OF_=$^`i;$Z!jHX)Y%bGvy`pMCZ0y{8i+{TVaD<6sPjIt0 zQE>S7uj!cntQG<-+vpU;FNUcpv2Rl0AO>UJZSI8u{^nXa69;8aXp&F_Co8sFlh=igt3x^_GQ&UGm`}3Z-7HJlBU}bW%vg$9?1)}>NG?4Rya++Nx})Ov3|brF7K1<{5|89Un}8k1Jj$om zk%rzY;{Z|j`9FH-&vK4!cEKn^0q>awpv7!THlbA3p_SQ*` z6bgF!PiXglMMcSlKWRi!z(X-uL$p&8J8IL9T|)77;(e`n4QL;)N>{sb1HP@L-*v z_`4;r>yYj7J^;MjrIjB2aLExp@eD0LNQC;AR`!!0nr9{=9!g{sVyEih8L84l^%b80 zFW!jZ%>mckA1Z_`TqJRjsT@V=P>QNCqcKi7#U{3_e*~Lno2u}1#EA{b4KB_p!tQrW z*DK>4yffxzX>Chop0L6Vyz^!d6I#FK=MIZgBUN#;U%}V8^ee2x5o_hJ`j!iR(}!tHIpV zL}S^J_f(W5=_|-U&wfFo{1hT!FNlA;79toQaIGu`4jQ&g5>R?AF)tR!TjeTAu8AJ_ zQVwospd))(nlkzO{2;I77~<7ex%`uBz46*g@W`bz9rBxT;ph*+_MvPa{A;*)PY&a? zo#YAEHopZxsH-|?j$P|{*BXiow$l`{#qqU>-^wFr2_dPR*~+Rp?eS7IK11B zs}P!U?!?=#leh}>h+2oiWI4LwJGkV1I*V38xLs^mGiiO*g5L`>@)l&b)`XinF z(xA93PRL$=qQqI>P&ISm9=UEBy;j`L1=nc(05@;8>7YzlXv1V}LktImvBaKJo7%JX4)U{Y+;$>eAiloYvAn4<*YtosPD6yRm|nT)}3_`EqDCtpn;8(9pltX(tb zhlPRDAZ0ArWh}VMo&GC`a;FTQ1q9Nnxaaa#HJqgl+bJVe@D?(IUDOz!s%P8dDIFi> z<$#YsYW_&-%b^s)ffRQm86T$7Zb_!nI!P{y$*t!)C*MKA6t6TKYc}3#=BM)hLjv;_ zmoBnXn}_9hhaxut$?PL2`?6);4Y_K9woG?6KG8okdEvAQqwCsusiD)+ z+E!NyM%#&sSP7jQ);6ZHYdIxbzLTEWi491m&s1Yq%xBho3R`iMLhgzK34G#YvE`Lh zFWl2id4=L5O=@<0lJX<>0H9~k42yn={0QTT@c~80jAy1jvwq>_NVO|coyY!HLaf1j z!u;&P$@TFFUQvx6^3joNitWBkxqM1}$2jcG@JvfRmF2ysMfD}LQeihxGhA(Z+nN{L zsJeUE9p$a56{s=zyryH9EmZNOv9Ww({;&3T4Jkg!bFDA-rCNNS`eZHC_!=KpBxl;q z*S&D(aB?fpo%zWy+`H%@;DxR`YKqA z@TsCZW|c>p;*Cq5?ehD0iA$Nu*SLWDYS|AZ+tx^XMr=$Sj`JhBM81EsLk9M)IVVz+ zM3dN~C*)-FB=uUcl81D~*r*_VSz_+XZ-q^^hxS33iMreFEu_dUc0Y`l&TjW$SRvrl zR*pP55bkg97G3rrKRJ>KrE@xn?-t$H-V6*7CdzD>)T7a*k9`GAm9$ladxYTzloi}k zGksv4nfW3{Jb2)m`U)4vFxCqB>hhC9;#)V2~wUXfSF`fX0~>InzqwkK9ht;Lt; zLOh=<@z=r#W$MA+5qwuA91saB(sJB$9>42^P=AU8quE3g1adpiDo(L03Y;=vMz~;) zj<5SSV3!;&{pq^pBLAs6wB7+D zD?>LS;A`sz$FFY&g`0RGrU{p}E~LAs@F&=Pl!Ml@_sxlLO$fygri-l_*V7eP5(;VV ze_3<9{{tEX0B!#+VEhFE8jo03XG+?c3v8JomLyDxyiL&+F-{deG;_;|Pq&>}#Vh$u z>$3OpNnm7fTW4^O6i?F^^i7MT=?KTd^KFNDq&4YWi*#&9Oah=c_an(2e)>SI8kn}`C5$W*nY9u!2KOHKJ(GJ+2RRVEjFuwOMfm)| zzZy_6a|fH$uWG$l{?dOKj`^$jx4m=8O^dyLKiOXGvQ*i>F+d&C&`$V8Nhc{el$30A z#2l|ymb9tVo^*#gikYWrBNLHZLjj}FXHHuPb1i60Acy3z@BkVM_IbfFIpbf3`zJj~ zZuL-59<887_0)!}33@ZsP-B;Uno0|I-diRb)ohLw*%X>(4tG>prWxC8j$C;L<$|*d zY#?*0_Oz9219z@HhsB&7)wNJ3)SN$3-j2o0W7;a`JaZ8cdU{aMr+XLu*rNzkJDzD& zW1>>+gdDRLx|9^2MxGxf`Ec; zh45`m5r=XihnRxa;W-`d2My3}`k-x^!d9A-T3qkypzXAQ44c!RDXqm@TbAF%c{?_B zQVTi`iVm#&-SSTl9Kc1Lp7Pe7ylrd#?%KzPmhr`n%Dn9sPj8>8#SN1=9Ro>+QLdf> z!R?t|y>Gse_YJyaPWv`ofX&dw#jmY9oG!BBt~md*4IjJgP zT%78BVz_u#OER;ApYRNA5?OVoSkF4BL^;&t`jpW`>+@1aE~QaZ+q&SG25^uDP>=?S z6n`t(miZ7a{CLp2gR-VrExWyb=9=V*r)OI%(*NZKEZUYzPRBh&dog^X9&ye+5%ArE zzP%3d8K8e-hjxuJufbRFkVGf+h0rOF!h+|AOm$0Vyg9?zX3jeV$!JdYoaM%!mKC?U zfmQ+K4kuW`iSLK6LhF-b)U+`lf{|UJ8gJ;2d<{ZxVF?`u%Hm-Y*0#BVan+#*(N&ClaqH-^Ih@pQir7 z88brntEWFM)e*VXd>4GDM#rj1y!kw018xlN0*`<0DpqV^=)G85Hk?A_NlO6JSu6)Beq7;4D z9E7*z{}u-hDRiLC?pS;+-DBDC2^vTa=Fl1QOk;#K9dikz6AJbCnV3K_FnhhEnUvAM z(yIx!jRJgw06d}s9$5g7 zuz*JzJelkw{=61*Pay8GRrT89ild?qdtS?m zCs4){$g{J!0-o1G=qT5KrI%Pz``zflc`=3KiSxY))tlmyp}&aDwBX{;d)1DW5BR??SWFKF{c`~!9^d%e zpY=Ca`Td>WDBGWYp3n6>w^x@vZ;(H1;~IU{;f?^%*tiwazj(nQ7}0(?O0@|YCc-Au zx_qU;eXqHlep6iMz3)6-L4llXeuD%`5aIvFlGkTDCCx}u8Ww$_udi6C4p}SHXC)y7 z1c&`VX>K8`su;zNdYG2qNSAhH3!8h?fQPchHh#(-!|4jVemD;m^>E$0=Q97X-$NU;%01Z^nQ()>ZKHm-+#~v4So`9ukqREME@dL!iwjG?XXHB;vlhox? zDj6gPbc3q?8LF2lw8!B__xTr5{>yWwNQ=4I(cEX&J*oHgYS>)=aO0G&4#LI&vF4bc zgjMxQDh7x(a~tecCxOaGmqlptrfSqD$1K;^r10*pM=_5(;>n1`M0|c$$Hi2l84#K{0F9+yWKk9+*WUEZ>z_3d~J4TCxlpeU_Dvx#NSvo`|`xGY%sH^ zu0T7>NYZyPUl#d#Gf`#G=^QpyHXL+EvxCZc-+=;6i>b)COtOdOD&AZi1RS(GUUXT? zWLG>H-1dg%LNUI7uL(-|R^%}*M?9;RP;*)lH6ZC9*@?LQyVNQAxIOYSo> z+9?>&wEXmfvqs~jMJ)_kCP=P_O5)%9|7-yQ(?97&82=4@s4#&=I`LFO zG{RrGMJ8NvqSZLF6e^Biwp>9;8pP%PF<)YWk(I+$bb!KlHe|v>C@DOO_7bg%>x-cX zD~9>Yla}rcbwJfN0YV#2ZK5p{Rl=HWiI>lQBqQ!dgd|j5Lu;geR$r_p)pI4fy7BLk zazBmXmd8l4IZbt+Q$B^-uwR;wKxP(YBd1vLom6=ZBbmimu7n%s)?0w^q06n9WlZ8U z$^dpZ-k_FNd2Sc8_nxzQzzvb%&cnd!F=cv z6~^Dp@O1NWvjCjG50qRT3!fLGnHWXs4roZFrD6`=sgGK}PNUxiXvX9bs}p-Vtmt=7V)T zf0*wgyfx>0nioI~!}~f@rHh8q8$WM+0@yemq&ZDzBe=007)Jx&A(F%Vsg2AB4RoxR2}%_Fe-r{fi=dLGv1#{i5kaQd_v1 z2L1gBs~=C1#klIVn=x&l_Ao|LIPE$>zGlMHWt*6n4*@TIzqoWAfywInlVzP7>iVVH z+oxqu197*wdz~HOcI|}*-hHaJ$~zSl`e`al&#R3osC9ZC+VQTys5^~ke4={oH65Vq zxowfQ#^k@xLwoM!Gu@~0hLNrE_yB{j>3RHHEjZff>F#06H}4Q#^}JBke{s`KQELL? z*Y;0$JAa(Z2*hzmnSzd;kS(}+gX#Qb*2S%- z_K~-b^uBoc0tN4QdSeG)@CZ>6@iBSgBWL%Rl@msX>8TLPMu&)dNQ_^~r1sm!_Hb^Q@-P%{-mUm3;}1eJMx<~3_!t>>A(&&Zh8=G8ZYgI1 z`rBTh87u2vSknw?eTw5QF1X^4ERQEdKWrL6@m>e7u<`B`TIymfi)Ci}skFQW_7iCM zk+gi3PrYt!Mx@T#hy7bR7s$4qM(iP;A&vgnaSq5{bXqo{@XXhVMJ&8yfK9B#Xf@#H zo&h|DRYrUv@Ep^Q?GyExNaA-H!ZNpbRu^@(_~|u0RO{j608uK62Uq-E2sJhb{J?os zNSgu97`+_K+#z=@)%sSb^E3Uhe0kdqyD*80j)>$e=vbc>~NSL}a;Fx(@mxy;W5D z*2wT^G4LeITyelhZxoGlZ(?KhVepjT&Cl`A*x&vN&REh{SU)~6j~tRWb;vzXHg0CV z$=zL|ezl3!bc@**h}E=;U1)j#aoQFm#%TIwfuiF=-vAr4Ca*$CEFSdN3nq!Wx^1E` zuNm>ll-qxH@mmNneQb|^zgrCdnszf^6C0c&mR1&~!!vO&@zo~%L!nRKzhmsT$2JTXtwNB8uicV{-1UZk!0)Hgl3T?ILGy!8**%!MC9?{3Hg@Y;hJ~7A zgI;S|Qkp^n!)a~HYr4ie1EDSZD6!zwu~!zTx?+YQzO%2QCYJ3s=gr}RBgGIF2_I^u z)BSJybkv?>!T<0IbalXEvit+#ULyXVPRai!!{YvbKwbV{q!|9kF`3qdF;rV_|C-(8 zmHi1G+6O`c^PV(C4hjYdkK7UnDH2SMI!KC>L=qKBu7E03S*u>X0+GK=GrR)P*`;9s zQ5%K6zGS^z<>$8Av0NJi?9nK-*4cT^_qocYNH&E8Tt{vCT(uv69Dnx)aDQ_jBPM*F zA4f!4hTFAeyGJ&uT6V6Tpu16%5_7ayN-cFtqai4uxF)OST%u>c$`@y=h@qutsZxvP z9AN5*#U$4qylYTyoj|5)^Z;&4a~Y5CC{kp?e8-Uq6z0c~^mM!9Y+CNkpak|t(NfOmDL6#Am~RFewv={PlFUbnAi}BTLilddMn!n zytUNoY-sbA*&(=cOy{)3>P%szs4Q=;;htQ;LO{q97QA+yowZY(9AvC+0ynitr6$Mq z$fOJwRsy$0C$e=yF!XddAw-vh9gLYBZH zd4k+RA-{5bZ?gi{r7m!jgvc^4{Z8rD7cuB8RQV|!XlhJ0ivkTuZhIatpaL%_C=sG|OsmyCa9dU< z7`xTQ{;IExOo*A&DEQBW+j(DB0m6M%%=^5CDWhmw68^diahjYN!|W?qm|O-X-3GG5 zCro5|sOy!y-ZVWzj7VXhSFpxUV{_>WsR-_Yk(_XtqC*CRmWbfTpc&$nZf37>)Mj-v zT%77oZC;}nn=Ia}z2z8foeduFi5tn3e6%&pj1^Q%yBy5F)(kq2fy9SD5rc{;)_`m4 zt|I1H8G!cin!1sK({wav)IUR&;2bRSL#jluV0dIhFjjHn*y!~`| z;a#)?rbY;yG@SXTZUI8zAi6t94^9%YX`BdOfwVc`$_~{9ALQ?yb1u?&aym*?d)jBx zHs=G)H)20_a#F^u&3O`obP4pb56Oc~3&C9+hyjr#2CToEDUnSNg4x-PG?z<=re{tC zy`SjU4MlTO_2_e_FX{hiuWD3NWeN8d!%eib)};y0BbGMr*0pLlxzUg+wUu{w+xak& zTY4)j)Ri^22376$5;M_}PNX)wL*j*y02XMZCHpD$=49-Iev4}?wY7x)P=p_WG zvPs5KwjkyCNu;VrkQ=0QY>h}7Z)g)jS2EE-!Sb`OSII7wci>=J+Mf?CK9l==VufP5 zs+?>MwPy6eI-|#q;JDO$3zd~SBbm=GxmK7@UW}MWPbS0DJ$jR)nPhDqrioLIKa3R% zL!F<-kC_O=4iU}9lj<)|Wg#DmXezUCNH8h%AJVvD;#=|!sRe>ZnIn6$S@lX@ImDA} zHLu^1l2fPS)1G`Y8q4ie?K6Ao)5tfbmOF>w5-6(0FZ$rBR19G{|{m)L6e%v`v zBspRF^!>_io0IpFiXLVhZFbC5-7T%nExadB|Fr7nOgC$nz}zxQ1j+y0U5`<`(JXs$ zA&aW9S2cyqln(S(5WZUk21)Zo3QQBIAG&HhvRaU!~IOPVzdf|p017S3MBxE$KKVm zGo+YX7kAv4bQLmZnf?u!YukMctCOP0NKxm!VuJ!%ZdyL^lEFTF^wA4-X+x z0f!~f8DqKr&R~+ptG+5vTtYu_LbmUcHQVr&SbC1gQ}gi8j|_h78~u&IHR^{xqhW#P zJflG=ZsEu$vQ=8Hn`xn$v$Ye08+vs#WVPo08|InquU4-a)5+nG2G=8;-Kni@ieCe5 zo2ql_Q~`fwX+5}4vN?e=bU0+A=Aa<xXwHsU}q<(&yWC8M%fMr2zQxAn+%oAo|?=}#1?2gl5OUm(2xeZbHgt^cf=(rw1P-4zJ}da&dFEb9RU_ zYvLLE5iHp?R!TI7l)F!Xbcw=vf7D9YAhF~*^ox0hY~(=XTUziba&O@LALw86hrEK6 zA|bO%>|Lbx?;`Mh3?zbK@fr+vh1)90uAlmn2wN1E?#6*nU`Z67gJg}v8DAi3RrQuO z?2T%o)yiW2$LJ2;Lpu9*NL#`l-b1|mdgU+Ok{`k!C=56j@8L#Vxjq`sr;3EPd7eb4 z-l%_%QHUZ1d4~=7_5+5n6JDx43FZN-kV%psaq5oYzoye^+Wx}i9Ls0*=lGwXzzwkp z!$B1px;C;rq)rof>g}LItev49mi*=o7|NMKV-o~zejW_30C_V`tq_aF`;DccE2e#p zQaLc#<$HlX%D;aNf9H4`C0PPD3lq(eJnlD9gyA)0u}?(EEG~zUvTOi(T^KQ}R{l~h z`626j)sQIfY0JSpZ?$;SSEou`c3T?BIP42*OSV6oK$vac#A}C`Finl=Wy_!wJ^B~( z+S|60Ba+;G-+@pNUStm};a8-@J{xue71qI@GX){6RK48PY)z9*Xe0naTF?;3kcljs zA{l`qRs5}!r_-aKY~@im+^Iqhj-$ukDT45jb4;A2~EG|5<6tq*WUkUn-vtVZ-NPt_Gs4( zAwwpccb0Y9M;*+PyuFFPt;w!|kCvI$)d3KuJ?^G$n_I9n!%^cXa(1CNJAQP4@yiqc z5Hw_E?9~z83r?49idA;m_nJ!}f-pFDK_M+JT{sXaK7R*gMz=N1dD_le(C= zlvb2-_>dY7^YX8v@}eTuIyW!x!)2#Tr^p>*X>t7m%Ys*bY*u}78JHWGM{9jVsN$w< z%ctkU38^mBfdU)arG+wVt_aq_xCx+4_5`oZ09V}w=SuF~dCnA=?bxaX_;j+I6@T|C z;5S$xGy-S<+D#q(t(H0`Ydj2^OWw-xpJC??ovw$HE2$Bjcx#P3a z8A`qecHM0SZtV?-k#GZ}M1?$d4WZ}{D=ND(I_sjSB{>KHg-Cb#LhDHf)uZ$DV;gG| zB2y-qHe}~c+QoLk+E&5ZbmX8hJa0I}1u<`~q*Wg&pD!e2C$qI@-Fj`fMUBeR?oR(Z zzbo3A=S_1#g|yFPXcZJuDaqbEe$osB_XJmQ>QcIq>`qu3JndKBl5UA!Q(B~b8hxCy zL!l1F@P=t8KS0w-sgh1$INgh=l%TY*0e%zT=!6;*oZ7Y1l$g&}Cda6kh`nYvj^xNP z=4Pn-q9;F*-hFI??056?ola+?q)8;vX>e<@Qgrh~{_Zrv4c+3w7hGxnf?haqm^cF* zZxu4XH+#Wvi_KPmVNljrYkljGex;eTb2YCy{jZHUVm+A;BZldTe&_1mfh=d-&HX1x z+|mh1T;sg*1eZ{;TgMQI|HG>TL&L$FVK^b?6jU?v7Q)|v@P%%+(2l(#ex(b)6gX6j zHq8SsdV-{Ze8j&$7vQmX)IrSH=u1AS)=Rsyt~x;Ropdp|iF; zt7UiL@7E2vS)RoTlxw}`CVn{dfSn7ZAPqs$-XHc&$e`Cm5MK>a@q;z^!)OqNVJCpr zjFKFhfSfA_J}!OZ{qa|TO0^1rB*d361I-WN znlQYnR?$I3x@OfLJR&cP!FGzw zf|(@)hkNBErLcC7!3Iejq3m%82S(1TEVLa8;t=%M+CRe!a;OJ#=L2%b0OAD|*!3I$ zKc+mHI|F6ba-(;lU_wrV>{?TR3Ry0td9p@9C1la0arnR!q<|nf3C$~ zS3=C##G)V?{Rjb?VX{Bz75gCpvwJ$Z20Vy3*hMWW*XNF&2?}mGqBAqaWQI&n8a>^q z^BCj2Ju)BbC`m1%@t;wK*tzTIBR#0)1n)c94vFO}rc<=Ghsc;BrF|^dgtK%f-3OlL zMOEWXuL?=16puRIsVof2{At^7e#fW``j((lz0)G95GK|89+|&JJTIj9*86DyV|A=d zzl`d;g&nAz`}Xj$YqDXjODwv_y6=#l=K#h&;d&-TTWoq3s;031EyUf0+2;7A1I8AR zUs5H}dLN{NVJ!;5qhF=oYDVB?C2=?X^g^dd--;kiCj92GdO_$S$W(BMQO zBa+6@r=)QULrl2T;frd_Ngu}O)0mlTil+0V%xP)S_}bLI0Et88+_7?VWg!ygIEKFa zVdI~dsNw*fslx7kH6Ug5X+ef8(%vhxvPdr`+^JuKl%;WlW28#up`O&UNJ_L-xI6$; z!d(tB+K&x?ah9LS@Gv?f_9`gaK_uEwuEmE4(lORQtm9bu`3L`aB9eKr97Jik={5lU z=Vv6_b*f{G!D4_YkiFm$&s$r8iT4yI<-*g2hV+xaz_-#>E&{iA6t_1*UO&DM(qhhY zrs%dy9NY$y7Ap__n04v~;^vO@F9Mm0V8jYOES5_S^X2rI>}2z+mj8+1XukTdLX1=W z+*%{g9<2EZIEsXd4zUQ}w`&x_D%OY5r~L1a)On_cU>0%iflZkS3=F1-RJGWSFyrPS zA54inq2d#>qutC0osuP75rBd5qWk4afW8^}@{6U1TSSr&0+-wjL94Eu5CX-0Wde^>*ugI~|gaB!L$g89ox zO;Rz;s!kA6?=|PI(TUYF9_x}sG>xuIb|pmD9dr_%Laog}jJsHiiSa}twK2G^r5v}_ zcQ@e~JZpdL-XFV}P#g>9cwqllJ0vRE*ETq$JDfc)Y=^SUi?hBPbS`&sXh_8`$_=U(TVJ?hjskvB!e(LbX_c0pRqmb){ZkONtd}NZLCs#nf{N$+ z&-abp;W!kSm!kutXi`81(K;A5^648sblKn|oO=9#on({E%ZGk9@$5O(Z_uEvJv$uC zJlF&BWFIF^xdTF6lB-gDCqay8Q8r2Zvf+Jb^*#NVj<|hcTBB?@SA#U?*}_{XIr~ss zf3a8-*nA$id7jCFvlL;csQJa3Uq*9l^kjOuVOqIEQ%v-n6*CDebx6YZWF;by)|`cm zHqO0*#xa8d8HG{XqBr2&c|OIhJcp(eUK>ApS3z}}b_P0mV{E$JUpGZ%)V)CNlaKMx6A?4X5(bH>ZDa zR|YJl_`5`H)h(L=g7XP=+3=SQk~{EDwQ2yv67|}X&+k2$rZn#fyZA58 z-Z?t6rrREk)3NQ2I=0oZZQHifvF(m++qT)U?L4t_^So~YyQ6nGOKO^qzkHyV$XPJRPe4PPA&Tgim+#c6kl z+5mXr&>(q6I-0k?Rk558`-0&U@vm1MOCZl}rFtVhtYJ7TwP=PD!Nvzb_y zxS`d`%$eJ{$SLk!tT}`Wa*Uc^JLBN2QdEpWyF5g5!oNW~{mc z&@>ynRN5<=ZWs*O0K|ay8httGV~cfiw97*Ij|KscSvwI;HvD`%vqUGthir%RpxY}$ z`z-hjQ=lUOY@2lP1Z!a>y>z&W2(z%thZ=iBY}t6NY}?Ut^22V#gVS{1x20!oQn@ryPQlXn7mJ_;N}_y+Z=P-5uKKRH-d87 ztwB#|U7|VcH{c?wxefx7FV&nq8ZKeC&NN*yezsK$v{m!FVhFfmd_4vKdTwFLxeo6g z)Bd?ap39_tlH3cuB~pAra${1648J75rn3uI%e)fg{B$em6M4H0N<2EBv{q>vT(v{Ia6XRD)R!`+}rkO z7#DK+0l4%1=amh%L3;?J)nngVn|WGg2>Ol>wpcn@DvT?$bj?Ix<3gXaU!OCyG-|@} z#}BP>)T*I&K_nSgb*v$yP#$3^WhznLoTH?@scZGn>`W{A>QA}dMqMFhsO(tknAI28 zRB{kS#(niL#mhG?nEb~#JcpAG~Yx)Z0heAEH&hzon@T%V8&aZ4&gh8!+3Rc9EpqV+9TJ@u|RPWct{=UbUL zP`X2uBx_28))OtX2*(nMAzB^-x?e@>GG0UG7)<1)e2O7ZyX}{Xw3` zfXtti1j=0TJya7|Z%N^0@fKbZyu1wT0vk87Hu)#vEan&QWSz$_+#R{+ELoo-22qQt zQV;BO>Q`z!2T#+hdBnKsV)}P3@#F&%^;!*v3=*!c1S1M^dyfn99g?elabDkqH!PVO z4EE8jZ4!b$abABA-rxk>kOVJS@@Fua8={PT0#MG;u1_v<;Dw?DFHw$B?as`CHU#of zm3HORQKewjm>VRQ;Ba=C_)4#VLSES8HPI}|O;P435pzysGZ*Z94zu{f0+31J+eRgg zT=!!sYs5v%fUmj@0;+pHnXHKqIUg$4ZhcdMiux&K6pLY^<&NQu{+h>ev2Zrqy#t&1zWP_4J^ z0ihv;9+WzPIXftpIfr4nQ6!%PnalAU$@3JuG=iii{5?c{dncOleTPZ`YL%b|!*dGD zyT?@plQ$bmw+L)<;2LQ0lw^mosU;g!%aV8}-aIrJrp3#59HHd~NR@Y+G6#8G640TQ zPNcsZ&`D84ixTez6VF5~Hs#A+PfButPEsuV(}0A;RBhMsl_UA7SOO4{v_=P{^ad`F zAA`WCmc`+7+c8}dhn`4k+P-FEiN>^AYe#jLe18&zn=9GRLt zN|c0|kJzlC$3p3$-`TbV?m)zSC~tHw9eVTY1^FXVFRPBiu|klMlT{;!l`{R**_Z54 z!uP23?!nP+=u&+ip~o}`cnStIgF+uJoAyuH{9tpW;k_DFf+dYLI1mkF4jNDcvTv2Y zvogpGv__$_dh~H|ExOq}^^C<=OANBlgwlut|Eo!ZnGq{dq2yp2J9h%7A^1wfN9(Sb zyp6>J#%UdYMeF_$9-#A)p!UfG52*mxvfPP1+m1ckiN!(eo`NvKLF)d~53$q>!3Kxf z{h$drd+Mg}Ng~1PuA6*HBHc^Ld?Y!ycu$mjvjEeQ_ASS<%LHv{0;)nEsHX8f!&Ot$ zRC-&r9jxBd6?mf*XZ3N9N?>(UwolfgAALGVEQK7VBmY%vFi7W9x4Tq7x8Z}t=VJ{? z$hB>Aq*&F2a`}KZPz?h#q^i%wrO$Ol?Bm_J^^{b69>Nzu8K?LDD^!L{7V&wkqgMIbwHJBQAriI%a^1p5Mb&q%O?F zld$DNiUIsbu&wsQWs8g8z-3GS?sRUV$G`Bj*{QA`hli5dKf}?^irI#fm!=hF(;9kT z1YCBKGW_hVg}2~kB->`MELX1yB%b6^59&J}^cQ>>Z&|vp7t<`CNk_jg`Q#REuHgWCR!E;qNLUo6*oM#1TMbLII7!8*P&Gx|0OKIloU=|X{m_EM)~u}U)C{m(al~QrTSeoW}(wcmw1Y zdKTJt-J$52N-NMl-Y9y4eZerUxin+se5f1AFv0YBRteW+SpnBXwE&^XsZD|&LAp(q zFojZRKyiJmSg#fw&tvcl;86(G%g3RrCM&9$#VhEug)myRb;2hS&;{IppY@fUDKonXRAvjZ*o?TfStPy6wcvZhQDV9DVdi~P7g$urV#^eml2<%kZAhN35t1%>Fy|nV+8E$B8CVG zmKPffL)p81c;{N>Y$I0=YcT_F)Kac-qO!TT8z@MTjx@#x51c+z7tYjWw|u;_7+n1{ zE>lr@rf%8ikw9F;y;H}$%V9i)QNvSM28{;8+?m=o8K(eIarNIf0j-Gar`rUj45}Uo z&iD-7Dt(LW`7GGZfQML~H7m43Rg>Rs1o!Uye{Rh~b$+7U3taOiK;Nk|OY#Mc-EsUe z;c2PaSF`cvZC-!zvT414UU#^E)>0cgKvGDvPd}(outd&U;|OMcAs{o=St!=tB2wMl z;n7O)PqP+%LwgR1i1ZeXM%(nN?#%h7j<73S+VH}6c)wv#I{O{g-|3q-R_on7g|x0r z{=Gw5j_Mq)H(JuRPFZzPqX*jJPM12H&%{zRuOne_ZDhL8o)C))c!y#t=~SZsD@8z7 z>}4G~O{A0g??s!|MVrD!T1wEyt^!LX-MJt?t4JWmH>{$m&xx3{oa#6rlu46nz&N`n zRblNUcDGYY(1p8CC19uo`q!4u+<4X*&?p(@TmaGo_nLvTOZC;2six!odFs{Gq+@S= zkIhBOpbghDoZm(jUE)R~dOO#3^lOwNZq^X4$70dBd3^Iu2OZA%QV_G)Cuh_mUG%nP z#^6$mj#pIu6E?=DDeSgnCP}!nL1%|;&TSYU%OCm^oKG6LM}xhG?!Tx@#K3!FN+du) zUZ(#Wb?Ki7O#iLp_aCHc5{7@VmolUH!$J6Ag?}y7Hlm$Za$!`_2mwGi{pkZ>06@mh z$F!wY@l}8NCk^1Ya|c4#)TITGeV*J~`FwnUCm5t+NyMN|h_o#GHP2G%H#J@1;>hvNze)pLf&K8TX+e0+mZ(3h7o8EA|VZdCMf&4g@&P)R#`_ww+{v z^jmJT&Kl<#97v3+*~ZLuOWsc=iioH`1*ggSY{{LK4|K~qocPSd0IXfsh=-W7&*g9AnJCG=vnVUF?+nCt?mzlm~ z7C;yfy+KF%!u>Jj01*L@ciaAHn1gP;sj-MWKRZ$yYa}1~o%jK!?%x612-l)mrYTX7 zd*EwQTTYx;jR{jnORtc=5M`Y4CC6g9dHSOLw0=caY*y7)bYEw-?a4ftD08Y!rZLq} zqpLfhM2j~Bq(ob_Jnn4vuL}1O0rONm``I#r`w_xrTQ^IeeTxw zNg_9g1!3=KF3K=1!($_HfLI{VhTpL z9O|ADpzejmOB{*|TFeDB1+aH!3?>Frqv(4RA`Z4j08@Gev5w4wyEL3SJ1lq*=E2Gj zj<;Z6`oz$B4isd%^kfE%@6xo>D2MwaREETP)*{cEYKGKxDFdwKXKJQGM7MB%jqBXe zg|o%in1cT|akKwq?Q#8sapiY#(06APQm}RX+X?<92K%oe-B5S;(p*g9Rb5LUC7m(= z$CV^2H`J8LNL@xGXJ?mT{NW}}&DAR|6>GhM6h}%tzQUQCU~mi~_&fOo)l40PsAmQp zGqgStu@7}jVbxCt((J_PHPbc69oHj|_UH{6dFC&&=jX21ONUF2E%mE;m|yJn z;i1W4jF8H6it8CJGxJU&`H~JlVzTUWo;_{4`X}qxxsP(L=5Db&V+HBvB;g(A9$Oyk zM7CVzXy1L8-ay%^?QY9N`1X&?Z9d}C3G8oW*E_xv3J>jkwx@&Pw;Pnp&Xa=dIlkMo zY33J>`HvuxZl{^mB16-No`F;#c#K>s}+1qB1XV z-5PyP;N? zZrt;G_?u8Ip6eJDSzv<-iqx^gBR1)Y^Lwh}p(1<7uL{uMA5b%;N}lZi2J! zZY+eDHC8Ph7p2qA$*hK!6;b+|!>Qk}+k9ja_Iq>AyD5b)65=!s_u4BYCo({fJhko- zUI=-o>)WdfroaQj&p_c7PeJA$oQXEsyTAh9bH4=fTI}j%R9uLlLpipJHonAfuudeE z9^w!Bk}>lf@1>Kh+9=rX2=KFeDP1GcC`-a90Pl&r7Fv3L^NM7twO6z-Mp&7?mCE*3 z-ktUBN1Up2U-#w#SO<=sAKd9F`9_tb_!&K=)AVnlIWTy9=EC)@GQoetTf+2I+Pyzy_2%6*?BwaEb zq#ktwfnmQw^s`^!*6gk@akvuVu9^8sQZj!4lv@?bi3UDx_|i^Rk-mBMJaYs3BSSoV z*GxgPxLS(}+L?IyFAOM}&eo#c6M4jpR_}|w8@)Gn72Jf?#XIj_rMq|Np>P9Sf@l3+ zgK0b#;W~Yq+D;UU4)Zy)SK4Z&3-XAsYi^37%LOx`q$eE0ZU>$t1-m3C&{?HXTLMMh zwC^}xIwVoUVYCe3v0v0C76-UfQt8lJ1_b2ykt2j^$t11?bREJJc2Jyl)KhbEI%X$i zXHF|%Nsxfzri6^PhA_QoJGe;eb0X?<=@G*ghCCtEfXy}OGR2THpKEDgR1>LXLiX64 z*#rqrtW5LG-`gX*yGhYu?jVTc8ZHJ6Z3x5yiRVNL-t&O$oL~cqwTHBycdfeAa*8G! zh`^v#&1@wqy#^;f0(u4rywRnpWvMvdy{gx-PS?TH^$MXKFk<$TEdN+d2*fArruV%H zYM&X}Q};m4TWGp0RF}gwoSRu_HRrdQN95T1-+}F`M8`ZIw;P+8P?*3Q7FLyZHRd9b zder*JF2{Pea@RsU&FPo8Y`QgX@4ws@;9In}^-cI_S2WY5ev{1B;VccLJfOywj>yN_ zv2wTQX`wX1Jx@vy(I>csHJQSQrc3luU&js~Myv`K<>|8P?8X}Nl?HQRW^FvbW_!_m zYrOxcJo|HLrn%&Qp1rysLngq(_&ScGjA9d0AO3z~6op1L{Henf9TvG;9C@gfDY>CF zq{mDn3HESLF3>`M1jZq9oGl|EDj)hQk;ptmk>pY=@xx5@TkWO-bx853ekUTMNf{YD zA89^B_Gx`J?G9a?!$C}-&$Ddz;SIGeM}0S*>8}GJd+HJ+0XB&XOfEbldH?S+BpU*{ z`Z<+oXLEB}WBC#wZ$^15PDt93AJE@Bl=l#naW^gZUoFx?cqw`Amh_CMvdFlt3%iJr zWAaRkI2+(OG^ABD#4Tsj3#;>-8?wY6J|byBNk3~^;Vdp4zCvv7YG9}5jsT$LXOlI@OroD6vr;M}Lr>JS zNSo2Ia4NC{%nIrvTSjbX@+qQqrJxYi3aviRqf*K6W03Y|`(q0}1sF z6&B7UQ5t2|=1FS~q1&)%%XYin%Z`X?8{sMP9ah!f~0wU4Vg#5JV?TefSSgT643X|JGj$ATk(wLu_ZaA z3*Up)n)aY7focCv7F40>F-A(%e2G?h!Pa#{?n!ftXiDyUiOE?c3mKv{qPPp(NysA5 z4Xoc9yue|y(L12psMzz6Z6#cjpa~*>h-J6T0}HP7qK&H(J!rU;6*W8(O+08QrBc=F zHwBr?@9gW^XwVKBnf>@-obFu0X9di0r~MZk5g*%~czI&jpFwDP9XUEle(OfBfc(Ty z_T3XB6)E&@Re&}Ei5gU3IH6aioTWsYNKz0>AX;6-ToXnDuTZ`Wcs^*XRRXsodL#}v zO)t2%NPCr1#+6Ruml@d;$a=u{I`bwOMc76l5SS$BedG;{-wG=8AveAnie_QX zegSrZS5cJ*xn(_9mjXRDUse}tpRE^^Pmu&QNZ+VlXe6-r;;FF*%I#FpZq4bE#g4^@ zv*Pnw`YvAytoZXBQJXU{P<;Elj+fJ;2; z8V=4?MIr(Tyr_;3c5Om6s6}|kr1^_|EtU8yU!M##g{Ud$ z(ozmG2~N32!x<>)cQMNOT&gRE-v?b4iKci}9rt!#$c{N3?sA)6KWu?p2L;mT!b_y6 z^CaY@%7vgRQ3_EJc`Y!Eoq(p#29RGshHQJ=szaemC*FbdnDpM6dtAR$=m`Dt8=C>X zX2pW85|WS`QbL_H0&O0z;Td+^3^)>X=; z?=x1#Jb9TAgGo;H%lx_+{2r)Rf_Vutp|lX!uj#b##+cG$>_L+@e0%O zl*Ufbl-y_(^RX%5voI-9ea5eIW8uHUM}Nn&5P7nhB%(1fjfJPfs@U*A!wtZjIeItHf<7H#-a%(qB&l3PCP#5x;k%3%~w zM;HNjXzY;yuVhgvoEK1T3&;%dB#Rk?hQ_Yf9^*4>a z6*>5$%>^AT*gjIbHfDGDW_O6vD31z$>{5ffJ{n}va*b|4X!8LL;@p82C;V+9+)|zl zu9Z(ksM+1BTG9KX{NwNzEFuR^STsrIs>B5G`gJ;-CDi*l_6hahJ5RzE{e()${}@>0 zb1{@JNqR-iow!i7EsYj9$gNEC?_CyOoy(NR#{*x|-d(ALoAuxp?|`0!U;hwxix0ns zR|NB|A_(rD)GBOcIWA_`CBte~0VaLE#;gKc%Yj(eO^~QLk#OVIhVnRp2HA!BvGXI5 z9*i`@7gH$vT%9!e{cXrzX8!CSUV=w|4Fj7lG0i4MF_3_e#H56T${#*udl>L=8@m+}rtC zbrT|}scI5-J|K29;$C;S?GAXmO(1qY2zEYTc3Y5)>^vv;1Xew({3my8c5vtn0r06H z=nR^#h6vDylBowN)(2z%`wQ;oGaUF78!7u1qn9(j+jh>1{3$>{;Y_}5W|*Bp>Lrw! zC?;@Er%g=TWF0*^+UBg2{`;i0XxvegBe}T{F6J+ySr6X%(C{ZA04u#m2=t(5gII^G z|0C5p+w|)s0<9L2)0OBlmdJQRU{`Y=7&o>&^^w6Hc#gNG}4=E?G0A0xb*VhB>1=I5(StWs?LJINlh4+i3r4h2EvA zZA&((NKf&nRWz>)=&lE(>q+_RMyjV(xOyC@EkuzRX-@xM9I6D0cCkV$Ba?_}xZ(qu zxhHnW4h9)8CXP`Hhq!)baB(BbNwx!p-{#oLX+;SH?_`mUX*Y=pDtStsvSgdzDdSpB zkj^*j!}T~DZNlE&kj~W@{b#v;hN?o6h3fq*p$>~x^*87tiPNvIE1UV~m!BMC#_2%? z!bI=|fTRilIRa~kA9-{vr5}pRS&*PQqM{x^hx__}&)HSZ_wUPw2+}EpKn3zcl0RKG z%1_k%DPVf?s^_;wt8Z>s`;1a86@Jb*aY?iBcdVsQIbHLX(TE$f2B? z+&7ur`*Td6P|_^jyw#yTDL8H!DM&KXUmw4cKJPXAyF?{3>@aWG4`(T13jVb96;_`_ z34OKXff*`&$z;7zp%QULgJYdZ=0bO`*c0TRs-VZT;7*OcHgHlU=wwb5Ea`trPs=9g zi6JaYLCU557K;oN(*O0+V<8D@nOsW=CBMcV7YZ}FZ<;2`Fy5d-Pg}k(>LVihxjCy> z1whBm6Bz2%)Tg~YC1B}5D}M3}{yqCclAk_(ke;P4J#EB#RR~{^iKhSdyJAG!e5PsW zlz#<1SkrecT~b?DoAtFzB|hNO@0IjIb4M!W*_1XtTTu60$1XF6iw_FfD_)7orf(od zr-YLWzaL;?wf(G%6R^7dSJ6VbQ$EggULd1s!V_%g6K>p3WB$S-RhIzP#Hc_(_U!+T zG5;qP$@34eNJVoSQ)erEhkt>P!fuAfc24HDHva`M$8SmC@S_fOi|1JyFq@aX@9`me z#@+Stca)G7B3seSepRl`orz#vflY_1Z`Ws}>K&eeJZ5TO3-a$glO`y0i*J&H&OM#{ z?Fip}J2}C2yLYr?3)EDTJOqM{$33P89fQYhf1OCg7b^m_5pR-{cU|$2=7+~PaUr_X z6F$=v7=5tt7-QeoVDCIi|E>@;)@2}uE=d!-;Ij}1%b^-{Lju1#$1JR=SiCKQKMIXp z{Nl=F+-}iRb0#u$lt>!GK%~Cg-5UbuiCw0|6mS$$vMl}I+{C~ zyBG@@o0!{}I~o7KPKQFJ6Px*;h#yV%2H0BBAi3aUaLynLKgSmni3i{rNhmA?g?B^` z$RrK+-Kf?m(5`&lkVxR|p`d(-@u3;c5*5G^D`N}qC(gZ?wx%X7o3FCFfY?J6u=8i; zXJRjgRrdECD5b|wd@_1dp^2mF*~yb`%_9v32EoxVuv`MU?eJ`)A#T2_`voLdcnPqb6?irzv5@mu#=m9O|%M@>P2JldrK0Q0Q3>UTmDAz&08t&v643 zP~oO(I?rD^R?X>dat^6IjIgL9IE|fuu$`2PkXp171*oI*&)X$uctqeh&)T4%hjEewT^Cohr(*Dh*hrM#`2Zz+&RjOZ@<%ZxyyDrCYkH?NrAMw86ZH|x-@nu@@tQlR-+tKCYVXVaSsu)5p#zmeZ(IfU9dZaQwW=u+cJzud`%#k zCMPj-(ZPBaOG$9i8RiHv=lLp)L`()@%qQ7&%Pv&CPa)OQ2W|irAJ542um^-FNjwlc z7{8wpN;;}RbpB(II}r7PplIG@1?Mj1WAv+Jg-!*j?BI}BhR_*j1(`m38-v|W%(fwW z7sRC|C>5P&PxHq&UL?=Vx4+9v{Q%gn!hf9y=|lYcI=p6S|CihSpC9Yjo2`Q>oxYvE zp_wtAp{=#Gt&Jm{wZ4-X6P=a0jj_H1ouZw-gQM|(3TOvS@Id$dL< zLb}o;_vh$!bl(q|v{@DcSfS(h2!@H1F0<3md*6ESWdXUUVHQ9P>B*=a?qFBqQx*q0 zZ%UlsRqRI34WD*Z9*_l65BL|NX;QAuF!#Eyi|JmjDC>~kR1;T-jLLZR7E4w(kz0Lq zdU;C_l6+Nj7EFat*L(Q8vzUPc6k%Uo>HqrwKL?vD|35nWS2tCR4V`QqNQ7;i9Nho4 z+axKj{k6RCtW{hLSka>XXgK(TT(TF)*?>%!BT+&TU-*sWr~6hx`9P8(@o?#Ob}S+? z95R9z5J6C?vlRAy*vQtTT~ zDgk4_6HAESV_=)391({H!Us2-GT0)e&bDZ;OM-XAM{LA{4PUNM3Z!$2zX~q?DB*`R zFVi=^a3u%au~8u;ubRHYdnx}8j1bC;Q9FrK@Zwn_y*i+l`C0s^+vj-a!-Eem1EtI9 zaYtXSF52d;;d!GR9mrMtdx!CNCU;tJurUxcZZtRF5RgZ^t-dbbkfxk`F2ox9sN7Bq zDp;1vs~|>f58GGM#4+l4qQ}q1L%2i#wrnp#4g+>xX)rD)KMAM#KgUGPKP!vYz7GK9 zZ+-Ueo036sz$AZ<9%^3j|@*%A^u9%G-hB+?ljQakZ{H z8k}U0sA2>UKf(HZ$f%P5k1( znA2TrkyMb%)}%c#wmi)wsiaeVJEwhSK=(P`cf673{XW0Zp51-ES=`#+>4CPn^#$T!95`O zl>c>fS(hsz-DmWWag}kKdF8cr^_Y3J-tkmzs|y<2;|@AbZ>Gl)?4JlfdYD<~o}%R@ zHLMTH84SCO`6rH5Z#&cv5qAZ5k>UI6toz7zs@0H_Rid|w%#qVRoSI!>sXgeh{ESCT zHrJ=pD-H}Cs(ienF(`_g*04C<)gM4$kH5d6X|s_?##>+}4VN&maY@Yl?+l)sBJ+8G zh)ml)I=dA7g#!$+z2~}23@4x=eZ2MAfZH@hWND!OcZVUyE)ER%s}bKM!8L0o%FG|r zo8NN~ewW8`1fPdic?Z6}Z7V#xGyU31D~eNaTtV*-cF9Z;F0JMkt3i>tOJs|4X2F*h zuj}W5ih7u(UYitFQ>%k{kro?~v~GlV99lT85x*6NCi&zV2i@L;DWG6QOqm@$5gp~x z5r>~70c=FEEig0hDBdokhd#knVwEG;Y}7NXqHGRQQ9A&2$o4f_G)8h0EGy~X#gUVL zYG2TQ`P8RxkZj|`hm|Ke?BT*pOrt)wJbV9s6XUQuZ-73tOxcA0eYiX93A{HH`+ka2yY6sAnOr-kAGT)^MK4s*&anOsaFQ4tuTX z8+fmC2SP|&hTYv@ncr#tR{6dCKxh>!Wym>$5x~n$G4q;?o}oDg=#rWm#h|#DLTydP zuUw0(;xXQRfAS53mVp^K8VP2;=Eoyo1n6^{?-JKN|CkyvN&h)qQ9=6pvN2pdFPiq2 z`gOygXm5{fY8Qo**L+v;sUd87yPh+P6~K`(4{%5S(@tv&0vDg-_Gc<)fB=hk$PDby zgwdsRvJF-m!x)!wtgGPfgxVEVQWZy?G0xvv;G0yxn3Lj@_oI>?%eOcvuN)(&5r&YO z8=ANADaMa?9jVsp+OEUlr&h-)y}ingzhQMw&I)JfCs7{VG)qIUx032oW>f_A+}<6_ zUG#)(-t;(7Bt+RZMv&sONx(WhK$+)M%VMiNe>Pvxu%AfXJAK7=P4zdW`+s=VsTOwu z0^;9~)Gab8b}brW=BT5X3!b&*9c)C2hzx%lu1HPsB-qjM{YtLS*n}ZKRX2J%C>-JJ z_lcusId`6_L6oN&lTRj2dXHZwNmM%{eKN34$r)Ou>;3F#ZV$TPxvrP^g;(|j;lKM` zV3&g$eVTZvQO%i8qZay_#J%e4U$-lMV?|)Pr>4!L?nKlh%f0P%&e&i|Zwvj>Ljtm7 zxaEJPVS8o_MyxB;j~WRqn>EmJ7I$^*>6KYlC_<};bN`l{b`A)6Ptkuc)91TC9N$Pz zvuk(OHJyQ0sIA?A#+P6|)t`hW8=8Ah%6S^=)-5lws+J*Qp1DjP@IN}uwdn!jeAGVP z^;9F&@g?=~H30|?3`D4r`UKJf47sU&`obR+aZ&mD^#P78=i^$Q0v-GO4&V4;^TG%^ z#U&67Y5wE{AleWMSwe*c2auGZXp<28;kn`5lY|zZ5oU?7d3^h#=~nEO^*sluO?N6I zdX^JX0{gRPzp!1w?kY2XLmU#uk6erci{BOSgNr-Fs1ZAn53`KfS}Il7xCQqbT`JY& z^lPU(Z@yEJY;Gu5I~V+=)_7M?81zELS=(+eX+1$KAo~E;2P`f`zhM2uDLuZgp_q>Z zuXbomolBE&?23bykgjXZ%$?_itgIS+4U_;GOHGV>xA4kyq1pkOU1erPknYcds4}|3 zGoNt~#xg)Rx>7x|Vmq<|M~%@R(#cMg29L_ypNSXS0iO{!4lz#eB~hARDt+|JH1XFt6cIe9NzK zSZlqDO{b?^rq{E_4er2$bf z=zORUk2Mn^e%L2+I6>x>(2X`hL&W#pBE=)T$%yv?*80)f?7?9N1idC!heeL6h?%jxhmAq-1kDlw!`T8NyHr7oRJW`yKWry7bl zgJM?Fwna0i3VCa#;W<^rR<%cJ5*kXRV+khoALBOVGI5+0NLNN(v|uh=(~52zC*-6_ z^<2lYjhxQcTI!iH8z%;pwifXirfhMRZN7d@hek1{XLp)D(M^GEEV`yW&~i4nRU(8Z z+7Ti&xK=XsweMjJbkCqrY#WuzAOnx2MP1$UXVp&}sW*h57HeqCvc*qi%yN;8P3S{^ zASBI2g~Cwo7egtbND@gn6IqUxIYVDGaErW@P6VPYg-GOJ5KCdmRJ{JUuKWj#v2URiM?*6zSX$ z@)?n#hdNQg?Z1n+H9|H4@V|<;xgh>~DDt1s%g=uhiu@b-OVCW;#`Ft`Q8E8Y!)^a7 z7KxIRmhAtD=)J}o6{UNR;U>-9653pVTA+rg0fytDJ5Rb&w=!a)`DTs(0{SMuO9GA{ zKm^)9!F|}tHt{&U1l$8^i3E@`oX^FNHOaMc-4Is&Dg~rV{JXuAouSzPfU9 zQmH$I7GUH^;&ie;xsaJQjPo*XR^mXUB{K;Y7^}b>S)TE(aD`q--<5)nn=zZr9M{!Q z`m$)$sTR$%w~?OXm-p6K#VoYS;*^O)74wGknnH4)`aK7gne1<`jkkijN4OLs-jkxF zxW1ctXxP2a4?&1v{Ip|)V-!pvB_3F)N2rUP$U`Lm?&pk~W$o>{O4YxKrqx=C!Ovet z-1u)S%KuC@g#Lk<|1H^IBvH1pwly+0G1oV+GXA&Jqfp7(a$XMA$0nVXE~+S<)49va zVu3YtvaJ=NjsfBA{($3J#h4JinAp_WZHA++ zOxNer8`@7$98P9xoEdvjQ7Bh9#w)BEd)+}$P+@K*d3kx`A7ngyO{&TZm_2$;{y&A< zz43>?o0K&7AI}^JUfu_u1qJY94qW<@cRDv;LHdhcO7_0u?U3plRa+x(BojQ1vI^$M z!)aX5|7h1&rB|~K=OciF7rIL$xEp2Kg6A1Kh@-n$C>@!?I(!J=U%uax5%A-$C` z=j53&wHT+?U}NGgl<|1#0d4>u@m0o84*s2fjq{trawq$ugH{2n$)_pMx|mzLWXW(j_f_zBd1SAe^RJ-CT6Gfw8- z?(2I9GV$g5@7O>Loi1+OM@V1PfN%1Fsfbtajf@?X)F>k9{r*vObiAm}I~#WuwrTWQ zoQB2+bu>$@e8R^l3cAJ;x(%c1qv9vpa)nj5zw3ewwMz;9kdXS)t8oo4uAd^ZBgRid z8aIwFT)LSkqAX-@8&NMqbj>CPmY}aPY95PSi4X4P#z?f;{$&+~-rp?9xg7WYf6I;I!D1UN4Nu ziI0Gn?IP0L^vA0;^N4GmGNR)^m9h(CpNgA$`cM^jXLY=)-tU`G_>b#QVyi zGk34?hY!U!(q;iX{mhWL6-8ilylJQuOr59()SW~rS?#%FGQo=NHUC8Q{DzqFr1)5z zj{P~A$241e*91w?N}O~CQeaTbNabmiy6qc6#0I7<3I0|rWYRj(aQN&OWDnW7)h&*K zKga>%gM@9h{DxYt(1I35%AXDFb6bVG@yVA20#G|EZOsZ`@a>d3jvyi2!=tybW1@x7 zi8X2REt-X#3c{x8ZS|B;&GJIuiz^7;>pLKKIjY-+%RRpf6B6zA)6WEXLafFz#)^b* zib#6*$UPw(FibSXX6E+axIRQI&h2SfL+@k4uL#*s_(7;9zFY%0~zncgukI+WuBd{%a~E`11WVa+Q5zpv9sx@lw= zBuAcrc24IrtlsZ%h46v_c1MAD%~FFZIhaF9bb_0pn%F0?RMFnh7RmH#W@_^+5&_{n z9ScsYs4P`P^_wuW0-7jGo5YWzxH8_VS(cJ&_wJzzBx!r2mS|jIxe1;4?wj$nY$U84 zB9m#@In-wIa8cNKN`hBk{0I4ZCIqjv^SYK<(PrZ0Oi}XbZ!F~SfpE45blRWQw;n*ev64uyd@ItzT z$yBM84Ruq~0KPGdY-s40%NXPHTx_Er3WMGNyXr^`#%%} z_H_Gz9?M4=VLg|0xa{1H>KA|gDpEuHL}8v>-CG^8--F4}VqppRgTi%I!HmYsmJ~eK zZhZl{*C1%ZBv-=gu&y1kZY>XKB4#%GVhuMf<$ZB8A;d`O+73x&Qjo1fx-6nKqW&O(&0SO{1W_Yl(d zLl#>5Rzk^4mj1z6W-Q-V?wa$O_Z!k50a~lG6;d|tYcA^juoke8C~y%7eqt4QkKwy} z?33|A=EN@-1*yY39DNQvdTuwL)jc&VwW+J{(~{y&u*K2uH`rq}-4Q$Jly)Z>MI*hW z;i(rf59(vg@_FDbIO*f2df5&$#;X^m5Uk(2!Z_M0qxDmV{ofm$GzZYW*EW~8Kom<& z$B_C?;k2lW(V;QMgiRV0clWqE2G2FaWJ+Z5jj~u6PN)UA*=X{P(d^0e)(aO8vKPku zqVM<&>ZQP3Akf+G2s;!+q;0!L+)SB%{5M+il2e!La#n{*_KC#z&8-?zg<% zn|wf8hN!#L1F?vQ=h-a|fwyjT%g1b$kxi`{yteFLn$5jsBb5)*gMmKW;)=5%SQ;8g z!3x~0e=tb5aI}{K0R$;3iGC|xXeNmTD;^(^HRNrm-|l#RMuCGNe42fcQqf5_|X zDN_*1PcD4=PJZR)Cs~$79tFk4%3HcNS`%yG>PTQ-tb&6HK(5VSAhjJsJqB@p3+%_^ z?b}WvcIR7UkXik_!}-fw!P*V455KJ9|KIkz|Fj#`|EJxAt&FYzk7GtDtjT=c-O2oZ z4zj5Re$|y)G9H1m7Xd8L2TDSwgTDDH|)M;afl))G!#d z_71qxa5&1yTBlBDI849%`cgQfbkDaIQI_QK2ZiAbo`k2`h41lnV3ZFV3T1xJftD=> z)LJ%uP%;JVC~?qONoKqD8%SEaaZ@$gCEOt*iEu6b0$anmc-g1DQ3-Z4$2YPHpg62? z=4>8~gTK=xKjqmX(f06&01GO+bII#ReqCubP#K?_4kBc7FXl4aE`^D|v?FgZC07)5 zxEaK&BYs{G%s~#&klytiY1AlLAri*=jiyZRru$Ln;pR~v!qGE~ktFqvNg(}UU>d{; zWz(k`T!Ydnq%K4Qbp@?xU4?J+DX-x8)c#TYfu=QY_J2|KjzN+}S=VTHb=kIUyRvNC zwrzLWwr$(hW!pBpY**cy_q%c9otZBt=0@b7%zv3rp1t>3Ywfk*9uq!xkpA)f=sH%~ zOuwHU#6SJ-|9^qUM&{pxin)RFKd5m!DSbODeM4iR|Ml7bTWnRd6|t1jeOLpj17q=L zP%W`3Ebe9{LKl)_BqSjkd#?$8Qa=1*%b2e7ss^?S`us11atMj099xN^@qcAtLhHci?7`g~yfA%0-2^(5HWipSl$I~{T>Rb|rs=~>v?<{^@8vce18wq5f7TH_78A+AE0Fs1ai==C^XBC1a4|hL5aU{h zPef%XFCdzxo}N#~R8g5Wq`*nSpPoF!qmOB<$#8Bg?5f5TA|9~HOY9a7>mHlJHf$yA ze^qW`_Lv%YWJZaiN%|I;W{N0)F{#%e!!TSaOj43i#AH}bTo{X8RUuN-Rh&c;X(Ck- zD<=`&K7?4VP95)&U%Fx$5Z0;EOha?Lf~-SWkmw|AT!y(`8aO_?zng4uFlk`G@3mXvH`RL85$2|B{NCQ!# zRC00xysCGXoTliIPOH_IUdMlGiWJpS6c7A$kUS=#6&b(C&zY!RjukdZ9|Uw#%@T%; zMOl&BAX8?ffqYKdV3Qgh$7`fRnWW{YMulfDgH?W+NI`5r!qp@LHiKCrS4>024C-RICCFYoF>{-FPvlrZOV`ceZM0+Y4#URXdj zkhP3k`<`eX_siM#_(}1Dy z)=o@STZhx>$*1vO9B}3jJTP18Q9QK*7Nw++46)%C!!qFBM1^KkGjVZMheUtUW?@$k zc8|n!VpLjmK&?uca|56EnxHLoE`;gn6NyJmp!s3%_{l+()Sb-M_&rWx7f+|ezGY*2 z2;4gYUgQIc8?^+Y!xU!T7YcBU zxaG7Oq5N2=SHhfAJ+dH{x=vsdj$MxeOB~?OCrEV}7pOy&x) z&03fH!VH%NhOMazCvYJM6=giuEWOK){13IC6IsMj0$oMw#I20RC;%JL`3KdNfT zN6Gf-_q~`4>VM;4|5{c5BS7;{RaNkt5_i(Kary^b^Y5j#NJ&%ndyf4qMpLn{rh?qM z_7A5itwigQM4-zBRTvD7KZ!`Q0aLSfJ<}=wM2y1J^`04sHN#Io$$%Tm*>AX+Xrz{; zsSAVa;BuUL@;+uXeH^};*8Q0|;0Bao*NKD~%zOfo*)s|(v+D#T4{eD)OFtHCA7prY zn`x&t-+U<}%~)$5OoP;X=&^Bo;$A=H(68XJ>8O1crKmtula^s##cz0uWkWsxIvYDTOT{z#nAN>whI%QX(*9Fx{=Wr;02Bt$Hug4?E zGos`n{?sE{{hoVFN>}=%dFOC6mS{RRDey3TtHFb?-oFHTGg$X#e1pkyFWC^yeU_R^ ztj2t?RE=SFZL%CXtU?w>K4~ve*M#3q3EDYKqLrX^5PotLf4v`8Im0-#-F>M>#d?@( zMK;iJ@Ud!+^KR3Eh5jl1Qg?@9ocxWJq?m9ME?}vYKu&e17+1aT8W_U0wNoL<`qCwk zO6ZieMZ)EZ-g3jtSsvh_NOV^p zhOvs)CB^bLp}D45Q}M~jBpdd(N&O6TZrNtLNk%=O4*x{X!$DEss$XWuu`RaEr{(rS z4fJS6l=rvvyB2d`Vows+L%qfU5h;{7vUqZlTi-_wTnbCcFgoh2ZNa zSqjxZ2N=W@MC-C#xDSZf+s#3m;_ID~YJYKIPG$(MM^+^loB-ce}yR2>YL!^zQnCUlR0&A|5CuAfHbc>vRg3vVOe7xOnm3>$rf_ zoj~p}cqGr>NDsZuEW`qw9ihSKaUqxS0?$NiAX`$F7+ytAS3^FcB%B1smG;kq&R%qt z{YN=-2}a0gC|}e9uwN>Yg5a4D>EG6%xYilZdml%hG~?lR?P8fKOi?_y2fSt&k3U&c zi;^dZtm*NZj7-+49_+^z9G&>TUAjFEylRU`_Znt$YxU$(+m#vT3m|>Z;r?-U4}<03 zztdHJOo08Tv&;9NCfa{GyHd8M-@}l(;lH2TEai1aBxUrkEauT>$(4m>KE7%lF-+Pz zRKGa~3Ta51Jc>f(aI_68xYM;s8ZG^_2!)GF9o9f~XxRhwS-< zfzdk5Yy>t)m9+$PdW}&Sq=b22kZw!zf1jRkJd8aR<==|lUx}#oqJXGkv|DblI9n!n zu*}!hNE>0S5ce-J3|G6iUrhc@o+bk71&#Q_6iCTq99oGf=rqtMeFZH@oHY43%@{bG z={^NNoxz%OOGR=ybwUzB$n8FikCN4BwgDd81(Kj9avQBVb)vkfwu8}MrXyW#Wu<7By6a|P*jcfDCqv?>{HeXe>gqggA97~GrPVP(fBns% z(->cdfk1!_B>XM$a8jrgvn+I`xZ9{s+rrV%r=&Vsfz)^Xriw4#Rd+4M`HQ3u z3t6$F0o~AAy(0qc*h*ox9i`9qI8ck`iQI|S|HdxRVS^+9vQ4#7ys4;jjOK+$-ip#6 z;(xgCwfzEZ$_j={Gt0-;S)tXEO_HlK$H4x0do0=`W0U`*(9rl`luhi1b;kd9mqHT4bHK)B3_+1qQ zaQb^pP)iDOP1P=G`74!7^8QY+QoNp4jeCl@nD8-`Q(}n1^t=@*VPWHgS-_mbw^MS? z?~D8N%O2WuK7Sr8E_393`IwdN`wb!&`VULy7Pz-lpWh<$p#q)TP4`H(ZOVc19~CFh z@&>vI+cEH)qO~X`H=NuTWFWmapj(M}h|={;FT~GW#BaTzZ>9q{MPEvT&neCmzTn!p7IZh0%*hm>(2_NH@D~!lt{=(0l4_B5Pl_vzFx*7>vrXi(DQvY_L#d!<%_ z&^7Urv%xy|yEGo*a!&a4_6@U_LfUmU#`cW3DI$@iiyr$_g*I#~JP72ZnBkblCYVva z8BPKU$5a}XBhw^JZ`=7)7=NDNxw7$DQwobMod%8XT6m-_o^bK=x$`5zK%ps7_`Xy%`&Y-mKEvI|WoOW1olTPF&0ZXy}vra+usA)B5U!!LF<= zcs$nYbNfG^k*gFYoS$}4)aAavMMM=Khwa7*3_u2yT>yi$%X8ms@W-q#_}BTUi&_=R zo3Z9O{7dyWFZ?GJ%K3f9|Ggao12VQhgU@FkmE#t`xDoEPg6ggjJ@x+UAH}tRlUVxd zdoV)%kAu;F)GGZ`ah0<*cXYJ1`S;pdr0VXbw21PxDQ*&+2F)Zsa%+$auP{O{)Td&{ zhwmqj4@CfvDlf02gWDgQ=H5>&ZYNq)+GKHtDAd?&p-6>VB#_@o+qks3RHUM5+4N}n z@f!1Z#%q0H`r2VjDma1$PoclX^|ayWW7>9{?YTX!3wU7u&G8&zJv!Ch;hOXI#*Oi*5$CbYi=^^*6rT5tMOsDgZ-aexK4Wn?=#Jf zdMaCF^V@CnVP5y+Wq7MMwMZn-b=Uwx0=Ttco`4tGazMJ{!^})95^pcTi`zu=dH;Q3 zRdeOu-GiSa3dKV!Qpk-W#A{$6J0YHEl>&9u2Rx`%lb`;erlqui2KGdMf|~>+w&R}Z za~loKcZPfw4ytS6#R?;|LvbNQ*<0g+w}{AfWt9pBDtZd(x!Y9qJ`joDYj8UZ%^97x zwrg)u)Y;kcVwJ7d{2DDjCdjv`SAJL_rnHSxKZSM=6Sda%($-3SagxGMzxO~~xU$_S z4*&vVJ{IOEqVy75wf9aN*4JxJ;BOj>0U`@EJ^2U(xTR7C<@M@iGZA8e`}ENC4W61} zrbMwJL7XyT1Pcx6mmcsX13y3)n~Bha86$CCau$Ko2Sky)TN{FQ6yreX+Is53e!0=S zdIzp#U>~Td)p1CE-hqOI$1f(<+orygL=H0u;fE!qLcy3CRj$4R4kbvn#ZMl{0mQ*#$j zN>rx3QPcv_7&Icc%j%gP% z+?j=eh8>t&sABWYMllG{vysACM0m*K%Ik^*i{b!LCghVX>77=Q_3f?r1(iXy2b4`wd<1zuJ? zlzw+p&D$$C~0Z>)UihoN@pE|X*Kxpa4F_J-%I&?I7rbZ1 zL~^bs?anyZwMtk8;@qXfvO_yQ`o5`Oi=K%}To3tKK~4O;lE5$H!AN z`yhlMk5y}u9GeaWkNE{)$2Aob6=Gwftq)w_ZP9ogFl3drk zwi(pe;CfV83RXCOyqUe@16FMI-a-XlsC|4ubrt4buoL2U)kIg7m{?2@+5y{Cs1F}&4#!q{bBEKkU`&m*WH&cTx8IU|{p*`zB+0t(&LKY{s?Euy%zfFeb zO+=EXsw1hF3yqAL<>Q=92rZ8yg&d#DO(NT*TS zvjRwS2qo%J2}89vKUi?F_50JBb|=>C()ABwk4}^Ms~M?O9m=a)X05ByR9=CR>n2+waL(js*{$-4dxdDcrm zTBZ*H+(ir~Fs50y#O+_A?z@F=yM;wVKGfvfa4AlmApsbNo?tgk*|%Ns456dFgi;iJ z3;bSPlJO47N(E1Ws>i7rJK`Qs$QQVR41XTFgG&(f>R{2rGO~lEW5ybgxko*=Vs8L^ zKJ5GM#Ah$8$(@Ng8a_W%o(Se$D~{z}bYe)m4yGq_OyTEc+>{Ma=b<8>g(NeCAPuAq6@VXlDB6}Q7Z#L8chLMmQ;pMaRzE}+c z2ByXDtEppL2-D=M8QF4V$2;Vc)1qb?_32@iM{O9BnSJ5~N9A|mB5L{STu^RI zPG%22^~oMRkzKZhgLAmu5y((tj&k@QjQukY7ha4o@0-VUE2ZQB!F#89;Y&qQVvdqY z21QB*Di~pm{kqkOW6Op5%3nq;fBG(JoZdgTXR0_89oe6Rj^bfu1VzQK`s{;&32NL z+-yF5Axc{yPnjekQ^aKY+%?8LNYzC}UA+c(q*=C57?rq}M3|(FTLtc{uz+-a`-Yse zr`)-qlcyF@@t7{BfmWr2B$_-55$JyKe9~C;6_FyQLK#iVQ<<)HksDuUDGBiJtB6l#$dMv|}Cc+2Hm1%7MW5gHcTs&WqRDU{MG z9XNP1W2fE+qb!!(GJ?7k;4PH3NG z9M(FdKV5_U$dIrxyAyJEOX@Tft!2ij(u7B-styXeTz!uU=rQoHkH)%_;`E+y`` zN60IHE!N~9%mVkMLu?Y2LFc*}pCyH%@^G^dqoH<`F^mm4tbR}-yh40+)_n9hN;p4| zX5Y=00FvoRc1uUa5ODXzQ%yA8Pu(4LCXPa%LU*GxFO?G=(f>?ZW^nZIvE?-WEY~Y?)v#Zpi6Ev z%tXcaoj?fnKY=c?|260$ZSLme>|iYIZ1v6m>pPh1JN?i4(7)dks#LY@uvAe#s~hLm zZii$t$=S=K)8`b_Sy7@j$(pf|*uodEgn9Jzt*L_z=zu*8#7};*eaTq(99r1)zGW(HCxHXqsp5K0QFH_T9ZzW%! ze+7Twv=;8&zyoK4@A`O^!Rih%pm>1)l&TP0<`*Un1c%n)m}100VInX~HO5dJ41>qC zQxH}WrVXU2ecn`IP>rbRk&lBTfL0YI2*h#APiCID+ZR`H3xA-yK0D>~LNR@QpkRGs zj>$g4(KU3QuB~dI?5^I!0_r7$aWq*%xt1mYZj4NG#c^!kNpB{pj7zRlUa0zx{E0h{%*BFt;no8x# zDoPtl%vx&LZ#TU4v{$ec_?;0+Z2 z694(fa1z{UgB9rKBINZg%3m7xkjg|dMCk6Q6^90U54D;XEc2=70=zyl&3kxXxtZD<=&BN zAY|6isZy>+IEP<9-pJv*lwqaOSFJ={U5~dKgV9l65LE4D`q^%1{5)+Yi-S$=b#`{6 z9E*230MkEoX0ELPbhTf_oKcGAhBDudIvi8->zK@Ujmg>EN*V^z+q2i&A}wv4dzjrJ zP(Yr``n#nUuq4O`crOgRdZK`=x66*H}Y* zKAH8!aNk3Z4zh3ddd`X$Tx8SZ4ha6nb{0SMRIR$8s&P(%c@k@|pRTlp>MaEkvTm%} z`~y80VhOIre~r0dyZ}y}*X)f!;MaYEvfxbdu=&$B1ye;-$Dr7d0bA>-)I{v8ZrHvkEHY{J(N``;OaA8F|QK)8eMQgTo@`Jfy@<8Iih zcF=!{Qa^vrKSRwugJZm71z+oHEa-^@U$cWe{2-;seUlgLwVw%@o+Xe;KjR&Esq2<{@E&-R!!AY?6#MxL0z2Q9TqcZs(ybX(tj5$&G<(Zi zxGR&i+aMhvfO-PRB{MzdN+kXHdQmR>+L2h>=jG!D5f@6Va;it!FA-@-2aazu8 z3h}`d{E|bW@Gen+PV5Pf_!z5g)jMz}31z9sd7gSy)G#&CMienl|`DNMTmwF6Dp)<^&k{tk(n(1}|L1Q%F1XT@@kS zUcj)kX65ZgaJ`%}^_>R%Cr%=wnRq;3etFHZT6-0fgoFDaemwQ9}uI+k7xlEuHP^V55e7lR0;l`XS>>I&H<} z{o{S&Zfi4xy7TDxeXYe=brMwR>uA3b?eN5`ABS{JZ9KJz7)8@Xu(%DEN3({`wY#dr zw;wS}Nu`5_kd3I5VvF)}{hQ?yrga1P%+rdQ-=?ep1xH4ByJjg$fI{XSa#K0EV*4pN zZ4k1=(K8!=QABd3!DY2ikP3~eWVz+U-~MKnG8s&gvJ`b9zWxmromb>Uh_rdC=IXL) z9+FyzLW_10bv!ogfbb*+>2c+*dzT}+(gut6!t}v=px{2O(QcYq3hR5UCg2AgVMi@h zX}{=PiO1kFd9}W>52aES%H)fqD#>>5mGX4Or_y0c6y2^NyUPxMkwsCtpx^jF7KDz* zZ&2E%H{SWm)OOMac>4v1AV<29O|#zewR9e{+P%}aj=GcvL_tJzomXH5xQZ8wE~UTg z9jg&r3jLp*Xm#=> zOYN6@J^pqYf$2j1ZMn9Vm|suyFdkQSTM?0t9toJF`AaE=>U|micrnyM%dP-x0-oDW z#v?oyvxv3dO?~-onUcxNE{}V*NV*8OuCE{8FfRPrUgA6W6PVN@A_WsXE%qd|BKoFe zdSWoB@-VlIC}v%_bC`;UC$I)(ZwaY_WFy}zgCzei)4z^3G<;Ttw%Z!7JVAAcXSKLM zSSJg7Ulk`UrtfzRX2+kTZCRRHmk@2PGdP%x8j4P9;>o}l5|p?(AZrPa9CGMSa^>On&sF3bQd5Eg4_zD)5Dr+0XL3xirpTyJ7A^h}_z{?&J?rq)0#lp5C>zv+(d25ST2sR{=sU=$3FmJL}UDQ=a6iedSX4C&dZVCYwQQE?qLD)LN zfZZab{zzAM3u@oeK8$*Pr%i@F3!V?NU=N8h2IAC5s`Ca`;t4Fl5u63}Ad=BJ$kKPz z4WCijz={Mb>gGQLU&#nj@i7Vm-b z-U^X)qFSAqh0b+v7cTn%?y^1`a4i8|#;`qHhcKr=>Wt~Pf#FZ1fEa*1Z+#tZng+7_ zEdskMZ8-KL5zbAqJxY=JqIG34;#k@aZm1^U5$a}~P3xYB@)2yTcB}!j=&CWuUvi;z-Ol6@BJJvCN0%oW;(`Lr^X$^AI=_a-aLjJZ zm{`!v-pbcs_Rrg#rtcm7eLCOMNX|XSsjUrag1lU=hT|>A%Wv5w$JJY=;}zZ4-6h=* zryUyIr}9S>-__fWW&ahR&6s_DH+m8-GXKz?>wTkN#c^=?zYXAjrowosK<;s<-Bwd$ zX-?HV+kC>-XYxp8>*^{X8r`!0IZIYs zzf7HMU1b(y{t`|*qqIaLI39DVvPvIOU@n6Yur;{~gXuBU4y;m?&BG2z#N^DBF^M)# z7=|qZ`5SGQT#{=k{L^5_gxb?%74Wbl=~5)fV!5>P(u--s_;%+zunm z-y~-xE|qz#*;q=+iWWaEogz)R%gj;Qn`Pec-sn@qM`Ch1riF=RXAn1rE#xN zT`aP6+^4HlGu>Ll6Gg2{ITP{3ZAZ^f&w{ihrI5AS=IM*C=J`XhU0d4Mn|Y}Gne4$} zwbry^G8mrXe*fYg{!Jc7jagzTRF$qkX!vR$3#OmC8Dng-S){ip@x5J=xy&P5dGe zwNHi~|5IPYU1Iu}i<8S0kez@aYMhWbiPjdD9JP2nnTpPMK^^Ak;`5j*K2A?kt@!b* z0IoYE>C=hbNA(;Y=*==f#B?;QD)@}4Kwu?G{as;K={j^p!ymihwsyn0y)sF2G;$NJ zx50NaR*r{T1l(Y{2#9NG0&(vlt$eS&BztT_?0%wsJj;NmTzi1q>ZyXK+!XgDd@Vx| z&3OCXY{0X!`E%#ffv&vll>BzuLwbtSPC|6<#5BDh^_kxT&gRPgRdx{DlYQvU3+x|k z6@Mgkpx!3LvIq#08BH0#w$Ek-1TjXC(VJc4N@}MoBs@#bQZY+?Z`n8KdDd=#J~Cdu;)Yfm+8?f8!+3*DIsxW{@^1qj^w%Cr8;kk zN*b9D%;az=A6**>Gki*>*gag48gMX6N~Y-E#a94XxubvTWHeh)N94USK^Fo3hu%vq zgxp|fv`+`8=By4Sru}1h<+ym?yJ6$xZ~JE3rQC7|yDOPX-R7hYqRzs%h|R4K!~phz zSD8MhA|{Qq8I(6wW)EVkO8x`X$sp$LbUrUothEbvgCFw#7BhO=-_#3sOUw$kdoXp{ zkYtK-LOL99ZV-$k<-R=F;SuynTtMs*e1aQ>xQ(f7aV6lBR<2XV58FP%?_`)G081Io zITFJPCkhl!bZXZr@xi0BzOQ+_6BA6QBXUOrJXDiM;DOZ3QRzm9+Z8RB*_E{1Hls4_ z%uIW-@`HDMT*w`Y>RLN_-*YAOs=`X(KNltSsR; zkdk{R>I*urg0@W-=2I;$up9{+(T}GvbH^TNjIb(7)F#)Qe#u`MjkXuB8_4&Z6j$SS z#nC;c{&w}~sfOy4#(jmwOKo^fj78I92ebNI=}X-8AlnYv_~M9p*|HH*wni>Qh4~fy zk+#BT=a7}FA_R0Ru<)?e8Bx82-}Md(GYcoO*6@O!m0y8+(YtEoGt2lbR^wia4F%AF zEY-_^1I98}WR;K@R|FQZ>mn%{&LyqGpXgw*{UElwM^ud=B4+W_FA?M9#jBf95@5|* zk@AE&88(q(v#e7M=d+|kpXv0jY2q(G&yQc}hq6kyrmDuBBE~5d^-wu-luxac$1wdc zeK7mzB34I~0bUL~06v7OD?J?5{;?WUa}C1f8I|ogEWNMY(_X5UFU$xQnL|)Ri_|h0 z@y$3jn^%hun;NXGQ_BZu&?)yp9HOe9>Q*m8!8MOATCHAh-YDCca&Gg1_GnwO$3J{c zukf_qc`06X&HDe`fOmB$FBqm==V}7SBEyV?;=_j1*XJXM4pL&HO|pOUEQA`$@$Jfp z(_Cd`{SoZB3P^p_!AchK8^Ha5f=($ZGFbbG;Vs(8YucVdB`|KoM9%~iqbs~pGNZAp7=`9%jim7Y>s-P1G1}tyHygxUv8+P zStB`i*^M%A7t>j7yqS;Zj~ji(H^s>uR$Kc~taEc%1)3_JHvh0GIgvD>?V7^s@{7s3 z3;q5bTc*X@6uLjHT@jjHkY z%7@keMU9-Ls%eL1it_1mR^MEoY@{ik=(#a-vNupJo;lzmb|&UxK%iS|1vX5g-?cST zPEr-C(yRzcv79`|1tXrI;}!sxJ1-LjgK^RW?X4HA@0Qz7-;ed{XRx2BN$St3FUy8_ z<2L7vw9GG$si&;F97mPUMPJ`rrXSjFlkUYuj_aHKSK6)wq3#go-;#nrI#exig8j}% z+fZNW#-u~S;h-sDoxbCAIlfttUnFQ7Y6s&aKFt$@%Cxx7yLWDp5p?WdPc`)n-LLt9 zmbB-+`%{+69lConx<`9dT3(AmHM?hCkHBcMoOqPFL4menZsB>{tn@3qX{oIMW=0nJ zZ0yzzUsjIv)XZFQW=@VRyetzvhTx;pY${BNsZ<3cAyu`F zI;Z!OU#`AympSOzgYG0XH}cAi%$MYU(}b&LcqI)-XI_C5E1?S2Sym0a;T;-->He^oXEh^mBRd=zBnz zlMEJxv1wCZAmg}sGwHpjikY>|TGWeETpnE>ngRkzP3fJ6&|-snxEOH-`rR<0<7vLU z*mN>CX|WNt4@ZKZ{~k4SQskmR+6^f9@ZFpb8T3ZWBW zD~BEb=;Z0@NGtl3IY(74x<_7()uhTu5qdjMBWwR?3=jo9mSTDwHE$OUdUzVvA$IIh zqZWg8tmLC!WKNy&t@r9gZ1F8|4IM*kRa=@!b!2w<=6tfbyt8|U#@KC&44s7`h__0b zwCMngCO;GUql$pW72>$!n0wi%omO&Yir(L_*j>5zsUER}y8hT(WA3LD@}4 zQMk7?-lHtnBEbBU{*x18^Ch&tbmW9Tk>H)b%z=O0sNKUOI!mc-h^>u%dT^dGx}f^ zA?n0^CzW&$xE3Rrp1h2B2kuTRIZ?#HNaz`ADOy0wDafVaeqDo1Ey`FEa0VuXg|epm zC}m(RKsot&WD>b|`&#|Zb9LN-tL66|9iOL-&zli7@DOJf%Uo`g-E#?T{itp(cppzi~FR=8LtZQUbDZ~H!JWL0jGM|Pv*ghWSYB^$Ssuh*&ajz|Gr)@8k zD%YKCAE@jd%+3lk_hH-P4(r2Bl|P#sux}SsW>8?NJ5X;~R4Y1pzCe@2IfNrN*U=jS zLhnL`c-cb)073I>z(ptDUD*!!o@)EDjT#uE5CgR;2`bzLXH8tNgAas6W@qEHWuFJsW9 z&p?xKeM7|acZpE}*QfURed3FQ0kR5ij}kzMV3G3nz_suhH);OL{)ca^M0p%O*(9NL zi&;}fBW!HYEk%E#@NP-rAVnl%(7G9Jd0Dd3wm28WB02pV|PCJwlox~HX^ZQGd~*R69M)%+u)e{ z(7M$k`!@$Z0~tWdKZZpaW7`=xMAFkFHJ zvkZu^uKD}vGhZFRXf7h;_htNE`;wbeb|%(vIx_4gNGzIeE?ez<@Por47CY}dFZeH~ z!zklt>I*-F3O0egZwwK##`UvZ>t1}0g%yEvgmWM^mqfI4-#BjRD>5+6F|7L31zXl# z{8`E*+>|K|sp!P8joor5Gne+EV8Fv%c+sl4#hj{zZq=n+QuXFsR**$reZBVElO?n0 z-~1`-g~mk-(lZMS&7Mvr)w^)DqW{C@6M#9weSJgwk^eMn{42CC@ZTdIHqPG(f8QLw z(Z9p{MXH`o$cHFj(k=~xE@Th{2f~PQLMs40={&t3zn~ymV^tG=1S{#+bBTkxn)aVl zlRl$1s+<+9g&=t>(f}^JvNqbmwYZiHV$Xc|5@AOVzP>#6ftm| zx}0Epdh6cq`t$Z`QvG>+&+$X~xhwQ-1AgXs$oj;!;Db4;*e!fKBT)yd>_? zu&5B=Z!lQQO+PN~1-7Og}8|kJKt3how zahv5H>0gsVIvKpeCR|7$C-Fk)~7v%OMjEY}L6@ z7uX`70@J!_jXg^S+cOmDS!1H|8u*>) zG7VQX1~Urt>TQCncyD__n76-+sr+{sRTeFzSoYcou_?@5^;OowFjb@Hiv?K@C73EO z$^@y6u#9c^=rIHR^?8>H>BBM|D&^@G3*aLUq-Rv?)IDvin1sfw59P(oLqu8OTcobR z;*146n8Yn32iP9XK{5rRBopajWg*~ds$AmYN_UIqH{gz{0!;-21HH3Yr--qaI+Ze z%DC8MRSm)sCFTUhFE;g5fMg-BBNJ75FK(jyEdOrg0gv{dm+@4`+AAJVGx`DT6k*jk zI#Y=-9lt``u0A`URk6p#WDH5mvS^y>h+Ulwaen{DL!#5?GxvBe5xV=@zcCwc93oj*FMFB?0wHuN(O2-2SmoRygvuit*l z2=|4Pg`!?HCX1^tk9_)$T156eVFvWK&i?y~FbJJ(2-4mm*Z4nh2Mw8hqiAe*Jp{}F&F<0s+Z;ZREg zz1#TP7|DQQ*)zF@!Gc-TkP;6eOoSD5*5b?RxHgc9U6O^DW5wC4Z>2;ONTZJ<6EDDa zF!Y8_taapBk}Tv()*tmIIFQX=ybq@|t`?Goa4X&p0|&9Xwnk;&8iKdi96^=j9hn!Y z*1{oOg96K6q}4aGKNReiXInAu*=CI{LDfc<#3ndtiM$0)pf4NKHT zw(ISMzqgF&)Bm(B@r=WRT_F>Bja2l|{K)O62I*b?f92 zNk_yM$|xs1e5wd91#o+%*Jb&Q8n-7QzZ-}O37)0a^T%>TWneBXG+9|{v{Wr_&uHl` zON6oCAh`Ylgey;hH~cms-we0G(S6uIXmsl*>+~s9F~-F%a~wx9v)Wo{p4^_>vqh`D z`3lI!uVUX^4n9Z6;zXQ8hbQ*G}9zHCsODxi1* znSjf{ugbW>DIrj<+cSC1rp&$iLs>W!Sskf%@%o@xYY;02oS4458P)#WUo!GwsBPO3#46`Bj47D)0cn8pTv} zIe_Q?=9l6MgSPY%v2vnzKH{h<5j?4waD?s63WmC-mZjtMi_E|ODJD1~)sKp6qRsdC zqgb^AQd^x4hwqZ!Va@s_lK&u^&MB*J!aJ2CveO0km}@Fu4?gHfXqLwxDhn{?s0>o!&dfEf zd}6hFmVe=keq&1pd5TH)*b(c;b1TDZ)BAzE14ga}7oURLrvi}D_WzDdZri631s?t_}>?u619NL1?J;o!YNJN;OV(*drbbV(PkY6UW zTKBk;=}j#|+`p|?WJpV9*E&W^%nK+f zWAS?{4us5I=g322rO&`mO{QPkY@}qASRbOfB&>W6QTng1g+#){g9k~J6R!eVSId*T z%!Q6M25*3~yyj(X%mvr9xtzwv-tu@G8V>_-~WyOI<{@w6WhkbzWJTIZ`G-DPwm?E)?4*-cUAuZ&sS@GRw`d8_)$dZI5WGY zWCXl{r-{Y$w~k6L-2G2qWwNywwZ13plMnL2ZKH|a?hW#OYeFSZgK-0Tv9$f^Hv!h^12$ZTWK#3EX3;jq~_NhP(;U zlLYZpp`O)=QF3J|20ZgHCIz7`^Iv)TaOOeX;!{)+W$7H8|kabsV zy@JHJWU4E~;yMG~>jP7@%soM5*m&A`6oNaHnq3Lw9todE*_}YQnzwvKxcqBf3_w0Mld}+Drf$VD!x#&%Fl)zhr%^=~ z9O*(`iQQyPTG)$y5|h$_)w2kB^q_#6bF|j2>Ur99qe5|QBdt*bonUR)OWUA}Ob4Rd? z(9C;kvJz)=lE;EZHwe{=wU**%J3z;p^FNxB;&;&sCIb0gxOq}#=YIEls*Rm4y+jr4 z$g}DBFt759d5R{F8DMtKa3d{+)Fo$gB>H+p8_e-HZ8|&A*meG7F`B{nVo=NzZqGo5 ze1|g(9g#Rw;Axzd%($!O<6%zJa{n=pvcO7Vj+u0}Wpy!E zm!$Ny5o_GnU90KuEMlP9*gghWFl9I9SfK@=-{UsOO$G7oOyeU z#MZD3RnT56tzO4Ug9UV}mL+ii@mX(A{fiqwbeaud|JN+P_MjrXVhwryn7Qk9k>z0;=uQdRGg zyQ}s(QDqO8pqzuF>MRSUtb^E_t)8q)P*w-Ll?Hk$2zD0ink|>^nsB^n!xh&k^;)2s z)rbsIyQ>UZxhI9)-TXbyHi=);Ky3@;D>j7Lqng@t0Y|2y)lUg$+rKVC$&;gM{!pzj z<=`nb#C7Jd&>K2AaM+!&q@8g;CMbA7m4+?#UlYJs~I zt)N05uj%8lO=5d6IbAB#lFxx0tLVz*ax>W~slp8rl~U z;MVe+&)$NxM_f+eyx{nzMyN#IJXMFt3;p-F>H&?d_deHSwEY^uSMd!By#{WZ-7i)K z?jxF3?CbCQG2UR12FE|cbUB5o$XEf8GClP!FyLl8uqwT7Xp-WYgON*Tm zGzSS@uuGFAq?cruWtcbvGgDVlj^b6gnNn5o3FT&3RX^?eT$J#ZFj|}1wXGQ0HL4sJ zCDN8ZS77l8g7z1sJ;QPX{b7&fov9$SkHb4A!P_E;MwdQS2*5Y0dJif>>Orhslk}C> zg*gb@Jylyt+(_Ho^!t1FQdz!#E~?QpvBNd`@m*nr(*;wANl=UsI>@9Wsewc+2su}0 zk*ny)mbGOnyJ(aKo<|B3m`x)mR;Kq21dxVA=TfMr@92H;CFn53(o(t^67^uRghaGz z_O}h5uw)$+FmG=D8le2}cGN&sU{{R+k}0Cd4>6q4ACB5>)0={aue+4KIaa!h?Eus{ z>hqxMp=v5T50y&bDE#v0^oh(74dn7|P~4RBnkH2^-LD}p9~Tja9Kr^k-PTZvJ~OXrGvjBFe*%gZi4{s<@T`dv+k7`s?jE{Hq3>qV55 z$6x3b5*Y!Kq$~)fEV+0!BkH$nWy=*!Fbs_RG;&^oqUm8$4^2>yJWB1Jo|gblETCi3 z(#;mq5eLmL52q~r;w|{v32j|&C(CK?Oer9(1>D^}i)#?axd**+J*c>8#gTvo> z>m7qLtsEBM$0`pl>4kJY_5gKMuOS>2OE-wiz_QQ%zf4 z6BL$`m>@Sfs>)VCd~M@QQ3DPwV;vr1v5kKYaC#5H)*bBEWijEihCe^im_f6KeRH)} z6^`Q77qzOONuiJYHDD1DQ}Yv)8!%NULn+34S0{l~bZ?CDDp)O$mKm3F3mr~Joy_ka zi@7TsPI8+cKfrXDCFb*;{dS5gB$z2-?nF;I%ohlPf2a~Mrp>9+XJ1|tTir|ZRAwzg z10`{H3klU`yhDO`5@tn|yf3^S#iNl3y0AEYwYzFmlG;O*{Clv`_5skU?j>MBr_R>= zKr)6lY2qB*j!%sMRO3~5<{aLa#ljE_QbU58|zPvd$d^}ug>ARW%|^4ru(NW8z30pBKhjdaFPCdSN1Eh( zA=}L2qQ|(;)#mGl%jWdv+l|~em~F1_1NNJ4_7@L}-L}t@BAaQ@72i5)Je1({A<$5{ zcZZQ^!LBJb(SPG#JmeG8O+ zNxjmmR+GSg#En*S^?q>wCbuo2`kv@ttZ_yTvK%SL7+w5yuGH0E!sxsDxO}E^INh*Y z|AaHoSH1lcIva5rMGgluO+t1$N^XLzXfCWZZuZXD(KH>+$cRaa*r*s>SX+NGRiVMU z(R{k>xsGr*ZRQs_zAzLU+qYb;&(`1qP;umJ)xaP8cRBP(~`$ z1sbO>A_2yLwTY<|8%7FIeKMH(+`~PV1p~n?{FwT`{DuioR>{}k%h;Ax1s2|c;|7@& zO8L`sc5Kx+zL;;y%upiN!U6&wbRP-Ye7#d30|KnA(J?Pm?czK?n=#76g*PK*c=G2< z{+@I^a_AYU(vq^49>Q@J75as>K+dG5M)=T>D#X)X)y z{0yLIYl}UyN0GAQD0bZYEFe$3XsUI>`&i( zzVuht2W(DsW#NukgZIoTb!=@VP5?*PKLiLe+bor;m z<3&paDTDr;*<$JZEhtfdLr}Gqv|xLMfOe^FFZttLGFOPc_UD%t-YVaGEO>Qtt%~v~!gmbLD#RdZs6(%KclmRyTGzISjk!-kK zEt*I0_3G_G0^L4ggsmY7zn#y#G)SBd9@{bX48}j%b7$b^ZMTd^SX*A$RfMq5spr5I zvHKw6$jzpfG<<9cQm}{0swW#``C8Wnlv;)44GoR`>9Ku{Q;Y@8_@W_MhTlpQJ+#_Ag3H&iW>tqgaf~W2-Vh0 z6fb1IP zpLbS}f!x&QI-=L24WC$x!a~_r<`Imwoj-APjtfL&+k>mjN8DgHR1z}^2hc}`QhIz` zKy`~2UTFKC@C;fd-E`xQ-9{m!+m6L_?tru}3J^Ti%XVEE=j?t^v81S4snL{bll(G_+EYg&GAPqDR z6MG^f&X6Q-=eY?SD0Pk#Mo3Cn(g^KFv;>OjIZ4I%R^3Dzq)}CKqzAWVpS&bH`4rPX zq0Vm16yH+PzrnT4{J=54NCc@zTJ?;NOP*mhtOP5ad8S0)uZI-Jy!kPu)f-IPksxqL zt0Ul5aPikkepNTH_`PhRJ6e1&#qA&x)q29>zU5PNZ)-H`lR&LgAoL^b!o9wTa6o6> zVW}`c`FCUnLpIqk(-0Wp-Iy(E^czCP>0hBID`BcCaglVL6Ww{X`_xHxV!MvDxa-^r za?f3M)Mu^yra5l(=-8FBY9ppUyBqr{s(;1H%`hL=3Cwi-`1)w~KAI!lbbQ89g>;t! z2zo^c2$d^d0wy8mgj*AZ`XJzGK4vib;l{v2ple&k#GN7EaG^?Oly6MbrhN z;MXvMmu0XXdgvY&3kH6ujeCkk;GgAkX}B)_X`Z|hQt|;sGGdW6cg%`);ArN`ylV_y zye+bH=b^pgFxIKeCtA97#66N0s)XMfThX5OC?YhwWOY7;<+!aXB+s&cRD@}I4~<7* zJjBVfuTmIsf(-SR8S%o+`);WKjv0xDvSB76z4?7{)NbwJ3YgLdKzHk;ic{w64e2qV z(-#ja^!+b<(a2oVS-_WwO7GuxJpZ|rTgBGG^sD3f-`7xus#{-pIFt|D418u8t&+k( z**~se@joPKL~nZ%62s&=gy@ZeN(MOv!YlSj-=6Da;Uw-7H*RRiJhS%qtCj>uyIN|v~8o`iINv{Tj z2S=c4fj_%i2vmVk>Hsw%SZpbsN63Bp1{{nsWzOz+VqSeWXZn; zVL&8!YX5jyo|PpFJ0}%$Qab7|IJkJO^qd)rn0RGkW`qV*ijg@I!*fN^+3L$s#!cU{ zr~i)sdg(icAo7N(u4$<~6D7ns!eOoTt@(yvGprH!enl#+x>s-S!)XgFD% zW8jsRk*=7zW12=&zZW<(^#ZQ5s5L*iO^0P?pCIbxp%Ll#U1q65Ab3@M2`0d9V8ki7 zD6!}ks-1ay(juq^GhHcI(f}1&)=BK79*u>_iP0oAD6p=gB!W8+s}M;+IuXUHmMv~+ zEV*=Y&EJ)%-0Ekr#+ZF!>fLczBVV#K^wZ2SY7!ln7fh_8Wd@5+&_lo2`CM$-YEgdI zs6BHNM_K8y2QYDDWQTdFwNyQLk#i7xpZiKVr# zMyXNCHIAySk6gw`H*G0=uE58p{ZH}=qe^QJfC@e-J=`&xx~&3#(B_7A#PWm+wQPu1 zb+M@AJlLX87#Rk;Dce^#3zcW5WUcY4ZURwI)XV<9-(B@uvw(up^ui=!XPSNiS9qjq_IX~|0&74LPRSj}743}bmA zh0nTOxbS3nd_Fi%aRS5*n=w=yBPAD%0Y5mrBXqRi{d*k!1A*XVZP2mBnk1ck1UHhK zzyNiqdxU{GJIcTTeKP;M>#lDWb#QOxGyLSdutH_jcQ`(u{s>pTrXXbmK?XuP)C)j1 zKJiDmNJtk`5-(r+C~R>(^60v-Cnp=XWV*Ji^+*zAb;ngbRzZNw#e zPrqoAtf>W0P{+2XRBq)E6m;Wma^=G6GV?>>KG%xUVV4N>fys3&>_qZl_RwZNzoYzIX&u5O5XD!T48x9;$s6Fp>}Vq9MmfkjBH>n>@+Z7 zKU{=7eK3u%RRaebt9c#^SNTQM;sNQ6 zq>mbD$*iAxVxQq~5>K2G1)`Gvp>mS`Bc|7#vSnMuHou21pFUJP2Z+1Mmk?T`dd_1Y zhinbB2E=k!RTeg)hHZ&ZzUGtsUr~k`&c8B3JB9AOQ_}Z*ECb<7;_*Eh7cUeqT`Aq# z6WejeHnDJvSj!sb!P6r;T!r`ei0@Wd0)ymz@2Q`#?UGE5?r!Z|LM>zHI26CtVNU z#B{bxetJj#re>kw=;4_aUDeZR2xDzNW9_R~hX8A$Uod=$*<5Tk0alQCI>Rb*muaD~t9VY0Kdrwy zZ{N$Nis|>+@nfY&h9BQKr?+^rS*nh%(YW!I?{QZAk8)Ia5-wGlWT_ixRdb%f0WfC9 z^E50XB4@$L3->Nh5kuWPF6K^WHMl@o+@XT$lm9oolhBt*ZU_9^w+PsOH$zMO$1}8) zowbdfnVqAZtCEd{qph9m|6egvsb=N;g~t1kJ)Bxk8~sBV+Y5uhkAe)sh(Hhz7TZH& zN`Npy03Et-ddS&o%$Oic_TBrB7>bpT@){L|CKz<(*F_zfK%`-@d0ADfGN#J4QgiLY zJf+F1Rr{js!tIh95<1l)BWdL^(`Rba?8@${{;{*#+jZaK8`BLo+hM-ipeQ=4K|S`; zwk8|2eb!I(9Z$AV*yspfh_mTh`u9L=y}>BQ3o;4Y*vl9r7qg{O29 zH}StNY?lK%ju*D5k1ad>Y$O?(UJf}VTZ#KxR9zQC@9sTOP|K$!J`S(IRiB8d1g_>% z_Zf!I&a+>yQ)^-nxIcNH?n>8uw?1maTOuOhCF*o+z0~8y_V2hH8-(J;NLMIFX;IrZ zo@gIh7_hxmyyXTTRk+FM^Vh`FJ*|`C&RLOf#{Iv4uNB^|7z}fFlZ+`=J*ma(|7GoI zy?C6=#@UK-L`SimYBn^v0P?+%o81HzKLQz1sAt}IDC&SG%SP0(a1)K#%vgy?`khm5 zhr3@{@xrv3-$#iE^Zrc7vt{Et1UV~g zzBnzC+!Itt)e3z5KBG@GB~!i>fYYj(j+#p36LyU*e*^lR{P{lP&R()d7f;=&GJQRp znSzAEkZrEq5O#3Sv?GP_?`+j@%V~{jieqa)x2WGwIXmx2f@2Ba0E+>lac9l8Fi}pd zb|ma5lIasm@l%8EpC_o=ld#E05fkP@rqZZDxgkdJmrD4MyCgD~aL^uE&NL)0)^ zCX)xOR{D~sykMW@>fPVLy~nxvSq13iDJ;4Ii9 ziLrj%7;O%Be4DXHk+Wha8)b4=9h76{4#}}}$D@Os_+Z>Wi32!)8u~@MJxeX48Q(+3&phgZO!z!D`jkIjsW3)+G4kX- zwX|(5;d< zX%#6hL^KN9@w%77R;}Hg&w-+isjbre>)B)+?N4)sovk{4nO0MNDX;LYtglwLFh{k` zEEJ0WO(J3vkH|%mPg|OgCG)GpJi4pAwS-4kh$Mwo$g$*+c_rA9|9n{;3iI&>B@|t) z@q9g&tvstXsdXxYU#SNQ>k8exk5lj+O}FSyBv$E*J5_6%Su(^liS6j0;YeBH?0Eky zp4!9}RG|LBSJt}>rJL}C?z|_VB@^&Fv9;@1*CYZ|WGzgsd=gcGzNwH6YZl)yIz^=V zJ0;NXS%QY=F3OEoe{TQMdh-YAqQF^Hh2hhC>WAymZ%27v0@SCFfJX_L4Ngw`Ii5*Y z)#`Jz95bbYj<*P?2azc(ix?m`f_S%8RjHjtQTych8Mx+j>|!yD>_@M&>tjP<{9=1v zf?1Vag_Wg#bCGpQHnS?3arC|w7^ulSu{T%cgw%|r(jll3euM5z|3Fh2w_FYlz`5cC z#*Ku+GO!3N`zdzYEc3J5qE67b;Sy14&UFl6Vf& zw%T=L6BzMxmHWZW0c}94;I_khYD*L-((=8W-4VvGfxnB(H2)6MLzY(yAUw_q*X#5M za`Gn>Yp_`S&;SKBcj&S{g$nTle@Gl#4?*k?dm`1J@}ir&XB^!|{6WV>c)KW|9BB#u z6Ap3sDBebl6NxD6PoTu22i;6{$`kGfBabI)5_>ebd)A6m=0mrM!OVzpYJZGxm>(5j z;(0CoMs07Cy2TQhZ6f{2a%VzxWW`aZbmXiX;&S&^CY@jCRylp4Ijtk4U@@6bR0UKf zRCCQiO6sRDh^mF}YhJZ_T!o-78Zt=Gcfa6b7*;*F<2*300~$1oGi zN%+=j)q58{9XHgP$X?FN5^?K}U6v)8w00&N;0>3s*h!l8%xJff_#W$#A>{gP<&uNLJERp}bhbjL_FvwQY2=HyoFP5B8-!aF?U8h$;R<)YFx^;r(Xrs~`7H)+ z+B_pCmP-NY*U@4qFo$JfEOnVS4~4FqotK&HVa}CQu`tnglpgr!0jd4SFJv2cAn*_A zgHY=6&NS<9r@ux9CQM1u7YMWaOCK&jjHo9AQfvhqTZ?Af{@zK?x9sY=ax#$BSf1w zWwJOpu_Bp)*Yc(`o+@tamv(CMv(RN~kn&MgL!m|C`moNtP$o4>uC*({5{iYwz^Z;J z$DtB@-&PFf7+j)>>uTM!WRB$#tZ8ZX32EL!h5Y5Rsg_D!bF66N<$!k`^vMZv%M2~G zrD@yGJwSO!P?}hwnh_Yfu^?&&un?Qv%FA>-s0)?hEk zqQpysRetx}Frr8#Vg>aZVuM_Yq}Z&C|k3Wjm10JLzdT4CnU zLc;)cfTCeki$VpeTPXD)Ypv}0-mS#nX!{FH#3tIwJ(_xjv!$syFUm1}$9-dtYy%w< zHe1r9rQyNpv75ArJE->t(Op_e>)1kFYvVGhFu~bT#q3u5UH6ARhs3YnmGdBEu?njq zggl?)?Xs+=^$-lH97&Sod}N2!zv&3pdpZrdv!}h_G?fWAsO2uC&u2}dlubk*?-2i- znPmF?Tq~fzeM9}XY&ib^xJ6bnFgCU}`65T#I)7Q|4Q!pha*O_zQIx1-|8->={-hpP z6NJoBB77A8MPu zGUJ!KAX5UR?2m-_WM&!8dD&t*4@rckHEkL7xq$`=M4nJA~86Q{AqXi`NUm ztdGY^^|I$G`Qk3d6FxRx>Vo> zKrhJi!}flCtn@L+lU0T3A!W-J=`?NVIBnIaJn-d>slDMPdR~y{eX5x6bDuaxKIdo5 zWAqn>`n0qxqjT*-Ns#AxI^XUY{w2_JS8s!L@8QZqxeLkhJQMM>0BQF@BYYrd(>QNdq>oeyP{wQZI;KHBrXfqZ!AI0+zvmiv zEo8#U-7x3Hf-Vkrt5v_^_?q3m*AJb9#>>*HgavDL15F42!ZL+`MXJPhrP;?!uA#k{ z2gmZtI-)7CzrBA0$y&}yp7~UxvqnZxW4pE!>6|O7D==^@He1FS&crZGI|fZ^zMk87 zpz%%@P@M4|Kd*~1bBlx}Bub09@T2jGp9q7E5tBFr-n5~wCs;oxn{NMZSzdsxuGhA* znl9^@@yqt2HY`Pil&^6++0mI3d7b{8KLW+hjLvQKL0u3zsWBB00wA(V-78Czv)Rz z<0r%j;>Tuopel@=E^LJFGwHDnv~5uryvvBa-vE!^2+lYKoHC+?V7}X_xu?G{o641z zsroPFSe8*=aRLpy8NN2gn{suE38RJmYULgj)~2JS0*j zib>2eRVB=`$CCWGpI;rccgu^`FHKfY@_q}Hy|tc5p}Ekn4hK%ZfR1u-QwZHa>{2e` z6#@k){B?l6rR=D2miD99tStbFaHc=<0(65GTl)&y;jd#X+!ZZY>ym?S1W}f9&%fXK zXG7UqWIYPf+VLIMc>}1r`SepqKpcGM2E1Z~${W)otm*QCkJ^%lUlj0;IkkI5wFgzT zjouR?y)bc8`|vvYm~Lbi87D8^SgE~Hjh?CoOLMgJ0`T_L8}*A2{x)PzED4rjiJj3j zVKw^@v&Pi~L!0`7gfM`>-%j2#Q}RX-qlwI8HBv+aqB$+_0XOT@*%1m$oeAp51hVm^<~ ze3CuU57o1SKKGO{8#fKdoQu3gYzrglsAQQEh;|QuY#DWD4_cngs9OSU}g`2>>ks8%`~wcATrfRiUkrwrK8fUJYeXVrTkS} zJaC5rZAC1$vsv4mhewA=a%vXwX zVWt;Mz>gx9Mpg%M`9#UL5j!M!n(t;V|PN0xr|F)xnn zUQr9yBqO}+q@w6KnrwN^@_VE)&GYXO2l0nFp(#s|XB?86BlAnQ)(mn*cZ*BTPRk8fYp=NRbQK6+D`G(wQoo3aqsUJ8g8^rkCxW zYQM?3*Yw9^EguZu&e04*^Q9N8MDfBuJk_GpJsIRq$NaL8#>Bhs@5_aN5`6s}V2Y4j zM3KT?5w0lr%`y4AM%QNNC>tN$i1{o?4zDquW}MtEuVrm!F@#}M^_TbyJE~f4SPM}Q z%$3?W1YP-1g2d}f!|1SjsODO0gK-$gGSqa~ZM7a>KVh7`m8xPM6^V7yp>#yMc-wyu zckdlNp@#2*DM=DWK(nt9$y4k0N9TvnXfD{FzmTy4WkWO&(zX`%UXaUs*9Xoj`)ZBxKj?$2N{Z8G%z zu%4`KEh#89Nq3|N64PT{07XYr>Fa5iUrKHWt{!0r5qFp)A}>9Z9#Ns1WxgZQMyXUANgU1}s*Cm>RIrE#SL~I?K-XARUJR z75lcqtqDHrgC!s~$32#!NpGWPZ{=dBjM}|Qk@@UX=CHun^9N=lwwgtQ^Wfc5cQd^C+}#NNN)^&v@=ZbnIJVpGZbUm3|l6xx@ho`3B{HX8n%(ePJv03 zs=!O+E=W@`f>dLsLMS?9W^#iwKS;c&ZHA^kvy8uacyH)O1`<}J?UJLmsYfxs-w2nK z3xty>sgQ|!P^!{XUv!ln+~0&I+SMo&WQ3FC1(A=DRESF0b37kEZZFLV3mORWixiXQ zWE2=ObHxI2ECP!P5f!bzzS^{~0={Bh$LDHxiVcL#!6GO_*e}GmaP=)B^HSjQW8e&8 z;fx}qx9K|rjhs=;PE53O)vggcgXKkbh7Z)*Ve|8WiY*MRdc+Vx^`LsMNG&QdLEvuj3ClyR%kpp5w`3Cl?Q`N)WC zjWIbKlwsrMSh!ldq1yqwg~d-WO@f1B(z|Y@kD?xDNO}qD5tt4}?mn29w~m`0n2ugh z&`hsJjncZvwPmKqqjje#w~x!#@~w}flx`6EaJ$!`$H?=SvtB;!+dY9y)EfytZuVi; zqj&b-axQaJ)4_7D+3)C2_-muq6i<2jEAXgtjDGo7-Jc~6PqqF?#5xGIt5C2eL#3|< zxx2%<-odldLngJo55RDiA>TOIGwDZCKD<5?#4lT|=71TvGpVX_CwtziqbjW$^B)v~ zLKhttuQu&jDT>1gA~_~gLndjw3H^@ z{SM12hfoVG$Hqv%cOjE@8pkBalceEjlH>)}N@Mg&OQ@NZANX4ye&I9{FC+61N~C8R z+(PlZ3Wc+|vl%7~rK?89!m*Sh9n)ZOg8%Gx~B1G%_>@#5qwBgou z=0*jjWR%BUZt)_lt5*{5O@KHVNAro2aY;7)+`99Nwx=TBf%ux5J+tk8`>D7hf1;NJ zx9~9YD?)`+w>iEH_ZDUH$J2j>cF|H)HmFwi3&`V**ZVkcEJPVj<}93oiG=6P)6l$< zEL+P)T`gpIOt8RP<>%P9c>PCh6SinMfy|1%@_$X0HOO)5ii_hWoXV&ZW%Kw&#>zvI zqE!G(?Dc;n2k9>&9TZr|Bg?wpc>f9(?#5qHYiOm;x87ESud(2_ueSsVFIsOIg=9x8{n{j#$+NiZPH8w0%X&mZ!6FvbsK%^pPN0W0>_b zA&DZyAsF=&vPKdS?P@?x?>G_h((U{dmq-WZumeWJ>!W^~d`yk-&o;Ou|?0s3AP_)iQ?%&rmAuJsdI zcC0__T3I7inII1fD{0EOGau*i6vz05$%r?Al~U^g#-_C8&pmWwAG|!M zc5L(foQaFa9DSHyn>h_)PFB|V0kRWQ@iH}i+}Pml=z=wCme$y?)3ea?XzR1Lt8Fk| z=tOCP!}sB)n0Yw!h2sI1hs+5ciKWo|1PeGkhx5|;xwc9)4O>s*6H(m|*@>f1xj9Yj z{_NO2*fvWwAou~z_~i)PEM}!x2(AJzMTqkE3NJ-nyiJDtMp<0uKSV4V34>*#rJeE% zxjv1n?Q3e3VefZY_P=@Ayq81hi4f?8+ga0J5eIA9eZe*=Kxf-BSO{gg_Rqzhz2R?o z!~2=>@^pR>b(}MiVd0(n)%ZQ+IHbi~%Vn@)A>Sb;4j46fe!Ix@M2X?b;U!*2YBE&6 z(7sItKI3qTv(2D(!cNcq=-A1Nbp!1(eK$iGKw82toMzZ{yLW4SX~%iDc8OHgjdora z;1m+)O)otD62$H3S_^0l(Z0Br1I1~>1CibRf!CXptsbD{yupl@x!QzpaOn`heryC_ zT*h%|FgM#Q=7rxUnO}%ETWx#v+O&-(vDVUPu$1w$$=wbm%(jK?Fe2Wgz*6+To?*Bq z!(Xq*nVii=3Xw0@_XenOgv%J%2|&)C0D)W?L3-AN>qB@{Vo%&A$yu-o zH4R}sR_q8SqSizs3$q0^04?eUN=5fmKd5WrE@1(Ww0MWg@0QDrOks(jjl!4p{P!aL z%`+@AB5g-WON2i*gV-CwyiSvs{=Q*(Tzd*NKD6Fk^pjMR;Xlm0YLzdRa?yj76R1|I z0kMyvAas2|vv#(r?Sx1=&UU^D1gDAhs%;5>+MMgWaCln5J$kSrT5k1p={Zg1_OGn; ztms8ZARm!kX2I#L5BL~y`}Xe6P^C}@ca+n3D%M`EF+gKo!v*bfDT{51z;}t=-}{_G z^5xdMm5Ta`6TTvvUK^F&Js!Ia$;l77EI*ZM-I}b&B&^$E6BaxJhz#IU(Hvhp6lX=Zo+=ImL%;t4J9Oi z6unu}Go7?BIlfqjFXkq+R_*WyUJ3fa2U&HH7xtZVEA9mheu{nUQV2g^KmI`f@hAR2 zC7$)T%iH6Niot~N@5a3Ue2*z>U}a!tU}N#$N4@_qYklJ%<=Cgqt%{)ee5{}We+irn zR?YW_re#g>1Qd{y5E(2QBA5Ek0x8yZgL=yC2qxZ>fM`0-i4vxl-H55&=qyHO(ark} zGkl*rI(zO%)A~T>AVV|Ht5&n=D>vTD&ZEOeU;OtU+c36X#V?`{A3S$Q=)Z7!Bfmm2 z?e~!MjNjP9$2V_%1>T;3PLY{fld)9uP_wV8{PTderhmc+c{rG(j-Eun2 zrG7ZaLfbiBc(w`uY2ny))DH_4PzXs?KM(Xmq@mk|Fbk2 zOB&81RIWvnN8zHRdMR=JW!tfoiL+o%!lD(oCy!FeznU!L%qUk2pO_dIiDJ&H$cyDm z>zG?rZL4HyBr{;NN-b>BPD)}yQ;U=gGK^9)wz6UFDqEyc0xSZ;8F|T54&t>HlmKH; z(Ei>(kBnxs!lX6ySg3A97<7y|nM}s%$*l{<7o?D;I_R|p-NH0lSz0AmTJrlTwFFAz zcM;HGqb!>{9lKPDmXsq%+?WR)=5(OmB|877}Wj*_(bf70a!hNM4uUu5`FG(S@1u`zAH1(?o59A!jni}z)6eE<`bI( z7&W}oe>bI9^{t?H3*(^edtojaccRE)x;V7^oOLWsY!x`kh;gsk@~4nv+03%Knj5ws zVjbac4R*=nX=>kL-h(!A8l@WZUyw4h<>+aoPMiEq6Z9lakv5)JKFzB4h9eyGdB$Wp zjXZp>60+p3&%^x+agWrlH?@#>RbshZ&SJf%QLh|BIlZ`va4ZzuSW~i`pmlAg%9}PO zwPYZZ6UU&DhbY@%1;ET9J163OgNNH8#R&-9YdFn+ruXq$(dhO^;9DdKc^XA?5}xQZ zMjoV(V$d`>iQAsDx5lQ7*M8*&eD{e2=>!Q$ZU8`%9h&mxZ?B6J*S03Hu{~D>-6rG=2TzD9-9Ku%i?YrA#1gK z4f-2!4)$ zSJ&;u^VH?xWB0EQ@E!@8G4`vVz@NJ30~xvvI{-}3D2#zvbSN0FouSak2wiQ#xd_on z*15iBkAz)XqwMa_-%lP4(GBRxE$4$IMaI(Osc|!khDAmDW@#F8Fg|2yu>?_)=6H;E z@rB2W74dXTkB#I~Jl!A9BGq8sy0pfrY1ui4wxpU_i8b}+SeT^11D3OZyEkPG6^$@C z#MENFd6qMOFgNzJ& zSt)tZ)25^c87JI>TIUy>kYu~+ngbVc>WA14CNZPs4>`?E^KJi{XU{DuCuod`vX4g1 zA)UmsIU+YY$tGwZtuFlIIHI{gTccl7G~m}%iXKkQPcUyJi*wa6LA_OORcDr_Hd!}4 z%vD&d$DUvs%(sF23KmF$7Bwpytn+_Sf!d@5T9;W1?{QvM6;Iq`i~&Rh@4AsZgAQ)V zUtik1RPY}Rli3V5wc}>m3+c2JH55<=TMT3{NTZI7pMn&IxOgXa$|Bu-+~Jql*Imk@ zYCP^aEf;LBDsIu{~y}UF}m_-%l1{VZB}gC72CG$ zoR}3mso1t{+qTV$PExU6Zg;=&y6@}P<9>M`&KUo3zVEfyTzk#m1PvXmI2|z*N)fq+ z+T#K9Y>ns^I<!{0)9F2E`#_`w!FlDcD?FR72{p$K>n+KTWCF&~S)Nx$qYd z1%*#;oyaq@F`-i2u~Ld#Ouu^^|NZ;a&blFAzq{_wS8CYuS(J8%O;^{|>F$w?On^(4 zF{h$SHpy@%K%Dh2$=leC9N5)%=!JfslBVzXR%(LAd2}ts zqeT2;da~c4;dk)c;y+Zv_wpQKg%M}b_8;tbiyWQ6FO5c9Py6gl41J+3oRO5Y2uB+oO>Lh*j$kxz3!yp8JoTTo&LZB2) z(hksckSca?rYS46B#+Ehu~7TQ)ba9^h!f8A{A6hYsEwWy-(qF0#o_ztGYr&|cIR*c zN^FbdQQ0x;!&x+roiRB6yqiXE%QkPD+k_S7ert5PmIgT)HQJT1b8MK`N8Jzysnm_q zt}w6zIRT%9ZC;_@{h)5hMY`M;9+fN4^;~+>h40Iiy|M8j6~I?w5ZCmdXv01$X_xSE z2B`dwQAJD|Xj;2#!I2NW#KtW6@cTDJiD0{Uw9i+mAN?=M*8hws5&xG5c>fzwB5CJr zYHsTEe>eG6Uz}ak73_~?ElCa9=I^jFHjda!g#D5)oO#%BD9TZwD0zzC$ra>Vc6(v{vDcbfvcZyrE=LGJS*CPKCSj)0f+-G_F}ox6Q_hHi#D;tI|7 zbe!4BN;{nQxLPpF$RH2f;G>)(eW?8TZwm{0n9Mn zte|-T+;D`WF%|`MX);nPl;Z33hN8<~pujjUn7@mm;cNauLOTdi@+uAZ(n)!p{iq6R7riwFNxG>G4|HR# zIPmet#T`jE%+nRm^U!s#hY-=;kc{=d0>wZmz%!L$v>0jg95JGdxp{l#mgR_k4?j+=7$r|b>w4(7<|0kBx8t^6vr_&lk04F;=YZ8zDbrDd)Y%yi&{ zhEa2Ts^LZh9ZjutSbmkeCqgTc?&3ldpE}5-tWz-~QRX!GLG9S*F6C{$jQX|9GeVY5 z62X~PBQ}!GsTdrLKI&q|8|z*n>mB`DbrR}33ewg#xjtWOJzneiLE_hX10R84YQ4|O zW^|NfeLU1x8LRZme&oh~WAJ$&{_??`ObP`vvCAAJ&BS4=HAmhuPi+{ooUG2x5!_>EyL}CoN7c1%Vb0a*TRbx=M-}fYRk$8HgIRwp2$@H-6bc!FM zdxtIEVq*>lI_!O~9LBjZ+D)heBT|Won3)@xCb>fPB~a?=?^eU~s;uscv-c*rro1rp6R|2vLw2 zi9O-B1_mJLF2*H{6pX&BE`dD99OH)$Cz2r8c)}Z4`R~;i~!i&M49q zozvcNr(6sbx5?32zts5=*OoNS8TkCGj$FpLmGK@_+bXH9+`cxou~ST?_O95?%3*%U_E^_PoR23 zISz}!NoC5TZZnbE;6CqcU~>|Q=xXO_)t@jYS>hP$)4~>=M9*}kfxoNlx8ZT;#fJl@ z$6-B=j6Zq#4!svD0Bg6=ieX#&0Cw>p)1TXCDKmL#5UXc$Z0+w?z1la=TfWb>lLtmW z_T(;YoFU)s+Uv)ZkC3lOyW)Irp0=h=?7gMbF)lF*A#&LP4jAa(px{r-Wdj{DhmWb% z*UCALAjIjyRALdi zbZ~k>UTYK@`yk@C^%L#})VOzLj&Y0(Oe_rY6NAB`{;*7^i$5fJlVK)TFwdnl6&yan zmQWB^WT>tjOLOFCh)uzL116Ng>BXTnRRYxWAR-jPwd}(?n6b1q|Y>WS?ZtY1V0cWfm|!TGo??NbI;=9?!OnwR4&f~ik8uq zv;u2*uzONr5Si4Zo@OAe@)j>h?7vs#q0kV^35GAS0ObtE&?`x&8OC~qE_0=GFSB~f zt?!kO%#d{p-~SqM z1^F{#K@3>*D`1s4umov0VGT=Q6=1=V`~qreWgrchI6NVa=IlyrG6i{+BeXb*!;K+b zg*e3K)lJgr($P9qRAz{gbM^IJF)zkuh^?u?dnwYXxc~fC%fDk9^0V*lw{|0yq-&81 zimQVJhx022*Z!EvBXOYL=A>hYg%rn=Oi}95azHxW?-D9gE0JOpvMJq?9lezaIAf}X zahfmC#&TPJ+7L07LPUAjcFE!2dfT(L2w9Y*sJxmqH73hd-kGZK@*=^Io5SK^X(OSq zm3?txt@1dQ$nng#&0~lbm5oLS{CBqGIP+6JS5{%&G3EvY(-+XI!T5Oz4GclwhSI*#L^(sCJmG!1C^Qde5r_mJF}trr$qWq^VsQ^B*aDd zBqCtB2^~-WeDtHSEQ=jh;G;r@5*%6_NxL!=qdxcb}#If$cF zXo`D?9W+trD`%9fzvdFUjW2oVVdW%yHPuoDRF(E#mKCnwYdd5tiaGW z_;5^viH@755m&{#f+#*3w^s|ipL`IGF_nO6yL}!8eIP{mbRpS|k9&fRfCotYNx;M% zbig5aJ1Sqt%?Nk%+zW{RQ3=$ruUKiI?|TO)P@DJxt|>gm9O_!yqCjDn;JaKxCU!su zNxa8k-48M{JOg|AE28JY>gk6;`O-WGS8c+4y1X1#-Qx=}T4OuV8|0 zI`O}d%`0F>9o7ORJNOo~vNCvdbz}3N%@)$DsNc$&iFeCZy_gDEAh`EOo&a;7Y{!8p2i%s%z`_h5#0wG^{ zzQ3T7n|Un!_jX3OO}%U_L!r8c$lUWTEq^&kjXnkbQ3&6S?Aw#TzI|)@FMA#TEDN>% z0tJswIJy~{!lWtGBtMoT4R^Ab2WAP$3FXiS@dgC)3(P|Mfw=ltT7(pj0Px5 zL49B6ekfj)#R0JuiYJ$gSlAqmZVc*QUt5j2)V01$yn%fQcv)4WJ_i+|mXJUXp!^d2pcZ6sU8_v6R+RWe7q ziUHJX-S?xzSMxzFMR8v(SN`+SF37k$_kmDYejU<9+zqk`)=3zDlpx__H73(l04^$c z!RR(~M?z4D&3q*mwl+iM0}8@Q<(i+^ol>ZiSv9lFjaWkXDvTg@%QC#sf%7zLxq#-p zGWbJKNmZks#@uD*YPE8i2_UoR&ZxSv&cFueOlq1r;n;M5zM;MpQyP4L94w*Oa`gbb zONX7)+jPC2#j&ffq(O|=7CkaqGY0cs>OsYuPrZ7zZ87;UTzYx%`^cPMFt!Q1sW{nR zaY97HKgaE=Q4E|LT!F9)G|7Be2itQPHMV*l)2h)VfB7A$1A3NSuM}C44;-n$X&T1M z8hG2*7pNiWQ{79uD-|iRUF~K6kbq%S(ec>I90#fXDS+pyE7M;NJnhR6#2c#nL41l} zgd{8|G87e#_4V)&6k^O@2@b@df4*@=x()-#1kvwTh9!nIhPl8!_m)b3j?}h7D|vP1 zW~4poNaaJhD02A&DQq}6##ozapsgpk;xmIf@I7o$=&O-(7AKOh*|{=D`r~Ubr1^$Q z7ACUwnmaFOZW$pyaQ!k5wS9xGYcUP65v&cRl7`*>0WE zW?cofoFNISj3HgpmqAQ1t&Ghe`DOpK&Ii1(Zty_eBtUq)p=IP>=QA}#3gfN*#iqF3 z1)DGj4=K)_^?0(xAxam7oFWzjNX+u?F47&V z-F7~};LgX{pyyExp1#l6EtR+bbg2@PIA|d~1zER%&vJ%FmfGViniGeBumm+P3xd-f zAm4Hry}uJ#uMPShDnVg(!)y(sEVGMVTn3Ybb5AUH0Ec=%+T;Yy0BB5kJig*%m1lG6 z%9i<(zsVXOa#fYToWuD;Quw)M7ml^|%^;Iwv4z}|nz&;Ks|BN&f(AoLpF08up0ytv zDwyG4Hpe!PCrMN$@SIq@4wpNgo!(%n+A2D8glo9rknn2h zWp%dSVn1IMgn|Y8{`_*&AN(x{#B)Y480-Trh+0xu) z#6B|@d%64;e@yJbcr^<4l39nc^GEe#VfKULA9WA#wF~F)RrdtGn!x|}PP56sT=&c@ zot-W1%o$`|Y@97!4V^5%(jfjF7AI@z?(E`Z`eo($s)2_8sDiSF?v}Qep8xj!?+@Z# z8t~pas!5+a9BG|n6B8!IV-u5wXT%DmgtNaTLdoBA^A>(u@wcZbL02WFjFF_dGACrE z6;fSQSBn@fsjdxyCo%;7q9jIJF9buWBvw!~aeJN>ojqEJ6%{nq)iL>eoFxlp`E2o2I!SZkXM78F(!* zS@HJ-RBw8q9ktrGvZtwuMh~M+ucRJQb{+B~@7x584lu(MEE;w4iMcMt>;4m7w!AO{wweV54DSL$oR21P!o^*pc9P7yI$@xBaiU3 zBZ#C&jvmurxju%wHgA#MZ(qFYox)^!sfFx$U}KCq*x#_MrVix|@X2PAdC3~d)wHMt zw}U&GN8@!*&m5}E@=Ol2bK1oZGw7ZP&pr3HcpAU`#@LM zUC?_UpbR_yHU9Ll^4LqvlZ7kir868wJrJ1(zokLWoSM&qg7~gAS-D1}yoaxQN^%fV zsf^#hA024I+Yu3Hm95thH(t3n22ykhEL`B?UHwzYvDyW#gwa@H0(cQV6#mEp6FKeJ@aFewX=}o~V zuo0Mjhj>IRikD-S4)ng%zC`ZGjvzhXC`;Vz+zNk092J!v7VFy$Ykb?39kIIW2oCJn zA;2>^MK5!6cK<#9Zbe(*>%+a2Qh+UK{u*kg3Urv?TOH%gYM#@OlM{&03cZs#+dNKo zUf&jk2G3A|aW|D2KH2wIUqh(__;m?SBT=ACowNOw%5m22Btp9Zg(Pc zESFqm;wZp`Udz2$^YNm#_rZCj79aExy_&{nC;z`OT z!!;2*Q&qJe8$$?PDbStA0J?KvQtv30JEaH>Wy>~#?WaS+-cbI-S1xnq7(0q$Bi?7a z6z?_!ARO2-WGX~oBXu23K>~vxX?)Io=dX^X>@Vyu1MRd993MCDloPBqMJpUAp^EGUptHD5jCv9A;Oo%pPwT@quHYS!6ko0q;C&L{> zAdWeQWiI$0geF$djFg|!F>8H@MJEz|QZg|<8&kuPHlhqgQ{ZT+6%>*rz`+l+|7vps@nK)cK&_0UfH};8&{4h#o80v^R&DsuT{%WXk)7 z%p2l%GS0`?AkW1?5K=moPJS<%9Tznkw|cPnZl!T6z}1yRu6;*xIMajZ&QOQc6s_x| z)v|@kTJCo**{6U-KI{P6P(K>whWF4q|=zevD8;wVdYuoc`_-*N4P}a2QR3{Hnb3NzF zW2B9=S(Y!wR6Zl|>ua_2Dz8d|20_1IXJh$E900S%s;Z;CO13)%U%2y-8*wdbkiq3e zs|ZqMWYxoWgv+|4#pd*U9p%!((jL=-pLx9}lC%6}ufQ2CbjP-$`xxmJp-6{Pwu+y7 zdhQyuq3Q?h+bqJFdY4u+Q9WH_ISE@RyDIHsrNTDD7 zozuq=ikQ*r4=w2W_i)^1a%D#Hz+$^@D3JlD%a86c90OR!+|yZV3?#dJ;SOs)ovc|O z6E4fN{0d#Lrqf{^iI?-yf8i!s3~<*%@5%`C zoZz2kW^fq!UlcB;vgvlMRRMJ+2=cj4aJjs)0GK-|OL9LKJ>3K=GU%~F?P033+s`D? zWP16OwK;T8tTKI}g4gL!tCLh+77oIeRoSR-qbV~2O3Yok{qwQ8Tw@EIV8mwR&?cxv z+n%L8j%6;pW-BBn=cMzE(_1gI>^G|t-;i<)6K~c6L2xvJU=<@|OZ!DjhlW@uhouHB zF34E(388I<^bzi8b_zf8UDBMwdd*_^4xNCO4%7WPfRI;i zB@7Vyf(UxbB>K{EuiRq1ZR_fZIVX)_K7BJ&u*JD-leWUq+4K?Iw#TTTgK_OFOzO9EIU-U zTX8AaH3eBLWcLd-63$>CD}V8J3ml%5qvvAyLl9tDWNtXzHs>atBhb}?WZ>TFz}MNS zb6S8`^*d(bP?NNvZ}z0_Sc2m=54Dd3EZ(Noeal&iO1ev{gilX?y+zY4Wu?zqSak}f zse~z;8dqpj?L(!(AvJfClg@S#8m*@;Og24V%GFTXl6sLJp?=z=d2erRGn%edDD8)l z*-Ip-P|(|dEr@tN+T_k^ATx*J>L5*-=bIe`1Vkrrx_~TA5k1=@T7f;}s)1G|9a%;)c(WfB+TrsT*tPVE^DLuQmKyTe2t6n+I6f zN+^Kh1vCa?WuwdQQS6KIQs@obX?@RLfa9%rzRAbvm0k~b*RdU^|KUKN%_?B!1?pVj}%U)u~G_4v}a$Z7{!4?;L~iEJVjP zLH-TJ6zJyCOEwiCRk@i{< zPP8HdH55gqNkr|`32^C~)UMS;7ndDlFyd>YrO@>XT4a{eP^Ym@FOOl^mg}ifEt-@Ta+G-c&`AfuVgwOTJ&!x*CRN z6&=}}oL3hDPq3iZb@wO_kDTzrkTVc%xQZt;+2bUqm0#-Z7ik^6MboJi3o+FY_1QD3 zaF6Tf10WmL4pPH->Fy~_SYsb(?7_U!?&Lcz-ik0}HO}9%u|5lvCEEjpX9@oxq^VgJ z9KpVHjCiZ;l`+*|(H!k=6sZA^$`r;()nxZBvVU{=FLli2GZwA!1V>~mNRIOO1Jb31 zU(m+A0-S>xRJi@wypZe^38D-DfxS!w8uN4QBhO!^jPym zD}RbqiezX+(;qK@@8iMUWT7FO47RNjE$=bUh0lcDw@QgPf&zdTbAdcVW}76y^QXE(1D$thpS= ziy{53nYOpf=WJ7>uHo2;J-l}BPObAWlDacu)hWnc+2>6vc}q0&@}iIW1pkMKZ3x{X zWkLA%?E&w960tV_-$g8`h@rEg(id&T*v1e5=u**^N0UVRu(F$Cr30bvfPvCeGjC7Q z`>D(Dt3C=7rPqXw*TP5%4qSPCVd~-UkB%8~@>h!}#R7ht`j>!k@^c*7u$R-%)tVKpFqFK&RIC*;p3x^g0Gu&{x^NeX7f`_h2#TECTtD~(iUsj2v{1@I(rf{45C14)~nV<%-8XFsUJ ze@oH$RyoDS@5EPBysf283_8&I?fnTE+<=oM)1zAQ{5?t4KG_-OEUDbqd48O36Eu;X zaL2DM$h`T)QD|o_qb|ngV9|BXER>dZ5@4l)R#Mo`3HiyOniH`jgd0L@^E1-l5SE0~ z&X7clF0;2Z*zV27Aj;6rC!SfMb~Z8rLQZovc!B!YC0tc>k@;$;+NFzMNl*Vux714% zMw>di`H4yc>~jYrT3&ig0`P!YHKo|Jab^R84`8cqxBmW z#%{GqTfxHC0v+NU7yQjg)hUe}hCJLi_#R4VPXt-Nn%gO@(xcAB2J5naLa2AJat`&Fe?;*gseJ$?5w z^5b}rr}?CSpT0iNTwps{RxIDzUiDy{X1A_5)a$iT`7DU}fm=Zlw@}J!)5X0iRw0QM z2-VX62KJ9b&p{d3q7C}(o5`0|3 zzEJXbSaZdt$VDdgwX2v;w}Vtycb?RGy^@Ntway-&o;f zVSDYoIpA1e;1?8mgJjS);+AUOA)xpY%-T&?_h_PbwFvQr6Hq3%^ z)$^M{m)BUgp4o1@Zs8$Qwc3H%5JMWgqOwn7qgj=JHZ>_ib*{F~DCy43u-^4t$5SHE zRcataaHP7m_);!CxE$ScW%R1HSdYbhyBedU>UMQ#FF>`?CWX4OF(k~T=x|jBAc>Ca z9^uJiw%2I7j>FENT|yIRMx;!aTAg(C42!e={w|qtyowzuqBfSi1FL?ekdEg#-j=Az z%)+8ZeSj9($fwG>mDW{e)4iX3x1b6XmEvVt{IU9xUCmu7C=lOrccloQC*oOZuO#d+ zJ2v0g9M@?ZO)Z|uRsx&o9L4DdceIWQv6aUA4!9whD)Vg zaI4}lMl8BvL-tAa!QQgL(;4Pewf~JEFOwMV2 z&AlsIny*52k;B6$HlJFK@-U~lo??nwH)+P*9}}VB4ca8Go~tbU3*z3S;xv9023VsO zI99p5UgSk_&MwPEN96`L~~z(U5>T}R~*QZ zF(}?GkVcuqdxLZIyHEG31KIpNw|ilUpW7w$SZ8BnvD~rB81aKGA?GIA@OK$L!SG)2oI6pq<33876CtEEynw-=; z+7O0whT5+K)!TGpC&3 zGG6M8lZ*~mo*Q2f)1<%~m@Gl-@!S(ctw1Ejc(w|vSJ6-jh=k0<#zrH=W}7~i5@I=( zmqWXeh2YqhhFkW>xWFsaQcOm8rArT&9_l2EF&5$oqT;4Gvp3CJ&$YEc6$5|hZ*M${ z#pXit#O zA)SSCB-9{kq{T~GyPJfMHP~VqygNuJ*G2?6S2W2}>C3!@s+xrrxhq)WLxFe1!;XTN z#1(}=XP7}fY94q{f-G#<;_(!7?8COm2wkJhJD%7z3OjB7{fbXj%~OAKH<=BZVZGb; z%du{7=f%qn(7*!8FEU)aErnfF@^&noPfC%zlL=p-p|44n5VCPCdTgN)-_;$~NC9WD zdlZcr+j4&?^avNCQ%$e{JJAe)ivP%)@)=@X{}FyZ$wAH^s|l1K>?=^D2k(Z#ZL+4- z+jeS#;-=M&YXD%hGyPOy5f1x?h-{T*AGw2ME4_M1DoPnC>dftOUq$V{Qud-boukaS z#irU#;<{f5QyS8U$a(Pnf#X{U&m0?JPhHR}J?yLv32AU!QYiztf8$+uX#ZwV7@5@&=bPF?d? zD0B*{y%tFd2^@_)WpbiLjp8&*h~hjgIB(43-(X!nlI)&wU*~q#&_DAkIm;gqpQ~4| zJB(6JBJ3XKp^qY}7TJq+;(pLLN(H^X?cWTb5lM45yZpcs$aOob+3(h;{)6`GMvg-K&$seFGjjO<} z7qNF1-9CRYbe|TuTxR`cwN;`wBY&-b(EIbctmReX6qqeNlE%f1K2b(JVWydkmXDIoT#T%~uO-z`y%yOh@}Q+8=G3@< zj-X{JudY|Yop+Y*q7=Y`6b(i}+Ugk%hFp!i=*&(l5k&<=lk^S@ks_cxgq(^LN@1&t zOF9S)NrR)o7R@p|jAE>}{DfI)a+# z7WK21G@_*Sr^MuzHH)*qL$O++5Ep7lmp)O7D4MEwxqShF=B7g{B`Q8;uL+PC)K}LO z#G5c>4zYyC0Zd*nIe8jox$`E}4e`@yC(g$$q*>Jk<@);X6RH11+&} zsy!J=NP<~8q~o}5zn~~i%cE#yJepQhyK2mvO zVVvQx-yC4bDGv9Gs*|~!dHCR^#n(pLEgP&MDB-&Qx=s@G0RKZ@r`q~TOnh%W9~Ot2 zRLzA%1x_CZ-9n>ax35TwXLem21wP|TW(_}=I4^w^sGbB>Lv5!wU8YCiS?gL87h}yW zUterCBH6DG5|3r+8RiMk&Q?^0vrwf9dG?(WttyIX#2lGvLru{5cfwi&l_&cb4;$){ zF>+iiYb;*nR3`f{ppY6V{5Oevx}Kx}U$))FAgX)3-f4-&aWDPTQ&wSJtiJTzHQj@4 zeu}02H^Ft>{548V2St5ctq|5WFmY=G=;@CBWqu$hPia>G4&|zRfv&^t7U!?PePFd{ z>MSV}x5xwj->GjZir2-l-(waPMP9N=?aoJpUXyok{a|*OHxu*=#&bf=p|!6dt?jpk zTxzchW@hW7&c_T0^eC#@249w6i9U%B6&#S+h_uReMRX}SQ^eniah9J#!k9{t+RDIG zjWIULZZ3vh@CwrJc(;WR?F_!zlZ3bh2@vhQr(VurArvS-v5@lu!jK;)+xl3_brzjw z`WFH4Zl}1T`fDoXK{r0%Nif;b3`zA~ZA?R}bO7dow~**b9S)tPZv>YIZ#>!peaY*m zwiotCc-5^aodB}i8^;Fkc<}=n{2Ws4XGR>2fm>)?jkPH%`brR2 ztC`J-4(GL8E@)i%)O*hJ$B9IAc5^*AWyMRqw2kzOWgd-*1q@1FvBdEuJk2^x#J;#& z`XW1;0lwpMx1^T9h8?W-&`a~OwK_(mN^9xqMr`ZcrhTh-30yzo6hHblyJ%4?H(>l6 zCTbfhMyOIhEc@gTu?zrPWCian@@ZSKND_>Mj=5aDF_;6r>Y z++~%bd1RSaVbS@;)lTKTL1f9Y;(@px`Riof zd8&!|URnD|(3gj$4}ZhjjKgteOUfzS*(sU`_j z49&ZRkR|7g(F=N=5iEL(dp7t!JR|AY%b9ME?+_m+!C{(@d+jlPRMvg&ulFYdxe(F5;{*NszMdTiCudI=d)=K3ia#Zs zXqmVK12t@%ItAG2eulx8##&nSA*mWmO{UlXDh{ZmF>;k!hK(qeLx>A!yl7u+0<64y zx%px4PLENEs(`n`#HW(=76&9}rQCmLp34efrI0FP7SWh^C@7*I{Qf3h3XuB6Qd~6J z$&^=mTbh=UbPw&AjLb^GYLt#5nS8vQzmTd71A;)x%7>4Bm(NNePDYnPVqU;Cm%4!} zO9d{hZYCSJ88s}ToZf-LpnXn;C=BFOc2%B%oQjaj#yCt(qiJhnXlxImFQ=lz#6Q_m z)J$@joBg{@oFS~f0OBgZruFl&LBeS&IzEl1AwO?&V#LK(EmO5VLNLQ2WIu~mIR$*N z$kcdn99cA5&DxSoQzn^$tO7j7q43b-yKPaJN`cF1yop5i`BUL5ioF)s9Fd?n$W4BP$atqH$9Lkm?f`mk_$A{*=> z>(1GkQvpijWa-+6jA+exJP~RgM_F1sDIzs3|3^|VS{vnbB>#m7ru731lmL|*#gUDx zoBT|+T{sbOC0B2HB*=@}(D>&F2X{HPq*6-MMbZHdS)@)&;I-gzD6JDgDZj-i%leA< zYD^V>kY)p@Hs7ody&7~d1*4j z4S3)UGE>`NwKEHze#KW~s09_X{Tls-OByg3wB|V?_uC?D4-t;ye5^(L{Ivk>&d1j4 zCpgCzO%aXDRmBtz3e2J_)eLHgH~qbRU66U?!TDqr7aZO1jcPNv>FjXag>i?yh{7?8 zrWa!EiF{>X-rEEvPxh(Fx{r5)I52i$`$3-3Gq!JD;KSj!S% z+ZN;!d9wu#nF(8p7>Y5AgwTpPt8rV9C4K;J%` zH0q)IGcv(@0$&e+Ip z>>;*%6-_0JDgbgpKUvq};E$_U0$A}lMe_6VS{Wo`vnyd}(3i3zxQv-2ZJ*8B$?BFb51 z&&fQC$ZQxiO73gNrhE%($Nm8?7JKvKj5H3GSihGY`|a~;(eq0T! zLQ5g((E`Na_X#SW>^~s)F>^_x8CFQqKs1601_vl1hzbT{C%l=SjGQi|kn{tO1k}|b zPRa#WOP^;xY+px*aWK24Q(QjVZXTYuTK9UMYq%-)kfHU>In%LcVx~`ylgW!Qht17K zQp9FvjsbT7k*MgYnWz{#=2|%6kyJ|++o4*_L?u~cD0Mbzbt%|%)g@VD-vE)-!s{{t zzndL%{-4LVo~zER*U2Vy)ROPxYxnC|Golh8NXiDlr?R&@>Up8B#*k6Q zy>-HeBn(_*sbTF&Zt~OT(Lk;&DpzQQ4H7^ z%rW$7Hkg%ZsbOB$RwTa?sx6~o>-S=ZEK;CPnO3RbVBv5(Y8~P1>`rKQdn=3KbTRYC zeh+Ez(wb}bBImPRZ#WFFO0m;nE~_4OX~`q?mL8VnrQX|M?hYK`>^)$P0sQiMo}Wo! zijsP&j=DBf8Ai?YP#RW#>W(7ZwZu;Oox(JeVtI%y=N&?Cj@8CTSI(YMKAHU`ZtOsv zjTens=8)2hC;Pma z$`2**8D!kNNsS^ztaL{&!~T6V0x1b=hb3_I#ChcUgouHSf(o^RVt-E>hU|mabVC{iLTr| zS-u|f8l5{^Q0?+BiVk;Xg5I!R)PkQ9ksd#tI)KyM?tY~5>y|SmFYH7`p0nM8T=zCV z5?3Gh<&ivaZ})5F;#T{+Wt~6h&yPyBrY#r$;FX}@CKi>tf$El(`hmvbr@W47&Q1d7 z*lvlIL<>%SWRs_46OH(aAbet-0BPy>xzdGZB5UO$DyBLNkG5)W?KC_nXyt%GFK*!O zUy-c0-w1OH?;0VMfGx9K!Py)-D{uXW6Ck(07;zkkKo8M+xQ5M3jn7HuPYd6z&SitV zYIib8^CMA(yPq%+5G3C~DL}q{LT{vchn3^cF(#}EGGayfI7u*y`m8D{33D;T6qZG| z>q3pS2YbkhegY)+dV(Cja$SF^`9t+{5o;7@YhY*02j6vF_2{bJBJmg2a52|?kd7c zixlc>M@L&uw=6Mc4gT5+`WV8;H2BjH2S2xD%4h? z`CLPn*!83&eI(Iv8%h^vu5%5wWi3)xPZ#9JVcYFd)uSappgt+X_EupQrPrin7p1Za3EneC zcCNJ(!Aip5`L%HIo9BaAr4cqC#AuN|MRW?OGs9om4uZfri}z|%X`{QC#%Khm-x^S3 zF}HN##%jq-X#2l7d&`(e!!$~}v2L8k9U7O$-D%w2-QC@xad&rjcXxM}!ri5Chh=6r z+1+n;CX+9DtA1Bf$@84|zRx+=60YgYeOsFf&aNSqQ^V)syo0?|fTgTe#(NYbpMU`?KWSQp#q!1~Bw*G5n=Is(cXH_dd<+;~fh0l3Uc#(^ zVgHl4y>rD<4zO-zv7{@3Fr}G;Yy`TwMrkr&*cgZ2=h+T7ZqE(VzHmeu6i%kP^LypU z117mI5w2OHM0PtwgU)l~ki7hLqQ15y27W7@yLIJx$O$E_avUDpW@k}+6gzS_`aC9Q zzSiVA<%+MaRA0>niQmB%tYR^!JD9M2%BO#1^k&WZ_8VM2&Ri>@$k9piCT19&nS=)s2=4YkP#e+b2c+#XE#FIhg2v# z*bv=2M)r@*@OJC-7q#!(w<6I0G=t{;um5WiJu9pKtEl~d4h$-lJ!}cm#&u(gq(&;66E{(>a`awChOiH`drRXCTPK5pC|-M-P;4pKIl*SIQQwg{c*x2Qg& z9{!8oOb$pNW|hg2Da{!XWgzh>H~eGibV087D#N1{N{oEQj*NZFrR%nH`qAsL!|@|9 z{+qeoTw|HN9N-GQ<2nT!ah*&r85`a+%!cP;2zs4%hq2K0Tej1lgX>Hr64yX;yF}=Y zUf21~I8jwl*<+7S)e9>GIGNAp;x^ZT_ee9vrFlu!vx~~OR2{ZXPrkJ$qRuXC^z}tD zdsDK(>(dR}mUkfSs}|>{JKx*WB~%yAHqH+%IG*vI1gB>8qFlwy8a>wi4UbMIZ!_Q$-bGsCghSPdI1!_1EX>fd$bqZ=iOWpuT;*nh|3 zmb#|BCCZOAmEaLss!PkDHCP(p_jcqmmzndFm#krG{@y!jsSSIBX=niV5N%MqBJ1v$ zbye3$mbo_r&=f{6OE-Fxr$*~n;fJyYd zUuVQdJ|4i0Nw;W;6(%InCvbdsIb%^82f|U<$D;Q|mVNz>Nwdl4g_5s6;^gLdrMY+a zFB|J$XX;8L)G?vV(n_}UDEbBMdZzvx1pT>&(*0)ogaM{}`czEWke`t9b}bqWlFACG zlpsN;k1O2X=0ZXCJgRNA*cT8O=8o+{|Pa$-HWATGJF$q!&qF9n~B^tXB+D=dQ30WUCwF~{|faMcm zGEC*j{RcRX4J;v3)|dbrcOW$v(astkSNN4}gKlBKmAfs< zJ5rPzko(SKW=bZ?!IF762vT7uTa|sSwXCks8IcFq7CLc5zv9<^9kURyYAO(`FeIKwHG+Fseu)MX1E|nt6Gd zDWP0ylKW&oDM->aQVySG8@nNfx`tb5KD?(7sJ`|q4WD0S+0)nN_METUcVJJGD9H`( zhkh~kkd5T10PhzuRS~r1P|n@lWX%b4LE2I3NCmg7)h&luqgt`a$fs}q36FUUsAvUnyKZIzq?886JX*lSX7no@c^FVAOET`}%^|2|< zxP@J8GZ@$f6FDWFxcP0~kyVBJ-AE=6Ni&Ey6e!RcT8E8CA&dL~d-sVefRI-+bBkQd|B;<`ZX zV)xYy8`i*X5k&Y*>;n4m7hB>NYJZn|I3PK}jumtzM5BMqE4|FImeL|GygSJ2DBfxG z`4n>{BI4X7UwME|-4Jfmd$={vgGi2g2p7s@e9L}(9S_k*ZoObQY0 z<->o2vKz7xPFfJ9sOIXXNxo6%A)QUthkDd{NzE9lkk246I{+|d~+TIonOjs8H zlwJfw!rO@|$)TiR+wtl-)z3G~f?t5~E;^%fCW)s>_M<*l<}d8VF^wZX%pXn;7E zwYYF9u@|ZhHtmON`Z{8N-vwo)a7Ji}|((PGlX37x>nBho}F&4`AQ zEE-+t*tfi!(s^g(x?{HhOy%&q`6DS6PQMSq0SeAe#jtQFAXr&10CDs%Dq*a!Zs2HS z)87`i%hpdPm5L34K`E!%Ow_2w$nQA4N+zPnyU}DW)Kh02N<7JG zIn=#8js29g4H_eb6)ztJXJqL)ddj5s0NlAzz{+pcDQ}_r9i<9`>K)|=4tGFxtZp}- z?>ibo&DIXz0~(%@PmlM52#&tbklX`$hVc;)`W0K-=xP`C^~a|1)sEH!ZHCFG-aNnu zz~#)Rd4QK-zTR{19@wV`w+)GBY%L?P7*-O3y69sp0D9VPz^ z3wh4uHF}9yXL8(oXGieLf)!|qNef?Y`(VJzLvV-N=hd>Drp75G&GYR$xqKdD9W|5`2nYx4D9=Yan}J8LSTepnycnUFS{iE&y5GX*w{r%94Z-Topu5fCS( z?k)JEE-wJI<7|}*np)?~6iEx?8W_pn_7C!g-M1Yd;M61 znbPh#Q&f(v6lyn-ZY1KFKdp8d6=2!cqIksXYE^Fu7 zC%B=e5?naw8E1)T*k~l%>izBf)||b6zF)&;UW^*;MQJT3N*L}@j#V`Fi;+zVIu0@H zBue||sHtQVQ_t|=)XV3^%wD$yC6(QJNTfS=$5)&wS6?Jq6;4*fZ>kCw4?ZvVwp0@Q z7PbqK)|d7xU9lJ{8P!{5|0Uz`N8r5!*UrR;tF%`JXTn}FgGsBQ@8TL{yr?Q(l0DUx z05$nQs-%&CF*ZIRVLGFpSXY`wXW?VXag}T3=Y=!;#BLmKx}=m`FRQLm`;DZNiju_Y zINLl+J=R%S+0n34=T;rm(Jus$XCgUiNX+;aEg_!KMhN>i^(tIjYC z1_w{mV36%LtPW#J2|R00ubPlTUy_oB;ON0r_MqGvM)xGJSh8KJnFkNsOt~na?9Z!Q zgDh%$31?zGFOg1RhoKq9fQ4rK%Y-U~e{z=kL}Fr7hbFey_e zAhYL2kCG`15N^FGF?D3z4P}138n$3l3&L!D$+?+hdn>q*4g_>Lh!n93J7#5aTPNu$}R51B0 zme5jUl(rl2F>F~OG_3*d_)tZ8XuC=w;F>3*k#5^f*ZGCuf)=dHip$2Xi(Cr#c^(yo zP-(OjCn_iy7f;Xn(s|J;09*+0?|>y+=l0ZbLsy}>ruaBi(oV;h@A|4V7Hok^ZyXhS ztOY*~=B6kTB~+BJiu%&u6+2l=YNN9UzTg!krU%EuEjzpIRG#0}uh_)R3HNL>w;CAwKz4x!y&s26pZi@$uU%6(8i=nu5OoJTq+r@ksDhR<})Sq!ou zjNh{rAx+H#p4 znqLImXV7n=37B^GqIiSu=ruP_9hhJJy=S##@;_b_N=%_z(js#R93%vIXt2h?kX3hj zLwdb@aIbHl#n}piOm8Fw+@ksICcJli9C?4u_%qj%omELma{(?z*!mrtJTKC`{ z_iteAPX`iwShv7D?rG!n^}GI**(K2S4Yu{m7vu8F-jREQj^1G&^BLN6MGn5EHShE% zN<)w_%Tf?(bqpCfcEIaHx|0&#+UuA)XH&802!yiBb>B)6br#C~OP zG8@jiVAyFyS0s}a@%v$1j0#gW|I_!bz$%`)0g(?bjfrZNN#1-qEVoR4M=bZ6_L}a} z8s1-2={=}ehw84@L4ki}`+{dQ*z8^8W#Hu$TwztLt5P-XP>lL)#QQEtR2#u9l-HZD zP&P&I4{&5x(W@|rSG|VAyT(%CfMA3EP<1;@NxOrXKN?D1|D@Z7bL8MPL5=Et{B2u| z5YCc3IDkCjio*{zR~UqGSHatUWj?oMj(~FqahEao|vfUpBg2f{r zac6WWLwG?Ye7Y(>dh8b~9;C_aYYw+TL^Je&HvF3i88UgI=g+t1C5h`$LggM=&PalZ zG?4D1;4Qj1mC^exr2cZlyDQ9{GeaOg#_QL2HcA$CL=nn33Ld(gG|?Fq;hMJKQcyId zVWS|albzgQu@MLWyMYAryfk$pKdgqGI#O{-aS8c%Hkg~H4a1wz04hOM9a?ia0Q+u9 z-U(ozG^~NYv(=>d1@eN*wn*w=(rFS<{)|C2t@4%b7FmyxWZUJ=FP^PeQ( zv2UW6YhQ&TMTq}NQt|!Ql1jwL#>&Xi-pt@%mDE29<-S}y-but210)>@$C8*d-W)!iV+z32?W?=iNM(asUi*EB;$k_!Z3V!S+j z6VVi!kNv@}xK=3-d*6{fS^7;_pDmN756vGx0-mlHJC4dbJGn0#w}%O>uXhwMB^azF zOeYv6R2ai2#?Fdre_|*9k`gPyXN>Hq#Cpg}qoBhNj&tw#5j7oEGnSV+#oYK{sAW)@ zVM>~gM|f^DnYfc&EFL}!Ak8JH!af%!NH<*SNSlZ$ zWVbdKR3vF@aE{RSP$G*dx0@FiS;#1>tP3$Vt{>ouQ@U8(6cwLdOUj~JxpR*dGd9Mg zZoFnV`#C!;b_|0Ht6wTSHX&?0XcdP!@ztM;g%rS@6q_`2yEH|tng&=Dx(;X)oyj*+ zckt3*C%2kIjsLk)-4vi)8AENTsG(!>dLD@q7*N0z?>R5YOdfhbnp=`vo99*)GoG4+ z%gUPKG)aX)!AIJ3wZl(y#ACU18|~HR78a>=G^%X41_9c&;68ZLlQxHrszluCYy-ZNJ>);ljYqaeMca@{?27yBCL%a3u{EpV2w5aLQs7RMpeuI z&UcSiz5Yj9iX=ThDuCs*@yWt@^{cx@bn*Gx!Mp^v+_eaItnYx^LzfMaxa{!4OkE!7 zgo~U76&H!edt2VhZG|+F2dkbN={x^trbvz<_0X-k?zhn?L&iZKys4sFzTfn9nL9TtD zQWj^}{z&_?Nz}8{R*C#1xUMZ1LH890WjO!i9jy)uA>4Q5ESlMqPgVlM{00QarQOkR zk6N9fF`TA}ay?n)+bFj+#r~jEi?$Yk3TAPZ>yG>rIsi4o6g9uh6hD&Y6Z?jM@W$EccxsE=<^W0B=} zaNqH`g|%WHB{{EBx4VMO+=OJj1*zp=zMJmea@~Ww%>xzF;7+s}yz9f8!#;2bZ+{BpE#{>QHK z|K8D}_^;=0rjnK=wi4P0>4yYq)K~kO-MGyP5~s9=4Mkx=AdA^~!uMvV=fWOqXNE2( zsdG$5ykNASLc6i(+BvA8%CDg6X1VG)#O;aSe8G{bL-3)9UHNu>e>BLnt3y3q-qYEw z2Y@DVJ+5;eWn6LcK2C`6zP(y~^8mU&%@l21Y(03rR77b@3ey!5g_yOb&e|~=6Qx-6 zd$E=7d2{9Dqark2Z)ET9P45sa_;4IvCj)n?&)R{q8dsmijP1J|uvDT_3NPd1l{0qG z5Ut#}JdZjupX-lVzguB zAz$;xS*?GmOiLYU3JAKK_B%+b{t)9(4Q@vv=wuZ>kTYC)mb-u;W#Vqy9<%m#;B*3& z+AdF7`{z_ct?aIt%M=Tgbqwg^rrr#;D>{GMzt94q;h;;)X!W*E2O}AQ!4TO|yZuD)k@w*)pmukj9*wKoGgf}Vu2p5`sd?U9O67`{!;^q$$fFRg`WuTV6H3(2r#Ah2=mUeK(HSviAy=RL zxiT|<`R32G3u~x(RL2S#0P`?PzR;qZ#j5e6z)&3GAkF!FOq+V(p6Ghmp5)3T_ z&STBy>Z|Q+xLWj=owyk@TUd11Tgip2uSzFpJU2(`r1WHT^i;I`NCf_}t*!x@irvWC zDoHz`7DEL;hr#lKWf;|HE&G)AR$qFeg>ug93N3gSPeF$J4{XgvvI23Dt)QwhR6Tp^ z;%Kacy4>8varuKq#K>(OwgSb$R;=FxFK4a3X!;H zk`SMY89wu0f|`JCDLN|z-pRg|=37A;wJKi7Ybf75V(eoq%I!O*9k_hyw7_Z?jKF1R zh!T!F%nvWw6GtvxkT(3 zQNf&(cmwCXONt#%5L(cdaA`l}UXyzw zK&0hC9M9lgn}ejh@>@$vWqedQ@FA`ymZfd2c%Lx7!-nv!}q~G#NWGZ;|ZSz=4{&oRHfpQ)WU8P{{3LxZe@umhkFTQ2Z+?#;E z<7faOhIf*2{^~IQ!~jCwJ%bNj)7@Fgg2NGYq>hHM{p493z?# zqg=DnrVbtRxjo&tl%%T@7RP1-6cbOE)VR;Me41o`lh_(rQY^|JIK;J}3_ zdH3G%#`lc08y2R?^Gu;7aQcq(cHX_~KkKe1P`8#Z$pj@AsNCIV%Kpju;qwAg4Fb{w z5NR2OTuWc?-Tv*8iqC*+duey!u+`uDPkV)e2Z$@em%SqH>+`>Z_y7MRe*d!`@?WLJ zKfo#2DqrA~q=ux9t_AW?q`7r0Dh;!IO`K+Hq~SUeGI7+kdupc~`m=jsfcmPEi%JwS z4YiA@SuQJ^Vc!H;c zfe@bb0l)B|=GsL7H-$gH5Vhb@9bg}{Gxc__KEm-XLM!dnbq5xblgpUPte_I`=$u}R zGx1cJ7|YH4uCUSJPtK4s+oM05b~%0Vs2q5Mt{AAlsK{wMuA~9VT;n4+z{iyv&u#xl zT*&ASoh6T2yscq`lumTP4)Wc&zZav5KKfLQ9I1F1GH}raq{y8_{;9Qct9SR2aAYr} z;E-Y5;t;{hN#h2Mogl18&Tw%O$Ph=vecA3lUZft zFnK1UgO0yF1X9cA)*y{m7kh@q(5a;cb-%i*}Q9 zQ3#!$}!??1LWLS?Bj5Krjm4O4u0;v6b3BQ33s-9XY&{G0Kztk zEQRkn8NaJcyi}8D8oL+Us(&R*T84`iR1iYt*Gc`fmmPy4)Y!ph@`ppadqBQWyER!nWTXAseV#04jE45^cUoqX& zSBs4dndoCAVadqiORpXEnYh`2x%00?DDr2l9>RWd`^kQ6<5f+)j7)i^Ax4y#qQ_6c zY}y;d?bh(_iivU4{j+UllvO!8P3Opt1|Ce-_iow8eQZDdIG1V+ccHQ3x;t%sf&=!7hR=B@9;XU6K&Z3L)PZq)VLI z;EtVbs?kz_x;Uw!W<&21Wv$RmC48^p5s_rXYW-;C3HEdZdIqN*{2SmTH z5R-{un0inY=DIy8O-o`jilk|LW=cozHo)K(qz+RzYuLF_$aB3O^51s3QcsVNo z1lHc;t!w+M670OZhIN0%!=J0dfIj*{{g2kbvgiXLyOu-v$(m_NXA$ z0Te#^C7#KI0N;D@9a@s z{w6icLR)8fS5C8!9LIpDL2BE0d`Ay95>zs4(v#@U(4cXegl}ZpHz@I2)J3sneUXWM z)rzQig)fv)_(c_U9p4RR-70hjg2W-J?I6xtIr)~=lrt)rz@6PV%N*?^P}h^lZwWm* zGI!|P-t+_sKQLcpj%=GMx?{1s_!(46!K>ZG^}{Vp!VN?U@I3z}>mt8P0+CQ`#~RZzLAr;}$ukR^uGc~#k=1?6j;V87-cg;cVQVH4LYAo%2Ie~tTZA4G zhSx4FVBL>Qdd1=8^Mk0v#q2b`Sk@C1sDl55|ip{2b3drfa zd8+a*Zl4s5ygyH`WgL~lxK<0VneFCd%m#^%o+|SB4k3iLl%uY01uKh9d>T6UoqjVL zB(O`fmp)SGSeXI#XnZI%5W8ndn%dWXk&qJ#`-Pi68X65#%A8j&25azA*YFy zDc-Ki`b@NTz<0=*54oIi!-ctX$tPzKw$Wt^+24sv*e9Q3%B`FI1A}fdQDp6vHx0l3Ryc@8QFhzV;lZkBXOmwo1>x%?uWLqTl}cR-#?&W zMc4_FEQEd_{G#ckzTj~`#d3>Q#>OXz+%6{4froGqZ8L%5XRBpam6er+rkW+xO~eJI z6y_Qzl}E1UcIH z^Z>tnKE<7nUuD;S!+s3z=Kk_zOPU7sQ}Q4RcI8kET!V7?i70u>Q}K|XWux_*3;+S3 zp77DA+jgGXusX8WgP;l9Q1o0BhCGG45_|!`hA`S6wV=}_t}G#oPvSp~T&uoK@0IhP z!RWIQBt?h%lMMh1!q6d3#HMFML!qYM8?o5^LH zev?~DtBQ#t)1@fR!%+7@-ztl5RT z^=zyQzWex_rAp_6GIun4*+>lHL2MohCcL0IrXzLUQNL(`pv8 zc250GRh;3lIh#|K6u^;8Q}&s#9jW?dW5dbKV@mdN$HQpMQAEIs8K!%d8$wU+8b{fc zyPHngRk*tb%@Sn7IVV+95VjhQdo zlwv}q5_J!2nXun&6kQyPe4k=82Y7>Z21uo6H=yS2$v4rND+Du!=&`)bN>-REOYB7X z%&d!W@G>Tns2MSt6|AS?s<7>!k9tpF+G%K`R=&^EHp@zE>`xF)|1#7N9jwascVJBT^Q!^t2FJ#&<8GH#MD3S=#@d{o z%*jQN-*;j1ggkSNmpV{S&%)77HFL$RE@7+OX?Jys`^71ZrQOd5XF^w@Cpa;suQ+&y zH3SR_yE4NV-oV-%U~g)}#QGa_wU-fuACe32_>rUrf*J4C-82}1oz#-fIY~TC2$uSr z5AsQN)IxFnLte7JrC11~rl_7)@s&$M#yaqg>S+ zN2*(t4F_sCI58c%E8%jI0m2P1!pVcICgGLnV@x|J7IDVtFb2&isD0_XxcNX!M&>2i zNeYvo{Q+^{;P9OUr{n6S>pyhV zuO5Zu>3Sh(VY!JU3|I(}TGih96+&YP6iUicTF6q8X97wZ)HD9m6-?+BP6;xXDB4>R zXWa4PI#w;0pat1q!?}1TGg=ei+uyYG8Pmi*xSWn-P%_=>E35Ew1-3 zcCtmhvT=^#H$Uz%;q|z2g}}ImJkHX;;USFYWc2WlsRdrF_&A_&?GAU`m#*o{Y0(BvD9-B)&;L!qsPm%_*x+p=R zy?Qcp*_n_L5EvaReE|3?>HCeE)fW5Y#*XtKK|ZMbesAGad`-lRklK-zI)xZ7RWLBs z9HY1HWDtnKcw`6Fxj-_7p+zor03*faF$cw)CjDfUxTmx?ZP1Is->I~hxJRV=afqRO z7Y6vj!5wLoxJOn~=MHPsnP_B@BC2F$F}+)csL35>ag!pAC;a5HSZ%oLhWd4X*?OXd zhgQJSZo3QbefQR|V^E+|VI-Av=S!GpQ6r6E+#w3oOuU=(#`0*VN*T@czHGrY`0GJ> zDe57r*z&DXsVk@lI*mQTLT8F?gqFyea-3a#h#l*)0M+w_C@I!C>f!m>>bE)iO_1FN zxpEzrYS4*!2`Zx+oY8$(j15NldWFt4VKs7X*9VR=LO$0V57V{v(?Ntwl0<9uToB^` z??e}C9}C?W4-;vn#&m|7RE6DPq>ORR2p?ieQ^cT^S@`XU5yN>ZiOKT%T4Rb z0AU8~m3T$WuMX87VcI_-e^`t8LYyt<9Z3w@B(i^X_T{BAz1uKp6~rqnC^vAEp*Xs) zzHR6yHErqO-N*p0rfa+PoANc=E(DMTP!A4V9%S^K6kgC9Ubt5uB?7L06FxKd1F;F; ztVnJ3E}$DCxM?5~gPt`R8MH~=4)+MFKpFjK^xC&{RnkM> z17L+}6cE(DR&m_9H^g1$pb3M7oZ0NsOudXBDqedf<&er=OZEgbm8OtQLR^m2<1%)y z^EehayPA>9PwV6D^PkhqZbmir%`fL^Fxr0-mHhv;s8sx-tyr5lS?c{iD8z{>8xF`y zD4$m8(JVz`6cFlyC?cY1ez|^$VYK8?yvn{QKKva~QKF8sq@ zm}4~36jo*4I$x$X_udz5U$XOyOz9&)E{S)y8Qsc3%;kHXXOgDZpLy}9vd*$!zyLkW zOFQUmMao6y${tq3=@aNYv;MhZ@xY2p$uhP0w5EnidhkSFU}xT4D~zyQ?{&k)e%xtZ z8TGN)Bn=9NN?lGHOmLio@T^mW<*3p2sF+`+=BQ$(V&Y4Q-wg0~S{J$Y@kQ;^&?U}d zT0P9D-7{OMMq7SclS2cNXTHG!%H2A%CLdjKd%pcq zxx_HqSFBy&{xP5G29oSNF8_oKHWvMHiT5OUx?DnXav*c+D8f38+si8$Z@%xiF9XAU z;Lo&-Wys>PJh|G`TI_CtRk0FTvBxOtfF}k!6}Vo29iH3He1}CgGQ=ViceWl%&Cei` zpx_$Th!l(mJ)57-7~yP4LlU-qAqLfcn^F}C6s@Ul#>Y~2=t3P;A||Yl)5+r?eDU$Fr0w2jJ!T?7tx`aMQ7H_rH@drUF7|eH~wnmE3jT_G|pSu!nxB@Z_Rx z$aUQS#YrWaYIEwuo&hgH=xcRdHz5b7?3q%Q9-am6?Wo+3Yv@~&$Ia&Zs0yB=cD2FH zJJy@3-sc1Fu74lT@w%9|`5Hnw^43YqM0pGnO*DCk8ZP+#nl?N=@T5A}eU}E9$r*o} zhB!Grsmwej-Zf<#gvjVZ$`#oDl?Ua~iw=%Wc(g9pl!=W~EtM13x8j8lgGqDct#+w3 zmoZwzUI=@A<c}nJr{i3^8IsSxkFq9@f_0DRFiN19$x3|Mnu0V)gc!i|GuxM z+0TPbWSi`m3asB=p3n<4HH0>wWOheGn0OXZRhWrSw>-s0YcR>Eq0;6WF@Rl~al(XR zGG@$y_zVKaKTOZ?8t3qukaLR*O}DS-?3~mutpBGD96A>z&CEQ3*dT`$B}8z@@B2>JA}& zN5W2_6Bg~%=tWm#{()O%Apu%-wl0aO&3^8dfxGSrM)z!!JCN_!h*?9!T&*&(!>G(K{|-c)aA3*8P*s8%M)l&S@80#Uhq!nCS9%)T*k5ol_u| z%7#%Mi_9{-O%c3Vr$qrSIis`2W?rAorFlbAs}aK^b*cu5! zIHAtj1ZaeM6;bN5zDIg!IXd+mtm@t^BhktIm9|VNDO^CjJbFYaPkbepINfM4OnvsD z)@a?`d>QXlUQvkl=CVO~Rt*!i1 z{_l58a{u+!_`l#||L4B%->sb{m8BezMSgk_RW=xt^!Sc=vVoij{4z|Bd}64L0DI8? zDcT1?L7qSF${ZUsciE==`^V)oNauy5zp)7USKv zP`9A{iaR5w;g~7q%(54y%z6Zjh`=0D4EUr1T1qP$p@1!5BB>dCB4{!zK2Wyox@ay0 zt8P%1210M+uzcMLat)4)7O2rQoIeE7PO2eCuCf{n>)B3~EqEcDur?`LMNuHC=r^+` zRXknRqw7s(*olZ}UvWxD%+>3KHBfGzU=P;0mu6PlKq=2VoFP zTkcEi3Gr25-%D4=T~u7IVfRj_%h~Smchxv_+_tH`X!O190^F*P;+%#0YHAqA3-e(k z*(tmHj{c1e8lU*8%FHQtL;(3^+Btn-%ZZkW=6 z!uWt66bCx(XT8j4_yT-;?yvB`u05_*m1dhPOMzNCs>?`hSjjmBVoe(QC`=s z60VPTCr24e5l<1Ot0VNxsaHNu$H6>BbV+L!l^yoPBBm+AYpyr8$z zv9`1}K9UynP09+PplhE^5oFf+mcTr9yS0H#CUJ7cbwIxlSkP{k6>0xnl&b#OY0YoG z29yTk+>lMLK3gaB-?%4G-9nvpma`da#~L<<;bk$wZGrg~?ls?!eQY9G*LE+PVN=hQ z_3qK3`co~lA1=oXc7y|2nV~;=9_k7_5|_=PpQsO`>4dKkUvqiBn^MEeb4un1GqH#k z*(1j*(DrbIyz}>C@Z>EKLP^GV_z5hGJ4xAL;9HcSFkle;TIBT0U*!liV2f%Y#UzO& zR3j`sjB5>*dUM71Mub{ldLq&)$MZ(Y-d5n};CpX4luL_W;4JjQnWx$dC{isW-XoTR zF7$u;HOWBjU0^2dH0jPn%F};@wYd;b%fqjLJY=gLKMaJJvWzo>i z9kRF1_ZKAb28>{|Mjnk+6SZ>1(of0E&HJ*)r>GCl*wYy7>*#LP3jSEC799ivJ^bJA zma`RjAGvs|=ppEtM^wbLnNF;#ecix0;@H!8rAo7Vh_B}*2#ai`ZQ}Bqzqb`P1)XHA zreWkx_7t)0b+Wam#TT3mJ&Mdtt5#>D=Gs|+bgaOjhc&5_qP(OX_ac4VmyQ)HLp+?8* zGLh2;sre+d;6J%LN=S1-4Zc7eXyj#Ix;u2AF&W*zdO>`}NurJ2>&v z*LNMSoi37#6E7X;Iz2EGpM>$W^lq`E5TrT}+rRNVm2z0B59H0=`Nt0wf_U&w(0_`6 zm%YGp>&V{s1*FlKSGjyP0r@}1)-ZiJI#W`Y?EA^|2VFJCj~cn41i{Pdg_}~8VZf0j zxT~OCZ_P>5mnNVjVzbyNZ(T~|^ zTgR9odH~b9;20Z;fX|b;XfHN7Vmc81m`rs+RQ%m|Pd$k&przQ$Y9ynKEJD&%(Hq{Z zElB}J*gE^*kD9a$^!eM&E~wPCzHrcU0!tiY(c+0BhZ38Vbdw0j3#RIC*#%q_t)ViY|>#F$JfdJB7j8-%!=c)0}KiQFgJ=?W5^zoY~Fj7o(`UCaQ3ecH{($ zqp6HnR9;p~6z#r2?U}MigtTa}l|$-_G0M!p3K)rxY5bw}KFF zN#Q(qdpq~j0NQ!)ate;|tqWM@iPAOWIe?>uEW9b@W0x==(TEuObe>p@Z!ot>x<4Qp z_16z{-j;%$^p*)|-6BU#{Bvjyuok8W4CQMZGL#eLYh3N8op$K1kSl5ovndKO zR9NO0P!u=^KZwt5Q{tI=zR)a-w2~Vk5qfjUvf6b9iina;XYXgRLBpp?;*|n&+$5c3 zDPBhN1M?rOA!)I@u{Y+^8piJCQ~*vkf*Lm)6h5G+HeK9eH;&4`qcw+QjkU_ZnBlS! zR|Gog+YBMXa6Rz5)z!z?hq{nyn3IiJu!4tT9^oV9;1J{nhu*#oPqls+nreL)oLtBz zTbh2uNn<_R}*9;WIq%im9z}PLZ^B%(U@qTibD!R%?Wf2xTvQifKx^CJUNH z8D3iJeZ!ge z&ZjvL(b(8XeZ2R#Yhuh0m!iDt%u#2pIfrh^?_4dlqx27KuWWxN@HWKnzS}iW^o;vT zs7?PA?cc;R$l3y{@&!G*FL92DxB{%;wJ~CZPTY_CJ}+}+v3~<`YJuT74Hr!~1ojk zsktcBS#DW7>WT%7mfJXLP3VuaKHKI-r#y7T9%jOr=WI6Yv8!Vpx_VKfW{4}7nBZXx z$xeAZC*k0e#QPZ;AF)xa$kof|hPCYjaEh4~MpHq-1cgy4Exlr9C;~7~+_5-$VtA(J zQ65E6O=j9;%r0_tdVZY53bqsUAOFd(fyIj9_%(&LdnSsn$k&KJOGWG&BE&v&i+#`s z_YBzCK7(c99&hRnzx_Mn0&2du;e&R_%2En{BlWw(HoDP>0n@rq z*}PxV@fFkYhSTB`n5z=NRFIA1pzul?Jp!~|Xgd~*dmD+nWXZb=yN8(icPD+2$vgbs z0sKX~`&uq3$hgf0C(Ak59TCH4lWoFg(2Vl*R}&L{w1(ty|8V8=%LxgG4}4b#jY&Sq zaNJg1k^n<&OIQ*=`Om%wG?; z2&*>YnYH2U9m~TPEs^Q4x>p*YFeiWaies0>+@_QChrV{?1{9ekD4uj&$77ls6o zixTlJb;Rrzt9V#_tv>XjIyxr=9c$NPM{(gB(SFTM6~C?A{qdvl6Mr;-U(xKDIdM_X z9^N-GD?8`o=Y`Umtl3-6IZ8+=`>!}Lytp+{zl*%T%cU$avn6qeR3&C^it;%WD~jB9 zq8HkdH#w>^PbsaLON}+$3hVM_YUqwx7ut-?~fe-qSsM z+VK^)bB0SyUh7%hocip8Z7yBGwW@L$5qY|{uM#rco9|w|?A|h^0k-<;LFjmjP@)ti zXsVFmX>q|DmOp2uyhkT4)hw?}dz+QwkNux=G_{6uGsHIP%(_)+A9C4iOrl3NWtyfi znWX_ExOuGwSZ5bXaw`)3b)`U)&Va*Y1#F@Wwl4TnJ}UAoGpL%Z2pMa__CJvVJtU|H4l-rjf>lMF4ML5ssovy5FhKNYnE}$LyjigyG3=% zBIH;i>XP;6H3_Y?sY|3w@Bia4$CoYS-*ch5v|Gx!(nQGhrz$8D}Wb0T0XDpGol5h73#`m%l z@VdF)5@rECIB|a2d7O2{z0G;NwfTO(9PW#6;xD@Tsfzt~m zBZAmReW5)*wmu3;##m^?D%ruzr1(+^lA6W z$SFrLNOaw?%X3G9)N3PKjHbll9`Z^wOM zS+KsYdvNeI(mY#dzO#fe(-E!P_BIaqN* zmST*90nG9>j+?orWx5qQ>$#V8L-2#>?x=GC$Sp}+#TeI`U<`}SibPfsv1(KiO>mP*E{qs3Q*6xp z0tSkL_Spg|8}xxXPIcO3+~hoZn5P!yM)XgkEZSu6J3xJ1-%FrQO&OY$(rA{IbD1!9 z2G@tlCHYTO9>G0{snRwuM$<9mhbrsCtma73%aVosH3u<`rLNvyzknbLSADguxZ9y< z`08-9FEu*eQ+LiG8uz6|ix8bW{q72`DG>+29oLlT4V7+uL$&y9jE$o8FdOc1zWWca z*5f5a^RmCPIy+mGOE09`>53R}doy2~w^-3taGo^NVT#wLfwLk#WOZ6^_+L8`D}VdW zTA8C0)gZPy$N)n)$?zNXxf>(3=O@C`Z^Rt#&s+z5l0Rvzx%O2Stwi(^s>@4ZcyxH| zS4|=O$?)Q=&i>qju`UQSzB4JKt+Y}l5@9e?ZAr>$nmGgwyE4?qnbHCtqU$n(K0ZP?R`sD-UWokFGfh^-ePFx2}VqPRM)C5l!n^T-=puyjqJ#kI}g zKIu}Q`w!1IM2+rPy7~#f!*3}g2tS7R zYtysydAn|gl21BAPJU%fM&GQJq;>5I^0@8;?rjHb=f$JAY^4qE&kAznO0Se^>8#4j zHd%wcL*ljyzh^8AdcnT)#lH(kUMS8DdzbEWil17lvtiZB0uFC%qyCuLfRd~YMYC1vG)MEJ+S+GggRegO&ug!*6n zSpTY={`W_g$(XqQe+1bls{SX{b64vOX9Hys)}TZcM7C>W6Cgml{T&%XDGDvhhsvJ5 z?mTMBZp#L2YV5AGK)$UnHiW77YZg;Xya*HXVY9oBzgOHW!-40C%vwl-(V6Uc%jxlb z>Sfbun)hRWThHeQLzsW02N?1cg*&bpnzeXavMY>s2R6?Q`2hYhQ?Hlra^ueER;@2x z(W5vT%^nWAw04I2H6GoFhMGN6GHS(6oj=3Y@e%d+Hy3-Es>WK#400xLgqhV-l-aD$ zl(-> zkq>a{$AY~=PKK2nbpNb7f8sFfL_L-xqs~tiXT8AwO*9-_(9R#5;&xRV$119c!B9(- znl|P3O_I8IqFmar$xM7UD3wdUozN+wQab#_nDxTSblrA)<(yxjIC-iyY8Go@9Nv&7 zazmTBI60oEH0lcJ6Tw-05uWHZ^{Z6nc7j;!1?;$?Fg=l}7NAnq#KoFRD`#-U{E$58 zoUEvCvRcK#mCpVg2EK0h)FWFdg(myH4X0yT#QALp3Hu7$RlUV1WEs@%dM2P)DoKb%gm!&iFt`Un4R0_zX+lD$xG! zkWg=J9y!_#f+vwwbbb>?hB+HS09^>q=Xy~OJmg{(QDj!uMVGogqCn{`ncuZU(EFUN zu`EVQx9>T4#WC!Z#d?7=WGf__vz$d3{Q0Ad3{6FL6^#+$fC`^W`hZzNo_hXLAjVF5 zKB-AN$t*fBSEFsQ*?|1`R3oC5FUqv7_L^%X!+5RCFjDNwHO=2At{)>;@dMm~cSSHi z@ipSnV9U^OlXS`F7IWA(&P#$jhTs|FLYgPY*#wst<;LaN2bGabf~o;TycTm9F@IC; zxrKdCBGhA(yiUS!`0iQczBB5?BpkQEg`?ID_fzB?3M8!L3(7wX@}Q*q8nkm#Mc99Y zXOubNkp}!vkuYs&0~8lQ(9ImY5&mODL%+X3%!&huPaWRxH3Iu==TtQpq8nxq1bo40 z0S}slcaYJo7GB&?a3aW6)_c((&6X$h0~fv;-aLP5Xk+gdWZ%NkOf+Ah9aP*R1s~kkQgZ+l1b&pLFU9de9MY;64L@jq& zkB%Z9U2Yy-VZ7=9ylSg~i0#W0rw)!>E_U5KtR@!8d#ES*&;cDH2YC{FWH-jYr1&-@ z$=7V8f04p24dZjNGfupoSw*jWui=__MW4q+;C_0uioDwk}c+TK@jYxu*^#qOMAb~t5YYQ1XjR}1cQqK07cQ1DEl#6CZokp`Rf`Z;x zCvq;ioPne@C?e*Vf%lm~`nB)_-~9InlC{+^pJneW?|E%i&9>_R-c|Iy8?I#b3DwOL zE=u-5DY$F)2}IwskGb&Yg8%u=pW=3bB`zW}J(1V-*lt&mqCmE%|IliB#`)L1f1k3@ z|K*hZ*QnQj|CIf2j6q7WcJl&=nY0$Lv@=R+Leeihr06t(17LItKcJyO3;+DcSUMxz z9NTJqB<|7M??KoRCp1N8XPhw{^;z?{nvC3f9iFz^2HpYQkls-PX~wKr7CYuiE_Bwz zbbehWF#3a9Voh@&Sp91>Gh=_f$-XgL^lj{gu?}h@*D1JBuoo8q>q@T6sky77 zm74slLV4l7z_fyid&em+U1fSYcbC%JrQ*Z_K#;@E=+OaBXLh#x6(k0&+a*?ok#QDc z(zHI1fIXVnvwbM6x4hO8`x$wZ`dIdy|K3%Fe&}uSg@lku(OIavSAbwMJGX{xLwoY0 z5;Z(UY&u7jhD;l+%`*%d&TTDlLJzJ8wk=8BC5&)wcgHC7QNfG&ItX@f3)CZ3@+@+~ zJM`KoG^Ur>#+0(Um7`DPq%6;RKD<3Y#9|h?*teZ>z~p`ZJw?s<`d~uW-Eow1Fg+i0 z%}pz&C3Sc2^{aVoj_=X-Jq+0#vmF+rLcpDkD}mk_2vQyUoQ{F;lBblbpc}|)wpPwA zc?v!MNa;Y1CAqW?I6by?ZbvOZ9eX1fZ<4Qac`9{+)euBCWHZ!Dwwkv^kn5HGq#cCa z7x*9d@+;US%*eN!$?6+J{_okQe_x0pY;K|K;9}tToe^!}^qpH_=;CZ)XZz38*uunZ z<)5Oc!_#E!P?Ew@$^w?$MbG&pxyXnVL@aCv5K789P&+%)W={2F>Q^!DzWQ%F&pTFn zZ+q!iT+z{_%v}4z_#Z#+^{!{Tdv4B;9^#|oTe^U+uuK@>AQh@Ko?cVq?d5R6gwE z-mU(;gd(cJ^}_|3FLW%d(c5fqZuC~DS{#3Z#(v2B`-$foKKP-P>n`y-0WuN*w^>(e zi?6U~06IitN~OZ9UsQpXphu)f7y^jUPjR3|vOjsl5X&aHe$n zEjw#&D0f^QKGlR<**n3zrZ5{{fyG27$*79cE;njR4e)!%WTtLPd_9I|)tpb>(ui-A z8LG&Xr&?iwgLBKI3k!@3j}H4;abixcNnb16*KPCE8Fs!3OOL^+-~RrH`SL?<*hx>Z z!f)_rTLl-ul)UNQ;VTctVmq&ZJqq7%$~c{nLya9r*%U2EuXMbhesrVwK6Jz&{&QIeN(iZKQtN0hkKe=B z9p;XiGaIMc#*oxHtJtC$um(tngEYO5YO8gidZ#QmEP^EnzGx5mEpi8l^6zChabRn` z!R_&_XK0d_QhokW1n_mnjP&5;*)G3)kU)Y^8y0S6_yU+-{GfB$n-TDtqie>@kmee8 z$|1!TaOOSPC?PG-qn5~s^&kciVB}RjL9TNlbF%rMnrzKr#S+LPRV1EWMijdEr@9pw z=+_GAY9gJzgmY^xV{U=1!HUbrSR*`6@a0__!RRmyV8JY>QNU*iq*40Vlq;eCXbg^F zV2Piv4#yM5-YVrOV`NsKbhrqGt(uqy%5+LtjpnYrhk>&0N&lXGRi+YcqcL**-%#6r{aQ7hBLi`quH5u%DNU$e7H-_FD)H@}>KEKZgsI6^(or zK8|yeV69UEW?*BOESppG?M7=WVJ!Q&`aAzhG?ioqE4kCnvZ$At~*m~q? zpjY9SOy=_mEc~eO{C#G7FVI*0-XxECop9wb#;Hyj)i2up_{LXxV6m*f86oAVeafAE zTb!$C2Tv8?W8zlAj$%S{X$U@skW&BfbIz=^6X5@WijgGcS~?l5 zH2wKwTDQafCMPL0hKkqYX8RdpAqxtm&|l%uptu}ms@h~K~1OeDN zqLBRe*@EL#}`EtV7I8?WmLEQevOeAoovfSbkZ8dd8WGMH zRKu%UNprNj2BHja1rS*aIn?~ta+A_?t@t2jFZcOiZlX2Jbk2=LO~Iuu-C9e;%qZmKnhAQ<1UA5YZu% zvN-QB3IF{j{z;{p##s3;jH zEX1CiUV#Ujv1XgtPM4OUucV!*Fxhj8I6Z~!zuvujMc_%B3ieJirA_&uxE#4K(PvLk40~?%)t?)~JG#g!) zSc4X&AUVt9)}Ot!anGY&SI~_e4IuNFkhV%$g8UVVtihf(>R9Rtdu)&Qryb^=v9(RBC{d(_^T5>1b&wHfXbZjJ{|lHc7u$EnIg zKZU0iw&$_DrRBeB`?9{Cm+l)~NjNis4^t%zvM8{@;F}|7JI8 zcsZjkVt&a!GOkXNk@$fw`4d!c%K9Va&XW8F5nRC#g2lqFt&E@i6M6oq6cJwMk1__^K#|)-y}$-^L)V@}|d;)6?vWTHcT5x$VyS)Cscmw33YYRqpMNt?jF~ zOI+QT>r+Oc@|&#i03V9y@ND{!cMfzt)f?8ETNi$w=ir!fyRzpbe7@d#pl!O|ix%O* zOrL~3?!6lw!Ivy|96$^)=`-IYRqtktIM1c3gC10wgUaBC(D#I)!xV<=-{JVLwTK91 z&$0MsdoAJkZ?&NOl)b{wr8S>5`fsTkyhP@1VVn7T4l;xJJ|fpC`tBQE`w)M=I*OfO z2ydOxDx7<~Yk(`S^m#I9V%*r~5C zSYBml<7H2wx%gx2Tx`^>-Wpz8Odl7UN$PnWIz4{Cxi4cD#jfTEz+G9cE+U^Q?QCV7 z7q)WR1eZ3Oq40YCRf;-?rdp3MhdbUM{t|k(_;<4_-xIW=>F5 zXo$e1$CV)UYQQ75HHOU;`AX_d;Uid?r^-@dEHKm66CM%z*Gjt7D_t#;r3$r3XP z5s}{*y>U7oy--rYMSPBdS>@_VT zZHso&pk-b#+_!|N1epc^@Bw_Y$Uq=AD#OfV1Bu#TU6{4@IL6yOJbC@{Sd{-Evwc{R z7C-Ma8V$>YcgE=JQC}Bjpq)o{mIb=g5CK;68J5)rbj0-r)C<#eEB&nH5Qc2&%4V(C z@m56=auB*Tcm0naqbfzT9#L6q14S2wWq}4qHo9yKJ1Yy|K{2P4{))_i>7vsr=ObwH z`9Kf|<-*QMl;H&bD&(2uK&TJo&mVTo2+J+9!W+5y&UvC&)9d?mh!8gCWRs=L%JJWC748kZo7=a$x)g z^pZSwC7;jULNf-`ET*JWd+d>J#Wr7LU>y4`&q|7v#hd7IcqKa;&BqBmVur8EjT(?| z-#T!LyEsoAa7P5c6X;Y=FYf9@^d^tP>pjo(CvwjN(OQGVU{Lmb#!;oIDHYq}wP=J% z5fz6Wcx?kYGp=Mb;iErpq<;~ngzfR$P(tjf{0S!U5u$BY>T1M56ouQJgT!=pky?IV@*jVAD+14 zm61)i!0On(r<}1;m7*#=>E^Qlm0h;O=?;6r<_?*aK`!~6INj8F?U`?fYf_dy3l;r} z!3#>7CiIAAlAhv`!r28{Ax)3ZAj>^qygwS0Q2~?A{?x)*N|V4g3yO3usQ#JLg^oWk z+#Y;MpSBx@pL!dML0-nUi+%LTRK>m%{;YLNKnh~R{-(LY6jkbpA>8sTc-K?=R+pfA zIQ)5|H)arCdt?zg;(KtPq)&CC0kc+#Vnvg^YG6bQ{57>LVUr{-(*gK9_`}D%&eP5*C=dl=r|v4z3}E`E{doX*|w#~ zAwN^TP4OTf8`v=;&Ni}dc;@56MfNhstD<+`@>CRi@fS05^?(1rv;T4h#61zzkZL zpoTzqO~Q@vY<^ylIF*A%GbLRjP1X=E0faz+z*J!hpstNMX$cO+FczvFL@UqPhs1;|I8%+`Ge=d?l8<3duv!wGr@?WIO}jg0^-*~8z6ZmNy-w! zwGP!*rS>&>k4a0nN6FdYuy9CATP~fHLnMptoM=u1zP+LNd@idmv96)e9VL4h9YdD? z#Op#H+S)HzXI#NlBK*oOq-xsuhW(MX)p3>Bu`YS?lpxc20L zV(J`FKDe%f4OooC?XPQ7q&cn9Y)Jc4mN;#Y!RlWq8Wg;CCQ>iKI7^8SZtf4~nnKclNSYx#67L>QOic7r0Se@457Q9m!Qu70q%aNXn$RDu@ zvUX{|STBmlviJoS3)HShv;(Mm04DG?LS|!JW`}yNvk`P#3P3DN;R*G6N0Kt=D8*h7mmwiJaFFgA*cTB7PZ6&vJb2ox&e3(Jaw|!EO5qmw!ak zk1J%8Pfl;nT5{wc9j;1uvZr5*YqYxCzQgPDx)~Y(utKA6tzhva%I$ZH7q8*1?O~3M z2KUG5Xn?o|pZ0IANnk%@*fMSI629&p@A?%J`a*p?`j&xP%)$IQqx+@pGu|JEbLka??4o$LTdt}SqfcW4PhJ;Lq0hdTL{m1uvsAT%sw*JJaf%(5ei~W zwSFWc^H!# z`Vs9p8o|pOA|>}c6lrUV9<-|svEl^`W+!g>jy}HQ-)kQj*{wEN#BQ95IF9&fLzJER z7^h|O&>4Q@N>DTu+Yu>PRlFzD`9iX{GgMHl6rkqnIT*z3)iUBAjrIK^ZL^uUYWyL0 z1OgC#ZR45v83#D3ZWi{<$`BG>=2<|aTlW-S#VLfwZH0)yRi!bipKv&@|1%v-_E4`h zwL(=RR5}1Kp`%kQvoB@ZraOXOI1Jb9_2bl?sM5B!6>}2SWu)~fPhkgypPa9X4nUgX z&MJvDL?Y3eiBMxGh9ZfYBF)Oqi#anR_)_O_ak^^iJoUfiYiUx`f>ms0s0B@a&Bmdl zCh#!)7+vy@v*7+Zj;Eq8QoEe4jblIkqsWD;HD-OkMU~x*w7R!&`~+<~eB9CX^&jBe zt+jc<(|7ypjrspisr|oN;D0T&Nf`eVpi`Fq2eA9e=3r7B@X5eDaBr7(08 zK*T$3jB;HD_E})@8&C2hA3IkQ3OK{_bRzN##i1zSNL{@?W58r3e?}skG@=cn%{gzt zlUT9`k!#^(m*?D>7evS2!T@t(LE9h8Hu4D>d2QHV8)DlbA@h842BRS{+jh{>#xIz|4)-k_>Hhp5kj}G1U^HcC! zCiv(GnME5mMyL?D1WLQSn`jfB&RjM7-xYWqSS`jr|3@n3kFalU=o{^={2$R?=Kl#( zF|xCEL77yjp`sya(fgQCT2J+RB5iDgcV{AF@@@YoQ-kf*F7$^9DS`}JxI%k^o?iBAK3~j2zV) z2csFi3e)x4r4CdM^lz%iMnB|$rRVo zYSSNQAYynDqETyy_U8F!IXZ(iV}gJg8j%U_2~qs5Q+AVOG#hnn{L%@^mF=2jH8(d% z;X_e;mmAl}`RK5TAZj+-FzlrH)=W%6i?Ku+Mk*zj1W!_n61R6z%ERC8^UjpD@d>1I>L=_TT2aY2I_E@0;(orQm) zpQF%%n3JxaV86|ZDRDaraC1qp?=w~XN$#-DABDh;4&Lq(p5_B7&qjj9C1}8kyv#N5 zK#$UU%B>K4;AOFqTYY)K={qTozm|K{FF5(li zN&4N39g;4}t{!=Lq%jct%-M1QI{T>#pkiA5?-$rV2$0-?-&1uUKtQ73VX^-k&iGeh z0?Yr!mJqXZv@vl0=bot4fYMGs#Qf?eIgp-<@h70QsI;lHB7~Yz8w6Oh!YR}WP#3G< z`t(463j0fzRJv%nOx0%|YyIVo`McpK?l;=tlAJ#5?6jqPyy4y6KZ$EQeRm`+AtbP3 z?dyGqH+|!qedgW8_pxgv52QhA?YdGk96r5fPgGUE@43-akL}SS**nSh3*HOuyk58$ zk^XW0^ZvL5|wqrc(lcFG$Xe#L8nulBYv?zYmkjV@2&4!3JXl;Jzwbe7sR>=&QaFc;5o z!}k8J$Cj6$+4k`&g8O4$Pv2OXrM#1kvX^Y8nUQQ~ac0gcl7&b4#B9XBH$DFv(wn5?ifzb_3Qh18-LinByY$lpx^l(!_;*utM_l zFR2La;#Jb(U)jzL$s;G3#hYXGjhu3fqu+_BKxaS$G(x6y_R=ZE>72owC^nH*_D@?{ z1!Sgmi^9CP+gPU&cXrkEjIHUH6sus*aCtqcGMJMIYj|$55_<)OQgt0Kjk)}KHFq*e zocs0Nn(?F>bQ|TL+-#tNy>UP+^f7QyDY|^7dw%1cSV9jO@#AJ1{w9c)u=nq0K_nsP zC|aQTgOulvp2%|ZpzI^^qk$~R1*9=35&zhmsWI9fj*^Re7CW8$^?qt(*pgkjCZB#a zF&LQ(`ZU4s1+|LRf@&%@=rn*RmPgG9Fkn8fn$I~wNUcq-`RxmvYD-Z8$jN1X2}Tam zYwjOOOo`0W&M=w4J@c!Y#Uf!LmpLB&20))NeUPJ9uNv2r;^4s68q^mIXh@I@za|Y3 zn?j%N3i9`wXLcQt-c3R$k5xy@-z|f-abSwdIwFc01>U8B5Tk}EdYq0zy?H`*bt-O^ zuaSQw8c!hu^7G&y26mMd1EQdPO7=*tl^w9yN=pXG{8*Lq7LDxSd#~SkbF+GVcoD<8 zMWA)nZlHD1MkFV(mR{4smv5-1*W6dicHq$X`_fU@nP)L77KpU`tD03Z!sl}gc2 z>gMgSKUYHYzj{1!qZ$06^oilWu8oL>sEztnD>aD!4K?!bUXZMdX42Z`cg0kB4U;?#C8U08khC;F^g)H8l@_ARq(;4E1uR8F~x*S z6>e23Qjsrhqy~M82;S-BxQTL}hE1fJYnQXLFL;cw94a4wh==CCZ?VXB|H(>UFA8TS z=hxWyIcZUHyD;Q;SWpC;?9Mxba+MLPr@AZcSt?$Y zWfc;tWuA{+Ib4%Bb%P_ls{SVEtkILr!DLo#t}>gwy--m@| zJ6k564PE8!m4nhJwMH+j_0IIOrUkW3LB9NUj}NUBkt5Ov3deXL<6>*kO~vYmGe&xH zo}>FY8DmAE<@gQkmU%V;_aKrRj*s79|P_l>TzrFG;lFYks zC>z(Bb*`YX!@R~4n9PbysFUWJyWoCf!YD*VA#x-{xpcp)~ZkHW!9=;h9&r`%Z3QFwdX zK-3*6F;p~pKk-VgmRKpvB5D7at{8(>?$t?y~7OK zgSWR2vz9@3J4Uep_2BAZPgnX#uF(fjH;Dg?(drX2gLW)9VH3W$2&S!&OJ3&SM)`6}nN{uM>&rV;!FkQ{ACm|2mDMJ%jHd>8PW zXN~4*dyCy4v15)h+=4uc$m8IJ6B$w;iR^p~b4!%m+PZ?N`It+}7eU%sI&%!U&Mr$=jV#S8lgRb!~e z5K_*~Hn*3PHs5QH4SR&PhdJ;@Gko{h;sK=fNVE){J{OW+S*c41>VZl%dU@odIv>R@ zCx*|Lt|z?()Na?ZgP3+!K=42iFVk)I93&1UbGCDTsTI)X3_RU-$|5}FIU{WlC+x9L zJZd_(A&$95o++nC5L{kG5U4Gw1J9hU7#*QD6BHhfYucpG$Vr*JR7I$HOQutYjEU5>Yh zC0st`f(=RUnV@IK@8Mdb#q0Z?GKdR)k!&A22o;SbPFZ*+#aw8W9+s!S2&u*%z1JcP ze+TNLxgZLVA;NZz{Sm?eA}vBUCd!8uB)qlzOcD2ttHtp9?f_S7Z^)K0(uODv@gj8} zts&uaRy@n#TnV!;C+&tphBB5uiL65>^`<$Z3v!;ptcVG{(4c8{c*8ZoqgD|uff0v4 z7)1#>K!Y^Q4P#(YEH_)a+D`L=L(bYM%5XAJN;6)RlSx!msA;P3WP@^Xo#N%IN zN!zncaku{Tf}-3gRgUW3vTSBv;-n~0DBFewp2z5B0f2HCWC8slY5`{=$*N+cMXeX9 z13o2fo*d9*j$_p-lejz^&*C5Mi6yrd)8SBIwIB81VIR47APlui@Dq6!KAi)CQ>g#f ztRGq)Hz7*+o}!9KIGYp-ZEs;qB#FZP?tH>fk^6Z?d=DM_7;a%UjoUt~apyR1u(EdD zR8+6Bt!qlQ|7NE-DE0sYN`eVfQ1gT#mGUhug8#OwM8s`&A=6chH%R!ZVTKrdeXK}7 zrpXxa1oK@Au}Rw|O2^mkrjmae2Nl8ViXY5NzAyvg@llIIFLOs;w$RB?k&ttXtt#k+FiC5wiS@c_Wt3{Pjo>dWgS0tWIhgWcfSGz5Tc)Vg|iXHZwg3|B=h11NKVyjheJ9;%Q3En z2Xn#+Tk#+Bp#pqJ{@h>cuD<-_YBLDhxQIWXM58Qa*%QaYYbGwcrk0rI4BUzdv} z_TV_kAf4*2A^;0X6P;2RUYJ;+SgEkc3kqJl%1XY&9^t7Qk+K*kI@$7j8c^U|NwAZ) z^Pt*9pu2D@CP|&$p!(ogpnqf%6|3V9WM_wsbsOa5Ii@Fc8g)25%;|kT%-X;!~ z5Xw0iPbw@XDX$U{@5xyy3n=g-WFFRM2_Ep4Ezw{W6D8m=PP#L=C`n46?dPo5Fb>?! zGo7?fYR?Dz5aBRMQzPZf%&m^^Y+`c@Exc~a`NmZ zG_te^Y`Y0{m4VUc#e>yHQ-i1h&jhYWG|nV>+6VT-b&J&fqVBq8c)AhtTcnKCNGn_> zR%gWP0fk4-x<{ikFZ{*9=^-+$Id?_qCkw;CUzI%BHVTwAB#5>O1RtCgl3fV@g7?WZbW#s;ys&n_&*GNEa_FP0iJ@y5wMnlXpDd(xy!6xGKbTzAQE0VbmdS2WhI zHdek2GkN(|T$-Crg>*;^sZm!C`HinZrjaD5q zaMt%7xj7{qkWoPlPx|Fm8xJ+5|CK%u``DCb%L*NOZfTqdh`duBJu`{kWqipaEe2b& z@H}CIJ1V%}cAV26$J_yvY!jayb=!pSL%ZJl_DPc?9z>i8LGa5pbRH?J|FVgyE_aY) zZ%uZ42KwXb;FjVj*hS@xMs&~xqAsEB_Y+wZSze+Q5!1Pn2 zflyB5M+-s#%spZ*IxPvSi;%m8{=1yq{;mtv$J51l6tH7>~&$ z!Y;LXUl`|4@%S%z)gn(dchkbWdNs2P~0w~V^1{ZjN_dwuxm!nhUV zzu<;a;dd~E`KLDc`#t%`$M}Y6_@@&(LWi%BJsq&T-BTA+g^{cEQLFb5b@%&UxJ(_u z0b4zq9bx0{Fzl^gz;^p)9Y*9H^e9?}b6zX*e5oT^ZHIr6#y~s0!zZ;{PtJJoNL}Xl zHLZ8YguBhIIn*sX1!QSv)U3;0dU52n4{Cic{dd~U>#z@gRCGnN;nA8DCbhmumNE?v zsy2+!Wwo2wS@0Ed2;GXvZB9^CHmhn3oRa{);%h zNMQQOE^@^QYRnnHi%xL%w-xsmj_WP@EIsg@m+)%=h*LQvqZQ5(oA9cji+R+*krSs* zQ0GqhpfRYMO(v$;G>%`rY3Y*xKe&SJYFby3ZwyQEzsTkO_0swuos0hh?TY=!r6ptF z=^C4(nySq znJGT>Rh14xuovMvf8Z~MN=KCUiB_9#xBBA8=glp6j{hLdTuQ^A-UL4j7|98Y6jlat zhM2$P#qAG&@dOwAuZ2daPa6{K{av}QiD#2Cm(rrEcwC6f^jx=9b)6#qth#zP*9%J| zB~3w=TF$5h?xvlUdp2(>?3P-)XN)d`hKZq6vaRRQ>J+if3|bfvMu zWw13h0uwb@uo?tbp6#*&GXMlUr+T6LLxql9;LxCmOVW(R>Z@}x6o&o^JKc$XrWvzF z`t)IeSzu=19LUz1h;!r95vLF1CRZ=N+4YAY$MoIwskgp)aSyzwSmtLCcBw^@^m zHa43%W0;TZH}6-PQKs6bH&*^%SFKO&PduN;8&1=zx^LG($zdgO8#_6e_rU>8GwH4h zzGIU=;a{0wor*sFOaI~XS<1hPeUD*(PkcC`kIU~a!neN@hWLQ{pr!vns($9S^_iHI zcfY)9eSyIKAg+EThxlOrfbo4(FZzs1_dQ1V>UH8jEc_Z>Sl@U@XXoEPI^K9^XYa15 zDrCI*>Yt=Iy~aV`%FrI@^}VT{<6|(S1~f|%plR7t*o2#JwJ^Z^h@Z0y<|-{L2aS*NM;XV5Wr}rDG)wy_bTtB3B2rkmeC`h4f{1h2c>9sU|{M%_m%utNJo$& zn?*eXV)cm#M%u!|7Bx;Rs?LR$Q7?L(KZo>5X82fUa6@e#TtXO?TNwX_;PIIU)bf>* zyaqVfKe3EYn(DEOnaYz|wPp|V^7^;&#Ea)SQsrp&@*(N5cU-eY4_R)Dik zg(hz2$694yI5rX}<5ix|C3hzn2|W}_JOTP6FJk0x&4X(u^?WnTH3agxqaP^7)PkhaPsK$cydr4)=O7*gLjsE&9?M*w@g6^p{B(+3OERG2aa{LGB`;^8@v!T5ShN zUr56B-&ZqD*90sZpI%5qbw2#2EX-C;zg6iM6}IqX?%lxqxW1)tnyrM5~Ib5J3`=Snv(F!a2xdt7bBa7_KWf5Ra z7LyT(t`tUlfk5+Pe%SMovxG6un26$SgGymOwg|QYS#B0c6Zy+2uoCZc2;ztZ%WnC< zPwo8SuE4*lWLNMOVD;6}JmoYNQ02q(u`(k+dV2MB|;i~~4-iiqR(>MgIkKe9W4)El+63yh7D;+bHs z2PH@nmE6%t&58^Ljq5g12i;VR^O&%m{-o>Y$J@!r(yYd|KSFCiehrW$&QpNap2Bvb zMmFNoZS$qBcU8VXG4kp@(ycOS2RXoZq0k z?|~;c$qVF;rJK)B7pUVO1C(4`Vm=t9yjlFrx~VuSwM+3?vPCVXehO!1MN=$KE7zBr zKeaV#kw#{cC@vks%Sx||^eoUV#&6Oqo>fvUo^^Tv(NjKG&)JmP1otGj4wQC}cxA8u z`5t0%mLyB3e7l=8><0c@6UXxfng!Pz;{m3Md=v+b3bBhC@k z5Ih%%jJE*Ax$8F;zG6sPm;&;_M=10YJZbIO#vcnKXI6qER-3I&cBSG-DeNWnttD7ywb?;5P2GI^ibohd^>g{@B1pB3;WJDV@ti!dBp5!tLYq5Mi&v9dY?!d5 z@>L+oxkxFS?O;b^xaTcFBIL(X8~OSoF7BdbI|5HJb=fiXfu0>q1x5{9z6=GBJ{ zTcY?8HQKwdJzI8*K$KD$1_F0q(!*(8f#G5%^{aR_7*wa)0r$2NVtNNygESeJ8AYy9 zLVUcFM}Dr4=Iq&4*;|J^b6?g_aK_St^7`&>(cE&pxE?x_g6bytn~{v{ z+1sV8aZA-dJWqaUJG<2HT8~T}F<`$TYzz2Q$HsA70Ood&hz>oezO`4lbr@XWwn&9+ zCIA)z%5J+;F_cr%B;WgeE8)&xRY-&&YQ&@LFf#eFOx}PD__HYj2pZTovl}sH&uz@H ztLiSn$W=b+)TE;_QTITb2}|WE%(06nzo04#OYWYHrrMVJS}xa!7w=tK2 zJTb;%=tQkX&xN06B8_HxEG1YlEEYxXdZW22vAX`4GGSdt4Fae5`MOdSvxY0Y((*1a z9TJ3v+T_3DvWs*-lXM4?=GA@GdN%Rz#t&^L)d3+Zry;81dX7ZTJG~IAJ7q!6yZPt*_Z_>^h920zoF+S@{bOw@|BD^ z^B_WP!uG%{z(3`f(Z+CtJs$k*m2 z0CUSM%K}8!r=L$VCX(Sz5g#xEb%0QGQHzyrn1PP%lg0;v&Ih!^t_PUFZDRF83=i(_ zxr{?e`-xO>aUC5^JvQbj>F0@UGRMh8uxs+sTaOjL;5rqxVAT!yX~-vg+ge-?#>+WS z5nMUkHA(Cy=q7IEvq)VtM(ay}Tlj-hbc5>p!^`d#D!K;o$|^|@_>58q}^LbFEN1irIuhz&^-9r}eZgjYwl zPh6TV6;hC_TM#`lgr`k(vY@P#gW^CJdQYdQ58K9*1Ptk6!wl?4%(nNKtr#y$nohUB zo{gIMceFTL%ov;8prWc>prc>s96@cO4S$m6bpdaByQ|G{*g91nKcTGGyLkL^-(L$0mrqNfKY}tEsyT}M$ z6}$X|-lOBTVccNENAH6e_8RI_cER^RBzAzN0NtCDsj2DV575*`dd;>}O(t1j|EPdUXu zc4Zc)tHCu^tvTr!6RhFA4N94wfzl?-L%Hlr%}g%!PKii^R2=id9TI5`@z*JL(@VZT zXGxEJrPEqbDvy6%R0rlaGHdx!|K8{xZF6HwojUUqajcx03OyL3ET)RI9=wXoeUlvi zD@Y*A^RY_3F&*RrjZH zg9$q(1AtSXJghA{arzXS=}oJUv@GR5oObH29WKN`X5EH~-Jkx_%=zTx#(aBAB$tC7 z*0_-kwIbJKdn?P;S^ngtwb72>EExoIPbs!409qP2f@-3{3EotZr6SSUQ*C1lnlFWH zkSH1Mr(!ODF=^>k{-d(+iVJyg!nk-y2_7{QmqjyG?n*{Uaq#C)M}0_#Ad^%ykI4&3 zyp_vLFMABw`>w-gx^4yPPz9vesLNAd*FN-BIK8LBc zU)Rg_rLJ1iSw-B#5P1mhq3YT>?&gc-vDqbLf>u<^>8UEeEX5+_FX4Wz2vPi&_8Kb- zV839StD3?&+XEAeF9-iq8}?~S1z??o%0E=8A%9O?Hrai#T4=%r{N#wTWDxEX5Mq11 z&|3_2bupw!pqIe^wE^KM+P0ozb6w?O$a@Ln&wh)may1?N{O5Ekz(j$ zRN3JZeA3VJ@`tHFhp33t*MSN4pddR&E8>NqQZP$#8i+p#yLr*kt3VrX#-lr;!^;=T zB(i5x;{?vj#-g~z1Ir2PgQWtwgbSd658&7PVQYpJn<&A9oC2^t<134)6xQnc0~-Dg z82Y3X)2#+vCj;zi>Fw@398++-!YE(D^Qvh-NuK3ZzH&T#Y}DZop1BYu-d7cfd!asN>Uo-tK%C zID4$~;YmuF?Vq8Ri|*ZMm$ zFH|fTS2-PEvGgKX+6!*zXchCBN_s$RgqAW7~%lny% z9|UPe?|TG2LMHI~Eei1Js#j&W(wlJ}W?s$|sm93>U^Qiv(^y&HEl$|_?nNkNS{6H@ve8sGNm&-+PfRbs)zW5)bYM>(l`zOy zu%Knuf?d8q#;6p>sqB+!*FW%9)8ZGaVV;j@(9d7|!nB+w|NVHR0orkDSsl@$k-O~o zd03v9T%P%{@a|xT!|_uevY}sDR&HxkHx;6@o!{Nd?p#Gxv630LFczt#Yb&o%jf6%S8W0FMmRy}kHDFk|sASPO#$_pFS zmoSdA5PzX}RIzAP2>>H=T(Uf$lw7GrcWazwCHtsZhm@S6YzG(4Yp<~j<7%cMceFbc ziqpv2gYXIe&iE)TzJ0d%fW^t*%#HTWiB*&sG1C;d_Kci%2f<%#o6e%BUx(_^=r>F6 zDQ;}nXE3*oKP0BsmjHaNoD30r55x^)Q*2W?fw(q zYfLl9h(`tjvZwy9J(z#Rdj3~En15$({uAE&H^3)FRYzq}5bdi49-hvS64O5X2Xgaq zs=A_()p9xGflC?a1Smh5p0LZ`a1uQcAS!rO54TjsTeAvW@9)u3@Liiicg=rsR&*yOpkImW=6}%knXK5%)LiVY!L|8gwIf2=7CZ@apRRa|1P&f2 zi2v(4RkPo<2u+rFm=Tkj;&Dg&p`Y>VCRmY5yG+lgbUy z-qAEoM|g-W`Zm{LR%R_m3C}}>i78QnGfe;fb+AH1#>9+_C%Zrkn4$_mxk#)m-6|>S)JAz+go;vxfM3~6 zY^<1BnngcDJe%!D|1=q;@fg|vh-{iM3`4da#^C;8|Hj>V=AXqpH$W)5ZgVKs8FPdh z`Hra0Cv!(JR=ua{?FG%dj=Z%AkEOaL3#3nu4IMct&lAYNjutrAz0GQN#*b5Eh~eCm zJqk1q*mzQTO}HW};e_~ik~2TS+TFxAqmv)o9AYH|QF>kvFO`%i6BV9jyQ4HW zEoaEherjrGLk;s=RH(H)%kKKmpx>@}?={1kx!vw5UuhUCSe-!CXZES@&gO&9?&+VN z*Q?2AdL$*5&uI}qZgr^?m+WyC*&Ne*{FI(c04Cq5(5W}IZ|>%4MpxevSW=R#U*C}! zIRn!xAW4Pb4f!*@J&op^;xSUXR(-+xu|rzmX%6?11(B{K*ZYk1b0Fy4;QoTc^GV0f zOQ)EHprX*&&MR!wJtNz7k;|?WYn?U8fXOp%+>`vK@-cwOowlRc+}!3gFK?tq){V3v z?($BF1Z6fl#&n^5EIo%%Z?yX^*^$yoLTDCu-Gw-5hf;FAyVyRA2zjs--=H)vGdn@< ztQ?pmYcNxsBltVD1B>*(>WyHM?LOzKW|^Qha>A-L1%vRcQHLYw1kTQNk?@^T7jGg;!NmTqhx+wC1MaS z){<+V83E%F?Z8^8?(!#pzJ#)u7ioj>*-zwI`>NfTw#g%j7~0WC)5W^svK(BtMj)Jc zM;H>JLi5JT`J!mn%t)|s8tWq@kHE}Rw^+&`2du-Nnn`27g%R{KgG2MOM`i5+)@ZY| zL+jow?V|ilhL2|Pn)vr!GaxcQFB$P=6!M6HIw>GYOyCz)<)^mhO`50GH;tMp!PG3? zO)LIftaq&w{^Vj-H-KKbNw|)jVH?TzvhqRezn(FFdsr9s0xK2tGHB@JicCRozgs7$ zHwU{?^acahg|cxE9QlzW zGM?w-t4w?3K0co0*tOm6#okEZ%=*Aoa`_6AZNyLkc%uHl?9E9n(XPC#rfx}-m;Y7>8VIx1w`b2`X1))%`6?1MU2vrgkD zt@%G0SC5-%D!0O_yWMBYJyZ2nbQklsSpHn?hqAUyGRh>i*F_))eHB;K017ayg7s++Jsl{RBGY)L6?Z)g6g$P3h9DE2QQZZ1wNxJ zR`x~9CG2;qr7Z0CM9a0C8fc$Xp_`{8m2bO-M#5lQ8nP5|NB_ocW=HIoPFK81#(1)k zuPkZD!Wni{us7wZ(^rln56Q}yO##pm+8lDgVQ7<2c;;<~=$A|Injcy{voH&ek!BIG zabcewXiMD6a~GN*if+ronBVSeO;gWX0aLOfE@O>umM^eusAu2TC0`-WrVm~Jy@wv% zMmiur`J>ga3Zxq6KD2bqSE^nDfuio?r)u4rt{IJDu_hWER^=v23wURd=Zwnnk25{I zYdt5~KuX!{B$Xr2N%g%%nMUO{Gp%Jb{qf-?G^*>Mu}elbYM0oPVZkPK@TQ7o@C)1T z4#(C7^g|oQiKBh`sCA&9!b0s!^HKQj@pE9uC);>}x&e|1)-&lLRxPmWgU#gt5l-~# z*b@O)4cTFJR1nrcn?}uQ5#ChG+iS32u7AFN{jR{JW~(Cl87Nc)q$L5L=mT<+jG}UF zse}bOpY+osR`ws#EoZcA?@01hXtvN5FQ$$JFX7U zY>@WRGQ@1y1;SE42fMQujNf3V0VO0&u-Op4sH{LUu+@hy6m2+XJ+OZ-6GYzg+>y3~ z_n?ToRt9HB>x~dOXSN7}v(7i+=Vp-iU_wgEJCjhc?GAj$QY ziHyN^j1foH>#s!3D%RqrBsE4R!KN$4HgIgL*)&&B=F~A<<;t^JRt39nF3Kd#6yv7y z2r`8Dlp&r%tn+p>2%bKaxpECa*>VU{vpbn4Dg#-u0y5%A7b} z6Y@=IzEikwvD25Q+EC!GL~6F)N^G4PA9bRx@C&H?67m=6=@A2VZV7nt#Fv_?(m*P6 zKO#V8xRq(N*@y0UNvC} zdu-~yP9gQxpG4(v(8u3Ib!a7*lW7b%3ZN~L$%Z~$+a-`klt0XQGm0;4PSmA?gi6QI z8)#qg)SX(Mpm@(8QkE!?9`GMd5FkA;A0VNiJFxm{`V_;C8;+S~+m6B{rDeows!1A4 zb0AE)Mn)07_OycYMjDJu@|%3WD8C>{mq?3g%X0Uid;JtGNKG{Y zC$0~)!=Ndbt16&;`F$WB;fhQDi~TI_KwjmJwXB56^SPz~sMrx(Z4O6U4tt7Q@sE1m z7MoP7ipsIUjO)^hR%z+?a>qEBX@_r-gLA z$?HZEr7D_^j7{6l79GP`U3m;wAx~;e3wA?>+GhtBbrPhs6lq%q7}_|xWfIf7adI0i zeDxo%oS&uVZ+)-~dccsoXzs*V?kbX3jVa!i*!T_6sP!t(`Z}+;>KEiaMy}~9ZVH*_w(K+GPSEs; zXy1nED8?`Qocbn>!QkxSf9gyd->(WV68Om@Dhi5pBS^%KCoFScCD*587pCJ(-8v--qG11;e`2dLtBhl*PL=I!ldYi zc`D7{SMNO0gM^RxPL(EcU^X#F5wZ&tR~IK9T3)@3fKI!E5FTqqyBvnkZy>1WHjq_n zEF;Zf+u$ku#PtX@gFmTLH-U*x_0W?@p4Ar?+etXz_t3pY_x0DIGS9RsQRciuZ*hHD zmPmO}C4J34x9Oi>O^ZAj0d7nYrkM2PSazSeI-%aiAqUn;t#VIhcv11AuIOeF@o$g= z8wN!{Y(F%1`@CM^H5j94AP#fb zqZ#2&WmjJr{y{#`*AOl{_$Hqu{x|Z;zpkbKktF+%wIpq5Y;W|P-6&`HZ5C*3>inN1 zStghP!GDlsS#dy1>RaoU#lA_hl;I&1={BLHiC5C>UYxLqd-+4?JUr&O}E~;gFFFlDgToTTID<$8(zHWY{6?vXrBAvR_An??%ohIu?!~En%}lu#l5&orW=2 zLMUx7H*iX=?4nW{GRh1VZKQwzJJ=-C9Y&`^$cb?VYBo-;vat7&a$57lM#FMBi3siSf7 zelQ$Sv2@bla>{TiFwl&?WLgn3Ab^!mhNmpS)Jawvl1;IiV{N3~^7YCJy>^i`Vc$T z{Y4Zz_kEU^DqQzHXS?M62b7+@P*ek#d}R0g1NzhYG$OyQC$iHH%-p?RitVM2&Gzeg zotGQ+osLn@ST1C{t*Cd8)wEaoXXntc38r8}eY{l0gAq{9gArk$kZ0bps6v!jM=gTH zTQv@hLu(X*6WX2`$lm=Ck{5E!J)JI(WX!m``O!(GI0{nUaqpgK+}-^p_w5&g9)^80 z{!_@V_psv^WWTBM+}nfFu9pm4fl&sJI~nNS#9Qmo;;&#c3u)O-O{OLjBN67D$nsDe zON~dqifdfBN~)b%qIXniwOu5Y1xvPR#pR0fdPxc8xFR;TuF->n3%D5<&4_a3(Bo}e zDZUFeW$8ABr_iK359WkFBj|-UF7{~^LtuyovN4s=g$e!WO9jxwXRB%u-tLq`oha-0 zSTj@8v?XM!V$bZC9S!!TG8#^`ds{VF9qf|2nbJDzqQq6j$I2UuE&td7w{-x5f+8JyTZMhwkC=2 zq?ChI?15E<0y~u#fMO1DKIhFulUv)!nmf0WMY~7K^Dgm2tJddHI6ApVIf$wHD0e2> z9C@=1n*5;#Vqf|an0WR&_pIR4HQGR#ogkOF*1me zKeL3jXFaOw>%5S(xv5&4IovUk>z;O#gwX5GB`hWF)VX4_^mn{2ivm4Vcwq~$1A_{gUjP}W>zKbpk8(i;3M z%B~ivGi|feR_7H)EJ+p(&V8K0Ffay&wZH*3Eb}~(hxto9U}1PYikW;OCj-+t@lsu& zzf^0ob=Fh>oTpit!2?Zpo=F3N0<#(Ht*3-}cwuBZMKCU$JSm;3XI!W~pn~E@vTqsc zF;78y*gt$N3oZZ}#Y&U1RwVX5#AK)BYAYy;!o2q236>eG#{@0;ti#TwV3I-ZeEx_; z%Zq-|5{Z&wI?WShWd7c!+J91>@4-jISHF9W+^>EDE1m?+#aDBFkk6SE*tTG7ad9(d zLfZs22%BAgj1I=l1)aT_PFHoxzZCfOQo96oLHxi802BM*TE$kmhBZ&KTBDCPHcE zbJ>RXPiA|O0KPPNkRusJBXM)^?)VE|PQooD_Ur-I%tIVp&wz`S)P*CAG%&N4re5R4 zBeb%U+3e(6xE%9Nz%=v59Q~n}F3F*lF3CPPHp77ebIl>2&aJurhuDA&^H*e=X;)y{ zIFC$csT2P%(hs?j$`_v9OG4(ah*gsh*uV5};!Y3z{^}Z$@c62<~Cp>-$Lm0Oy8L?-qXNZVXKyvp*AyB6$Nik>j>%y^t=h|VP=4qMP zog~hKCbFs>~^;+L>BX@35QB;b}N(oj6pC#9)B2vTp!1$p84 zFyEA}*q08=w{RJaNZ;-HVj+j+@c?m@a{mrqQF2YRK1V;ptfQY$-YC3t=PbN+Om;=q zcq2tMa?@w|kwJ8Z=)H+CZC*%HHc9C8144Pg&adW8mJ9{E@a0iqu1R=4Ys&l{uTj-R zh@OrFMehyq@82%WsJ+eX@MwO(7%@eQy)Eo(5Wpah0?Xz_~N|9o0~;jKnU;=Tycf1)5&StEVD)i59ytyD5{) z4>N);k5i9X#PC@*suz4{oEno*zroYpmp`C%%<31it>9rUQkqvupQRJ#aj)YwZuwe| zkGpG+2I6rQDYHL@OF3HAB`@3S4g~5EokHBQ8w8UTn}AeKw!+<&#JJe2`5eA5oO=Z~ zpYDlg${M>M~V>o4Qz9!}OI=v-yxc+X2j!=Q^nRjqwWMtr2n1vFZ<0HqV8)xpWv~Vapqm zZu7%lO`SmsFIdLdVJKr%#kxqk%<^6Hv&fD&7P?5fKZC8ANce~}YSstdwzj;r(BB8WqL!R#BN=&a1zBiEXpsHnWe?#E zuophcTYxgy@Ik>v3k;ev^LBtC&bV_dIl{DCHsU<;mQQ|vl5;C=c6&S29b39ctd zW+e6YimgFTLo}+!!UmTj`I1AREh))uu}8k(C11@55l&c<;1xz}4-+_HVA%YhA&Py% zls^F9*~&1QP~fz|AmJ$Y;e!^kI=v4qfrq-Yr z-D6rjlEEO?&P8jCtJfy{)`tZ5$$!Kqwc;@w6zr|DSyC2=1inJw6K4wd1^G!yKf+^) z`CV(d`PH)h)m!Fs6(-86OMp&tc?9ia*DK+#aL%n4<_Wc9cv z@W)x(3X}&u%%x$z0%_VIm+x;7xs~MvuYy5nAsVIHn~#s#ziw(X;3=+SLk-c>&8u6L zqqCV7HB3vW%fTCfaDsW?p$e(~MR^qo64LEwWoS(S(-|48_e*3gHhW-4&@fvL2BwCG z0%}t=zRnG=2)F;cIjbBsIuhi1r07bbsV|;T+_T-%lKE20>4l4Nr_EZSK~ET<5ema2VW=a6Nv}y`))0fn!)^$^Y+g65Il57o(_9$i`UCP(6cP3Z z$7bNCDq-H2^}71jSc{IMFZ*!NbHv!TjC}={3p zHhIn2bQ0`_N5uU@VSm#t&04mW-AJ`uqz#9Qq?hC}dlK27;7h&14T+8Yf8$cc7rNo% z=3@Rr=-Pw)qw-inoRma{`>rcU{-?@A@c&hL*nJlwE|z9y3_>P`w$A_8@}pT}TLV`N ztyctPWm=-Lg(zG#(&*J{bzwyvWUWsacT$23xw?M^fSp*MwcXY!bauDR!B=Yk1LhVm9VAl+JJalPe=xe=O{PRC8D5IvKDiOxP{GWFcT^dhy!Qa!+u ze5b?5TSo@nVqL5GDsWKi>kh?S9H7&hM4D&jF<)f2YzB7Sja108ZsUYN=RWI@)aeYC zSSYcXGBJM4aE`DHXNA!mZSCBcE?esQfxAhBq%XJ&Hbd{6RINU#Gc~h72Wqab*K)tK zmdB3y{AIF6=NQ%}%Oh(7XSrx9mer9eDQ%)7i;Trh@8Dvw&;WM=1U~gM!%+)-5MbF9 z@ruGzn%tf}qNTSruXj^3D#Tt+H_BW=KdB8d_#HqX&^rTnasO-Nb?5Z_M$L*!^4Cvq z+Z*v%fPPXG{q>2~@NrvJUn!U!Ve4{^QR8RM?>cR#7u2^?cg?SOR<~mp``?1p=pKSU zzDNUBbt|_NNZ;NoBZTVV7tRjsLNdYYZLQyo8oK zQ3{;}`a0Q6;%zk`muR#%E@?|=y6IvsZP4128cBl&>w?)RBn?KsaT|<7A299~D3Zbl zlD0`4EODA+mtTr>jk9xfgf#AXxIu{kauO&LhFyj}tk|sF7sypbbe&c(W#`S^>W<|BQ?H9)75-lgz+UuhPbn z`2hPzv|O~)VA`a#RHt;0YKBdKS)(F!65oa;)?-_OMSXduk&ON=>}wDwh~{7zGmOPS zJz)0m7KvaO0K>%OOogzz=Y?k{LX9Bf5Z32%3J(>4i_g?=z9-42eyPM->o3crH93)7 zZV0vw8?gVD#b=9E72ch$R}~4z0X5ySCvsZ$-Im-(s5zE_f2$s96L!a}syIzW*UT6C zRHs3!_RKmVWWmfzf>8SubNTavtZZV3W7?e)Nw`^29Os$V`t}Q@Cp=ez+Kb2&4nqSW6g6eliLk%c~N54|g= zADJk`16UstUk=npngi4UVFpxk3AFo6IBzu%Q4eM*?j8^UffPdK1quNmo(C6=6tyS5 zzk&xu_KOX5_ry3e;(2($@^!^ek+9^~a zVuvyA>2?&IPYsuQ86qECqv=BzH6n|&CdupXeBryQR@jHjp$rGRBb;l!&B6K$E{vL# z_CENI^h%YtK}VHLHhh`$Ly!rWV~?*r=Vz9KOlaEAXG3jeSwR#f%~1VSJOoyAkm+?n zXZpEp5jln}L`8&Iet|7WP8dtI&`!kdzlcw`*cE9sY*1<;p0vUX@e*uM;#KED!wkd& zDl6{KbfEw@s&5xj!elRO(c=6YhYx*j{AW?nQl_>jEdWaK=f{u<5dd3K&yO=c7yif` z)D!=>dyjv}A8|X#l&j|BpU^4(@3@;k-){83k^bu*`>&*e|1l@yAL!11?6H!T<`#yw zl7==mY^?tZ@-(aJ*{F)4ec8D`U)!%Q*o-Utp~WmHUub{HikMQ_<`>hYY%A+U9{m2( z(Cy-G-|pQySCAJ-OdWXuOWqTY6o@li0IWo%kcdTUC0t;SlpBpWLU|WbwmWr=5g0ER zy?C9$a_aN&i^Y6qtM)IqGln4O&YvHhnD}dep>(7}yQ|0k5OW{RDD#jtvZ>AxkD0L3 zyFeuGA*Wg-2AI1Jg&pKDVwhpGc7Je z6651|55(FnqY)t+Fo>KuT2_7(phr((xrw;z;r8qj^=KbsdG%I`_|iS#QaX680&+9% z#jT~hb#HxYd2X`PU)|a+$!oB#WUmlg&}K)E*i223qtj5_F*0**No{^_a?#h=i+E;# zc5AY+Q&L>n_43`W>YMj3G+cH~*|JJXV7o$x*1>H%Oa>J5#S^ zk6#fZFjJO!woC=Ah!rjpFgwAhf9D%f7sObM1NahIS+LD8$1VQM9YB2>?I%>#o5~bz zOTt@bxY7O6?^8~T9H7btTrnCO<7gp6ur(H&$8&LbHldSQEZyz zHBYd(m}wimWAS{C_xXWJ0UdKOu499KqI30FfmG|^#=I$^m5TlmA?um@ZW>)%-;4L{FJAG| z20C`kjaaKrOmxmPwwZc=P;2q*rZ{(l_T>7uZo_yJaF3>WjEym*0gg_6$=uS+7W?D~ zuV3iuedm!d8}~do__l6}V-3c(ShqH7dbaVftL_ZFkym{{LmUmRkO$YSo?UgQfho$XF{L&>#yu6KO5rKxtyYtcpTiC zaO2f}Iu;Kv>L4d=yR3fMRoN#rUJi4{J~)UQV$eUn$fK!Y(*B9>u-LRmw6~@?h$RJO z3r1s50fDVp{m}S2Fg)l%ZRbt+zgEh)Q#~tqVfh1|p%7&IPA$ruX)Eqo;W)g0O@65P zWzG=vU)7~ar}XC6OfYnhi{I$?I$hn+z_xS4`}-Pl#|ReYnjD`hja%aQ_t*Jzdcvs< zNF$ZP$PcV(61atS5AHiPGGVC?_B+J0yViy^kr=8KHO=zIoD<67+abq+Y0}2Deeue0 zMQYnfpq{E>nLA$%*nKt2cWSKHRurahdW9luKF@=(PzF)*e@SqmRD5|`MP%atAO#ZN1 zQAb#+WugT^bw%foZi54Y_&=}Af^^+>3jI11-A@a+2|Ey>h=xo|Im)q(CE;n(VZNhB;eSuLB8!Q^zsmh83|i6yN0k|YBz?hP4c?q(SoU4r1v)R7E| zw7}(1M#$)3=NMGtK149#T|%B#$VdC7xqkQOrA;|JNpcv{xC2z z_x836fl?2rnK^-JMFi|2K*9~jSX&Vb)cT(5PcJ({328g5cX)=0#!8b>uc{% zth?H!hgLx~f9e72#vt=M!Q0os@8Pz^KHQva+dFNqI_vHpOvC$Ji6ie~IHHPpHd<NH|gZ|HPr^BkPoTUpr~Lbd!>gj~`TXIrS3A6;P<4%|1Nd8=FUk+CX>}1o`v?8=w!%eMQ5-ZTiRkf)-;THYw%V zQXT%$Bf)YM={))07Az{K1a^eX{Uc*7Ld!`luN6J*a=W4?Kus>Yq)hWdcs@Lro=KQL zs#}&7Pp~O&h*?~YBdd&z?LAiD@F$3IxtSK8z3IXv2;K5IHF=m-$Z{h00h+h0wPLe{ zIF`P+2-pY*9tZx{`Ghj9+KFVVew8q@ERE@|?QU7R-ug6-A`#ZOr9%5qxBu){wi{mhjFc z>w9%ki_mGO>ic&lW%8-O>+&x>W_G%Kg5AUEXR;3HnL}76E z7)!Qac3pdlFUs{m9NAXPC(3od0%`O?Da!Tn^lY8{z^vy3tldM}*&*$-)C>A`+O74@ z2gIqA$4?c+0|0dI@hw5>Ee|j8z7j9_z9TPSUy7G(-;#H*Zr>wvZs2ZWBH^$85FsgV z)F~-%942X3c$(;k(m<|*;J~Dhq5lXCivBUw-vQ*F&{eXo0AD!kSV-_eDitJ#RGtQ{ zYDI8keLjUXy^{3|HI|IKw=qWlgSPJ^WbI6t>XhqQt5B68myP#2GM44UcWO805hq?Ua(^rlz|9jZY>#dq7@7P|rnv@e_N(G;Qf9{Y zPxK?5v)tKAO$&Ciy<|^;Ry&O@oK!a!G8e_<%_t*i3kIzqp0ebmC8qDN%JoGt?u@Hg zGnn8n)WtB+t80zl5nvvcYhKh9d>S?Cx`P4@vF{Y_ET9uoX9hA(ViL_$QDe)k5@}-$ zq+Qqw4Mf+H60Tob%Fojaq^^Ud?Hc0c?E1oyH@w{+WX?xSxIU&zU{=rPP3eDwJZ^@N zSbTisiALP+akZchbrLGdTkp`n6Vt=ZFX+mse!4z$K3qa>wmg=2h6fD+d_p7x)RXtlTT4oII zHq?1q4tZBNv`>DRGc2F5<0F-$^!4i zwU}q2!Cl-A347#D>C}62<4B($*vxiVJz|oenmhz0ds6dp(JrhSD|}iedt!5n(e(vAp=!`=EMTe% zPJzh)@|io{(HeGJspAXN4-Yk`G>uFj-AeS*N=;dq$3;?~FwMwP6V=k+X*DgC&8`*g z2A{HqbD%CtrU~FZp*czcKNYuhpG1#r3h~TV)ExY<@bDs_U?0mCz)F2LF_0plh^h6Q z&A%vkk^=(39o_zr@|8r0*@vFUXW|9KQXCxsqJ$7dv?2~l{}#Ff2DXnHI#f`1PGYr> zUhBAVj&aMvn z%eE;?@FihYMFsfZI>4q}36Z(h_S7KxO0&{V@@qNr9Y#uxhic`lRk=q_Q=??j%@PQS z1;Z9m6ok*kb#?d7fcCb@-<{S66PulTtkjF!5Wi7PWS1%hm@CT6=6iY|xIPkV2VjPu zicQp|QFeaU<=xQ_XMiOc1tMJg1LhBOjXnFdkX~bsuK?UThOOvU2iz~Y+R48Qu($qg zg!YR`*F-sefG*K-@1IOwWw18fG=?k@HHO4lqaZd+l|L%aH-}28$Cx@ks3qo-{(9zf`4`bAe&{Dr>{!;A6 zfNfkuF{Ia_&K^sJmRXa|&-q21J)#a>T_waBSB=i<*72jxb%4kkMSRU`pBw|z&XjI| z#3tyLbd!>Ib_Pk`?Dqh!P2;VCTk0+03RTzi%!yiL^{B4)vTRcl;h+b;%v`{9{5TDA zw%Aie=7$qV3zFI(hVt<_X{35Ej!S}p>HWMhXI2^ZQSo~n`l;flS0KS0A+ayu{?(Q< zjkIFzmvI9?XppSNMv{^7r>$-jV>oR`LV*@|zvn-sEL@!LBxP8Jz&Aa%Baaie2n z9R%jwn#;Z6R-=r*E_4dDS-i%ua5I?|kD(!b%Ku^Q9fLay({Iu4*tTuk>DadYi*4Js zla6htV>=z&wyl$yTlbv*otis$KHRGPZCCA2yVkp&=Us5Bu&%QEK{>nI&$HuhMxqeG zwPSzZ>g*bPjWBDoVU2KE0AXI_(JhM+EUV0!5&W_2&sTn9-G@7ZunKjKG|M2~u&;Xh zZi_rUS(Pr67}${li%HO^U(M{?i)dKbC*}Kh_|^|H#U= zF_w2Qw=pu|U}gSSa@?c_t*$(b%GZB6#ixPRI+9F~PZ*X@w~fqrc{_`BgZPWsB4FGh z7rF^DbVqSPKXQeH* zbNSi(#M1ug{ixgY(-Ckuarvt7mgD^+PF4|Sz%WRNBnwuRP53x`5`+uMJfNQ>0(K?} zt<-2VeX^p2KCB>Guj}?$OUcFO7xwh!%V-y~)cgF+#pw(?eYZ(rG(!B$iz_L;IL19C2bhd%| zTVXaQ6CoUIy!;rEJ3jm-jc3Bhu#zbhh^|s(6ap&!S5qd8HhD1OeX*Fs@LqIh9F;U= zt%m#-zz(3XISRHhs;VUB4mg1Rv{kv`jOBB#-~Kc!Pdr+wo~Ou<2XsR1R@OYB_f-=v z_fNp5HP>5<?y$Oen z7rZ}YvrqW0^S9b3a>Wh|v&=E6jArU*?TN@W@}^%!?5?`G>%TIyY?~u!2cS5 zEQUi?8gFhlN-sB+JADd3PY+3kAoYmVqU zQ$_9lm*^w7QxR5$r{Ufd-qB|o%Z9s}TiL-nqH&k6Ev5u!g0mY8l{98J&yS-+*OP}0 zkBpRb&RsrEi<0N-V)PJsPm0MQK_-muB7GV7YMitmm%V@#K$&$KbRI2ITl#cSu01h5}8v zg`0&;GDodFGOXrIGJCB=<%!L}$6dm#LdVz=wfOjja&i%~oQJinv5s8x;YP_Arr zWnitNc}7#qbN0koxX`bWPDf!r^5k|89nj|btsSL=z+o}0V#iUvSNl!JW|r05xJ3df z(h5~`;tb9kOr6(r={bA4zY^A_;kZ-IF8Mi30!n+x*2+mUeTA=NL>B0Vn0GNP$?~f zd@i3E40iWAf$I6eguF#jm6>@29o37Mo;d`z2$GCJRww-Z%1x$ie{d}1PsM>z-t@Z|fN6ClAFj81D@#{_8Kwday;42y2v9-UE-8vBYwh=T-zdaD~SA&o- z`C!7UrS}3&73gYMJnY6woEagnU81-gw0jzf#t1RV3Xop?fLh)l(9-fXYI`BN1kv`p z?Hh#W&6~u&k!5PC)IspWCX~6fH^H`IWUJEWL%UpWzveEcMkHNxRs{@wD;w$Z16D`cau?-0oY@)R z1^6#8T(7}94jKX6Cy1EekGFO>A?#r+7<-(vy5H6*ABlfw5lscZkdti%zLLgT^1n=z zZH2xX$6^J)l#-`UpCiYv0zNU5>GOS64~BQPOsV+sKBiTCfL@Q3eTZIBV--LZNGq67COBk4)jXAAlC7e^L$TiNI6u>TFOYS&p1U}ub{ zE}*8P){YJHq-F<7-TG*&?B}W*(|-nslIsi0z7O@9XL5s;X`m#Ag;i(+qNM(8#2Jic z(?`q4dTt*T2})43C~YyxVg{CJDDCayXAdiZ){|5|8pc?p2B|N>3KFmN!?HY@YB|MX zj+%pNVG)tIa5W0*GQonGQeCC#-O+!;JcU3j1dcxDukIx zlqHPO5C$nkgsi@+Q=|~6FdU3TI)AkNmi0GcSYw)ep^6oDF0zaYY}}4#%bvQ!H5gFi zp20e>xxde)0FgoOR9G(PC#`1?j;1q35FZ>QE5j23azU`3^%r`Zf`$vUb zGOOLos#2JlSlX6g+11CYcVKdWfvKo5T%=+QO0Hl6ocalyx;aq9 zeh0VF$CPFT$T83=f#C*OMn$sR##H|P2t{+Ksave+@-Q>Y4b0mLF2eQ`O}s{10Jw7a zbyW+P$!?o8P^!c}6L_06QmOMn2`G4Pn{c|t+ubi(+ zWz7Lw1c8^hs!>;iLK}w&ajnfRoMw1sxh;KJQl2IhVn3)p%KaL8Z$TZa9)00*Y^0-~ zITuJ}Tb}3orx%LIw0Me&1WlAc>Oy+X#axMJiI(r@!yEn&G==G&z7H7HS_=aplP0g< zDewyi$j)VHZpMbu225~m_!ppgz` zR+7n{@=FAkqYCYEY;lz;84A^k==Z>3&?6sgpZQvJE?dq;aU{E&6f0CtSX(CbD-ntN z+uH93=c-$%`)Iq)5)Ljrw(VRqLlvvQMTu?3!*({iXVmVDW}w`0C{#kGd1XE$NEFZ6 z4QB{FRE@+HRLfC{$(zzERho7?KTo}cPpSSWY`YlMp|%DjxDNDmQEKCje<*kYI*-C+ zX(Tcr4Kq0NsJQP{ozqv*r!0?=xfeb+sR^YknbjTQXg1olarBBFbVJ`{RF*`g;XHMo zG@QMI12WyLc9oFjFaQh8N$bg5;pFuTKE)P_sCny4b!E!Q`HGeNj^v?^Cp)))tAhyn z)yr+bwrrp-ZS2O{#hgv8Ux)5_^~EnsL81dKeua#0$R;Lr(%qt4zQr zF7PS#+dWm1d?hU-3AL5V_F*O#+$BaB;wi!=_Sw#!Sbj%tBE}Y3zc?uKxMX&B#x zglnSZ?%dHZr75RKX-woL4a(2}?6F-jF0;z+Fl=HT){fijqDt#TbyVe?5XCx;pTtCI zSD^wzhIL$*O<>ew-zpB<^F=POn%i@(_u@0hO2QP9_fZg6;}9=6FA%@x%+|L%n|`ms zQ)lFJ?sj=)pahB$y5>Zti4KIF^?z~Xn;*6aYZt7&CKhQ{Mw>?{#dz;QeaxueUkMSb zW)ljU_c=Aj{fbfL7sRC|(96ip8O45a@*&D~|EZes2^+2#|DOJc#38nXli<`T=Z1heBZ?Y0r6Q;@Z|Vs)1pbY9a>ID-2O&r?a}0pVbL$_`;ZwY>S1aA0pC8`|2l}2E zdcuq$+9(C;5xb1Hh$JF!BtQ>XDGFh~F?uCY6uc;dazy1Lwy8txRN0-$hih|av|NN1 zG&Q|*E1WA<8Yh68$~fN~Pa~$HH>9r~Xsa<5i_Nad*t4ZAG6`F)E*wJ6Og8qiPQjBN>rF5j$$ zMra_uZf!K%A0xZlT+yjOzLLY3!uArawF=)N#%E-!)bOTFs=l$dxJh$;st`=J3d-d1 z%pWm+tKl4m^p6`;S?BBRdyPH4jczR(vYmJSzoRTSQSrOBFU z1`LM1=m^F!6$0ITX{v7B#N8QgwQu`yt(=B{DgITh;CiTO+SvCY=uCKL>g$EarVS8S z(;idsz?H-gsECY2hmS>H;M3R`e?K`R)2!3}Go|Ka?>ji%o(9M@55>wRZ!6yBQbkRw zL+fo1fVGMkUP82@Ed4ze*Ir8u6I+vE5HQIORU8LU?|5GruXP$UWAfVSwnMU4hMlx3 zMIBz89Qs`}&#;j~t!v`Q?=Ji4Y>{a!2e~u@>m1$gzP1=sx*f5oy|J839P-jtom2{N zJD3!`z^sXkG|1~Vlt6(tE#2hSi?;!G@aZqa=@hBX1=D}?w*CUw75oZV+GN`-fDdI1 z)5B0+-UAD{MvKlN4*StWtaM_}_JJhS{g=Sc-a}LZM7@u}J952nvyePY%S{U?njmBi zgv{fLKz0^cM-fu*G=|)R zM>}&+cqyv(IB%<@?de7UyHl7$5TKlo?DdQhpLkugv@Isr8|%``|GN#|`<8AeOnw9P zS|HYo6BnUii($e}8r1hSxs4Gs&pFK14k&ZhY693SQw8FYm}GQBcuBKQPijVUc<#4b za&y_c@E317DvjM8{65M+c^Du5K7fjS`$SX z{)(h$5)DEL!-kN_YBYysYxQUOIY9~+BG`tewEBxa-r683o>XkaDXr_i4!;=wLW=G} zI`qgV!Y4s?y4u(PVu+E1IU9|6QFrRVbt-3}`s@9zh5yI8Kb9a_6x~F~On4gu-(W|O zIyTyMdeGqZy&i(EbzJR$X(}m<{R}EyJ(U4%6r9(T*dnPhsTBhVIg3z335KenRI!RQ zl?iEg1=$^-%oxjaG{NvHhUADvg}(4~x~3w6&KTg_REXtL?wi=lZ-k~C5<@yEuSQjr zWnoRhnJvndI?<7DOO-P8cKLg2bKw!A_>7y-QX;Uuxw#=xdlAY+iP>t$xwm#9zi7EQ z*%0FVnlQwyz;5Iyrz!<=R|aGVfm7C3zFIV{4dZoSNYoCw4i8HqxazAcb9!R z$6KRdJxg6>(s+6DDZiXEz}$EKFr>tOxUox(W>w!RGQl&B@j@h|I^X6H#d}imiM64g zJPvbc3YVZN%E-Rh@Vkn6NxzmPzyO0&3=E@qYFufI%*Sr$n|2AT#+wv zlah?^)|b0$m0DDOyLz2<(dOr?fuWJt`@`Ixag%_-lH=Fu4)Rn6Ds|12`TMW43P(j) zUWLaK5ge+vIi~iT;3yd{${lLV*jiEpt)Zpoki4%Z;`kfduD#V*6N-`15yy{oc6s-# zns2+lD<&Deljz*Xen2?DZT&fC@Gf&6wIFR`H3fi@+36m9?3d|iBhX@Kngn>jL#d!v zsAJ`Alb&oep#*p0hd!dp&_&=4@q`u9_&q+Tz*5mhZjqBax-_j?fX*vYYatKog8W4Z zCRh|mx>3R(y$#lxJI(GP-Od6!6uPd98PS zxiKK~Dl$jv^9mxs8c1y>5ac1Z6B?US1$-l$;ue#lSGL#x=N^{~Q6Gn}&@Ne1K@5TS z7&S!G9@g79s%5j^Iibs5n(97a@?8 zJ^odvaNG`pBD)|x;^Pf~?K4u$UE(=2BnsS^mR6iNhBj51Y%I2P7-VZkdp`55gfrB_ zPt%@6n`*r16jeEB!383{HpCnFvxm8{dyFyE`a zOd--N+ECh?g`Vl}QOX$Jx0oB3SZ(lX1+5?Vs-Z zh!e=LNAchw9`IEc+~jScpe;13_2b@q%i_xFF6SjT@;s)W|4b8G^uxO<{07DJ|EOl< z|F1z&%-qWA-vgrBh9j~H%GU;0t1)+HZ>ASu+ zRDlO`7eW;Kt~y74kV{4DUQw`^oghX{3qPytByeEQglEjFZWI^V*a3iLo&YO`WyV&3 zlC+SCE{xKi8bK%K9Mt@Sl0L7@%iH?LM_0wkfH|*%lhqd1g`PotPgK){gRSadVMURy zECZ6XOldmYoVe&1I-=~xrAVoMv5}}BPhdogL{3I(+?a@+bt492T+3onnWi7d*v`}q zy}wPgOui$(2n{1ZhGcNNMyyMrG#{Ur<2+B;&@RnO&&;pQ;wYb8NK1SC5VgWs@mjwi zy&-f~NLos@X$aE;cw=1VU`i1t?=VDs9H>G%FQ`W-mQlEL!`LeN(B zsi@+NZMua9v!uw+)SXlR!~%^v-k4PB#OErGBu65|5GnAH9E0cIZslj!l6MBwLK@KY z6bbO)JIS$|h#z@p#gcs|Uw7ph^al;6%A@s38;gtmc>_(BZzaQkCIN*jw9nkocy^nl zi6pMFoBk@JP^F5eF2&+WwOuOwDS^8kKE4M(EY5vz2Kj6K4RBvVYRju%c}9^rI@{W#Q-8=swij{HVi+~@U8_86T}fV#EU(Jqge6KQVr0Ikxv zX=Z0|)9enL`Buaf_#?&iX(vT(g~;ga{Rm9BQE{2o-$su_QW?2OwEkcH%7#umr6$a& z9W}+z?&}$h$tZe4?}iAG7eDPo``;%v8Bdaa-yhv750p^6;O2XZcNbI704!m7zrdTveS5(={n$_L zjw(O0L0*-AyFgDVS>hsT-`ku)=IG~{n!V&;(RGN((Wn1dINx+i`)U@@eB{1pQD|KA5+{>ji zGNVJ59c|}V_+&pQI)bMFgLj~YEu8to9%@tOSz9{`&StmtI17=pk!RRai-YY9D{i&u zdVKg8szpkBj!vS&CE!L3>FsfPtG~L-BHy5F8kMU#e2;GJ?JSdnQn)%^kVsp_wY=Cd zG0?iy4V=BY!7jAfzv@nV&;Ezl31>9ig#47_KtHYaptbbO8{4kB0FcRg?~-~C`@O^` z@Z~N#4OGrscs3tZT}7)XsR)k>##IkA%&gU4*(h=hBxj_&nWeIFZ9_BMTcb#`{neS+BvCY&%o#PshES>hTU3bJ%i!q z?(IEYH_RDxXl}`LsB@%g0 zdt~NXLH9om4XfU62qhBYic3A#fn2-QX?;xbw~58F;+dyLFirPqqHCGcxbcc$Y{F>- z7VCTV&Jh1{n-_K5xUPQywaAThL0#(W$cei(e{7LmK68Jf|C35D{dybyRz+qZ{ZA_W zuL%bd|MjWy&+VU}fuk9~*1^f_-<}_n8jxNn2dH1&D;riWuJwfeMNt7jKxEj0K^BeJ zzX>2sSP@7mlecF^FG(=hC#oA7{LQ4`>sl68RYA*}=h0$UEh>7=q^!$$k7eLJ*DRXQ zS2eY$c?+*HSF&jk60H0_v3%YpGp{_KJh$F9+0Q)>;(33dDK_G?fYf2ML>Oox$SmXa z!FdhDt^vI}ctV)83jM-I?H?XEll|$f{mT{V7@5!u>Cb>&YT6$yn5VEET}CfSn5Xca zIm73uI6Gei`0WM(FF1Ix8w9YybsI(=8u<{A`!EbV*xfsz8c02afXA?%NP(>A;eqwk zfM=%1*BPy5E4Xuhfe%!HyH@qDa*QsrkebLHY{O;p5Zj0yEgvtf+SeGjmuieI^ns^3 zyiIl@^v=hLg7ov_Yqf(H7mSaf;D7Aui+d(K%#-gAtAKP0Ib6 zCB+U{c~*5c$BT-BGBTE{=jQUv7WrzH;)QRo7z z(wZyf*sB@ZdZ_@HQXNVeacT1Td9H=|K~JAq%ZF19!ST8k<`yua(jr$^b{e^I@0Gg+ zD_hsqMi1*z`~F!E=>^G5E5Dj=YZM@+h;9wgsHGWVqLj6LHFu%rV~J*a3OJ%oFiB2z zHJK~RDsnDV$|%Evq~-5cl`2cw)Z^iQu)_vt0_CRXKm?<^JT}uDE1$;gZwJz?HE|Ri zSLdRCy8$8mTm6Jlp3JO~_gY7E%3$A*g)0YUwe1V!F4>)e(Q7#y0x-Rxn0~oI7VK|T zp&BWhmu9wZu06wuoFsWK2lUsaS1!yaO_q`tJ(!0qIMv(5MrZ8m9FR?qW_imuu)2%MP9E z6j<-FoGvP*4EgKsZL6SnqhANwkX4draTlMZW)^eRmbzPe%|%~UC4V12Qtkb)Wy&jvwztv%*eX%r@<$QvaIi{;f%3+2F*na z5`x?()vDDnFo4o^cqC3W=UppjBf_6I%5 z_nv(FmM33)yYa;I?ZG#B zhXnt=FE_k!$Mi+(*BiKw0%rV#4p`H>$;bCiym9T=ALcjihzj(1R~qWRw#EGFrDlS= z*(4*9AcJ=|xm8HdeP>GEBTWZ7PNw|!#G?>t6hlG1l_?fWD3c2FQ7f^^q?kjA7-vY< zB$#7SGST%PFl7stjIm?`Mx3y+Wz|(JehZsY^4J1qDR(>{=_ixS(I!()U^4bf+L$H_ zm`%#_IGGlpFsWsK-HC_E@D#QF#Yt4BW=V&Y{ewU4QaE?vZ9#R=oSWs--xBRcRrFw| zX8pJ?9DqVdiy0aPplcLO$y@M9SwiX*x!;?yZ)$fJ;W`RiNYJbgd+)eOOXJ&8Mpm;x z(@TpG&m20BiS4o(+}QLO1u28JwsVgKR5{V{HCT$4sRdU|n->^e8}!3)vnFbNGd){% z7p)~xTEf*132!RBG?wvbFjqqh^xWlQ+9utg`Uf()Esv0#h+zn(4!K8d*@j#qk7>Zo12k&2yFA zwA2PFb`)T0kG2MrRHvAu+6;MD@@kVk(~F=5bLCSpsYJxp*AS#wtxHe!MGMx%nO2u9 z=8Q%Iuwc3=LSz}yQDLH=3(}kGvp9NMt0EJ(~IB=pZAMry6&TPS`!l;$?v7cMpFCsMw6jrEssJ@y@2l*og(xXa1xEC zW|h{})H|E$v~L1+IC+yBx1J+dA48exc!{$aT%s-{n|~J%oGMRZq-PbuVh>s9ut$&$ zqZT41XQq#ntW>Ia$k}G5&rcAM(x0j{tO^POP*ljVo*BD{qKX!X`eev2_I8D<4mx;P z@h##jYnbOUS3TSKI~+_t`@chn2Ra&a2#&pG?b$}nOfM7~v$KmNZZkC(U$)zRlQ=FS zMyH6A3L8Y_-|#~?A4yQ`4$HY2Pm>`rm68o~j*Lcn4s&?bTj+&cT$-zICO55}Al8h0 zRm6~$qAz&c2ywj>D>>a^jc97(=hl~p$rEK`)_!U2m(Jqi8&J{lDD}EmYFLL0Pq7Tz zo*BCb(wvN&4q0T_ z|J%%n(jx*RH@VlcZJ4^IdAK-LE8hfM(}JpJTJZsm|NkM2Nyw^_>Uv84ExK1OZ35k2nW2E>v2(qr=g!3nMm$hE@fBt_Du3>XX*!*Jnq{ zUYCAxE%j&nfeq|VY17z<0%_GBEI6JhPkaS|Y=wr1=8t3_LOE%u7>OAxSW5`p1y`dU z6gDWC4L_YICbH3QXCSNU}0E=ttIA#$AQTpx%SNzp>&f8{EkZV z?$e)mod`)h-zbKh?ekAai)$qeHzeD>8hc=$K<;Z4WS;0@%ulkM-su}|qW7HQUC4|W zU>7#4gO073;MM?Qd_%bDy=ZyPF|bQPbfJR@Yi=YM(6l4&c;gNN$M9c!Z3yKQK{h$m z$TKwiC_>+h8_vPFsW@XHY|Pu`zschEU_s`1uW6CfQ-wBD%3@tRW9-^5U_kC=AxY*Ry&Jl+gk-989&hwy^o?q^{3P(md` zUNdIdyDDBCEZzvrr-KfJMN!=mppACS<^i~L*U?FJ3Xxzp7CT@!*yE6Y;Aq1{@dsDV ztoaTEErj*6tCJ$d&xbhA=S3fVl_B{CoFtD4Cw3kjTa>bqt||CpFWT?iPFdIF6;Qy% z`k{vJ1AOZ2bSd*3eD+jC$C~Zq%PRSa+PTk3qq*av5sCtL{bk;r{E3(u5DIiU65tM-XMNII~ zZl0NJj{`d>KSx17_0j@;@7OqlR1<1bc#cbcR1;!ql>#j(VX!NbUKUF%3nkugq^5op zZl^jy>Fys1WXR%W2qd#44zDzZ9m+=?ey8FUSeE8A|J86J&lY-;C*F`dnz7N{kcu?N z?@aL#r#?oXmj*8lhMSQzha4>8(4o+gteSPPNWARXj!M&OG_CUYXGfTfVKSUO=2 zQ6mU9qhAH1M8qCIyWde|wx~5_JYh_CbIRm+vV#j#iv(3GP4CB&l;wpY`arZIc4}^m zU2nUVMWa+UO@wrwG}FCmhfES($mSFeDfa4^8{WvQV`~f{eX*q69`3|+=v~o|d*n9;QroH>%}kdnR&7hzCC$JpXDb$MY*^(Z zTB$!NMLOe~N1A}v6rFQTmrl!-H=S{qC8qu+n#mN-$Mx-1$3V+zSelj%8>5bO;Egc& z?P4#;FM=yus?pZlKsyK?O*j7V*mAo_CH<9|8_n*P_wjC zR>S?;@ZQKY@rNd*gpL=bs$C%k>Eo8S$^c0~(v|p~QaZVDF5_U|fNgVG90b)EEVu=K z7RXoi{3Dyo$g~kb6Vu6w>s8@{V(+>4BnltbdES10i}UGn5)6niue2bJ_w6h9&bNDN zCHHG@m-I))H7@K6ML7e;pujR!O41G;j7S>?vwTl&MCjlRVI4D(3mkNxm~vz3vlmK( zoiGDV_D|U1f!oq=SKzKa4mvpbz-`bnH|1|7AP>b~a*)U7bv(o=rorz=$~-l@prFhy zEUwMx79M7%{V@Pg$2B;Neo^bik%t8rj^^aEwL*P>5g+?L2B&FmJZ%~jicgAb)4@fT zrqSQy6Lw3_TVUYAGF*nN&xNLo;`j}V^c88xMH~i4IFTf0b#Kmo%4K6%XJ;1&>iU&2 zjVUzHaik@5(m^YW-R@KGeX9vm3VoN%WM)@1uy50zd0|5_1NWAZ@e^h2;SA3j0M-0= zku`Oa6Bel6!~B@) zi9vRP1X?A+?C;+x&nQLe?~S)c6s74zwyonT)lgMkm`@7o875msnIT3IjjMq#mEx88 zG?M4J2{G8{i6k2f^XohE3PN;q#;c396T{XfR($FNwD2w%fq})HWghLM^qMs+d_+l| z?r#SD0A}hp%!X~%ud$Ur5%%-T!GF%9MvNI0CJ%GW6@f@I zCYvYO29gJo+OJ(^Wc}~K7&FXDO*AHotzA*TPzs9&urN=y2ZsO2+N@oIQ`d%jd(X*Vjz=Sgq~E z2~0h2W_*M6sPwk6C`){-nHaC$OU4#WqAL}4xAaN`czMuvDMezl@9!VNGjck z9cVYs5IKDb7`=g1WiQTrsj!1Hj;dX3Mla;82m@rc;aW83fNd)nOAsf~Ur%9yjsc%pzq)Co*8H=fuxwri zUFYCrGZaA|68WyGKQL!By|Bru$2ILLtuEjKV4JO@u21k}&?~J(4WSlg${Ukw{xEj_ znFXJ~W3*}1T{}kXB;B;Bs#3ysjI^mttbx=8d6UWf?pDqBAbQ9wL9g7MQ_*J0DIW~S zUeNqy9*&|Ad!b{|dmIzCQ&9^QFy@O&k=59VJ=-gVGqr zny5caC99U14iZ6QVZy8{USS<4v#sp}5y#xORnkRZA9?J);#J5o%lO+MK7`dgQ1kis zufSUGuswSD50F~FYeR}wEkiGxNN)cvDbg+&lOW_$vMi7!&@jTW#DdXzZPK_j{0#i` znrtzG^w|Yy2wl-*a0v45SUU#Hzek;s;-S9;%M?nX=!6o@ILfZl16v|W;tN07tHMep zc&pV=8EG+RABghBD43~gUCjg#D61vRWrzULckQop{6n0BsCmkaV`s6R4|Nj;AX+GVKMq_IA&d!E?uUd(kpAhRxr0zF_WM6O~%1?dX^()s_51986 z@*eiW_@9RSva!U&ark&R4Z+?q9^j6OlfTL+c%SJPl=yJ<7!p#~;eH^->sy`W5k{5v zb%;!Wa7TNEa5vQb3p!pCS(`C0h%_%rvsle0gZvJ?QBErO(>KY<}@W$j@sc4Xb}`W6|0-X%E(eBMF7?5!V1+S4&Bdq;Tjx3 zyahJ6j0ERM!^5XWg&y1!^6F*kGkph=+_;1Mu;lvmwMsZnagE3!D~lSF9rd%dOrOtn{0{2epb;3!LM+sb zLNNRL*IJGAj;g4&hwawEJmbamOp7Es0_OY2Q!=vSaZTWSVfsNa3(S}ibm{l_sIu5a zTov6`lGAiHbOEtJ=!KPQUx3(}x(u@zrkj!fYGg$J!{ZHkn z-KpOkggm||_K>-Q8@F}>?#3#k?rp+439n3K3bYv*^w@)fOMYfNII%+odsR@mVSmfV zT3ZkAl?qCem_%+kB_m}O79?Qt)KoZ zzP;1NXmE+PtTjo~^$DyFA8AWk>@_(?I0s;a(f6!Le<$%;0~~bSHYz7LpW~J`RTXR_ zbSv2fJ&om{M~oM~bKRvVDDwDjLzcIG>c(&Ac0MR(R4m*!X?CfOFIj|FsGVwFomo6M z)875#(deQZulWn?f$Vwis2kk;*Jp;YuF$HQ!*)PK%~iF&P}OK@-eRJGe0y~I)(~Z@ z&G(;|wR6nPzxBWMbGF$3iPVYw*QD;BYj;^&2V+Nb6C+Dy2Ll_&?*+W||6TB2rRMJS zkBDI#fO|s+LIML}ECR@ipg0DSq@RI;@vmBm9*`LXWnCuvL@_dEd#3(;=L&OcbIU5{ zGUu}00F}l{NWusppsEErmpK~?>qw~8&($x>?l*vVSb%i?cTmYy+flaXrAC+IWwzR< z>o$QO)cbh9K?S(T^LN>Vr+&ZdzFla*Rr}6BHl7!}E9G++xXt>-AaCnZ*P&{O1!@O=lavpWKa+J??Ja^`8ZlX{; zRoh&k+$cO}y&ybCy>9QqaNM2C!5g~gy}F#|iF$tyYSrN0NNU6s-wys#hXO;r@?0BL z1RR0lNTJbdbSV>*cm#GSJdq;<2J{MCC(!MdGIvUI#D`#i8eK1emYE30hI~-xLlRpJ zd%TGQa2vP2&?FWB?0 zt{_FWDD@KMoJhL_-Gjhaa<#OFVY1%0`r7kU+m^vB4zev^dK8Mv4NOkX$1Q00<}r%v zKu?sWtCQ%{YcN{FmXNXtbB%p8jXshQcWK&2#3icXS}qb>-nUXNnHMv>bO-!Fssfbs z>`q_cEr^uS;jIZfKaw$bNdA8B(4}LJ7BAi6EGpnbTQM5|1xmkw!FpdrJYzuy&}6Jq z!%9F+Sn;%kq_l3*us_o?_K(l9v~Zf;BZ)38tXMRYL?Pgon&Gr#(J#!;=gK!~A@0n)`;G~U*Lm{TWY#2$ z5&z`;oZZq15Ht+iG-e7}_kZUi}{p|x))jk4cJPH(T&2K9_XmYAPyk8BVQu1`ZE7Wtd1nNOr)D8_30AOHdII2Ie|L$!UqFs1 zCrT@?P0GNh^2aptxLmb!PCqg%1%^JOUpC;+LnG@^OO2ww0i+`yPH}XH6b{d?;>AU6 z!nu+97-l0j;xWO7P#Uj4Xe?s0=m-_@o;(kA#vLo_fU!%q%PbRKp_KfHA2w<;Va`B$ zW2NHdH5f^NvTaaQ@EaoAbVAgah*UfAUISFIYbI#^0t^kZN=D=K@x)jvj^bSopYm-} zD&5{`)Q<99)_1`{dV6twmqUO40$}mU?gR_ps%>Y~?p|9JWrLWAwzQI6*XPa%$qB`4 za8%oE8Bky48}fIJ?fmH#vxBxfm3L5I)NA;H`RWGV?QjUT{)pAepg%I!a!V4f~Y zG$*8Jw?jA}d0L%2CB(!(*yUorA=zA&5cQ&$GQb3*uG+0Q6wG(`bSejz-QuBL^3f z;h=sTAmBXvcvKhu6!oEKDKQrUs@C{cum`-guKkF$vEDzY{Dd6OL+bJACO5%d0}pE- zdgh>Q(LC~?y7cRTr*3tl;*4c~%_Idr$|sK>d0_C#+_dd?^D1j>9lW}|4VSPCk|i%X zR)6zN>^-??OwsSFhbrJ)1>!!?pt{5r@ z6xO@F;?WE;t*Qo*+f$~@RYNucKn_k=#AJESN$a|SHH37&>4YU}etuY1Gzp=b9r^W!?jf(%1&@6#%>OjiDZGs1XdAxMh*jl6IF`p#NRjsB`XDvQn z+2nGaH>Gg;Mt|X8Z$m@H6_Hhm^_IU|9~f(3uEF>dy%wFk9EVRVc}}vW_%p#R(svt|}ipkzGIiUs_Vq3%32qwtSX98tAAWpa3DW7i> zm$98JqBj2Qb8K34d;C(AJk<*uWQgFFb~#~k#eO$Cpc zJ&FXFHqHK+-9VX~o#nfo0pfqH3B_+QyJ~Ti3gwt%0moc8V(uaT5@ylW-sHu zCFnbsq)+m?oz9XOo_oi5KVvui9`-9ko`54$Kl-D-VNZd3JLBl?D4&x7Jy`?1J8eh{ zy3#(pjD$4mv4F&{CKZ#nde$cFxn_gnDvKc7Anha@p}OMN`nKD#I`lc~V^NJIh@4kd zHMU_jR_7lIuC-wV%27xwJcb}+!f;fB;xs7kt;+iaqEUj`6ax!_{QyR=mT)2~R3rNq zilGlfoE#F{(6lgKLnOGcQ4Xr&ZEHqUa*^=bNb^2g$zZbL2qi?eVxl>Co zul!I>>2=s`@~KvCY=&sfRmj~A#-v(`JFuC7Tr#cXRc~kwSvjbb22UN8CzL9=r^}lR z-M6YLD3pue)=^E~;agZss=HjqHY}KwmAAbFl`#;UTVT42f_yLFY z{}1>7-$G5L?}m|o81EeHY_0xJy~u^SmJ_xZ=I2m?D*AY{l@#4tE2o6{;A%_(nYjdY z=0KShxp`LMz>q$7lg2o;XJDaw%weg{`2n?mIuHe!jxM z--m;5zF|C@y0A9m=oymV+j%4;GQUlKO~0qw0=h6?TQHxC7qgD?@`75ss4k zzk;6C;PI_CliEgi6iK7NCLGQErR2csF!F5UExV>NZLbdlX3;fWZcy;;m4d z`THMI-R>%H{Y%td*Xdhd+X(2yYO$y9rjiMC^~1D8jLP-Vs1GO`IQUigY`K-*Fxx|D zJlTp;@6WU1$25ZjRA@?|+L>JmoQMA21s2EWVvb;g798I*1cgqnKp5S4)+l_E2r|z+vIcvBNJ8md5 z{}*HD7~DzMwfkh^WMX?_+qP}ncJhyH+qP}nn%K6T3C}$Dd+=7BbDnytc6F`p-PIrZ z%U*l0YyB>E`yN4~aeGC&1xGWFXf}#O*qHi%fMszE&Qp}V;u)D2nY~JUwc+2P@G2s(u){2eaWN+}QntiV zT-1rDunQ##>gi@F*WlDC$_@Y7YVAL=u|{{3QzZJf^OUKW4a(hW@A}H6tz}ByuW~5Z zXMgihTP@y>cYZrYAJRFI!7E_H?wJUWH{gWSFq%88y~w^$Jl%GB>%tQu>j(faM5Nv_ z3XRH`;SEy(SR#Y~91$yk2N~_?eIMd>{~|bIOt>AwNwGT`FRqB2-OjG|i9q?Oo4vn$ z2q3dN7e^n63YRTt(?os+S_{;?R7hp8tDt(PCj8A3)M z(_J*(o*wrFe1|?DaXIKSktGFj`^#jiIP}*2ez-UgpsvgmE+!5QNg(6PsK*;9WE2z?9UFth#3UdhdYpvBa(AuA%WD@Frv3ej zt}<#wx-B-iN?C{POAD+hjKuTzn?@m|a`Hlk0{B0ac3t&aodgUCZY6nyddDpp1O zt;QhIkaJQAsx5z#p&?cY2&l+iq>L@yGA-DV`G%l2coh>R7yObzX4Nw^Y`K}RviKQ2 z0>byF0{rApa(C;ByHwlLu8<-8JNWxW(L>np3%kAA3ci@ml)R33L(3|z66Hi?p=O56 zr8KPbnBd@U54a&`6OlBu=62FX)p@-cYT7RHN!cQjdCU)7FC*S&6Tnn$3tTMN;_Gc% z!C!IW-nFyQ64vpuhi$Z@6^MpgQKnBoZ<#;)y4v!9z?Md^!Qd1{$7`4;WDWX^~?Y_h|$tx}ZbnlSJ z2dvzI5%(a9wxJCmg~#t?l|tLpoqLvA+W`IUhbJ~&1K%#mGeLJT?*P>$r*5^?sFjO_ z$LL(Wv1fgvS9hp^VIqdRSK=$RMAS3G@CT9v%^^>yLV_m62swiel0(Fzlvk>7!2T8K zGPW3z$df@p5oyG`)(XDJ%ZCD7WKJ)>i@Hp z{4c35jtT0wFVnbeL;7WjM2o9rJ}@+KW=b&)jdNm32ywB0Q9o%lGnhdGmqf`{KMmL{UY|d-r^#w4NY6F5wNFH8Snt9w+?@ik_4=ccW~lpR+SZ!A;HrGH zPAa?pV5K_2=>2io-kK`^o3yAxX>GD2?KmH>ZqA5Z?@qS@9&Dg?_PpFA+am4U*zmhT z*HY z+im4NSNexxUBEi0h2ULO8YjV6>}F|Aa@Cyne@tQd8)N9A{Pu-HC=F9u{ zFiXOKC@fuSVW{U@#oOyhA%9kCOv=w;z#~_-s>E7UD$d(ZpDK3}VeK&BDH2(!2%UUR z>HDvhBDaiuMv__hV}usJJc42kSTe7n$%#w>rq)|YOf9=ZB;Sxe2Jm=?f(T4rD3+O82=?G(2d81JCCu@p%j)U*;+{*6JD}+2 z8sHKSV;fzYOGK^r5NRrgr#dpY4_Su>WHRz!w2t$LjIhV(Je9csRu8L51LkEEwv1Cc zx#+1wpXxBRMPuO>fu>~cu)ZzCT1&(dMmof8cFC;#;rU{*X&L#!YHJr0VlRysTTobY zLM3RrVs|&roK-SmqnH|~Yy%QHFgC{Q2H$=}N&L!0bNU$Pa{(nwcfc^-nUdp{aS)xR z7@P9N1Y8I6H7T%NvV5Hm^{%#(&4m62KHD*Z?nz_Pvr1F z9@rT#5HxzoY=4%4L!=fd3t7Pi^cX|W5IJy6GbEh0uul1*Qdpm&tZ2o)jbn0UDx#fO zby6P)N98P0O*UFLwA6u#zt#jnkX-7w@!TBhM~-1Lvn0ZOSFL|OW%ut61+JP-8dTP= zO!{1-x`}a{1T~>@_SRO6w1>qUxqt*`Hyi7kMn{pn;@ROP+Z75Fd=b zh6m+NtOko2fBcM{c;)aRI7kIV<(m#W=7{e8AR@y>g}AQtBq&!G9#~ zHBsm-I%PpeZ5+5j*^L2^?ZyGv-wAhiT|@_buXH9o5+2a0Z?uE=Ua?uJ%s9pIVPcCv zJ6?>tVz(HNh)Ed)ObMytGzg3sogBhol~}=r?C)zNpsaeQG+R2LR#{A?8kq2I!Ybm! zlwRm@7!>zggb6k2P@P2WB0Lw$M5M^-#E?yH)Dy~Bc_f_jdlWv9`&UcgSVxqeTQt>S zVh#Bm2q{P8SQqC+r;8}PQLJ=k8mw=ydWR{_Q)Cmkw0y@Ul52+ZM|e9%&kV0J#8a}B zMTTMK!XryE>(rR8E?jk=*#7|VpX7hddIs3qtyjv(5HmY2iyU0B68_SPT($mioyrW) zC$Au7JU=#j&G?`crla$2K(yf4s>C-g?_P=dlgA~l(w?@_ZPM&_w zN|7eR;zB!T5B^ z2Fml3J3>`hC7laN(~Cc=WAA~J%AthLDs^|;7ETy@eXpAk2NMT9pfX3BQsdQE=xpy= zVgfFyN4dtYe-rm4qLGKnOSh!+&l>S`kD$LoHJ4ZEp3%3PSGA0d?$5A%QYhw#8A zYj8Ns1aoQNlXTrV{(4fGE4t>9W6Kj^YZ+cCCy7#Mg;paQpH5$i77k_EnoCTdmSQ!n_Y^AL+M zPF602`rXMkH<#T+x#;b~!mh5;s)etTDZjQcEYEuG;!JK~sZar`;v<+3FdTa$8rDtq znB)!7Y%`H`?_t;w%1<)5O=uwIP_)~(r|uI3`pHy}K{odwd=B-9a^?mV@K{wCFGDT@ z#Y6Scd}O^`72srPiZT;tieeXR&juS=R=O+`)#sXYAV5uGNkTjmV8TBB24Vn~Qs_VA zcy7$BSxGe)WV(N{2web8bBQ_tPLBneZ;^rbqDjT--)&B6C zJS|hype~OU7F|KHZtkX51v*JEgHo~(fR~FGqSYrvju|qw+x|={4yGmli`Mmz)u%<$ zZ$)@taFXA8l7mv&4F=MU0QRe1_@hUydf4QC!rruySg=S7!w$tZBW&JB1XIv0>akQ= z{Ez{5EfP~Wqm;4nysEKn102ej0DBNT707J^;t;-WNe8UPz~X(w*xAB1x6OdHh>cN! zWQtAVq>lt?GrWVa=B|ZvgpF+PR~lc z_yu;()4TU-8SXV)FIvT$H0FwSfmb_PC+jsHvnXhz>3u|WPjB5}Ba6d3cP1=%F^j`y zX2K~vsmQA`jnw$kB-`NJpVvDv>n>Z=;>;qIbd&vh-J5G+mZL=pEpgUbrtCy7PV&!88knQcP z-RO0Kd8@N+4CU#yf16Pb{n5!CfaC^)&H8#P4$ZGpEn<1_BAUFDC+r`uk*m4RLfWVv^djIgp0~1=;pHzlVQ_~shP+XDYmq@BJ zv_`zHESdeROu<{@rVZJTUP04_at&*jBB~@w4TV9_u1$G$miZBXg4?ZY>f*qHimmhK zree^S>qG?cwWv2IQXpUII1R`u(M4Pn)Q3_cnKTO3hckwft3<5LO2e(xD_4ithZ@%? za}Lxo;rbJcwlI@sxvRqOH#nX9gGmqTHKbs!TD|GENNhl(a)t3hwf1?o!v zZiQkijAb`&80(&+0nJ=9wf;5n7j40cjogfgm=hfyK{(P#rQooSN)Txk|EmIMVOTXw zswt_M8kw5V050Drz z@Ub5)+aNL9AZ1hLT&MqxLvya({~3E$6kfT zoj*FL`9$$P?xv<6pb|`!a)(N*PDIp=tBu(cD1#0NKH&e^GNg6r_53}oG$a0ZTZaE! zsPNA=LD0qduTiq2fTN>(qloryj0`R3K0|3=lmxa}Nfx7C zl;o{mYDbUTWF#0HXQ6mC(|Q5nOL{B_BIf6T3{Dxan_aKGydn3obO6tQI78}AT*u6H zc6p>@Wm0~Y9Dr4>q6AaysN`?$i}EzikYS#Td(VKS(h@hBYG_)jX^_4WiYc^3Mng)z z`ZnjWK8G{x86Z5p`^x<;8a7nKiT_G8D>EK~Xj&@HtVmupG#Zr?^a5b*} z0yLN=lURE;OSbX67E7on2he8DF7^M+fA<8>r^&xG{aZAG%v58t8UmX^=Nl$P5PXC`68LuS6;zQ zb)WFgw4Zp-;=Zo%c^`oyE`@V>8%E_a7R3;mOn;f1Z%v#nQ*3P8|r_ zlHO^Puo-05?Ds@uLb4^crw_=mu(9|kP?b0;jShO)mN+nNWylqtvyajh>}y*+Go62Z z*48dlruWMP>P?|EwxwU8I}K@Pw$R^m>t@+s>T;A9^?CA3w2*dP8`y@&i2pV_?JC9ndz{1KrbvBH3le{^ib{n184TR-d}ur`Ta ztJzU-mjHuCtw(J>)gWbrZPdI~za6ulB278J!5}3+Q($bziF`3#731aMU3{cc zIdK|;=i3GnLVrfKUy@V5SsP+*#Zo|&$T%xGnVm)fn~#9+EI2t)OFq}kx@^lxhuWwj z6rN|IXbBTA19mEj5^i&SkGhpvR}0J90toiv^AKb9f~7!pOR7wQxm~SJLWGMm_2rFh z(eLVPnsj6C;Z2t!!*pXyG%Kq4i}SRnV?kN0QrguxS=Se{{mO)`J7sAtxmmVRjjHI< z88d+dm)F4t6q~5l9N^^ASwD@q7&Fa~=pxuL4~>n*A`6b3>~F77{47Dans|_F{na<4 zHO;f3qdUaJTy(4HI^b98S?OyO*LO{^OZK13u>lLB0vNpTuT--2EYg^^j<93gb&Vdf zx!6`#Ml!U~Pc1GF!pt8l(aAASk1k}+;?erkh6AoA^x+o1AYivYWzp=SUQ9*R$3O6^ zhTPpco|TI_h8jV6zg-^T-~@(PskS) zT5XBX5BY!K5Mz`bfXiBYY+OoP_Q75Z(7Up+0*{J-QYw}%C7N3uM6cx}q5s>!vaSaf8)Y+7WT=LjyARFGSca7{CE3`>myNTP8seOD8D&2+Bk3Xz`DFTnPu1;e zhxZv8M-C@Ow!68}oo@rAl+gOs>}U2DS;jUOTuIpmobTICuy!O$q<~Y#WuaHO(j^;r za$23+MA|J!7)g1!^Va^A;V(9EJALhBm1|g){tlp<$oZO|oS*hnrS!4rLX~9j%pX!Orta4G$hAnVT2eV=)F`rD5K{snfkl*I|$1v49c zh^-wp+${H_N7>7Wa4pw%Su;|orOLI8dk_rL_#*nRRS#>K8K&-BcEsp9I2wuPn|)>T zTEP+;|3fSByHfSt0}>9GrhlCf9$IQ zoAgTa!G&$~;dTRu_Y-Ew31I!?!$rtNY=s!YHB{rjMDzS%NT>8wwTh1Lenu65_Vo#d z;q?)Ss4<6jaj;%KTxlyy!tm}bF%-&VbLFU=>qX&s9o;&-A?jF{$AJ&jjaWaQ3EspV zKcZ=MLh*`!2xzUak*t*@)rxEFkQ2zg6PQbcLEO=~`&sabvMB#br$;o%;xdl85@MGu zapP(3OFFOPiFciLgh8k^%=*g=b8m#wm?@ZgzztA{7j5D4AYjBD9N`~52xbB}jQUWT z!SBl+PqmDi3|%(HPp~*t23ND*)n=|d`>E8S3t42;J@{mo5qdYZKY!?Rz2gkbxb+4f z8;TO{bww(rEFdrJ1A)FgHe4qED5|QSEc;!(HLhFpHK^iCkxqMl`x<5@+69C0_SZ}` zrju=$Qtp-lWSgK`_9ve-WJ!~u*wOQVUyT8HtT z*O#!H`dBwqTg#Pn-9L^?6QdL6Pnq2c3v0|`YP9y}9dHNjb1PW~)8LH{)n=P3jUD~( z)Vn<&b(250FenVmLsr4MQ8fD}z6C7(av)c58KpQ~-+MpPUvH7QF7eJ{n;m29C1^hL z>}p@C370K!nH?p#E?@tg_1e38v!`JN{@9}W_WW}KL;V{dsT2|heMWs=8cl4DEQ-{9 z=&3c>mha*lymAn+{JEqX>#6lp_LstSx~FsUME=v+H*jU=^oh;=)3vsD?ZWQv4HvIF zJ3|%@(2>j={>&QnoS54%Hyaj(n5-heWR6dS$xuX1$RhlA2RpVy&_L*j(Nu2{<^^v) zkt^tlreS`Q540sU?2Io{@LmpAJl_5Y z_TUK;^DQbkKB4e1HtCvZgIikkOkpA>$v|IU-ZklmKw+4p>y?Xt7uT~A+z>gtWN;{f z<{S|H#1lKsXRO096?2G>;L#&xn@_aq{H!_f=LgCRdW?Nf952KL4D1%zyA&)gP!Y2; z!fy<9KITirfuS@WL#yIR4c8-bBN4IkSNcDM$)}ZFM-}r&^xX9k1{h)liJL z!YQbRueD-RAIEY?q8iA->?shC;T20R3u1g?PDcih)wvVJ8!@{p&p-~u4@pCZX)udU z6+;=~$sod%$uj>YtWQgcBv~Z<@~1_cY_>+U2k#Lz)(Ql|nQN$?SCoX^y28Ya1(Pdy zs2i~Q8ap&%K61u$)F3Jdmafle7{cr86Uu=Eb5@S*n?nF~W{8=0z>vHb8hhBv z*7sYTDM80GIX;= zn5Ed+w4mK;8a~}5|Fchvbx^COAgwKfbC|`M1*8cbF+C)f+JI(HB_@DMOl7B`F&V@S7YkAJks!K&&NBRMQE zy}L%6kC;m#MC;b5jrkdADtf=L_z+>Owp>Zneko)y;+5_RrB?z{!TY>P> zuPbIA1Mo`;^A!a5jC%vJLlM%PGNsoQ_|ulf&i2QGvZf5!JooBmW?IbD`Q+Dj7$@r< zR;Og85i$>$xaDc4ABsMA^t>R0C8v3cUt#7d3~nW91oIK-ZWxCMGgsQeQk)v*l!Xns z{JdakoJcOp1o$q>GE3+OEy5JkALYN4oK}SW9t0?~pbvsv1wLUXSW)L65U21ZN~>p} zykhMHz0fA*=g6ZLx^;bpx`!wXPnHNY6;}3bg90Kh{atah6jczQ=iJE784!`|gk3^e zf<`>KAYY%I7NJUzzwF~`oT!1;AWkDTLkLl6TqA^7Pvz#S&{l%2na4xw`wMngcUNnc zLkjv05xgl{^VLNHW##Q^p3AuUIiu04E`W3q0Qve3^e8`pYXS6-T{mEn4tA*XANq)1 z`7jdO%3@8lRe!6m^*#3WjbG;&HC86m9KdQWIyKim`Z$<($r~1g)DO7EyEg-BJz@lR z)VAFxWs)C$=fe-qc)KS1V46g_1+e=j=Sa1EcDf=_y`mdKzH@MQOq|5JrJnRY{2u{$ z$h`&VLz#~WfJj|*y9KWO70B7vAQB&{hM^nb_}A_-#G5cozmo{JVaYp)d1_rGEBQg& zI6>{mFK`R<-VdT+^B-O5Jhcc%CYYbtUGoCKTBRour?>z#vxs_fHAWbU+h<*PW*# z{9unl^alNsbn~%uJwKtgn3dqLvP@mE6c!lb4>DC22UyJezF;b(aFI27w(FULdSuDo zkpO8HO-s>JF}76~yJ-!(=&^7a<~K^xYKfIlm@yi#waj9F+jS6m2CZmmjlA8MKcx-( zO$bc#>1h*&n|^vTjaV5|G*37GSJ>ADR zLmM1snvUZTKH(8nGSeiu7$SO>-njCzO+9k;@gByuX`3@M&HVwP%se`NM+zs8xlbo% z)D-k%a84g?@sX(eL_w30Nle5kTbqZQUrLaJ_VRFl8DbbMr%a8YQ$*w;i`(uD2<)jV z(X0wSJ;NL??8})R{c1iAm61=*oj@s=I@qL$x7)(B#^BtE6Y~s8lhBN@zgT@d7HAy$ z2)~fDN4`gZdRLkji$T!^7EHw1rw-`sn4QLooS7N55f-W>ECm9llQU)^0(aEn$f1M& zoLhSO8&cDC41EIjh@)y5%}WipFwzt)G(zJ{s40VH4v<7UV}qe3Y=tFAsc9%I6>Xj# z5wl=LfE=P3nRu>Z>m-a@>_W-8O|c>4BseVes9?5V~t`<<_K|=9=8-( za~xk6+9dcx=&?Seo>CJHYJdFJVRSXR0CDowr;EjFl$X*qibt7|v-zTtJZq5qy6-Fg zPY4v^2rhCKLXT0cYo?$}+CBZ|5l?-Z3}!Wb0djVD=g|r{RnREm0T*h%S6X$!cKNE% zmwZkIUli>|`R?st65ZiJxL*#W32vd(^BiEr3=X;z2Sjf2sSF5f1Z)0|lJo9%+*@|| zE3uOhItheehasXK(|bLt9rlQlb3Ac_{+(wgiGCWd%hRYc*umldmW>C zcxSPfJ(8YtzoY1C3b!ma)fY3c$|d~aXNYwap2y;;>>Cn?{xWGDcB(Ur2VX=X>K2P zg?_1^TGOgZs|Um82vvy^qD$JZWGh{qLqVYA>%1D6Ya>`rG8Qvg zox#>?tS*_Os-Aj*2?st zQDfD!7MzKdr$WSNWeK%9Bh$p9IX&7B_kHg5i8$eMJ~=4q_pnJi&j?<}3_4z%&E=FY;Mr~O%M?ULSs&wO<1lS61x|*%=pGVspdJ%c*t2DpDn8RU0z6(% z6$X+$>iJI+5DTWBKwYiyII18{Ctxs*Nn={7YgSIq)+BNLwy5`jH6MMt#0YhBep^&J zvd^CWOmSWyPfQ2AwJ_N@Qr=xgrtDELC^QbLrP8sxB8NJaGx@L`olpJ_OTjtjr=5@g zyiQEi8GMp~(-3mT3}9zbEGs9sG)ypPFh(_*giIc@#GTEv;7G0$Q$#(msJ&qsilhL1uILF|~`gy)g( z_`7mWmtOE;cZD`@Udb555}~_tb-a*eHg}2PJynGmZw2clvSsH-MTZV=$#uM*QtYI! z0^J1JV&^@D(6}9@&!47vx?F~mNwaA8dv~M!4>zNFuYU6cI;`w_G11hI`uKQ02G;Rh zOto>gD1kpzMyXy4?Bu>Sn>4;gUJ75!0LdOBFR30YZmRE5fbQ2gKqH6Qr$8Q^%4EM5 zQ@$m=)aw`{*+y0wn5k+cEpbWRiSmb&KP6LYnZq&T-+Z8&G_Cp+*|MNrK_z3QEX=(- z!}?lPX)3T{y-RK>ZAbVUmu1OIVkx~>;ptd{W%|DIOclc$77z1bQQ4|K!=PFjR`sWM zXoiuEvQzbyWsXZ{h8>UJ7sg1e;g^Gog|`w-eNXjFYmU-nmD(cM@`YvbQ%lDjTp8Mi zLgi&##~7^&e&cB6lWTRvnv+UqxA3sSL(4{L8JuTe$KtiJj%(_9%e!)Hw*tu(l}c{6 zh>q!v0>yit{qQQpJT=n9 z$~oRn=Xnpc;)|Kaxj%KUM;tz_Bh7RPEa3c>i5TK$`tGebJ+yQJ%!5|#Xm9BSA26;m z!FH#6WHwD~#5uiUw?HvMyK5zGgQi!K3!G8Z66yWOnOE1Lvngr^6w!x&vM>vrJSqE! z{WGBDx3CjfcJY}?hMQ8d52=b)LWz0Vh*!vOkLGnv$)oLaI6J*+7ue~1y?b6NiONmy z<0nJ7PqI8pr`E8!+E?v|Joe1(p-mJg{;I`>;ObU~5iRxVhMYo@N7m1bfn!kzw$Bjv z`p#S0&+3pCehAt}91qxVdPk%(&)tIG)!zn1+b=&pV|^moUUTMqW&W7= z+-SXRWsCfk+LZF0w*n$>*tfs5`ff;ih#txKfjg$z_{qS&8<#wLvUU;qn~bj&8_=4)>3~6UK-LUVR&+6mI`v z-J~?38zla1i*Tg-chyFP|F{tLZv=|OLUxXhCPvP7jJi8!VN4!Ak{ous|z4Vtr)FU5mM4B_ol@WD``mkMbwk6 z${(=D6nwwr+@m>8WSOcG#Q8gU7Idr=4>9JIC_t}tVG0OopZ**H#N=jbi~a7 zzmY#TSbb0AWTr)g(qN7XIYL8}OmC4wgvwQgc#biBnfOa?BBKa8{ns7JGyH`__LMC_ zqf}MaN(%43hEzp-ftNDf8Nd4x<^;iwZI&(}nLKulWxg*g`RZG^ zP)o|2X1uw*a$Xw(3NT6%D6Yn?t(O(t&)m}CG zQMFa*L#&`{m^y||!Ra;+WsJBtjn~+ut?)HbFGUOczRUn&V9>`YB6&U>F8Qo5lT4Uw z)QOUc!Za+k_dlX1;R0kw{Eo%*`PX_`Y5!>Vwt?%Q7~h7OYAI<*aC9KrG}*W$UBl`1 z+RoiUg?gf$9=apR3dk}pU93`;HZgYjO$fT*Rd@>*{mMT#Ej?zwSQL@iVsy_>6}R@V zgiN4XGQOn;{{2X*?2(zPcj&@?Q=vYA+ggNOX09H|_Dp)l=-fm*IcL2TrDO&0$N*D) zkPCvF&XckL92ev@XMv*X;xmd$&}??;_Z&WhSvO9CRe`@f8f5R3_Z&KG^ozdTH3B=^ z^~DPIAVBsC_s(*Ym%0yUxgTZyDM^0__|c;Y32}-oz%p(L`6(>N$3sQ5gp3fMyBEGF z-G^PC?MJ70ndz51A_0m=$nKxTRdgmo6MeB7BmPS*O`U?e3Q33@ZB&84+ByZ#%NkX| z8id&J881AoRjuGE$SZ96_fGs0-Rya)+0rFAn$_5o6Sv1Bdidet{P2?Kss1qS^ zOooWq9^QSSO2}Fv3Sk2|;izXShkBB*D}=LQ%$$rMR`@BX3+amRFtN-(POo4E3e5Ot zL?;t+;O@rU^gVo2C! zm~E8Ngte7Y3riMN@e2;h9ayuew%OH6V*ydB*>saMp|~dZI+s#L)xs`c=Z3!Ze9`+B z9X9CPh9Bc2mZ^_N%*zs57D?h6e5R2|`6U5uf{(So*D+iptybx34$|8E-}lk*BJJ+T zsy|73Qim<`obd`@9y1$oUdoGKkni^xRP&<|@E`f+awsy#+#)so$k_QS1<~k5H8HVi zH2xWzX^tl`moq7sBKCE8@e`h7Jgm`=hoX04qzat4%6`H7VZ>Qymc3HMtWtt-W1F^J zM;RLz&+fWKMNKKcnZwbqsSTO!a^|^HpOl$g^OSfyPw6P|^*khg_YTwCet`T-r%^gE z`0E!q5KuYXzgwREbEo8gmZyIdG5^2Ty$vVi70hqkiylp52*Ly~M~8Dmi57W~;U7ku z>=r1E>%|mix3>W; zyUUezV}U>Ny2|wNMD6RH+M9EL)N?ZU@bUg5^-lr(j@fPMZ;$0EIqtqW2K72pBo75S zIjnGJf>f$QsqidYIa>)F`o~MWg)viCv*@h&RyTT3#baUJ*2$FqT`as~o)iXKbx~d! zo(=R=l`#w`0;@7#w~1w&Lb}{DHfkr$)@h5t!$;PM4I$IV1R%PX@iBVmnB}7c&&4|; zy*fsc1#x^+aavkGc_wG7c{7c-`RPvxXePmR-mR7?BI4pw2H7*A*mSll-I0iRPA_we zCl5bMgoOBz=+5-0&RpsRZLHN&^vIBAB9FLzeRNnRX7~gy_+%%e5SFS~lX9~seSgA> zJlpgxoipc+MAPuSul0%h#ir@IJ7GQ1+2o+}BpVcn`xXOK7>zAjbuIv_qTU3zs3C}{ zgp-0;p%%tM<2#MfI(3rNfL6oU*_KKR`Q4?YS!4YiMF#$|`Hmps=Ili1`epn%olD(56A3h4xB9F~pg#E=A?9UX04*dM(Ld zhxZDP`GI#dWf<1Z1hMbw&B!DAE{jP7m{)aU5*W1c0PK1)Dt9B%>mjT1`qp((oD>k4 zmwl~rJ{KFjnsR5lES$XUiInLWmY#}lWCw4ihW!v+DOM!6dTZ>|(Wt5Bl`vhpKp<^#7R3J-Ae=Ck{$TAXdKUfYYVLiMyg+^M1y zNF9w+kL-m;=kf8!=;Ys~<-+xdln(9t75yt|=OqH|83*oeCO!Q`MT|pY7oF>&MQxJh zF0iFp*uIwT-|R)ghs<7UZmT?nF}UBC5-x6ZTXdn_t$X?|uV*5BwtbFS>Z12hKUWW^ zO4CMU8Ay244!?Iv$TO{_2!i9NeJv@z<*Wgl4|e%9aCS zXT5WKw-2WE_CP|61M|laU*$#kT$wIAfFq|?-;z;k9B^NX8lA86vuTiU5AU+a&Oy)S zR+Hk7xsvP#>ax45iIA$BJ9U~Hhl!+exCf?pJwk@tsqxAcG%7ChzZBi2srj;FiB>w~ zm#FMUvRMD*mis7D9WrbxN!6waMa7GlCD|}#=1J$EjLVq)FsZUOWhxk+Q!!$5Hij1# ztJLr?vtfm3LmZ@}Z-R6+80~_+c3{dRsU%V{R`ZWo7AUWJ0XE8#C2|%m;4(JOqYV4f z=CH~frfxs^&4dXtHNjzu3?`*h`RdH$`?*Bak<&gO*oIBXd^DxD^CCpG$OZ2T91k(_9}j({>E!$y|Gk9Q#eZI?B91(EX@t z&PyLgA5xcIHi|=Q-G2fsV1uga5V5g9Ol})4CBF&Yn%5B*BqqOMo}(te5q=LOB|N4WcNrMxzZi|^n{BvA=*u58R zE~(Kx!ewdz^&%^n3ylwCRs>+S7nvRU9e2zd=yyS#qyb7N)FeyJG8X_9V3Dv+ipePg zhmRJAipzr3P!vQ>K_DeLmhj)gQ=$pFviERk$cVu*NQ}|53-c|C<`#+SD@7}5%V@Qx znZdLqdPkirMYYbwB`HoEb2mgfoA~72HxMwI6DuD0C;3a}eD{n#ZW;0%QG1?Pw&-7_ z?C;H>^HkEFl0eUXgVexQ!+46Lpv|p6)TyS|$))XvffQ^7c*K*$-^~%1eG0dOKGFaEDDJNbr(i0BGfDNT{;nuiib9zQ^F+pV@sI<_h~-!~!x$>s zYipQdp$;Nf@O%ztwmm}44xWrsC%9I2Si4ai)dg9=9?r5nr}H~=?gCS&7Um3r*HW9_ z10Bvuc;hpn?FF2;Y#vd?x9*l(+Zvz;KyO04^J{UMba7jyzRX$0J93bFR9r zBVaG@m}n0(0r_zDn4Kp>jl7*&IbR?c{uWd19QwW#EA}`Yg2shV+(VBmmJ80s9J;o` zO&2bTVN>=d(R}1$mA`aNwo3r!gH&WqOW9y2|Iiy9O?D3wS3h<^;u(x{uqOaM>^$$0e8(_-U?Nuw|xB zTd{UdUT-W$74r{k0)r7XjfL_HBO(mTk*hZ-!z>k`_Hr(yb8^nGb6z=r6fR(nVxG3& zY_(deUa}tm_BP);PjWo3Z?c?Twz^#J4lRJ3?sOSg_ei!s^MOhu35*2CwcqLOxRQ4X zF=WP_YnTM=bBf!qQS9g_`tk9Oufh`MRWW3szQk8St-jo6r;w$-i;Zn>c;&8KNZ85w zO+TRw4w|Ca(4gaFG4jINjFa^BL~#HwWQN{{5I?BvTDC3fwLa53!A+4ZD<-Bb{m;>_lOQ!0`vga=SwFwvXtqxRIkuf$9e2zZL83{`nYK* z3}9-Sm$ryfHg=IZ$hjIBah9> z;WO;WG-`~=+pWuUz9g&b2FxTz$<)XQkAbTGq_np(Of%&DpPgW9)v~~>vq+sSWL1RQ z6zaVexEVs<)(kUyvtWSay^5s2T*&!kOUB}1BdQKgjMW!R$@PQ!B)o_-Dxvu%%M)yk zgWoPqZAn29LL+7-~ zZQk-y4AtjwT=uXMp*%@^zu8|%MeS(wKb$2h8-Ew zLxlu9IUjg~f;(&ved%0HIIzP@_;#^mqL{X~OCP=`<#YCg6~ly2YQI!vj>DU3bX6-q zyE&g=j6QLbZsX%>qRWzgbk-IIHrBOEINMFqxo-I1^>P^WTtEX)?v=KnC9q*RlaMMAs zo#=B`)v@59rk1v`<;aFCWwQKLN2%2)Zp{i35kTM#ux@vc%)QB2&Ujxs?+Qfy560dx zx{`3)8cwHU+h)hM-LY-kcE`4D+xCua+qTomn{(dre)o>^-E+s;KWfx?s`lQ0s^)su znrqF;af6=ey5qdn<=4Y`L$<8FGv8v@4P?u81Gi-i;nTIBTx5voEUvLE^eV=<@!))Y zs>;Q1Wg$*f7HxLxG}bB!Ge`MGnr!i!BBd2W`mnDxNV7s9WLli%>6~vBfAWku&%Z~p3zDN@?99k@Ci}J@ZZb;&_KH{Z0 z8}|f#RXrZc1(9%L9kyq^k2frOK%b>$wq0SQM($9-8f^sLp&7Hb1ZU_eI0ucin5Gb_8^Op zKKT*AT<0<{W|~;$<+XDujI+*%Cx?xF)~NEBlXBD^Wz-R6%JH8^XTU34LSyWPUb)2I z>4HbFHadK&yE}VLAKvE) z`%b}q*~4JQ>5X11IBT%XfxOK>i#U{E5B6$${CpunV3mhAl=Jz~o-AH1a|@D&W+N<{ zES_fNmQ!*o%2(yZ-Tj9JTbFl=x~Jtu-DAqbWi-U^-Hb8g*_(1kR;dP7zZh7hm{=3< zV8>bAR{A7qz*om*0x7tYNCflaV7$wUWnes|ciS|iv`1`6aIM`~0K9ilTDX+KKOJVP7e5~~a zD}c|4Nd?5K6qB7FqX9GuG|dwCx4DfFh6?a_@ixP(W%%nw_7}0Vv76hql5bp3zjb#I zPl=w!lvl`G^m@3%?O#dolIV8+eDLBW@D1+Y`P#{K2a;P2vKvti=&w`b)Gh9bXM~qn zuiN!DBTwH?(_;t3Oz{SLKU7YTfyLT?W)qTgPUZNn=lv1zM9rb9^g=eZN<{9OuyKTfy9o@f4|g*OZ-So8~U-5~pJ zwLe&tlFIu|UVF=-HE@kL?k;0l%4fbYtoZfMI!dK=#Jw&!5YX5ET1WZMhl+&1rB3y2 zjN}~5Z48ZBnE!RyrAgV_N>LewuLl3Q%h}cv7dH{|r{JIHAI4TvxT-&F1r;xnZ8b8?OEs~<^BErXd~ z)(taiM`^;Q(nX#D9qRi@KNH}u{aA7&^pJq014Zu5pv?9}>DAw+Acxwv>hV z7ztm`$xk%Qtfu|#oke&a)yL#FJJC&uj&- z0W?Q^q3>fU6lAZ1R5`Fw7g_up1;>D(V*n%G(>;B!fK38htyfZswXt?WN`U{6v_j26 z`0qNn6y4=SwP7TPgrriqn8j6DxGC_J4Sck(ihr+V3I^H3s4wHG5<_akl_IJq*cqljk0OezdNjP^ zaEnrX&IYV_9?sA-E4-m`1;MH776lo@o}W;g_x6vcGU5q5S)_+sRW~#xy*?%CiG)>} ze+r`r ztRZWR?Uc&1G#*~Qh}>mJt4ul9uXhgrI2ZHx!5hHcmU?((z-v#7aFBc zLJbtBQgrf`pJ9~~_*uCOBW~x$B z#1`)H_ilgmg~s8)B}hh)(0CT2q{BYnNI84pVC2-{piEf>++Gb=<=}TuZ&v5l5drgX z)){8%-O-D=X#?I$NYh%(U;00|?m*WU1o;E>p?o~UaeSb3brw!SwAD2~P%Se8R9HqT zMQngPE5POPu4?}TkAyFBz}a`|`z@J$1j`5kb7dQrqT3Gi&J2V`!dMS=kpTu~LPB@0 z#PlTF_vTaS{+zSk;o&o{>6g=))ekW1&RB(Db`#VMNa@D5y!rbtvcZ61yW^XHMioca z@tHA}+*mcwhDCB*TF@FEF{nbvl6!^gj=YFO*60yZ+9#naR6N%&zOPuYXjb)sT*yVR z3X+W%nI%q3aZeawGO0(aukHHe_+mt|e#%e>u*Sy>GtM6O)>Vv~ic|!0)Pm6Zp|6Uq zHrf1z{zp;XTNcD_?c2f94eEc(4LSeg-0&ZAdjA?hvJ^CJkpxgagSB1ah%kPk-r6)3 zDR(^Olg&L46*eJ8{jd^rGiz=QVi~8U4R|Z@Lcp`=?0PlW^Sw#In4VD36qgFUw>!$T zoqC-zo_f~B?*Uc=Y(kjG5QeD}ItWgjrp6FOX2=)XNosyUx;qs%Me&QEwAAHR`FhgE zG{$ct%u7A~c+?{p;uSdUmE@dwA!IJ(4RUvluyIxBUa}k`Av#Q_G-j8_BPjG1 zXe=%jvrYOg0X>AlvuByjU5@?<1A_b`K|{T|*N41o3p{*-KPlQJcso)BD zCU6_5+$?Q0dEbFqa^cLoa}X>Aw zw|H5sAOHd)A^>_0eipfZvlju+$!XyX_FhTH`v%Vbru*l3Ytu+m>Q^4){x8yw=dF9L zX53OrdJ}|el33r)>DmHu`b2bx$P{i&f49ltrT@~#4vV4xB zWH|DkKjwW7Yv*fmq~6U0Hh-z{Dq(PBIEu=w=<&%Y8$!$6+vz;+N8+1e9;gr-s#(K$ zVi~A2Va_^e7)ZsC)So)BGGU5aF0BlWzzNAlH72H9&o?FZI+Z*$X4h$8fnyX-U4%~A zxlW9nc;21rZ(b}1D>By;B}F)`1Zxo+U`92()^QEkiSSUyJHK5gng=HuK9hNuJppC zx_Q0Ls0}503c@#$-TUKnRmTsV8j9-foUuwc({eDg0kf5_`6dc^bpjHX zPO3|5lXkLf9BS++*`oT0UxOkHh)^$v_>52NoxtVBr^j4iwFPLjKDYAKQ z+2tEm1!E-Lg{580P_9}XB=5d@hbVKkM_*d%?{{g1-CVZn8f|BsOKUyO=T#-cQ)fiu z?V0aA_=1bKR$EdhTrfVBo2qx68hq8#vuM=of}qxJ(tYRb$HUlATLAaqAx)E-9pEj6 z8`i1!+i3rY*1{d_OjY`TXOzxqWBi+85wFr6MqYyxwL8v(NIn%i3>4vUq$%s*l9W`Z z;DLzk4!34v3YvsS0L}ae2~}4Z=t=In{&obOMe8Ud%|_%^4~KuVFC%+thI+6@{qfv6 zHr_JwNA05pF-S*CUPYl&dL}(haB#iNU2HnhN}J)I#V9gOv`mp?v#t z;tdt@Wj9RKS#N0>soUk9$M*^r=%OLt{R#qtGQka+71nQ5K-fe9 z;6WL}Oz$v1?IP{n$FuB{SmKh2cSi`?^#97+gZ{_DxaeSb>8C+`c2V6AZd3B{cQ8`P z{M{N`8ujdJdA5+GuC3;#-3nDXe4X*(Wr>hW>Y-`3)#K$a7|#sb2{PD`zCR-c3sP;) zYrI(SVEz?Z(I|JQ>%6p9#f@y9i+YRHD(+Smk2d+L9bw5Cq%0VA@|NSdUKTg1=#Tv0 zZ}1rHNnbnx-)wo?l-9}s?M2)x{oZ3nghwUJSjm!BhNC{TQN6}MbZh+(BiRQC*Kz+s zd@ay)@os*)mXZ;#1ZCwLP|1)=8y5DM8N&E^7Oj;bW~wf1wu^kmST3-|4LJIvk$9q} z6lP`d@qOdTvmp;y9i~uY2F%ElM(kRL;ojcMHJ)Eu_OCR!kTyYUH5L<#1hjX zis{Gf27tbqk2{o-EFvmZzRs`Y;~!XDYAfS6&`IRm93jH5ua}e&Wjd6(8oWH^%sn>y z<#Z@8U>SkJI=^m1{IM-=q7Xopd>yr5$0!$5JodAlP{tXelH9`HhHHNehmDL2KZ0Bm z)yUPB2){V9(vY7VHrnFmXN88zX{*c1FUi*Te-htv6(R4SJ28)F9gA75PGi=tE#aa02p}v)ZvyG{-q_dNg{{PGl zR4Gf^Vk@J3+E~RH4u>HduHPwlK$l{hljTR!JBIWJmKDuI?B5 z0sE_5P&)rWLORQjlVei?hLnet8w9T7-(%|yMn&qlqTJ~)Je~~~18F++?0L^}{I*fq za2)3Q_*~=xDqzPK1tveVqYSme;5|r$T;L zJ+M=OOBfTj3dw;o(8%qwP?D-@HB%}tHq6PHfDEPZTdFiv)t+=gZ!(yK7{Q49EYs%a zFj*`1)aqU4tNpbz%}Eu^?=;jHwW?vhT1ss;F2X1~!Om&S67IN3@YklV5=v^CJ;_Ug z%F?6n_o+-7K&veN2yI9~Nph93sjWSI46Vsxv2a3bateE%WqI*PyMWugL$v4ug=M)6 z2Q~H5H`2jD7SR!X0Jnx+y`+=SuF!WUhe^3fq0MaVbwO8YRqWYelEuZ$(0J?6ZBA$O z7GjBcS&Qk#4)||dW+hQ=oa2UkHkhn%96Qev0el?uYX%BL4QJDsV4qzRGo&b0yJ2ND zBlXD-OvMrmlr@*)Sk0VuoOO27wWjjnoWnjo;R}b~Y@xB_sx>s7LB`qEKNW+H(9PANFrs%@!gPkUK<<%f^i=c=Y)?OV zBYID}o_2d0buHTrD$``D&YD8_=i@sQK>gtEXSd9mL2Bx3#XX!apWI3-h&-wk7_63| z2LyD!0z2nUj-JJ*c(hpb`91*LAkngMnETZ1;9%E+URP}+Y*MLA^y0@9+(Ia2T)XPr z$6eYlo!G#`rxe~veR&;b9!mPz4A9yA-R;ZG{{AG0x)>+Jy)F#Abh0OwFSPXpU#9C0 z;ij#v6{&JUV=)3Si=bX5GZR??R-y^7QUq8+1m=fK0xY>;RZ=6Gd&ejxh32W%8S2P97l6`R-K6DG_jOxkcly z?1-}TjrUt*;hBcrPTUOXr^z#Pc_2R^AEaUc;ilI~ggSb$l1+-2%}y-UPj(jyo;2Rk z$!^?v!De!r+}(@&HKc$`KAVl96rJ6)lU|iU3n!jnZ;!cn7MC%WmTXxKhllWDA!c2+ zudnjOFNH^$f=+T-7%XgKOzRoMVW{5V%aD#+eja>FPO{RTk2vcRZ{& zt+4;jAez6mTmO9)A^snuosyY@v9XA`so6IR>iBPPPU%`!QyIetu81bcK)=x;0%moC zn!X6waE$>xf$_DCg8pde!%mg}-rc3rqtu(F6p8VfXyY*wDG3ZAQc8j5>f4y;9klJv(tg(ZOwvZKhK{ z=fO}Sw_5K&+FO5U1YK&KlO-Mnp#Zokpjp|@X*_KfJv>--DD*1l9K=gZYTPLr%581U z6oeA|l0%4q*+ye1Y;Vt;o3_Ec(%K6t`uXcQxeVt6D0g;(a zz0_d}uhDTFIAne8dP;r<-4VJtDSA7v8~ikzigPGw1>w#w)?I)Th{ssn%ns_Jph{j95tloiXe3y3zdv`s7^?QGrCU9bP4dqu7)v7ei#wOPTzR&qpx@&0gkh{5QqeFr z{3H{~I0M*&(g4=I zhT_f9q0c@+DNPQA#vv9mG&2Ue&KP*>)K3>%SNCJ-GO$Ss?8mfU7mkk7;2Lq1ldqZ zI#Hoa?Y)OAFGbsXrthq?>aTDgxEZe32bo)yqufn7=f_~Fv*OHv7*V#S#wMyhZS|X3 zeqliq-R!vD9mZJhz*yEJw@`*Mfi@3>)fdK?TtXnYQ(4rI= z>tu4!7ePRZKWj& zXS+|dC5DHe_b0=yHkhb;0O=FpNE8@B~*V!J{Hk754!e?*Gwv{qN>0-dKAEuD9TKugAhz`WtIjr$d+s3e1iW2Akocf-^#xM66d=|3w+6b2svtZb?tS*(c^fP zw%POf`Iqnya5j_&rRxsnu$B)taOrtpno_>MTb*mPSBP)kE^ETopYD84pE} zNE*h3`ZB7++-^7B2ulN8-8Y4Ou5C2%Fp@6q85S06>6c0yG)NsQkv?Y zl3QTX60H?jI5W-SxPlZTodLwK>n#-4iF0T2fki%ZYmbg4GKZMjHmTXfX}AjL-qr$} z%w>MZau|p$JWvgg&=iYO@z6Tj8U|}B`dzX%&fo6mcF1Bgmih44sqB$9$g)(k0avM< zDL2(&i3(dxx4gWe`l|q_V1t(#fLN>1o}pZLeRz}I5TG1MunbkpAobI?+CNXoev)gW z>S#KJE+J0eX?g?B8Y$&9erJjszR>&8AEi4McD;(WEUY4sSscp^;J}?i=Jbn;`FR_v zfJ^z@@A81W@L>5QI4b;-{cJ2b;%#i`X`WEI)P7wXL14BTa=C@4{n3wy$%1Hp1HQC^ z#lkNIHP1@^Qn+=fMuBfNe+iBykVXEZwahl1J9L=r;)MIQ!oKRX5NRLAL|_H%dztPa?r zeF`XBh%YzJ0DbQFEwrUmWUPP`82!rLege6uDbX`f+>`Y;XD(Gfyy^^CEolcxG1;{U z1FOTxV+A<`3S!}sqb!|(5DFC}1QKDvB8Sg0xo27+#uifP7B9bCcsl*U@}>&PvoJ@t z<_cH#0F)~p8s!j=*~}o=5KVTwSplVKyI{Uyu&f&22u5gwmDmTbFm#5dq(7>|*`J}b zZu27J$yS8JU++>m7pp=!17IdueBJWSU_8QpdMK{hV7LQsldy zA}UF3s6jN?&W-YpD7at^UUf}1aJ9?&`$zMF)+XVa_FaD3EYpN1D8enRSZ{}uW|1l| zzg2_@gAj%M9Jh0=z3;tBJ@^J$bW}1&E7JTg3(n%Zz&6!d_%Y(!KU3Yy$j4cOZ*2Se zCd~gmwn_fS*!C}E`M=rzsaV<}FQa}|7izEGtugBPK@>5=hDC)}B% z3`yJRTDr%ft80j8q;V3~pa}}*ikmAkHd2_I{F+ab2`LQYA%$!uRa}!nev`=P4*vN4 z^xbNf!!?ggfHRlCy*&B`DeorQn;ulOh#* z841KHd1hQ~xB*VotmcgEC#@?|1!e4mW(q{71`_S5`4K^iDr3%2gMFEobAH}2EK^ln zpbwf>w3}l$RTZKjUVo?98=!6K9G9$%E>e{-Scl2l>g^&D4D=FqN2wxsUHfUFtXB3= z<`|f4i^(e0#zsxlEvPNqk+T>)A`XoXpQ^R%3Kd7v+itBvxl-zpwAZz%_);CK1h>+d z(>5l7Gc@=JRO`_Os@3(2_GNk!a?o1KoEHxZP$sQ>=BA1azlenj^i~&{P}tviA#1Ry z+CiBPCFoB5?-0RCTU!?=j%lviI33l!d#i&{LUo;!FW~T!ShJiq zCat37R~0|CW%Ogz^^Td3pk0=zrBe1GE8E&Xl!!|*H{2FMJASz&i9ju&rMbtqC6R{qe`DN4GY zpS5(!P%QSNS+UUL0fVuMH7Gy{P_XJZd3}KFA<-Q|JiGJtd&D0}ir;F%ej&MHj_q&t zs~P#7(_aGXrJPS5M}NZ-7Cn~ht%~MUnkcE6Az5vygB9bhdrI$SOMXUXRwmv};D@&5 z=^kDup5XfaRJVx}c99SIROFriww_*}rBK&D7}y)H(c$_S7e|Q-r81>F^a4@hOHO_V ztQ9~@LNFtJ)JJsJ#KJB7S%=jf*jW-xN7_>s{Ow%U7EDLpQxsf7@Z|>Ell-xS<%8>P z3)_?3SraTavb>9|yfv-slHQL^>0u}Wufp6R~dep2w@n{Vp10+8&xm1;YavbWlW`#-z7?i zXTjC(f%dsb*XxK!wZ(KM{vcK~33GNNM;A5H$prE1C~1N%0Bq1J-kgaZWu9byJIRer zm$?=kt2k|^%WK!O4&(V&WOJI#4XEm4yePxBm834moNpq4qZbKZ5tN3OT$^TOh#pbw zr;A>pf(ChK`Ndnxj2k+9!>JNWV>KSPyd&!)s;c1DOn3k?x4L_C+{qdCx?p$Fnu0f4 zAC(X3u-f)=9m2MrC2th`ZiZFae(R6v(pv2C>Izh0J9L+CWqAx^PdAi3FFjNw@8GIE z#ghhZNNGZ3!*Z0V1c@h;sROdy?uzb*#`$STxkHCT2a(moCgYUlByAl!?PdZbo8n{dboSSr=F%83 zoXA4YR!3!$`F;4{zo*%65bDq>VvMI!vO+8Pk%4~;Po*g5=STRh`G)ke% zh5E*36AM);X;31?O4pev7xlO+%Z$b=x?RzjfjO1Gj6m(1)K`~PFPO^ggp8r}4V~v_ zx(T4!?T|bzne56jon|bQ2h|Vi>*muQzEIz9ye#nmViY~YT=wDCZ#W^(_iAC+#KGw7 z0NI8bU4ww`iS-*O(_Tyz`(#Cf=y#vr75KZ#nFBeuswBlhZ zhbE!+TIjP@42W|Ro?1JPa9wMUz0g}kYNj_?4Jo7o>M%}+1DG_*4F*f_xco>BxACM@6s??9mhZd&;ggHs1otdR)^ra}>5GWo*2M z0P19)0sgfNf~B%CBGk-n6hkyrkDK1)Eml%1X}MDDIDoX^Jl_1#AnZnxu!y(r;zFr} zqKs8XE^L{C(V6ALkhk>ax?{rh%*G6!>6rryzMNDU?@L&*8xDyC)w1xKk1p(p91WM? zH||W>z2fe&_9OvsM^jR%8z5vTtDw6^3|@v)`BC7S->~<*VdP7v2r$2O(s`Qru709|i9^ z>-baK__V#a-`D6C9lDByC-;?ENqzY?ON>?C!}Dvk9B_@4u&l`NOb$4H^Zu|Lp8)a` zhn;oPG$ueZGe@V?%*Vx@{cUP2#&1=P~Iq zbA|b0xqcz<&4QVn91(3*#`Z5TVSO7CHFAKE_78>yQm;|8DczLbwi7j+(80i$%DW^G ztNR&gf(k+u#AFiA^q`k;en$*32kd+rznd|BZh)2Z3|VssC*%Y+4z+(VhJ|&N)$h_DBT;5P(@C_soDKSh03UEe`efV8ECuFi&LrOXnNiitg%5t z=GpQ1y=2!~qK=E^Omb^)c#75gS@5Tz&B?vPEGKb43v^-!YgE~q_Sn$hG3E4_Gr@*+ zh8V85Egd`@+Y8_6D20%B8JFGCdSbz=_cN|HzK`ha9#3Cj+89z{foI6R&r=s9hdu&u zPCfmcl!{&GbWV`609J^?1nqSBye8-LVyWdsO6jyb3MQ5!4Mo}^7a}9>AHWGA%P%N} z!M}O9txg1SF{Yyr2@Kd|4yQ#x7z+^f?SI9eXyw7R9ys09rzYpi%Fb3OJYZ71O`vpf ziVSD1CPwS;LqPp5Q$YE!1(X!Bz_0gs6#eDvnoA}pvhGKPl!t+N(0ISPKxJV$_8}PK zfS=9Irs{N&EM^f!zD3g)2zA~h4bZAkTn1|gwpoGWbBzUN!<6m>8Jp&CWo!F`(k_m8 z+dhh+a1q?07lD0cvWG`@Wt^W8_MY0B69%5@78_P2Wo5WW`2A4tA+8AOT^;*q);bNf zi$h`#GfUZXBcs>WL63^qC`gdCjtVOrksV4Y#WDh;$JDOH@-U9V()C7w9Oa}alE`tt zsN(s$H$xgEAjB99E2?bu!qqY2gf=SETI*0X)^;pnLF_el)^jS>R5@yE0c0wO5z&O| zZai2Uww#Uv>pu&Mk+V|c(l=h}1-hlzY)!FXoP$NrV4u9f-hBf8{^|3X(X(Y)S%-NN z0(;jF`1>1wJvhgWBLDLjTqZDj;g8rX)P(S2H*1}a6c1dT;{<-P$3H>*NR@cCk3da~ zP2f0pa#0oi=VLx?;F)N~!IBxbAcX}~A(4yTHk&DlRRKYe2_~+Cf&UB{8SnM4PG;UaTEg*cIhT~HIWm512a?$^$zm{-=vIINtv11M} zS+j8qUPQ6*lxrAY(^)93ycC)wv=m=~mnkJ->u*R+fX*J+skl|_yn#z>fEo5#j7WfGY>4pkN)ec5&O# z#jKC-Ki#!Pf*IeF+YO4lNw0REGvUznPU2?y%erLiC?g-1pZPf~R@1K}ysvy{DhbUp zB>izwTwp)wW#F+ZBAj6k&|Vy_wy%H0OI`hmu9*axf`PVxak1+CvsLX+cvkF{9|zCQ zJP&*FsbAaK3b$lA@$gUQVz?M^v?jB7X~+9n2ZQ-H(ZEVhTu zwhjYyY7QfDsZ+nA70$k-mQ7>x=QWG^PIaiV@kco-m^>A%iwddejGxBXQ`}-d&E|fn zU;|e(tf-!|#$;3snlJ5xz@BTsx^#$V%1huBK`f=C2)N}Eg~BL-Fa!h`y0fcfL#ll8 ztAYO1kHQ0?k{!C^*D4WXo|!ck6!Q^jHiTFEt77X?uzfUX{;=NF7Ugq>yLjU2#uMdJ z!d5ezBi;2H)v>dd4#S&Oe+tLCIa=JY^1#f>qn&*S?*NFI=_(ld{(vbf25QN9kF@i(Chb8CWp*X3`KH!ezn z7t|R8JYRP-o8hq?R5oE#ZHUu=jstKuX~`}S$4_vYls>|7gOesJ|AFL|9d}Ef&ObDZ z5lc*V02K%^>y!b>=E0kAYs^lI^I*f~EW3@XKgdsB4%;f(*I3G5^p{^xWP9$IrKjM)9uhbllaRoaV`$dnIbqO=z!ohk)jCb1V>JBn@}|NmD1c`M#dB;L{geChxF z%J*0IXcv=j0xmc&LcSs~>ujfxtZdXhGuEGIDo{Dwo|SI4AFJvGydH5?9qPQ!sqJ_or^rGAoVIAz~!T4xE6!Ck%UM+Or6ho zyYHhnEX*H963!r-b!Z})W=p@;_R8K&x^rQWh6XV8b(7C zPp?S9loeH|HqdPlFAWZ=_Sf(#+Og!0tt;1qg*WC_xWSOc(AZAP^LH-Y;H)O_g9XKE z$?4fRI*?;S^@`RBJ{{-0#uTMhLkoWFXXDWE56vr1h)cCTJvFLx?NHz(DajmPjM~AB z>h$e`$}W#Fznb~M<@!@1zI*SBXam>Qt+cJdFS};v0?HgkN^zY z{A@*|-`782PHC$4F;alw%paM&`~ek=ZQz=b+ne@OTEn&4vPUsMU7Vn1;FIbXgqAfaD_ z^t?o6qw>N$)lg!_t-)XpLq#$6S&i5+W-M(QlhsSGb8mqMNL~_-G%wWf`<`xDX4Z7O zw_U-F;I_;My9I1F3>N~`BB$6dJX(=Kg|Q`6Xm@xzF+n~KdEg_s^kAU-CZx^)n-h~fVv>`RS~bQPMQv@ zpF1_oizu{c&RpMt!aAnj2?!KX<_vU8JAlyLMhAK2XM>YeD`Wsy?3n5S!Bcz?6WyhT za&ssFYBd2S4>(i?D>Ov9Tw20m`0nnhbfx3&g}pVUUcGrbmhj7x531MRLFGTWd1w3D zLwPRLTHgu&(9Mu9{cM#Ur9@QVW62cz9Y7*3h()AX)4M{9#k_NcWV3pz5#5?hTz!~g zv`ddsl}-R=h!V$?O2&*6Ge?%YtmvrC5#1rSqY_woV9$n^W{#AN`?cSw|MGmW{SR!O z2xEjJ_#WJ7LHzI7yk=?t52LI9@AIF#UWr&67#kTG8~s-c-+xiJ|5xL$OAXR1Qv~&E z+Q-w0O*i9;OwyI25k+FvD)-dbOyV@H5l{?nUDhaau{@b#l<{37c`vdqEj263{qsl6 zd|W-+{})6&GccMkoB*6aVt%N9Xs#9!k;CcNqz&8}5KZa(yEl{VR;T+lpY7H}#_Ica zhcWt}TQ{yh=Ip~UhW6Dc+p&Ax6jLdCz}J^Gf?vQ^-im75cQU@WKVEr$RoZ%%Y`2K` zXcj%^Nwl^+=lE?ShC^4bH}C`4L9KYoX6 z7PcyT*h23NuaGWW8hpS}_z+EUdB2pwyHd1f+^I+iRPCh5*;Q4N>Qi7)u{3G)#zzmL^DI2QlgrDtGFsBDN`(5XB#Y74qb?!I)5PbEGMapBXd9-?^ClLI zI8UV%e*>_V)GVvY6O(MJHTDkTPmc^$Dl18+lA3aGRA_ur$4_Ebaq{HWVx`uh*Va|m z+lrRXP&o2}rTQgk8XUyU(bH^7NYhkTRNtK!mRHQ!o^}ynCfo82H_R)fHPE{qvwogc1oflr{2o?i zOCDn*QEC?3W#3=WwA8mlY{c-`A%EO9XU;~vlF5zC8|MZf>fBu{Ws{X;dC+}{A*K>y zMKNsAT(&eXpJ9JAtBWhSPGV75M!~ddySTDl->V}gEIq2VrJkM$1hY^jyP^&|9n#_5 zIvnEZ{etNVs%rB2?qXr?BO6V@=)Jx?(Nn{*VuEAu;G*4!NXmfgP1W|=I^{>2_N3LH zosd|B@u=TnTnSPi_S!lPaGIcJKyHwl5UmR1%sbMn4x8RHLLScB3Jh8#n~L3&qBz?3 zLC#5z&MBA${B)ZM36bKCR3`KB6Z6X7mH$v!j@ea(V&Xl$qQAA|wlQGKroYAhSOO&Y z@4Eu;QhaOy@QvWUJ%f>b0S#oIfn>;3gCAi;^*E2b+@^ceZd(BHexDz{47aMMT+q5q zvjhv=6gmJ&GM(f-R0^HJZ7;V;!1ir>nC}iO@)yd0?Vc{#RzDN>EZ^&B)AUu^s+qCz zeT3uPsN&@(WwB2#R0lam1=O*DVvY( z1XHA`>DqiWOv7n}&j9%~^xH&bW|CPGE?&pqU{P@PM9=uyn;-8U(dtaL3`{N)Hg(8V zul+I==Ugh$pK2lbCt0;$`)=KK>*z8ud4(pXYxNZC6rm$&+Jr5TvP4PZl0>1(4;jn- zif)69yb`)K^H9X4MN*8h zStEAYJRT>rx0!>V7L1O~THl;S_-%FVD=}J-`n-ND``>C%PQIEIzK(ZD#p8MIsMR1; z5^K{oCywG&1;6c|V&Ii@#W9xAkR;9;R9d3kugOLU1x&0Rf{p3MZ#7MhqfMOq^L_ya zU3FZIlY8DnE*{T?{i*PPjVlsGWk)mfZc+|Ft;#XjF&2{sk2`I3+`rD zf@S#L^5v^~r22DcwCMNH-zTtl*|95BE1nI-blV+|cb?WfvXwhGa#JQHDzVK9?eje0 z@P6iA%P)xWBodS)?n=v2MeWs8&1rJZlTKr6q^pX{_u2bCmj zggP1bB3_6|+`^gg2N4zmG&OXN6|U>={ZC*Zxjpz*Gfmi$4Ez_Yh@wzxiORA-d$W^oLVg@n~uG+41aAm3lPs( z0pL@4{ACEu)bSOT%s-Mz{Br$UmxM-}&qrI#N1Mk-Tf|3Oz}GyFuR4pb>L|)}5@Y!# z`?*6}Y!>j0mTE)V!q|+;8=?%_lN;^=C?@w|>Sue98L3EPv&=OS$c0cE4XS2$!^(qX zxBUo}34Gr`oY}EGOkHmb{^_*7&ZS%fr>~P9$4~rTI^N+Y7xHrm`F2bV9WGSWMPDsa z#OR*%rp>k2TB&0-Qs!2eN1Ocy4(7WD*2FNyQ@M%mBErLUGb%t!5lsBLZ|Kr`jzN-!+16-xS5=qQW!pBptSsBMZFbqVyKLLYvTfToZ_S*0Z_JtR#EFS7V#kii z*w354GT&!o?X?2iwb1RrMWiW0llt;Lj{a7gat3S`(_&-NAW~_uOG=7xGPsLH9#`V# zYRJLYVB@lJGLVkk^ZK1?D_~O4thbM&z``#>$z803>1Ny?6|->;rA!5?x(=acNJ)c@ zgR2c*_N(S`BEt#$w>9p@n9^etHpOkm%Gt0pcVdY)kfPeal;C`Nn}ZKLhDK3@4N&x% zQyJ)94SjN>D@NUKK40KJDhc?X2f%7rTiy z@Br$KWaJ_wuJ*H)p`-yT`$WVkQv1O!R@Y+5%5nP$(_ye}lA+g~dpIWSC9-%Cf6ZEw z6g9h<8k3xH$1Y1?!}Je<@+^ggiK*SX6VrfY|AZeSq*Tx{DyR{8(JIpium%@w4SI_7Av%5IGwjU1h`FX1=>zqc^9gf8bibzS2WI=EceM0z46= z2mQHmadXdzxLa`d0ng|Tqq}1yZ8eB8x=7h}Xjk8xQe~RLzjz$5CwDNp2X{~0)`pXp zJ3K>wMIh zq<*%T7hA+QL0IHCkzI5;v0bb%kFZECb^QG|%JE!Tv_)IiK+C3-5?C>SMPeQ&S6Ldl zZC)#vQ;6v>&ukEzW=*Za6ai~qSOXYmols~PkSd*6Dmg%JDsvn7ZSH#=qi)Jw7{%sX zMq)o!I*bmu#D>F?f}mh~FQItZab#u!0iCa4|3R}CsKi!C2%t+Yu^RhnaTjuH2d54I z(^9Z2PNH&|-!i2^vyaqwR?qXO0?OtOL1Q|kK0?nC8cvbEMC>O3;-RpxQfe5-41p21 zDJHdh!V&2yL^1@Ie45q~d{OQ49Cse_ASK+FDB=p|XHI&}HQ`MW7-L>}5!M?l#E(jt zi?cV>B2&b>lmjA24x5e!R5o}GW4HJ9O}-u8)Ql55R)(lZGk^gz_Q>U0P^?I#D=>4` znqk#3j}e$JRK9RrQo8pGqYV|7*=HGu@ldFTp;&`wH;mgrH-`NVE{1%CpQsvM48b7^ z(_Z0sU&$pTvD-g<6WHiO0l$6oA&GCl^X)m8tXV(T37)>S;(9#ze1WCFA<(rk{4T!w zKi6pgT4VhC{;kkgweg=R>;4lMDxl|JYHVZgX!`Hg#QG9yUFvc}xJ&jMc)I0$)da zQR8BD+hln`{YrB?>&mhkS03<4YMfbqJri>D!a8)-IN4|kGQ1U~Z`G0spq4AlcOJ

|U_^;{S~vb6G*%zs+BY_XmdXH(dN`c*8V5mSG81*{3e(b*;7Y!g zQO7)DBf`U%P}@jY=90_`TX&2wQ-dr^eVF2bLS^S_UyF4!#Ophf0G4VQV%8}8_n@a} zj&ljYS7^_QjJuVMO80>V-Ag}TuZ1M`!G)@o7cgnOZIEJ2oW_d z$C5n3Bjzu`iO`6qCRcOH%Q5w848jU4m2Ra-p64$Axh@23=LNUB;hXhw8OE`fIz99s zu(8NEzwuBTiTqltTY!*c4@!`D#kR>;k2IV~Fxz3Jwy5Vjzad~67-PpsB==Pno^-)P z)KD)dOi>@Vdl@k~NI+#j6*|kS&+qSxDRj%dhI8N>aS>n$PH5)PZMwyMwgil`$g?`B z4KzE87&H#^jgMlJkLtkV-t7~%DE|FOLCnxo8%PV43jbBMi8QKr@YlqZrJ&RkNd*hF z0&Q-&qmY6>mlVW`1c?E7Jr$AHMrd?L>Sm^5MGM>;U5O(TXzlXIYEkb8p?oNIjajHC zc_|O!;G*=>a>{R|=SO8IY^dYqap40Ja})OfF(33>!$g_6!!Autd!8}V=oJL(K+(25 zQ8wqVetYTw4W4|1yl&>;YXpGNSIuE$%x~zt(^m@I6t)+^_41T=2|?N0X0Vf6YOuV6 z-mqQWbS!V;euw$ulM+`JB?mUT!$jcB?SIf%-jw||2`aZA%a$-V{nZbCubte}^%U+LQ|4{~#Ir+>- zsNkW&dS2T3+`3#kXOiu2svecK`f*Dpr{J=E^6vNk)OWDdnJhDkA0`21!7BkH6a`k* zuSUhp9Z_hoN^!=i_Ris$HAhBsEWH?p%TtCh*W$;ZUG4T)4bJ+NL8$@KsP62lBjoV$ z=k+xH9yn`q)%b}xVnO}z;{*yosX-<-FI}op$zRm8#-tI9!2o$0ro_}@Pq`vHSy z%+aMC5jc{hk&N827gfFb?uy4+g$ujgl=YpybUREY&(78kM`6@b-^d}@XfzJyeB0&Q zf{s^5shRe`Vuj*JDoDFfCv{pzB9`Jcc>c^0UOr+Vs_ihbjd6&0jgF(e5!Wmep8t-z1Vq>pu^;_=92j61ACm* zja!Htoe_hJjbDeIfs=D^mogfU-5Bzfy8Ch!++^+ij4soLEoFHGc3`+fLYF$VZJS-$ zYgNM=c@ELo46Pz9hyBgJ0mTD8#q|BuvGXr%!}}BME57kVX&I`it&?5C-evC9|3iwM zB_Aw&@%Z8|Z!ymw0kk1Nn3hiaf{*QK51PP=E7Y0!RQ?YG63iJw0-f9*yqhl}L*8hQ zg;M>~9uk6R#jh4RTfK*abh?O(uR|HM43fuB0&a<5?m=1ZXcBDYHjXmwD3Io`C(ibe zQ;wpI9tJ0@Nt?mZsJz8o2*ij1&(=j5NH$$xq@mOheS)0m8P1xJ6p>V`xAZ7|@#~yS zX5P$BSUeJ`uPrt7%HWz5Jp?#sf*MKNWCRC}C3$KCSIs5={e+$E;qYq0cu-WS2oQ!rRmp9@+CD2a z<+;#4zC#x9nf)2{Z1~aRTqJ`O1s;b)TCGEZghO#k_gm8eSjl+9oyo0YE=tt5UsJ$)HC2QAm zwPP+9a-WO72*qoSOtM5QZr4T*M3sy35CU@!*eDY!&@3)TlSr`Wm)|F~i?uIn7Fs4G9ATZ#u|&%pk)Eb0i$;&6bT3541NNg& zn6uy}ck}&mqKrr^r{r%Bm{rRz%=1%L$@N#|OUX~a)A`0#9X$_N$PrbOXjQ!y2Q2rj zI5CV=)*n%xmbZHtqooB7qp)Mm}Z=SOx& zhM^_b+CNtV5T#+M47oRqVCz(onnIc~F_ncjQB0il&N0ga`sC-t*;CG$E5(hFUdWdt zOQS%4(arG1DNI3Fz}f$pO9z zMLOwNtjrcbWCLA8wv`w(hf`B@Q0-1r{`}eEn4)!Pfm&sJa`=}@yea_s$D!EbQZp47R@qNmJ2lv9mF8LB1nPD|{)L#qt z)o;?zobw7Pi0qvFLc_Cf-PfdL+7>-9lx6RDD@)j1S&aD}9e$g+V5-S;QW25{aHt-Ms&k$wXWUeRO%6-MOQvv)N_8O56qh`HNoE{t$qY+CVUS z!w$_9?VviA2O6JqKe=ILPh}k`Du;hDzROMd~Lr@eQH$!s&vEO69(KG<%s@i7R z>@4_Qy$S#_Ws!B|^Zs1If{98!>q$FBPpSG#s$e$msBBFl&ZN5-2MuDhPrLiC=HGVf zT1ZADa-`zRSf{AJ6}bF9R8+LT4otzbkcEQ-b_HX)%- z#a>f5Mu;MVawNv#nG}pGqI=lFnLc$mEL0PLYDwpY4IFesm>y8Vywbch@e{JDxuk>& z#l3X#-q1H%>3g?4&Q~$Hqc=2Ey#Fjo#chiTAipS~RzUu>B>nfXm*Rh1lKv0BzyDQI zM9Wq~6y-yiS0#yhwN{^`1CU7?h`JhjLMkn1jzQM%yu#e2YTo@IwWZz}XG6JOrme-{ zw3-haaHT-b#LX~v)r~X@j=n|EW2oz@t6Rv#ef863j2@=_rkBXp`Ep)e9+`{PI{274 zO2uR{>wSV_^CC;@)ZgdxX7O9p78k>rD1l!A`VVqPLEq^}LUBau+o<96vUaybHY01L z?YM%BC+I%j{XK)M?s-<5(zO$o4fc^?-}|04`WXD66HB%8o8>mUjte3CXp$(9rO#sVsN3^yw5>C_wuqtzS1fbB zDom$u-}WF>u0NIbUbel@g9&cDYu01Y4z$B9s2m)$&@Sd9m znQAKv8Lhqbm?}eXow;iXdv^9sS!fJ!%$6?RbP|d|1!bW+#V^b0AfjN%BIdU1!=@II zf|IxXb+r#@PadqWvShHqQy}`Z@xXZ}>hZog;(YUIg=6aivyt8#9K`eHZ+F_*OMR`r zz;a?v%8OT|mri}7$o5{Md>d2p5{}-5#MWi+ssrPRQff!+Nw;ecJcR+mOUYofT{&Z4 zZjsuEy)ae|UZbpq?Ups;3@%>Xvv>BS+w82fclM`awZB@mkH#z?!0iyXqluy-!7y>v zGTuQ^VpM)|y4#!jpD#RFIDHPFDk4E%{h;#(0Ub=Xt}oXpn1&8liTpuVuhsC9dwK+x zd@-N%3d=cJGB;YOMpHEtZh7P=iqy|2o_ldg`iZk?zZ^NUdiM~9K)ng37!@2;G`tzt zqJL9`DK9vS0|Ip-(Kqm6?tt*70lA)9OBG&7GQk0Sn^GRxyIP=a@RDE*gsTLHmYSS{ z+ihYizJBCb71z}mdHMy1|L1)tyb+)x&{ccPC z1p)n{2;Wsv+&AIog|s-C;XQ??h-^=&c<&pEjH`H=?fkC~bWg)YS8BY^$c1lv3MtkS zJS6dlxLLQqzYZKWV}z#1{+Bx)o}7wMaGjRmx#JmM5kBz`UPRDW6-?P?lN~@&0#p(F zLdb-0>a{q6;wx=s=d}oN?=V%5Wai8wSR9x+CAA1~>s}{vnR@4Xi=En4T$#GpN2+=p=-6 zVf^jlCgqapoqpWZGn~y)n4QpQyh1o#gHRtq7EkcnCjP2MYVAFw*Q6d8HZ>gX6l(*p z4+iby9|0~)UA9d0e>C3yFo1bL?s|P?eMcnum%B!BFA$Uc7;(P>+#yW>CuC=k8AKES zT(}+X`C|5G$Q?q!@4aIXhZE)QHNH?K)Sf=v?mK*B4zCp}Ya%Q)BH`T}VM(|=;@ ziNOLB$S8>ORm7l(5RZzQrDwlm!vtKp#SywDy(8)1mq5p#RizM7gmJ%u900<447<92 z0M-*e3FzGQa|Xk+lKn_&nTG>OTc(K7()I-6H8qp|VWx4=QuaB3{|d2_wy@Lw{|EkC z=$}vR)b9D^K8`LX_A$?2(8*)BJ7-^dI;{8TdTdXG_2N8U!rOQasxuFQb{_6aO!Xh` z_DU+t6Y!5e?$=9x z3_21z|D8_&Xbj0^UImm zjhWh++A+r0g^fc7U__zw>8n@QCE;1!f=^Y)qR)B5Baa8(W44bO);D6Pj`61k6q8*x z{eiecHY)&U z28TBjr;d|FIho31a4Skr^)-xn0^`N?#r<%vR*{7BGS%_z%l?Su#fAI*Ozd);ocnkG z6prENvpFIgSu(m#ug}_eC{Gc~0Kqa8QZ`=MziOZ4tRneVa$DLhWGqkRDY3V(hg8OE zTf6V^DGV+it@^*m2VYHUuGcR;Tk!q-WaORhNV2C;ZIRcGGje=^(_M?cc(8-PFR z7Q}B~OsH=j_D3WpGR$(c+l<8_QNER>cvGIi_P1tFX#6F}qQQ@>!w-P?*+ULlh|sKt zphlnuR;L?lo4zy!^#m_ip%0uQYDFbvHN36nvlLT^=(|%+`%75vk)E=l?QbL%G85oj zO27e=Xxp?zuYBrQZ9YRUQou(I>Q=xcK@+L!_BW=Ct|A|R;zv&7K?^|WY&#c>+DaV*Qi?&zos z7e9x*UUft9n|}7HP3UBUaeR!!y2UD~)SING=jxq+6UeE_=r#CH`=Z%NSf4-8N>~#W zyBS;uEGi-fd_8i3s`ZVA_oZG@Bk$O$YK^9JXxKt_&abEQ zr>{&5oyx$s@sfoF84V3aZhoypn2c*Nr*c(f%Fl#7YW|XY?fEDm#^&rgIA$U?#9le+ z^lux&<=t{al?Jw2pJ;X(4=@K#=Hu$%pbtNcufMvCXY~g#9`vBsftvos}07m zI`CpAO~l!o-)?CuMcjTD9dBB5Jsk6rXuN5N-<0i;B;6jDatl7&Kd!e+mgau6Msau< z+m5w4C)jSlBaP^q5PWZco_^KyWEPj4IOhg-dD2mW?Kj5`c+kZ~f7WT22hx@kwZ<>r$Km}ZZJL28=> zx&+jfuLSDalWc5oAoj#+98&;nl{v!2wIGEP_xBBxWH0WLoB`+;_DM!>cyCCp|IQn+oSeZ7*jzJn{2~kt0ksbuW^N*?_auzV}-bm-}TwFVeC} zti+-j9)MML-)eZt1ymCo>~>H}xM=tC<5+I?5+cL^Phx*xn_6XCFH3W4`_%rh3u;o! z(jO&Mj!_Zz-`0g?f2TE0vi?k6?sO>FK%!VGt{V)J8Y;PuWTNy7nl*=O4zIV`E^?q~ ztAq|7SKL*{Vvgbm97$XY$Be9_xM{1P{4i!1=TMtgm&VV+2t=YBE$yg$8(~Zy1Z*gJ zHkXYZJIUM)5~clQEf9yMeT)vJOf2NXyzcn;MPTN9ojj7LUra*%z$nj^_Q9axmRol8 zgNP_%LjHu7o->m+Ir0Fgx^wfOcdjq0GhNCcg?@QGgFQ%y=|^Q@jyT%! z9OG?-lau~oe>537bq%$eCPFnqa-dWc3&=#7*`c^;&d^3nN6so8VPvI2SnZE!CB*Cc zjni@*Q{L&OZJ!_~m$84-Om<`WQ3CrKRYj^%ioRD~YVYPg@Ie+HM5Fu3pbz9|oM9S1 z&Y}4(I*l(gTzUs5WGW}Gtae0=bz&#wsG=;hHHT>Zw(ct*lz{uH=)ujrU>>Z`0S}ck zdWjAhP`^1Ux(XFnwN|l$3|!hHeCEx&Dr)M)f8}+AGczzNoM-P-7^^i42`v!DJ;~KB zR#DN34o)KSM0OA^yPmA=_%XYQUIc9^8#lT;Tt+K1N8-$v5+{1e<1BrxoD_SaH!L;> z%Ghmp=bkc?iUMjtq13WuOJe?G89hu3<<32F`&Q~TZ&S4qT7S;xmX@u(HMftYdgatf z+tR0vj)j+G|0Y;8bv$`V)$!5m_)S^!j1ulIq9<$3fs(REnC7xIE82?A4&Q8OW(H!V z{5U72^YrjE!}?BMTi=RpplyYeDVe4T(Cw)j_ONb8PMKP_UqG2!zh7UOdmxOY+%*G5 zrg{gU%-tVWP_8-wXkE1 zRS7(_YED9N%KybydqR@Ge5K?Gn{$b0Pgnr*ipT7OAW!S|2GeP}Z)&1)s~TMwQbFac zN^}(VP&c=EsK!-P`^evDzif(ji6Fp#s5m+(W5x^5?jKReMk_vtNFz?-_qVX zc3Mf9-up0;0iA}vjDb#YkXu>WaZww^x}Uc250eEY1a z+|p>KV~Mj{-5Rqz(o^pl0#ZgMv^0``T@2|SY;sl`TP$DF&(@mR*Gsmz*DhDq+~EOT zZ`LtC3p><_pMPvkzc>l7`7$KZzBx+iRx!`u>2WT^@O*K}GV|#m{H24LLIXPr|3c&c zxFh-gvito7>HACk_ZNllFEih~)c$m~hguW3fmISeUw(VyUg{QSDcZpvpSBJ+GqNOU zWVHE7Kr8*zAEr<}hSfLK3>8D58Fi$d9^*{YVxk_Ev3_qwNz#Hu(4tb9p&}B-s>PXR zc4c@f%K|6G*&n7x(}A8wJ4jmdbgW(oqt&(oYqoVXW~>3Z@IE02ZPA^HMk`3N(ukp= z3g*2z30VJ~anIh0el}=`KElF{uJ*H{yQl>F+nK|ozizOaE$mp3t1E=OF5F#k3;mA+ zeg@&C=azL2c?sbTv>!{{TJCfAK5w=c|jhEO#$kZJn%lDH(AU*RlYe;zBy68 zIa0p)-K8LA!pj_*^TyW^gQA@5n8Z^}YMVBun{TqXS-rUg*A&az7*Z2V> z90|kwVb~(al?i&>iwj_e9%%IiYyCjnp`Z@gZ?9X@OEROkO0GY&{foBon8D#>rFDu{ z*vNr4y>hP5(m-B{Nbu>O!PPA7z&f0Yh>o=L#w%!RJucFFuU}0&tRvImQsoP$$}Fw( z&b9K4t9+?eeK_LARv_ec%%aqTv{ZEhIFhE{F7XA`)1RzH2^c$Jfvf1y2?>Ye^joDm zywPmL?;c1JKoYbWq*q}@m zh-n1@sXCo!z0QrFnvifFu(RhSv*$s)nOKJrOzL&UO|p@X0OE{bKP)dk#}{WUKeLES z(|60#56hV1(LBO!zbEt~9t~n24URSI?C*YrR4qP#bcn;fUQ1}C?w*-2Z#rY%HD6g* zvFQ9Q`K}4U07j5Y)c(wwofpU>8txS}ByAty!*a)XHfFay`1nFTMT%$*B4t7ms}~9* zLvF!EPV?}$eJQbzTM2$t(Pz}FQst#ZIqvSxXel)mXpWIJ&yFC9u`qPy2PXzv9`zeJvG0csw+CU*WJd$w8vs}R$%b;htU#)G~UQn&46#PoluaB z)1N>)#h^*YKP()iKr~KWf~^1;9jZTxgHG~6HY~sCX)R$WE%xo+ z9Wk6E_Bb#mEU;BIAsC@J`RsD!MC8DWA=8ZNPrmgBvSI)oyT$)#4IDrr^!^Z5Q18cAF5tOtY8p1q!kJN zSRR|Vrs|{U1;@VAOMbaEV8RB_VFM!5poH8Qi$mxYEjz=eWCk8My4Q{|3?ksFj7MzR zU!HS#Nex_;8^Gv1{~hc5x{;zNO#*ldp+RXO_)m09WL;C)KRNv0gK8c1(jt!4ySUpW zG3p%u1SZoM_~1Zb$IGJXBJ>Gh;~P|NLG3lJgY{#hB0Hc*yG2BReSO)107kgepMGxT0eKuyoK>Qh({3Fd~B_HcLj%hPizU@hqidw z{zY5Rt-hXs!+E59uSmTs*v5ieL)LZFkuQO4n4)X`CtN&#ylT{mEe%`L=x!NTC~s6y zcCx;1x?Wv&y0tL;HDB^KFfct@%z$xIWVk%Q6Q=MscN(moDT7end`tjAken%#wIY@B?58a!!^;4xREgmD7LHR+F*w&f|1?LI?&)6 zd5vRf@rIHoHGZY8z}(10vg1@JX=yV8gexR$?@^3oDD2WNH=`Ly-QW*Cc8Fkm55WT6u+Z{hJZ|{Hm7R5~0BX_{UzS53j!-ChnIu?BGe9NY)%kQYJ zuA8&(PF;J~tuMjrsAk<$gUXhqdeJ98DtOdL-EWr!>l$o?mZS!!*Rs!4zSk7S&iP2j zhkTL0n(4d#t^PI8DBHd3$kYu(r)T}+5!$*zyQy@#;^F8qyu-0;sb~`$FZUI!%_M6d z4Wi9nX2=PBM}2D#l|3-C16yh_C-0chky*<(s&I62`_tW)*^P}otsNa(Y6B{YvhKq#PD$KUH;}VRo>W?M%nZR_L%RYxHOz zUk_VK?tsVcUl~6qw>qjZih#K7(X{?dTMq5nNz0O1eEUCql%+JtGrGV2(n4LM?`kY+ z;_J@u_M6{C9SQAPJkTbjz8TJ5+!O?K={@U#P+R6EmkE>9+!P_$|H9h8V0SEWjZj{YXx)^&7d}?Hg^$ zlhXI*1sTO})^gVtAhu;;E)d;2Ll=fHIW z+_e=>l3e{x?Jy@rMR{A`E~RSZjSDY*kHkpViZbH?SvfcfDm_l^Hy=szxjOHTm6W6u z1hEH0G42^9?DfKFgjTVQh18OtTG9t#!$vGTup zLJ%5{AY<-13Oz$}#Pd)U@&OVu#MzEgoztclUZX5XXUvP)0k)n{E8C1m0i)aOJmFM! zAgntg{JrA>66Huc)!JeM$pQS$l0(1>KddIm`DU$@P_CyHHPG>5Ee3C~OHiiDe41mT zIO-*cx@&{DazD^z*OYvO91<&2QL$Rc;i+G|1Qf`XXq?+cZ_tDl6jng|P%EUN0-qWi zRZULuIA4j+!bTAYw2!FlSVKSOUeC7-VmVtNKDS8R4T=L?g;JnaP)B$9c4 zXY)s+lGyEPktP3Yg4BL-he1~#(%bX==RaqiQk~0O)yUtz`7-@$qx9crog)A7tn&+g zYwKv{Z1fKTBnLBhqkkW?7pVNd+P!DSIcSY#=_+;Y^i|uoi1xY!SWh|t}}qn;~K>?5v;Rt>r^{o z2P+HZ5btfh%G+(H`S3x|sC1hFGMSlNYkZow6(Ye0OJ*u|n>|1NQ ztL!BfU3f1kQ$OA)pPIG8{+?)qY`d7QwU?jIkjRh*{>lYgrgbSfEB<#npU85q0(sIQ z+`5e|5k+;~RQvUzB<&mTJnMsl*P-Cf3SEhG^G2e2%x?xsEH5+5gQOVgB;I3$zNR8Niw5Ty= zzkxohU>EZfQ@Mn{HugtzTc1$%GF1-zXh+;!KbE<2Q31|qk zw-PvLng{U_4T{qBLY8t3E#}j|II|~=)R--;Etco~Le2;jYlv)_03~YygX^dyNh}H4 zoa(EUKE=C{f>4$sTclKi73!l3`ReQ#m!g?Qz5P-S?8_rv*V#Mb?4n3}aWgt+!-z_! zz9Rd3BXU>4tu$O(XL{6g$6R5N=hUswV-jLB2&iinOF^EXSx!W$W2lXj4s&? zR);BZObdA!my7*y55&dFuzB{sxrkDfjRxQj6;PcOJ6undVM?lnxlzO7q)iN=3?=*( zVf)2Ou5Y*-3A-X|6}}Uc36)f_fitn<^&c^|-iYRgd$AxgsKhVw z01H1@04&VHF1sUb&$XoB=Zc)IB9rnoD~=ADbNv~peTyuqtW0n90i$H8R>y1R#8&3t zC3xI+|5oxDb#3G}nw^`@fd71&pd-CiVP)By?3*?keC*?z z8}m%Yh|UJSpI!!Ye9WI$kbX+a!_go0jbhy+kj>aUIpb;tP?%B1)h{0G8B&XMUPqqp zalE!T+a$~4g@n>G{vOWG)vWGD=MLcOo@$P1aSrF1js;A?}A zBm(T{jAzg;u-n71s^Rt8MY3C~B*r9;k@rZV-4N3tvtu-&?P!N9$R=Xj!r8&iEZ~l@ zi1VgY9XRrNetv0n8wDDWbHMTfX>KF*g7)b6-{GbW0$$j2czl=d5;UU~0-l%)&c=x6 zSls?U3ut8}b4iY<=fhfYDCVL7r)Kft-=pWA?1D(d*l+0o9q;MD6OILA*3Nj$o_S&t zxOWh^hYl@NG|w%TO3*I1m_HVhzLgOSaAE{`$+7haaVI>ZNV zH+ML0V>nMR=a9orL+b02?ZE@`VeQ?&n-@6%J$MvcnD{}%b&I0kp(j?P)OgN>B7(O4 zJ5x@=pEc({V!Cejc-GVpAfL-9kGn8#%}WpF+r5TU)C(om@As9xh`eh)c@LRcAR_B> zpHr6ocknCMqvP<6@-eBVL*dYH1oDcC_a&B zi~=3n!y}wieH*ULt=(Z5yYK%|d7?``bY)FR1qW6p#;!WA00`IywYU92#6R=ifQlcS zwiyA&jOW0di3V-ngI`HzNzjYh2b-3C(i!di0Gwp^Hy%D4ggBO}nZdVqc5ax-gBX0n zgiNrw$l#tV0V-ZGxQ&gY$y>U0+RpH^eD-*zW&afb;mK#cMyy1!9zzUFA>$5#0GrQ+ zC=+793`D~+JI7_f;Sz>)hUCpc=I5poVCUQAXF$3Pv#=8%>y_!V%s_Lv;<@%ga=7+w z=7+G$D@K48s(=XR5^h<-C)BS~C5Mrtco9-e(Pwx+XckVI<1i1HZ^pe z5aP|s3GdbXc4&5Rmc`$q32jdhiAG@e$bU#kTp8~SO`M!RditffGRqmtl(7KNY_iN8 zyGKwVZqeQeqrk-xiwzQ&Yr)b8z11V*;ls1@HYXR2C8fm&4LZ_N3;J99w=s#Jl3C}C z^x7I`N@G`Z7rK5Vxy**YJZ3f164%34W2ggb1^W=!HN#^IBMRkWFk`oP?T!_-=1NY; zE%WCiA~jC|$^mE82oZE}MuA@KQKDqIELDb>YrrNz4n8>~Ply>|i-jERRF*Dnia3p8 znr5os{VuE#pjAufGx)kU9k|CnMLVq4XGeD?tnByA@!bzmZ;d_JuQwR|K&#WKgs@)u%+``ft(7BYE^-fm%IS?h3+5ocX!=t zv)wPMe{!UMO)LL>{{Ek{`usONl>Zexx9)&7kMgPIbv9Ba6iz2UWU!LS(Y4AcOJyhSW8%tv!yaQl!Pfb%WYf&gc^#Zdhq8mfu$Igiq7ZtnS) zO|9Wv@6z}5t~sMICNZE$e>FUV@)-tGMT>Vu>3+Do&jxk!xOhcZ`Eq~Hhe42b8cteT zmiFpidu1Ya-E^Gx0@cIRO5s8I1!Gingt685LUzem)KL;c)$&052NM?ii+tu6p>Dl$ z#mR!~C8*#Qxf4_0Ktz~#p?21EMFy)vZc<-L>Y_MOn$eX@6@xBXBqp%V#aTH=WtANH z#X(qNQ8cn8S8L8f8bVE@Dyw{{Rf$C+%}QMmrsv0{?o!J}2GbDOY-_pN7hR9(R&R(| zw!WB^DGj~jc;XmFh2z4^A#9ztL%kt;v)Mj?D*4)Uy>=*2bV-c~`hk(mZezimG%<5n z7k#Y{hSAa@voO%ypmdArx+ z%lT^oW&pPt*k0K()|4;%CRBK8>M^(ql82?V8Dver?WfjcFTB3+aD8HN64=WJ5|Y&O zb4kVp(cl?|;cR`W;<(c|>|j`U=^!?PX5IqiEyy$>l>4Y&4s_xWGN@Q>S_Ui8o#v3G zo})(27sIj_M9NhMsSx>XB9m}So5tE&|94Ax67G)6Z2Uom&%>d|;ri#Sn@gv5>a5JX zm4?P?bsJB{sNsdTz?z%(A+AT$1(q;VM!|UcVl>8EQm4ne{%aqJm3Fu;nKMJiQYjQ} zk5T*Bl*gj{)puw_&7M(gt;j7*(Wq-+L`oJtqo(3bdV-3ZkM57!H&D48=Nxn$CDD9x6Z0{(JxD!q-j8_ofS3B^CBnF z?SdJ6*N?tC$kIKqFF@Yu(M2AT2a;h|LEa%jaULZH5QD=a#NpJ#`$OpQZr|P=yR+kS zb051M0Tuk%Xk2Ii%RS;>8$rC%3lW)uyD$6jw_Iz+;q|h$NPheD5coE1=T$@ToG-=` zDyV$}zn+K1{~2Lz3NhRJ#{X=ytIUm;@ryxlN>_wwv|* z)3qhMF<{zZldbK6Y)%)`nky@;Lr@Fc>=F%OeDyeP2nBdP79tyk>tAa^LT+(2gn}(d zd!W}i%M1qnvcTy}7`KpiSUFTk)>K*sh1Bv6f>-QFXWUHWZU>Vxn!NRzKBQ zlWSs!|Kd{DHRtP(#btO`;9?+F=l8X{$X%LFUN!91&`YF@zPb>EQ(n6;S#Y~gID>%P zy_|sA0R26aA0`m}!>jZIkWO)vTI>@2w31ox^=OkhnVvppH*%n#w$J2IUHGHVguv@qY{L|B>DQ`;Pf+Z*gvjqwIYFgt}obJ73TkTZA<;f-Jt)I@aca9&W)=>yK443 z@t9n$YneGUPz`HuNA|ET4a|(xR>LxCKl@rj61~M(K@t&*x5QQE2YQ99w>1i5igokh zA*U5eRpZ13HQEUZq{(VD#x0OYm7F51kdm0a;1fW)>50z}OQn4y_-t``G$*OTJr(60 zD_Txva+r8K%uZ!8vAzk^@j4(ztk~1yX^s6TOjtR}hwtAMKgTHXk~a4tYnYTczZ^YM zdjY4*{58y*6dNra{sc|vJyCZ(PdCzaDEuLeaoujRd+dL68B_l;?6Cf;_5*O5Z8YK& zyOM19mR#_p!tmfX)VY&aHPiKcWN~-N^8)`O6Z@WwOgGY8C2rEBj48Okebzrt7J*w0k$71)xso3JDyRFs0PiRqd+sT%Rt2 zFM7g6Da?CMPksIgcLK)&7nV(6G9F7Zj5Y}V~RpPkfcwW7gAzj+VU^x&Qurj2$ z3PYfDWJqAuEiJA?Azey8@eF4;JR7@sWuO{;|54IWc#AB)mbe57xgPQ;=#tFK|V;TqPXW*2@Q(H{!WgeC*a+T6USca7iH z!Lg1I2eMfJWh6$nV^zfYw1Y{avYF`PX&sjvDal2xJe_ZzS#EOyWl&8RP=bYrX>K0U z{pDNe=SIe0Zatk|V!Ll4l|G^`$(BS(Xw5Gy9cAhW+(-^+3%R0kOYiz!G05D<)+#Qw zYu6fR;Xc2WB|E}cGM^ERMaeU7W_;WklWr^ed@@-{-oe9|?c_5W^5B7|>JEZPpVPm; z)fU4oV)!Gj>X2NSp<(b zHO3x;HPBpBtRf%W7}aEu8avfiMQ>tGMrh>^OLp`)6{DW!qK>k4y6?BT(599qm$dX! z_L&`n;(YhdB(_TZQ%y7-ZfWb~;Gk%Q1$HRe)q_N*){G`Em&_EYAi^4#8ekpIvA&rc zN&iykH@YKvoAKPAO{Gs!=>6^z^i?HFP`q_WJw2tZ8t2tDuZACJyU{T7=rs+BV+%J+ z9bw9XIV;`%oUbo7^`ZAQ!3xSJGIGBc!z9!6S|efZW9n#mTp%&j&0Tl`JjJ;*ZZp@N z8#yikzjXgOX)R09H#n>;=KHkl5$eNc>P|_iO!T!W6+!q&UApKuycfTUFBjXKO_5>? z4~?%CFh+)35vhgi2$H|#0`Oc#4G%(`WXu-6iKYesnJ_G#o3LV(=5Q=3QiFMl7g6S{ zex_`zi|&yMm6)OnWPFL2XPLe{vK#^1e`GD(_TGou_5x|r%EdgaewHyoGOGnD&x8)f zWbhTwu4KgUe2j7?baZQq15fYri`QsP6O!Jm>*~odB26kIm*#B`6>rNLjHBsPO5<0( z*?VviV|*^nyz!KKNqI3j^CX-wpR`5OhSv9RX2DH=6wAMXp)_D5HgzK%<90p`P-@^j z%~h<3shz~`Urg2>r*hD9Cr7CN(D(av(AL;o?`0#|x9bM0{z z>E^}~$wII5ZS2|ocI@l?EEagjl#%5HZhi!FXXQu*O50;8=G;-jm>&#vabLWa@S$SQ z)FceEuK2TuN5V+jBbu&m)jhIq#eGVb^dWZ5GW(PZHvOq5eeK*23nkI8c%;(388E&4 zV%Z~lD5_g{-+Y&RQ;O}uPej`Q$!5_7AMehyO|E_k3Kt32rBHb2ELe!Y zS6~a|hPUd`u5l>Sr7`FPCPJ+@+jN2(*D_Z(JjrJ6{Uy z+s8-9uTWijv^i8wBvgd^aE2?Oe${o~&bS2S<^;d$IdhZMUlC3_zX$hIg| zM6%p%SbvF=;kbv-fF}An+M>x>yB!MYz4TNx{HQ3XzLtQ$rluGXYlFwwStrV?;x#TFz7e0vRVm6M%OVoXaT3b7`n=>o>rd>59&Uoj&AUIzYT4#b+bH@oQFzBmyo=gi@~bD)yn64l;8YF+NmH|gH}$W42h-(^z{q3$SznqB0+QuS+k64V zD{jRsQy1qF&3s4PPzRvJJr5cMhtWc!8Zi{S&~xo%WFN2oPQLfEp=G;wpNf*s>+6U1 zs_&9o4Xndq zMKN?p6^Q9e0!qhgX|g=VmZYRwSy1Icm~?<1zbyV*cw3}%ZiH#s!mYq(vB1~~Uh1Ss zX-*Wac1ADCtV;lbk5Z1WRR6ghd2UB-nS7#;I*RQ}gjY(jY4|Yvm9KWQFS>j zTAxvMo^toS&?;UNb%G?64%ZTFpj2!ngfQl~e9^Mo*>%5cEMVC4hG=n#ek=)p|F%*Stopl%_qb`fRqEpp7^`ldX z2H*R_#wzg%RV)DhkWWRPUWIH&vB_hJVBIw+&c{DV|B6)8@$W}a6&|6M#JpYt*G?#u zN;u7RjFS7_7CRP^$zc-?sF%rI8VH>;kmBa*><%X>_pUx-@?7F_Q5^c32{}t~o`aN@ zs@Nd?{9}F(P?~rTg{sJ~RoI13nIn?st^AV6Nh zv8zmbV$22w;y`oa_3EHc6goH+OZ)@n*C}*R0Jue$)@<1Kji%8x&1*Gz!tVwbu&ZXH z#~putgI8v&KGqJMB?wKL=LrB1-EwmZn^J6DTM(vd{bKBgP;bj$D$rXxRu;lkOCuBd zCUf7Q)sQN|l0hjb-~|>jQvu=1xMiR~deE;8O;7{!!@&%!VhH`IeA%aAS2U9+!Tp5# zvCg=6LPnKDbF_U9Fm-zN$wvloWie>|&<-`MsQ#akTbN5^1F*Pd{=>DvB?NyyS*Q9) z(izXa2J;oSSQ|1{qZO6ClpfS=D`_EK)3{O!vZtz8AjaZI0&+4-j1hj_ZRw40?@KM-z(f&@I7C231Slp zJBUTfQ>_jbQWdW5CUvYH}vMMGcljAM31xIgiUZm0pWoI=lYR^eBC zB?t?0XNv$PP6@uz>N}V>#?Qnak=jLsGq^X(?s1qiINi`JW3sK8sbF@!<gR)ho~VqynsHeQmMIsWo~d8InyFmKd1P)y zY+~Oa8MFC{p69inD34zJKsDrfK(_fpt1@}Z;C~BsW=!-8ko)jo1w=HDt!+^L;vE>< zgjWdJN@~Z!XdYD8X|ar33_F?;xgMNT5qElzU*C?lF2RPH64M`+$y&mQKki20GOv8Y z{iK}pD%ar&sj9_uyZez6Z%$nzl9V;R(Y(+Z2oYljoWRs3;sW@Ez5X>P@cfrXeTuf* zfZZ?%*22!d_rl6s!Rc>IjvQxO)so^O}kn=o8*Ll2A&Yb{Xs*S$ByErN#dIsR%`?T|@Vwgo zcHoV5%Cd^vpRMr;<+b|!daC`;ak$sT_9q>LpK& z@^+8NtkRrDy^e=vAqaxa%k0L(zIQk0-tL63Jcr!Y{fE^P9_9z=8$9_t8sEKvW$4_& zN7%10Xy0H0F0*cZzn7LlDbe}`x$IL~O*HTQ?RVaz9l7>bEH*x~WsK~`Rhx~5o)7T= z82XNTm=DGNT6_5bf?iXvu(sD282a`*t$+e!CkoAGDy%ryBEX2dvRts?bccT#>nZx> zygb#yx|^+W=??c8^5%o3k!?IF@rGc6dQfgfY}0wYF$q2~0uYcK3A%)c;CyKE4xPLz zhFmbU;C24VvZshsS2ZoZlxkCmV&!a&dR16KGZN2+BFgf(V1;7eHX_uhV0kQPMk^cZ zLU?72x42YI%bZE*QT8z138Z($(b`J!@k9qp{*1f`Gb)T4a}jcadRs%LuVfk|`^kvb zn3S&$NeTUxxmGbbwoqjOv!XgiDIzTtDbW@i1YY@aLQ!9r(L1pf8pA~iQFS$%3T?h? zEc&60DBUV)IzLTu7)rh}w?LPpriZxxKm=y|t$LZv0d}8=zOrAP&b39KOCIdPkCr@% z&tsDP#Z=99Dr`3-&;8G;9Cw9UN4B@??PI@FE{j6?f)ZX71kA{mJ5_S1FxiXL!W(~L zR9uU*lP5VTLs!6j51dLIc8mQc@#_XS18z_ktOPe~#9wDn^?_I{%RUuRDOWLxF!M6A zQ`1gY3Tw+5cQG4t!P&<}Mu;kTfx0o+V0BdiDLp#|q5_LDpj?ASqBK*{NuyD=U8(~3 z)KqA)PJd+7Dm1phv}@Q*Die6J@po>>VTHO>b8fivL@?&WK&A^G;rJg+OS@H+lwu8) z#cWV|^s$uL3wAKgs{A4ux8v|imfSYxyw08zIRc#BmPfJECzv;&xKqy~m#eszmvX31nV?5JP{Lgj zOKe!CIa4Pe&1dW*iWgl?{}n|S({<6*^+E{ko+A8rmLio8EFGYwx|#x?dnXa%Y`nnLp&zc zxXD9K`hz2($Gc(1^7bjjW(0Zzsv(3?t4y?%%{j7P$vnh`JnhWvq?zj*h~fpEXG4X) zkA_BArC1M@r2$>(j@Ik6&w|!FdI?-CRI>L&$^7zXQ^6h4qCz(ei1f7m3SU*h-9K5} z>i*@VqU@v;q>1(@e|d14ch}+lg=JUy0`pZt6v>LQqi|36Rbt3{HpBj&t`BfdsI9BX z=oe2s$yC#N%3JR_9oSX*0QpwF=lv=^*uA<2v4wYfBoKWC+Hu?$Li-;6)_xI3>!Yne z95_LCRbdx~Z!~7vR}P6HNs#gm(K>>h!UpC)M8^_m9XVt)qV=ZBFB>3MP8(ASQ9DA> zWe`LIE09McCnS=8jM!QRoxze#g^R&G{@!vIqZuv&pmz@wk^k|*RAb%AYHzBxjM1{c zzjrl#!{`2b!B(yx*H6m*i(*HzKKW9m*DPvx0_StWK5rxdA-~8XhHRt&4<9g=KP9gl)aa?8Kee3L}ULoW2 z^>yU)=(|yUTP-nWG>bUb`A)eSskta>4&M>`7G+Z8e7XsA6BRL%4I(dKCfPP}U{J?+ zP6$_P3(2{I}?2aBbgpimDnIpFkrDx7#soQfqX!${~#6T1z{ z5cg5&tsiY8_AJbE6zUXi^VGe1>iY$oUYY-GiT?nSU{4SP;*<}TninU2+&@@ugOvJ3 zNjq#d1|l^%C#mGCw=sRAKm;x<{0Mx(MU3{lBOx@n~uovP!|_}0vMpIBdC$^ zir<83%{jKE_&kw(pZ1vIP?>omlEXaI-95{;J$e^S;vOLHQ0S8}AVVDnMQ?*KqI73+ zKmc>XN!XQ*za@5mE<{6^n9C-P2(6wAo|irfN!Fb556;g5f?DMCO~D2K$<7|=D;gv_ ze-3AcpnZ)<`p0NSue9RmX}{nbZG4j12qB_~kLdr2>Q7GbOHT1uE?L>^+$JwSNv;U+ z>=P9K0`&h|iNNw!7tM)BS1A5PX#UIL>923U!2F$xdZt=oBJ59_e3rj?u#721sap{jP}_j$}V_EQe~4|yJzg&L1O#*+j~~GGMY}IORngApg+Vw9d=*MIWmhO zjJ)QA{@J;`$eRD!^5tpu2~{jgzU@SrWHw7+tj_-Obf}R2)hjl+%#BSt1d8LyFpoL4 ztSxp~o~fn8(%hTt6-3nH<6N6cjT9%$K&l>a(&DMbP(z=Xz|PY>-;$q>+qrn+xZoI9MCq4)&Uvcygt-mVC0+3eodP@#uBMv_zEh=4P09Vo)xgBidH3@Ro1A_7{09 zh!=jzIF~7uMGj%&)3R6mc-_oBstdQABUAIp#A(OkyjzjZgbDXmGdH#N_!&WL2b|u+ zQ*csh(ZKE`kekdZ_T;)BwO8#i)1l%oy9}Rb_S%55lf5P|z(Orl&(JR`0nY zrQg-lz3x<97H0J@mJF>Q!pswOCedI518-xT1K%m`w+C}b)A86my^xZtI?lP2^4)I= zlaL&WlLEmu1|^CzG<;@gw6t*UDimF9@`rkn=sqFl7O89!Zo}j;4Du)jz$J>&urq@! z^PE!#yGm1(p+hsf%+_yNjLl)J1BS$(vuub^fh;zByoFQ204A!@dNrcFW!f;)rjmWL zMQ18L>mOPL+vOjeoF)ODH6nT>m@?xB1rMxc8j)n9hGgaX9Mev7R=ujyO5ivT51bM< zZi%!*=$#1?9f?L(N}Z5OkI5tehj;EJp~U4q*v1fA3$+8>G$+Gi>JWIMc3JazTdMa_ z!F&tqYQhoOjoY4QBC25zK3jZl7`xg*6iN9|S9U>%e}PYMY&?#{!^Xv#q$3J(3hAjp zhcPB@5c=rfVRCUz@F+C0sLC_RM9~iunEPq;gP8xUzai}Agz%c-Z2wt7=m&p8((8*R zch$;%VISXC2Jc(FbSQicg)mQwX}e|YDy05A9cOB*%Wzu3N@H0j3JjBnrByjw3?6h} z(yoPzO+;$8f;2)42)SI1{vBo-%_YenE3_zQs-~|I2m~->x|VY=;`Bp=j4ch&o#d-e zl};n}ff)j=M2fV9itmu1AKK3Q=NL-lJ@#&L>U5Y$LQ*Ua ztAjG1aBW;|R84J405)4>d9B|B|MBiL&VMBC686_GU&8;YvHrW|N&0{N?o`;$(Z;~m zSl-dX*2v^1a^!zT3U{l+xGSl&=w6bnODra*vKCV|jV-3~Q=Sty0oxRTY2kxyLeu^c z&n&Sp&q`*dr9I>q07u(hRggcbKobz~ASRMzWQ^o2ASgI|Nx!FxF4zlyij9T8(DBO4 z1|(0iAG&?ozB>MUd;VeNSbcikHb3tl-{$cG|6<)T32s~~7$s!T7bfs~c`Zy)qd!#T zk82mT9{h{H857L)l6CwsKd$F?-+{LEMoPVNA6a=XJmE6MaQ8B|nx}q8Nd47wG;d*d z3jl$fQE;j8lR7WKiut4!iDa5pB=pTJWqyDPpZA#=*y$|ouxIgg08h(fF z)KG^a1K9YQOl9Y@o?t4=yP8j9u%dfDcmJf1q#Bo$*|uApDm`6loDB<2{Swd3H(%x(PnziX43FYhGcsc7#KWGZx2Y^)8AeBqmqtCDECFbCm8rJh zWj;_0VkJbV8PMpNZvSd$Q)s<{H~_sGi%Qv^2=`OD^A8Wwh_Zx_pD!SIfGp4?rWV{dKoVVh^im^;W%5TUNa4K z`zs$|iWQvcLP-G0+4BykreD0fE{xs>kT5x)bx%E5`$QM=H|-f{c{6<7&vxzQ zG=QV1h}57{i{>Nk8k^bbb-A1NmY&X|&oJ=?;_Vb3mh&lwiyVY*xnx~^cs-8;`V+qs zgV?ufDWyEBjPZd<9HC0SvN1CQFVBmn%+(%~*!(=4o^c<05*Q2~-_ZypvBPkCuj~;^ z?it+mCycGa!&;;LgM?0Au4f&z?v38o&i+qECvA_D7UXV*01ij`Xsbn3?U8{T6xQ5u z0-o#;p17+@cRyD`C+Ax2Tvprih!7^x@BNiJKM*HajnfaMk7>L5IS-5BT5b&N_9Ac# z$(ooDjs5vqzw~EL7_}nP=?r^oG$(B%-EKM-rYT%3jDs6^Y-Ei#`&nWH>z5+~bXOTU z>$k&1BbqJmuaCp$k*$7QJQ!%X8!rLF*w^OM-IqgSJ{UP4&v%x=C$4lOAgzZpmet)6 zT%{e!+p4Z(YV_QHoehx@dbP%}*pH9BZ|`-W=ydI7&zT^jVGZ`%{pBJS?*{;PazVi? zu00plStp2%F5g|2<6=m55Woqi^0z*^^QG=m9>4tp3fptRywfQ61l$!Y? z+J<)st6u)}f4RhHYDge|F=6c-uv2@vhVIqbZ>9cl4cV=^+eGvIS?pycg2X}%G~E|W zWGSg!BFN^LTt_F#;6g;^+N$}>H>Y~@2yRi*MZNU|Fa&zax+<<9x=7ZEN1ZbbwTUnUZ_3K^d5y%nlD1 z_LIG(Bw;`8ptr`=%77-REk_>IKBv8Cbt2Y`;XWP;wQ^`_W_9z*{UhCC1>4#wYk_ zmms}ID?y=#71-TFpm75?=NN7V@1mXIPvgcNc*#4-6(^?at>u*zkfMGk9}#!j7LDzw zv>34PF-?s$;m_K0yx82pcYc=1?(CrwpQZMBDo*a^3@`c75*Lh8BIHPUw2B+V$3x;8 zh?K8%XxC&Ep)w4PsKjav52(a?4B_bA!f4jc5IK+_AH2`jwYA;VnTL!UNd+5-+BdbS zT7Tvf%bK4CICO>OYqXEXMS8U7evMe<(79F4h4Xj&b*y4&6gxYCXiLI%R%mHjsA^SO zz^6fU2|PE+B1dEr7MadyUR>FmdVQ`tU8E|)XDs5AU=3?7xPJ~M;@Zgbl5?U?2ek|z zm#m6>dw*?7US6%w%pm_nW{kaeUT!~G;>Yynl-SJ`ZzFQeYV4lY9vl9QaYuG0u9p5& z{nU*67GRWfWf61Cub^!T|6o9+KXh@+xMNGN z9PN~GN3i8j|9UK9lg%+0xKFnkptethVl%9Px;>^lnm?PH)M<-bwF%Tk*_o}Le#s-t z_Gjhc)gOSkCk!6{PHPts?--iOs)Han*|A~RCvH=T+mwEx;58k%-kQ|gGvvAXvw!#! z4CUtNx3%WK_wp=UZvE`B#k3hDa60Vx8y2O9nTwJyjhSn6gX*LI{HSGP+v59X{b6<# z31r=d`3JJfakl5*=L3N7 zAd9dojhm>khFjR`?hd*~ObjIDh3#j9M#CsxSH-&CsdX;SIhmO#=QU-R+4sPFGW)GZH_O;ED zOLm8hi&0;1wjK{zOuI2{jB`1&0DfeXXuutl00kbkrR3-J0a223L>0dn&Ma*K%DBiX zB=M*t1|~S5T@YjA{txC%znTA?njo^b>A-Su2J|d(mD)b`063a1Kf7oM1`=z&awlI(&3ykJ_Y zEeUp&5H&>ns)5z{k9mVW8(;PaMjpilB#~mI_&gl|u0UDl+Z^bi{-ppvb*KR6uT1gs zW=nW~+qg5X#M~f%zeOKl%@MvnKu{;&6l+- zOit%4a|Nm0Ijc9Y8!#3x9_J!q=BVCDtE;red!kgQ$e3Yt9>OW(JWUTU=lt0$H4L!E zc|w=SO;DG|u%*yRX>r3e60jzUSF|_N2lcCpH6pk1TvG2b(kn9k(;?9wDg}*!75Nbu zluzqp@zPSNWR{B?g7h04i?83xmRyAz2#H!U(#AuLc_>>~_&IaVQP>uwaV$!%cdNcV z#|caQtJrbjOf?ZK(xHqfPPnOR`yAv28D@s>>*6KJH~s=SiBP~biP8rV3Q~fY{2neq zERghgnHCMc>c^cz(^zR)2owQ8RtO_%U2^hM-zebDi5~ z#)FFGU;enz^MJi(;AV)e&^ofG5X-ob6Eo|B7;7`@O|tc+^%m2*DeFzH^`*_0*gET4 zTVX>Ee++V=zh*|Ee79e+E4Yq=Duq>KPPRSr!gdopg9tFVMo(X+O%kU9{MK}Aqm`P-tzj#Kn z*TEEXmaF3>i$n_6jy2%I=`76*+zX(?IIeOBoL&4j5Rj1T@WQ5@)0_ls5oAb^423M)Wj&zg)u1heIJoa6B=1JD!QJfo!WNx3-q8+ z2oVz#FN9yw85el`BA;rtB>u#xrJw8KC06WkQK^z)zMsjrWsF-U_d9K@;T?GqX{=<3 z84aKg4PuX7wC9W&t0usj^2!ba?Es&n?6hy$g^g}N%4~=RT94gvkKG1#+Ao@opj8L% zYD9}W0(J*X7mU&d331Tu&Oz6|em108HE1_4u^P;QEL4jcMXLz>R)h+WvRI>v=`&Ge z1ur79PNHItw!f(>xrMop#hN)rev<=k4EYHffX93UGTAmgMs- zO>ydq_1>nf%0GIfqbW(A7<;5W`#s73Wj91U&ZvmmD!Ej^OvK=v%sfv|(5 z8fgmFMX1G{K~0%gr9pJ;WW}n1O({S%0^Q)O7^%#^@f@ftndC@Wp&OncDz3qd(2YoK zA~k5v>PaX|l?c9&4G`qEc*dKSriUc~lbinl2qK@mN1K*oBwFN}V`5ik!KY()bVq=Q zGNm!kFB+=bp{-I~<2zLF71sW3G?FCDp{L1+sK9rhgB3{t30|iVU?&oT1e%yoN>LIH zEuIh{8a$uSAR1&mW>46MJr+*br#Y5SFbGNP;GmgI{3Pr{kp|aWh)x9%2|CegGHKI3 z#8OM~`sW5yxj=GF%UAz!@Olv~-@@wt`awqhe6{&OO1*{2ukr#H;*6$1Z4dkVd$O}yDK+PQ)*S}~S<^a(Z!?jPmajDaWU^kNE zPLAJq{ep@=B%}z(OHDgmTBHgq!M1NVJZy!eV@d!9V?xvOtZ0Bk_cv#}j#~2>A21SA$b@m#8^9NVstD;D}yRSnqZ zs3biyy2p7^Y*$EX+O#$gH{n$xh;s1V(ltGz3tzcKJ|T3gqvwm4DjoWH{xse>bZg`W z$UQ*EFJx1reEwPXC_Nz6FS+q`;@UxQ$wz7O`rsG0L!2G68|QQBl)Q2jOJ~!rSRHk_ zA7g=vuSuj-3zo>^F>npyccjY>396L4s746=F_22aTNckrt(*S$wG2pa!)Tl?BEk*f zhC@y$f+oTYXbU0=dB&IYUtjDp0bgJT_r#c?1VM1KeaaunMI2HK*~AvSL97EhFJM(e z^da1;(1psR!xd$ym2*KcsP5bn>*Qd>=c(8(0G>Smgy=o)raBvdaEW?wC?Vo4Wf) zsxxsbYp7JJh!da}#X&CE1OgZYI)vhR36pLTC7#EM-i;SP7|#VV0Eh_}s0)LE01W|b z@nBJ51x6M=>OJr`rqTz zWGsyB?JR7a|L1N~v674(jtVLd{lB$lrY~~~%}0g5a7(Vx46=W#H{(mzM1o0lNNh+@ zL8V9N|3zJ6S#hJ3SHyWDI^o7c_GznHH7tv|_{qnDYhUqxqOU`9;&0!`gD@*m> z^*G)3y2NM zP6fQ43rJqpP0^KWpILs*^nX$Qt>TiCYsc|bu?%07?=rMRpb@YZ?U>9*jYx^A23DZb zN(aUmHIa}OG}8g7QNOfd3`5t+YCs=uCx}<*E%yX=imF+q(9oH*ok+ZP<(yKvQ1^A} z5N=K^RH}@LSxBsK(>Z>j?zx)b>H&1vZa(PTcJVjg6<~LGDqS1C*toP_xYj~tQ=@)s z^_aPI*c>xUek*QBbhv@&-OM%g94zWOU$C%xO+GBA8skI@R+m)%sae+Uo$6TycaK!R z=bKHmR2 zRbj$nc|Gd=S$AGt-*U8cOz}iYQ|LUR>6677$|-BwSh1F?EpwX9`s5L2PE^ta7U83g zr1iIx70we8j5sQj$GhK&IA2y_yy7zdhcZgD*J^E#Ke#~T9 zAyh=|xK9vx&+!c>s;xc>-`^0MCI=k6t+1f5qpv^=)_1a61vE2z;6rhxW4tbr zq?o1}6{spQT)ooq3)`kS5KTk*BDQ#CL9%(}qTEsT`Izsr9{>DyhfQP8f5nO01pe9g z*=zT+<=uwkZ9RYR*M&VZjFP<-8MH%|w(HojD;(32uNZn77iqtaW4qQt4|$r`(ZeUr zRuqBw87~}ME{C80TUyBby?-dg@peuw$Lyy1ESS<_U$#*YrVrv6Cg>Gj;wjxM*y~{F zwxfr5gEu=4h`TUd+{7V5<2^AqS=#9F{U~-W;+R}!MEHE;mNW^mYE@ye20snzm_>u( zcrua{Et}_?bn6lA#jYOF-c8|8b5)poN>y$ka7_#-!~wlN~CQy6r(gY%-!{NXaA+5|f;gPCBQwy`KH$!dm<0J@d#4z@p@& zU$-1OG&NK`O(RYNkMaew$w^r=CK2SWE=W6w5U))*YmES%`E-G<=nXID8b03%*R_4e0T_&xDQ_dUt$#u=9@B7sQYRL5PjDeR|)w!C(ou%c=p|Abx1bG#zDHw#Fp+lmKJA*dW8{%TnVs->F=O;{A00I`K zQ&Qvw9NUp?lFTz%#u~X zq#42|NAYIdd(U=x2e*n%X)NG&)hX+kp|`}zBM+byPOu;7%s}~~Nk#J$-QkmRP}k1i zwN63RikY2@>zFPlR#GBnOQz-+EauK8&v{RyLIs?9%gvPy3%PV6 zrS-c}8Rm2LeNjQ|Bz1e06C9LI2^iaFcL!LMFB2M}n{5z?&5sEMOSJ1!OXQNQ~Ju}1aZty0hR2J^FJz}t|T*- z93YY@JrQOqwe)D`{)d9x7K&BiqdtQMO*qWnsMGZFhhzKUjF>%2hM#39!D#6>m@}TbD?|(x~c-Zw7zn zg@kvbt*ym)Z37Tm6|Zbiow+{Rlp=I(8VQhff;^h^D8xOd@_(N*l?E2AYC|XbI#HYR z(glhMz|0jGujmufiH0(oC~PFliPPHI0#>iYO1>$L@p!*!=&C%R*Tv-1c}?H(-uLkO zaQW_aHP5njW-iym+zbP^CP%p|X;aiDE^~anaGZW|Xk{Dj9dTX2*CKeC&>dxa^EG?K z=X!*fhMi{siB1t?j<&la;~RBx&$zn>;%^9jJ{N$<5lOdUyuVmOB%gjXl|)!k9}2&j z9>ycE88Q%-KopoCszLZ&{c0f?q6S0(rXm`=@)0t`ADtFmdvs4OJmEd67gE&}$k|Sf zP1X%Ei~p@3Ct3LHA2}Y2X4Xc3j{cg+HhU!rBI}giOhIS)HK5J)~xVkal*}@sX$Aow9^M0s>=KwJtpz1 z?CAQQOU}VFIsl@JKdpPr+z$%O9jo|?5zQS=#hN*WUGn)edxlritT$ltPKxsbj`L%6 zDq~k4WoMxEPRn|bYb{`R-?nSg?49S|A&+bA^F8&A-Q%VgdjP_HY5p89!tgnSCIcv* zAjbxj#StTf6jb|IDe&YEJMtea){O$e7cbE?(_$59*tpDG~q?t=SllT!emp8&e#FdcvUJ6&xQ3- zV_DiZC4M#8-d+2}3k9+>r9ANw2}wj-2uOx!NlggIdWY65EQIn0`=t%p#}3^rUG9@K zSO;l(HGdqa(*{;aO?Px4AcXl{zX_6;M{5>JG$?>uq9&mWk`$CD(Jv<#Beo@NJ526r ziYQrf;g19iiN(mDa;XG#am7_z+(njcJa|;e0`J*BDOw6>KL@P5w^xQ28$N|#MsA^5 zSRqhe2a_OFT*n~{M!vVasZR29(+IMj#5!HDc~Y&h)sor)v`q{+fGB#|C3lN3;!!*s z_TE}AVufXDS*>90;va@v+O&$CQU!|5y5azCn_H9=tapnuJ5-I)F&OUv#Ya~EHx$T~ zl56EGrXl(K(40CMC}#+WRR|2!{z%F|kd5FVd_qL0F!~L8`x^a&y)^1x8)gWC2;mp8 zH?Ce(2$`gC3oTmT zj&&(~8WJ|`3d6OrV{*906{^*buPaFH9!@Ysy1F+%N*>5GoJ+qf*aDeNpO!G@?YU9N z_0Is82r!}GdJ`#hk~};M{RpR^2PXZ$GE}GWZ~|!>L4y=^M8UZ4NFh*I!(oI5&3CY z7i8f{+a`eBE;yCSQA!oO|6kluH|C_Pk-?MNBRNkLlyK~WkEc3 zV(a^cSW)Y)?6LK`(nVEIR1rAa9xD6(rIGoV@W#sLx#qv6PU*4lChVsoPaG-@g~1$6 zVpTK)ycc3k#HEU2u!?0xFfnQ(Prz)n6B_H+)UKRvhx8U-b+s`lBuY8^7o00lXrxLx z1v1D{yoWs{Qgkc401Xvoy0R&O59HJX93QE*X`)XGo>)db;`FWey0f<02{@QsAF#%% zl!R(!4qbNKd~8P!FgDG=C;%wWP+rywHSofJaJ%jjwQ3hA1)kv4!pEuiVccXq#s_5c(oBGQ@!wAl&Oax z^}yfA)c5sm%5B3`raRE485rnc^>fU{0yZmK|LI+yb-gp%KD%MdFg2ipQ)pR0d(T`c#LY!-3updgp`t{M} z`P!Otv3OKzD~&F$bvzbCWu{1Mw0c3)LmuYe&;XQ)zZi7+Zk+7bs^KAR+3{)k84=Ww z#|!jNZHe-{-AV#Joa+56kn}i?5Rnwen{Ao+xrNwWO4GqMj2&_OPO$dc&E(ygr403= zBSQkp9Qw1kJ33{G8r-Jj0BkQ;qc?ovW)v!i@2b#<*04PL0$jC_5McCl!+t1D>tH?W z0p@xvr*`^1kNP%43XRe^jny(#ys+^XSx;pv9LW_{>;7iue1GB|o(dhYs;KnpkKP!% zR=D?Yc8;cyBD^F`S+?4F6{mR5zw_76?Ix}N+Ep6=y>Pc=BrPo+Ib8=!@(`fN9;RRi z^p}qhKDG6}SxDozwB*kIst3b&pp62sYI^aIHEhYEvpp!-77Vi$=DbVhu7=}5Hc&`S zV$>3YX;iU)yv+_!Eg0Jq9(z%aSvF~2uC&dq`ORGKS z`a(p_M&$Er2ZbkdKkIh2jWIZN`H_K9F^}BWsno>tu{^$ZnjNAU$xnBm|5*=&8nPF ztQQ|WTu{&`JL^wSnQvt3Ft&$}2EU6p&X~hMJ*WNCt7=MoBw8n0=l9#sIbdJ{EZYf% zL1=*#?n)oNGoAFZzW>o(7(JRrjNlp@Ci#-!U5wM$%>4h;9hEnBf7SU%yCygtxpD2q@|=NJz+E|9xuaf1i!2 z=wfSTBIV-jZ1DdhwpFi{lvOalbGEy^JTy>-VUYi-nqJm4M2gTuNBBn)Q6N&Lduq_x zo4DP2KGRv|)n7@`=UI|vMp~wqTa;w__eV}OV3%5y*!kQD$uNDwt>0$r=rRsDWJhH1 zoOjX z9bk}1DO76E89p0fay(DCY8+;dMR7b&vCacHD2_UD%0g91cCM6N8#C$To@)U2^q2x& z8#W%|q2E1A)Qrh`ti)S+#!}b)Ka_oAaHY|Z= za?X9PZrxM2PMufv)!KXQAN$w(=A2`!G3TiNc1SZcU5!G}s%=S><}8z@w(#t4H=OhX zSe;L~S7SVBqDi~LfIcl#tXbuCUoYbN^CPo>sWz`rRPbb;H?P~)^9hWuvXa@7dP*;) zcsK;mV%EW%@l2iHRyIiY%W#Ez6VmK>JrUaBi#}TcAXlVh zN7_<4N^MBbkJ4Yx+`^iqt6noSZZ?xAG$&1Dri#zQ(q*+8TDe@(eMfLCbOOp+$mPii z?3{HH8+eafj%3{Y$U4h~&I?a;$5&wH*LAr46QTfaiXbqwVW#J_iKbGfAr}I%D_L$f zQ503OJ)*NI~6?F&6r3r?i(bx=hH4|F2 z162(X<$Dc+bJ*&z4WEnrRb?;iyqUUDCb1a)J0kTlOi|MZ#v3h-TPeRfZytG6iFkr* zfUtzrVme9ZIoDAgekDz5VWz4Qo5`x+I)PpFx3%0sY_v6=3OdyrcU?mxsF5b9# zf?dWjItn4kanYeVIKbnl$+1^lUkYw+qA8B+PqH8C{~GqIR?z918mB(F zcNuG};jdM+ajk1zVqB-bfJur|OHNRwporgiw+n4PJ3b_dqvp{6lEk} za_bGuMjga^RFwp!7uuq1;ZUQ5$B6_ZNK^9 za{AVq8zXG?Gs*}4!;4v@<*iu39uUlk+uF0PmH_{JR)NCi{}^OLo zR(qfMAkzcTTY{g^J!^Ge<@6`Ynh6-7DPoT~*c#O|=A1vKe1Vkc2}I(K2u{mXl&ZWO z$iW8FONmIrFQ~8vnJuTV_Hsv64$h#eq{!utBcsr`EW#h`{rmQ$aUX~#x+dV2S@4B& zN`Jvn^NAvr&dC?d>gE*br_|jEBzFj>a zbQt>&7lt#=%H3D+KcA#9T$6^KBHBY5DQ-1rSGzw*?NP1}*PaZV+(yi9b_8pe>P7I# zhJ2hIP>G9nen!$dqz2>Y_!*+eZA&cXMQz+BoknyK)jZ{ z2}{FA;UYj}ZjM~4Rs82jkdTEJ~JdTE~u* zGsKy0;|@J!IO?@r+hZ2w8*z|nI%>wgR)7ANih3K({LlwduK-z%A;|6-&@p8Dm16UN zvw8RlWP-ON<{g05@E)GQcejrQCP4<%6gU?Lvdj2OO7f_=Q9%Gn`D&P(cnL~?ND8+w z_7}DZ-rbA3KXP746tI}mHmHZ{)cCVqS=;cZ?>~ocC-eZOFTj5M0RFB={yV|^t7KT@ zKdwdoJHh;~4Vj(lUfw7RfX~ZGTT>=3te-me3KX@x2{MArA$jekaG=Du)Djc{jnb?_ zbv3ayTrdNg6*T!OR%Zo(2HuE9WqHJ4{u)K^d1zkEw;DPd8=I=C2vseswOpI2)_N{t zVgikT&swIVO|MIiEuN<=yUUGVUmJ~BJtyvRLM*gP^gw#l#lxxUn*Fl?>MD~HNxTS$ zVZ!8bWir@`kEqj^V#HirroF1U zUDG~kO+^3QVs)+AnmP-mp3aum^tK=Z`NkG{rkugnRvKecqjVf#02qe+{(b&vt?@Xg zn7+hHPyNC8NTtb;WC5ow@mhIir8D&kDn*ap3vd7j%YtMiE(28x^N}$!jcMD8dAQP4 zsYY2TqMm-C(fXuITh*hwXr7NgnQ;}TgbY=av&F-^b=^c(dLy;atBtg#sn%+ZqD9Pt z;w2I~-!jsu)vUO<@Gn#<`Zl)l$r$eWlm0>W^v7N7Tl-u5A9tQ+2u&JIhFc=?Y*#^U z7OP>JwaSWlZI!jP9eD$YNtXHXK2)H}IW))?%FH&HDWg`BZiTxYlmsz!TFUa8c$_ic z=c&JeG!lD(Obct=*}BMJP&EVZbijhD4t$uBY3=x!elA`}_)NZiLzrcii4&2a0~f5;x?4$E$_$jU5q@+Ert&E7yu-BZZCA?5+qO64SiI#nom=kfPp-$5uWQ$DfjL` zZMtbPNMvb5T6YOa`0x42kfepIJm@>qOz;Rp zrfv`55;Sa8plm(_1|r(%x#sFP{=}!E+CoIT7>1&@%DLki2?Q4l%Fe&ybB>Yb@iwFa z$k`~kx^L3?+p?{eGLsW8JZA0^wDM}lt9QtuNDUoF@7Ol0r==?d1=WV_5wrj<<#Uu} zWqVUJ?cGPv!9J`vB3stc`oZ=XmgB? zyLw55WOU5c4k8Y+LWvREQ}*butzlgMTLLk`VGYPLca+#NckN;1<$^s3cg10Zmm8GF z^5v2}3+{ql4VZN-b=($ePzUUc}qV&}mtj_3W;NX~oK_(QCSpKyHR$t(L8(@HS7eEO!)D zPDgWN`l7NwlnGcJ*;K_5mZ*onn^q2cu&kUY3=Uij1=SUhmF*ZK(_c>A*>qdIGg)e` zfo59YS}ZqnIL_p_UJ+ByK_9I$9CEAUB?kqoDCF=MQH;Pz(QKu)iDSpUR&(;L$9~SB zS=68q+g080Ux($K%Eqry-Y)(n$ecUzbZ?qHFDyw+!@WxsoQ44I@FqS3=lv8d^=+8( z9YpWXiM!a!{135P*W37PuMmgeX{O@AP<~A5ISErof}Kknsn3VF(I#RHQk-($q(RLUBSjc!y|2rsddeqdpxSG@Ymvpvt>`jDO4 zbmpUBC`Q9J0J`2)2WVN-<6w;A^9xr^krP7Jz(#ZTgo_`~Hq+ zjto_)i)FEnE-gAm7noa$Eixjc70Yzy#|5JS7xK?r@lj)g85Bojt?adLq}PsvBG&hE z;K{hiiwk|AXd3b9L|aQS<$D{}ARFD`W5h8a;W%)T-Shr=c&RueGNhzgBq|A~M1^wC zzfn%OE%jMmB5|W2&BFvP>5W$Kw!(jb{Xsjgn0W~=>xI-f#ciH-2`UkL|Xp_gNtk4QVh;kZW#f9S2-rV1Rm46{Gq_S}heJ*h0YOW=r*V}rJ9ZBfPI(Mf; z-U}QxRKfrcqu>v74TTA{(xebe;g?jL?_X2H3^xY_A{8aq>p>h_(p<&YKVvt3k}I;D zyiPeu*3QI0)f@ttpSqKTs{Di1HsGkqi?{YDa z#>394JwB0V_9P4Xq;IVbgHkmteacl0Gd#y!g+(TwsRDt~4KNZ?;plvqM;o#k*!?M& zxZ9!Y3jDF6;kL%_8Uw#F$4ly{Lr?^>=kd|>SX#rTUWsj<%G!G74WzjOZmo2B?Zekuggk9El0vra)VxT}vcaz43H7$&LgJs`X9q$G`q8_~FF_|_DLLW&qwkZ2#BlE` z2f@;Kbu2^Y*?oFTs>C8%mQpQ&MvuJPb$0h!Dzh^w5T!6NWAWL1NILkpR1Xx?@-X{6 zuDXj`HsAKqU^0YD-PP1t+&ors*N_~l9)22cz)8KqDMYVv$pzPZu#ojywA@y2} zbYxLhhe&phQTRSWaue1Q_JBU8S6wsqfY&hu5~N2D=@|v{3O|45RM)4fuu)wsc}|?) zicYrUq+FYdgy`*mde5jGG#1~3S?B<^Xh74nO?lqO;*PPjo7*B=+M;mWq5)bfo3x{< z5V$t5(xRj7$0dy77Ey8h3x_pqV!j*T7MUu31h7VWt6e$h?W{&@nNpFt3SZvMh?S`h zUOtuF7FeR>-q(zzU4mQQX+vn&Ub_ynqI0F9#8q+TE{+;b{QGSLTh^yr1pbyJ;jVc* z$;Ga!Ew0?@$6g#HKTdWF+fPTji5!z-As2g6 zoFY7>BFGh>9tuVm7{To`E1eR1zWlvB&rg=ryj`yj%vZ0Nb0y9=-FGgkh*Bl}mpDBk z$;AXXC1HQa{D8P29)M8XvMI*(Lf$96q!oq;3~U%?hgkMyE2#G9 z`o&(3(O!+SZE2)QfU$N#x`nYmLFV35^1cPYB=7xPzOwUvCQw~AS*dsZY;?{!zVJAo zTcn~;eiV8$ubnaXX=gXDTv-{MXQNb+f4u}Otes82zA%B(FoBw4U%d}`+EYm{MwYpl zm#37|*^mmphhmB;7c?BlDq!$~@$Z7M1d;S$!gT|0&{1P;^^AD4hQUCTQ|mw(&bT`- zTOvDMS(dsuN#DfD_W{k8tGk2=lHS8BxWfsG;n_sF$Hosr#g>|4Gk@DGM4t3{rSBFg ziFPv=+A2aG@=8j&QgV2YWWCxFM*Qm4x$lC&+lD&b5_`F2J?S9h2F@3cLM$f-=qkuv z-35_qmUinro5XKM7MPD+5I!U}dbr-qn03$5@=Bi2)QPh&u&Ncdp$iobc=8IyC3s?z zNp|gvGn#kBA*H5DNowmxB+;gjs8MSgD|paHK!?CoK^EVSb zx(5pax;9ye5KzgAlV7mIUnDVKVSC++H+T;3PAkj0WE{FyIDZgtEzyRLPRyiIkqGYI z>b^k!!G3Lj%1cvz1Cw~7e+N#4{$p_RKSsF!D`8rsIA%M?kHUk@_P>q-U#t|jOU@Ajd3+Bu5jh?UwMWPzpWYcZ7fUVw@3?q1U;dr(W{++BFjlCsQ=ZR!N0tw(OYl1 zMvGopn#2mFlspW?rtKNoAv|UWoo!GRKEumVrJTh%L01 zeV1yTlF9<^1ff;vkUj=ubVj9DHC_H$Mvz1>k08DVF`WXR*PRGZBR92xV3lxzQKO&| zx1Nq(I(Wxy@y{&G=%t~So!>%2qMGJCZDNd+o>Mi8w^=>$b_z;*gyPUrDA}Ucl8L>W zbEcJJr#ZW=qok{-L`3=JeOy^Mg-BCCnue&nlO{22W^87)f6trqTkt&Ly!aXGA1AT> zQN9HO_{Wcl|G~rlD@^A8k58hsi?jLv!r3cL*~&oE2CKtcx;ziX-} zJRit&Ez=0Qklz%Sp+**4xf$8DZ@Mg=$@?S+Y~yXK!b7$=fE>w#qL8o+z`=(Z(XF#P z33sGt+o&eTK~r6fKXrLrdD)q6zP~@Y@d1C|Cc6YdT!V*rhdtBJ)?|yp+Z{RpsV$rW z52Oxjxo7_AE>N`{PSSkY%X*$a{YWU|#Q=e`X}tB?ZOZi1`+7ZIL=%;(iXvIo5eLST z?O8ZuShgV^7lJ}3*#=g{Y(5F@XrY}Zd6%&P8c%Q@$RuFtG|Y6j5Jk@7Nj zyn3nxObomTCd|t?UluNl^Rtb9-taRnA@!=9D7~D5fAOkNbzgYQd2L2%z64Lrd0}oY zT;~9rB!9L6Z)j_2YE|3Jf48?NJ|+Z6Q^|A`^6NPNV&g2s=ThVAl2xK<*(Xo4Zt1!^ zE!}eMV`;xYWLkjaY-+X*rEMljkM_Kj?{$jCKgWFRxxB|NK)!$T=VN|#ozG+wpST{4 zTAz?9V2JRPZ8;Z{WoszFr%vpncLZ0SF&s_|Ha>L6@nAv^#yM&jo5OD7x;`0uY?2uq z_6A~I1#`A9`vGAC7Wq|#od~`CcL)Ev#T6(M^4VUd{|!ug7y`_CJ3qkebBh$vVQ=R@ z5x?a!8I?aG3t>0T@@xt>_1GSQ5nR1R(|qb2UG>V7^V)T}p+yr(<$JDYA{u{&QF39> zAV}I>QAHoYRTNWjKjL9#<`9I3@SErzb3mGnz*KA*S^k*0o%wOZ6ONOSd5V{}D2jnW z)HLe+X+(qVH*P!B1r}m&u4Im>J`NLm>{w87Fi#}a^+05rNbarTRgc)u3MyYgZtDXw z@DHthH~X5x&peIv(c)wia^@;*p<0VF*dhjaSB&C-;-W!SvZnjdLwHijQyO}z#OOd7 zs?5Exow%PF1f(TH;|9I!WQ7RGe=Hfke)Iq*Ox+bMCx+K5<4$>vG(9D34a0wvqR9^4 z(xEA_Cbx~-lMcqcL-%W>Un^60OBzSaU`U5Jy+ySKN=x8QdHhvG`HNZx5b>7!zO`3u z?T4@Hz(SdUQ<}Hn$AGX$QkhS}QvaRof1FbFUpyGzV-=9w_sd=OKh%x?deI{JAHU$= zBCWbGV{oh(d@tp3S`DLWe2I+=dA)SEcc8d)1SIc=zWxNEBbzBa~F(mgDiWOrC( zwA$iL32Zb4(?ghxPLPgG6PkkZu1W6_JT8n$Wl3qO0tf}xe}L7t)Ts9a7;3Z?{?0&! zR*u6#Q9uL}q0VeMdxHAB^kVv>l_6{RF-*6$?soa>D935)iu$R8`=&P#?H9J~{k9b^d#wgM+sn0!cYmOVk2mtx?T+dCZf_OuvqL7{)(|S6?J$nxw}8hR zLW{>dDay^mz8N9-xqAO4r|>eKdn>h{74LHJmk-L04+8GBemlaRePGtrwSEbA4{cff zRN#h>v|u+jZc;xk$2&hfUsAuHa*G=LTVX)xe$Dsi{%U{1DqX19{&ng4O&SCQs5ZG}Pp zMi*m`*`lFYZ4$vMdt+=b+`jpDa~0DdGg*WBxA1tTj4b4j>L+56>x-cNF4Q>T**vnw z=DKx+^OJLMBXKRy*)vwYsPqz2@*OgijgiVPBkw>8gY*<>^i;)xpZExkOuqsuo6>;~ zs?v%2cqUbC4|lAh(&8%tX^M`7!kEQ>4x7N76JQx}tvuw+#O0W+ev_*~rwpw%99z;D zjCfcopue-&t1%in!%%ZlR3DXzL@^@Yz$Kl)V&G7LQObsG$A@{fW$ey8cnadDtxS4m zU$yOSh|Y!$S9adw^8l}GAQteHg&t67h8_hmhy^s&Qo*gikda9!-YBqO+s|emMx&=T zfT~phjOOG}G#9~{y54a->->i-YFYdAjejPQQ59onYog&~7|RZ1BzU43ogI9wDU#c( z$vD}EP4k%+oaC=c^LQxsFX5ar+@<$(i>yZ7)XidQ&Mz0zF>n%6AsO%}{2_~a(41BO!?X?$?|;cqf+_nO zLsbP6^)B3>eKR=~aJaE8IsM2kWxlN5Y<(Cp!g+$rIaahVoak+8lav@;CLt~>xF{_A zyf$)6rOK`p_Yc-?mcl+`DF6;rk&IZSW#%=_B5V(LQXb#Fj3tpPrauR{poRJwyHkeL z(q*j9!3et<-#0lnJ*YJ1Y~L`E^m|H+p;z7Qn1QusvPL5THMOBQ;H0}R^>3ZkYJQpS zv;rX-YV2_c`+1Aiip@mxIW&yA#&mAy89t#)HF~@yinPFbfHrUjhZpe+ zY0KARd)FlAOnNLx9K*rUaDd(}0Ia*OzJpYBAA#aih2m`~;Wav-wN!x~%gpmSBVg%93#_{ztI|fy znH2aX^iZnd5^@RU9oG(eJ~t{;J?B6>d>e0h!UP);8h)1s%x(_{>}nSd>}qr;)?Kwa z-V@JP@!E`Id{__V9pI~U?e;Fz)v4IaN0Iee=Ot}~87mj}DLve=7c{yx37yfNJZU@%=W*JKUz>k!(B=S{EQ z2otrC8pX$q)rp5pK~N!zE%iW?eB>Y!QBUENfYeU*mT#@XKaA@0{C{y7G8n$xbdZQLc6bTg`H zAGqWx1R!f;1z84DXC^wK$iP13GDn{A_bB5rJk}Z9%NM$ypdC{i(rq^sa4TqFvt*}$ za{I(&DjFwN7;rURn3xx*QD|pIMmR|w&-P((t+8Q2)Og76F29(F@pD@*BMvrrB2@1( zZS(mx2TW3Z)E{I+f7gCe7iXF5e9OaGdvhQ-j*=~=rgpO2>UsVIh7#E^#lZZi#aX$& zmGQN}6Si29HI8-)v66~>+lJ(P>RHL>eA`|HbDLIC?ZC?UH3HwJ;-;v-Y!~D*K~V@{dp^Yk!HIemt`X0uKFoLK zHUdQcNncwEFCw*MQ{~>M1H_6_Qb`&)Kz707N6BSxP|9pRuQV(tm1GeNN$M%}mapEl zN|&C?MUg1mLzAKw6)kIS3dE#e?w(KAFBGF|bfJeIG#=PY%Nz^a6d@aP4ObYe57=&< z`uRG4oni?V{^q&HSpnbJZDZ0f%!Ek%N6a z^SrK`#TlW@pD1BKN#(GL9D}e8Rn;AThT)7%T%di~jB5FnhGMU?5jzSm0lqP5Dc4iL zIjURD34&{;?&8!@h^Itsn3%!tQbZ=;_D9V6GN`~lAIfyCu zk#5YpFXK(|vsfIEyLFyp6A*Fvt`5Q?W5(h^adt76`y}`3OjWdYPb+Cf?DU|Z%;Pkp;4xEK*zsRK^X-~5r z6@c?t9~o4v&?C2LQR%)(JdJN9gbDW83sWMu3Us;RNzR0@SMd@_;-|b5lZ+(_rT~;d zgSk*Vq*27Q0>x@=#FT2aRbLHO+MLFWkSU0gusoj`D}fSvO0F5C=kcqGsbAYT40E(t zSk*LleJ9jTq^e&+0y@XI>YkLTpJYRdd#Rf1 z5rwc_FvGN>L;L=;=ZoHB#<)>0 z?Uj<9aTk;yO+@Y@iw!N4p0~{pphu>hz(g@B3?KlR>tOvbmmDs&Vr@!|Vd8TqbEymN z-dK_w6cg~dxgYGMX@RF~xzGov?O*IhybFtn$$^^_A9j-;Oh9!BS^ClVToO35KC7mj9m+XxUUwUocZX^)#8^R$g8b5t!ePEQt=a6^4VA_AwQB{n-cWMxa=_f*IzitHGWA!}_dYwXb( z2v_FZJBIJJr7di+p+1SJ9oVV~KA|f&mO^fRa7h=^|=eBc*@K$-%gt3}XSK%5KgLPo# zt@Rk=`jXe1?Pm`Yf)(Pr$Tb+>@j=hs0TMc*dczw!N<$D5V-3?rhuJpR4=%qtGvDlZb-6h>1P&=VUy$gj*^>F*+wt2)r}JdP`q4)qgFveP;x% zP)8PE7raw%-6L!}k&oCiOlQE;?*-8O{EBkbj=D;dR>u!nOV?dT9U;6^9&mW>lU6Oq z9DjC%zBj4dM=aX9M;*mkXt3G1Lb*pBJ^$~oTl#+OyaP06Vhhi>y#y;j=Ny-mo_&TF zasba3T=>@yY%S9VZ(zUE4@>FpP-s4Y?3OzNR6_vg2G4K=8PHD<-Ti|ZwZ33pR!ncF zw4N~^OdEu=Q}){;S+OG}xg}=P6!99`C7WId*Z|8m!bcCuB@0SFAZ?N{0ZkV1gli{_ z10#(T#Kc(^*imn4kwe4WCstumYW|m>I&a>edHnJid%TmP<;3hw%1hTx>HfBnbcxK zg{8_J;~hR9k58`;i9T;{!?{3NeS!F^@z+Ec!XQW!*SjfriMt=ROq=~le#L{EQGT{> zw4Xq4VwIa{&s@7V{^~yDxaI1_@8S?MAyMk~e08v0Kr%~}0z;++4*la4mI^XcjwCiH z&>^~t(B&*^6;YPlxhJ_f=_^^r0TmvZ*2GgV+Rd+QWGsy9@$9_Z2{p=*db3RZ>+^>y zQkh3n7<(g~j5D)CX`0lI_1#Vhy-dPuu5|;IKBW9r22HY%;umFb)!ML_=WK;5maw9{%pJEz9&4k-T)U9G*x*B@xSCn8kTqbDX*DNxq8y{tuW)+A>{pf&7MK#5xKzH$K%kb9QE_MOeV zzmoNR+;{wL(rP|$M{Az@I&sY)KjZM}wAMH^eVQ`^8SUySkqb*aqA8v%QPHz-?F~|3 zo%2>k-g6e4_;fdv%~lgy4o$@fan0KbiR-5pI#Pnb2ZeL;S%)Kt6@=uB`WexJ77(8B zQ&bA(;OF7s9xpGnfxz^yD8~L)8`ZGur^KJ0H{id}*W*X#-WAA?XsXim@)(Fb8<}W# z%lB1yN}@^*-8CDki?N&6XNrh43w9~-FcFrD^H9Zrhg}$Yge$11la*4+ifP)u^0A=G zZyOTF%lnmlX%d?|INpg>3v=468=TU-sj5?GdAlkO;}pa#+J4bu6c;=+G)}(K#)Dv3 zXaN?YElG*$*tJ>sd9#ns{jeqfWWZE}z2u9YZR#uWJT3v!B(McQRxj)txbNl2vKJ8p zJ_Y@J{1>Y)18c*`cB7vOKgH*SYVaV}!anX%wrqh?Yay2G{qok}A>eo8XlenWH_&Nt zIK2v)Z2%ni4pCFdvolTjbNmoeP?jeG5yntCCe!r%@IJM7XM$1T9$7jJGjG) zLsu_h_0OH$fsV0j=4~|hH*cP?YX<86sR7PiEz!jKy(>+@ZMF3X8Y1yd@Cm(N(NwjN zwU>^N0Vq7J=9jmhpjXO9#A#`_!Wqa??qz?<0`6e4V(r`CfFs3)J8A(04a=QTDWb~q zW6S-lh%1^p`$P>g55gIQ{-Mk53H|lUB67*xvI?!n6sjDQCmMgtMW;Bpdvv@dm!?w5 z_2X^x#OSZnF7e{;?4|`9%&t*s6?%!w8a7Ew)1My=Ap23aAPP-_@_yVPv^qy7#28Ya z9fa!~j)#a^H1~$kBF~!(sX^W@Ppbq7hxn8jxrN_)VoSBi#^qXbou2-Z*5&YQUs}dU zbshRfi?fpq7G~P3-@8X~E;&iAz1hi@1}55zD5?MY>Lk5NanG6TUSN_Iv%@}$HheAm zK-v&={mQg#bwsq^1WZ=EVMWi=^mqD3b~enBWva@#R(GxF+g+V6N$uFxu1D&+_?lMUwIeJTOX1%Adiu0X|1DHc`OD z{^U+qtw%W*n|IkxxxQ~ZatOfc0cJGReZ`Pn0YDhlNjsDn)lK$r)quZ^?68018tFmh zLJVMt&{=Ai1>p-&k(R9urCo0sQG%3`eiNhqWz;4^r4&>#=}$G8=tH#zSZ0<+kJWVU z4EYLt)z=7F>&4E9dV{bav!%5t2$%q({Be=01@-xr0-@s_i}q9BZ|X{Fyk*K56CB2D zUFXM)rGf>^)F)81eeWx!Ek?#rTJN3u`_rW?2NCUDCZ0BYwy2%}zy2uF9_Vx{Yn1=2 zOb}aZ*qY9!I(#>QUMgI)c5QA+@6f^?y?;yAb}&BSM=(M^ez~Rf(qx-GgN~pYSlW-+ z9Bk~%Q(M`FKOD8tRr=fZ5^YODc4lEZjW?kJXp3EKWydWW&uTbEZ3q>b9I~2_ky705 zm_K?u*-&+j6hhMImJ8m|^wE*C`%tGG*2DAlIIPs9id!AuN)s$Swz*>?S7&@uS!z+q z#mYQhX|Fzfij{l}fI%H3`eZ;7hD@D6T(kC&HZw8S;|+wAAf+4gprO z`KzepYAb7qu65N^skT^~)-pOUL2AozBV()VA+@U#S9eRlRL`hZ_IgGsq+1j^dQGW2 zGu8UCnXW`j66UE1HaXUng_AR%ni#{_^{H5u@Su7KN zqEW_@Wpb#9UbAnHo^uF^=9;$HlU+C2)ndII;$iKI_L7P3MA(|Sb93nK1Ji3lvGztl zSa$!(Wy2k$!|J+cfE6na8T#QTL=lGolu#vZ#R#2JqTOGduv zH}7y97RmlepsCxQB4zTEUOqbVeTx9>zlTyHw6PM6ldaJ%ftj6^bZ~51l=TQM4o^;d zrESbPb5HIgcf^xRYK~ydj9rT~sXT_4JyiXSj`9rMzE zu(V7h+0H80I=+^byM4;LFteRosoPhiJ0w|kE$yi|YL&K#H>ZmeoBCkP;?6M za!%?5I;Ct+!1soF!$cQk>fs^IGPYN6bbp^A7nk$$Y7dV;5_&5AGf(^CfOFhKq3z;_ z@@sWEKx}vq{_r4BT2W@x=wQYCn zgg^ROgBvQErihb69IsN&h@AGc8_*=bF*6eMK{68T12Yo*gfbH1uu7e9IVq<60{38> z!wtBzY^7ufvTQR2i3fXEU(m<5eLz8Q1Zc6^1xKe*&eeWiSc-T5*wepWg`Z>4JLJSZ z4r50gUJvvbtwELuf&W}T&kZa6!28f~Hq2K#a@9~Kq56bI(up1&a%L2StKAyVyF-Cv zj<}-0Ch}KLw9ne6ZBQKBnHn#4<&6^NBsq(h7~hJ0Y`A7=br-cHewZ%EO{#00SDjt8 zW*jKM&4icECs|<+EP>Jdkyq zP&=t!L$pJT?S&v~5k3LU4kgJBMU!w5B}43v@Q0L$d7dA2@UVGcs4i7ncyuc@CuZfR zN+(Ckf}5cfF*2)36DTn*&Y&kWXbDIS20!yMqT4RgX+TQpIfugy&Qklzz|os znJw21H)Ze04Kt4qm!rG-jw@s0IBUr1iAeSwR%s5)*$mUdxlz&0*g-2U1I4q3^P%!K zpwWe>Y+0?@g>^%z98jJ+;5Wph1gLayrSb3!!TY`auqqwAOY@3M&RUuk`e3jVBm0Es znYs7av3(t9r*Wh{A@iW&Tl7J}&)TJs3F=4&Y7yK{a($d5DTQ6UNE6tC2xxB~dfVPk z^kG@+Be6AjpJ<&}kQSisfr)1v+umFT|0M^m&0ZaMyr=E%7CDjU9d-nSQZRSIPJN@Ta8+$->*~r9Qp2}cd~OeyZA5o97Vhxivq+cbh2%Y z0=OxR3-?X+2nr(-c=Q7I8S-rsBPv~1+a9VRo9AGMZ!^{PSUs%v8!VkyUwtO^5Tltv zWKm@ZnD$KN00x&m?-Xb0i6f2Fcr+DOqc2JdEu5ZFP1?zp$puG+2goated|}<0GN?_ z3;}F3Lk`1PaMM+oGQe^CqhNWeBX|s(ZJ*>{u-fV6m`HRHNE^}gXbT1=$0mjVUQO28 z`4&_?BP{4W%mS>6R;=C{2l&OfI(Y`o+7!4lM6@%$lECprPj8&mX*E99`L|MqLRY4| z)x=&3>Lhr>N$2bu5gJQm%&7Ubz%iEx(X#^?0kWaf2neo>EK)Mc1DsrdeFpgsvqikMnRmWKYO{zC zsRm6njRQpudaGPhk+X?Xr1xSYiB2AFQ1vIy!zUq7Wlr_^2$`0YIwe;z6&Ham--?QE z!Ps%~u2a)*?p)^F%&HW^GmvMht7n(-ek^u)yIY1AET&nA<3}*kzbp8}|KoyB+``PM%+By}eUB{Bm|OJw!63%r^^$Y^v1aEk9202KU3%NH_F=OVaSF?Dou((OtHw@}OH8@6<>n`>f30|U z^4_@N#-&eqpE+h6DzT4FP_1{I=C&S-I$hD<6@X^?q-rsB>m+X9dLZWF{i*^jK}SVv z=%_XgY4jFo9^dGM0&j}`-7&@p(`32YZ&_UW;?BN!+iwW|1->zV0S_)WcWVG{m&#Jj z0Q%;vbVg@7-0)88LM@a7@mfh7tU|$FRWxT+@&GK9KlQi7&{9^WxKVxfuc-u8ipqtv zRaE|sb`#UPoFaOX>c3T&X z)&khG%#8tP? z)TjfaxU1++&V%cON2(mnqv?dna2kW&if4;2721v^`PH0-vgJVMy}Gu#X3MuKiyJOP)>Q3O43<5c^%i^~5Vw>)X#dEZ zs@CFfa&$%^ZfaVDKz}SE2zD)A%qtURsWiqp%#|RCquzN;Gz>D#E1@CWOb!Sw2X8PV z%t`htT_Y8rCgKptQB6ddZbeAx=R*DEtutZ1lc8I!$(8RRFhGGA_zFCw0dfAB==4FQ zsvF>F6%_4UEF|ncZ7?BnEkq*xE0%%yDB%V&dv8;+UiCdUW{;xPtV5c|<#cQUJ`9LXcby?i4f?=E|Y+ zL>lkY{i2Yu>IBr`n7v7ebb1WYCVI7^s}}BGAgW?xL#2oaq5;|*l13hoR7G`&f5Pma zjF=6XGeoGn3wSH(vui=K{z5Iq=I5K4`z zieX0W<9PG%WpE9j!>=KgFea9a31BZQ_-SbZ=* zvSS?yYNtj)sLUC}E8Ehl-+`!`MfWtKkFOLRCC|2bYwCWv!`N7TdO5OP4!X2GkD)%*@dpHbP(Zj16`9U3_uowVh zjY7%g&vTA4v|?dy4UKG#N#P1-@d)EwgcO>jLZ9SnoMda9OlCm&rcXh!pTrGMg_ob_ zE%Bx%k)DxYBfxWlJq)T?O48Ubj$BSO0d*X7D&YYd3Q0rq0fZiedCjyb1g1_Ke~osN&pSPyVyK_`Q(Ugu;bFtxO6-O6RZE zDdj{pZKh#t|6!YTMliNcdGDVXT9sWcvD8zCnVF(;ah=ZshcC0BhDNE*t2j6@y@%|C;>$SAey}l9t2lT%S z_zM4V!2efAs(;5XYr=fDnzw#+ZLFlP7$;gMNa(W$;iJtG6L$!}UJ-W?_Xze8`6bEJ zNuVZdnABt864J$&00%(k%j2Qcpegb511BvtDtpqISE*_JX(m)JYl4h0yrF!|V&bY# z+z47K`gmBv;~P2m{o3N#dYSz4JseN(`9F-kW0WmHwk}%S<*HrgF55PC*|u%lwr$(C zZQHhOz3M(^ynF9?ef#wo5jk_sh>To6R%XmK@qN|RIGjKLnl_e5b}9&gh_-P)9q3cL z23|c(-H9N+I4jLJ^q{f(k70D#IFd z^|wvm|2k5>z}IneN)DR0m~mc4|0Q!{`izX;Fj;$!(^;snsh_M2i0NS*MJLn25bnFr z{c=Gy^gyFzbNyRT@kTJQAFRN5dca?{wTbDPN?l zhWTw+#|c#wFnqrFdUh(MPu;o3d%bz#OQ(FhoaeCKi75(md#l=LxmGfJa2NfV^tdhc z5>Dan)^w^g7!ul>))Ri;B{B%vSJr>Cyq#kvp;oZcEj;o}%44<0%47BR7!sx-L$u&v z($w{M^5CGLEZWxF1pw{S@0-=4oaSKiTv5sFPG>U3F>IQIq=lEV_-?qWk8H3#&e-O0 zjP>J>PfnBQ#=|uq+=Z)jKruhE_&P~V0rvQ6(e}K1)Yh+i^&PHq^3(^MtfxMi3VjLt zbN@7Vb!({ny)4CV&ivkt)rM9*UM*jkIP;9ce9;K@nEn3$Hf&FgL*$_G+ zds`}XC-E^qsUkNLF6+~VLBAt-n|u6MWYlwZS>D9_nFH3ow#npL#`IS<%_;i?rbFfD zArB4i#H`OLAZ(XDV2e1WiE|;Q&{l#jHvY)g4?&k zj5tweXE~|e>^NiA<_u+Ji61lhNr@jcvV)?pA|T_dLt07NwKua!ELV|G&sT!ud`qxa z#{)h8Uu`7(r8yceKwxl{s2B!Qx!hsp)zMwY1VuKEL{~F2&Z{*kCRlI9W-0xQsIy*b zW5?GVGvmnl%j-xTYCFZYKVLr6p*m@dr7bBo9yrPChu6U>iL)NmNyX0t>ljt9MOk*m zakdJ*Ir!cE*H|aiG&XM*ldtGMoG3 z$xs>T9Y<&XhF9_Qd8yM27q?zVso$^PYa0_zAh~_}>8CfbLk6LKrcS=YJXmeJK;9fioKtU0Qmfgrdbp2JxmRr!Z`yT{PoWP2330ai9 znv@m2CpHs0;aU&hVrSR31?(F&yE%~MC1=i`2Em;M$ynCm5`qv{x$nNq@3q^UKYWY=+Mb%$iphi%P4)c(dB6wtM??05QlNj6dME zF$GWUoYTZAf(F4`Rgrj-eM+|EjGJhGi0zGfNbpjbemAT6dXnoA^NO~bx1W$4Tf$pE zmZ8<81yaGU;sGWup*nex_t~kBvzRaQ*$MW*GY{-0(W7~ag?;n>XOb%o^@(h1veS_t zDcjm^rE76_@sq1;1o0-34Xph{U0{id3xi$Ceu0hBWQY{dSj`4yswoG;73xSw81Pu- zMmHlo#&!I@Zij$%+3((_3lw#S4~n|)6}8xy33pwl4nJMu>kDsLCI)= zaQyK377NC8(X>?=W@lmuHG1m7@5TEgY(wVD7-emgPs`~3z z>+TQ53Fh%;dM69?o9zOKw?r%{4g)&P@++2;E?5n|_9K7*d_bE}fU>yT(4>B$F$U#? ztQb9dpbW3TM{O0bm39VF%%dHYBYWmPs(&i{7To}#hkIJ!S}Hnw(AzQU*+q2X{<^?S z2tp1zn)r|g=>PshD6tEIBL%)2ATqB;7y?t+c$ZKw7L&6NGA4>Zc+R@iTnNJa$GAv? z0z&P)g>EvuvK4svdU96*LNR1+e1ys|9QfK2 zVgUg?1qOWl+A=cuSk}diA$a)_EO}r9biXSH+A}qiD-$X|z{#u|pCf6PzYL_DIc!MS zGpb1Nkgh*H^{2P~^wppK`qR-DD+1WZ@!Ntq!@&b3%(3-=XBI&p{h zk8!R>E(n362K3bt+%=VYMfo#~WC$8Q4X^Hb2E!z5T1EkiP}trg>%-T6>5m5pKrCIm8rM1W7(?h z2h2__!SDliZW`IbPzm2$#N=X)ov>3w-Hg8h4-s`LTC@QHp|u=e@h%FnH4`tp^pcrn@YY$aZmaZ2{E1sZB!2^kkWqMGWk<}A7nm_J z^_Qym6Bqk#WYzMwgMY6K0KX0;bRZ7SNgL|N zpLcLsV8lU5U+UE_x~v&+08dKW3OFpXujz9DRl39CoFeH(^!P#U!tq)B09Wbf*b(Ih zFn>L)iQ0yizHQg#`WAOd`{uIPq3II>)Q!jOt><%hkvf4$55%hxOab75FY3SV^Kju+ z0i%Ij-zD1pZGpTMkPUgPn|=dhfts%yobrn%d~;`e5U)m_(pP!lRECBdhzC`S z^8RROMjnU+2rxeaTP7yDSf9ZTni+3QXl@e7E%Yb|1oSE`sDOo_TofQ3D_wH6psoEAJm33NDGt6jt2gwE))~BHFT@nB)ZrBuP9BglETn%dAefxr-1VUWy zu7Sy2Oo3EZj?>rygjuyjR*r+=9muChDkm@ck7i7PSXw5D-qnwtF^dxuPZ2ZM(I(($ z2IbH4ERy5tMTe5}cR|G2l3sQ-`Zjk^qQq#=>JIJzcIz#s6rfZV!` zhj;YZ^8lzTy=2NGv#_$Qda%3S1v(72(hF*WhX*R%%Il&xWa(K;%xWn12C{xU_4k=# z!%S8Nv6F0UdZfdHLXoP*p7&^LoWpOHCH;j$FoZ9ALlAnZepu&?GC>r&=+uFRFYHLm za|4E#!PZh3Ubtf)$h>~$m@JrG39TC-Y`iE9N}+aoBJ83`4!MMEWJqF3@s7DDcHuH5 zg?k8|xnJG-H=0#gPn$*;KhP2QQ;+*T`COQd96A zadxy3JMoG8(jeP>t|P)XRQ}UdH-BR-#KmUE67ti?XxdWmC?^w8=OtWgf5fteYq-44 z`=fGQ#gg`4hfvw1NX>9DR@I}CV9_MW1OH^hED!KH${0A=B*8mfqKd>hr9O4j9x;3+ z6naFRBHS<^Qph}rkfI(wpFlq}AU)C$BHScDR-nB$l*{1rR;5a;bh#)=vf-ixefhCk zvcna>!<7X)3o|z6MyzzTC`qc}q9lF!@!HaVs>RrN4u-5*G?FFH*6B2#*5VdN+{?eW z&bl$nadxw<9&z|6N0Tb;KFm$Pxq8oYfm^=-D{k-#`cy{(qI1A9{5@FVU|-OZdT?}c zJb;vUft~`pcT8GB^mpwk{l!lL$64XJdJ=DlxPg^zFg*g_cg;B=ly6yXB6VRkSjKD? zQ-V5bu?4GWglvIn(j(gCiB5OA^BKDK=6MtBfHk2fGp7ija*~K=}Qw-7qD_>AZ zZ%bFAwnI<(tnC8uNMJO?ua@LlVcm74MS5$4cy>PzG;smPp|AIWL5T8}Z7}R1;%u^Z zNuP*GA(Szmba4FQZqfUdF2rS^HjGw$KEcgG-(kc@$qIQ!T;^!wGvwaf4Z{9^;o3uFLk%9`-Qcmp2F8iC7j z07dK(lS68AgKERdJ6jXL;~NN~s)N%FEBqS?SoxKXH7-ZxVqAEi)Nk)4^ClxNd z)3F>u1kJS;t?=~-jDYcdKJ3L9lzqHjf8P_hJWX``Oh;mgiS3h{%;QYOKEjOq;D0;PW{VdD)YR)XO1iW`1G5kMZnR9wRNK*qaAGrwi0mVhPq+`b zg>8FxU$G`bSv;=e=M4L-ZMNgqV^^=2`|@-E_T2Ycbg)9!gFzo0YG}7NnV0*AL=>Os zBRn!#aod6V^Jk`aS?TOLgsnXv>#!#naXS3Ll46<$BbqkS_tIg`&1Q?EwQYh$))#^3j>jdfP8|fGjSFH=?36i+8M^xOLwj|1vQa8zJ z$}hVwk`=)s@S)t(nBON~1%0oYp4#P)7g}E%Vnv0l!uqC`TH0UHbmQ6blLlGWn|yASsv8BLE;R`p_UStwZk< zk5HO&qel(^GY{nXoMg+IEqWGwmsD6aO;Pi#C445auB6EKc-vYTm7#w1)hXubuBU*CiurqMg zK4rGaE5H`HD5I z02y>CBIN3%utm~EX5GpK!ir=-Mf$XD;(o33T6pM2}KL!R0)q`C}Y10nF?X%wdFSpUQU$8EUjmrl-9QHCHKa( z#g%U?-_>w9(JTw$n{qb_BXv~XyVFY4P4P`xVjI#$)+7n9e^T;a-LeUw(QfvT$Yb_W zirMz;vBIG9XlEnmMR3FE4roEc>7$Qpe26l71v3T>DfbXL!wuD}_gp=qQE$MskPcZX z%5LIT0*GdP?)50NP&QozFM7-OaJ3NiT{Ie4zF)sKc~R+5?>r zW9Yk5KiJJp3Du4yPw>rjtNK@@8UoSxT@p%=uXnJVcIdQL=-zOOE5n$y1tUt*61@kk zFl771Xmm+rsoGmYu=Cu`h&Xu{dcra+D#k~L&VIz~C~;J!fxb5j{aiGP;qdyH~bMES}eZ6+X?`!14@E7anE+ef9^?}O=qwfY0C%34*3qXRoMPyw)q;&0uy!7ID|9w+qv6Y;PDoy`G0CXA zDVq+Q#NIz&)6W2OHf%rc^~;}_>i-?RRq{V}umA7y)PLt%S24FiT>i7 zQ^barMASosx`zZwr?aB_m8|R+5o(EBanRT)Ky#4j%Pl8ol2!osrj-`=u!&>>VTxFi z3t=@MC-LQ2^cnkgav)rMDM9kRmii?+Z-0HIrONk$%rZZUo3d#?opqn--c|4ZE5x;9)A=G-Kh0=5*(<8kL%ba1*nx&B1cC7T^ zqee7}bR2O5Rs2j`r`ptxx$r5IaD;5oRjGfWsVN3OKb3mKE<9DEpg8fhCY94~hDQtM zwFUcC2{{IaR_35EJTG6}TL&WJ8yG{o;6^O;dM`W9wN$!hdI4ic3fcuY5(Zl;S8pjC z2KrZ7UZVasHbiNK)ey}4R;)l9fO8=Rek0Ks+-2nSQZiYnAVqsp-2T2j@;{SpiEDJ) zL~7gf^Gi~(S7}AuRhol60HV;B_CyPyZPrf#Emewi`mB|yuNhM-U#D)NmkTsapI1*G zT~E~FOxL((_{I0?shTaTjoa~6T+x%w^p!YQb??>L;a1*&jQWgb{^BQ4KI?&#@zbTJ+#&a z+zr@a8s(#4#XQ*hx$4uj6J8*_R7T;-Uv!yxHpCHwWz`^qj#ejya8jV@TEk=};WrmZ zNilczb7JvtAam`jEp>m~Vvm^y7xq~v=G0!bXl$WyL`_F9J-${faGy#zvF)m*$8 zDgBZ9+nEkA-^Ut%j)jbmt-F@KvbD_H?@o0+&9@jEF*_HqHMi&2*zf&T9J7oxGEH5Y zIo|YBJ%0E(&^=JJ=`H0oon$cQfn0ujLZ=^>%7WcMb@a?I>f-~sz|+`NhXZQ#(RiZ4 z?a)`*OjZNAglfB^D+8zWR0F@jXhG~Wf820bdBarGR%Gs9_91#R0U){tN#4u-O4E^h zEig5R7dDkKy|7ptg0K=bJKasny!ChUW8sKq7RjHA8#=E}WU9tmk~CIo%eM_{U;H$8 zoLxY9IHm-AI&X!Jl!!DW2*PY1zcygRVX;^1D>#jy9g{M)l()29TSnN%=;jJ37%Gw) zBjP~M^ro1x!(=FJiA9;F<@esVP}7;e*b-}o9qUYlsD#DP|MeYY>#jFvqB?X_ONR04 zC~I8buUfbjJ}6To?18_(eSMNz?8qbPEsXpL%qM=`N`-MNM2>GZfLhuC^2BM%g=W*$ z252rDtaL$ST7Bv3S<}rBbn_e52SSuzLnSz-2lv%pbT}piqmNb;nGXX`6giGJPFe)) zmXB76&~52XEh?ZUjK^%b?UW(7%7Cg^C$Q$m-*cM?;-04c0|5f?Xqv4 zW2H*$Oc`@@e$Z^78u1c0AQB}&pqLLv*ivO;pOCnt@{H1AdZ*{&3!YOL`kVhBVit5P=rFxhbBKy=aA@p-5~B6Vb#1 zyURF~3x)WN66z8H@kvW1S<9yK-jdo-<&>?uwv9QB?K$Z_%AOU>i%D;JeT3rYT+SPU zhi8_EWW_XQY2>4#fL|>)lN{>#y&zw0*O-Xs1%8_v@SMzH5Vw`eC`@@vZZ@V;{O-{b z=yct3{w$DlL!_;REY_Y`{&f)o%n5asL`?y`W9*v9NZ)%RWMcjA-5}x%JUP>hE4OIs8D8qzr z(aW6uHly|l7ZJX+ZT$*x1zlmYiAtmN{`Be-29oYkdqfqug{?;n-+}-kZTgdls^w%D zDBrk76=xV7--1RJcMLv-qVXPDHfau&+&j>Ahrs7;c9QEY%wtQ3pusfAa|oq0YdtgZ zA$Y&j;d#bZk@LMFh+^Yq5{^<7(8MeFI&KNRK#G#Lbuzt>i*jQ@@(C5hFHfbNOD%z+7mRPthC;uP7_X1j;0c^)e{;g9sE=ctH#yK|D!R8 z+Zl=ee})ncE@J*`*1sPAxo&LIwbYAZMHF#Rz5$L~_JWj0T2sLKl=W7ZP6{NWbf^n1 zPB1N@r#asPvv~0J^c(0O|3_=&z%#7C0RV)s|DB=ppTl$gA9(~!jQ_NC{%6g=p^Bx9 z!ZNzol-EW(W%v~WUKJin z7a~(AbLi`g5~d(s>cWQ^i8p)ZPoc~xW9F%ZcLUE|K0~IdvBdWCMmtnExL(7&sV~>F z=QP{(^RQ>KG`02zcn`kENw2?Ff=)Ez3t|WOZZ4ME(_LM3a&V?ivVX3yi)%vir^GEm z*GCE}*iB2=WUC91bQ$Z&3m)<_Lc6zSp5e*wY|g^HVXcj@Y}&{9R`8wT4$l7ZdM(c2 zPMIe8SsfmMmMW;2=H_fQ+mBhafP*P4$K z{4#B**wUHA| zsmW5K3%^9P@cF)5brx-?ppO&Q7wV8I~fqb;o=~^XPL6sXG2}>%|DP{imYwi>OB^MvY7k z+j5bb$=a!@Fp;^FMTFVOg9unp)5L_06xv5>euns8s(V)lRK9zo3&=9=`k^TD*NDI2 zhZ?{rD{`_ID$K8?hvbX4(jv}-g!(Q%jku~(Ykg(06X=uhFRC}msVM)R9!093JhD?9PDA{6B{JSN(I4E zxtS1@(a|^E0y)n)SBa&w0SGG?gRMjm+V3dcdawJLw=b9Hyjp{rQ z?PtL9O+Z*?$3=wJ%V=#Pm0Ht@%4p(a%to&GMC?ftRct5bwL8@Co}bT0uEkl)P-rye zYYuE(NMN)x`D6I5NO5CF5KcYE5MJo58tsa>XR(SR({7!-qD_h3=g-p-|E?J6Vy|hWDk=Y};-#{YB5|N}p1L#lnkhCA#D=}1B01XR}s0{b` z-7BVL0t>(Ckf)wS20khw=6zBfu%1r(=53`tSt^j+#ci0jw#dGmPoZvZR<+5clqWSu zPrr9=iWM&Oc!I`Mg~i-KHJUJ+%QC>acTbEhgL0Q3Ho4fPXr)P^g;7R+n~O2*`GUT6 zlZyrA$yhL7my%4>p>SK5kZjg*+ON)4;c8Z`&~k*Ss%N}E}g#Y_Zz69w)de& zAf>AYIOCedVC_9moT)oI*kT3fR~u|p50imS?uuSb58ajEMd(aJ6D}N$gLhQ)Pk>^N z7w#*>kd2U88J$a*u=c-`1@=3M+d>%g`~}7HGwdzcE^cNP8EWCGuAXu8zy!@Fzsygv zG1LCqxn00%J_?OR3{o)vRxw6f!}X-NZ7SBgEg1kQBT=l66EaV%$aEgD{>&H@#ao_+2gf`3xCr<8Ac#iy?W#qR^PAtoIr6^z`b`r%>UmybAtci6#Ldi#Cb3=w2saC5HW zLoi^$xH&VfV?|&yk$z#hBHRY`!+MMOwHk+XBT|@TLcvvX>-cMJknX3| zo1hx+o*SA2vtr`Di?DI$WbOj)>U9WIq}lgSBxk%bSk#!%))%%-f#4`09f#@n6 zQCGIuG{(LjS6h~vgTkJu#CA7IPJ(Muj)fZI4bjZVc1=nCdBW;fDA=KWu%?^3Ubl@W zY8BS?W1!FDA#q?vd zm;qrK*TS%mF)hrroI_T>hg;Gv=otfzoPu`VNT&q<4u!)ttYqWvW$8tGxF$R55Qi)Y zM3@)qt3R0}_?aY2t4$JF79=H9@t@hNtKITPq3m&=1W}m#O_arvPO44)LK}z5b?6Z- z*4&MTJB)>Q=pdtbcpcJ~@07^TY;ras3Ea_W)Dh$nnW=p((P8ZEv`$8l{?kIJLE$8} z>pSra4=tKVUOwv0wR+8oiC~%!s1Dh~6Y!fzt9IPji*b+)RHeV4pKZrHQ2WXZ& zv1@M?^6Kj%OR(ckcu`vIk`KQ~7eQ z+ZyvnGIckMEGeFv(mE^G*4b9qvEA3xJ1?c}M<>^+Wyek2(FEoC?__U4H?;P1-|M|2 z_i%x?F@$R4rNOfpB3co+eO>Qtw0!GK7G5nv)s)TbNFf#)VtM7B*ON@FXZ}3=s(-Ao zy;dFw9nS{ayeIE(_Ow5~R0Sx^p@5xGN zfN+o?6K0~hfS{!BgG<4{5t>faNKf$JEl!x2tel&`TwQ1>DWZZ3T{ZEirD|+lM$0g9 z>m1*)&t;pBqb3=mIl$@mu3%JPCoXnT)U6qx@7KJ-&4u(%<9z)SviZJn%%lCsFGhv+ z?@UIS|JXP7uS~{&9n!c|G5=w#N8U2N%H)V2{YyMbXoCl$uC5F;@D~9RCIk?;O9mT} z)?Q}E=!h6SBRQUf)ADcllW*m8Q^O*Px?n?C7&r_#zMPLJei z%JD|)v60aoE|RJywMqrU_Nx1K=k(S)$8lD=@pq>&4}gRp99IpR6H*^R%{*u{xg-M% zz`HUy!i8L#l7Gr2wU7Nyve^6^F|}Np6|8;F0GHT2z4!(MUxzT8jj^jxhq3?fYsIuF zzX+FD%g+?Mna7;>6CXn-Wy(5#QeN$#ErL>Kv6ZEHjV5f6|S-PL2Ve;&FP_zrI>5 zpNgD%Hcpg_snU%O@Rd^mku(i6^gOvp-_os2&^$b^z`zQ>KoHfu6g=HHpl%lZ6ra|4 zN5?h;BlhWO?MQ&UXt4iYKGsDfd!q*xp7!A&(3W4C2vK%Yq#%ZB%Bcv~W=KbqWXDXp zK*^Mhkr)X_V?KkHnplQ`koh<1WeD+F!^uZN7k!+F^Q{@e%NfKncDbP&Crzf9Zb(G` zUX?(5EaJeh!K#s1M6>_jPl$)#&Pw=EQe*Y&jl`yn7QLbuiw+wb473NyV5SL%#~O73 zIA9D?4RuNRrTo+C$s($A_|PJX1h2~#c-*leC=*>Upk2iRR# zEnQ|&u3v6w4O7a*aB0KlY<>6d>~!M+`0oPu`J6G{Pl-kYt3#lqO!5Q<@28V*=vGV9 zJCZgiZ=yvon@gv=ACAuO^kzO&PvVd9b}AY8^SosoJD0t)+@UZRY8z8kgO@NDDv~Fc zmxxrfqd<-*CCxsxSr&jD;;1%0@6LKOoTaE$=Yi+$yFpqmb~F*(;RLOk#I(95EYn z`qhogNn%8b`Q9?X+lQ2Krb|7ZAT0}zK>w_1-hk13z-tYGMRP#VUkJ9{HoMa z=?fZPwE@LUs{4V=N~-78=f}k4vjFF(@C}#R!W@FC?laeN`Lm^S?luqQZFJ5)R#eUK zfP!`3w|;|K^mmoxrVe#0@VVoL8}n`vBQ9(nDuk~Y@$F%1!it@G^>DGckIt#X{oN4#{2Hz!yll8ekD|BZ% z2}Q?xwqiGO-$%)(sQ#~l+`=jGfi-+vub+BXMSeEJ^57>c%s(jQ7X%Fm%N#Cu`h1;L z-JWP#JU#6{5fT|C)`A7pesmjH$|G-HO5I_=-{5-_fJn#Uc1Ov_6V)TBG?S?`$ zspf3=O&PAF#@JJ7<1gXHxO=cj8W5m6fVfaYk<}%#hKr@-W#W$4zv#Qbus~pa7F1}Z zsBZi>fWrokylfu-0tQF>1)oD&ZqlkN4>)qGE9;$qXeb+<3$3sxo(rwEL8>c{I_g_) zqFQXGYCIFEJ113^@3on!vurIb+H9^iS>;uh@3*jA6Rn2K5~z^r6gu0-*##IV%jW%H4sL%`1gP>guAAmG0kw6Ef- z_}cG~Leg1~^4p5&5d5SbDWXN^B01C&6VU%=V-q8gV^s?s8Js0ofw3yVjn{=iC;(Wx zQ$#V)t3<4=ni>%6TNVhgg3nbKI6;AL6AXC72NIkn24&f)f7zpj2(c!D3x_at-_6j0 z1vBO(3@fP-)QJgc6d|pL^gB5>;{9#O2<3OeUXL46#qx84`J?firv%TlP6g$Cu+;jk z6co5KC7?oruaOyQld1aas#*Qz62+@MaNBA(Ik8v53z6Fv*kf42YlYt947w+IHUOJ7 z*=NNztZd=oZ@j;>2GbOFim4t;(hwCRC=*kcw<u}z(DbvTWQ$h?!J@Xa9X*b zg_1#V14{W@3ZFrop>3$CYy^t2Q7DFZMW2QlN>PF^#aNh90#5NrMErFZ`Fdw|`@M1N z{c-#K^KljNx+c1Fu~Do1{buQBYx%g7^3LgzA8ftqIXw3ce_H$b|K^v(3QZX^PI6Y zBP?`VaR(9xzRu;Va_}P{oz-Q_rH*0W}>*H<%PaE@{eGCVQMJgZ3}mQ zXDXw>K|I6Q>1&{lnA`$e$0mg7?q?@D{8FQJj}kXLDAT5`v7DkG0L2}ASJQUO=C?MB zo8L|=z1+&byR9Ar`M1v8@qTCIxGn0o=MHvBae>C$bf9>+)S~+*7nyY|N%TTZ;&+Ty z3_^`N-{#ptX(=@AC>{c4Tn1u>LN>>lwM13~O&*xGY|6r_W3g`>s=zsOXa%_c8Q$S8 zg=`Y1Tfw{Z(VQcx5vC66v_rgzN4#mt@B_AE;l#7{^S?84k=ud{&Y;I~dfP=e2G6p; z@J)Utwh~YPffE7SB^Kabp|}i4het+KREuzJF4nJ^u!NXs)jo1L-;bRml!$0ni zhL23r8vtx3DC;4=@aOm)*{fC&l#N?95Jnl8jgJxTSla)#1))_D1;WG6C~=jf#dIIT zqUt)5Udee-se~=HI@W*Md}k9>!I{BP!HJ}Im^;yYC!?g|O8Q>OnLwa~T_r~Wr(B*0 zro7H|>f3{U)Om@s8gD z77JCj$#9cif?Pczzk#@`^<`N%q6zejch{q~9DD;M5IEv{YV;Wc(LeE4JMK=yEz=7| z{_+?auoj+wT8Fiu~8cdZE0ywEPd^Xb^YKBT(Xvj0Y4S*;rz5PJ%K&9m*Mj zkHCP*51bR~ntS?st7My9{x`4aMvHEFD1;DV617IVZDF?nm%X?ep@~R~Xt({*!-Vsc zhw;&QwRAhc8$47Vpe`s^V+hDDueHxknfD#ZhIC~W*@=7(MGJO8B=8t!#o%xL5?l*^ zg?Fc3XfYRpw9-1(#slZ zn~J7cRds1ZVx?2$R$M8@3k`qJGWv$`WjxJ?y1+BZEhW`o5&BJ9j=wiRv&M~K>@|4` zs;R}MIph@j@jG!L^o`i1=uul4!~8&Q0{3kfK^abxa~dbWM@LB>F)8IYm?Vm8O7xu3 z{GgKbiw7+E$yU5hV&9luV$Ds2!u>FzXZ26=NvBNEhC+hUA+2)d`$_XKhG^x&ZD9~o z7H9+EF$QNLCpnJVQtS&3z{=?+upHCAiEV||vYQ2GYcl*O*!U+QOI_z!S)t_E_`{O- zk}~quJM!w*o{T@4N@L`drtO$+av*L97+uDG)lM$(F)Fap!)u?l7> zN%fiL$>U7gMC}L)SMLPZ^p}87rcFu!>`Isb%!PiZNg}OYJaljxWSK zYX(kTf8FY6Gx&0m(@@WtY679~{V@bmkA=JO?A3E-_^95(Jw<cqphF66-@D;!vo<@BV$wlt2l4YywciG&yG zBg~j-7`I24XQ1!G7hC+>CFs~d+i#y~?y59cWb7wK7chQMIrCK~TwEE_76|Lmc4n~) z=_)ow-K_Wg&mzqM(rxPRA9ADRpG=bfl|}MDxlhFZ?B| zP>++Fqlo?bZ{P1Ax2sJDJR+ikBy^p(m`(d@F70mnX*PH3ub1OyMF3&lUo)ZMUKc|S z0LeGGaGM^qh<`Eaxe0+8UqX1O!EWfdcNdC3=!RR5opXS*Z-Xq62ik8Z6vaGu=t_B8k9)Mlm->hVVQJrvNHc*;H4(5 z>jybz;c@eH*A7IKo$#4yD2JPk?%Cbn7x?yaR3tK*2h;}I5P%)0(bv+I$I4qq&g<`+ ziq|eEkg*h{t;Ok?il3PivwGF@bu`%Uk|qBnOxUINGKh^sU&^bAcB+sWDcCEGo-o$C zkByMO84fPIw6KpdzDdR8Xa@5LlKTj>Z+H8S*Pr z_7_w>AHv)x>B(8uu?0=}Ss5Vx@H+8{C<5^ z6JLg*p^>*PK=74ffsT$4?%mszKNn(=r$9hy_k ztTKF>uejvVcV_NxtQN5A4w+k-LmBg0<96CCqt;vr{WG76B zbklUHHzX_t)7te#RQV^58!LqP*;}7jNG@w>NPTI&g)exmpF*Xyz@((7R)g8gyDHFT zNp{MMbh>+f*J3{8tLvrzeMKW{Z}L1^(I8P*2s6~AKt50~nx#*yXq*k*pSrm?ouBSj zbrNM_z2V8eZ9Ic6hzv_rBw_SoU|Y#40IQ-94-3FHAiUsBhEs)LD?xb5TMsS>;Dkg# zK#QvZm<&Egu=<-!8wCL&Xp+%R*!x$tPci`=e;OvUoNI`-i>NYG*8z%eL}l8^mvf&c z=q5-HS$zHwN}xzWzE#qaEvD4OO)BDqd+mminGHSn9!*+ERoNuHh+%oL;zgLO9J8bO z3PSjd${A_lari#h#$V0rXd8-znQUxEtV%%>4V-1QW?i)DiJfkR)gbmK{eeo!L7d_o z>8XFW82wCWw(`I(i~B-|1OT0M`bg{vj6_ND9`a3gxBH5lbNr+XYn`xE;;uRAYrgxXsVbW8ZAF!}Q$ z*!%k{@S(-lCksr3;)Z)Ime5+x1JiEsm*2m$?ma3dbV-jvHU3ayCU10S- zUYr5jz6p>=YF%3hvl!Cm94UoaFx$E??hyHa1&Wv`aBF{9xhj4qhmjv5(^)(Y_NbVO z$g_svd=w+sI>^#mdpesQMKsh3K&*% zvf%@CO8K${CNfK%x;jweVXS!2u;0h9p`8cnr&1N%JyK)OZbRKJeJ&$(*luJ0II0hcWKoNP zNyf!7k6*jYiScxkV|l_Sq*qao(=yaYc(8EWedtBXo)S zS(U%RSEr)?ZnK0srX$)y{rV?equ-rB!1T`^(ue-P?<4<{B=0{*clkf)8vk{OUU^#{ z^9S99dX?}uN^Zl@oSfL~(qCNjT>L}jLJ&eCP%(Tp6N+>j(Ig1WHVYdxoX0`s;a+EL zk6T`ClX8YXS)almGz<3EK}0gRFf-`F45LRI?$goN9LF0Q={#R=mqb44JBuN|Y+&^P z8Fe^)exN9ZVdz2@^Dv%2QYr+oo(IPgaNz0KE{7!m99?i1j6OwPVhwI!Fp6~H7$gGs zTq*KT&E43?8y&nHnXIeK%iA(9XNO?2)G=7yJd@7ZN*R*&%QqUp){fBS;fm=eQS>bt6n8&ORSM@TG9-8rJO z8?ABbpE_+}=-g0;lLal=Wsu&qO)jJLA=l`GUlrH1Hi;8B{dxh5ANAFRwCjX^(d2^j zWLO}Kh$vkL4VMWRU!0>W45m~FTF-}$m3ikA6xA^eni`Wx01aIf&Mm;@i>5VUtfFn= z%|`Qd2&#g#?1YlC=?*#TYZ0H4TgWgCKW9c=tXaBalZ6|q3Ob?)v-Lm}Sv);a=_~q6 za3q(YJ``kyiTM$U5yeFnLrt}@yu8%HG~>0WBsmjBCK)qwXt(ty*K9Ig>pFI0#Aq!| zpD}%KN5;jXe+xsPt&-e=Zk3%vlsJ6Ls#ZfO<}jOUtw^tT!p4h%79<^J>%k6gz40dVV7&adebwZP=emB?FLgH_bbTp$%|IK5`2Ag*hf7Ln+~HYvSDPye zDAc1@?B13?!+tr6qX(bj?bj!@yITV{a^#D`AQt!izCAJ=U9}!yv;yZ4V$jp_(cUmB zIZ7@RDjBkA%y($L84sYHs34pb-3Hg^>!i(b0-3Q2r8g#`=#pJq>MTN&VM?mlweh0E zNhHT|LDLMKWShGz;d@kIhIotR1xHejW{g2honM;{P1Dy^wR}M>2Uit zx7E3MJ(5r;K1wI(0e)E5=q`Z)s{k#>4KJ07q_2+NL|b z>krT|khCJ+1wp?FOBZDaI9f>mEapHYkEF&>=chJQU(B1?HdeK%RTel#9*{T8ZnV2p zga1&u8#Y9ePhSn&bbpD0059)5o@jn1Z z^9^ff#2$nZxWyYH^vyxc6ZtEMwrrXyy5eq5b+z{1aO49MyATBnM%gYx2Qo?p(R9WJ z#8DFI9+cKk<1HZHqAI~c5e^$Zz@m6j-2F}X;BL{zr6=OBfbUhPzA8N;z6M78WO|Y6 z)*d|}2-5h_A^hz_Vv0o~6hB}N*_ko~VsxV8>hr_SYEF2=6=xNDUYeroFcx8fT(1~x zJu8SUUf-xVkyKyQy87l*kZxt#O_9Wmuk$7@wk~sNkl(MI(2)=ak1G?}C~L}n|Eow~r8uZ&s)%e0f@1q60Yifi>Mgv<@B3(HtQ^mG zO?=JJ(HJ~TlFmk<566LWl>{zV{W$iB`zR+M1eXWbY}gGlD;pcHN_y77T3;j>%UdhKkMlt_DXMhE5^N}$G zmG4e`{$?!@;@-N>FI&8Q{r}h2`X6f{8D}deb4Mp*yMGRq5&ydyq=b$6U#2tn_=gbW zq?(o^iVDIX57+onSyBW7XbIw92=uGp(m^9I@~?rz z9@E4mX6GUy!K{2s0;1zBB67E!jXNgFVp}cyUQ7M;q^Hc+&ZjW#wO_p7B z3~{vNG{i>BmHG{G$%aw7-#zSFeeroQfA-ATN{p!*nY0O`NImuPH_{_kCsl8p1dXb+ zT*bV#&{Vx(HgmFk-CW&1h0uUUzE@W+SwwPx%uHSp#raV{mL%j>qtynh$`)Mm2Q_0m zC(fpesz%T$J!2|pqZr#h zp1Z3kl+~mqTz}(A55`lh<9X}$ID|8tW&^>LiW3Gm`9c1;k5OUwU7i@xW(RqkT9QmN zXfX^qi8aye-$Ge{p}}v%=2UuN_VMijB2U=lQ>;XbdBsMOwnqE$O(&+RMGn-~Om$e8 zA)y7o^L|-VC$)~MsswWN12B!F``s@wD-z9(?rXCxf)kqz4N3_zX**?jC$`I;eq$Z& zAi}EDut*QXz``3A1!|sZNAw^q$5TW;k>qRbn5v<~fOXj7E3{QZ)}OD(MfKQqFR)wd>A$)(ANvNDjSU{w&O z#l2N*1ec=N3N}KYe~!o$uF0!-`wnXI`OtK6En7E_FzEz%w-f_?o^X+D8XE555%??8 z;1{*-3+$Wr(JS@2INa7;p41(2wVoJSJBj|1nG4hnY@ub)b2#%Qb z(6VuQYFM=gMEB|uY8e#2xh9YAFQB*KY8tG+>U+0ru5HoY3zuK641LQ!Vsl)alyLL? zk^`f>wysE1+hPzZ)PeMbRq?2;2`=?BPQd8i_<$7b78KVLd>^of# z@;zKXc7}@vW)K~FED4n<(RCEGc_reJvHaC)y~DYfgU8Y6e6j z?*)J%@VWcOVuh+%O(2TYlQFSwMb zSU%Pm-FdRJ;7vdbV;bJBA2(crTdmd@kowbX*O^E{ymAejNYs~6tz=5Y?z}P8jyz>Ibp61BIE`vld%u|LN*y+ zq0sYL-mp)h`!Jt@1BH4lPaY$bJBI_6xeKK`kwGbxP)>D}HH1_}GRo8M$%9kNhbS6A zWkvWg#Ey6gzg)s;*;~!bWC-+fBQ^v~ZTJJ2p~zeQ6YMW!5LB>R==h~~ z{2lH;=DL67{lxw!WFTtp;OO)>VDPsZ?Y}_>jf$I+z+YUuD4WcDU6#R95kZ@y2!s<6 zLO_B|N7~XpXB{6aSG(h15(TfG@(eqQHPR&>VQ03l@RIk!5 z)^cK4&t~>wJ;|t00H{Ydwgm*lf_!CLe>MbM&mU0ODK-wReu`n5hVFf)rfMzl%}%~g z(7!x_k%FRv`=yYT`NhWm6Mbx0+W%EF|N9@?*Ed@SQ#ybhz|hQ?&d}D{`U`;3Sp%HR znCNVcjOpY74ghOoCu4^%h+(AW0I;+B2hu1^04O1gVGMtIO0?MFl!(h)SZbA%K<Pq5Bq-td{}MP zQkoe0V|3xmegWEWO45eYJL(8JBxlS(eNI^18W_%IJDPu}V9=D7$&<8p(I#9IjsCvt z9_Efa;251@Ao0eOVVXGNlP#+ely?L>6V`a$bJj-~Tg!Y8xU>{!(1BrO>g864s(b8mEPuL{Fb}hw`;isH-Mt?C(@lzOmIm$N0IK6`ce=OjAB=d8!`wHCmSz^G*(}`Tt=)iv( zwtuu!J9&xKTnHm5nyy|s%`}B`L9YYo9_{5(8{sWh6ir1zW(Ly+&(PhW0Nq&JF)`Bn z_i02m&UgC=+lQF?+Fx`hOQ&E$@I0L!RFjz?l&*9dvP!lDJh>t=6kP5ERii|Q4@ z>uE2_a}sMbG5U;^Y5`?Z;fJP#OS-LlGu<`#ecn;$XEU^%pTGU@o_oMP#Mzt8q|l#6 zkC9%qwRDR!i&&+igUhW~Fbxa$_&9oA!x1f2qDTxXXo@_ElmR-mmL`WMmVbpUp(6XS z;+Lo$IQV}I+kbsXx&EiHHFo)`sT}G4_KJ%9^?>iP1uDz9vg9VlJ%exvcxT=Y;c~ci`z6ZqPBOsZ|0};?VG2 zj?Pm#wp+7b9`DB0zRjy+1O%>|w8js7tCKK_!4|{|B#_>z3Y3733Zw{f3ire;ZGgb) z8g9g=r%rg!IlBgPwd}M1@Yqz#RXT2C-G4^i4d~dqE-2$HS9D9PLyK(e9tel|Xd~^1 z0ZhAqA<^VIwZPXKd|@$7jGykM1-eFNCZ2-qu^+86K?6uSM&gMDNOb8BG>BH$G|}w+ zB-@8ur0@kVwoJ%FdSLV`mXe|Rqx%5z5T@nuhg9>ho)G{KSLAk^$FB_L81IA=Qi6_C zgn6}Jo^N$oCGk!S%Y!;#MVL@J5(8|kX1LVjWqWOyG43E528V=?Cg$nQE&KLki?2&f zcFw^Q4uhSU@T!-Knn(qrP?&!EOIsBpc&L}lRc>AbHeuo?YD=h@zhi5ZxH^jD#@+lBNtk1!+rL3<2+Q`B;~Xh zrOXI07AQWC4Khz?5F*j(n}w$x{m>R?K{~39|BbrQ^VuD$PQPK zc_R^LU_C~z_dS9sjLE%jj|ebxk4hX{ndlvUFE5dRRz*#47slfZe*YU0l#ei!=%dIQ z6pS-u@~PMT%<4*ZJ(ZIS%k3!^lC=fSa{dRH&0JOv*%R6na$-TdDsiaZUqSJwu~xI< zE05*=w?V=3zYGdx2Y`*EiLHb6KQdXSinZLlJc>`7vn7Sd5&u?fb0{{samO>OFeyxB z6f6xw`Hc{!afDUo*OdI{b@WIQ`+nYTJ>Qs{%{oHJKtSWD_vHo8wBuB3G0(@x@i5&t z`*R71AFBfWj*!1s5a?-skN`l_t=tH93PTtm^DGOX+(--rf1Ow9L5qi{Bp^5}YXLJ7 z77^dK{jT_Fjfe;da`_thvl*vHK$T{^VL4p1&_I>l>B3|oqAj0v{_Jf5EZD8h>KJuD zK9-9yQM*-{QVX@vNI4oU@z$?2g{(-WlANmvpz<{oKH7kc^L%k%HAGNTXoB$yxtiiN zED&-|GT%<&(RQ5+d$<#-P*F>toLB4e{LX1@ejLg8g1*&+QBfrIT<@-^uW51T@sFCMqOU{NWlxl9HKLFyrvCIqXQC z5@(msl?jznr*U*W`C=fFs@Hqka#GfzQqM^FahNLDy87=BWZW6|c4Pez{WA!jKo}sn zE#c%Wofws*kgFt%yKi8hn9tSvu=Yc>MxOabeBqv1AB{n)GpMVtWw-^fAHmLf3ybc3Tq(kPan3F zADU<*%SBD%DQH)P54#D%uuAC%4hVA(#*zIQ+y#0;6Xx02wH36;ssFA4?|LJ%VV2V# z7=zb^X-2rgF9+S}@vK@C+6DHig)!6bFNiDz3lq+VIP>A`WWlK?)?5UBb~1afkNc5E zyTDMvvctv0_eKDPuUtzz<_#fHrk?ccRlHsSYL+Kjh1<~%wmB08WDSbTLq`% z2KydxgVc8GC(E>dLPB(EY7&TAygwVh?& zyakW-*9gYRC*PP5{y7-2Y8r8<3u-JBx_#{tzG!H_4lIKl^-yZ8c802t1irsWpe5w;3L4!r(xTN0t@TF=1@0V0ViAecMLxG&;X7FNT zRppzVv$JdC*;!j#Tf2(ZO~%!hbdVSU{U-1u$1b zEfZPP!%A+NBTR>GXw!-NBHI_~P?JY|~#mVCwd=jUx_y-3P}%jPgagod)Yd?O}YE`nEmf3jD0* z)r_;<-;MeF^o@4V_u2Nfwfxs-3LBzGHyzqL|44b=d+vmf(atc~pLn~iBBwq{7j+`* zQ!mP8-ng0zpLV^W+>Cfx#0fV_W7D-bRaQ$=$R8M770SMIQwXY7lBQsUOEHNn05PP~ z-d-n4Y|I7+F51w7w~G)St73;$@pc$&ovg)xGJ!6u;LH_Nxx@2`nnYsx2>C4W;-HI( zpP7;?0T#R{$JsOrf~7;ndjUUr7zg4ix`^>L-CuvNLyNULs7`HV$=O6T)&pzWV8#QH z`uQ1a&1sMw!_+gkg+=1lDSgOV@Rv@Mq0zNxew_g&|7v%fdNr9%uVhV~H!*%t&q$Ck zHYFP4=@y*FYFi3Y(_bV1+RjAIn|IOjA0Hcgt3N%cdG0!#3{SI&+WDfEJ!Tc@f@(c+ZL^Te5Lba6a{}pPhN?g74e}HDcY@ zV`-~2ePPG`oFt>8@^D~fdiXPwYAG|Hw84xNz(qCwE9{r;BIdix*$MKzrFvmhyh9JV z=75HLZ+9aqnP8>o^MLlwdqlahD?vAE6SZCeRj(prc(_CVG@WO-8 zX+fe?`?SG|kOmorz!^Ha$us3V1*dR}RnZ;?0aQ&K%a`UQoiTNGvtv~}dzopKH(h%* zwIx%;y;dquK%uEy_V2r~+*LSBGx5$E8)HV;0P(8^%y^eDOqO5?^FF4K2VIAssC?yW1}RYY#uWp!T*dlD-dLqATZi>;a()mVq?t#@v={YtkE$%0iM8M~ zaP&a@kP0-*WIdw+I2tsjb96luyMkQLS1y9{C=IC{UP8PqKvtSlNW0RKasJwY5b4FK z7qG>2#$Ll2`?bc?GoW1^SC!Yh$_OtgMb#SCJKgO3q(8?hDNK^^yI2U?*0t5&bJcC7 zkrD>BaW*|zlkpVUdv4_8YB4iOWhH*9Poz$=Qfm#V&~m^AxB~7f9OSWMZ#nC{6vGem zL_QlDQxK)W+vZ-R`?hvQ>Q!YWwc6&fnxq>H{X@BfWV9o*Q(JJbVc(lWv-i$FB#HU7X?G2YN>8}B5O`g|WA_}u%1dG8Kg zzP1GEX1LK>_0k!^e$MnWByCoZh!0_o_bR|vHi*lHiI*&$DEO9`ZnOu4%tM`J!ho+5 z;$tgMlH6l{G~m#bPzGUbEASIr*?P{ZjG;8?Oge3U>L?8bG{3*Bbh~B{ucq#$f=UIY zg3T;T;&`SNY?AGin{zt{TDlFP`-f9U;Sc?}^%KH)tP_KHwCny^K>`9CdUHf}`y|;b z)+zv!T5Q4KX-%tbapp+o6k_q!Wy@9c(oY52hcQwr<#jaA&Mb92-CY)rcr>ov6MdKaLYAVllih|R0Z zvBdSF`0s&D(O{(4u_`uM?oVfrww2!Rp1h_^g2$`bo*SE$tmR|)$novGf1&_haDxkt zR7Kki4)Mdk+UGf_Fb&}g>dsor652BaY@9Y|19TjUnjR0jL_Ed~&^-w%gHfXBvZ9zT z*E5xurVdCS4U-lei57k@(%8!_3p*a&+JVv>mlu^kydyVe#hjJuA%(Sf=EQH(-{=&r zoq3Tekym^4xx}4WX=9!0__iR8c7@3DylTde-rF=O{F3SP(zkrSjoe&z86;tr%^yr9 zt|gLMkPFz%E%lnr%ySGKoZ9ml4X%^9z$UdaPi;j*#+SXY38$IeJH+AgyqHkx3>Jtc zNxV7s?z?n2@O(&3wRlNlKCP{PbW>;zE4(XvqOq^bR4s}u|0b*ZbW z;KHSp$t@WTZkFtt1TMui4_t-{(PQ~Ivb)`uzpuKS)PgwFT5n(DcyH5c=lBC$7W_zG zu=YW*)WyUw7mW5Zk4O(J0KZ3FN4 z4YAI!!%)3D?~tm;t;T9@#(%Lj#@$Q->A0cvJ@Dhq`fv}|4l2y-yU4wmoczJ15@p?8 z!o(ls)Tit?cXYmvhF@do5IYgY18mM9PoV;(+ncJNGr~3mV!`b*RKm9{MjdQpZLs)Cz#hCsMeNxGV z*(CX;%j%iP1o1w564nGuv03uVf{ikyLq1<$$pZ5e1$BEJJNCxA8}N9#f7P}A=EiH? ztA5SY{3(QLL|#?Rsl`D0EEcbxH)t}>fOl`2zP|n*1zyjEz=PK86rS2+MNZ3RHik$~ zCaf@sK|j0dD*{U*)1-l^AO%U9v<)6NtIO>XP{KteJ8RgIU5#iNXmYURhrEE0y^wQ_ ziD3Q*{B7)>fA5&t4|QA?F$G?RO)Y_Z+YU`_53gWOcD1xDrPDU~cGP6T0v*zPv_)!` zNAu_PC1 za9ffAZ{oxG%3=9Ndm?2$S|W%h|y@`S1vZqb6S%%n)@$Q>BwO>aO*DH6v(WB zmk6zkWv*2=h_pvm$%p!&u()ATwQ7DK64mrBT^P@l<)SUUM!TzurL(*94fr0mB*dm%f{qQ?eJFmPEvC05A_+bqJq_77NzSK)k-h(*5 zc0<--s$ahp!DWw*{)lHyf?g4MzN~9aak-mXx;bQbSNzOW>c6IgEZ@(BZt-WMJhlq; zscxt$>xr;Le`&h=@EX9|+AV*(r#s4(O;mLIjaau_RAFD#L4!s$vQIDk1adIOBm8Xj zCD7v$5$AfKtFK7>8*DJTWI9nyot=cj;a<6c!(w0FeXH=4>iFvF99%1R9g?vP?+HmS zyJ~Vx%$h=mr^6^`shVa_6zB#2*C=nHj=HqJx-5k-MdZ`WgSY~i`xu2K?GBk~Bs2tX zg#WpdV*MLN@Au}bVUVoA$*g@)5li^|Lx5a3G9}-p`ax;guVTCbF&>WSn(P53o+>qq z=%+FNU(c7Yw!SGBckeBt!}b?>o;%26joezEb&O>Tv%FC&TJ+I2Vj!En>h5H!b2{oW zPbeHY#XCQ;9t<>QV628#OS1+*Y*sZgA0(BLFtb+l`XSVsKrl~{ z+9d27^eOxUk!be%yxn)$?XsblkegmM-tn^Y*lSzkaxS~O`{NsZZ~_b+8VGUL*w=ak z5*Tqu4B~(k!5$Kl&;9r{Tc)mr`YjQ$kolCJlzLK4-#0K4>$D9`rUuQ(WsITQ^wWoj zg`-DNR;3Nuq9s-(s#Yf#Z!Q&a<2#O^Rp~{_^0i#mwPTA?%~IvbG|kzwH)spz__U7EA1NR=cqHU4pT*NPvQ$l{Ku;B$t?UgE# zoH3-f(&c0fK{n!;C=>{t?d8&2ep$M7%}xMfJQp=gE@SmEO{ew|+O|wONw_78;OY@g zP!<-OTPQbkeUn-v<%You^mbVRt2B43b31E;A;#90a%8`Y?Bt+GY88CF-~>ZW1I7f? z1edA7HJPMn`Et4SXyJq?$?li_N{HN)3btzKd>Ol@ZzMx+r9N;x)Mc0ySB^faB@Bb9 z07?X*`Q1#UlV0#2)?4=<@P*YTeG+OvT8QCy%vN9P^iX}PqWbAcoLGc?X}Hle&l_u{*m5csDr_n` z^#fP0&v*{_vcH%W3Q~#Cm%HYphzE~b7~==707~8pK0}cZ?d|e|h})Y6sC+snvwM zB312rd}p&`8mL704RdHJN%fSGyLFx&>e#E4JM48*F}Lqx`xHRHPERyiGpDABCsVIv z9zAF-DPC!d6q^N6{_X(=W|QXtMnAw)S;!+Uk|ibh_&OBT>P8k9dJsCwnD3Yc$+o&* zFn!p%Kzlr_dh%Xbo7$iyw+=IYiB3;=V`AFe-!o)%KqbV~74>iI14j-E%J0dnd3T8bLXq5c3{IV6{J`c(zyuy;hv@U5fT_aB(l#WdEfOZ zWUOAY5Z+nNgo>{t8u=%=M)g3icTsS2**&yERDB2eiD=``sqf!7Hw`7Z$l5Q?jqktZ z+*tqraBkuN8zZZKZ;Qy+%J$PEc&iD5MUjZ+*Eex{I2ERFheE7{->M>ut2F& zXu~$u8up+0>>usdOeGyNoWF!*{}{2Z%dCNE`6~Kah_y?sN&B4X zAxlXjU-XzDvca-wu8*EiUM{Sr9$pexLWl?;fZ~G^R4x%h2o~zYtb`?&?fBmdc-;!T z9{4{mfZx=HY-d{St5UY$vTtX2UcOv%e4VVX{`0Vi`mKK@Sp<%Y6R;OcjW;+YE2t}! z9pnQGg5`p_k|{z42CEJh1j;$o*%STdvXo~^2fAq zL{}ACO0-8APvSn6A_X?FHH(0k;hiCijFn->Ih+71J>qcrD~3C@IC#Uz9NeK>I9YQw zYW*oe_V-ZdFVozI5^76CbTAd>RTn?)L58yxDU~@#=7EJS9_93Fc*1&m*I@x~{`tdA zn@(ciAJYnvbq`dFGutGZT8CKEt(Z*GjnXZx?vh%iI?SNet*3z2@yqIlC5MS7k>lpy z;O|g*)Yz4gPB@ht!XG0#yY;7KWX@#T$zw>*bdXHQf@=Ke^n4{G(c4~bSrxGbD4UF4 z!J9&*5VDoz^pR`*@p|B_NRJG7{PC=I`2s6j+DEqsySJo>>E6RrZ2_c9sZTpwEJZCt zDrrsFT8gH27O0_q;o@*USjW#$2zPV#U^_;@(~6P_`7f7;j`XUrnxn4SyycDeW0agN znt%AKBNF|bc~E~B^DTH3iO4B+M@*s961+`T=I%BRuu|+N_$OeF)uz`n{jQDty7c9! zwcmIYYctD4Q@d>G0>>3f$8d%Svx~8P%#B|d4k<3(X9&g{264lU!lW^PBfDqZAv&$3 z-h<5^#ddmw=DIzEw6%NL?uL7{3!GFN#?%t>bi*>Wr{xuJb;D4#hx{IL_Z*7Hx6kx0 zSZ(dt%&a5NYbM{@@Y4-$;p1zV~%fC+gI%r(OQy8+T*8*@3?n!_-qVh`14qUzRPl zEvoj$&$hk#cD6E25LyY-#8g6GK*w_^q6U*_@hLFz{V6c*R=|jx#rn~LC`egLj##Mn zio%@@dT0)2aD}XBV>#+ttk2D*`-f8O??4!R^819iqKk0)gaPK)HR)D2lqjm!e1HD( z7;r)d?2Px;3@Ow=FS7ust47EI4l8EN+gW%9f;)@iC4jyXl%^vH4^vdf&G}%V-kj1K z5@l;Sj$ZJ6oEB!Qhax{zJIq5NG+;-{f^o(0D>|0fAVJpHuwJM~>1J)AyYj~jT?aAp&bOW{&)lJ}N z;6fguq*K;_XolX9iIus`EsF781#l&`OV={pUk+?&j!M-2dX%gF(@fjHcA5TPaL~UE z#$+n=%KpuPeNYe~VR+mYeHI2HNOTxNz-ci#=nzkJ%IbePu+J7#juh|x8{gP-+bV`( zhyGs<%yj=!Z2ilDn(X9+;hVsZP-gT8)n13g%P^5g*9sM&@BwLe3RYe$S1=opLRH14 zak-rLi5+@DO6EfbSO`k^7IL7-0IznrQSFXvA~5;{a7l@IXkioygEb-RBW-R-TY}c& ze);l{U_#vnju*$)ILfH!6$n%wGh|7}g){nuJzE3OqsgvyQ+>xT)kLCB=B$nf>%BGj z(^PNBM6dh~ezE&FE=;=niU^!XOifGlzMka;dYC_F$9x_;vTesBGs&y5xg!AowsbNl zftA~-(NhA?@17DiC}vahusaxVlZT*OE5t^NS|tUq;|pv`?tcoMkd28(lO+F;sZsQ#tTdx-ey z>v`2KBTnC&rBbfS(E1G=N)VWkpjDihI0dv!J$7<4j#~S2??UIBb-76RV$(A@s(`SC zmVs7T2v}&-(rcO7g;M3(T3KVI_sU-Wl4{`8`PKzVGC~~m;gjK|=L8$mw(n7T>ZB4l zz8gdjv%e4a`!l*iG&OmCxNa4bZ0X-8zZh1T96c}!{A^J9 zOYYD*~6%c1CX>Oz|U}Zn#sAC-N%_k z+*Z*@C`y{iV30fNsEOLB@B%aOu4ItiAH8ViiJ_}0(fV^$>Bu}Tlgn$UX1QLbreCeX z$PdSGgoBabYH4s3W(uyApJuz0!WUbIZ0wU$vDL|imJ+i8#iB_H3_>PuhZhMqjxW4e zw2NXIY$0wGQ)TKXNKzklYQ|Y413cBZ%ZT?)5ZV`Lb;2Fm>>bRA#j`6O43XG9r8&v1 z&k|Uvg3%2!tjl0Ado^&w7s?=^U}Wov_5Y~DjIi6;bb%Rxx(QkKTcEd#xbBMh&7{;! zgSAyCk{3RIM;KqxkwhKM3K@>qu3u|0K}5vz1YprIgxV<(1&71Eb}Q~=Aad^#=vwJe zCQ*g$>YjHOQvU=-U+w&$x~uG=m_eU9yCZo&C-_ z28}>^tH}0shAhd-aUoUIM&&LHYiv=-MuRU?+KL7{CK0isH{$0-d$ZhSlA};-xSc#u z9onn1Ih`p<3RcXhvfbC;rD7VA8nU>G8!b|PWoltdj~}yED7Gc)E9dIlT4)spwVJqT z?Uf3vSI)P9laDeuLgB~QvmTA9hi#9P40&O84~_#L5~8B4~%K*%iT9=5l=To5uYhupNTg>Te(@3 z@N!w4k-0B1&b|X@BR~Ba;S_!$2#VL$D43(TXs`z;q0#QTKt@w{xM`sA5{&2lw4s1X zjp&c8BNwdiNp(*Vz=vs_DlBkP7qBP-``(JV`}ngw4oiVZ)fp*;<=1}XjT6&QHsxx5 zf)_dRY69z-vQ$YpCgC+O(Iw9(5P{2WBFe&10-b8z4O_ z)g7;}=7-XRCgWI3J*S3%o(I(@U8r}+QQYLAv0wgLX*!L)Gj^tUtlzF(SX2d*TKZxM zz}#hVGc}B~v5Fj)ED1KMi~z)X4=^c1(r8vAJ6ozDs|asMSANL4A-a9JA+?;wL?U?D zna~szH<{_e+Or_eSrFtn_QPx#$s13mdi)*eXSb7uVyG}HNy~$>R@~2gWqtT^%>-K& zy=i=)sgR}08!=PL?pv0l>A<ze)=7r>h=jm*Ds zvze%PK$t8QV;X`6tB~5LfK5@_Hi^KV>kfB##CANAG4C2Y)wB2w^RWP@=_U1J-i?A+ zWFPvQJ++nHtgO_IkGNl$ZV0~yofS}bC%lVa@a{<NS_=E?kJNTZ$XVqwX_s zlkNyNjlSZDNf8xT@GZs)}Alp`iH50g>m18`GO4<_&Ix91_C;`SnOd|8sg#FK;s1BKsem zu82umj7NpW3kU&^%%4bmY`bj%E^7P?y@Wh{J1(G?{wvlx)8^DZOY};tm~$q&-1>ou zX$I?NG!YOAN)<+-jhmT7k7tOXsPd58y{ep!mG5)p6;{QKa1MzW#7m7-V&^hM4GyU8 z8z!JzIGV=MHkBv+Zhj(u5}x)j!DxnDrSK$3>_eCS&G3c5f$7Z#n3EgcDL?e7Q|k>Q z{fgo7yV~H%R@~~x0OHlx$m^j<)FdAb8&Jue;4WbndaOQV ziVMKavqGz~v0hxVJ#fl9v~71bPJ4J2!<{RFabN9Gr)p!AMTIa4?2DwiPfa4EX3g66 zL<3$~vzBX>uvaO_Gij%^cY<)=*1_zWXXib+xw1@EMRPUhc{kXlw3RiY04oBTD+q*^ zYy_iK31;?Gd6O7yvh<&s2H#YTr+J;>QYP9$hiTS#YAzVnrL{SP_usBZBj4=KG~l{B z7wl#5WtnE3c|$_c!6+|>PgQ7D6%I}G%ekBCI|{cHhjHV=ea~ZY?PM-{?I-qJlRPe{ zUgd|j$k||TQ+aQVy_HGk3M^UHoNL1p&{`1);UqWY-E*!0)??2m-FT`@;e-n36z->vbG zPf-`(?weS?(WhQsF z2yq+Ty)*K()`2SmGWF)|1k^e8-D>1e&rvT@ZraQsZ0yDiQ$sG*qhR3!eay}@v5}ka5rHcw&9WL2HU^4`CgRq74 zcGGmw)2@iQ6<@RiV$R8%KzS3(j2&E%f}p4G?F|WC>)7W^IwHKa!`! zWuT3AhW<`CUHnARu}rl78BG*Mt0;9=P_Z&aB;zzvNJ%7Z#u6iS0hT$Xd`73+`ls+3 zuR;ZU=0?7u4l^vL)b}EB-jyoBam0!BpVVP!?%}cH&>r-o(!5ISq2Nrt!qa|?4-0tg zQg))GTE_{r_6FTpOqTMIsVpTvf9B&fz1Kr6HXX_nFq&onyDNfXodvaB2V4tFdKln=T(x2SuR|z(usX? zE~9Kt(k5df{HTQ?Hjh!Aqm|x{4$s~?%K6u4gR@kN%zgQOa5-$F1v7oV3*yKnRk2&t za_*<-Z?t}5EzJou3zX+4Rf{|UbaWKSq3+MWQ4F1>OAbLW-@b_u{U1|@|Hd$6#_8B1 z37`aR`vrdAfLbb3@3v@bl25d*^vE3wXkcE2Xn>r-z@`f_4zNzbWo*}fXVCSmBpt$- z{~C{F%vxn7*wTp4eBzltm>6E===S+!2dW9I1g^@>5CdAiL!q(k0PGb7X=&P6w&oiT z4(NP|4l=dhZAEt~gv(i#2C-(_*%DjHMGZ4XoHIm=tvBI7XiW%Xh`FfU(0h!?tb?<8K%RWOFSd+uN8WM87#sNdvw}BFB^XYnxtke9QGHg@|rY_4~)v7lskXH z3NvCj^i2s_W5~8oGY`=HLBxmCB+MNLg8U?1p`k7|_$%-`w2GB_OEfslxJM}RwcSaB zvFTalqZc9!mZXI7Zm#T?lv;z8fj=Og(nXfaWs1@zE)2JORd005iadD^^3NLqPL>j z@tOyG&lE-2_ZaZeekC#t@JZcZf_aDawfO_h-_=r73-RbBVj86t_%dQ6yM$o}Bze)| zN}%^${+aL8ULt4Vf9AIJG2XKEJ0$6)Qd09JQZfyrW-<)3=#zI$jbet8oV~$}D-0sN zaHFpS-YL#jNNjh$;ohRq&a%{v8gCiIGK&yJj!QHIP#u6(#Z}Fb%j*g#Q9ObFMTQ_8 z8*PAp)zpFicl7^%S`zA1+5B1(Lin`SV)x8I3&+2~&K1`pUj`ENvOccfdyN`8gk)nTMV@C#%(pxC2>i2FQqHjG} zVwKT7RMkjH(kgA4W1`xii%zwXNWrUC#?`V(qv|T5eYbZ=%bllN*CiZ}v5q9b5`4|l zP&ODm?vgh(wK9LJhoOtVz~iOaUBD6|mh;3g2ya3ee;5lYsl0^^roItb-kZXzUbWa_ z7G3y`*`rS_PGR95?3wjr+$=oB8!2TuxOK;KUH|c*Ln**4P^KE7kFZ# z52XOvWVhYHF#y|ZsRpd|z~Et|3<`ln(--g7`f-nJPIS+hs9P}o>^(O3bFF^>bIv3r zv1reZloS=2aAG%Jn2)3ZC^QU5i|od6RdcU1WlOZ@I*g*gK~el80yL0=Ro#M7yqkUn%60eHwiTG5>36z@w}?iHWdN*FRlO4_whsrlo| zlK&tOc$}7=DBQ_ z=|YjRe8L}KMEU`j+v_dd_apKm*HB)2b_-_BBr^s11zIKJ1}TpqqvUUIpcfy`Tq}?ke<~oCkUWQL z;ZaVg5A?r6hQ`EfVEQX$nE%t>!oS`x`QPpl{cTG9@7|;c|F$CH3sp-XJ zlO6PhJFuJYBmj-~1pIVo=j3K&cX~gtbE;6|7ye$>UZ0v_X}qC8mDt?rgp7X8wUpYg zN}BcmvG$J9o$txJXm^s1ZQHidv2Av2+v(W0ZQHhO+qQ4^o|!vm_BsEVId|Q)erx4b z-h2z6r>dTMss_uu;iD`zNQFVkd?cc;=9m#iU?zd1o*^cD74Eez-Nr6jiw$Yg9{ebF zIF3TPvFzv$uij1Hao|98)}c(olKwQ$f<*Xpmx7+I#yyBR>`h|L)&l!6?C~lV!iX|3 zJDBc!rpJQASsho8H1&yFY;s=fuP*3v?z#DZMNaZ82Rlh^3om*-n7vs9jT&OPxw!`; zJtfmQ+nAfyqPewV!d+ucwgw*#L*7_#x)+&AXX(hhGaGf*FtAT21 zlGMIo z)e1oPNtN3Yi0XXpNRhW;iLvT(4f@z9i3Ym{jxddL{$5RXU6G z1_^V)wZ7gZ^Bp)wFaf1xXoN`J(BQ$VreNkXMmT{X0fru8b9>Yz#^|m%%ot+FT~WYU zVlBRrpDO~ust63u%YMFT!M;ayHlQ990u1hLZsa!SN-XlY3edX!?Lrnlr(uU-j! zT^KRL72Nc&SV0j2tuHReca+&9t-}g=qc&x#$eOzr(eR-D1Fx6zZ;((c8;uW`#eu{r(JM4d0sVD z40J#S!>8DwhY!PORzVlGK$*4UNF(s^sgTaH{iTWH2(Q72ME$Tw%qwy}CyganP9Z+O zNn5++Hhkk3Zjy!YbcPFH1{vpo`IS`K5hXwbpX5|H}hQC;ho~9 zlkt;DicS%^TOtdAt|6~nI{@w5dV==DHrR<@j3b?m7Eyhv2OqQB_o_q6b0q-XmT%7A zPZ`gq!JjI`BpU0STYV7PtikAtO{P}aA;C9(PZv3A30nlxY(bzZSBd*1imk6^ZT?JO zqv4?t%XIavVOFR@yn+h!4ddQ2o2$tENCj?RH>Tz0ja@OR1E$ds3STj;Lvl=GK|VzO zlpzjH$*L2!p8a7E_{BjST?+dRH&v;f>7xiR)D`lrohXhdeMR}(Fl{JmxDSt&8y>L9 zwmjnx2;TaHs1tD!2fD_mR0Sj!l>7XY4pD&bvt=ge_iffJc%x$bD$`QSV!=+MU+->~_tE0e7K^OE7vNOlK zc`Jppv%go2g3ir*+D+p%)O7Lk9{?c8&Xp<4kV&kwhWI+j`Ww)UFqEw;D5_+Tuh`L% zt2zKS6K3)$*f*(j-86$Q9K<6?&uM1bq1)TY@(4QA1%(0M5=h30TCAq3*7Q9mx@aW& z(`z6*eS1&r5!X-Jexj(~7yEj9{Rz;CkCaxjz9g)Sz9gal=h;5(e>sid z)%!!R>hHrp`9HQuQMsH>7c40t8@~Glg^;c~7Y~J|!1eersMgT(kH+-F6wI-UwJexp zWxmPM!_%QdWxmS}9BwcHT~=;xdIG5Qjsg)P#;Wwxgpr|9h=%FJ z`xa<(icS=A>Pqq^tQvvau2oPZZ8`D}5c}p~+_ONAGIh?*j71hWn42YRTE1#2o27PN zw;XgfGQG|{_*5u001Q5gK^FUlXwhvP3oRGXhQTbAj_}sYGM9vhOk|zSKZc)t;5G02 z3pG0qu_$jqFA{s2ws5tMX6-}p7l^sljYd_lWwdXa;VfhIa@v{*BQu@ipgP{xBizo- zY0R3LxK7!$DHYRdBub1oN;K*?Vrp@o;kp>E9&~t>%nGbV90GAb#MgL^AH(_){>OYG;ba&v| z1|J#eLOOx%_OJ+E*EXRHSmEP4%Bza>R|aYF?SMs_f!X<;;6grL|9m>m0yXNhid#+>=$rhArQU^GjQ9a}iwd3r3mxa4Bl<+&!Eb7~cl0C9ju1#x%qI^>R?jC4lpY<0 zkm?f``FwWWOw1$i⁡Jt{v@?pghwz{hiBKv=8)<)<^K91kO^&mr;mMGIR(+{pnA6 z%%F%aLE|qVQwH?!yqN31^x{8(%-^X$g#W8c=PUeeF`D`hm!{b@U=?uZU;jx4il7r) zr5zp`i>8)9=}DVECp%MLaQd_t8512eZTxihRcWqL84Bp)+Yh_ktl3R?WVqR0dVajT z0CvG=^y6*m07O>d;uGl7dBag&U#aks^9~zmRpaaU=xOn#>>_~0Vk!%A8o)BPzXaeZ z(F3m9q3zY2s(mEr)u}0k>Xh$1L-jvtCxImBx{endHpCUcVNz0TbmXfDCt%be#`lW% zt~*hBHMGim<2C1+mV8LfinokJozxtjNHr_Xj4~fcsF|%lm9aPjrRtXY8_9Cs;H>{3xjV^|B1uFH)WW8i;J2coDW1@xVH9-kNxUX6u z+A2q3mOB@0&p~b;h;gxXGo>I;z7q)=QLR*9nSV|1t>q@>i#S-TOptBHEt`a<9!v^F z5=ioLj_*=_-QSm3wyL(>!7&fX^WCm=n6y_lKP!0610+VjkAm9LCgMn^#;e&A0Q9LJp1Xe5U9OJx+4FGy8{D z^t%xFj}y86Cb$d9O+~xF#7#TWX$g$Q6fSrgDw6w&Dc=MgV4~{;`kZ+5+hd>$4L>u8 zZY>KH!p@~6vwK|20~>JL)E2U54MkuQ_bR~K4yuuKWc>?cgJl#h%cVhoTI1gV_BB5r z%lAcmPE+q-KSsRjj01`c$(^x3i;!$*en9bgD1@c)vGZ~gg5ePkM-5F!K?dlPBFE@l zb5x52TH0$K;TF&5VnLeTtAO;bfGu5TqUFKmtMuV2q^QNunW^AKMrRaa9`L0NqGsYd zfXUFdBtJv_0plBMoycRqykF}pkN?j(T>k&Y`~Oz?N?7UXm`mz7^IJJs+6y}C85rmr z=>PH8`k!gOJa+OA?To?BO7mhW2tmZYkl(?9atOqJxqd%QMQH^Qx;FyP#aj)X8kW=X zyYH596>Z%3joEu5%iiOWesFFw; zXN7W@+h&A7xb^%*^43BqNDUq?V{XXJ#Y5R=G_GC3kK-|X-&`L$_HUTss)c> zO+X-DXy`0{V%+jZ%3z-=9M?BC7w25tw>(weBhs;@V9Z`8K3lj9P&r)J`1P1b{ zh@O35S|pO1;Yxz0Gp5%a-12I4`l$q8O5c!H)e*wT9a`;EV6%9_kzQb{)VV606P@X*ng}r#mWIW+)0?;gA7hKy-u)>DgU~F!qgi zPZ!4hiyj4~WBnq3F1(JS&&A~yR|qcP>-Vpo#;Uuv3>L*Nh*sL6tj20HH+mZmYAO?v z0|w`fw%-TnNVH94Np`VHzz!0mYa%25bVqbamKh(rIM0Q~2Z*;7b>uVpSjd#xnw=@# zs20fOGMVpsul|IqF4InGfRkXrjpw4J^{y=YDn_gb!CT%_+&En0G6kAS7{U+)Hdz2I zb+wpcm-kY}G(YX4@gXaeU4n3EeFvNd={@jCdD$@oyOCM*8b#x?Bw7GC#5IXDeb@6h z2s8uV^SQHygE{`&NACXv4U_&K<@%%*f->yKfT|JJE+H(O zF<5@SIR=Thx#v_}Up5d?w(5K}`57)c;Yf{VHH+q@niWgHgUo$rmLi1L&wjk|?|D8e z*seP=_cPeAB+x})KVb!jjTNW@(|mMs1}npj*N0RVhSrY9L#Iu^q&|0aG|XdfZNJ zI{z$6(07+b6#wxR13d8ugGd6v=dS8@y9WFCO>k4$c_=VkeacM~+wR(48EbuVoS_ht zMT6e=jQ@rP#*Ach6)tAZW0F_iG9}MkRY*{as@v`gHflvDt@W3 zsdy|^f-^9G5=?HL*KJo^Gd}o*+RxA;s91FkjAK-Ok@Rt z4V1NmEMh3WlE?Mq>F|Cf1hPN!*V!Od0 z4QNXhq>9<{rF4U=-*|2jm9bO5~A zRLw3Yj};G}Gwz!7l*zX32uV5gS73xOrx@q@GwarM8|MZyXJEAV{Rq`|WCiE^?oHXM zapqj|47T#M^oP$uq2xW)s#XQAG|ZmfxR8LXcz5T*7xTEou#D1txc3I+c>T!t-lF0< zJ$Pxxqb@(SBVuZQhPw{zG3p4=s_JwLwxxWglOBAI2uwRv8sM?C*@LsMcurK8`uTIi zil5jqie`JCI0m~aac^ms_gvh)A-r#i%0Ao+;qZwLc6aUrE&+4YjZ!cnvc_Z4^5?OoRWZuM zkAnrLCV8rh1H0Adm0OYeWi^aPsc}o~B$L;uJkJji80~-u-2`Ad>DOuzew6}#(kY!Z zB0wVa0rc=4e5_uglrDBjJzvAEX)uu#eqX6=a;hymcHdNeoz#s%s*zo4q$`5-e(Aap zH+yWJ*&lCwDAyRvP0|LOS>V_+z}T`-o$^?bWPJ#xTQDz-7yG16VXyNi`8Ckmq!sh> zn0*xP2nJX^rPmVe$eZW1T9L06hE_DA-#3=?yKc!o5X>q9R@T#BApQvMv&45dm#<8` z`u{r@^Y76e|5q+1X^M)s0L(wBd~*ilmS!ywUjO7`E{4+$KuBtB+OH&cJb1Wwv;!Jz zcm8Hz>b>ykO4Ad*}}(IE{sfvU4Ff3U^KJ2Ikd%7 zM7)WHBX^%7jykAXHY63|>5ChSbi2m}v?C)$32?Qq^{P}J8 z`1=>7FIaldcwz=D%b#;RAN8DY1mXDjvkC6!72D>;{c;jn*Vu;stV3kv@y3?`7wU`HrvV)rFJ_@zat{}(yvd^t_CFWkk|DB422zCv^AR3Fc+&<*{yv?u_U3ROT{ zJjICU4jMZiC9#}t;bbKEru>2r`U3cd_d?UxTH1jaiu~(htl8~?t#|o#|8;Qk8}_yq zlCsTs_dPm!)Am+^@2X$F0+Ct(V0<1sbKp6#_XFsymbn~7IMxuYJQDJ^a|JcOWs()+ z*EpG#79QNVcIPrs2rLT)nouF~<5Ah6^nEGJsxp0>fzA{Ij(IYj{L)#G744FN4-;Z4 z47)`Oj9hq{IFk}o*L2ooP#64UVjtF!BtmD?7J?Vp1~>lC zBZJ&UefOG5sJLhv(rseH?JJkyX~+_H zf)8)%MVE`SoIaK=k1K427r$f}(sqiZ#O8%3Adh}bk6ylsm*IYVCGd&(oC@9MtsC;% zRrnH~Klz}ypRC0FU!J4&FF5S4p2PZ|JV(&k`fFK5N7vloPwZ~!U@k2n__v3>U0Ks! zK^f^|LV|u)!V;Iz8xd4S3^Z1v$8S>%>^q?hJ|M5}9Ado&G0Qd|eeA^AlpnI1S$Tq* zMZHp~VBJSvy|D>|H)2XogX#S+$l^`CS+j;Xjt2LG=-WfHlVyOYSdf8e(yi0vGSBA6 z1NY;{HIG#|po;$^fpMPm5EN})jS;{Nh%{u6Kq**HVZzN$$F(RicyHD(7v zYG&fGlfms{k29VRhYh~Z#qAD^@p}i6@~XBoFj%KCNet%(My7Y_TN+ zLmSmPPn47@nQ*tUbbi@b12;ozeGT}wci8$Q7I=BEeF2LlbkcCI66Y67L%Oi$+H;nz zjX2|?VTa>PV&QnmUOkz)wQz7mCduN#!b^L~-uz;%Nai4T#R3{q1r!2k4egwyb?5-H8Ru%(x zU$l@Ta_2Sra0h-s;%tsNBNGQMUk@ycRWlO6mg;y{J}So%M>V7dAs+0Y``6$e=8L>W zFb;!rv@;%kgNI-=NF)4o#xH<{rhf1>Cbe5CxHbC(u`+HFyIz#Sb)zz}iU3v5xyMNa zw@L7|aJAl?VkW8&a}yey?!p`crU)Q*-#8f9v@SVfeq!`Ug`vLa*wC#jgwpmyl) zkg(6lojZ*v-d>Y5#8l4D%??68F3!K~vPzjMB$wL5@DZ7tEC-NNPWI~OpsN(~q=A(e z>B>b2dBZyH_z3b@(4DB9<+%QsPU3?JviGd<=~A}98qPaxBx_h z0Q;hGYse1uEMI(E*A|@ zy}2$ySr;%p;Ef&wK;^3jZyOEhU99D=|Et^=f$-GZYIIiCnH65q->>1mSgc%kOqh%b zeD{GJa0B)X+zk8?#iJe8{<_)4wNzZ?dVtL^hd#^AFpqJ`YTqXogG(efc=V7jt={th@%rR0V)OJ#V@ zCax4pbd8olLbvYZuOUHxrm!%A=x4q@c4;_%fqUtybH29(T7OGlZ^wG7^4``gN#;9z z_w9L;w!iv;ETOJoM;`~SPp+etZXw@E5A2sfhHJYGicS0pc;sz`<8_EWD6`FkKgHUq$a{-6sByBI&kns{g!GSfeDT>k6Py26&xDlOCi!H zkp)WU(L2pdO99Mcd+EQiGV*O6LOg7GU4SN^!TDWnI+2Z=FgU%%Ov{{{lS%;2Sgx+h z=*Eq}%Bp^g5{icei_aQbYqY1f~wEEQsc<$Fr zqFEr;ulpIS;}m!hXsi)i2SN7p1^t(gR=nXfDso_Uw)ksVs4uffem;j zF@mq_9a=<4(=Py&E^f~fa`%L7yWTsL5m@`k1Ah}8>`5T<#9V?P4}qlz#%Y~^@$(TF z%NVXi*<~bx$0yI#IC}+L5~R2TU$5I7-Kn57#FQ`Q z@67Sqd4xgx>T^4Gg{S>rk7NME+dRNQuAa$^G0F3;lgUipez;F_xW^m?)fjGiH_FC= zT9yQdclxEMgi|i=T{qrd|3+_qXk7BkaA6lCAnhGZ3RQ+R=!CC)d1g%&+N=yOK%VrW zrzF^vw0OcJ^ze1vxVze2O)Sw}AUV#7rVZAD{C1);VYO0Tk(QTY2tWUznPk-V! zbu$ZVqF3iK0UofNJ5oV?0M2?)lk}ZuRH&`*le}bJJ|+&?4!J>6+h>6;IzKJh6+)(eMoY_51(mqejL)7HRtoMJZkuwpj@#3zmFit&~+kVQg1Z}ek5@wA_ShG$8ATCJy-@EED6y|HxooDe*B=VeWrK=y+; zy{!SmwA)uh&={>JEWDnb%qR!TeV(vI^D9A`K%5X%doHMX+iH+#(x|={)Gb+j7T4>r zQ^uG@_jyn(ku)(MP~#rypKb>rXAszM{UNH%~93ULjT zfHgsNIq`fmK{24)?~bms(8>A9&E?m_IC(V0KBKOAKvL(>2;1at=+Fnw&Mkx#z(15fSCbOTRAxG=iJ1Xi*vqM zcd9oYa1||_AwVVxy8g7x;w~B%B(CZ_grR|K<+M=rmA6qp+w4LJQhE}j^LZEI+K8GF zn^mOHPRs&>ii#ns-|8PJnHVFSJl!}N`Cz$B2b#=__BQ*(KE9E46q5HkyXqyfH1FGX znpz|{`BT}EFpbpMrs(jqSJaoh7QLiI;zW^)+fo?&HK;hv>4&E=bA%*8_oi62@(LW@ z=SS6N>25^_6LB)zz`YYo+$D?XEDJ!p07^@gZ54YP5eLX>CxyZl+G1sE!d}8o$FOPf z2XuQOMeA@w|A>!VZ77nj%9*(ONUIKMQg$kKJ+~fF<_);-ntwgCk6QF;1wpd)7iJnU zm>`~ONbP6R9QFA{HdA9^d(3#BELO^8q~t$$zv0N4^1JvBEsEp_jsDX@Vl=QQPDvhR zHANm0-L>8!KeS&0EcdQbWQP7+5I)kG$1G1w>hF#AhLQnMJ`Q-v&*OhD`56 z#GmgCNIbie^2~5hA_A|SDm+MR&&^~V8$buFfAQdGYnaUrZJ~>nym7HJzWsR^LfbaP z{qUUWVtG@=+f1I~})pq|3qrbOr<%gvR=wPY%anGWvAV<42dNHeD;rYOK_Pn)eC_M?@yGXXj@!ye%%xTRSt+1i z0ma%?b4wRmdJ!7gQqFtjbE2``m=CVeDDON)Zel9Hui+KdV1wKP%07d{lHrb=f?oB5 zlG4_JCclP%Ua!orb?DPd=Zet{YTp~^ALQ>03X#FNnJ|W@hw0}`8zsc0d&)bq`b81! zRP>8wdC(Zt!4b~XoNE|=ww!l+H6RJr@9q~Emd=w6y;+xUvSbT6oaXIL6s0NLLQvV& z!M6wT5iYg;WKLu=X}+)q_9Uvhs>FVKrPYfbz&2WttFmUkG4`mc7ktzhnXV7H%1Ud? zZ7pZpmcA}X&mF0n5>SX2x~fcYmxB8hxS_97jhGQ4VW?+=k0iS=seT^ufM0zSzD|a0 zboH8<+Hr~tvH9V9+qt+m&k6`kAmd((B=;TZTMr#7jEX2x!9k-A_0?@>SvZ=CPSI#gS(-gC`x>|We|4y+3sXt9gGa_YdpE&BQXQ(pb& zeUN{18YKK5x)ow_V%{NE+Qul9ec%Wt`Ou0Wgvi9Z8VJgwn3#npjdWMv-4S^`ze> z&(t%sQMgni3dOVUHIC$$eO%#6aG)q2k;|thVx?ZC5`4a?l;3Z6*DD^;TaTDz`dfd( zxOA4)Tlg`!R7QgOeQ)`Cyy8&-W+LIhup!XFIC_F5b}yi%{-#?21c5$w|MdwY|K;)e zYiH#@K3-5&BW$%SqS9?l6JLS z^_3w=?WyD0Dr(o2J?P4eDX++bhq5(`L=}&4E_Qxg_wq~ zf%;2Ha*s}xB^>cNIV@A%7WBQ;ej!8E^*v+?!xBF3et(u5*@K@0}!^*4RZeO8sQmy`LDL^XwjdS!Pfa zmbE_g2Z-ae9G$z_k=wfm>!)9wKeKd)O?CJjZVN|C42yuL#X7$}ELX$Rv`X}(qQ&*}t;4rc_pCxB z3=9lY!kj(*c+8#QT;kw-cOR(>Edojb5|bVgOU~jr8fUo6XlQN>BcSXqU)Qi)2AY=t`Bw5B*2(I_l>*4)&G)^{%XSi z7%O%<7S`q_mPUWOv?2d>rSD(I!7`&?v4YrMT(5Up3jX1135nly6vtOx4j%6#uhG;x zp;17VtS>S2_g@Nxy z^1#p6V0||-HCK0SmcZ7xi7*fpg7b#tCbC|`4wY|{f zE&cU?t^2gEXvXQy@Z4vy8`XGd%Jdxr;k08G^Jwhyw@P%A0bH;^Th z>?XCX??>k-n0*hFg@Mn*)$UZ0I|ujcGbm0^bNyl*!kK^}$+wjAN3ts^VIPJSZsXuhuRUQjTr<+>5(uD{ZYY>$Zj_8bE=%xIrAfqcjq)$M+S#UK{Uoemd zv`rV!)8+P<>y7ElNny)-r7tG)FJy~K=2Ud}2(2)D`4iPvSCr)s5G*qMgHg|#)|CK65V<~m!31Y^iV z_pIRVoS4lP(P)dhZP}oo0Rr!+i_zyqS(xvz8F?H+@3=7)4i)!cBTCxe|IB{`j3yk^ zU&g8bx5oMTUmNF-xcNG1Y4Nv1mV96A8~wi@0nJwwm;XA=@nIRu{I$iOy^n`Ws;ll7 z5(J|*GD=T7`#o@O;WZznmyv;SFY*aYqCgCiN> zV1Oo_IHcY55>@dY(T%S0s9Hp`64^zP*2Gfvu>c&~!Xv7daBbi~b#xUJ?=GA=y<=-x zc9}ZuS=+WMrz%zM8LD9H>c_AURw3mec_ErBI$~{0J<_PW`*T-LGUM?=hh7{7w#{>H zVgYh>xMHEUvg5cWFd2GoyRkcs7tFjucZC5ShhX`9{s?RQPC2z$N(<{7H6z%*LA;?vx%|FV>+*RYn zXNLku+-07)BI9YQEfUpBL1zfF2ZM}YpeMMaZGBZx(kbjpQ3-F#6RRYFpjF3;0`@GA z&u;AIAGvQv?N|BrS7_1y+u8Vk|2F**UjKXAOOFx%5-WloEWAG zXlM=bo`@^K5pL34%j8M)tflib@fUV*pl-j{lrn_RZKRXB!IYtIWSqSz-nlQ)Av++* zJfuKQN}?O8sWeTCFi|j}`c-II-!r*$vkry_N# zr~&a@ru_;QV&W# z3cvYBOdwyFIdv2jsgNfT>F3x~(Uj|thRr`SCYNxwq{&yt?EaUG`Pa=O!T&mAeq~F2 zI}-yvv;VVg^Oel3H4M-^JI*rJ&xVKdO&SQ>ZKq?*jTht4MZ9%~8=_(wQsREnkQcTV zj+-#MCDaYMFCt1d>A;mx*0P&^S=<+wy{&=j(;#PBdG-R1BvtKGnILe#ZA-$R7| zF*zBpLBdfm#c}k!I^#G!5y5_3#=2nl0_fj$9jdhf&6#PV&%Rj?7rbd}CiT>kws?u;L_v9a<{J7S z4WGKt0RYc%sx_)?#KB^~{NZIrQAu_hmawqYpR@a`>i9f(R2(rk!s`AlyggP9{%*|GUt=CfKG8EZnoMIZdDwiUjiJRP;73aTJ<$$l*|j+sSh~*n zSynApPbYc3a9Y`f{+d%ADwMq;BR91d;G2a}3IrNQRWqG?a6&CNZZV4}FPflL;WuWh zR0N5_g<&WhWsm6zYB(09&Ih7$0&Tt;?A;;}8jzCyS# zc6iZPW$T3|e_NCGv-~=z>Y}GHoAHvh5UTt#b#mDno5D-ri4jeErK($StaRVib1cV| z`I9M#I-kp5`{mI-MsC7g#?ot+x$mvWI z11R1HcUsiKZPxhr0@`ab9h9153ZDzh=K6IvdtRpqdJ`%0rYyEG(U7x4%h!6e&T6Yr zP5kpO{Y;QA`aN{tJR#Co@_PC&YdV9PZz(l?Lr`)42BG5gn@8>lyGMS=<%p6NacI zh)k)9@Z`wM%B|!NA#Ku?tn1_&-d?&%fda7I8f#~(xIr>>qHi*qT9Fs>n*{+bTFhrK# zUbPOxVCEYpNI5P#)=YFw>}B9C=k$_+SaK6$k8-!nkJpyzzEK|C@RTc^N zD=+8&e#0^-J5y=NgcKQ5YB;-v`6&}@8sMgz$6!C()JHwf7|{^x@WUUND&>0Q1;Nrk zBqPzud>w$vCtIRuFks3>7ha%5@MR>`Bcr5I-;`9*u3I4_yjUB(uDe(zsVW@FTjqz+ zRpesw8wYByd7A&@&+YcLc^$kQxdYd6t(-$U^4pvdwp1{qSoSjx%tUJ^YNP&T5v%}L ziO}>?{}Wc|sUuU${Sk2gE6+PyWWYm3NX`lQ==G!%?ywexM}#0uK7oTHJOMVeN!wRRA8;B?Tv$PV~e zKj>uTjxRH=uVfQuYV%7_gsT#&Dv_yb`XrKk7&m1p0PM7tIH!LB6j1i_bV+Mc$I!yJ zs3L$aY!$jFBUa$U1%<~oK`eI>@sii$%XYRaV)pN1b1<}k1{O9ZMT$@rNGNpDVwDNI zx>&9h+`p038j%vSGQC3&CHikA+k)-1qS#Yq3R{34p?$vIF`-C{NflLBZYR(n?*~?fB2W7{e3@v`~C0>bo8l7q(k_9 zKYN(|dyGM_NM$l32Rvuyaj`kQ#3@=PH84Uj5?fIL%%bP72bZRmwg56L)Z-+hXxk~SJ-UMdZ z{wYG-$$aDe%>ucWU^x6Mtw!0bGgUz)%npCuOm7_YwZs*A!6AEk&n?Bi5xp`)B_Z|# z<9iP}r^Gq|6CxwUM#Yx&5pB=4*bPtLr&Cx_Jjg>dT2*ek`=oT;h}20 zYHucP+jQENJB?6GfsKQe@6UGq$V!G;G1{b0A@fL5Gk@*>`jC6%*c61l{_%d^-xvm;p9K+=5P z86lz!m}dQ}P&9;H1hc9*IyB!pq%XL7%RYZ=ZU>r2Ojh5&2i1S*>3(wB-69z77oGvo z(C+f+HE8ugt!+vquU=DpY`-vJcUu)btG`9RCSJLPzXG{QMj*4$x>1d7%Z&#ZuC&E9 z03X{SjVd_nOnNJ+a5xh$>PKllVdV=I^BW*r~6tGm8+Cpo`V~6FHBbnJ-E1*iTW(AfyED^ zWhm|GpY{o{I$v7my{N+BMPT%6xAfDS>WO6apmPcKGyL@WSGa8m&BzvGc-&nwmtx*S zS3y8dpDXh&?@QW_X9N$3I={l4P=+W6Cuz|bj)((JKfsT7x{|V-!QL5+{rO|?nf!+v zli?ypOM)2;@qw7>_ctN1bKUHZDS@!AHvAT`4&7{GqDS3=CRYAvcQEFS5P|k3bC^p0 zUZs-Q_a2Ns)ZI-sAWy&iGwgE*60_&wSxXzqqbkk%pCKJ1~>4UbY^H?Xmi#FB`H5M*IHZOm|bjk62;ffygcW~cNP#6 zH|XqSF5S|)J2AoT=*>-fS+_5#n|MRs$2k%i&=kR2@&bbA?JU-X1A7Mo3I;~#nFS!X z&EYh7I-VPUDpoa<;daUPm~or#hHd9{H}jYQSOp^8f91G_)yrW`8F6aE8L{3(65+I? zNk_d&wa3LriKjOW^2_gKn4E-=rVp8(T3?rdc-y=WY>grhHxE@9tRjM1RifVpMQRFIsvjb z-I=Rk>DHQ+n^Vzj9|E;)V!-M`zCjTENzjFzSVU*03VibYhQtkN^&J`IxUbYOb_L>~ zxz!vxMO3ZJ)VQjDZo=UZyLQ04XyAuaB?OzSbS2K&3yt_%+A|IYv@TV_WT8~k zLrA9tRcSAovZ5vFG6Qe(pg{_iBHiGtk?lj=rA&SVOwjR-b-MGpphNOCAx3{en|kZK zyP_Uzc3OCR^C8n_YKVw?U%4}zTUT_Cc{6K_CP|rz_#go=caXZh`%qV)O|7@(8ucCl zJGbeU-cyq|G$ACR4*F84I%FHKW4@nLZj_Wgng~QQn45hX{gq*x;9xE=cJJ;Nn@k%0 z36Z;eG-7hA7ML4_lAC5{R(C6GDU*RVk^~a7M+eZV7Y>jBmFemSr^!|*-^(=-)-UEO zBzMK$jr%=n8cp}FE2SaO;ptU&VILXwX6#ir>C2BbMrZMHqA;oq9%V?sVumJGpVjE; zOcvE^#=_66H={qYKelB(F&2JxqT>TD6A&oCi-}~cUDcG3cgTytR7nLi?Kzs2Q3j`o z-l#9NcO=vw_$D4O^6(-wcrDcyVl~QDC{bP`h>9;iC_Ak@mq=*OG*cm{OTu{v0{uK*3TD3y;&Jbu=NLL5MdKH%ylg(v(=mV9ciR+StNcHy8Oxx>!g?daRwov7u@_`TzqSsZ6;2^Z>TI14br>TmSf z?jgghhg$Wb=yLvcG&J`$v6bF=JOQ|aC1XeX3|~iRC~;7(+=$L-#tAs*Z@}0+7HQ`K zBFwocuXBKPvfeXu659T8H!MF!E(>lzg?&d>dzBYFz%j0iW-Q2Yg(MqgXDxtQ42Y%t z;^W_ytN2h>dX=keQ&0%PCeV3(# z#@2kE@S}^er{|ET3Go5b#BW$UT}lrFdv5Ul)B?kpbDXcURlYUKA5V%l>UAhGk6`?~cz zeux3SY^X-vJv#eX?UNj24lwc7tR$R_C2#LegSq6MBHN`;;)&h1PZu#_GwfDAo>kQihM%WfyCn$QGh-Um^hxc0nZb(Y}WC z^?qh81m)3eXN>&fOF9KH;!O|m*F9cZTiKrUdXu_`m}-LZNJq!b-}Ig4%)=)@AjnO_ zC$jq`6rE)AhsQRm(W7nZVn6&?9_5LrCabV`jB1~LAZ#VJt^V4^enV$_1OD-rfb+7+ z5U-_u_A#XL4mPe(To?^qcysf1-l^BZ1g5 zbz3|Y5qY#)Fr5)dR6MGkW7G_=i^7)F0IPsFH1Ke!c91&JL2ulx0~}!&ODs}=2gq#dus@T``J)`qS-(Uyc3y^97rF*N z2pb3}FLzPo^B=E%c~}%-Z1FyRmwk1^|AhEZWPad z{h9tGNBtjxi?W%Fh7p=4x8pL@sHh2TUjC8@4cKUpW4(z9I8bVpcs4-r&)l8+D!1RU zXZ{!dQ*Pzc8*{E^az*nED^sTGg~@q9qDo3EaSg`dw4kKfuLD(ANdo{XWmfoB5^C7!IIa=81n=dbMK z0?5z`45|!R@q1;_cIriNRYMUC^_xZm8R_ebgcm~7+KkL>AnoW|)de;PS}yLlxz}h~ zu%otlm!G2|UwEi%0}UR)qTSX)rCqPdXs~5vX5D+hH%u7NLe)+DJ$#Gr6o%61a%YuD zQ^W}6h9yXK3=1Fqcskp~vkm7m#8Q?uR^(V^ zg3B(dt1Ga<%QEU_lgoO_F(78?p#unVRT<3Ar3ZSHRx+4sAIb#Lxb`ooe5?m0ySLIM z@*|UvQPY_#wvt8mW2(dW9tBs(7N81ez!)qy_3~kk*6}%csr@Hv@*r)(={eUOXC@v< z&mIFQLbOkH08ZwAp8%idF{O!1s2tPT;Y*3VYm=J}z@(a}cR&a@Ij$5Sv@qv7)ecVH8imYQQT#HebM}b;e>i)`=t{S3Yq%=5Q?YH^wr$&XDz&t*y0wte^9lb3UW@F?#Q(OI`sus<7COvZlw3U2rom3M z*J+)<@qA+FC(@0!#{J!qqO#wrtWEv$4kX`-hktsjI>shb+d*aB-E{5xTlENJDXLNV zK-xA5o;@_^?vTVel@p$o`~c!9=3J+dfm;+u!tlmkuy`Pnaf)_S&pt zt_S=4i}=*`TxJ&i9S6ZN%5j(F($~zTUk9afg50g#_sep+R$n zAnEurax$C1Q0-xWs6@Gd1JoI+*Y+IjQMt+RJ-YGptp<;(hMYiw&gjeY?RU-gh1Ff} zk#Jq~prWtBwl zc`~AS;GIdp1ttm_6Fnk=yumVqGeUlT>UiL{s>{IyE8@r=Y%u7+@EX}qqMA57_JsI! zGyFusjToLqUqi;MJ@|ue%$@tgS+g)I+?BG=auwFc#GjS=G`&owhyB;R;pC5yB zURV9SUKQ%80%)*?*46pW zoAj;hnHel+rnBo~Saw{S=mikHV&|9z^Ie#)dtyM=1stKDPrrhHHb1t*1B=j6DF5qM z27WYD3KxD!2P$rjG436ha0_pv--WgY$R+0hvuwH#5iBc^<<~KHIF+w3f;qq`r6>J7 zh$y3S&ZRK)@KMQ=TbbMUwPoRIU6f9A8v1-`xdVKM10t&-snz`)1L0qE1ji}xl&p%z z`m#=;e0;+>+vNT*vLH4f!2Vf;T7*oMy_l?kHX5(=O>H#*KZAqr$%mJYA8c}AitUi6 z683fC0h__$Gw&!`*X3xs9OU!=;$mUp~ zC6j^a%6s~yCa~v%*&6uLba4$6vYONcvN=FRekr6isUgRg5Bq-0b%#s=IHB1ns17+3 z83r%r;GUN{EX$!JuFULC?R2bDNaMj#-m-bDAK4yoHUUd0L4*2PNtmA7va}q{VB1pd zl<{ITGb_P6UA$C;f4(oQ9nlRnrm^&_RLK)HJeddXE{(dmZiL&mvzGxvFF*#ulAD!e z74x|nV`Xub_7TD?c#@i;mi7iu z@=Sp49c%IR-|xE}t~3gOPr1J2yY*NZ|4c~Jqym~z84@CC>Yn$u3{5;{sy(d2;AZX9 zfU-erqZ}cvpme3op{(j3STK(;STKd~80cCe-|gVHKyUEgKdwLj6#aFl@8nK@l~};2 z|Fd@ZJKyo2w>1A=V*PU@RPj%DRIYl;3Tu_#u!nMUCB>XE{xrr$#Yi$HBD^%!et}m; zO2lPjo{`JhkZ$p8M(!uTH@P8>{?)ieP<}9vtBLimut1aFQ&&7ZKfjyi=<$mT3Mz9; zDneIaxLR)q`l17(Ryf0jm@e(vQR)LS`>*Wi5WnUwp}-4R4@0l-GYJ%Fp3on+>*>($ zb6DeUM!#o;aNlH!aExdE+R;uHsnRS?cc*tW2&$Aug|_70oswOaK7Q4MTjQ1q!eFjl zq5Cb8g#mTGxcr+0G!*sXF6Sz=WVD76PK+Z25u0_OS*watx^P?=HNyU^WFfB8R4miC zaU?Y+A1ij4v20;YgCSe~k}6Pwx1JFd{9OKJZ}5a*}2MnBE=MdVPm3aTrD{ zQS|yl1U`5Zyi}f0De4)#nM-;Zw$osTFu;|`=H#f6oGDE_Yr0_UaTl{-pN};P^JXe> zt1t2nk4dc_7*d6DUe0h?lM-2A$MZK-WCO-vB8 zM1N{N+7w?r{>&+PCG*JaI=;p`%moG;`t3dAD1ee*Wj=2f6LcRFWqfDE8EFwv`6GygVn z<}XCuUq-|tWhVa^r~Hs#57hoYur!*t?Vut1RfhCd- zb4SEP4SG(wGU4Xl+WanQTV_{aS0UTFUFV0r6yC=DQyH}p34OYLqO;HO4Q_5$R;J0w zz+h>xh8gSNadseRGOca1y@v7NjoVP#>psDtE$ynox+&@PJfOf1|CQ1@?m**6ZKuNa z(%JY#U#Pl(_PKk7Ma~dn!4=`{#Ar}CEA@k{pT}*2z^ZzWct0)%!`eF@1{n#2l&J*i zQT99iZ#pDRNcB<97;Z`w)PKxM-gt&fuYX|zh5r*Zi2cW?;V;sP|GoQtp}L`fp@j6g zVHnT5%%A(cK+(zq@;R^8uL(Fph+EtYtU+-8g^y(vxGCOn&sgA$HHyaTBpiq41DX36 zYJ1y%FMkhbH~y#pUTgd4BBhx)zpx2=rrs2n$79CUd#1xQHuc-hZ<=m^mWT!%u9lTh zYf5lCiI4!eael%;)th+Lhdt&?$6QDY?t+1rEZXYV>n>QFr)#|a(#nh^W&3jWExAT} zvq@Q~DO;-C6Aik;62m4p%KU>n^<1QJilIkW$?@A|zcGiE#8$UCkD{2&y|%V|)Ki#j z{bNmqW{5DkMR1Z$@+n7hCS;Nt?(j`ZwI#RSlA1Frv-BYU8!^3dr#mb27eJwD`kHpA z%?^1=`%Jwzu#7_<3Pfo4T1yc4*z!pcC5LP2a^Qs!24>8THG8e>YF-mBfitLC%1+~B zu@c}c%A+|=8L|^hwHE|+;n7NpHu5YA;n8Jf38=eB77DUweQ7GoLE~8>0Tue7*4MP& za280ArEqm=I!3#WOmnl`RVuEIB&>d3D*x$lr5_R(%U!c1mU$14HMm)4$89*t#~5ly zikeIYA#L=SK%cKsu#KgVGDsG|X&I$xrrpgM>Ks!gRAQ?Pbomakh-6`y=2?&7jI~&iSO)1BWB3Bi%G=}SxtiiiP}q0S{^{oZ zv={{k%MVVV0**JBxxe&Rwu8fz5Eb;#@8yQt9mE-9KRz$rGxi>*c_yy&Qd?ma7euI# z#@SI29;a)gpKct@?Qf5XYWj9VU&o>l#>p7@m1lpu70Dr6fJpcA?di;oxd+jd>>9gw z?O3)Ef{nPM;f%V13(&jIkmT!xe8&R`WR28AONP7KF+j`SRzSmO8HQuGZ=y$9kEio@ zISDuK7c3mzr^J++F;I-sdnujiShcA&I@qaDrbf*JbW1Y1kY?<*ZS&POs|`JtQAE!p zbBKy$LO*gMRud`BV5SfPBzA4d<`0%)e6Kr=N;{ZkbIb=-lyaRRiORZH_@)UKvw7u; zZOaMEo>lr&GIMpXDcctZp>c_#pj$kt+w@_E9pM9wlCuL;g|!XT#nlp4-c@wfpM-ON z#h-<9f5ZQZGD8kb-uGg$#T^17zDZoK$Z~fo_ZRtlA{<85VjlgHXBEi$#Y`a~YM!}5lMTY=9l}=C zJ{LqG8UaIuVxCivc%9O#Mjdi^tO7FlLj)~sC!Dk=BS`{*Q=*YVmR7w{@m6`%75f42 zWn#-LXMOG&HPLASUggvkOW?09V#^dQ>b~#saDx7X1bHp5$DBS}fm^>CDa-h$W6SW+ zDpfx&T)(Y&vXO-z-UtO194~WAbMBZh-7U=*ZNY`x*kNs@YLZlFU3`e`q7#Rz(QFPO znNhnV4l!j1teJw~h(lIa|0{xj-7|Mh$ z^@rgl10-DxGk3zueg>BV^_I)j#M{T+JBkm2IGyNn)E+$cxN71JAq+4Z-mM(v@TeLb zJcnFCfH(Obnm|RB%GMG(Q|I8d_}yF8*z5XnYS|83)DetgFsuiS;#GbrOv_v|RdYFW zu(8f>&)~I1lR2B1YRN$KVD<73>2fBt{fkG83)#0s9!hzKlYlh>hn{QpWSx>2MWV@= zS<0n(5$WN3jShpkC`?>TPyJsGt8_d&Wt0B++zaGKD7}&vS-ls`zp1`64aRF;ru4ah zhqqO#Rxzy`jA-%|X4xn_)|kvN>PwZM-R_JOi|=IE3Q`1dNi7=NTU?HmYIX;6;Un9) z6Kv6Lsr!93&~x&56>9LQ*US9y6@!wOgcM_X9e|r-GQ*4rkqcrBMWlJ{V104y>JZDRi{`|7DY}$_E;G57Aw2R&k2$jwZQF{A+LP`}p4bLS&NxLhr zONh@i3K4zMg(YS{m}a6|{MjY}La3M~A4v*fkC^bvh?tA>@h6426)?3z{Z&n+{GXOy zeE)GV@F#^RZ02fY_&?~@e_(;a7^y#|x&w!a7#rTI*uGnS&2+aZ0u=fR6^aw;_gaUD zgi;KL%CqcRYT15+39L~F1qKKRBl39rah2|N_t@nP>?6SnvqKv|0OCtOMn5ubtQ7B1 zK}Qi{qNJv5JSx#Jh+Iv0qZ*rZXPTzk;Amhd7->FJmNYOu1j@gGR-7hIubja{k4i|+ zVyXg77t(aeF0DWZe|a;a=PPV3PPqV8)hu(nuh;yUQR=@QIX82B6~4ksQV-lT!jzUV zosE*9wo^y6P&P`cyn1ogz%Y0kSODv>HE2!U5$XHnbWW7is2uf1<<~p9wCM!`<-RRL zqgw;$JJ+tww{-&d$oF=+$#s`aG}`GdP<%D#(*_^QCn{?GZte{0wCuQK-U_=`|d z&)rSb#`0e(p+fmlaX>yeuSBaMyLr^#(8%^7*clUtg5%lPrW}~-2iLC2DuIC^l*d4pcO!7Qx<9S^^$UMmQIg6 z8ppot<)a6vB$-0C6H#&epR`&`&P+iN-Cl&m93@??O|cAwc-zJt&~?K>gS&H_$5Gw>e5 zJ8ls@M=sF4NGTYqH%_P&(43&9lKkq&86b0rc0!IIm^SgPq}&U7N@5F~KKs*AZ(|PF zE%s{{xco)*^8X)&|L-SHE2<scA->GQj#kL#`#Oe96&|rGUh> z`k?5YXJrXGARs?bl4+8!8N~c)_y|MJbJia`f1HbArk#(Huj^*!>-+!R(-8cRFQorM zC;vMzsZ;@XRa`*+*czuC-6z81mE`{+$J<8;7aA7k!wY~)$OoM7C!rH3LhnqEXhKX$ zy`bK(SgA}w-B_s+z6dP~vg_BPh*aLV*tx50wP3EYwkq|S{kqvPAqkSW`rO5KwC-@l zb(D3G<*+p+bGZScOU@0WOKg3g`A#=q{f)sk-X|USO|&N(xB|sC+(!fWO|Zubz#7Fi z*oOlU$OX9OJI4Dlm~Q-bE4_oux8J(?vgv@LtMf_UnpWp^zx`gF_X4p zDkN<2ZLXHfCpdrs5Ejx^uqPkDn|zy2txlk181e?l8NyY*XBvo;Xxog(`*N7!`|4Zx zx3udDADth&Y@9UPz~5;gTt}mmfxCBytKVD~qP5T)v_CW$QMCYTQ;@|d#Ztf}{JSzb z;B!U$!X8BW4V`G9A7XXVrtBA!itp4bR80$0!73Ye(aC2`qQU}SCYI4n6s)33BRUP} z8P&9AM1TLf>^QLRs%1+y6h&J>jB-xf$=6>TlXb+sMAc(Rw+gq~3~_Z7!go*$t)c&c zTmdFDVSDUYo-VCX)Z2}Zu3$_G0C+I`QF6QKUDPXIfD_bI#K4UO7}{ zs-we*U~|rZ*a^xg++I24Rt$aJvcGZ$8{c0LQLDySVE3E_aWe@f#2>2WsJu}C1D$0| zoi7*84`1$;Q#}_(#l+FSAEAkKLEn#MOi5@Ed?I!qRO0k#LJ^tn^}ZupP;4h{!U@mN zp2DU46?BnMf|*}#?KWP=#qo-rM!slf!N|DewK7L8hWDZ2hR1KlASuFtS(J^SY@t3i z89F$@M8RccPWy=$WiDuv}j4{#ZP(v z+DUiwl)7B!Iq2ppikTvI)78dQh`+%u(a5B(xJn33;<2P9QI($ZS%iH(;*I9476H;; zlhhcsde78_*+2n&C3QS}bX1i-EMifwQ5c3f<4mkT@fP4x8A1U*SRy9C*kRRM)(|in9LcnMvPhm3A*no7k zrR7esoTAnhmv5;w!=x^4LqLL}F1bngJkh&j=(H4Qn(50%(#uP_^e&}#*)^{Q8E;kq z$St>|Ac~^SsW!b(QcXrDdGJK7UB;cFv8{Gea|07AgwU{i!OE$4d^8+}Hu?9M6#+$= zYKq(8hT01LQB*-Tt5=$~HUd_NliHntJc)&~ibTi5M{4C;Ba0)FAHV&_R>v|&W|SDs=hl+&aGZZOiv(nXiC9yoydhn zmYbwLlrc4YFbr0}VzejpDQ4TKYwyTrXw87Vch}(_8(p-gN=jFhD>PS}Ziegcrl%1! zh^`GoswjdXr@l6?l z2kTbL#RH+NV$b`m8Rx3kcvRO2E*H7L4^_YmRlxCse&W+GPmK?x759X4ZCC_@c`sIM zl5IYqtue$}g7MTvV#&V>B+O=;&1Q`lPdFG)?9&{9rCz9|+Tw*f8@;Gl&NUXZ?q)PK(|3MgyAC+(SEI_DBc6r6>vP+6Ez4-~ zg2Dki>qcOWPW-AIW>-TN)t`5cNOFrBi(8h695YnR5)4F7950~{r88F~%P%7=TPP71 zW?I9BYZE?JPp_IxSHnt3#h_EOZKN!>7T342*5H?}v^5W8P-eAovU)F`4)Ng+MXANZ zBcP5efkzpC4wX3ng$$lL!0mh;)YpW-6wo|lb&=;M;TCLI%Z#EG&C>&@r&=e7@=YZ!|fmH2O%|{J`2p3fg>J+CqrVJF*=^2v6(` zAJCT`@z(B;UaslDJ6IXRphHHUI_o`0gT%8M&n=>C59ujs_T(TNYm6bt`?a|F!&J!C z?1g!Ip9;irsM+o8lEsld!`FK_1s`IspM#9AEJJi;eosJ=Pe`D*c{pXYLZ<9#jhvK= zoUF=sg-Ss%OGz-z^o}`8rBGO4Y>Bym#bskTJLO;w(v(~&1Zp~PlKKFjuU59OD6%Ui zJ^6_RN{av@YT0E~=tb_Fx5x4Kh6mD4;e*o6vd{a-upmk^H*5xsF57*|_+3}`{;Jb_B~ovq}jBMQH(#`wSHEOwXURhKJRCws~oML zk8iHWJKUvZq`$AEzdBfRa~&P}olgR?v1ISC|McB^_fVymg?BdrNE`ssW51;ozwuv zYrN<~{iD*~wuRYsIj|32ZOis16x@7sUw4-70U3Xm(e^=(K3~!npx1+{vPr zMDi4H0=c~ynUZ$&cgG(fH1kzyvWD>beSG&gEA1$$aonDbh2JdD4YGr5McZpgwRQ>y|ixbPACT zk_`?+EG}>Uz1gKgPr<8+{U0iSLNRMIN3%b)<$8a_I0)E$SvD9s8W~FI*;^Rd|1I93 zQJzZ%Su9(t zsFLlngZLMB?q(D5-Plu?xP4Yf&Cej7{^_-V(&Sas&oJ5<_jMA*HRqlHVHFJT_+pcD z_ftxE!!8R0v~t6i`Ols*oRf%}g;;p}G9EITJgf95#79n6*-NbUjcB@P$PC#t)c&f> z5=w&;jtg~`h#W@0U^g25^a;LVXQs3O(HA zC(BJ*^VdrEYA{Hl5Co$jIh+0SVEtNj{t6IPf{gWezP{6+8~y99nYWGO#^oOVm6^M~ zS(^*+%(QqoKyXr$`r`VyO2Bh*e9W1#s$Ua&y1=*F;P2nOgbpOc%99Ji?z0Wjy!Dh% zS9S2wQ)t*A51zqbC92+tC=FnCkpDpCx{!9Db@p^)dOc_3)XazNInJkV zI7E-+q@<69?P26)FBk7$W-7oikdhFXa8Z@}BGQ@?N%Na$*5JkU&l^eE%Z@8<4v3w} znq6diW7GTKocCI{QzBi`4nnh(SK((>~7)EMvA^oQ>_eNcfR^c{_JaVOa(=rvVcW{XnT_h@cym~RRUzh~#_roq+{g03 zCFqz;yB(@55fpIS-TRtCBF0U?AV;Y$CfZq28)hgAsc+nI^kU5^lS1)WSxnc;|EsJ+ z997%V>$%~ga_l-))#`TQSbsa@FbqtKX)}F(SBhn~(W}XPyAeR=g>umHsSB!H3SKDA z0UJwp*I9xVu%5bHe{pTHP`&e-g=WdRqFoP(<&CLTDhK4VkypZ43i}!}h zhI!@6Ma)XY+agt29UCX@$3y8)xoO3ZWfNuS&5z==c5FifHq+oJP1}WB)U!4vH;E1e z;yPNX2wW3=)l>pjbA6;Gr-{@S-}Hb|Z}zI1X2*5ndDuc%e(BMM^uDc{WaZ|9eua~~ zHdN#CFxx7vZrr$}}hF1@U$s)ds72L}qWDc@27}5E1ikz(DGGuKj7}u+) zp`8&l{C?GdDG?(lnQv!Aqs}TtN(l$NpAB~==6nbSqGNn@^O0?*RS4%^6*~@ zdYV3DjQEqv^cfKeclf#<-2UQ`@b|sW_V4!kzpe-Y8*5`T6Q{2i#=ipHGUFz#=Xj9< zr&*f>@*BW&1F`|2yQMS(e8YeNlz1tCloauS@oO_udQ-`pD2DZXT`>rod;|jr{6LQd z@S;e}Wbr6|WVJe&Or>5ebH6?8k@#?^QuOi}d}pRU>QBV4`e9cYat5#vE8d9tsK`Dm z_ICQ*+y(PN=|%oAc!(8zgh*`op~1`q zkPD$@NqY8I@+&T^9RAV=g*j~ zIXQ3Zw46GcT zLq{1`Y?~~qI>v`pW}8ew2cy2Fxjk&eYzP_*b~|@EyRQy|6fLyKHgOCjPMwVgt+yzE zoOy?}b|vYJ9OHYt_zL^;$q~j6EPuRt#I||pufMKO!@n@(e{Y@s+c~xW_Nn``L-lv- z!b+vJubl;lmE2?vaSxNA(JBDY0D_077!0vm09V?80CV7G5UrWqh*h~Hw}aw(Nb&@P z?Ya{g%^$H;MOPWuBt}4#o|?(vaA^GbakoeEjWdvhopW}l7NjlQKK{9+SF^RQcAR}; zo6;6q0)oa?3Ys`&PZeR!Ms3>`2|eW?Qnm%eg24k6n&bYRHUuhrG}A=*I0v4tdlKBD z!eb;{w!W^CZ}fKEXH->oK;_-Nj5+-<%$`N;9ug%Mtb0A9^NAFHr8OtfCvf)HEfb)eXifkX!scLr+| zV2DRV+fWeiN)|pssrOulbjB?@g2Ds`pt?U`m{5I8*y(01hb)u4@aG(p(410)h}OoX zO^~}uOvJAU^jyFhD^v0bP`vy zOR$n6b;LGuBT0ZO`X7m0U-}g_@}R2wo2%%wY~dI%JZg}l%P~MvW!q)BT)Nt#-!#&~ z7y<}@W&*qo+T{hW#7Ax_vNeKOG3>p_RxOIB%l>{&ukE&6}AT-a(Jd3J=*T5 zOZOSo{?O&SA(R zta;VP)smfy{fp&YB`A#jpZ#05Tch?rOrIvcOo#uw!uWfU{%<3h{+A;CAH_tYs)i$m z2-?R`Qe#qG>u!J$EuREN|ZuQVFGjE zucCD^Ux32G!h`~{2O_8Rh6YV_^(q<8Ubc=NU(l?bo}KJi{L!fM<(--)ldpK4=cCu^ zyXvj?>GI@nmP1$X%YJ&m#hxuFIKTH0p9*l8T4Z|PyIKWg|o3WCl;~+~v7R_U?I84x`bz z^7o<)^wGT3BIw9p8}TUbQ0z{sAbU#bzP9<*dsp8vCaqW-Ie@sh5f`oaufxC=yGc(ll)%sJJGbYu z!MLEJvr}>G9dmN2>i1XyPb+nat)!jYt2rmFLFrzzn@w(`1*K)d`A>J$MddP?ue|e7 z6&HfK(pnkSC!GM*r*YIUnI01_o$IDsSrj(~AS{joEk&dpuD)DTgACd+ts%cPOHcQW zUF!y0b6BrW*>dQ&b!;taju*XaGo0LFj`rh2HF~m&D2n1PytH_P6-=EP`sO`LBbhXx$0{S4@xlOATEjEKX`d_JeM zE^aUYnWPL=FNh*Ys|>fZo85ys4lo{{=o`2VD(3+5jHAR>7#HtS$<-^V4>&HMi4zf} zB(-Yc-N2ogb)Kk==onW>>K(N-)6S5w^~W?QvES6Wh2U?~N8j-{775v+9hg&c4L>2T zz<6m*r&MjAMDHIud|;p;#DRTM7y<DXbW0MbQXGSZK4`aD53d`Q65;t)Wu2;i+Z(9DCTTu(`aKzO|?a*N$z1GsM ziwn!%!R*hoPYT1~n3}6%-9Ca6`IMKQcLlvevMj+ylu%$* z<|F24r+|Yd{6NCJ!=l*OQG?w6gZY9|YsWQH^2ww_*IKEnIELe1U~tO`cAlkVpyq@hcNVhnNWbI-YvVr)gP$ zAA3m_zwWTN*W{Olgbag2z2uj%yVF*u`sNCVAqsD_^Jf1@wR+dIU(--iMi_vCQ`m_F z+k$~Z;fkvv35V?NBK)m2#0Uy_w+MjF_h92YzUQXLX+)BQfoWR^GSlrsx~kg`3E&41 zWe{OIhkO&HX3k*bK(F#PKm*mzs=}E$`xB-Ed~Vff4w9N6&zHs3rCMjGGwQ4R*`|lU zI{>KsWm)!DfL=>q0iH>r9cKBGZ$AmSK0-Agr|%zWmZQ4ka()VceC8#73TM%A4s^I? zEJy%*hA74k3on)?Dypl~5hfHB zW+HmsaQ3cyUzSq(3XP;CdR-U;?DTaaXt4@=UnZZgU6@;@A>?B)EC(=4g(zqxhpT6g zNh;;_12UXrDJ|g9x}wV!dJk0&u^VSfCgB02k+rm6&3xL8O^^}QvWuM^k4Y( zzr31N?DcGI|I4bmP+3g@Nd@V{y(y~@G?sOYFl~VpmsJkPh&O~Dj@B~F4~%+Jl3~uc zsQuyuPydk|M`6^$^8v4GAFnhFQfzF@;+Ex>qt5d;Oa!hj9$DC>!?g4C^A!F25l=TK zuq~91P%TP7JfW>LC$}OUf>6#FTBJVI9-ZWNM-H{1T=Xa^^={m@)F5r-xL+E42L-ut zU|+_zCUTvHoaQhza$A@ivKp{2Foy~0F;?w{r?|_#Wv{5wh5TsKSZUlP@~T2YF^E+2 zd1O0V|6~dzWRQhwRw)XowUXm>ficTF>#WS_pf|Cj3JqG;PMS-^x~s8IP_CaL`7)Ee zg3i1G@-$_Uuv2i}NI`0|WA*N=-LSiv%!BHDrKkC;*wli$SU#<0;raFw2s}%hZp2VR(DzxJe($;euY+M%8 z>1|9Gr%?tij;bVx#Gz{sT0l7S^qYv%ps-q?KkoU2bp!!OBC{}M@CFA(%g)RC74|J|Zzl~+ zI%x)$=R(N{0EeS<4_N^}Ov4rh5$Sn=W}7}CWtTo__M<$-MYiP+sk-z(y-6h{NWI!u z5o>zPOn~bYH#0IS+esTu#OWo9MWz{z)di}9Bi&o}dnUjFN;e1p)3R z>b8yJ(b_(E9SE9&gHYfX3fe=Ss^QM*Bi!waiBFcDmRBjIck86S9ODJ?h2OkPex#x(VL-m<_c#O}(l~^eC&CA8tM`3- zhggCf*53GEVf4_S^o+nfi+M0&V%-s<<>r-7)qShd*eZJvC0_d>8v1>6@S#(%)2--n zRgcOG=D95TCD!Mx2CEc|!cxNn&^f}FXV!yksE@G?P&HwG2n8%#yTw+ zCg7jyjmbl>IYa^<0qVbjJhB#;sQ@!|(T_r(fR!&0%ISnSi|D4xru0A{Tl%(q(5&Ct zJR{4Wk`g~)+5-A>51g2f$kYeTwDb?=D%>foYZ%;@!M#w88a+xxc+G1z1ZdpC3SLZi zlILFw0OHsMWc}mVCA32pw`!6q&+{TELtp_>3*JHL<8%KZY)ttnTd4D;4U2;OpNRPH zJmkO4xA>DL`U<)D(|7-$SXgQ64;9l#l4V^@XrLlESmRLA;+r3sltp34;BEf$x5m&C zsm6LjNK29xS}|M0p_@^(cMQ+_z+~#s&yK)Bm423avSS=`?r+;QG4VF>#xm;Hi|Rgc*$J~gg2PmWlXp2|g|ava*DVHNZx z8*f6NgSZ@GzrG?=_Dn3ZQItShNpG}taBHtKUc4PrPbDd?U&xcwW-?FudQ^?IW(#Vm zD4=*6>L6;Vneo87#Ied{nU%yFuArO>lw*ve_oys+{QU3HpDJeT?k4^ zFkx0+bfB8ka-r6MjSi7D2%+Bz1(kXtNTLB$n z5pJ_w#yClA1T~hkJ#9U8t~8y}u)o&;v61W%VD%5zSA*VR)ILIC5176Y0)vM#eWDL& zCk=oT;0$1)E7;Kn)7i0*(ro()fl$qT4)GEdo?w$;a6pq(&ivh`MkOm=^ewS`hjF-r z;m48oqT6I|NGDwFM$Om>k+q3AlR>anZnc%hL0kipCf5yOO$+H^8x>YZ|5hjMPYN$e z_HmdZsdC8o235Cd?1ITQk4IYf79RiR7M}5Vc18Pdy@K?GoPoDMTG2!oYno1eKI5L+ zdNEtTNuHuL)+I&9mHJn0!RLyHk zJL%)#9VWfd)&t+�Md+Qd?fM_4n+N13=4JY{SfhEC8&Fz{l56BZsuBpU>^ z$d$7B(-{++V+p;eMxoJ&`2L*khxK^s#~gO!@RhKRVrT$b&3-~Y%{}(v?4TJ8#Pp#! z@f;5YJN;$s>YQp-D7qT0wffDh(LZ?Dbt(E9WYrary4vrz-9qA5Oe!$&7Pq!RVRU#U zCLVNCEQrQ{cTc^T%z2yyHgW3*RGJOShW=VnyB(om3zgvVoENkL^#j*SICD7E=ea4* zvXH1PYkQ;i8ziSJ)_$UOZnR9P(l5E6;!iT3^cl4_j)pO+iMf81m-b2l>lS4wMS z%vX*GAJkCyd}Ds2In4{yk9j^I8trB-a4MwE;<=iQ)l9Ov8(8kNKT<>x>XVhiLxQ7Y zVsyF)uW+huzES^TI7UCmz=UfHET9vqA`~OU%v`5@ioJ;Q(jy^D>T0<>3Ygkn86{8b zt%im{*7)p+`q_K?k!c@)4VMWuUU+;RM5<%RJO+BiB*+R`ThpP>f^x>MR2o{zI!R-d z61oup)=5)6;y-5`f6~wR7UYZ&T zoB+%($=qT=IUZN=3`<^Jg0~d6QWj~ZNr1jb*IJqw>3qi~O zCbd@F;_VIq1>VtAVRZ%*;I@~q+%d&*vrsXvw2`8@6-n;2#fnj`8B6)-M^xiYblUi~ z6@%ka!*x`gB`GcgH1)DqPriC6>MJ-fD0D=$N%EAoo*5O92xw?0M+9ckJ5A>Pm5!d( zE;1|i@E?=}$QKN^KaO5eO7&?Rq=Nn3@zcfVe+z9EbeAlzIv~P9D-6b zlN+fcGtdVuko`h*hXw|Rg?wsj(afou9yuO{JfYjboE?&%XS_E;R5w>;fM%m6_gXCA zi*lhM@lVYV1~6lWyD~mLL)o1?6i<1j0H%nwJ7==p))m7CKx|vksW|(8q`hO1Wo^1G zT9vlVO54Ut+qP}nwr$&XW~FW0wpE!`H^1()d-wkCJ*VTujhKJdnm^~9@s9C413hwX z!pYXU;o210q%`e9E08!I<{6SLmZEK`;zyG2M|WKyQG6p*R_OlI$-%nRFpjrlDd=s_ zKv~EgDGp`QXXYwxhD`y@sMN{cNKO=6Bz28QqCj|&tTf5#Vr>5QM1{p6QOvE8JEO!; znBVy=Dk4vqQeQ>H)BIL`>mct7Qohm|+Qfky_01o2m`f$@m;-)B1cgu$6)yw2!D*%p zLY|;e@2D&34nw6cGn+##814#$wcloS5H54XPdPdhQEqoAiAXNxoQYW%w|hRsB1e8Y zCKokL3OVUnNyv`E1O%=Hq|bW7xMx|rJ@;B9vQoAb<{2PwBdNVS@^D&ZtXFjBdjZb{0L38Q`ftZcrFrZFW9Y! zuzZyt!ZAV7Qnd$WQ^x6&N9Em1NwR?!qT*g~x1}Rh`SGlU(5E<7lV?BLqex2TB?;qVRlUpxEqo4faAfp&ED#Sz8-jtTvNgX;k$I`e}m{<6h5y4tt zeL%d#I#CZum!IZ{E}dkTkUUnDlnxs@%S`%sMrnZvQTd+_d@TJX7x0!_(+!c|;|~S= zI?xDinMClc4+EXOxVA^3r5#*8@IK=k^??py85}VHuj?>wzp$pwK(c#;?RfCpt-xG^ zr7*MfP{P}9OD_m*mYpyUo&Z??*gZjXps+&3t)MIZ!JI~dxqxgx8V-UM+B8eY6V}c> zVT!ALSyi&O0USu4&v;&h*DYslW2#?PsuhiSrxnirBAj-5JEb=8&uIE|=#DW6%QKe& zcv($~$u{gY6vk91C;3nx$L}>q$n3#bQE?}84NgQh9f+3$zd_GLHl2<(zq4%xCb_k9 z+J{R=N#^^kcJ7b~n%`e_#j;#6ddf;R{&dD`=FxfzC-r>hIrkB^TBxkHKN8 zWfL;+`YoGvX5clh5l{0yjFavUm^%9!hI7|+C;LTf`YCZpAe!skx>l17I?Z)~Gx9`V z81jIARp`ZQM=$2sD#5T88$XZ+o-lZCbnI$<}GFCI~H>H^l*0{SVy?|=KiI% zg>U^C&w!GQ{5grS7o8!IuR!_wb`i<`iCvZ02aY}QT{N`{FA3e}VZ@-VAkv8SzH8#> z_fD?{5VEjix3EsU{hCnL6~WdEf@_bkg}^{;S9@au-e$HU@La?#in$-WG0cN12{U{D zq$Qr8PT#PWmD}eXh32{l_q(7Kly`-0Er;yKQE-*3#KHf8ax$8 zg}~pnX%!p>RD*Ud6ULcT#mQW-PWKl$IHadHBmDvf%l`u${GBz*{wHAdUqe4>eJ2NV zLt{tc|N6u6UuvztRk~KI+FEIBeZNp5?-}{aU zzaM5cEc75ehm%ZC`wlthCC;pyf;gz!&mJPqut)+E%n%%vHWo1)M^9r2)~Mgqk1}PC zNfwt#Pu7mqLTD8AE-I$o|QQjk+*a0k{mt^)%Qsx5DyCqH)Phwv7m7VNZ@Df z1q5BlJr{{zN!6k-K%iZGwkNSz^-tcXaptYPr|n=m&j$%)6KP73r2yG<>gvM>QP2Wu zbq7QWaL3i=jwME&`FcHmHXFD>hl3(djv+(uJc*g#I=#ZC99~;T2Zoe%dPzbgX;FYg zIX00AN$-CLN6FjC3JLJ{i$mgIAuv9f=w+ABU6fSW=8H0S2W@vet-a29jZI?+mW-M{ zdBk(YTs(9H$nGXW*$kWbuZoKDLq0&^Ax#0Hp;GVZ^R&M^=ua*~gASmZtf49wN=vsWcUCB-t~pGrKUtIT;2V%bQl$ZSJ;Kv zy85dW7|%;n^p`o_V+@Yr`i-ZTIs}^p5L54vE6MnC(w2*JxCdY)Egkj>R@`q4wpyJ= z#|iO(v~}MpAJ>Ralk;uc!sK6`e@sgW7HB!atz*Q;vvOFi1{|aSt@o(a3p3H_6g477 z&K9@PbB!NQid>d_MWo%`9HVqVxS|QE)GMF;Rvn)1j}Iv{o8^C_c0JC9JH5^ zKLvxx&Z;fF^$*w(7-|Y8)it?#ar3JmG=9swEM@5bu2aXML4|VPV5o^LB_j%ue=?ss z@vm#&U(o1|NSsR!+%VmECrqvGZAw2NQ>t?$OqOXxusKp~7{>pU&NEZ;qJ9I#^^^7D za(_m{vp$KB^=z;FWqRwZ?f-|2`@WuZ7UIqTW1tj+3P^C+x(#<9^A6MM4&&N?M?2E> z6Q!pTqUs!r)Ks@K#&#d8$1S=RSyMgY?ZY=TC{s4UL(T_;vla_%*awr)v_v`w8N$o! zGh&Hw64iG2BC#Y|EcjWLJ1eJhtyDKGfie%isK+{Oz$|6Jtcp#s1DEFu_%onrnDoFp zbbC!ZISHBWh$)A5gBcO9r#Y4&bEthoTw&tJ zW}|&Xgj+mLRv{AYEVoX6=&hheuVz!&3&x)eykUIxW8joORDcNI`Gb!z9$^MfX@F9R z52xV3BM5F`qtRUABL+ZtW?{i8CnsO>k-A%AW-iwK7}vw!r|&iO5$Q9<*hlo_^rh+- znMe9>DfClar?C~jQg8kDlu_69LD!p&Hel^j5vJ)qpJzkt{x&~P_ZDnvH_$*a`iNZ^ z(zyY#VG5&H-ff9oObyTK&|@4T;)&HTu>$a~yjX11Ff+ zTfmM#ImsPXLO;;?h^-x&3!wnOEw>qbc98WqaA!R@<5s{=23NLzC+yz=ofs52#q`%E z&p(E4ZC8%t+KRVf(M}z^=-SQjC*HK3;0ygC!7y3c$cM_}Wv`qsM-XogwlWAQ`$3a8WfANjw3r|Jg(=`{WqSo)jh@Bh+&&?kZO-B+ z52wxD=ej|<%MgZi&2v7P^bK9}BubhsBS9jf*gl!1;Fr&f{DfkShX3>*{QUACoJQ3x zru^kUprR|F$%I3G-rP{W4%@m&ObZ2-DQk_^Uy)EssekmoR9lH%lp6y6m;azEY*4r< z^DqBFC|5?J&W77H*HN|R2Uk0d!0Yyx2LV?*&D&+Ct69*w3PSNO55oK0cJG?(P=s?( z8vJe2?Vhg&$>bk2-&E{c#U4kF&ds;L*6RIk*56}jIfguJ|YzDx*u$vuJ7avU_~2PEZ$pS*H~j@$_yK9WMfQwdDUISXmj?e{-#L69MQf&O|c z%%r-xLcZ`>$CuvizqM|Ee=GiD^4ot)LI17-O-`8jYIsEnkwq-ug{8yZ;nQA4U?V*j z;le<+M{9Fb<_t~W|Ej!+*;~{4hhAO}Wz~%SO#HXw+ce49uaOJvZ%%r-1Eirea2qfg z!(dX~P@}uYx6^M*W%cuzP*)NCYYHfoMy35EDQ1kaEj<{^TQW`XkVk6Pt=W%pV< z5+0%n{8SlcIKILhO&phYt4DRB;XRdI!!={(+kIVoS1)MOxlxOe2D9o8i5#PO0Ab-8 zE6V*o2xmRJ57SIFk;spu+M!p+n79%?&4lyx1P9Jc?eSd$$lpDbU`@_%yIMcx+<(h< zm6ER1H0Vd@2aEyvv`jj=9wqzq>sfIMV#8o8j;frx)^P@MRwbP%9OK zW###Yr2$(iclpQHLlFD_`w+gGcK-#1rT=Y3{xwH)MPB(T$;g;nHGpCLp}5y3eI`Mu zi)v@t>k@@)6cAv|GRhYvs80=h??=sXpJw1-E+8gmmiU;VBOoDhx?ikKC5<6qk;wEWIJ3C7tW5>*7-2w;W*&pSu?S z)3$)mIK#uVJ`uHOAj1vkD!ND2&Nh^+w_xtqV?jxX1fMXQ{4U$Mr@P)Q8)l6`U(Vgn@_V zHZh^TO~4`@e-X~(c)axoubmFBaWV8;lzP@(jK+nTyZH7Y75R{`{&mL0eBte2C?g4F zlRWynUsuTcOi8tPttn1e0^9lL3eKljxK+b6r!dpiBwKOYSsIi`VR(as9G*pTQre_C zke&79_&N-a-VqZNjAcCf#c6QZT(Ci5_DNUg#9ZmPV^dY$Y76WN@EK?-fsJIYOdGOj z^!T(-m1kR{_ z0oNQysT28G_o3*RQd3eK%OJY+lLm8H;^?Ft(wPO4mW1^%l4#ls=lsffkt@*05mz)G zu|D;a{MK5{^zbazVle^MFN{RSWn3KvgH47fMo7OvI4|Au>&>}RdC%?2tcmP&L-d6@8QRl-%hXfrEX9hsBr0!;&G{{~S3O>+2be z3-FvwqMM^UcP2m#?=mzNcATFHo9R0gU&f_!)e9F&b!#SHDZ^2iIPAWo?-{#U@gRQ% zqpU-Hah#g&wVi|Vg2o<-BGexGBN&#jB6bc9l7F9LmJvMv!FK9@F`H?dS5R8c&vj>h zN(3@mZS#)c&-cR}H!}m2Bo+2NJW~!-Tw;6unk)VTIT>_z@Pbw8ex3h`OMU{g4Yl)3 zhfLblaVhX~HPA$Yxg9PKw0gfYT?v~)Sb>3CN_6P@st9P6-v*bX#;cQVN9N6Tg72qb z1ai76qD~f0e!0RcTdB$KT~G9+51%vty>U0ZOSM5nRuqOlKs4kv`V28~&T>oV5~<{( z3Z1;>Rppj6`zH4$DFjdmtwF7K)Q^)X*i$z7H;xK0U@5S-{1j|8SAsm|Tlpd7#e_9G z;E-LNpAR=FFWzJ=^RT-RtOw!+Ed2uP5}_jI*J_aa+C2N(AI=NeQ`AwSY3Wec9(f>l zzuaAqHoV^eJzjK2+LymZJyASUA;E(VI;NUuzA|KziA-Uv!RHNIxBKRj6j?n`paF61EQknI3 zHhCw*-U9F{ErlLlkj_49$apFQk!XY!M2RcF8sCem9ynX75yLH_kO@fTuMA%}DCM=; zK?Qki1Vn4OM+GGGk`e&bK#2I6@)`#xk)cz#@R>%Cthg2MF=)&E79~WhoaoEkQ6Lob zgerYhJXZW;P)#9Ac5%1VQt_njyF7X6ybI;<>LvL05u3aEImV~>OoOs+v%JL@t&-m) z-oKG}`z0{mLW$$X8>?RN7b{dkCyQ)tkSG=Z;|@}aJ8nVNHEs6I-OLPWEqKp366$>R zldYk5Hx9bSF_wlc0ptDm7BJgFA7VLQmCB=%?vdH`hJ}uqPW*ndsk$(G~3UGUFh&z1Zhs5Rz{MG*OUYs?O zo<**ztt+HQfj>v-M8XZC{+iTgZQ%*SFkm^XrLVQGx#y&>ecnA>xPEg~8!te2WgImq zKzEmtm`E~^i0D+1GGzdk{GGkTP->_%0wfsn)0#6L9Sk-k*?^ofMbUMWvUPLzWz6zT zMoGJ_pRrY96E^TZgxpczv$Ip{_Q!qJ`a>azWK#9z8@JhPj6bT`6%%obHJJ4d98t(( zPqmZB8g$nw#X#c+CIcB8#T#WX<0ERfUoG1wF6}lu7t8%&ME=DhEAHNy_vKhqbD{t~;l3^K^*tN@nAlO`Ns!8X%foaqZSW;@ISu=iQpT_6WAup$g0nGtVb z_}kfDB5sqk&z%O0cak(^$AF0D`oZ!@+%APXN|+X4d^w1ARG*5+vvUx<$xMH!-+auR+ly=eP2IoMVT ziI5S?3_^TZczqBJ6^q$Qlbv}pZNFx&`|N)7zuqDzg@okoG$;%`8}n)A%iTBq8++@DrW<% zgpeGd?3o|s7sf|J$R-{}+_G0JE69~Za0NpF{AGjnzJvbwuFDdSyYe~WY~Ke z2AEh60|_}XC*AwGs{48U*X7yA>*trlU%m?>UsHf;n7Bz_tDi_JXcm!l<^WAaN z;=z(IVoT^qcgf}^jzX{Xc1)T4l`x8{YTwSR2m%kC#lGqAx=m+P<1;OXq&~9gQX2l& zf<`w_pHKLcL-SQ`fA?_f>!6b>(w7`-fw^uwD@)>pC`LDyqR7yS>hh?pO(jNvbH} zkLW-iQ{HASuE0Vywl>tHx_gk(NsrD?AC_{%2noBI7xUlyBSYeN;!B~$jd}zb z&HvujJhxH@$%qd}@5ITK9vjkm`j^r@9mTf zG4`|J3S&UJL4g(TvkesDg7q4KtQE|R1v1j|mcRv$_jEs0tLt*#xPJrd1}fNIbWb({ zejXqL_3K0QwwMw2H5QRwh(1}uS2!%6ZkF$Xpue=jIG!ca>!hey~z%{`AWH(!6bL%K^=KFJek z9~g1PO`@ih9JdAvsE}2fBHv|J=tTWk;-MtLRh%snJUZ&dA3kszq$at5*wZ5EwjEtO z%O4K>!z}R(79$-rk@^^z9zGddF0?NYG#d)Ha+{+6+$iD@Ms{$1xne87S}Xte;}GTl z^pXB=hh+cwdjGXs{8wbhe;r=csvC~T#wdTXNv~SY6e#5on*AVFOOp87HOZ4wB$|u) zESgc0t?%P$tyuLNDNyLNP(j-%U4;k1O&cG|s8-o1Za@bUsc>R?(U=+SN8=;5=G)+z9{c`o}mc)9{zQK?gswvgsfK#1pQ z@be9V2#A|TLLof7X6sdXp2t87F_;jP^~PPLDk9PE41Weui%W`)rZg1=d7$Fl=Hp~T zy`$hL+~Vc`s2DovC#1FwSC98YTM+;dB18xmGB6>AS-8yH^HEa+Nq5lqXTFfJXr2VC zh?b?up)3-Wn2^!%t0i`aIA2{gJ6DnNqDW@2`e#7)1T9nb^J_My)wuw1ZeX!7wbGnV z*%j73>afmIshMlnG@NN8+UnV_oNBm0Oxbla3Mr+rM!I#XrI7rBSkhh#KXz?z*zOs| zz^1M9d>jlY4q7tooXcRg0_aD!71pdZ2@lR+rb)^4ac(VMaR#Wz7slXN6tp)4dYkP! z_b;Mtp=c(~+2}W0ZhUu5LtCoGk- zW|q`p!O+AbOm+a+e9@vT{0muzE?pvQG^NE5%^i9%kV{21tN!Gx1!o4ila8mQDZS>_FXyEqcjUrBi-pnbn#mx)Oab5 zw9-8age6BqcE(Hu#3P+;GNPuPCf-@`VZz&x@j-8pGe}XvR4cKe*Cc{Qg%p_Y`Nj<} z!~!d>mqQA}!LRVP7NcAM<95m_jzb4h$-`M}*I@qm4yx8Pp3OQmdS*BcE!W+IMzKsp zIdHdVr4pfxXi+59ac1+zmdUZp+>%A=s4QwV2B1804ES{AYC)-}US<3AG34wO`xr5m zW&H+_*>d$D-;?2Y`~qT?yrL2*Ddoy{kx_H^lL8hfc?K|1P3>id+}pjrqeCVm!_`F0 z+yzHSwpHy%GdwV6kb|iKny3of=V?>{x+tgfobWFT@u=M

(ixS8aob6hqy(&9b2KMpxBX%OYB82{fI`1M&{wiV;PwM6(b)W7^0CG zG8w-}So0^&$c5MX@OvEJWZe*J=-`u8WKPN{--N9;2vfv+K zdXnyp2kzz-+yQ#41AkD}#+sC2o(3j(^ZIm`;O}A3mbPkW|4Jje-f$qoAh zV1uXa1ZErrX7us0M;JSLA-jXnI--7P_t|trd^*97oPtd+NPh_I?7DVD|2);C%->)R zyq=YKk71pEX$tnSgUXLtQ0Yfq>s`9)`|1gf&hn|1GU{N*SdSu=X$jI9LX+`E@GV@6 zk2Bsk^-&GgO-UwdCm?#mlI-|!cycE7OrKAnEKmt)EudL~CtM<6KJ@Z8e7&x#D3)46 zYT=Nk$iG_clQ_paSdZJgH*E_@f44T}LH7t0q~5Xp8viU{WJGGa1@C+{sX*-b{sm&2 zA&2;~zZ5sr$p3ym{++%3M-cnP*__O6oNb*QWu2YuoSpu0EdCX_Z}q=OoGPRj$`R@x z-$qjxGPX!+Ap}HeR!GFzJbnKV9E2&-G!WFPAaR$3C@Yr(6ZF19m3qA9^<`+e@51Yg zXsFc)ggOAB%4Vg?>Q#xQ^#K)OYk&pdeS7lS$kBoL?TXEI`=!U#_omzZc|sHqoE|y1 zJuWg6w`~X%lC4x9&gSTdRcHC3!9O+HW;2G%t$o2?+NQ03EtsZlLfF%lsVO=lSnn7YH(kk)7;#`Kq?bW=H8)6xB#7EF3(SmR&Sx7 z-x;=#1;lk^vBt)~Y8^UhNkW{vBv`_t*~Vmz8R7_EJzq?Y=1hgNQ$VAwTWF;!eswv> z(4vV7Nx>k#EY~SR_79K?Zzf0X;v^lrX0HZ+C@7<4bDakIjg@?%w1i|BJx6oA3W-w- z($XuyziF70dH(rvPPsfR$WVhFFWhxy#8CS#tw!F@MS$4%gRjT3GokAQpGI+jwL$9a zTw&nQ$oIGW#Rx58hTkIKARL}B0u zy)CsoaZk*$8?yul+3saTMI{SkK!3lw5TdoJS#tAtAd)K(e|w5{CBaTelNK4)_qZDT zwb`Nz^cVmesFt#&#!^k1h$*g{O5R7=fSKK)8lIr2rmFHh4U8+(K?U@Igji%X$;N}F zMVbKA^kHy;@lhnftPezeVbCXp1XyGWGN|Z@kh^FI4+ERW{AVIUdY^31Z z9Rf#d7Up{MwZ^!y|2YE#Q_>=bNmHd0ivpC5y-y!vvX-WgzmA!)fzp<)<;a;=BH@x= zf4gF+y_fxxnW6|?x-DTYK-{C4C*VA?;f>~!HX^= zN_f_>jfPVlH@)~qT>+nq9N=8(S3b(a_;&$Oyn6zewR?Viefr?CBIvpAOggD|VB1M| z=v^cSwW~M1J4PS4f8y>~f1maKH2Q+O#$6*p;CDREmjm?UR`lPiGoLlMq!QI^@8`hF zQtk+tc*1}gdjheI1`$k|wvB?}ZX0BWf7C<3UYxOp2DvdpvbW z3@ICkILe3++l0u&QVJ|tQrZTGtJO+qid6PKui6tACP^auS)zApU9h`woiJ#ZNWSAJ zY6%xwHCEVZdsqmxRumD#Mnp{?Z#P_~wX} zj{`4x%)0MfED0j)^N*Rylu4B0 zd?5FD&imS3FmM!?Cs9jYU#c>koD;&($=uYniv&$sg92J+694$s&Rkz!V-)z{K6J~; zWmu4*nyM*fp~688DP`K2U$$R@vN`g?vN8i*g(X{2S(vs6rp(&PrUFulg)M1?rosY8 zE|`+Y{*!8mUz)sTxfK@C5TTA#!=U%eqg7NB2!4~5uV%27@3c~GY0%;Gm~94&O(#J= zIv;X}81#Kky}Zn`)9u?p7@a#k@9?rAW#sZMQ=xcdhy3J;7W{yd0H=o7#0p9weot5r1; z4^FXsJO=+(8gDysH>7KxQ6T?*f-+9sIocxhg<5n>7*nJy@w(#0^ZNT=DsJAwco(!r zs25aM+Qz5=-EQFzTQ71HSuuc zl;4G%eKt5NqZycRSrR?u=L2^@*bL!*=2E9MhRu<`>;i%uJ$gJAOy5_qica6bu#=g? z9P)VY^`#1)kRpzX#YT=$o@^Cdbo>duA{(wPn0K+NdYhA=SM*tWq|+|iwhVx6gy4H* zRkngk?U;0WX_#R*B|cwS?Wva|9juV3>eS6v2?g3TwF0UQ04-b+xCkRGl95n2yKfveM^f38l5{`x)IQ0=t z6MmoUT@1$F)5TZAWXs0QKD5Br1TCVL{B@ZqR_r95vlYKfm-{GMFlDnCfl8@=PiRii zxg;jQme_A;nT-wM)_ALNi6iC=uM&6HjOzhkNIjB19}1U!6eSbf`5F7zmV12!x8?cO zt(=g8Sd@St4A+cET)a6|6(my?o=m@Rwj$#I`-Xis)>ZNj_0&}N76G;hPLwNybgF7b zhzTO6pifpjL3@~oK4RC9@bI3TX+g=B3?&{|Gp;0&-w@>Rsq{V3B3OKgWX5iVvOkzy z`LRHNzy9>(T=9HVNLT;f=6t9K{tc*#Hy#CxjmVa$)e3WC6eL_h)%;PllmUkA+bWz(WvRaQHmE1Gj0O3@Uwj2C{lzz1Xo(kRDbE zGQ*x2BN;Y@`G$Ul$x8e$MW}jfF@hEnAxx{npbNZ|YH#`twwO2?>2)y84MC$Zc7v8p z#@OtPRB9IIp|LU)GTfa|pfU1Lo^Bk6?xqrHYlVlnf}0{D8BT?aWARSp(tDlq z=nDq{=#w&yN4R_}~#=Hxgu4li*S%s3Uk&4OkyFjG*fp%ti`pV!N zVQCz^w>O140Y@T?%rhN~R5Z1L`*BB5SHtDSXLy+`X{pJ__0AY&^Ybupb!6UDTx8m= zGBGh@t0By}WPuF2R&z}9q8r!zJ+*drHS#IeC0^PhA{Nv9jgpz9G`D_}6_Wt1{@X`ucr3`a?YW1CsqQ zs=B3GgM$M`e?Zwd)&IQs???a3CSaD_flW3_7Ku^#?g77tNwNVTrqM!XS-luztSLTYr87#J19JiL(uh@~`URY( zr1KNwc}wOm&rd(9BUJ+u>$^1eXGyfrg2+$v!kwl$+x1g6YpW8>fx6PQrV&}^wON4P z`8C-VY;>k{^k-3hzG-7QnJk?M?#~<_?vXQREhAFWcxP@RTOoIS`G$R%ERAyF)uOAe z3rv$#6OBygPUBxtMFTzDs8FF8}qbKNw88k;B((C8$TVke1i>{U5z8QAh^` zz+Y*>C%FI4w*D@l|BpF+|F8HAIR{%8^M92XMaxS|esyzZmp9M7D+AmSW}plZ`XZkW z&-tm*B6K{)O+vR8Z5oUkn_s`uV!wK1_b>aD<0K#<-I*TnZW!=$ZEwEWfq4S4f?7eY zima~C(pB&Y9x2QCe`L?ovW^qt;0PP?ydbkEI#gIuiuPe=>ckWtkOf^&X(=K`H5U8f zeg}N-)WU5ax9nh16kz`-5vFMDgQv??=ClDm)m?Rzi! z%W5mqT8eED4oD#K2Fey`1HxL(cu~J;n5FNA^MLjM&C2T^3rf!*YI^7|G1mS6a4r0u z;q%l?(lk=9SAD@|7*LsPaNoazgSTLkQ*2+KUF2)k7`o=Vu&S(`V(SPmhm_&q`-6 z+fpG20SXCBH(RbZofDleJ)S$h_Xj6B-{^5~jtU@Jv0g=Jt=g8tG23WY36)+5KF<^YhnsC+`ciSgmg1O^OV? z%f4JE!PeOR*zNU29U*F84eYk~)x+(D{%h&B%;2l&KDK<%zL~o$gsj2RH?=`R+*2VR z&UnW2{KyyJ_4v7wd|A3^rv@vEa%aQBT^(Y&Xt&tg2=)$xgN*WpJ16jU5F>`F&5YV> z`F})$ygki{aqq?zM4ZNM5B!-_`XQ~23Tugl zwTNjIZjRGZp&va?jpWGn8L!8_Si>^&iE@+mN2oIS)rx9ciVRZ3Dd@C~MEVun4Aeql2}8ZO{b}R2TF&BR-9_mYx``xHTtm8q*7)bB?Ctz<*Kaynoyilq^V* zXlX}IILPVDwcw!E4%qDHW2SUkc3TsEgyBrFLLWw-?~g=?ZmzO_~u7!-VE zSWgb)AUiJEp&qA~4S502q_fA|q_?51K-O^94(0oM)mrE+5>^!MN$j zd4B&IZ#)MNW(xQR&D-@4zT5%xKMlFB z48kKa-x0BZATWQ4msM{o!toDCfXSr0LUPkyDZZp;A>p}uC#2hhbW&OUnxsDAy6LYh z8B$%<5ZK9aUk$^^xTnl_F-Q;CAIpQC7HxPd>93SF^!7wH2$QdWD)aT;gYg~mYiO%< zN!Be@nkux}*ex|Hs%Ea5CRNfqlMKn44xq}0r&ZDh}FG&U5ThD&c^WtF3;==j7X zLM*sZ5Ue7G+x%BdHxr7jCC_VWG>VmJ&sa5g%X!RO4+6{)BK!oB#>?%KJK8{?wq z+JKgJ8-r~nv1<-vmlOsZ7nm$da@1L$CKJX#pRm4Cw$+qAkK9-oGWEznl-z#(*gmMM zJ`emP$Js_Q!VQkkaOjFDwDSm`0aO)JAF{)NjnMV`W8}`+ClP*!Pe=>WNit;eD$1Z( zQwti(0-Z7=V0#+RjSu9WHdf5>FZ>F$`L)M>31}pLN-!WtX6GvR;dOD#4SwrKVc`Z@ zu|KSxuN!{WAB;S7shDEB6uPrVsp1R}`1L@3E?7^<@j7ueB8IIaAUP`1<_bB!33gJ0+qowmj(w2VrtBik6H>1Z8?q!d3-5$H!4IXb-b(|K;C#cy6etSgcBRlOYgvPi~)0^KA;Q6 zlyebELtM-b7JaP%aNVp*Q^AV-)sye}o@9XUnBGAH>T5%<#5%~{OVSV@#a zrALaueGV70VM+^1BS8Vr;cIazm)l}JMz~^je@LsVg z*EOt*{l-S@4k)5B5k#hb17|dJj*s~t{3z~#D7o~)E__rM98#XpS8%yYXUvGWMA9}G zS$fl2D=d$$HFu*iBFW}6MpylU0%dFoQ=P9%(KL42*1`b(K#w^;GTE9>gUU zvgFojJ;5m1`Vw3!C6CdBEC{ZseviIZSNMEIy2Q!+@ z2u5a1t&0ZF>j(0!ZF<68g4bt)#}A523D>PX2{#1u;n zvL+J*>11R@Dl%hU?yBd9vJHH{NuTaz%@g2<$neJqH`vv!3W+tdspncx0LQ%!%kq)R zRbtBxShj@B3P4sh+Cf?d_3fdM(Fx=?rfm6);teUH5Yh48qrypXp`{uTc+08WIa4Dd zJou!a_wX$bZ=y09QlY2#j zjjL1Ibp1eGm{G3(1*E*XxT4=taziBZG^g>DvmSnTlzP!IkdR=^Rfbl@f@83Xq0nLy`cY}eErFeMy+XGD8trG!}1(6An zjDpKfMvOoE>og*rxpo2DmtlFBuATJ~0kmw{%|C3y^=k1k(=p~Yltr3Y*y^{5Z)nPk z+=uGqakjdhMt7|iXasvmlijv%@F2Z=V+rS_mi9?w;o4K4xs^CmsDUv)w2OnbW84xT z=Br|Hyn6&5KU?VYFQJl0)fl2sB|A~lKRmsO1oDq4*zOm>+Eie$nW>FU%tDxFFc@Kx zvKr}0vs>|BoE0y{CY+8F;wH#Gk`^>8D=>$`m97B#oc0q#1+nOA_YB`>MByfQfU4Tc zUe$)0VmI0Zk1#*|VL-7N!rCmrp9+!Zh*LCG_biP*amNn~^Me@^M3>mS$AQ%u ztD+^@K zM;FdZ8$y9>`hPELrr{A<&Dz{J9Kq`WN5SrP{Q}?rrHjz+2=NXg7zQ?M{_Txmuz$Xa zsrMBWneON{@GzG`2{VQTUqIa)tdYVC&()sJ+Ys;nVeBnn8w;~7-3l`^Gc$84%uE$# zt}rum9A;)_tS~b(GczaU3REWD_w~%Zt-6EX&&3{?FcPee1Whlaycl0sj#G zHRACROR0*S^~(}o??3MzaqEc)MZZ*jhX2p(=l|%Z`d7m0|D{gVS{>-XBz5a=MH)O z5S@;?#dF~lhbwBz@4gm%rs5uNvZFCP%W}M>9z_KDgUUcUW_bDnt34b}4t_2NFdg_7 z515Mbtfi3#zCZ~RebTTLf2$$G5mTzjHZzz!6?DPDOW9ZYBa>Z{3_rFC=3z`=E}Hzb z<7L}2ZA&>-l(iqAAU*+Hz?+`5{(1Gbxl5Xz=bTi$r9r`6By~hmk~B@V1FTsU<&0N) zL0crY=VaU~a)?KzHajR~RUv`eU*dsG7>0h44U8i~K$mP&i4&sE5aa7Gj?9)RT1=Md z^9Kzzg{`=!%oM1tm@hp zb0?9XQx1+2*#p~SmxKi6FK-^m1xU($u8l4a`Vpvo|3o+_ifwdTf0eV%{}8SId*9{# zPs5OZmGl3eME&=yq8xR-A72Q-ZLSPvy%a)uJihUPGG=8t^KKnWC`7z8VhmfDpv zS?s~3ak*@{=I4y>%0#~POuln1YM5>{7ft?y$Gi16e18H&`dWO(x=(YR&GUR;+S&d* z=I!c#YYXXg1Q_X$E_0Kn6Ae&fhTUWCXiRdn&?B0_Oj@_s79mUG-wtIw*T$xBOWftg zsuSE^wvjMz#P?L|1RiruZe@XHvvGRF?c=BBkg&yH57ftrB>lQq383> z%QrCwPt#FaWzbzt_oXfGDg2;$(-{u-VEM(c?orxnUfJ?gMZj<8(wTn!sbqkFp;Tyo zt#XEVsb+ps?|6&^L%>>W)Tw2~ftyRDi3eICmnSTMjBVxSJh2a-=q-ajE(@8fSkJC* z!@b}ZZIIl(*XyvZ`#w@sxvccGrq*@P@?Pn>sKJ`UBledk)Py)DEBl2p5@Rb5rsjp{xf4xRH(Yj;R{J|r*kywmPX5O@SosF97C9Xh^694vF5nZhFP>lIP{x(jt zSAoT=LBNo3T|f^_mf58;vWids&f#7BRnV20DC5cxhI9578o%}tVu$SB5M0{dHr`?Je)oA}+$RR!O@iqvbTU0&A8zwRrW|X_M3bH8n5Q>Rt@HxMKWJG2AP^(7{e9pw@%@hG@&_D(Swrah zqgsvJ2XnILjsy~Po<{F zGoncfT<{8iSO$eA%VAmKZEfbNDYkK0nK3UG7(Ns`iOBn1RWKv-o(_WA#%q=d;gQP{ z86?HN=sZz7c|tUT=@~Ng1`7vLam$-X?I8_KHnkhDyo0k`uP>(gi|0LCmqa4y7R5%Z znMZ=xq4grK%%Hj_`WrQ=@lAZtr{uul&HTol32#!eO;0Y~)@U!XA)PE7ac9moIr6i^ z8}-}Gd15&UAc_!1=NZ-U9+G>iM5`MW?U9^#A$W`~MDS311XF7UYrM3RjcM-dtbMXG5hpSkf!lP#GjR zeg5Gqmrjb#3KlxStbbzkMhjc8#9?6GDZiLI8C^XBz2CS;gp5>;WR0@ssxrsSm=j=% zJ`#{hIGs((s%z?g?(&~)44qfJKwM_m*he{1a~Ch04g_Xt;-qc=qSQ$AO5K^z#)skx z@q01#>}gY8Q(j9^y4f`RQ|a`uwG*{_*91!xYko41tngQR{8u6~aL(EyQzh=!+=gub z?nj2fCoLOi?BXa|Y^yBB7*o6pyS@wY3Tv%o(#|9!NBhfwj{j~wg@Ulqxn^l3p8I9Hno=|jDiCKo zikJ&Kv=};Iqea|$U`H1iSa@BIHT|0Upg&%ND=;X&YOFrKu|>pZBE0+paS~Pg%VZ*~ zxpJa;%PWW4Tn}=YB58eU8A%?eKHDHMChQ>#@v+%$n)07$bY^ zku@GP(uKlc{O6LshV_z~P^?s_D)Ul%-_b>G39gae!Y1PAN&;>BKBs_e&3Z@5JmN&V z-XCRL>@X|CZ^4jZ%+zgIBw$UaSzU3RfP#C$eWmW#HVy{d$0O7}W_gI3!WP-qP#0k4JRxB*fPW_3FQ`hAH z%koKjTc0D-l=~;qKS~|Y8uS+Zb=;W#AE)PkFZKV3;`|pN>R-gD|7s#NTHX%2>NuY{ zzT2kGS;f+6?Cdm3vfDNbcA4y(iOqqD&Ft~bDRah|)=k@6IVd=;Bcr$3opt71@+wzTxz0E3r`{huw?4b> zi)o*aSL^{TKv5E(Hd(~Hgh7jAhhO+N34`5E!0fQuPUV0iJ3*iR80{^pU%k}fOc?u< zZ3cs2wRoQ(&$BV8KH`HcToX0U1}V)3&WFPM#rth|vW|ISb)AlaJtSO2se@$V9_YKt z#c}QT+_~{pR2=-rBd|WQQN9~7j&fr~Np{(NY`D3ugV8hyvsNDZgU#Q-pJJtkm^Z_M z@7qwYsBd9MC4(a8;^%vhJLU~Z@nam^t$r}$pDTc)jimG|x%hKqx39pD7>Ci+)3>1A za*E7L`OooZi=VMW7Jh{Fb?T9ce%-ldBO3a(8~}kPLqqy6xet%Z@A=~oQKe%KG%7!;4}MC$c)nW@c@3Z zF+pudYlMU-)X{i@64XXdWpVQpLbv={t>R>0`~AwQ{h}k$NK4!aT->day=Sh7{9}(hxVTwjeElTg(b|nO@}sv zBl81le(CkKu;9Z`X+yYq&oX-bTmw+Kr6(^F5@IvUktISyg)jEcFKq7oTxZ1xz`u6V zP_wS7G-df&tNPKN!%G6Li^$#(9&vGS!F$)|K&uXkahmxp}+tISXq`NcYTwz&)wb zy7(&_Dq~`CCG$r_UHWyw3rzYm>xBBL-U5t76(RluCuUTOAc zV4AZzNx2`c6AwzPVZD(wsGa$@4P7cXM@nep~T9m>tS8FpB@=h4OlP zW>78Nr(FCvKfw}@<9Pe4^F_j=32zO7L``ImlU1e%gd(yk<0NpCBq+I?!t6GDeoJb^ z;DuLD$*+J=h9eY2%RQ2IQe$f3?g%D12?b7sy}q^wlT+m^)r+hnE?cazuUH6F^Ks>R zv*Krxhu;P9WP3Nr!5~WY`+i#Vds^Gb?0C`GJM=%yw1Ack*~J@kF>Os{Yv(w61`8dE z;M^n#{vyzp72KXzW;3-xm`uLR@N|ett};Q>c5OB+ibZG>ll*q+svFBmkTqXigd-2C zgH_x&v5qT1pyQ~5xb5U2ED46|S}mFsrpntBb33=@d>3FkGE&G7c4+R&K#|J3(I7tR zelLK)bm0NBTNaFIDc7UlYGTAcv#=v`?4N&V_O3J}fI0>C!mf2sRn*PvgZDgz`<_K_6=DvEK4&kT%Z&T7`fsm83UD&KbAPPG1yQ zXDc-${V7h$51D?lw_HTJkf>R?eE=wI8SD=K2Sk$dxuM3Ug)5J27snsm`h^T{bZezL zqd$6bF|7@3P97h;{;v;b>17NTXYpN_NGCyiPi{+N zes!dxCb(b^V5<{@=#rHRWUT4fnGlJH!=b1SC_d%t{?qm27kw%6n9v+etQ8q%GSk!J zzAKCzP4U8eDlI*L-s$n*^yb#)G<&+SS?LY6dykxg&jT<}r>MK=uwK@el*(;hs5ev? z!jdW|d*7lQk$*THH^m;(x>SDeOwNbfq|vB#Qwor;aXS#GKeVnT@Htf{?QAcUYCy<5 zxc_pFi3_qIZd>4uk{Vod<3G&bRQW;GpfoJkyg}m9Yjr5D6D>q(8K?{CGt!pPn?lnobaY>FvTAjeZ=*z6>P`$Qosuj zuRa=NQFC}GZz-}bKe8S^Rm3588yvicy!b1OejqA#BoXung?@NiGmuO(G;ZGY*PPX_ z1(H1CtzY}vGq;1+(EEt+`wByjT!OLQ4p=wCAK64h%Aps$9R(Ozd$=7_3YnEhQPd>~ zeo_ztN_3HRF_(Hv6HZ5D4i%4`<-LdKu(7B-wfaK+Fxl?9IM-*DIYQ#w!PJ=pDxfN! zD#o?4a!)kbyN75=nw)`OJD0l8u@na_?arvWc#fApti>Zc)<1~$dkLU@ zPKCS%$T%=3Wmbj#>(;D(P0g^4+Z!fV2dmZAJV>L@X*?F#hR`KMwdAdF0Qaxd zuvpp^dvAhbSr%_TOgJo0sfwAYiNTlS$DKR!p!DEhIYgCc--}$O-jtProxT!Z)$5n# zMUZfTy(eygugDXRmeKXOt4f!3v-Gj5@|?b5>zhrNA!#;)G{+~>33CK0B1fpd18+}1 z==*mg{_3#r-O5?nv)Oiwm;4>Ceqic&+_n04;b9#Da!QK)3{EU!ujcpzbZ?KKQu!Nq z369mb7m^9*_k$8O&n6qKc4^|UOZsnOEa$}*qsiN@sNd*}EJbVnWOp;HuJ7=A^Tr{^ zY9TAty=kj6%bh?D;&z}Lqri&OObiQm~IYQIt#S+cPuY zwD7C<%8PR}9O$WnG#qrr*j4&jQb)|;%~`oe((_CqnW&)XK8qPIU_(`d0*&>mpvL4$ z@uk)|0@d|iG`#!v9W}>YJoQ{_M&}I`2jUx7g}ryP6BLGM&ju!w4T2v-k@S^iy?+9? zTPSnzu-Mjhi{523tfs-F>n;FA$|asG&-kjDaJq_h+8aIch@siP&8<2GuGa!YJy*2O zvk}{_K&Fd4bw}rv&Yvt1rXf-wTx@C{Y|gFYiWtr2l2QwNK}JzxIJ*-YtWuIGRu)TT zl}Iw@skI#{)*`BgC|#mt8=}3t51h<4^>b~>I~FV;%FPkt1)ZHvQIFZM7)w(YEHZg> z8hz|HEWDEh7q!sHA>Gs*n(G_K<8qIddtzr%yRBE$re}hb+(B>cYV_T{W6Jk$s&?C; za!|2JB##ds(9)ykP^0OUqw+OQ_`7N+SYr-RmPm03_6=ALk|sBDbDE`nE`a)^4=*@{ z8BnO!)1&oBE`sV=I|ri{>Og7g(1Z+e9aFeX#{tcK*pV8X{e~np7o8&s6sMwrn5nP2 z#&7Qt_GVb|vNl;n_qIS&LSvTi2b=d5S- zKYSTeeF1LF;%~_TCD|YF@1Qf!@t-88CP+qa|2%xxCxqwYf9+WC{zo?bzoWqZf6w~< z>FN3R8~JHI1P`_4lv6qL6M1ue&`9!WXjp1%R+z|$_t1b4azkcvDG_Gj(6n(fPv(rs zN6J7;47wlXiD)miR4RJN-Voh7yUpCh(cGnu4dYvn+n|7;qzw2&lH*24=-*&qG zjFV?bJM^kMpZ2`X2>Abg-)1|+Bl5pi|CSysYPS~9YGXM{Pk4pOyJg6wkZCENz)X_@jALTB8rcpg|$_YVv3UMC#8p z(QRo0C;($rMiqE64O78Q4Y~ucNXaHVz3qu0r_A}YF+cWo32V)(A3Zn?1|U!wT?R#T zkHR1{$L%q_>tU(x>qDUWr&atM5$v@_L^-}QT1Z%XXiOem039K|*P1%5b~F(FXus#R z*;}_ZuM2#h8xuuC`nlyHQ0vO*ZHaUD{e5XlG&oVX^B&U1S(L6-woP~dkD?0( z1o`OIPzhlb99{2+E4aPwcGQI{0t4Ra3WwUSrC%$y)wLB`zgjy=5kP*TI9ZDb3lxHr z)yU*4il-BX8Z^{4l$P{VIGX%)9qa(=H4-X&*Qp2PfN;ox!{W74f5?a%h{35Xg@A%A z6U~eC4@0j{YyVJ+d_`?;M<{Uk5xP(X>|BQRFE0z%tTUhLIxczF-jTFzPy6sB36Uwwo++SV-RWiLA$TT zyVDIx2hG?Y;YK&E&C6QbQi+P(b^&S~hYOe+p%)3*TX}*MkE;i`&|kaI8>#;wllSvC z;I4Kf<>q|k48b8I!-{}eH8Tki(@I_TGZw~To#&|~m_@;%hVOFa$67N!O)7)CdKP9V zqybSuiZn!`6(}zC3Dy@X0JDn?InRdKDSAo5p_S80b0A|_g8DEjs8Yf7MLXUB#I$ADLka#HNL=ep@VzLOjqAS0>xc52Z@zcmWJbQi8J>QbO^MB13?6ffM~cLf;augKGt(eu!+8?1)88hSHIkCZ|3MJUIO*`GStK2qksYg}n!( z=J$cBNQ(e|eG-8i-iQna~p=<3P}+X%$rRxES7r^koMYissVzMtSroDT{V z<=~Jm@^y2fAPd1?S^(ow4UR%LZ7nCg_(pp1f`|=z!;ozr1douB$7sBQKV75%!hSL| zfgr^Ix|KuIhg}b^BQC^*8XEZ+s`I3BPFqazd2UHAdTnwHZ=uEUQmWBz+kA`}xI-qE zHE7g(`7r}*qe~#^@>;~Bc)rX65W)qTL-zneoSuVjeYl9Cj^*dN+2Jn1vb8e4j@nQa z>C;7FM~(pQ3;J_SQJa`ro2S}Ltw!tW@C9FEq%n$tlXv3EV@KGaid>mPIvs%1&J*>A z#=LfLDze}Au-+2tYgS}SQOJ6n0EMHjrX?LI8=WH=Tu4jm$q>m2R#S)AK)RozD6uti z0S;?i5u%-JCVIG-Vqj$XpOiLHta%>Qc6nK;j#NKx;MjICN(|yH9Z5OxT85~p7ux_w zi?KUB5x7a|#hV;aJyfPq6gV40-}Iy}Ti=%TA1Pa!G}D6>+T3erJ3zahic9*?Rl_ZS96g0C`!Ot)Wlf2jMF@rsgpaMk8n{*)eY2A?j20%QX>- zVJt*j?nFbGuz4{@hU=zSf~=N5$&$7fbC{A-@drO4PtV$ITh3UGyH{jBj-PNX`(jDM73(HU~naQmSn7ec23V$8&a}6Eo zF0vwX37^QQgy%Eth3|HVhX1IKS&*4ptsFEm3y}53d7q;Z#d4XfhiIM1e>5QiH@gbC zoh&~v$7vn3MRglri^&YpG2My+!SOcyE&{nq-CyXLM!NbF-~z{z7R^m#NKRf!Lavuq zTw`t?b+j31goD_psx}EAbG!4?8-eZ`;KfVa*SkupHyE+KD*$XZ{3zY>tqS=y4zvpD z-^96Fbm#=Q@0r86k9kn}NrZ9jLmk;3HjAF@Gs3vD)^?(t#MOn84Q}4W0y+(QLpsg6 zp!8Gk^$7)|e~){7_mTP?kdDzDqMmYat+^z@+^FT8ehTHWMs^qsj1S36x__*0>^AiP zGQ&>*A$-I}BpverZ~JkqPxVFwhVj83Qenv72}edveeip!_t97dBNe5A6ga(8S-nAu zlOEu46F~U9{vY>RFkc_#$v;BJ-W4!P;{q7#!ewZs1^l(^-a&=s_)Q%cpdKa-ECev^ zPon0=-;*OYvX>#(62^&?bIQKFG^p_vcFKC-8qK%;G@>n8oRg`MnB$$+_{rP-=&oZe ztytxfgI>aCugbSP({_zD%09n_1zimj`AUaqXvABF88sZ;R-=Hbx}=`;%PPUnSfq%I zW7Avq{DrT8ZYWvJ7gi=zhU$1R=wSaoTh&y!QvRJo-=Lmqslpah;M2q9c(@{~gY3nN zpm1K;i=g|{&ShtF*@3$K(avd-b*WT$_AK*hJRoXhc-)aof~~;iuTHsJQHpB%+(p#o z@-dPD#;(p;%*6||e;}10B?SjE4K%=Yny^GPH*0N_ZH|f;-XF?Tp=mv5>Y|KvFiQZY zPrgX;t~JMKz5OlefUF1+goV{!H#~ff<8KuAB3>|NOaL^;>HdzGf{;WDEAoXB=ucFp z5r~!O%n&>$ea+?S*b%1|S-9BK%jS^Dc9M)9QuLkD5I)JzQkUjBJ8`84%8|=leF__t zgz36f^}}3d<!T)BR`WydHBZ>0BM9aNThlmt z>y&d-2}ReiqG+OdArNt{IQ)t+1oz(A*7F)@-CP2wq>)=At5abfCfhut+?MlG&JhO1 za%1akJj{Q)!^XaKcjFtMl&tp0a7M-0ZgEa{pdDurmaI09PHhn3xM}&G7jZ^W47$P= zUQtkE?Js{~S($JBpm`YN zr)@5`bkS8wuFn`~E=QHQRQeU^?i)-xxMv-3fgtl?{bJ{^wb9qxo~v)@X(+Kf-mtzG z<;|_Lt+B&?rkiDnXHsZuUk-a6LUJZYytH0CF`{S!5z4Z|9p+X^IF}7wQ!e{d>1djxYF(jrw@&xwVT7Ez--$8El*(_4dQ+3qo^wTQD_DYk4zm8$m zGk*T}j*e(gDW4N(gK;mS((eL@1|ff6<=Xt#C|ADv#FHo1Z+ZGQzCF_VLBzJCle~hI zA0*L#Av90;AkOFnU^ordrN~^j0jwXZSol%_( z$nmwr;QFBKaJf)Z0Rya&9Kcc*TmFEM!Br53XP>IfRL1Q+$NxaxXR3<3v=O_yzy7RAtE3FfVeSanX)28BTl+f&6KfqV+k&_^2FVSYQ3wbr zmjMbPdRIZ8JHmvuu3DoISa{ZWiLT2Ht(uh4g`_R*J9V_|Vk5Sq^2ba2JNcR}Quy%w z{S`~*`tX$_kd%hSjrg(#Y(Ga)6Y8ND`Ibht3#}L(%QqD*Yu&<7TgS@Lngupn{~TR6 zc|+-C&_)H@xjWf|*ama;_@@@pa+e$% z!`xLoa`o(@4lDyS={tt}Q$m`0oZxI)uNCa=ArRRsn!Mh~j08bi=WeRdBMZQDZX;2Wwgf79?^t0C`uaQt_)4Jo9UyY zYyo1Y@Ij{uq>+ziG#jH2tV#}ec(RVz7l+O(tUqvw&P!Rv&kz_Aolen(Xg5L@q&F*T zb8h}53PCl%!D+2qaDbPYouJK0rBaj8AAbtP;b+S(SU7e~_!8#nJH4%IIUH?u zO0dgsIVQ9eWxHeVVZi^*jcaRLxC9V<_|VFK>ruSwkuLo!Dl_aaTKiz)6q+Z5_Kt2B z)LU}+fdljWJNa^_=;=wYB-#Kr^eM5ET^VSG<(%-SN1`i7su?Hsosm}4JmY6E>}C3I z6pLSQ%h$p7r~vsX{cwAj(M_n`QVu@Hc_e?~pNI$I!M930hGMgL(hZQyCSv{hEkB0F zd^N<3Vcj*+K`}#{Fhc{x_p8N)$za1gKPkFD7`qY%e%4C8WFoQNW!|D}^pct(F=0C; z&Hwezgc!`a1Kaq5hD@n2%rYPFOxaki6YFA#GQ1;I#7pSt+NM|#$mJ>tM6DYnUD!JA z3(l(8Seq>@u0?7^ybT?x|42p%e#C?hoW~MCrG3 zJR)a7ISKV(=c3F}6S zdBZJE?AGbnOc9_mH-h)>Ro3+^CWK2ot`nShqamWOqs}p-oC1T+mk|455i!0W{sD3D z+8%9K7=-wkz{Uc%DYV?r7#EM_3U6;qrSXBntOr39>0V`nuA+7JefP}aN(R@psf%$0Q1nkZYH~h*gY+e%><5e`lL6`63u|^+9^K z2R}BN!HmTeDDFX{wohL^Vr-lb&U;6@7U{eXk_{Di0LmQ@y~nIEu-FE!-&f)QSr@qK z$kP?+dWY79DR^Koe@II|aOptHX^g=+KY?r0*Rlp+c=um0!rKYpT5JQ`yw~3f@IE_7 zwi_yHgUOSG=#BJy=d>GXS_`$`$MnGh1O9~Hw`Z|&F0z{(jHm&BvoTwVW=0^l}f(Aoa?hl7k|e*U?X+NufvoNmyN|He@9_ zGP&>Me2qNKje2~bEFSZ22Pi9%Or{d zG9qw?#NH&DR72<|zZ?z5YxB6zbr)A0JP4!$GF)>^oNyUNRpgnl<7)4to1YzEkK0-r zGEKv`&uTm6wHygbFo!jNno4_5C2BMkfAl4$?qssw9A}D2xy4be-_nnRrkZ9_WJo09 zJiIqi%-%}nS`K}p48QMYp?n%ZzZmTAPPse@_B(IbXMz5tA=S6&P?23K(^eSdeW);XefN{+w8$O&9&O*8aOIAq^a67kn6%fD{XL`7Ns)|Kbugv2u+tQ3sYj{tPo zVyKyxp|%bAI3-PJjx@C>dTNbmWJs%5H*NkDW|P$2_}R2Tc>CVBfy2C*n<}K*T z_DOH#j--_y=AD#88U)`v(mP8Ewn`)RY!ddU1oEI|LXTRNM6LwXQ^w-02+>7 z$<>|XMN}!L7J!X>gpMp?p3PW%F=@fYI!XTYxjB7?bzLxgV720^6Q}LNqNvZ}oh^WC zuqOV);vd_5gn8xm^Dj^k-1q;k3;OqMzTAHj5B~c$pIqL^%I=>L!vA{bf5gGpsL9&@ zBT+ck;PA&Hc??OZ5E}E6TcScXrf3#B#8o;Z4|+*CH8#vP!2T-o3WtrYVS(Wy$UiWI zw!sKQWw99o;;S(XsYXD2LU6lZb*NW{~8V1)N&_Xypm}9Qvgu}(;(4D(uC9zzkFlw;oL(p>xnNRL8`nB15d||uK zp?K+2_d{;;aqBxP5kHi2g82GyHhT*W$nEh9U3WIshL-Fh|0@+(8@$R zU5L^+lt;6*_Crj~ONYx2>Lr69PR&M`r5;Lb#mmQF{3^TN05FQVW-|Bg=yITbRoO{Bp_+dZ#f_m+d_4*5Y*TC>oH=&fg)RWIoU-u-a zvU%P4l;;-toqOnII@c9SP1OTrKJhNMa1%B|BL`_ab2qotyZzpBR}V_3xGmXD0F~eR zjuX5VOG5Mx~ z?X_}gQudca%t{X!>vU+Om+#tc&Ka%5h!E0c? zA&Gm0eT9@f)A_EFt9*9}vOtn;_;jR`1YkeYnXSioV3Az=)FN_)oPBmu2~$k+IYm&y zBC8ln+u&i)1e6w5jE$C07Z-*$vE=SD+*L8(0+t2Ero*x6DOF&e*^>~3!myshKK9-u$>OUQub;2Y5UW? zX4|$iZllKb*Y6$E$K8kOZhmxA|j9E)(X404O9R z)_qB)Tg=z_a6cT3?^8nGjfP2yAnVuSC^TtJGLR}8bVp!`mJH*=We6$n`;lh{1hWCE z9xo6QKCrW;uXk$vG2vEn2QIleB!@0Ivrqk`+55qe+2efbe%TQI`5*_nrZ{_NR0IN-C5pzdfIPq@YD0|n;8Pk~-e=Cq+HQvTVdqZta37eQUX z>0^CJxC9Op^-u}+^FFKYO|Wa5$Vdt+=eP$6C^5BsWQaL^OjT(`#*=kv^G=F&AzLlZ zllHn#%SPSGOUaYR^@1sX?XZd$>wJLHTB$q5l3HE?iEi@mxx$m;dG)H7$_Bd{&eW@O zY09Y$LXPFHZ?ImmoN29SudC>?+-e5RNpC(iC9EUEp+a6o9rUB?autOn&yKUoJc`89 zoV2R4NHlWU#>#d5e=mMLW&B*=qI0 zDl(l@04_cLt(l>loW<27dyI+uuWKrg`m?&lrLzP) zR%xr6syVeMHzsr54u$@w!pIU(dwK59w!TYQhif8GYt*9Du_%LeNmE95R;gyQtuj4( ztE5CbgrBa`{5Z){==y4^5hJ9d5=JwfcsWOc#UB(~ihRggCpIf&fj-VHS$%XZv)ns* z-(m)%uh7B0dW2m z#sSAAW=_fut_%@Q`(gkn3Jvl}EY}pV)T;~YC%tn6Ic3)n!K!?smh_4pTMfGdVCH_b zrrRnH5X;RM+m~kRIE~h{XHr0i2FWjCc}zZ9fdQPOlouiUI2okdm4s3*3Wxj=|$sypXSp!GfTkfb?DNns(< zx;qS$Y$^G5;3stSPEpOWd=51yCF;0Z=Ho>5Sx%r4eDxUnpGSp&_j@P90=vs_(Oj{{!HL#Z;1P0yfDOg6*#cWdz)iP}tlVXbY@j-8 zD}W&Hkxmuc5GUv6TGmQ=I^Q9A;jMk)zR|Z9>+Pmy-c)8p!--b4NkrCeS*0a5E+xIl z&Bq$>r+K0(g(_2Tkte5L?CDm1M0`q{Ntbd0BS)e=UzJ0O(|M%LT|2pIX-6N$XuHx# zNv&G%yIo&fDzQ+V-Kf&TVmgMn*i`{OF{v8gpWbvAdW!ZDj@B|zf%ytsk`c7bmG&@M zInb4+o3Q#L(~?1o#YS-H?s)!U1I3q&p~$Z|v{ISGX@HW$R8f2~x;SGu+>P{ce|7#= zD*M>*2D<{36+Qv<>LtY?zMYP54Y3Pfw48-&-sHtPetMNC+M-LY7i5Iir&S&$us3!xW~17?-F4L1y< z3wxE?P>ASooz^5P=-ML^@Drm8ok_JGtaUL(v5T=SK(k9iHo;C?Wt)^&mpCzHjS{y_ zA#iigj`i<73}C%er~mm5el}NSPqa&Sgbuw6m5bT~qY~C`C>@XkYwZHbbw4-kei=Ru z>oy32;|ft1c3RF%<@mB3P9h?-l_<|`+r%{#FyLBmEamsztQzwu=i z1c@&Z?l;>31`~3r>KHAe{F@h|7dnovEr#Jx4_FFVrSkx* zvpLQnZlQD&oy(p-5knVG-D`yk6vHzA5?(o4dNR2XbSpOuWd*1>VcQ^ zPTS68-%nM3@aGYiP4sM?TmEjflZ`LJX05Uuxjcf z*FSm>gOjIrN3&J6w-Zk*{zebo-5b-g^y?}g2TyEzvFrD0L;<>L2phs zeS%4^xy^(t$dhh$xb)?R_ccMMi|65Sagd1VvmL}8j2rV`714?5!D>`5T}*{>{)mZX zOtpDoo-Iv%=)4}>FH0xTHX?dN$Sap8+pMT=4}~a1)o0}otJUVJk*Foqah5HldJUjV zcb8;`X4>i$Tlaf>ZQT! zrsZ{Q65lj#0lfr9M|+Hah!`47UQ9Y~?m?JfO#kUz7qZ(mHJVY+;?kQ`K{P4ZAdpSS z&}o?^U~=ss<067?QfT9(ik}XXQEqwTrr1mmWA8EFTbpqMHDgr=As3*Mu8(1d!L#BY z=hgSwB0*@rd?y&!qqx{N*4DI*zW~(OYFOwinW;}yFK-dJFVovyG=gexYOs|&$0w>Y zG8&KTR~nIdW>?b8s;ItprVb;y(zim7Un*}AfRC@gAo38TuE&4i)MQSuNT|y`@M*H8kf*#=&o-z2#gf59eu5s998>NXvx-aM#J@LGn466wzGq|GBxlEH#@wR7)S}U?S1ce(CB!p z*@yCgZL(B(MPMPW*4{ra!&=p2rl;{TwKvjgG#A%)mNrOFey(tGk}VPG7@82(#^{3Q>AlHHt zwY8HKw?lqIwJCJBMzp#)`K!cV@rpUy<{`7i%6p3Tl!kt3w&fDVVNG=IN%l+oDO=8> zBCYtI*Q*mt*9CO%eT>+!_?1{HL3Hl|8~nF0b%a{LDX~Y5q>=d`mLmbUzbSNbV<8AM ze#k)@cmdM_HyEsy4cW_vl^cv&pLRNE+Q7L3&XN$+RIqD3_R1h9uew!2*yTRt{b%1J z#H4B17W*bVV?LXdq9Qm{0lDZXm0?{Fs1gL@Ft6F62oTk0eMCuCafdFV3w9wI5j0M7 zsWAW!e-FWgqm5e^ zz!7>v!YO&`VC<(!ql-6O&GrTKi7sAT+&#P~&wx~qN^w9By^Y|h->?23w)CrWxpK3H z#T~Rqh+c@o;*w+61R;Ch)MCZjVw&6ah;@YqNQqAig*(o!gQSq%5;A0r-JqtojNPcV zC~DpDwrtUQVjaBJ@gseANz#{$=8-0Yktdi=vPk4sEiR&Au<)ERUrodRb!G9+-jD>R zogewe^5#-O?WxAtY)?%xhoC?jIW;}ALKrPy8392D?9xS&RFQXrq#2euz?faJ6(|IM z6MT5K)JUco{!)Rqz)D7ibB+LtkoHC}&QwcAtl>ANz3qeW3P6P%rJn9dT}AZqyxs$842F8#=r_4*J0wp$B;NrelY7|jQg{&4-y2Bi zi#vtzL(Odr)VYFI!y!34pot6kRc%SsRtA8lU(w5@H1VRGT%{!-D-Y==w@4jcbODw8 zqkaD^`(*%nrzdxG75Rk#&Tm5s2ErMRfiVBE_ z2MLSZ6-AFS2~Wb$uo{q8Y{8(1$T05g ze8Xh(AGCFnT@u<2A`2GH6VmJ`ZbYTYXhz>_xWShRX5NUW{MhK@){>hzrTYn%gPF^A z@Ln_!glyOF+>rXVq}K3gu>+b0c0kfkVJDxwJ)ln>FM|NP+HMatjzB(ch}b@Qpuo~# z-k649Fx>vE1Iv2~>L2C&M&&Kjk}+Z!$?q@=vzG^MFh($m=?xTZ!vKZ?p{bpGj*L5r zF<7o7%U$#hcTo-u82kQByVME35Ss3uSU1ZYjU5WUmSPMtT|mv&!+g{FH}jP{*GpDP z3`4S^3}O?E~s5bp@)9#7aD1jvTnx>{57%^TMHK8?<7XJ`8MxE<2tE^DS-u9DVhtSsX+h>-{-_q zo9+vAZSNU^wWoveS8X%>#^|z~qAiQHoEAEXxSG;=K^uh8|3J0h?4VU|tnbT=UyYc0 zLq7~+iHXcd7k`-L3?yjnFt&yq zSA!admr$9W8?4_D7k)0|-$kIqW zOHngt!G?2c%nyTO!N#Zlfrp9oaqtw(@b@cQYZ5CnjaEP@q?3teL`KA~rE^QPXT$c7RTC{dLw-g}RTlfE3qq(11FJ7aA+#o;6T`#xZKijZ4-{I z55jjZvljZJKe#Oc(1`Y8jCD0?hb=*{Gr-*yE^r4zxkuK8=@$g)1EBPY@^t`zYe45Z zWcQjGvTZ}H8;!n)Tyo?axtG`q<#XV=8IruC^ntbS|L~yeiTHI$*UT33RVQD95WL&| z+rw_4Nf(lT*zZH8dysdIoBrK{L5~pP?}MY{LsaD7Z&E4Z9xIV(x zBOeRLPg@a8GJJOw=Wae)8_{)AZ+GhF1o+8<{UqnA_^GjbB#0#GL2MOwFA+Xh;S~;* zW8H!i!^g%o5u_J34W))O$x4tP0hJ}aa~r?+?P;z+rb2p)a4YcjNbPqaFv$0ruOtXpQk8IIdBsG~R%&r|M5Oen`|1BsxmZ;j9e3*&K!D`rZ`-$3X2gN%UQ1G-Ul zN`t?V&<`ex&9l-}DrQb7h&k4}&}E}-^<|0)IGKi3;-+PVUWZOfG++BpDEdHH2_&pu z$bc+RwwaD|sY6#f8o<(ZMX}}m1i?`M;tVMCbFMo@_QwJ1b1R@l;bm~T3(`9rg=a5& z#)}}Org&w+x7pv+sOsEM_OhT~xo6dnpEA5-3UKylIeDtBjg1ScZpW*dAZhVUjMzc4 zRcH3ljCet@KQTKzYbv8PFug=_>Fb&QMYZo%j~jk+qP}nw$)|Z zwr$(CZQJOoSNooQU*0{rZ|5ZI?@Cry=KRK(8Y9AF8CU*Y|5?xYY9f%g zIXG`q^@?1I6_oq3*P_XHi$%XL&4~=02&r#!wpNot=TZl@Op`iSU$*H7rq6U^7{6dr zdNMFTK*fjK^++VC(H=XU_iKOe2(>5=~pX z8%A91-P`7AHSQCARABNvtItV+3uWNDkmOf2WgRR7tCNhQsEU%Ijq2`jUS3kL98I%E zJy4g?wknP$AIjIB8-}~um$b^$re))C&yMIu%}Hh=WfW2V>H6(PDT`tY5?+4*?MGDG zr(&oLi~D{H#(Pim8(>PGY>|0t^2ZjzFoTOXco&hW~-2~7W5 za^({SwrL~H0;9s{YxsQJH7a)s%lQE*&D_KpWvOy)DGh4+Br)*Gum5tO=13~k#`(Va zZ2j)#{{OGX|C2yevNkievA6oSc>FsM#mWk#xs!{$kBC~{wy-4lZ)-|rnt)Mk3 zYxW+yffsZ6MR+iKXy|!_iKr1L@b0oRe&CivKujqnv~6a6)8| zKidRD#fQ!ylmYrQAl&0i_*B*dd=SZTt@rjdRFuw5Yzb(aL9tibpW|D-JEENE_YA)@oYrIQpGA zcJbOCPD#p~03l60C#G;>4=NldslwSIC&|MJCe;SO4H?oFS_~as%wGMK>W3$uk317P z3bMt~JqPnx^QxnYQ%0OaJ3XAd2Q*+UoOgd(f%C}(_j8iJ#*Ii!CS=>+H}WO_7)W&g zG;aL+MN`(ZbTU#fvj6s#{5yJ7!N1QIkUnjU-Qq_jzyJl2dkc|+!Sw`z6k$UofA_}B zNb&+Uy@+b}?NFXlhNzzhIhATvuC*x&X;d~E!NDUXSIw+>*=U)&Tvly1R=#CFYZFJ0 z{`U3U=5U$vdd|AvuHQ;7*73Oz`%#}r5^~#8i5_m(9>Wo^L3R+&e+6&f9OU5#wo={% zYDaU0@T9<3myK-S9RnKRDLmqj&aDv{e8UEv4Wke03{pe*TlL2{fGS+i*bjAoFuml8 zO{xPuXb-`?E!?R7-!Xi6(F;3roWzFNLBswjQ6zpLJ7Ul>W-oq0G-C_N05A5ikuPB# zZ)KvZG#)SuI~Ff(Ij-s}HX&&?V{ta4)i&ed*Fd*gp3~hxPuZ4#x?*s^UUP$R$QB0n z#x>wGF_asJ)e#jnbDhnY<7rS+`_u`P7`f_V$Jy1Do0(nI#tp^EPAt~;#@9HM6OYOe z&orhqHn*1Mme6dhsU|&09o+8I1o5{vl+zx<@}8OmO&l~#%;t)Bq)a>{yVmi??#JWE z9Hd0b`L)iC4Z`6jQvyj}fgzMm@pp$1JzouV)?`z3i{9f~4Vz=bi0%V5?G0*UCX5k} znvEU2a>rWYFP^2&dr5y6u2l?K8^{ zWVcl4Ro`S8AfMpY2ZvD4Rx@R2My710UGt;TXrJ_ktO&xHzln%N^r!9MCO%V)i)s)^ z#%t5=W5CSD%jYpNeuGFSCDABouv^&Hp-j1onZH4R<|&l4&aLPfGBh?zDyoyKsN3@; zP03UD4yis)Zv-tC_i`0>t6Ml0sYru$R%7RbO64Bc&C;hP;$z+`49X^pfX1Ozca|g! z2qP=71U_uU&1wUmLgtFpDZ*ZGRZTt@L@KfFM>|9 zj$mlrAU(Pl^H&BVt{c>BHWR3FG1{T5EsSzft(}@736RqU18}#6d2%MwzegzgfmWE@-1j(CILfVow<@Cd^s(BgVT+TSBC_*czM#!Lt06(A5TxvXgkh3(SC?YpY zSH7DjCm?b&e43G~0Ju>CdY_IQFoVxcT!c5T#A$JP*~+G}-;S;VKTOs*0P ze6BIButa_)zc$vEtBE3Pq28=^9JDX8*w$HEF>9c*8Ner!F7If1P82NA8*YKOW^mN* zAcpN4j+Q7zi7PJ(Kj^qNqSdiuyJ(I0p6P5UZiYj%}_7k;VO)d3m6S| z==rmu(ZxEXdGPQITW7hCBK*pczI>x55neG`Q^f7!J9TzgCk3~9B)m)~jHMcPL$hU;Ra)|e@n!0Q$iR%sM52;kvx^^a8)~Ka-L}pyQ6&Cd2 zlX6nGX-&piAd=#uTVIgx#x+0e?AG67+cL;)$uK|~ z9+Jy3#pIO&1}p976}`V_G~hF>S!9JhSaw?xCEY|`?jM$!a@=`j7j8?dGtzNP5H`mQ z(Ehn66ztoQ=-j#jOsDRLDulxf7ZPUywGE!5lB?F_$yx`h1hbaCI-W6Yg_BL2P0U?< zmpW~Nmu>7dV38|U@UweTDVR7OgekooTncXyun&4~rC3~;4esZh1uepL zzvY(V(QQ=Sk7WicYhCw_>|LLH3QKHfD0{r@AN@ukfb4@TX6{SOW5A5no>MHYQ|wK* zqn9N%oXqsUOR?6=7XH|Da9%{fF8_3q8{0(fw*zR>aF1&Cv&F2FEGHj_6QDNb<=K+b zB5*p!++-U=ER8Sbtg5`DOk)o`Gm&mw^eFjEOy!Vx!=OaDJb2S8>9u|hh6dD&4#ewI z<1qp99~NK2gNl!Bp4%S(1Dsci?pric&@?--Ps$7_IOML4-qWyK4_X<2Y4U<;yUI-4 z*Q9}3fp1q%aBHrglo^h;J?tc<=L!UB`++MR)3R;AmGv_NHFg`&bv>U|j4v*Kpj*pz zyNaHGQ^0{I+{`s<_KOqwmYFBxXSjrj&cuYNbLtm9WKJJZ%YxWUNg_^!SLk}MxcJA? zL3maCoA}@{7iW5>8=OiwzmFjVL;Hp@jl(nrwdyB4Ww+9Ap<5$Y8(`e5Oe0?Haw6rL8C;FjMFmy%K;gVEVC8pM#3A@1-RTGfx zbMYKyb~J`95T+sMvWoArXn{F;?MPuAjT(BN!n7re$YaD-kU^uje7}R5jQEV50BKm~RTuoCg>#I4D@RGM3t8 zRE2pd@i6pGg1wy@kYcxlrjwW^6L&H2YkXiT%E-9g$NpG3p8GP z_vCF℞4zb{4beCwp&RmF|P)pnl_|QE(A`cTmfIQQR6whOKt4I+5wG8wlFptYXvk;j5+x|CC?U1_?`^lN3VC;ZKPf3;LN=)dBB&Sy z!zgUXLNksx2%X@__CRcvTN{S8<{lvCtf|B};&(~P&w>lY8h+`@wFwnT_>-E3{@t zN?G^O!Uk^tAYv56Kd)-jjSMU+1I^*nmvia`C;pc2yMw8N4mOwte2`U&Tyb7xNn>%J zJMq}&S*H1+p$HrXK$Oe*<`83E9f{A$^i<%VWVz)e$=7^b(77Jrsn=I#H}_Ja^_4rf z(+(ifmk!gpgD}nqep>lR4KZ%!3g@eJT=^2;vIWmu@@uNJh5<7_EZ}X40IFTvvnf9= z^yZDm^H0Vu!Uof%e}=K^h)a;$({P8;XRbyWO7~y?5=S#BLi=~|f&4#Yy#9S(iS|Dz zPySWl3hFuP{i`~OjMK20r$r6YiEc9cc5#b<9(t9O$HNa8kRq88WENG5GzX^M8Jmo0in=$j~Sg~b@St5llpA) z5S?|$k0R-qY{e$2{#jf<^0zMVk(m-$RZiZsQYXW88Zq)2@Z3y6=pwwDMvXe;(wpDn zknm_*m<3T?=s8gxQ+VmQHO9(NWW-j-@2j09w#rj9j8q>Cmxs0;>}OOVRot`dR-TV{HFHjPaW}Iw&~W8|hj7-^SkGrLeM= zB<3>GXHe#*UNZ1f%3#1IQ&0gjWh6_Lfxe&rExLa$kfy(xWk!&mOGm`&W^a4_0AW-p z27*xH8mYWCzJ%OfksVG3bL<)_6a14yb~$<30_St-nLuHYl=|By$G)BvJQF$m^YKLM z_rfj5cIVCe*M~J=&reMlJr-lY@@#=mpxB;Q*kBVt5pGAxvwckd7q~2hr`Dbw0W2L! z7_K$+mhUgJVBPDFgy2zt2=oWS+N*+nx8u5R)(&LAP-;o@4ww-6O$BC~+ge`>K_vR) zf+WzzA@Ggz4bNWD@)emY_flu^fX7n&-u9JiEzgBKgr`-Y(B#=xyj1yGzO4;J9>iNM z&xGFQcx(qK)1H0<=%_qL06exNG9fZXr3)G4$)~W0&%b$QB^B9G^h>he+g+n8dGu0J zurgXF+LL*SO;e(lMktZedX?p@LxL(0b*3~zls1?p7hlBXq6kOi$<0}nFI4kVU_2%0 z8KRX~C>lPyOpd8tqQ}SoKKH~_k|l9A8y~{};MmPlfQ4_uE61Om8Sq;GW@zq_+H%iA zy3>?>fjXwzOrq{@&_23`m_L0j1kSXON3)HAPq4+IVxQuynnK`U8F$ahn!seYV>6&! zCG4p1)iEFRwJT4FCmF(g$oN3Rr)qtjr)ZK(0xmMjy`SnbW}b{-jADPRw;+mTv!Rvi zbg^BTU})W@G=}E4iMekvqKZrhj=#bi-mxyK5GOOZ0V6Z}gTD8yvyl8q`|W5yqfn;o;qMZif`>r@t=LXg6gaDW7p2XTZDUc#4gY8h{@rNfoWh1s0oPu=&q48r^bB zYRk^_Q80fZ!D!E#swA$u!M+8`V>DGnJ-Em}?8BhDbzECS`Cv#qN38WW+pw6=L~&uR z&-hA{x~ABuL1XXI6plasS}QS(61xJ~*@pllx#ksP&Od6F<%uJ4XJx*jIH{cLj{4k2 z%8KH_9`xqkzTm-jI0n4>;F>CHA=pD2#CvFK{l!qmx*ns*6ZA!8dPY^!wXWUt`y;Jt zY;MPJH!XQ0l3s?9{MeO#Ziv<*wkeU%gl#5Ewf!mH7zo*?v(gVPk0+EkVr<2ufa+?f zih#f?u9Wz*)(!qoTr7d>*rdydkXCZUg?^k$x;f3KImSUK`G^ztK_~XX^iDArYvKp= zf)mg-zt5dPz|g?Vv5m0Svwrqc#GCRLJ37iT+$m%eh(@E+g(_#Nqq0=E1oMXX|F z^Ml)TYZp*`n|)qNW1YxO|DqLj`Z;QME8#UA&&#HIH*#zZ^bnFdIwlSmgZt{x^=#ea z)fM)%Yh3r`@wHI(C>7LuqL5*RAQjX0siTV82bI#rWx_l{E_S$H@F$&(1lpiN_yK4; z*|0@0D~Qni9=7N^7pQF)$YnExFV=yKzGZxm0P4d!G^+B`rzi^?%lJc?)y8Z+6z%Fb zqltKxqBpxcB>)O?a@S0!WaRGYKjr{F#!;oGJ#Xzn+Y z80pzfFFde{jn(;&Kg*oQU2Pbyq_jh`@6p_%r-x`(W}jEHble#)bGW5NIiq3sX;tzr z_@ayW<`!Bbi;6ozi3zjmhUkWnx_S+xt4;QQVXt8y zP)BdZ^QmKsz-Y$Y{qaq>0FrLs-7*>FcQClc02}gP-V!<|G3CH0PV)S?T#d;K+mzbi z)ygv=$nt`*>ciV*8>p|6s3Xa8{UL*40O*5T#S=FpWA=_fGnp+mW`dnNaj}cxa2vXq zu#l%JB|)_m(*6F+_z-p)+^BlUW3eR7G)yP+{841FBMR-v&3N*{RrhMYlq3aHijwCDsW)Q64@;qbr9y3Z`z)$3IR~>O z%pD1&c#7N!rRajcKgonRH1AL<(0${wEYq#mLf;PL0Ho_Q4{qkv4dM=UIpwKumx zOhbN-^`My0N?tTpbscgQem(J0kQf3)O|u25_owxSyDy-8EYYt{d^=u00(em*aujlD z%ol{+$rZDFQDFSn*G?PbZ{Zy0rPs4-8fyU5-ZF%j2MiwU9y0J^qKw#^3K%*`F;1)DY2B;7^lzH_V)7tK-(se&$fNfuXk$JuaGWi7-KG1ZQg2ir1cHeT5_d!&9)RS z3S47geuYE%M&l%Nild>T!pN^T?ftoEmni!f3qj=`I-WkwlO#$hVrwyGa*Jl*4U)?^ zt#m|NVi08@O@%{0BG}Y=iKRYcIuj-8lvZeEeTPF%78W$$HU-DUrOUFO+E)9+#ss&; ziE52f&sJ5#JjL0H%IG3;<5F4bBIU}+$lBW4{ry%1&BT$i%CaOS*co^WarUJ;dsAiT z#0vLHE;(ce=g4-~OZnb18YGdcS;k~5XomNtkC48GKDngkV4?`onEEEQd&}Z!l?!|a zkLLMt?p$4saUxc;-lgJ+)?$+gYC0ofAi|%eLK!x8?(d{)yba9qqFx4 zcXeCr2lm0m;>6|Lr;n&)LqPH}N30K&SQ_@&0|9vWtE3E>bdFak_Uy3*9asVcr>=sj+_ zu#E~v4)$(MvmrD0wH0H}r;=6(7GQ@r1$q}0*W8bOGoo8!z;eq=qPk>Pn&p^2Bkhpn z)dQ6qa>))~%q=18W!awL8e9KGn%XEEy?qYNUKv*`p8SYyTP4$y5|Mko_EV4OAj-n3 zSRGb6$)g?X?t2~njOY%WZd|FOy$l>$@glpgYC7Q~SG+x2Y+Q8J_#@fu?$nbxiixwtW{3QS#w7rTfzODp|NK^8Axrvkl1?j-N zmzhWj0nf80yXZ22+RP<=vofT6R6>%m$omHLB|pNXC|$fw1DZ~1yZ(4$)nqDl{PW}S z59n{U0|eBeeAcNwJ9q-sxH`(i&;%s1a`~l#3W?R2IV*KgS`6rQ`$&*ybI73n%Cb#bZL)ZjB-<7f4hks$^6!JVbExoAh3?EP zlMw4wrCwT1MylJqMN&wU=;U)mG^#Zu?d{_zGA|y~NAsfbny2Yf=jclD$y%!W%o33B zDAuK)Oji&#DkDSrrG90DO4#2X4+Y}n1&I*$t|Hv^SV1jBTkfj{GA-mJ6#IaOQPqic zK#AbM(yV)ELqxyi zR^c{(Wo8ZAW<3D7v6(&q!l&BkrlwZUaK{(xWjs*g7nljg@@1rTif*}*U?kh3$;zmN zjF}RvlV`UcGQ_9S%n+}In7#l?mE^M3-IM$trKSzFXt@F;>Hp1OCFtKnR5$MBtH5pB z1{qPZg=kwB=_~r9h0nR3<|YVW&hA8ESGT4QbJY`P$7(~4mtCFPHkMN1oxg`!AL_cj zgOBM>v-UwcX*w>TL1yJ-H4u;L_sY3~^w9QC_U%pkhWNt)H13BQ@!Z3iLogdsILi`D z@tkxdX;FI53%rzEpthu4trMthcd$v>K7O9QRNP(C0A3uQ#K#+!zkqfz_1U%VyUxx1 z#{~ILftHSqje*7BZ=n6QSNXmk<)YcYUD*f6PUk*j1h;y1+|(bovjewM5MOJM-UoVv zM-o``F6zd!%dSpwg)^Y9%>${IIrdwpx-PA1@*aox^hdWhc1{uCHvv zlQp2=Xi{DLu1yrMxHXWoY>Fb#J}G@WTr`1wigl7sCsD4y`ZUwMihaeuZsieWIn6V} zJm1XKVPL_#Zq?o$K4ZNOT&LxkL)D!I8?}>~Rr!*-KwG&v?g^Y(W&1>!o4dlOCs?ar zB9kv}9PX}@?uB)AuBw9}7EWNWT6sVle|w=^j2erFRwuHCRVuNGy?NmnCWqFPpFS5O z98yS@KX-v>K+jKTF0!5(#aL)2K}?5MPjp@PSt>Dvtb}Y<`u>8kTF}^-g7%)4L}|7v z%<&5QO{YSd<8QNSU?P-RY_1xtqKJ`O_%Ai`N<9*dub2*Q*gKz$%n#B__NY8Vn(eTz zcR(;V1c9}}ykSsWZm7Knls^2>KYv%RecDy$a#(c-SD?cqbjRC-)m`;gr{EUJRb`*h za0}7k1>?|)NfvkL4O-x`YT~bbZ ziA(*tKLd~cg8u6PSYppO%>PD6v44C3{!u9Y@0RnwP?672&-Qz3?e7*>{HQeo-}kN% zHVIu530{iVb}wOonCMC${K(#pu01XxKwsg0!w9Yi$dCaL3*i+fK*x`EUfpjOhfqM6 z-hAA$HL87Az5od)6_@2@A0?Hqm&aR%-#;aXXCv$B1Z}CqVp$`P5mfylErnMjYSBy> zdWk2E<0gfe(U=u1sfA)A_v(0Es@^{ih(rfwDbd5m-2SwniQ zXpJRasY+gcJ^?HqG-eA#{0SJ}Np&q&jM(N@FJcd$)rJ%G=B+Izqp}yoD_PA2hD5ZI zm4xyUotjXnKWpTeuoF0m$>w`~=f)`e!7{p)rbqFEfLB?FKVTu+{5cIc-C* zp6l{UpF^$P9)hDLUbr_Eoj*-lLy7;Io*(7(XW<42DBXj_T+o=Az#iIpUJ>r22b4q1 z-b>dCiC`5%^QBT|$u7DaU3|*Un94jnabQHePjm9KhE?wq>3;*L>ffu@4k0?%Z;I?+vDlx;IvZgpaiYJO0# z6!=2xB+~!}IKhFZJQf*Z)dK00g~P>hE-H|HoTwq5puee(&%(D%hGD z*&F>UF_n$}+9v(C9(19?rTjcEB3F7*D0HBHqiQ87fc_f5t^g{UoG@9SIUiL>|4Fv2 zGP)^(sQklESNN|N6%)f73(p@qy&^kU3+-m0SXjmEpCenHF3%Yr)1B$lI@>+~v|(b< z=x_KTIXaZdN>HXTv&FFvh0yGC==39HsETw2`YC+QQXc+#4JR$>L9GT!6dR-*jcEoR z!jlga`#~)`3lZ|VN3D}u^DZ0bP_fYELsrxFmLSTyvPD$ucQ*8rCxJdi64mll^-~}w zAxKo|G>aDJ8(MVB<%ppunRRMfOj;5zlQ|bEl+nA&q9kIf@29Y$BF za*ll=d4S(7Z&MRm^-|S?s$r}2YR-Dj>~_DMg0NUpDKE)ES40)MUfTQYN!=5~Lo}uN zEyk-#n_05S`|F@r3?)$%EvwRtXI8 z)p_{q;T)T0UU0QyD6kjbdXUcexrha9^O6iAuA!D5#E(Dk*6{j*WxWY! z{rW9{G9X6U(UYS`*V7N6#4@bpvH5(-5e>I^-%5}58@Oc3np zHRs}Y4PDzcSCUu9ZFKbCG%{?94rU7CWYJ?>nR7YOq{h|@y#lK+jdZY*S%d?BvXE|C zo%K>CCKCK{K;_M9qnEI$`E9n*3vjjfb5%qY;@fvRFIb!>7_o04cb{`KhE9NfKpGrm z2DUUWz*-a64sK&uh+lMIRq6#14>eLzasD0aFUT5C-WjX?=By9@V>a{eMV-`tkR$*5 zl=NTIn!l!k{{?3My}DSbY^Cr`XuYNDYGNv2b9BRLgd&;16AufK))7fz)$?mrJx`3a3v$ved4n z`1&n6^fdHE5Ex6brA`Y|wH^&q+L%gINwOmBn|UV^`Sc>JNCeW2<1#s*CO?W(&tut85LMuAg=in?=gpIT}^ z-n%4w&Z<>{kqqAe`&2xC+o?l8`|?~cHbMGgU`L?#`qX031&)g}C`=tDfkvuJ^YU5P zPp-)R+C&7~7{d6OvV6_Oz;-eGSweGDv??wG)BvP$I}>+sy$EKB)@WFcMhP z+%OGf?tzeBw4&qmJuSztsWHtv?172AnhGY3+GBJ-K zzxUs@tf)9k*O9bIuK;CCcl0%P-1n)>X{GNzx)tmQus^e=@qSUZacbCnBwj04eZ!19z z>EE&pB;vmOQTOt^vP4+is;ImIXWw)BNVx>_Y(Kf<3ko>4ag z-m5qg-JotJM=}Us{gmhVcwerPXyXk=MT*fEP8W^wZ(ln{I9T^@g=+ z0i$=h)4C372#po9SWmHgy-$>}Z-X|2Lb*#V(GvXg4c_FG!tm5Wa*m}%aJw$x8vl)8 z79nk&fU91l%{9Q$Z}5yO-!=AK@9E;urVwQ%Zuhe+mq_N;?BosRueal;a3V?XH@-%I z|5HQgA05{Irn};T68{3$e}mM-xaq(4Rh|GN8PW9?>GRel^ZWQ>c2z{Xu%-Kk{}6{Tr>_UAoucN zXR=>x=BZ1{9d2lt#qizT)B-8ab@$V2LJ+%kN5ui}oQ?)bNWCtJsma)Bn2L)!6#?&8 z7CGJj-Mz1;1C$$Pz)lg;db$iaX(Thq=kdIl&gf27Ftb7WC!y?*vb!O^V04=$T}vpf z$7$IPPEmTRfVhW;d5OSm#6@c2eZ^$+M?f-NWGX$mYK`&YpgP)l%ka&~-sCJQ6+LR2 zDQv_Os^6F06dz`{)pdp@RIx#9BvePxu%vejuMEj=Dv6NN;C*{MXvTW(tul7pzO)Cq4qbR*ApbK{p zkJw)E#z-66PhSs7KzDjyiby-6zD-fPa5JgL|LU1^JGPZ>eea$ae#g=O|IUK?Kfs^A zh7(M5^#8qmqNpK*A%e8GbtwirZs?q*xgpC4+Xx6P*S1=*}K)&PH;FP>Kwqizx>_WZN8l4L*0p> z8y8m@Xz#w!oWQocw@72_v7!6Ur^B`8{tb!6<}Muu5DzTC+GqqenUW%vY&F0zjn{Fl z`mHyDm(@;B0heBf!VRFa+_90m=r|FmVIV0kx3XhHT~0%( z8m$5FP`?)@rT?a!sQOijsDFhk`|#=&El`b`vyG6?noHiEzpvo;qmxy$_5-q)n&n4M z$O6n&7DoRMW1qV+s+u6o}w!OAC>Gp z=U=Du3pki_IPyM@qS?9mJB}cs0-CAvY1d?KaYuIRj8Ax3Wi!#C$UeRll!xR~af55U zsK&ms!r6`y$Z$%vByGZg?_gL?ZBzC2W2cTBZTp0)Zc0TDm~2Z9mN>ilSrQML+)EA( z`>$rp3L-C5)AjEmn2#M&(~SmPhfabwXz*4tw=reG9x`#$Iky%dK6Ew(;2Qe!?pQ^z9vF zY}-e?TaAwh0B=6H?%V*L+f4LP>Gstt(X1W6Hg?Ev0x@Ep!)jCl$oXfHh1hFYR|d`e)iYL*z~p#l!e7z`q`H1Z0F8vhM`+`A0up zj{hJD|5p5&>XXBr#>0SzUcasB>4Pz?~R1V-9YVJ=g+)hgHpuPVIwm^_44eT*z=gA{_isF(ye z+i_QM@vN(%;cI!9%~ktzm&f#7w!<{r^XVZErxO$}^k#fG?59SWjMv78cG}nMZ8x{; zO)Au1km(@Yi5J990x>hkJ&SBhiaA*Pv zLlC3MNy7KRqi4}PDo&BCFN}&@t}WS|S%vhzXUbIEjB8qq0D_mIBoTY!nc`8t7~^WN zc-o!-u+-wIBu?20B@Xf|V`kCu+^S=g^zj>Q`k0YWpmZYl1VML23f|-dXIY-woZ>lS zy2zc6N^}`Fw2gg8I!C;j9drzZxm=)}rzkLsEmA_RKm?~rERqVkUcw;_~R48xk8W@If|kb>^^NjwCYS(hPGk0;@4n%d#ag}3vHvFbz@^i+oYOT?C2Ya z!YvTP=xM~jnnG^^sWtd)dYE8&I>9Jn_oP*{1=HWHBl|2&6;{u&W{06eOH^%+OS- z&dp3?eWe-(^RU)EJZ8z5$$kTmxy&_GJ$}fp1z3r85ByLt1XKN0gji`|Mr;G%4WysD z?A7?R{2IU3(?FhS16v7{>_SQ!iwkyT9XIyuF2a${(+o>eFY@-O zZt-u=c+cl5@#=@0x{0;R16PeOM2-baiU$dL$MLcjPU(NiA|damq?T!KE>#>jJQC*x zeB{!Axtki$#xlN+B&=1ds(Vzm&AQ*!>5Ie%Z9!v91fW?ny#5Bi|7rYTtww0Bu4@@G z!Z(WZCX6Wai|^Y2DZLJ#x|`8ep`jOCe!OcVKqo2^Y+p^8lby9uQbk} z$)tY3+<42VNPVJG`9xXIH(!ujrm0w@3X+0chR7Kjs8V;~mjOIPsS)Dqj zODA~!Wy$Xqhi$FVz<6MUP{DEsXEQmYEYKKPHKB?hf8<{0rI^lnH2rf2u$5V zD!N7DKK!P&lgr$CF4T!c^29>wTIh~LLQroYY%laXSB}g4W5^(WV|q8|$&1yzeNu!D z2+Fmk)wu;I_)G#pzQ`%6-87^h}`UzGq1-gv+9&NSjUcQ@)9dE)c+(?9dQ$DXFn$ zJHn0_-%`Q>wf@#cRU&&984)7MVGJ~?eOCT_T6yo=J3T*|bAjPi(gFz3s>5g6q2EBf=6k-ioq9lDWQ(~#wBd|xc66XR$R^L{ zI)b0UC4`gEL9VV-$@+R^P^rG#$bi+mMtvV}C9`Yk=9@ht-4uUjE)xY@(o;^I0eKMe zc#@BFgyx#n+~1N?4u7S3L|!F0x!4^t(4T7Tg?gfA^j2t15eTd2(7B(ti)g?x93~-?1Lanp_nVGguy=}Z**-yTWdqa z=9H#FR8=ScBZ{dynOR`DVH(72$Bm$16k;O8O{9Hm%c9!)GKfIcYuz+n5r)9i ztCV$dWl^A$+Nv7zoI*#DU>}3kl9Xwio~aP~ICv8w=v(Wbe(~No(G=O%fN?ZeMQvdJ zD$CLsF5)a+F{Z#BEL26;KTfz30yj)YdXAx?p}YvHzP8-lP-Ro5qa;&;p?yGuH@c!_ z4f zp^0{^e2JxbiG?bWCUvQJ5pR(9y~%LQ@OlDT{0~yta}EC|r3rDk{Le=t`Y@{ zN{PC&kn;u{STT<#-t-JkdxjrOa32`vz9x4(!wKC>S~LnUY!{JruB(Ad$#wS^X-}6M z`Baf|<-@e524ov@!4!d~pTkZm9Z>3B8`ASvrDpeS9n++{p>|RFagV=eNgym7&)l>5 zy{$~S+@7^Bel))xAHI56R$Mo_8HHsfkDgttKBxr4X`#v@gQRT`TUkb}j#WI=Qw!r@ zB>wXK*pKl61O6c845;XzoO{sHeE}=}hXE#cVmn&w z0wx}Y4K@ z%t;!?vVQlpM|IVjjphN+EhxbS3L97CCH1_f+r%$ThfGVn)}M7 zUOZah6H6nAEX5d-Gg1iHd$7LS*ySx`+pEvUC%p6p_3#DDcu#>SBRf^J^ZY0^II+ja7+iAFbIsAa-em|bL&5P1E}{BFL`Z~(oWmG1 zC_DP61XuiF<=KtOqn>hR`v4UL77&)O)0NgcZ7xndM;347JKDsl?WE~-|Hl5R=nEEl zgzsGY8ST`1G`Q2%AJU3@RRWpJ<^hKfyClZZ9qoQm$=xi$WGqZ6=UdlyEGx=_wUrcH znvH^f5w;Y5w-Q3Y`V*)HIc{ZHJU_(%)JUN?VqM6@9rU!2^Af~$GfwB54Jyv&@MGtD z2be@M!)XHno#u30HGMlF1dp6SI9Ru zmMAQR9Q*LHzxX-A)NAAQ9?x5d*?rxN@2Q4`uHd zTv@xVe|Ma8Y$qMtw(YFgw(X8>+jcs(ZFFp>V>|ihIeQ)AxE) zw+oEuHKa2YAV@W{XVZGinO8|uao5Ua+eQjmlL=>>V2)MA6R)=Jns|77OvWFoGu1Vu;d1zzS`Q6fg1DJ!w6eSC zlQ>42#35=KAT_M$yyx7JONT`yyJ4)zbUA)UN`w#glAl2J3BqsOIwJ<5*O zPP=z!mWNBlYpvu>Pj#xTivV`hLRb6vS1FIZMTGIJ?)2H9#HuOygM+kBWRE-XGIOlM z5XPxLP*{*fR>33ZS@V@5awXfx%BWK_hyVdJ01C=0!=a5q)FC(8cO7N2<3=EkvM3g+ zSZedpXWvj$2@gJQLvUha0hNWeB&9~3G|RGaicxp8s>i&R4&o#75c(?}+qzf&y7pyk z&K|MXxi+mL{wmuWURtlT7oYv)ec3~P4a>y++I(x;#C;U(@_FU6h^52v!`(NTJb^6b zvxRE0>Ias6^ELHLY(Sw{wN7#LMSls04(G`Tk8(RE=hVVr4lJi_xa^(58%$dT z${a_u4SpaF_!&zijgMxLNy$z`x0G$Nog+}<0)ySS*P^nwoX-=%v+CF)^$PT0KE21a z3jI|55YH$H|JBtPW{|}HP{1@MXpW&OsN9q6b6A(HRH^l>jXU*b2%2)9F);SU!TY_P zlc?}e`@AVH+8QDA(#AN(D?P;LSkogxbpG}VbwqjEGi6`hN?BGj$^BAe(z*NL)bf7H z_}HE0{5hTZ{`OyyYZ*(Nt6E?69d? zYA2tJ2B(oazf5VLpH`h-&@$2Q?5_V?dWWNaB7LN^RV(SLzQ#IEa)Pn#M0*eGp_K$EF+YiWY=PRcbw<$Hxwo$yTkJy$!VeT9$zpd{ten9@! zGyKN>6gd91jRr5>|JAtvJMr58WZnN;2k5I$Wvir&^D%YDYZ9C{FIZxpridqq4>;qe zs1m}TfheLW0t+W!fM}kV@=P11alKHo+XFA4T0rfRpOayuoF!*Y|3O+Uz20V*NBn`9 zUb=9(j#=CoO3HfDdh~|3_1v}foHg(BxINzfwS_gRFbeW2Rd??zlpeG!C`YE!frGK} zfom&g5iac$fog)r*7V&vh*Kuqu6ZU@KF+im$RjkvYThe+K+d50xemoWPVxR#X7rJB zNA8}8-=qW)hv`)0n(UA`d^&XUPCBrGJpXCaujDl<`NahNQ^D!oM4sS{!47X z<-XZ6#Fc2Lr0IY{Gb`#1$Bg`PicT9ZIk_HBW#HmE1&iwex8+(ZZm2ZnQZ1xUY>EP2 zh~<~p06*_gl}vZTA~5H)*mvX@AJ1e!7dO|>!C6gZFh9yF`LBN{D6J+xcWDnQ(6N=%XzIB+(bfw|K#&6z`SgMP+c^QM^GHqS-ci+zg3_l~l zNRQLRbD9X!+Y1a^K|0n7wm>d6-u`3_OY_b{AGIy5;6LbkPT?$x@gIfN<+R5)M9yM1g1eh5g~G^J30*`J;kUOmc7C=t7hROgS$Ur_ z7uejeS5qoI%+HNIR{UBONAFPOEflAmJRGV0rOp~9Q=UTJOVEgOVk)lZr>J{V*p$Ez zcH*iS*;h&GVW3lAnUvHcP;<>WD^e5V$crk12$4pXk(>V==w>VS`?Lx{V%vj4SjOSA zuI@ZNYEkfs2@$H@VHnY)b?7Gl6IEhP6fKb#1gfso%&}#eC6Dv0$g#83O#aveA<8nhV+Dy)^nifW^hdrN74jQ0~AB_+Vtt3!6s^t069TYyMrHKA+~ zXj$K3vn{`Ba&BT3-Egy|FQpW}7`+nc>M5d81E|Msg7XSr<>=z~l{0$Y4ZJbPZm>k% zlce|TFmE_x%s5wx$oie#L7NU`UM*fM*-{pZrx(xVPD&p)XU?w`kcEvb3G$!0u^1MM z=X+Oq<)A-U&X_D^Sif~dtp%f4mP#qYMy9KfR&;bQx8Zg2_&7X!qO}B~5S9tON|BA1 zNl};~QC|atZSrpEXhYRVzyc`4pL^DT z<_;s5`X7{6z%=m)3U`Xf5g1BOyww5KEnIcgh~8z8;iVzG{P>id^%gwhp$rpg9L-yq zOiVetm-yetmZJ$GrBMhf2jT|HgIQotu~;$kad#k7Jm-wbmx|UHo@m(G`{;|TrA+mf z*H7`VXkAz5SgYTPSS2|0Lo+p^53(4PZX8X~(_!))SI}U>+73d8W^AAygPUKBB$kRs zUu7;dB=NC@be6E_ai+P;he87U2D485nW9@BvE~}xw>%Kep*ikGd%br230!DGswv8o z84o^uaqgaQmk3ROxqn$N}P~fl#saj4v zMGfot3N#U2E?vQ8E?+Sd4W~=-dpBMAyy@dqEYvVQC(QIY zZ~L@qj<=81$NS~)t#2l^n*4}TtW!J5QEM%Rd!${91;#XEXew5f29v=-;fs})*HLK7 zG^`CzDiP^H?P#ntRt#zoeL0W;r2WsU0Q(=Avir|dAc$vWi-i5#@#t=|*1>UeqX(n7 z!Rz6x2{8REbg>y(Dnh|)`8!fkfa)t(;o}qc{0Wg)oeUtD4lGbct!t5X8VSex;=W>{ zY$#V<&T5NBr5P6u!qpr{K}R)*!!}|n#IjmKt@sdRrv1X-$qL$IJi967LuE~Ab(H=5 z=1ZlF?aG}UdBau#c?cs%3eWU&A@kY47U7w9-A$UM=N-`PQ)IFHx9d$=9r4E}9F*3rTqVI8 zysiiJBLKhpvV0E|51W1b%>n@7C4Y6NPQw-MFcJ4+3HR*8G<$XL&J!>bPJQZLOEfml zZA)+MRg=3hdAk3t$c$4HmRymPpVMaS5dEji5ump{4<(KpNK48xkgaM{1n`Zk=5o2; zfPJrgn?HEADO_qoi5_*Obfo0NIE6g96ET=nJWba?y#5zw z&@HJ5V{fh6KCB_1!oIl?8Dg8T{(8DNV%)s=jr042&N1m z9eIQ|NgN1$;t|M@b{P@t?`X_+2T|5jMhx>HRF8MR2fi+Bm)5tnup5E1c?bIWtRwB% zWcgF+&uy2AA+J}afw)I;^=(gkU+Z3k{p`a2`Db|GLm#Q8?mCD54ZU)Bk1p<~UmqVS zzF2LHpQ#K6<%oXP_kz{EUA3h_21(USq(2YU5otQ;AwDOL_DsJ;Jjmy2MqX>w-;=lVpXQBVkeW@J&0oIixLGJRihGfM^USL32RN3x;eQvavxpr+-f_$lJF`}PmCt3jJwt*oQ6g5 zY|J_|Ka#&ks;5etSP_{wV_w_LZ!kGO#gg4RrVbsvVX^cy`bjfk+UNMTyMOGiasn;= z5seR|$tAIp`e9q0)NlqK{yU`^>KGc3Rot^oN@Y%aDeIJaqEbL48`VvLYKR05$jemz zVDEGK%-~rUZ5eM8bI!iMc!TuN zcj1&?93`oCfx$(c5q3BoHCVq!VbwOmO;a6k7PhPzJR4eLfs)T{t3(HEO_s$-Eer zYfu>|&2m6eL<2>-QbyL&OA?nY-jaw0`-G1`9>-9BqHx24WWt0BFQv+GDU2lNw?wD0 zt(JjN8xCk>h0V*nP=jF>X8qB~OPitnyx#KoREAZv^&nA1WaNglLf^!39ITCzryW$D z4wN6|eqQ7p=uOHEP78h9jd5yXLIs7cPcTmYL>r}#q>Ir32bvummxzYg2`3&)Zyom? zrEuwTUc$-t|00Btgq##UMc9eMW+2&KV=%9tLrk*`gyFTFZ}$L-KLH{z9{5 zZt%Kq_F_CF*0pJEO?=)dBhQMenPh6NQgd`to+}Z^L0&!WY|?m)>L$nevI73jI}(GeOx7qWf% zS4d0iMr1d1L>jNJk=1YQtcljpESoBK=)rLAdWSdyrFgT_x3M%+~l{g!4SY#){e`=@(8{^5j=XcnARnWT(k8{><(e%!rBJ_ zyK%~pKlIK^%OK$~P(g+wfmzxM`O%C`8@5PZSP+fQI<3;EONa-nmDtOdR2N__gETFV zm&Cxukd!#f?mu(NlGM2TK@N56IpriNld2?7@$qpt+I6zM!{BiP$cN^If7fHg94+@B zAr3@vZ@n&Oy>o}sAv)64_t$Le{hB?1H&merp`sM`|D@+D0oF062cFQVCo&z$%2W4RU89+%iz3?G=XZCYtrGeMir5Yr&4|(K6_n6d#wDo9cH1%<@G|?MaVKaYeWPx(&_XvlE@-a4{5{J~u)WRa)8_Y|=9dp1Vka{O_FL(8@>_F{NMrsU zwk>q4H4(jW1$VhPt%{$Ev*LpsxXN}-2^uy~S>*!jTpj}Ajy8xXZTKo>(1cp}FfZXv zUov!lkM2@=eHriP%+A}~eg);_`i)j~F54dAoSfRSTv-2fXy^&}o^b zpRL}mrqd4B=5C35uTP9v*;)jC=p4TNcfK9mH-C5rf4OIkOf=x`?j}j!U z6)Wy+ow5Tg-(i6)a2A{nDm5J!A2J&;hHJ(1Oz^iPhR0kE?NkQVWH(Lm87+s?V@O(6 zYc)1{eC7P4h-%+ZXHyiKba_mFfxG_+vm~=ta#nxg`b(bj9`K^@e3yLpe+-9SFwPbt!((3fq2$kU7t3(374Qwc7c{I-)f&5MyXvmF z9vd@AaEC4?J{~_m9WOrLJ{+e9Ri|~o(L;pvrAEsrrv^{PTg4e!VyxL^5PwPjO@h&f zZ_S2*-Slm_zKm4q5i%q^f$%XD`xx9CbaDYv!p*%pq1#RjiHmX8(IIP`4H(%yd}9mv_jya zl}eK|RWEP$YC{G21%WD+5y+uZt~IwK!8sbsSpGq~88h}PSH`to`F;Tn7;y#^v=pMKAZ3@jhCi{X#W3IJ}7cH+y zuG!tOs%;) z7EFo5`*TCxT;i#Q#KL6zUHcs*nxO=!ZEq%|O{@{nA*jB{OiVjr3$`bbnxAoe0~iBB zFYj5*_BS}uTG=i(^m?KeWd}A1n>b=NNk-lHLM=7&R`>YIB!d!Sipt1sJZeO<7rrrS z`bUfQlsXFvD%)f4ipa{ir7D~}MKWY-21gnS?CnF|lKJ$ispFL_nle9sl3CS+i|M1N z%Erwzrp45>NMT?BVQF&{`1@j(nQC+oT>e2Uu5h&YjrPcfMztoJMN9A%+qAUgB#&MV zAqB$C3CT+0vuIVs#TS0gW>fwjyul{}7?jumKc}IYTQ`tlcTNafaAxVeJJB24-8*GH z(gXF>^YN&}8k)Gh#0<&(Q*vEhLNq;mG8N0+9?|d*iA>eJ8Jj*@Rh4)S~r(k z#d%XV)Vf$kHQy*rvnLTx^K&*;rnc(!x)XSw!!*}8_v2jsb9(mCa<-~o(P?W`V{$v8 z{e9gPS`jbDn9#D$xB-p>2^vw?ASBI{3yp`eR!FS&;OMn)1G{#H{gs+S1ZO9la!7QP z@n#=!Hmk^Og7~avU{H}vxECcXU|N5jLl~qtQT`t!4rz>#x?6TA!|d?{yP}F(m)buYLdI5 z-lbf6P|mG+Ef1qEecJ+zre@H>;k)amKU_0pr_B;pny(A+68%`Z8?0z>-e}^kX6a`6 zgS^$E$-*O!+rab>3s3GTB;KCtu8bQ`Daoy4vAIwd7gMVJlM4^;9Iljedt(fR7cTBd zjgt!5_|(-#XNY|6qTNq3j!`v<=3YxiixvbSud z0__&^@)Gsl1!38#q=y7Yn0cP}APus1;4*pCDuslQ^C-ah2hXs8d*bkzJ6wN?l;GNa zNYfN_72)s>q3@u5Sc63Tf&>yEd11cELqGJk*VNld@+Nd!t9v478=+i%$V2n`J1VzL zh@IdCz$PJ1Wr2+eIlP>zT)UcZn-Vzt3vaFD5uRHC=@A}V0qOpI(o^hKcdnzE`G^G^ zy@oF$n26BHftW`$aO@Z|>E?eNRD?>^k@A>aeRGD#FvV!tFF!V=Ur=|CD!A{ugRk8( zb!%$sdt+`3-TjXa+1vu${I}|Cf9;^JEZgQ`Z;1kJ?MS?6ci_t*{@x5@B#A9+XM z+ubz1V%8amxmJA>E`2Hs-7z&l%SMF0a-5Ae9b|nIG`h|l*-P2A;iiGxb+@O}K^VTu zcSHBF4zR#0DDM@1Wj>sYsN+~S$Yz6ktei&F<9*`vz8cJIMR-KVE-0T|ZRrdkNm5Nx zs8ak23T*f2N$8s8HpE#Nx0VKJ-R8|cXxa8UDBzJ7Y2VYdeFz@pqq*R=@I1=2!8MLi z?dP5fVp`ALmV(tNJ(-sptMJr}q5e`iXoE^jQw~p}610V|MeMP4FaCo4>~7uezA$1x zLEu^b+y^_CYeD{bIQ&ZYhN9Ca22}`f3;OYnE%4yVJ-s$W@|H03l2SU@Jt+MqMm=CG zc-n2iq=VYdK=^R$aU)9*ew5I%6(T;?ZNf8(EaRgG{cy$ZPP`H3Y#`gV_veoBWU73= zw2-S*7CrtVk&{H$1Nn~%-APo5X1dXes!AXNqH-!>pBc&?y{_;KY56QgwLmjQOvjAm z1qj$Dul#n@YU_!0?YZ?E{$KJ%anmGC5Axf$IfVZyU;Y)d#rQY6YyWA8{gr6>hki*? z(zZo0M)4`;nqSdITdCf#FwX<HEG1r1rZuc*mDK|ZkqUq; zt|V=ukYIhlPGF&Q848<8H=nWJKy=(_crUr;^GI2SWDdP1(;m5xIF2@SKVRH2`QgXR z_wDJUNMQ=iaFKRp2;iU@$OjM!Bn4r@_6xB129Q7IFoqZiq9dNfv21q&?c~N_#6BmG zt`%?%Ib}~URAZ~uyR13)l6C8O9+ggFfsMs`Ux22oz>2XWGp0I<-k79m0pb+$&@-_R(J%(E93;;b=DdK-oM{XA^qf1Q^LKXO!kNEZ?eSA zsgc$ENaZ-EkH>x(12sfKdM7UhXL6Adc&t6jp-Xo(aUY^g?zBjPj8JAuJ)wFj*1Rqs z1etH_VH@uaJYe^PyaYys)N)2rPEw0U5)92VQAY)%z)VXdFixI^@On#{AV6HSRH3I# z_$`}O;w<_Mhp!oEoc%{5#h*Sbvrw$lz1s@6Ndy|UBF}j`9eompbB1g{7~GnkaXD}j zvjN&N0zorqnRLK~z(v0~x|xYRiV0JCw=(o>{#q9N(tt9+aocY`RlfH2Gqy1IvU?7G zRlu70il&~^tTovd9Bbe?kLz2y+V z&~AZSkNcJI7+tTg)Ye~zLyJyrOtYi9$?BJr!$`|+9P7msFdOa`%!0Qnaa*ng8$Q0- zFFy|_NZQ9yEWXTuHnz195YUe*`0B^?QKaCG-~D#cNhKwBgOjitxHT*8j7uqlqmdt6 zFk=fxl-$5Op^4kXIA);p6oYs8YsQVCZG zM0T|NwV!UcytT!GwmLnc;xNCw?@v+D=!>_$_h3=VZhKLm(1LN)$4hdhy=;{cY>6)2 z{{8UDt2heMW1eU<+R2M}4KWE(mgF7T?P!M&^j?tX%+1`6pS!nBpx+C5ZWX8#q8Sgm z`>wIWe0WOyXt`4jNfLg}IxVv$e5}vdggv(u#~>ahPJzfJ4{e`&^gVF9ii(~ zl^v)fd)T7_=@F1ci=aEm?Nj>oWt}fq3-t<*6mRq{jA?tCX?$AhQPKZ6NN%iRkBGba zsUm+PFQFfo6iHp^Mwxs*N07x$0lIEL7cjLGQRXmJp^O2v^~ zM9aQqNr%7gIKTS`_YqYd-A?2`f5X0TAz|MV&bL%AJrEn=6%^WE@2jpp@UDvM1RO6` zA4op#3YfDJE^TIScs-YIw3!8?XjkmnyrJ2gfH3odZAhv0q*y&u>11bgeA|ls&@9~1 zJUg%h=Xj!6MYAzPnX12uUeF{LXf7jUP~5&!`eY-@dPSH8)`#4 zqTVD@U_4%f*g# zK3yL|0UEb_bo1P^L% z_QnMRU9Xjy=6PIqoZ{KC{rU2`cKPj0l*9KNBbFY+7XoDWn*}};#5;SS(KjIsxNZ7q z&>sfE9q(f2nfQ43dti|cvAcTGI9Il>mYgd^p!CtqWHO-Fl%&rtl4qZ-q@%9$I5>NH z!2wI`Zra@RcZ*`(XD_v?XP@=OVrQQ$^%Ylp@Rt(ov^%g+WEgM3ItxU(8;_ zrNhScOuXrpAb)M@Vd!+GW-^_*@Ol>l-V@r8%dk6!r-rw;%%Prm7(o?RNL1Rkh?Xtt z^eLd=i(|m445=Yg;c+Za1ydlvL;=4B<(G%K#`s~_F9zeIhPOx+#%G@-a&||PH2tmg z6d4Y!Z3R_eA#{hA4#W6wLWQNec0=ci0^=Fz_bY|k_H@^xhWq60Ju};!ybPv{pp(0O zdfsH$Nc^odoYZQoCryX z0h9&E<)A`CIMSG0PluH-&>M_5nTp%FBYu;;+*70Eetor%KM%t4;)Y4H$s+bn&eVC1 z=!q8;S!sNP#c%RJ-HUu@n@sa(RpL1 z8gKWsPgY~^Tg1!&dYFf@HqhxCUa#gAj;`OM3v+`TZm$_=-|thiPO$4I8Sz<4tPbTT z?>kL_?IuED1g$p|AQ4DpP0c9l078VE5Vt^O-bP1E0+zPO+H%NoGpFA^!7d_@G&=nz zNvG!F8p4egW=+Y6>Vg4S`S(;yyV{_hh=j{xco$+IIs!!CwWtBhQgo=D%IrY}BL*no ziVNe0EyA|r!>K)lq$jN)&$M=Y*GLa7m$S-jvJ-=Dh1|4@CpVqaE#fHf0$AUUNyTSx zm}jY){PGt|e4=L9mIvfT#-E9dys{8_nSz}YoAhr?u92B%=k%59I8;O`oCDyngoIr< z`T|FUZDpU5uQbI{=OZx~n$>A-LZT>}>>`mhX$-6@a1mAx1=%<#2wKNNA6Foo6jz5V z2%&yTUt@>m?vm*fim=a_9H5M<_y@KY{!q=V=R_%UDY=gQ7=>JI9c7?Oxe~kT*gZPb z$P^~SMU$ZL*|n*Iq1vfevq}>5{vHgL<6=Ui}PFzed6AKpni3NqV z3Sll7(>K5jdjxL=s_XZ)^65oFyCRv|gQMMb?TBh`8PK?b^Mt$ng{S3`zzzQ~-5=qd zD2l&XV<>ej2Cwfk7n@rn>E-&T#Pvi@rpD6)OjkavYyl;4|Fvo$LjxAz4~{m?ms$h|CWhk9U%Y*B!D7(%4Aae z%LSO#M|hoIO;X&dvg?7#ka2^?I<#J$-B&0KugOB8OzF30C%)V_z#XFzW?Nv_yk{o> z@X9YPy7x}#qWKe6G^Iomsz0iwpt*ZoG7CIRUvW$Z(h=Vwxjt2J#m%y_y*8;W)&5EG z4V@GQE0fBeqXyns3jmxKB$|k@DxMxFdxtjnA6}R>cYs#hmkw|KI{*89vuD%cWni+FD!N+Bni#>pPh-(f!j46S8%1Ft*Zn`cI7Izr6;XDpCNP zzq~Q-HvQwkKu9PP`2vL_KbX|m)GHVmghVmMFbw}>Rv8E^kG8U60zLKQWGk)qrb>f= zh|)UBz`jEH<`3ZUBUXXJ&;2N-xnK|*Dl3!cY2o-K~8_o?%XoR2pfTz(Ky1NPvh zF*_i1W#&NyQAZdWGi3$k@b3*}W-)o7Df=@7JXsDSW5y{BZR0ZmrT>gkJ@s%Wz+XVOfL;K(y5sJlSkU7qzOy!VN95Eu0!iyCO!8z zZPuN((Fed{)1r0>{1Yo)BPiLYFTjnSM61b$e{@Jq|G0EtcrJ1iB$|xZy{Y(l84$k` z=fx~{*dB}$B(I%BrvV>$3*)6u#-wjLdoL81p`h zHC@;e<1)gUybb4JUSxv0!t9Egs^!!CD3w~cACk5p^Z{D`v-Q)t`Px zgdHFC(zlQ*q0MO3rJUm#e z>>&x*VS7O#Tt=*Ng`!;9+b_ z=+MZO3{>LTlht~6Q|uTd&UTzFO>)JtT@*g>VSZ|1vpT~k_p(?d2uEjonGFuAb#yV< zVbhiuFa;kOU#c?Y&{dW|&?$^&CGrWQIFI| zXuiU6)d{9NB`7)a>xuUg*6ZX4&+FlgLVs>eOg6$KaX_QnG5%$_pA8x>9LEh1$?kTD z8JLvFJ^`LKD`%vPQ0_lUlq_Ow3oIz}l&4DSZx#8PrMnL?N|zNcmMqs;(ZhmDrTjF} z2w{w_H{u-jumME5AL{67-#ZF+_I@+;bjVgV z|02{#w~i#|2+-uD<+%>lYH1WD)#*p{BgvE;-m-~3b(_SB4koCxz$%VhH%KMtqYGyL zNZl;|mAlP2Oy{ndtbUH0eW6nHc;5T%v0RMT)~(yIH%>GMA%_qXb9=GZUE4g39nmcW0-KK=hfmHroaW7_s>_~(lW z-nn^StPU|mLrgJ~Y=Bd{mx`tM;|&s)eZW4Cdd-6>1V?OX_P!lY*4w*DpScO z<$X_4{)jSsmAtLEa!lqklZW|J*EOqJTyA57?bfTw;bgO|sL$PWO*hcU&aW_mj!C=B z9ngLW5IX(v9h5IrDHDt-W-;beknQ}_b*?_x6H{*7-%s;AQvgD?}7H-5dZ0q=*bSPca%}El?79;(}=$85tfdpR6PJ zNDe9x0D%rlI6qlVMbCc3vi_X(62IoLrCzRJY*wwF2Z!?~z)3#xXQZT&Wy)!*sgr+lRW#tTqA0TuD#)F33&(VX;i@vD+(o#@tEP3X zyoCwxk?*OpX5wh7+;B%Z)3l{W-YB)v4v_-dQCx$ZA;XlMsbky@io);i6W(|CrDoJL zdDUmU?5RVXUk>$TxNZOiupsYLSF;X11$Z{2%*igSL9e*G#xvcqN7KQ3Jlk&O0NToYb zL~NsiYz%iU!T2VZmUeeD>XdpoSc@P5jUE|qA@)7uucuTv*SOubV9M$}Dlh*UdyuWZ zULK{HqCb~**N{28bkr5{mv_6X-|rdV%Bb{q<#1HuE(g9+I?(fY-7|O+;p`Fk46@P% z?-z5r?(wt|m|J@Osj}@2ab#!(a5meJ3;{1Kfz6?53zO8}2X+_cF`|+7xV)vkSM~va zt*GZ@C^G%NrhRa~?9~5OI4l36aQ@D;&p))?zpSOTqqk)H=utv`4)*E^i46X^HzJWLq4Id zkj!fIM8uCq@UwXsdd&9e=brS-^3f=JF*{GW($1=Elcy7h{1VtY5i4MNfcA^kG;~l* z->~%5&BS&tHT3IAODj|5s7r@}$x5$iD{rcXNiL=Zgg4t5yj9+-y}(AKKL8330b9mSWc&^DT2 zV~ADh-wXJwhU0EJ)q_(3+2J}w6R3&?S{0~EkZJDS6i^_r2crke+9|!B2AzZH$gnx4 zm0|oRAJL2jVaPWU^el*B7JvpKOoYm|qfxysl0NxggGo+>Lk}R1g~2y&u;{!FMw%Ic zq-y32q;%z4QNjZk9^X096t(`49QGz5JyACSpi8cEK7FFT9a z2@%mt90ZHBEiWC;3|@3Ad-KjO)WJ37{GjD`IXHG5 zRcC4YW1v81L(|Rqi=?XME-o;n{%S%jqbgNB=gAZfds>yo15(6gJ;I;Njl`*tai2m% zA{bOG33{3x>t(9br6Ob!-y_AkodJ|+qJBH8a&C#IgX@~XPj=kF{_H9nNG~>B*!|`QjN=Cl=G6mBN{JPu3-eF|%3_>8=5|Q7+?ohaxub9U%d9SAJ+>@c4 zafZ%h*Hk5&`MZfc?`fm0`rmR*Z30=+Jhyfl@K!`?E~1q#wvUH}+3-JFb0$=!cP(M& z*~slRi*4JDqU+m_uDIKOcZ1_WMcGcJb>6p#9q0PNs~NJoP0&?RMii0A=6MVtx-!d6T|y(R z8LlUwL=Ks+R@}oMXGsBGX3%KRM}w6OH;)Kj!eqora-0DF;fJrc8&Q)E=|=F|^s`r2 z;gO@rO#(8kaCGza%-f`jE%hgFFOm!1rJjVpJHWz(v?KyVj!?n6k{hYD=$(Q|#bkt{{Iy^hV%E)?k*DHTRO- zNiG{d%|oUyxEZ$N?+^ftpMS44_?AWRj@4`dhwCk-;o5%o$xN=xSc8mh`i_YgOMN;A znCj*Cx=Bv=fII@z)giC4T9XzjugQE_=A+|vjh$+W#gIwgW_>hF6FFk-Cg)*i*a%PM zRa7CeDL&mhQEpGk>%0zi`m_9oAY;tFrn)`lP;tu+Rkac6UzPr%*l1bt71+%(*Ni-5 z;W*3tYux@OTBhP(+f6RdM$y=_Y7|o*b*UGob=g;NBK;t8$|1xUR0B0dOo|{y#F{D9 z=Hk;=UIdVgc^{~nJ;7`dDO~h_ipZQ1T%oeGmny$L za1X+fqliJ7!8l`-Y!cHFiTp$Xh!aLZGb>Xuw}h(js|cbcBq1Co zB*khWF1wJ=6gB2JlpvHg;gSo6NekTb_`~8OsJwnC&WCG+I}W&pEEqw((%xU}AUP;X zn1Wr3OOP3urATs;bjSRGTh-qA8J)YHL)^4_;}?HhVi5c9mw+yXG0;!MqJJlElY&PK?+j+Hn&K21mjYb&`X5^p zsc=BVZGWW^s=oSA|NRR6*B%t}-*~A0p;P{PTS{2l{nIrqQZskLRz>ZSOQzPu;`01q zEt%d_M$)ciK1V%B&|9~wG!!kf-!f3tBkq$-nkAAo*f>wRv8Da zq75^Z;1yq@Z4VoFne~NhUSc= z1;&$ZXtyCk#U!rUlJ&UJNS2_T*RSZV!{m;s5Ia&_5N$(+m7_!r#>1F<8cef>!F4w_ z6o-6MnF%oNjJG`gA(%3CbcX$`HOq?H*{3H|91C0N9AdAXG3G4o3%ttBta`}eml3GT zAdVy`(2PmU7$k_MO02Z!Vzawc_PZr5FomAOY&KK?4JmDBhnjSb6N~cZm*I`?d-YIh z&za4g_B}IfBzCwlrZ{=_D6)#y9^-63PLkP2?U`D#pir1JZ_eOO>Y?7SB4v6cridln zSh@IDy3lgxi?)0dtbcO`R-?kj6|(&z$tlRMw=4O3+f28%)PcqGUOwX|iV$-V3Zy zs2;@y43%u0tEE1zJI?DVQ*0iNkUkjBGqFnq2sJ>9IRc1d3bf}l*^eXMWtRl7I0*HX z53q2_doTG3m6`Gog|ahbK7V8mA>hdWK~ zVqc0EBB?}npru_Al#MCyPAC&uvaN9w>8CB`VaK>QP};EJPvnBFwWiqUy2t zm81n9FLrzHN)PGdM=$=48D?K)6<5}0D`?6Y2rf=%cCS!GyTg9>Wzj9LlRj}doG3tRfwEUFhu`J-kP%Iwlc z##1kCH+vB!fJr3q}MC5cPH zGF_>XLK%q3U|vW;QK!}wrGBkCVhRqv6Z19j)Xnvf<>YoS>K3BSsDf{mn*XC7O|~EP zm{czM%eNeeH(bO3wtfxHKg(Uf!&hDWt;n7bd9a$_Dm>AB@4LR$?Lp5x;0)v-YAh9; z4WarTvBQy80z;oyD zg1be~&%wXi@dzB%$`OTani708z%S8)^I>c!UFmI7=012@!a)|hjpl92GGHT%azS0p zaW;ey;6u@$-laL`kAvIue#IVq;CJwK((#U?Mv`1oka9ClW4#CiJw$VLE~;-70Hqw{ zhXDB=m5E{eA-;|n?>Eqo+pA`)Dxu*Ogpa+rCvRRK{3-BjF`}$FOqa3Ni6F5?$@_!@Aa)( zRr|-ctL9pBjycvCeLs!nWhFwh@Ajdy0uXYpQB!;ECFSsn7~U(9WI3US1|6xm&jEaJZ5hGie@ z42ss`!9fXIk~Ldzt|w9mT_&Qg5>h`E32{Ecs21-*8*db>b{qU1=d^~eO1l%?Y%OOs zu)-#KA@TP~8F>XW`4^w1cAb+GpHgUZewLYG(-dX&la?gdzDAf|!k|91hkk^7=;io6 z^DtT)-4%3|gE#{Y+<0T%O?HIQ^o2OBENlBU1u22mqBXMxj2#+vxPMzwCKA{~s(CT% zvpM;tjzm%pgGFI!vxaWDiEI63419S#``5s`oz0w4>7WYv+5;%FB3vhn4O)eHF-yH$ zxBhgRAQAXFxI^(HI!~l4w1nl?*bvLbC%e+@-_cvaMw}C2Zr;Mi+g9 zAzjx4d6Wp%W8cP*IF&Jo>m@1n?Se1vETpu7D*S-?`O*24>>ch%#DMhK`bkGAbW(`2 z9@KecgM|1Nh-Q3C+zV1G8uWv~3v~2WOjp^Vj#b%lXhlT*xs2dE_GQ@rH|R+mfL^@T zHcPVsp~)Uh!yHC^4c!2Max;evll$-?;*@(gGg>e$2eXsgKOYKcOmneS-xO);c=ha5 zTLw%x*{k3L!An`I5mxE+ywE-4dhywV5?E-?^1R#^sh+6w-Cesw_)`UN*N;q6U+YwYyX$8RL*VGs4N$Y zG?a|wpxC#CBi?3z61j{P@&cC&3Y0lCD5cSFLZx^A3kg&W9h30@-itUy9C~mg zV5*=s8f~_Kkbq5?j{My%_>S(n#U3pUC3zg^!pdw{`n%2fmfbCwscHVI+#J64FA5C1 z`*PABAkZXk(8l7B)Xnx_q^X0hnAMb|4UL=7BbKE|lv(8=m-s?No_h%Bg67cnU$+-Mpbb5fUkgxI8#b?BlrhM||D_BXbbeOn)3e>;6k^Xkj$ zhwOcS2_V0U0O4sV+wYuTxSaQUQu4;a{T}DNdHR4QzisKO=*#Hi#;P(R56r}z-Ak#9 z=nLtynWCKfymmmN`%t@z)}%jseH7nOsB1v`G)A$WW|6VzaH8Q^E0MnrDQ6FX=$Um8 zO6N;D9YoeW#GANDlliXDN8B-Hw zZnw`jPPYiTU6KDb*edbpaV|T3LWU>iu%CLIE6=8{-7n{t1`qY}(Bt=WoVH8MRx9!T z;ehQ5x#&}REI+KnpZf`RN z-om@cynP!eM1M-QT@MnXm~&YSKN(}@k&<~7ak*YIj7I;bcuPS-;%hPR*xEvgzMGZ( zF^%g|R*nt-lPBv1ngaOB@$c_0c>?<{{vl$%0c<`|v|NU}pFKm~&bL@Szu!>|^l_RC9|12^hr4S0A{i63I?JSn1-is^&(|jmgh>1Y&5$Em;r8X;!vI zfYYZZD&Ik4Nrqo1DHAv^46(@?SSo4GICq}^i3d;_r{}YO;{pG*botkq{C953iyK%w z+u16aIJlVD8kzhH)S9iVrKF^W`Uy|U2|(0`h!zFe2O|Szc%&=HgET~i1RD~yJ}1Hj zh$jTL=XsZ1Dr;?iUon@WU);bd$#yMy43KrHL%`!+?43WgJJGsqbt7irYLQLk+|~Sj z*}bZ}+q%lx`}J{8?1xuJRfjD`>WmXq2o8J_Kd1{bI#+to=8q|hIp?4#)(Zpz;^;Xi zfGflm;CNHvZvZP{Crpl&Y%e*Q7PH8uySRsi9Rv3eV@`<^YcVJHH1Zk~>!{9XQCclM z6Tz>IW@K6s14n5x9BP>^t(4PJ0hde)Nvz%JllC={II}+nZKJlgOxc^mdkTX z`cL*$m`lCBNrGx_a(#p8&bX^NgC{*j^*RrX39%gq+e|Ob5G{;}IK67dV*K8IlnW=n zDOtOU>K4z=U~uB!q;I=dZe|M|^38iM%vHLZ`j;sQ2h5wJ1P$iuvz0-{&y4a&wqJ0L z%zrP+22q#vyTnGZ;Cg;i^N$T04j26~XkYuykWMu|{3DV@G)s`p0`CN3b)*nZB@O ze?r#qz;hW5#68-6_@Ky?ZafhB*g&V6F;s-`2wBk&4)wckH59$ca_x!#T01ZBb zDOyf@&&G1?UT-`k`KRtjgz}qSz@GFL)2Rh*Mg_(|__uVG~(fup1APEMohg|#PO zMsP<~1mYy8VDRYCLBcUa!x#=581QLU?l#7DM=xfS-o_rCmu}=iyMnteRZ(DGkH|eX$)s7t7lFnZ;s~_FdD#B_$tlIDH zPy@SV-fbS;i9Olz3y8hY52YPKt>~R@tNIB5)!rj0Qs#1tQ|0@E7pViGHWEQjuc$pV zLd+(%zQm^90ppVO#;|sS2 zp?+f+N?9LlMO+Cemaqd7MBJa%9>2u2K}dVXb!?pj9KgR3f{l_i_rtESG0C(pB90ka~y zy`SLck*2Od&A%U0IvTkHYW#e>$vL$%#9hF3CO40B-#x3PGkqPI6Z8#NIW6bz4iX?C zc1-htPG&A@TK5)*RsS9k%{~9)8B;+>$rMJ)WVvGA{(> zazoJP?sgRI_<2a3R1tsAjd?GB=!D8!1WJ{3xcKv&?xKW}?j@NjA`nLVpad=<~!a|cj5$|ESc3TSeWu{S6#^${m%R^ey` zIp$&DhQ(`=58v0=k(BkK7evtWzaAomhBO_L+9V&4)FLq%3HOIs4TIWLNyB~_ zAg@A2w&_YE2^of{Q!EU5I>fjA>JqZPIiQ*r<>xC{KOBY2nD+4!Y#ff2v%vm%&N8he zV7F*_VU$}u97VX@oQr7EDUvy}ReW+MwW>ANDOZ0(J+~azRI9Q=v&uEpDOP_&JJ%fU z(5Q0 z5lr_(+~g0943Fc)96UR0oqxCks~aQ{N-&_NVfVaryJTdX&3IUDRvGy3c*R3U$+fsd zw5pVu@}G&5w|b6-;CY;><{SFNmQ7m@4L6u;fwUHkQsN{@v|6Cr3! zPauGT5`%`fy#;cRK5)k}Jpc2LxR0AG$@+fHvG4DHV1@sB;QqUmg@4+Z|L-hV%K9Jf zst3KJxluBqXB%>S)qRt2EdtxrTp47Q z`TBE(+fSUK3UaAKcC=(Ztax3!n|Z_|Z(C^)hFVai%*I%p-)nQf_g-gjMm!NgpLU=GCrB zEXL=un3`&gNhi<=c94NIhzY5q4{&=BO9#S8(15w}$Y0`tE`A^ikidf!ueK3H zjqMsjdyLB-&qasyYVuo0#Oi*ZgtW6x@@_eJn=5+@1P1@rGs`^5I_x~P#>#wQMbd3m zW2raq<(Y-AT&K{rK$7TwXMXDw7*6zcOC$bvK6jINWi_`;sjGA8_Kc@X>eYgB%GQQ_ zWwwe-ZB0ufpU!d@?ZBQaH}2Z>s|zdc)(0ZrHUYl5FL3GAEVwfQ`|oCwhj|d2?bR9Z zFAI&Q>an-Symx$W#+evbHA50TN7^zx9J(tnSHvygV>ERmzw@m2W6alk@jbAfzi^^2 z$hyOm?kKf;I+*SR9$rDff8~c-wO{brZ%8DcvCw^nt(cw>I^yv`eKF+5h!k#N_Kn$g z?ojN)Zh~U~5Yh>pWxW77-=IZasVCI*$X4Gdmh?>a?oinD&}{1i)b!MkE#VYt6E(0b z^85N$l^CBOpA1Dv^i$vTGc(WoxwB>PPU$ zR(FA9_dSqj%AqP8qPSOMUDp}h*{pW=r{mgd{vWV6q(QNr=U!Vd^&z%?5J33I8Ll-G zJ9L0$QufhsN@1>4i3~H1nn_X=*H0cs!Pz^S^+{+GWh!(d70tpDsY=I>6tbP4)fc}9 zGA}c*lQ9@mQRHp{GG!cd1WE2vvQ&iAY= zM4=bZkon>+pO-wPlFO|gO&MDJfhb0(uB+NybNvYUU0P0~Er^vjI;`fPBJU>#ia61M zQ@;M1r&;XQaUKH%aIwL|zhThJQ1(%_-POVv;pIls6AnUOAz?w{Sc1AqV|c%wMlqzw zp$X!Xg)gCCY7Ux?Q1ocJWvyHxEL`#9CXs!b z(DxYD*&+DKW5^>Idi&6)Tu`e`<QqEO#L3t@Zrtdx-xiizFjIojo&I|lvf(i;VCx!}; zAotg&lYn$IcTevk1#t@EjLQS7)~8*;5gDpnl0>+@BE<~8YSD7Da%A-&1>^{_1|>?|FM4wflPcv-qP9SB|<4&&G8v(iI;S>;B@T z&kM|KPa14WJ#WrAKS~68Z9XM*Sbe}s7GE1$H>lD2($xi$gY zG`?2T_qf)dn9ZbH=to~32iLVVEYuo+Qy&^C!=s%Un&|*TZ~eyr$5(gMulCre8`@SZ zIg}6VZ=PJg&yu@~z{oE!*MqnyAKm)#HldMhCU8XP0?naXaL*?3B?5RG>s#VI&!G1a zdrE92p?Z8)#8sN>W;i~N@sm(^P$yxyM-m!4I5F_bC4*)5B9)hcenOjC=!*J$G?gwQ z+^P*ie5>X-bOj@TI9>qmvKP*f#W|Jl7=c!_{$0`&;?#(JZwN!w3z7}xg1DYX2`B3@0+BYa3{>~!v<%5%lbn0O!bi{FOlO}skwVf-v%dk;-X ztyl7Hl`252Eb7TwO-FU z{Lp{d%W*CtK0&;Kt#y&k!;vsX7ZKao2*_vreQp9^o+g?alV_C))VXVFPC!MHA@=y^ zYwiyYzBk>*tS~s4+*ax7$)1fuCiXLzX1f#EU!-ex4A$Skyfs z4L`<*aS7gge`3a4Zd50T7>bV&LdBP#EqL9Ar4YM@o192QkW55=u8FJsZlk`!sX%}Y zId!5mx0hRBL@1vp@_aU$DrdFu50ZdGtn#Xs}F!m$Jm7oA5QqTw{7+7&3JoZ$bxt z^?yb|F>K=&K#GsslWvv%eE}(=4Ft>H6HT`EvmVD@dJT>Wp1}@%*Xi816ke3DGp#u2 zFN*dIUwZe6o)0GP0h7ZK`t-La9SeByY^{Sfh0L{pdI7#I^JV`vNL!TJ4`o$)-B!~l zON$&e8Z?#|LAg7zzbOIwEc9XBgDeM`(HXRdlyZiS7yAOD5)BX#xQBWxZv2_EJKq|3 zG)||p?v~geGK`Ka;jj|85{4cPVF*h^TbJZr&K=CSQC62QCJ~6f<#6W$T8x;NW@GL!2es6d#t16+9^uxJpWI+IJjah# z;;Qj*y-Y|W)Lp}=LV9$}Q&_PNMkWE0k@2?4U-Mj4MpM7o+A14zd_n-V8SuRW-v;*E0Q*WwhiUy4|5oPGToYLY#wBjt8&IDapxC|a2XMW^ z_D)=LgDYB{^E2wyN%vNe>;B(J=yLQH^1%#n$eSmboY6r`0!pOFF$_mqroML+|(|J_N3PSUe&2e;x!%4&$ZkV(X|N6{jBv!-o=~4(2T~ zMLcaMg6=T~&=!;8#l_Q)2`DIXc3!TQ3Kv(Ra<&&{RpqW}jt5}4#@ZP_^eG_G+K4Tl|ygw^BH zBi1Z?_WCHWd~Cgo`fGE6UnAY8{N)Um{3+Ic^&a-oAE@Czt9WhrQ`}-<<+|)S;cDd` z^U~kk5ceGVx$Wsd_`vbSF#`G&BD6U|N;&wtX%5;z^!nBC%tJO2srcwmjapEt(lN+ouDl3XM-yhB|!1@7gSPHWe^zm`Eq&6TzYE|bJm26>F{ z=fDX5iNx+kD!DkAbjZ#N=Q?DB2O@l?f7Tz_Xc8#fZ79C}O?o0n3L_R*R#p~#Vpl>| zZU=8{VQa3v)D_#w>>PW>BviIRl|3aZ2VS4n@qkFKta)H_ZrIfJjftV1H(S149autOwk zNcNX|KO4JQM+Q^)CA&AUUHmogqOY)XaA?o5QF?rN>IE$i<(BOp(wp0;FSih~6B-?H zwX^#z=4K~^GW}qCagmi)Om2ki)KE!NqS(&roeAS)d0Qy{1}*?f)Fz)!l!SEU*}fN>tU>s*EIOeqm>8VP|2R#bCjgQEPfZ30mt$Y;)PQ zJDaUZh;O;2UaPFO^>kyTgxpSzo|?&}r_w|UC4hp$C4ijnei$#gP5fX-trrDJrW+S8 z0s)p`#Bz2e1*Su_>2+X`1b56NATCHVp}PLaM?-s$=Ay#x+}Z~D5T}dPwW)=TwWLmE zt*5@)A6QDv$LA(^daSDHMk!!koReh;e~nvz?Mb*|3PbVaP_(Hh1)rLweyl1%w3 zCRfINFR~w49Y#waDEokne!%+8&ov0hHz4yX(^rK~`W=L@V?j-B$kzF1tXIndkD}wL z2!%dqDtIz{>Dfq-)VkHO_BwsOx$VqgS32^rZZK;#haPxry^Jv8U)vI$q$2^7Cq>aK@Y5cs5hMLwFJN_3 zSRm(=V`fyy`c^m)Z$}F98^`LvN0+s0meW$(M@n%N{^c9{O>NVqv4fhe>lPZnLM^Lp zt$=ZZ?eG6Gj@2e_I|7@g<^E`eFETd;hIVft1PX3;EOy^^?hBxpiBVlhvXBLi$YFM` zB(wbygA%Mqm?PUq^9(%|nkWxH+vn(xui6hY2V0tlqw9aZrxG@Rr3kn$s_I34wjJ!gGQTR!gD!OsNUrSpzj zM^9y#=Gso4K)rOu?)iQxoN#J)?AaPI5ri=D_oBk^QPQTDohkc$E z)TfH-ux0zLC+OHxtCME_bXvoh&!079^EmuHrjvr2;(UihO}#Ts{qt9eK`tQhOyc7= zEMI;OOIuqKEc%{H!2$On(U&;iz0OVFlL1y25bF*3OFx1>-aBGV2tj}3w{&3s?gM>luKSzRbb0Da{5}u7kV?qEN;%#>+NUB8?s%8Qo zSWg)1+O-X8s$iE5tEuE>w$@AM=56I_4z$t_j-(D7SrZYLoJnnc9ET%38vlil)}=HA zN@HKU&MC4wec$MH6S{2`BbRg?)oSH=(u>X2| z{OgCTd+hUXf|?>T5-)*-XT%!+*gT9+P;YxxaU-1eGbYE^(y_ApvAvYO)Uh^e(&XVA zlZD=F8e<}?H-mjP1h#%Pi)G=s%{_~Rkn}yY1e^0_!{}4St?1~x&`+!oAfBuB?cIUiX=&*wSK(#&Wjl;H!DIzyb_FWf{x^fK%zPN$+)EM2Mpk+0n zr_8#K-2l-37};aJ*>fK7fTfaL(A@J{QXLJ<Y2H7g`**<|QIBekanBO= zCc)lSpxT&FK9zn(6`^zNE@1uiUoBy{YrS#fDxn1po@7h_Sn}%3;smoowNWkdi-P4u z9NL1&A$e&%#S%NN4F*gSPlScKL|H@m%9*VRe)=~Y1}Tx(Cn&8@)O(8N69Gl1i#wq~ zjlz|_(=nzxOH%Vr-|%L9m0Ek=m7J9S1e#8FeAk8N_4bX(`Q*&ZSt&WQ&;izD0`$57 zd3us$4z1uIcX9z$rz5|az=wBRh+ja243W>h!!QP=!!{Q)E#>&dNQdmq_Rk@}h4_$S z3O=hDf-tY2u&lL_1K}{O#Z7UpJ=gb-^g^*Ae)8hn>XZ+;QRo|i-!4qy4)rGI!v(dD zr!g$1c`8O(C;`_@gYv&+jRf5!T9Y?%CZEtktz|$hCkCE;F@$~2{v>};0#RcAWgy)W z(cq{A++reFE9Gy?oVQ7dM4JCSWXU>MVQ3@p`2);64VvQ!*DW5!HD2P!N!3LS(uEqu z10Ec<6=q;p7ZvI0({+O{3-fY*%4z+S)5zEHMhFyC@)jeq!}U_ee~e6t>a0={(0P?y zxA4H!ZZw{OV2&O~G26{1OTEtGl)|UkOizHWDAxxnN2yw1WzgDygek&rlkPx2E1I68 zvkA0WaG9gG3B^l5C{X0TNM&gg!e(+LuQ!K02_woQ>F|5LJigH*y}*-)>dnitC=Rhk zdS|bmP#SuI@2aFeaoFZunaaLD40-@RQY;@EE>ACJUln%^bb1U(UJ2Qt*1$B{t1Vi` zOVl}_XseF1{Sny&v9%Db%)bRHRh((i?hI3v1YZRDzzWW7Rpu<)v4;IjfHaq?bo5U4 zUR&c4(?DmS(OclSOZsqCpg~6vl9CmW4Ow|S!+e6kkbPgWK#-M}8*{S@GL3eBL{6w} zl`bV&+niBhQp)qh(YB>pdcoF7E9uI@QB+9=fiN>^AwB-qh^^Tx$`HIv36*to>jdu+~ zoWC5;<@;?TeT7rLW0J0(2PRqm{Dvp7_r%~3+RyNrM-dI>(M{2G$2a{MubFQwU_qK@ zP3KY7v!KLa9WZ_l8ypz=z(Tn&o}`~(hL|C?y~Kwk&Bt`5dnP;tJa(+<1nX)7#wnSA zE!FNY&TgyCHz9}xG$Fgr9@b#z18d^TLRm?nz}T=~^lck~894Tfm3nVAU;I@T+Itw> z+c$t8=afN0&u2KH*a#6XP<;bU33+aF=tNF2K(ptU0iR3m6IpsGpeG5q05;tAvscEs z0|%7g2N)W?{{!|IX)H&tELS=ub+KMN)MrLV&u$5#Zr(xSvs_+?zDfO26=vvmCfu*6 z0XPdc4GC~QKjhOvR6kjeykWvRIgAU%f{6!g8q&7klzcIyA_Ix13rFb^`@=d}jw6p$yQA5T|GY|Jwtq{l1M<->lqET(4~Z;VT)iS7E$ zq2@yu_(`JrgF^}a(zT)b8Qq11Br^0zvqN|;_-3$KyGI1$Ih%W&bgs!cUE?Xo>1q9U z?#J_AK8jke=cS)NDsR3o&DHIOCv)WOTVmAoH`A%#f=Tqu_@C==gb|^IYTK8r*~-_; z#^@#0;^=s79}XCJNeri|Y*p=}V>sTTLD;$gDxWhVHkG%o27tE!172P_Jw5sRnebbu zf=D5M&b1s@?WAPf#!W0=V_-Pjw1#;dV}I*#1R%A0<$Cif`qFt}JXK<<-1F@yo(8jF8ME9Y5N$b}MWU*D5)S%Y9;2vpZjLk`ftUl1RaJs8yZ20Vc<6u=?$FHp) zTJ=^n=37{4c~fIKX}UhUz3>|N7R??=4GG5gumWo~wia7h4U#=(_mt29nK7{F3-9Nf z2jPGgjEfHx4MzzK6lwhSWOJP41xDwruZ0s44Clhu+Na%~$|u5R0d3F}L@K1^tlJKA zd1(!WYjrE1Vo57egPU zJNSF}=Q6%g#Ps6CHM}p4?NpL7@<)DKADEdc;=NeFJWwos2QT(tEH$!d@xHdTFib{Y zV(dcj$fR5Ybz_Ef{XW>Q9~e5P-D635``O7dBgD)Xu@u;)gPdX^6`bgJ;?J#KJ!terA%|U(esz-JSiNFnjAt} z&~Q5Q*`lOPvvEZB!HZa=h=TEX{YlgblzHH$yAxq+DuAV4K`!EZ( zw&H*PVl$GgS=7XhO142APK>e0`dc%HQVuU6*S3xdC$EiDh!+x%tfTeOgk; ziZ?ls*iBeig-eGS*%0zTxgeV-PGZQ60E;?_1Gn3|QYK6FvQ~}a!&%7_$$P`6*~*b` z{N_&Yv5>EH7avsMp;6&20KB;?=dB#XGS4{7mge&qUeIkKu}-*>7n&^psidN!QsyZE zIPeh3yTq^_MUzIU4-wc#3>PrMHJ8oRp`WuX0f^x)PvmclLX7m=9L;{3`QLxl8ltzI z;2v%iG&l^&x=XnU0c5d8TAYS4)`4 zjjy(aB)WS>xU@hM*UThlm9j|hS-|lRF=Mv`BJy4@TB=9zQrF!mO{foADwn&<4&J-} z5~6=q?kWS2b$PL+WjEhL8Ozyi^ms$STw14RE-hQYmse!vR~&6IxoM7o9?9YmIjm9? zmS+TS?@V^p7ih^I=u@}X9X8Fh9%)lHq~X!LfVWt=Zfzx`pUDs>n|TKa^F=sgJ2XNq zjh1S9T8y8XS)XFTCv0hq-Oa&?9o%VW4dYpy1u(m4gO{^oTiqkbx4lo9PVH1uoAF1? z&=AXvXQO9WpP15^Y}zp*M0gNHn!HZbd!e73)~9x4H2^Y2M7jeV&1$>iP8!>flh-)1 zZSe`$7e&+vjB3q3lXm1erkwJM%nn4y8!n>US%)(`QYOKN|MFvQ(;}pZ+F6jG--4@w zgJ-di1G~%jzfkGU(v%&tQzzX6XYmK>PG4hd$9<~4cmtyBvRj4!syX$H;5r#svWmHC z#lYXyi1Dtn{~(6NxhTSSjs4YDJ*xjx`6{^5zUHy}Esh`F$_)TT2~D8*j2~z-;Enqi z_mKm)np#hAgd=O)$X=!mCYESWC(Zj4W{zew?v#!v-2v8Vi+VK9j*bK3&Zo4GZVUi9hbs;zp$dUWhn?L(A?%v;Vd3;r%uU zSasAf`pCXym0#}d<_sp-i4%Rs&qgTjG7G;BR|gY%w~gs!Z|!hy*T*LmajRT0FWU#|bKL>D ze`53VrWLD`@WcRrS}ZdaZ7`ZE-p^`O^oBqVD9>ipoFYbV(ly0;4mi+r`aG5+YSykq zN^9&BqmbMeVP+ntin)_*D0G^!B%4dDI-Ec~Ua&gYns@k$Bm%cOyvOLA)qF-U(TkV1 zLpeJXFN>feU5@7!XsTRdNJ2$VS{P}vpPyIbqBT26uPK{0q&dfDv*wZurCku@)>rF? zaCZmHG#2OqAS2hT@5{LSeZJF-$?aNWP+5k~6mg^Vkh6x2IYv(IISKTQV|oS#UuktJrxM(=!VFZ2FapJI&dd!);g-N+x1 zhXek$^aGos?Qn$YEoY__S$vwzDRo%cMiFw8KPjp+F9jncp1EgH0c~)&_B5O z`u=tK0vrmY+Umqid+68`BIFgqY%7uNH{rOtxs6E3_lOvt9igj;Wtq|xrwhjF$~hn( zu&Mg>E{&6ubu~IN&4xOBIWi*&FcQFhGcAE zjx6CSZAruSWT!w1!3-~k1>l{-V5ZhBh{9IthDgGkok=DvW8aQD)U4!rxRif#)Z$IW z7y-!4`N>j!#TkM?lUy?@9>n(x%MLvC44st5SLO|*(+{ePe!?4t%8uycs1|Hq({xY(}2=u>1)0; zDAP(5H?tZLak-RzSJE`uY}tIoeo=v9E4%jCS3MEZjTs*02Vf)4Hd}0;{|#I);~S$z z0T}{nSSk5bRO_4?c>|Wvvjr84YZQh)R^f+Loa;1UKuZ{-^zf%O%VyLzq{i%cTXc*% zk*sx}+kkoR^x+<9{qK&`dqnoVkVgD3(~wccVohesNlrDSOG^|?wS01ETxJFXLu4~) zuP|MI9C}*6t)G*gCo5i^ecm(o#>2O^V9BN`uYe2YQvaVQYW6C5#{?`e=UNT8*lnhU z*jO$$D?>jYGTLH*`~j=f9erz+z)~us_c-!rE0|T1n_SCr;X+AF}UBq}=&im~%4t*_nwLdYg zU>;mNKWcZNw_b8Ryl;ywH<&A5zFNo&chZcA^q{Vd+%|1)FzId{B?Ug5hn9*2_Bh;7 zk^-1~ZjpxMlnqagG73N!VDUu|SR3(zP&g#gl`r|EZ$MZ!{H;{qf%Y}ei40%rDOQ`) zKb;U5I9B-iimg^Gx_d%xBX}`i`JAhpE5koZd$l0uG_$2<2lu#!oz==@1_i+b#|*Px zNo|D%$WNQyUo0Mwv@rnP;mk-$23;arQ3^s)CnPih0~(glH=GXyz@LfVk+S=W57H~3 z=Mm=q&WKEnJ&#$8rlYivwDY_iaXr7>@L41FC{>!V z7QA!2=q0@Rl>0evph4=nhf>fxSc4k&J11Coh|Fuk&LkeMU8-mDusb628Mg5`D_)Ob zUn)s{gx7k`lfbIXe*3TyO{JuE`Yi5NM)i`1)yM3H4g5rDOKnVt)lr!BJoxYc?+!xz zV-3ighw503<`Z7)ZaO|4le6na5S3eelRKX6f&CwR8y>z5Gxu+z*4KZz{r#^I{ofjX z{I7^s`X;to|L3qyPV;bASzaDl<-5ncf&rB#i~vbMB%}hiB#a=$h6GP1q1u5Bg25sL z32SlrF_bUsvO+~nOce-Ayk}kAY+2o`THU;&X;uCG`F{SkFj&r6P~&VUo|i~mQB=r zt@I?P+b|7w&o0UmTr$BR6LQM8{OnvoWH&H0aZ4f1WISEQf_lx9sln>FU@R0;>ptj2 z+a3cgMO8V`?3R>z^E$=jBhylSi72Wh1T#2stN#q;tJ+di z*c^=!_wqL}#M8^EJMzf8`KV{N!|i$IzQkI}NW(-*Ovp$`%L7afQFem0#h9CG^Eo}? zy2|ESZakoKwZ*k%iG9hJy6b&^qI(2`&1@FC(7|555%%%x%KObnZR2)2)tS16=A{O; zre;k3){TE#?PfdENk#_F2BopN9bIPgFyt@%%#T^Z9LwC@bTpkQ_0R0VUJWGe(uAf| zyj-hyOE#Y}SHW|^9y6q`BMvLt11H+-%g}o)vl;OE&f z!L+PH+Iv<6xCAw_rNqBdWjHQR7NUZs^QU~-@pIB#%=unt{gxNuF2-6~uJNEW2)BuE zi$HwK_?3W&NezPNMR3M-{WHdx> zl?xqFr00`#-4X6C55tP!b+#-B9Xt9N9lXtoV4OjfIpn0x$|)22&-N1y8895jPMzyCLC(s=eU##{|EB*GDf%t^9VV`fR|6SBy2%(DE>7`Uvfqqk^;RFS)KA^XTFLcGCi6hS;bAPINx} z&J&kLdT@orSGLtQ-nldOn3!lRsb!>D?pR|O*YEw@np>^TefooE1S2@N5nr%f3+6Xo zab1~`S=GBrXsK2O`76{NQQOmy0h3M2E-zsNyBg_u2tPf5k;bRBnnNnDtJ|C?q z+0M9H`h!)SqRGofr!$?&=rvhxrAB^w0A!EprS9R(>|as~hFu3zxb;)5d(6=6(bZK9 zuE)XOHihoOwL4~N975TG&)lkU$9D>=K?ppY;xBy!XQ;H>q8_7d!O*k#XUA_ZGnXvi zyTCQVLglYt@_Xp+PfDpq0|7Ta6R^=)@8+D*Q?Z`3rH*FiSp-k6XKIQL^zB~qK21r! zj)MvK5`cvljMMF^gl<=fsqaR)T>^9NY>mUp6Z*hGs*)sogDHExF8lp) zYn^OsL%iL=npz#Bn&X38oyB$0d{YMboDNIiRf%Rt=yZL^(V`|->Pr2<`Ke?_s@awR z`y6?W1@o*U0e^dNZdc;fL&);=YTx+h~%u9OswG_qZ~IXylFcq_rDI``td}) zM&ClYawKedX?3AT?jJSpoLvFX&06A>C+gFB6V!aNmnneO*d;?;>EpRup4`b^JeCNt z*j=XAO1h;#$gGSm7XBg#BCIW1ItT8{thVwx2PW@l*!(DJtDxyk9pncleTBKFBSvwj z<3?#e_ZcT}`;4+qCyf$*0vM;0?$T0!9@I;jLdK>`bHjTIv`CF+s)+Uagl9tR8PsAJNm(VeCPhdoUst$#Bjtv zPYMgdzs3X?wj;*@@&sK}Z%%R~KW{n8C-2*+aL!Z|${ePU|3pFb=ZV9}kGaGs|GZMn zKmmHD2?09>c#!U44%`Q}1IW3~sQx?zEU^GSLs%g18BAy+%t3winJEQ^fVM%BVfmovhutvBLPAo>GQR41AQye3dX-b%d2Br+Mew^8i;G#|3 zNTSBvP$kI

bW3Fi!ABxKZM2V2w$P_(x15;|ywy72kf4(tb$wvi=&wX^>9zM#xj5 zBgSdfQ9l_Fm`Vo1)ED)0Or=9TViZ8`c@C5@=dHn`%w4gkxT6*gcFeMX?ir29r%I!k z4SMvA4T7UI)vY_F@n{&;d8-1k;OfAcO#6{_unocq8x6u69qUAyj{1;wjs}o*GW2DP zSO$@$>Ico3G!4SbkNPJVj|P#on)@}!%tKxH3PDoTD^OOLMu63cX9d;Om}dgWW;8*q zzz(dx7dY!y7 zb0O)29@FiytVy~c6*Dg!*S3RF`{A=U&`b8SPt!2vAS>|m|~KH_g| z*D7Xt>-aHh{6B*2X>s-1;AJVb5lSO(bUDBV;Osr2*ayC4_CZT??U}Ru2j2E@skea5 zl5TuBC?H!0%290tm1wu%#aw>>m^mGQ04zZf1SF#H!5(V^NbF}Y_@KpHJYi>+2Sx!~ z#P3j9$paL7WwQLijSA1CS)sxFf%k1UKRGHEX8}AEUf40Or&t{HP`SbPB{vxMI~aTr zVvo;cS$G4-fQEKO7ieIE(=dz!8iuNNed0SzE>8q`gY6+FnJk4@|4{Gu4(- zP;Vf&%rmz3GT_M`C#ZH%#rGYkX5X^FidijI`Y&gYmnH1qpJVhe27jfdi;Ji32?D`xuL0JCOshU24I86fPzm1BsqY+k4(r7w~e=#D_N=zN_agPC z{BIfu0{5hR86gH!dko?IYq=hR=^qW@gMHKM2)v?uF?*helKOUuFA($&XoJ6k?0vtYaCPe0L_|&b>b}GtP-P z85tRS@3o(ewa&Q?k%2M487QtG$p~V7hNVUEeHNqz@ZX}-!sT63gXK>Lq{YbJqRIqH zZ*s!rUrW>cN!uOjDrb3 zi83iz%E?Ta=xb<7H19b=(4o!_mUoZBgqC+Y_e=gPA0zKxX)Zwi!9s-mV{Tli^fM<$ z{!wQxSpIG+T7K_}zx2k9P#KS!ztp7`KJN94TKM!!By=9kjEGa)9X7upXiJFrqsJRB zZs_fMlJLn1p=@hPi1_Un2cAN~HK1@+-(VeP~nYU^k4S@;}*w~Lg&fU2;zMP-@)S+hZjPXQ>@_s z@LE-i5P!^Shlro;dJ3l#l6zvRt_lEq2+%87>&W z7)JTg7(VoJ4rm3PAz0~kpw%t*gAQoIVIf$pXM8_uEn4|tk7rmFLKC_G_C&Pk+kz7I z>W786!ZzVbjQIp4KK}(rsIbNNOZelO9{74>|1hm4Wy)a5&C<>kR_&!b=Wc z!S4$>Z1F8YoOv>bpjGl28F7VfVk*uY&l@xBJme6AIDN@1&OEc5KmX&JgZT7Gk5D0p zFGl$8mFoKfE!LdZFG|?wlMpfLj!pc)tJnjg?C{B?aP>=9p#1ZTM)BdRLVV$?Td3US z3sZ68>ME}MOHZua;}b}+>W(eeGV2SW?6H|G&NAlc`}_I$%Rj!Z#2c^tLY2GVQvL83c%Kmz7xr?* z7mo0VRP?@}$`;?qzJF4}3)`*p*Bi3OtxwN8n8)fDuTb{Tm)^d`*B7=&`qvkM+}kGF zNW#_Hq166~ZwrveTsd1pql6!>!zq{zsoLj;S=ZxLm#@y`e)k`ktlY06^gF-5&ewui zNT~pDKYn;%{HKc9f83b-uZo$SwY7nxv7))%e^t#k?2y03R3==De{;1LRnb>u*(AYf zNkLKLwShEOd8;;ApUhT+lmpIfSh(rCmW)nKwUeI!*B$t#7?#IUR*`cfW%6pkmL-N64b+U;-Y`Pe+*z zG${4cp2Hf!JzA>!`w*OZGIK|K7)nCu)X;O}5?1BQ3A&W%)KhIBmTNA-NyI+2ct{D_ ztkP%9r;u2Sw{NPiW3xGdP-Qzsh%_rlqfJN} zXnC*yj!@;ucEB0FzXbweqafI&@*3A3d^ql`XKCd1nayP0Lqb^#E4gqC5>*T%A`!sp zG*WZxj!SPQyQn{t2;GFSvwVjgIP~h^M0Fx7M6nvbjoBUZtV%*9Ishc)0I)Cbn!E-@qz=x0al)vS!zCWl7p zN8paJLFm9|)(W~OT$C_>`?BeAq(xfgbDSMTaC`H6fkTxU{`1VpRZs1zp}M|8wc6vl z!dRiH^wbolZ>uuniamx!FLoY(mD4yHL4uVm@26+8qM1<4WbhDE-?(ig1 znU`i3_po^1Sw=EQvop?LZnw34b6?$C`70Uh@D%KvVJwN)7NfyDMfez@xH9FPY=tlV zL3*uD%BVm2D7h}ZrVVvh?r`|$0m#aZEtXnX#jGpNtQj((`X3E%hMz3Vx)CaggixZ> z2nU#b{qDa|345ALcj1=5SOCRp3Mg$Fwti+NMp4PH^0Ccs%F;4J%J9Pd!uSL^l!fTC*$ zE{CCCkgQ^u?}Bg73|ga3;ubWlPI7@Orft%vLC}x@)#jTFRwrOYa7tK}bZ(YwJc#uRiIm z7};=u66=?;^=zb_W942`Knh>%a6*_N-So_FznuEj_FX7#5V5+4|FA4*>{2R~gwyE_ zH=oepj9(a8j~p7~n-+?A`$c-TYNC9$x*oZT&+o_VCpnV@STNy6jq=7l2dcRKP(J{s zzR65+YSevy$1SuA`>jY@$Sc(L+Z|Jg_?@07+TJY@&I|o}3zQM>joFQE58c!ryJi=7 zvUlKYWJhQJhJe~TQo&oWn@)d^RCbpuv+s#~S1i#Uiq?0qMQ?;-cB>E69eaXWI`P25 z;6+)KZ~v^XgGS=J9%gV3$|}rs^Jp;MJQr$*T9p_e`~s;psISVFrjp^;7XQ?wRBlR} zvaCzU7}2@R3h+MU%Crm#>3gF^#($+1s#IafhBt~W?0|;#d2N4}$JEn5lx~-zL#~*1=85rf zr+mtmt#dE(xiBVM-NNKqFGQD@GR}hsPdOx~wb#1&EsgE2xqnKV&<;@P7Vod1{kH74 zqV`=7wf+~L*?(U`WcyET4m*2i3mZBmi*F)K6IBCi7ZV|K6C*1V$A4-et6V8ziJ<$k zcGF^mfdFHQS+&(XPLTigTT9p zFie8u^DNwNf`fVJ>>cj0Kz*F~oMu^V-ctTL#e&RC4QV{8C507Kb-Q|6wcA*<`=C{H zYidweuZ#$9;@_3OWDTauwA{2F9r-np)1%+NN(DCC3^;6s+9}HfFHXZQL)JnVJDx1r zYU3|Fvla(vMk%XQ?TV>#VyB^!lARZBrghnLz-5Wefh4eD0X445-EFE#Ggd7%_lOB2 z%7&#XpTp9ry3IT;Q!?XdB3`VX@~Cq%l@LRx<9IS!)ke4GGPObA0g2vFZZmZOO!ul( zsHXbfApVO#=7Obtwnn0>+H|ZYzxI+tfpd{&IEU}xetil0m|HHJzwKbGde4P?lbZyY zWf^BHh4LeRa2R#kEptOhBBv^T)fKmPOmPmU!YZwLp)$>Cfom4_P|j1(G()z^0t6># zY+Y@JLV3;KZbg7W63z=cVCIv?Y)=cj5PDEt6hkOzfy*IXJA!R7m ztI4|TKD|P>7UMY@r{!s>v#G$+_~bYA~zBRW(h{w zzQ2cZ5xUZ7uqQ=e0+~Rt6O~}u%}z!yhy_C3UE{hRr_qnM4)=D%{qR} zj>8J3krd2LvP#B@J1g5l2XchJxg#gPBGu2m?xQI7z=)AzN*?1pL2d9(S_kgyvPOv+ z%T@tA4`5+;vdeC{`Wo^f6oEz*bj#ikMY2oe0e3k@^32zriG8~zlJ z-SE_J?LD3H&OPHR|MqX#buK()-GpJ2*0?f=7awior<#0-7^#w|uS`}~Kd z-hpYR+U|F6Y3PUSaLixNHzyDk|Gi{Bt{r=78>-!10jljx1Z@<=$v+ly6*N?0^;W{Ed5sHiArgkvpEvID!AC+^}#S1{RAY?%0uMCv7yQPJ^O zrnimmb!TM7d)A2VgRHQ$;b)T~p%n@D6o^B%i?b{C4M5BrVYo}WVwJ-82C8WxSder9 zj*^ka3v9~D=@vyZdNEUPjBbQB8IhtMbb1yN@2*1Mf`hZbt?L7Q#GsP}rS>z=Mexp> z`T%BUT}+7j4TG6H4ixm+mvX+u@5$?Xzqfpk&lQjd)%3z>*D-~$r#-M{ASPlm*@pZK zt76yb^LzokB2Y^l)?@~loNMT)tv-^|NK9gFHlAcw`5mc&7U^Re5#?iT$f@4GM!DLq zUS1&*=*eww>Jzn5eIZE;wbY^JPo5U4x`17*^u;e825sOHg5|1)RL{S3lK#tyx|5KA|;Yv}2(wfS#z z`=1;0|FMnt-w{jD&c)W)>2Iq_Qq;0T6hQt2MQyTX1EEl*QMs7}yl85A5H&KCiX?A@ zTObWC0Z>gfr88bxIF9g>Kq?ZAx>?cNqm!SaR>l%CY+K1(%Y2#S*h;(N7wC}TdsbRY2ggu3m3Jd31QM?5A&0h&wVyBg%d+Z9TV%fJzj1ZrCswrSJ zpQgxcY{z)(Jg-aXtaTf{V4zOB7-ggy=Ju<<=M;Li8tv8QtSgo$hdsTiVM@;)hpbK( z`>e%3gR?$0DpR|#;43+Lt)*X{R}>7V?-&Btjt@YOR=O&eNj3g`bWPDE|jTdi-Hw zNPLo0yehdYOaiw^wg`s9?8_{GdKtIyIo2*-ZX%@+F(K1SbhHsWjsQ6^Ogu^9N!VmT z024ArB>u>hm>pvb2<0H*8MOvO{nXBT%RZ-t2dj=JoC$bRdB=wmAqGyBNbM`R4fI&) zIC1Dcyb=;VD=B|rXljHJcuH}s4%%UNX_O;uSxhRaQ+s@%?4j8>H}Ld52=E^; z=Nj2ixG;Y)JU%K(5fMBSoIr z`YiRCy)K>)2KBCMoP24QV@s-aR5$!y;!1vC0NI*~WY)Crx3v63f0Ha6A@9C}o^Ty5 zw75C*wnsO@i2*IxOfcdDa~`2Ig1p^0p1V^+%4W#bkH0D9l>y z{7khDz>6g#REg!`(NLJ`{={-vSE-A99?Y$P9t>8|cC> zKoxCbso1OOH^~p+$}ZQ)J~s9o`N|r+{zlW2f==f@g2*S{GDlc|zEa9p_GyGk5WuJo z3)Vy$!SNbnv8czb!3Puvq}mx7Uw~I0AE7PL@{Y3fcRPut#!#DD*ZPXwAavVpJXF9i zYffpO=_JqH-%$|^+)p7r806dhO#j9F{#}xX{eK5!xxcb|3r_=Q3p-nRN4symTbq9- z_Axq=Kn%!1a;vL#4>h>~Qu4xq;dHVzBf0eQ=5@CCFez#C5{ibVxZ3G(v^^pcObcjL zj1K-N@BSX*#&1Sj+t^DsZorAH}6%(e!#U<_&<5_*(vbAM-6}?zeH#n10 zGWDfIqgQ|RAM-`p&Az$As}Fy8c3@5lleiN|4~flTNZ`S#(ga@)B+JfbQ3^ivmJU@M z9hePI%0kVSxPGz&@7Mpwqknhw|Hzp3x1;};4!e+@t*eQn*RnwQ zBabrEZeGutr}TcD8?-|LJyA|O=%qz5vW_iN?g0o9ApoR&3QBhf7wTeTGu9I9tbfmG z)A|jnwfXLk;RYJOhE!1m@`l2J2>G0g?H+J9h%oNB@{2oRb8)BM4yYXg&KDh(Kxa8* zwxH%X3?n5Yg&1HLsg4vq4TPJ`!c}!;jsD_tgcpN~Yaw(T=s}vS6X%3pl4I)5_|V7G z&TQiH*ucAR^AzsBglz5RMwqaMxzqRaphhXtC*EQf+av1QR_!5L@-)GN5OYnATf~y& zy50yK^AH@YNh|0GUN661t9HzxJ9?Z%c$PZzvu^c-pF$GrxL!bJ^W`hjA<+^-fwLkv zY7B-{#mLriKb?PA5k-IeY)?4flYXFSTLL|f&i_?h9z*M^lqB9R>yDB#vUuza9kmI3 zdLgHOk%g4FT7_he2R>`hAvO1hm+&nW+|>aDl}0~dH&Jv7GuA^g*d!Zqb{fB172jnS z;6<%Y7yPM=8HH&TPr>s`$(95t#}v_{UO}8$mVo11F88G2xATTy-rR{>AB>PTm8qS+h3ODGp+UG;;&5SUkHN!ePD_AfA?W)3tJNdM>=^6S374V6YFm*`F3VS z7i*J$Cez9`a&z*?zO*#XR4(HHgh(O?&RCLJzXsHarTK;Gp^Y3MUQenQ9VGO`mo5Us zz9d8mMGJO*^NqUOYCr=MBCPIbW_oRAAKkBizJ6Sg{bW3xlV>Q{!@aZ`u^>ODmru-3 z6ci;ps*H4x6;wS9!8~M6gouk+e#glu@l#ZntO+dbVM53gg_eb zQobYy({d%bRi-=OssK!=YuMrnn)qOtRljE=Fekp2k8$0Cqd-!Gk5eWxd`9BOncR-r z@G%(Sq+UNcwh^o7z0YWpG@Pk^?7AF{{S*}IJS?l0m2eHMophGQbPaA2OokR@t`8jp zBfV`ZXH0L5A3+d2{)d4+_3Ka2;>u0mPxVOT@ZsRLnPq|>1I|0oW|}wd6((7Yf@BWr zVJ}`zdNS% zj$Zw=i#DB-2@5Mk<0JA#pqw`CMre>(=zuJ`7&RbAM9h)?E{W_3P{qvU@YBE3uh6Q6 zq|S&jtThVxGL~CVk%;s*?G4t2s)Pbe{DLS8y)7L*@Pltev8`cV%MvZ{k#~7h&ovEr zfOx_(*z>ULQz3<7UFQD&AJwFm8e0v~Z`67H7mNM(SonWHoqt-a;$LdF-?r*xZejmV z)KSrLnp1`UjJAuni35(C9)MUXuQEy}2k0YlSmz(9VkxXz8#i|6WFSNxi5E-W5xW5d z00aW+XW|Ptcv1%mc?B8U)2VvA_3=_YI^HW`y8;;Bo1#{1iSJj@p0gM2f4~;48!-&y zIiMb@%`9k#%;>IDH*gRdZi&t~*H}=Pc90q_jAns3!(;`<*SCJ@LaO$x-*8<83~THL zrd12H-%6&@uw!@SF=qwpwqY}wZ!rd|8nIc;KI39+_;TgOXx+DNsUq<=PD)6?qQ1Kz zcmDXmIdQ=T`2EVy8{b6s;nQA>ja;q4#a8}Ry#S1Q2@9I)F>ny}u&{golSHwimxqvD zo8&4>)@cgjE6xj-XGZzr;teok@auODF7!ktsLRR4$h1i;I>o^lX_@rO!$v8g{CQyW zLP#HMktj^c>eS-8kDh2&>}ceJkyM^1vNMhU%&v2{Ma;6SNlHUc((ccR(}Om& z=0s}7pa%mBx!DYqBDq5qn z?DUt#QSL160_R^vYNYO+KW2l}^7v2Smm+LKAjG>J8*+aJ5DPi{ofOuf`11y`hD&)f-ga{*o;7ed`Gk6Z_ z{UgUj{D*`!j(8SXp^g3lGHrHT%6zJ89-WYmoKxt=BT>03VSg{2WC4E5K}tefUZWdv z7TVM(fYm}&Hbs~JEjfKdhz2JG>E4-EwhPaV&Fx30bLjawQjpk(kb?e}vbW#kkJb{f zk-4qsaHI0YYK0*}76nqrB;4^DUMWh6-cGfO``K*Y$ zk;!-NXlMIRkWrkH!umd24+*QyEel6AX=+h>iUZ>eM4(eFGy6AKIjSc}!5P$J#K)~< z)pEscckk&<>jDd$v_5@u71_<93QsrP-}>Hss~^2=dVl!(KoFKuikC%-k3AsNSt(RZ5~Xtl3R9)zl#i%3Yc zLU{D}?M3R7F^JS*%>H>*gdUB%AKNYP{_D1Fv7WBMEGWrs749=XOVpAVK}}~wcS0B# zUj{15v_zHX@zid^a@eY^YR>a_ul;lFyk9PH5FheaBNvC$OM#c(j$>KWlK5OV5c(oL zP{=#AiBf7o=nP1`@lly$D6$B@>l>5$DX5Z~xKBEMPW(hH7%N0~kaoapmRi78dsWU8~hPJ{9nmlN2PRQe}ol=hLrmp z3|}MtWIBtop%x>U3_Kdo=GaN|;;rao8 z2gi-dmGwKF-rB__^GkIAmrYIb__v0O<%;|vlThe$SRwDp2AP@>_=zYRMsgCf2-#o~ z&xIPbp!VJhR0~nc=-w)s%k*0gWy;Mai4|=w-KfG*Z*uK$GAmX)D9CAM?z+aEN>?#4 z00r-p^y|?JTk8EG+4UHu{Tsdsb}3mni{T5QXxaH+zmQaa_Ks}uj4G+q((1L3@aVGF z16sj$S|n(7sqYn6)=PRqn2g|kxj>f{)j-e0h8Kr33KjQm6d$t~w{VIx#ye>Nczb@Y zZeO<9#n=9l37}yTmR?N+qqLefk62^r6v0Y+ZQE-PCeMh!pnJS_lLTbW90bD@y@?N= zV=piOrYmhJGQhyIbjP|fPaSB7z9Y-0>3`@2Z>HsjvHNMM`0NMUR;@oA5e(%Xg~>h5 zVy4asC?-Vli`8N%R{e$sl7A9Y&iRF-BY5{`-fQq)rTtrPJ=uD0^8~90hN+`iU4Y^y zg00MQFu4uX9u%fxd|sL_6MwYBRyCK_VW&Q+t1No4;|JL&L7-@>xL%IItG5V39Cf~q zFd~F-n|@9nox zeO4Y=Rv~vp)K~C`oDJ9wKgSwKbYm~tjVGS{eG2ZipdP(LTqQ9(UH}rXs;^ijnqLJ} z4){%#Wk=A}!35;Tczh%5ru4#Afs_XdZa$Q^up&<+gZDqwZeq({SWs_ZD4$Vt zcDU9_xT5g_&cl&yP}vwnV8RfDF1Ha)&YzWay+ebnH|0!4Wj&fa&P=e!tGF-If$LjsqSzc zna3U%huB6|5XP9dRLM~56a1bHL8khviOiY$==Ozft2+%(596?cQrR_wptEkpXyiQ2 z-#Nc&wD_HJy@V>6w^HJo7roa435Im%$RtOl(BmwOITcDY!W*+%FuTZBuKN z9+tAOP%ne6fgOHWPSN4y#R|MP$4p|BVC&(5I65p!1Ye$v*GqA4R9ICf_h>ZdEnr8Q zJ_5U^m_j=z^#Q5itS_CgJWeISPm-IMUm2QXdDA#ll^ru(E-|i{WiRs@E`(q(NC^JW zG#*tOO-tnqRymwDOJ}TWG{LvlDOd2sZg8xhja(i(qj_Fyo1><1RwL6XKn8i%I(Z1yr2Il zguJKOkY#*h$o0Qq$iJHd=l}V*`gcd!UD@C}sW5Q)JB!%RgmPD2Xw+H(>SV89q;;^^hMRi_!T@`iV-I@cj1 z-XlEm#G~1(89lZNaO~oyy}ns`5ya3TuD~*Ou8U#2CBgLT7o*{(NT53a0emU0{78|W zS~$k>&?~+04^{_9pSuvQIj#jt{C}=^7FXPQBNRd*H-#xi;14(#6%< zuTx>&!jHi^aH!+9oqaa#?G_1LCydqd?uhE9iqXaMi|M9|(G@sBNz@hSy;t45+~e(< z80Onv>vWEi_AR}^!QA?zJk5U8kVf+mahTa|ei-0n#x|j~Jneqjk@ov=+-NkdnX!da z9R*gDvpgNCPQK6xQ)%(soH!d?6fq)T2RG2deLXZNU`Irh8aG@Nb#aN|=H&8;?}PdM zHT)*VaCXx9w!^%#fN~kf`hvM!vp`1&Uts}7+F7tJ4;9$8|*q4hwmTp=#zbDUIQ=CoSM2An{ABQIaI9Y3 z;`AxAZ!&CCYE*5uI$Htf2|yxrTkwEU&DfEMd*=m=DguRV^SG8MN+f8^1zfn0VnoZ3?G`${jZpm?Kh0{uhlHvqLZgfDv+{DcL4Hi# z%M&M-nzR+)OJTB!So|*7sWlMj{%KB(S$9076=={Q8v)u+bJiARA$2;6%Ft>mwx(ZX z;Am+iw**PFNSGh0B&LMhjpgO|Ly zbMh!-NGzYGktn@E1N1--MUm8KG&A&TyoUctAyE?6`e445y&A%&ppJglpH9;Gh*}oRgdYgahAhlT(l9fK z`vrBhQYjRFY8sr)-Ke?PDL4i9_(?%@bLb5P?zY#>spk>Gf%^kP-_DuVQf;wc3+Z;{>x;A`PNSb_4AD zYlE*Y0}Sqy8BJ9-oQlxH`#OdcW`tR?Ce!z$uv^24tj4dm^qO1aG&K$8Z`^SOIuxw3 zvhA)&hM8HKb&zO+A(yeo({5Uq9@i^d z(x|*lV8k?z0+1{FBZjku?F1Se1eGe@<)6To3p-)Pu`0bx#Pat@FBIvy;~a_!sb28$ zp(`RlL)IF8QwdbHARtsI>Jq06&D+>QQkNNaQenywpPg1_w-{jkXc{|XHN0p!PGxbC zx@V+IZEw(BnO|B!lKs`zPXL54w}zvMgQ5fry#R1%A4fj0g~Oy8lFxI)j5cZxRR!CK zQT#{hEJ-yaqgEU%H`zP==dMC#Vp=^p?fh>*w~htwDWFBJuVaR3Wq)QmsmK>e+%yolG>b1X@u+xpq6QWKl*jy8=eg;B^?$}XDq*OW3QE_IMGFQ@&($}#QVPdk))QY5P;y}5yso;=> z(mIqe4!Uykr%-+tqfrcY$ILfAW|c~rBQwjUW8IxDw?FsYS1RUM+mvv*YO^C*D3irW7f&eL1WU$_9kX!rLtIvg z=j`U(oL42;j-82Y7TrT8-R^iWztoSsPAIafk+x;C-cB^KvWv}}H%SW4EPhY6n>2{P zKOTGIeejof9S?Kr2rZpvl4bY_)toq^T}+=yctX}W*A02Obmd4nPonjd-XD6X%8{>= zn(jAp^7Xv!-{elh-SmqyT2Z;s$~*6J#;5{4hdK4Gn`Ys~o$M2pF^Cv^&2ofva`KJx z&Ac#d*4*uRC(42y`()*8lexTNd}tq)JX_qyh^a~*ze68i%e`o1eaOS`4fD;t9KCl; zc5kCG`zkEE%N*(5N?~?a-qjonW%*6i9N)9^*Dgac&5+oxNjzNS0_BCz3SO zpHM{kRotDu2g};&NBNO$8*ppyZJl{DcZca`Ifo{v8sGz1yeCiE-EnbtQfqzokN~Nd zaY)?XR8L;r%=PsEMCHZ9J;!jOImS&A9c1#|gajT>4VqXb>nnPwdx#!sfBwe4Ma#lD zpVtVKI7abQIf~g&?H(;ijp0npf}81!z?EeF#A+DEJL8shehicTtiIuM{v^AYe(rYp zMDr`Z`Tl^`J;Mhhk|+d27H;#eSgquZ3|h>fAa(npy=4prTpYjuxw50ry@@W989rJ` z17b3ia*7Zaq>PZR>5Ai5O3kO7fcQLBH&Lj7cFIWT;PO7uUnA#WcQnC)G&Q$>5<4s* zwwgxR#Wv1e(Us@>2fO&ZcLPioyeSX#7P!4#g+W=v^BS$aK9FA(J3u!abgBGgY*Tn1 zxR*i_P82wps=6&@yjtHaP-D0h#Dtk*FfwGbnX;lk?x6)@;p$zjCVK;9ed#`p%OW<{tc%p=8`y~oVur8#y9 zG^@s%fyJ44Wrd}#j7p}=1yCM?hKV@dA}(Y|5x=e_>eXiK2UFkk6py?@D&B8N$rT+n zHM&Nf#oS~G7BQWT-qaaHmblYGDq%N73H(3haAZ;;hqp5(Qpv;3NXjlKw> zJ}dh*Sr8Fw0c0{~-j>R0=na9uam+s6Es(N$XQvpAe1Lu=E&==8jQlP+u8>9btU_^J zA%Miv6i~pec6GL}MzGM5UXZJHg+;?YD*DhR(it<{HpVE zxznXH;0Cl?cvYt7fa6|WK&>gaHC&p^9U#*@>-s=t*R-3xV2<=aacno&(?VwG_!KLI6O3p7HU4B*&*EpiuluWZL!X;Tpuu->oGWgPCG8-}v zAm1KFz?aLceW+)EKhTL!37c{nzDuaHnLhiDG+PiefKSu4I?UKL2<`xhM7iq%xgGqu zx45@B8CP^=$Z)Q=U_j~tKro!Qkayc4SWWtw2wRyfy<&+PxYNQN~bZdy=mXtjuC^#k^9 z&{apU$p-iq6mSStINlWP2Yia>Dlvyc;WDqo#50M`nuGFpbf&{0o9+<#7@KGdm#TGX<8w-@RALLZq$b3IcK8#DeeHz&WT*QU*u!~Ady)X4{1Q6lur-r% zQy;F5MNBUD_pI%SlguEeFBsCX{Pmqa9hM)**v*I*t)=dzCNB`u6>d5IBRv0wZaH^* zi#Zw&-+~DSVMWh@^Pz$Yp9<7Kc zU0F6iz-9uZ_6PIIRd!2+EIg!0HLLX~W1QtHIo4a{A4(1-jcK~n-J|Lzz$sf!1gJ^O z35`9MMdN2CYYfj5AB;Dq$7u;z&(LD&2Z*W9$OD!%e?UDxnZ~K9#5LJUD93UWgktHuLT;^wf_t=vF=hu9z(D8}kv3nO;;TWDF(zjr^HAPn494 zywYr*D*^0K`{_%gh`Jxnj(l153_zR3Xf3YGysiK^QAfI%5^(s=mjw{_^jX3&Jx{m= zOgjRg+(tk={uQ6Z4|8)pp267#IdgZ$-n7Uhgu!5Q;Zq>=*-0mAv&fhh&Eo zTq*e7ZN_u4a~|Ruzbm|z*|G2!~2sNRY7xz0lUWK3<>PSl$*0p zM5oUkleO%czm_5vw*XRaR+n;CHsY;XsjWIV@O|Qj)XhHxX?8-kqiPswK0dI`wsbNd zSW6eDKS33od^ls02Gm-jO>8jy#Fqj@PQ9R9=_4?c2Yn;&S&>9c$kEI=(TGiL^RybKirT`*D~zEVbzGCz9ko#gnraO7gI#ZJJ}=&p-x|wPqYQ2UbLEAlkO`y z6+i-3zwH!G@c=Mkc#BC@lVUnGXp=dw-dZzsP$^J&*X~JCGkaB?y^E1^b&}dX1G5Pm z**$hB;{in*9Y`impcdE-;f(#wNF6U&$rp2e?0<(FRdEaWJPLd-a=jg3a@%`mT9m8! zN|L!zIjGwQ+dy-RFurTguuT|;C&}G;{fr?33v6;pRAtVV702928R5>EY)XzQIWE(L z`F?Me#Kw%hQ8T|CU!$=|Fh`HpJZ(SH(YH4z<6{|qWX>ufgMc{k8Layod$TZ(VnJ(zO&&_-(J-iUfU?C!%O; zAfsUvyxgY&3?N5`MB&|TaWj#qqibA1snxNsyiA@jRIW2-1vL2KytvmxjT`y$y`Azs z)G5l(n^AVbpt);q4^#Sk(PD$8_qeFuv0Dp4{ghwhq=wwJQRcp#wT)f=+%2#Ib-^c?Cm`3Co(rmyLl_} ztgMQGkh}8SA4yLh9FU;FKVuNW6D-UDONt17C~-$t_H}m#xlqT<<5L? zU$AbwZDujMBCEH@ESL&t52?(#{30$7s4Vz~rha^K>qXpq;`oeYq`h!1x>Ft9!emad zIY4Y#lPy9pOJZzD49f={R3FJ#Gd3bkYFhT%3JQBE4aQb6D^#_`YM5%-I{plwA0dI& z=NJdam9@+Jp>JGb73;bMkko9>`Qg7g8128hG2kiJx&Yw0)dnxaE|y7Gv93X2Nww9S z5%9;$Vkk#zXJJigS1$RYOyeFvFgK0rGc<0!hi@hX^+rotP6Q+r(0q`4+AfPAWF8gm zLD9j(p>e$xprj*ieUd8?t0OHwaY!6nOk-yUPl0qx#CKDmV1_OF$VUd-^9u7oM}nl$o!5R&u0hC2+dnTU&xdLjW$>o6FSO)jdwtvKDt@2p08NHD(Ob( z8AlQwaX%%Otsr#2Nc0o{v~DE~86+Zg(K!VV-+aRzbN0I}73#_Wgs(i>S&34qPl#c+ zISO)kUx=1rS2w2%p32taZiUY@+!wU*B6@XH^7vFg&)m|=997s~RKhii&P>hn3O{7x z_JQTP$h_`QXBp^5LtItM%pVMY+%RkJC66DvaiuH6(tWf4m)25vcv;$0g>DHx`exKW z>rie#9h>v=7rpZ`zW^}5&@!%xk*9rzPv5aw?!;J7_!+WY71{60snjv7kJ{T7b^EV1 zLmyPGu+R!AP{CHs2uh2vIhiB>Ufqe;YomUltFzr#cQ{2+QUdxeIh&1@OBI+3^Tr|z zEeOMsS-_$laIP!=dO{B|-QvPSyvaayGO{@wsvk47rEc$yr&k-mMTfAE^L6{J-i8B; zkRVO3;TU17rrtcVPu<;fv6QS5p{ABnRlojNMeJ9e?Y!^L$7jMNI%_^mPTAi+s-R!t z2+a8NKs$5*h+CE)#paeBps_)NUs|3rq#=|pZF@0l))M+`wDoqsSw7+_OqJy#XhrNn zNlnw`fLwy2uyZlYlGCt`wmolvthPlGBoz6c_RuF(ozIXQ)NsGWr|k`3(`!iULTVa zFVZ`G5<5Fb8S{Vx&hICB6DMrFoVq$+fUTU0A8d+p>SrY?r3vCJ63EeS-!tzg>IkOr zc=iuF?kCPd*0o1O77sNmeqX0ea<$s;Ml(aAl`x}$ap`5hkMQ1$9LttCzrdsUAB4DC zeN|iwI^2u_97M?8d_|Ls*rafX;sR#xv|e_>I|#w zyJ|;WJLB}tnf{tSJIRRFeRDh{^uh%y6IM!DNpFiB&ZP-9-Txx2C60YF|Fvzwg@cSudx+xezu{|#61?q_NLZ!yvva8 z{MHV;^?gl;r`VD?A`=RHCEaO>(T?sc1F+(;b1o@CEc&(_NS}J^l~+ zj~~$A>vjLX>HhBxlmEly=s){se>dH~$48x<9Sy$MXp~I;YgIPKQCjAHVu0>OK#yexKm8iuGo(B3l1V9! zRV3kd+G*u&T=T5br>*m5W5E8CzPWrK=-fKqhgP`7^pgH`kQVEx{ra@Sa6TeW4h z2|~Q3LrqsMXM46m8Gyg0?H)xUIGZN3bw3pYa#G30u5mMZp-V|Q)J|f@Qf-sV6TucM zMLabZCR=lhRj3cs2y<|f?MY~4`z3R~DxZSJ$1KSrWNu5Eu~<)CL^>XX2IYx z!P7DHx(OeF$Qbz}T&rRhx|0`y2VDgB?sz*>v8I=Ya8f%a6eLmIBBVL-hf9R5aI0Z3gHP3Eh6<3yKsu{ zjKmYd6*9>ZnF(SsjqPEt)%FteOa)4hPCBNoXHMWJ(pV=1x5feTiRHkd-umKsw*{4! z2^FYc0z?5riSnTlbnw$5G@;r9M)uVY8cx`=bd?0x;;cSb@>@w#`MfZ2Iu zqJJDA4${6=Q2nj3nqgWT)A`+2Yykc5p7QT=g+l-5*5cou^7lfSg{z6Ei|s!~V*fd* zq_XzS(TV-Z+8k61FDcn5PyUcDMKUPaDX%G|XuZlGD@B>RC{!OiXw0^;A%7Z4*JZBP z8L9O3!^c20t8RJ*Lrm9s2<(e^c#A_L*@hT@&)D(u=&kE6YwPMf$M5T%>L-FaBWZu^ zwJN&7I`|%O{l$FSp9n2)!eO%FzEn}&A?TVdSR+)Yj?^O^N>q99J=RSKBLpcM^zAGY zjH^+1xuG}4OY!3-WhJAe087pEJUU}0#KH_j&beUQ73pTEN=3E6_K$Wy4L|EoS^)~o z)6;U*dF72J;>;=jP@Mlq+B*hG8gALb-Ni23wr$(CZQJZZ zmd!4^x@_CFZQHK;>YO+eckY?Eb0_W>kv}pbBmZPR?|#-^d+oK3_yui^Wg6z>QW>!$ z@TQW%f|fA+sAVk!u-1J_M=)oqFw$(L#BroZwlEa07BzzF9|j%ItOE-vrS+s(tkEOr z5OOt&R&oqdR1&y8szeZ1N5?7IE&=-{B+lzhELt|>QtW5=R)9JZy(TLcuSr%FRh&K9 z7nnfyN$f^x!RJ>~g^C-lT;yl}S7zPSJ#_2C;nN9ZZuD0;4U#~F;|vA1h|_{WqGRcZ zRP;l9<3|NmJti4fzb!k^qw3xWcDis#F#5mS)ByLU0)2EMMrF`4^f>y@t~}MAv1W23 z83By60JWR6NEcANJo5a!97r8NZqA^}I_QR#+g*cX^St8EIgNwPLXDCV&tP?r)fL(Y zgHGmxBaafF{^wKZx{;9tuO>#aP3$xz4D1c8$-|Ad6#9BP79E3R7MtY+Q5`yurg1a~vJ9ee&)e#z0^GlryZ%c9 zOoFj#or~p%-{ddxjvg1Ervs#%!bV83LmIEU&%MrlE?)LsP@XH?6h-OF&^2~e?ybh@ z1U^4s4%H1*!N5MOcMZ<7AF@|AQkjo(=Wp4_9S=(w1mKE6D0c+-il6J+We+0O^kRk}#z{k7@TN_D zhUmf5zK%s7hu|-)>Hb*&$Dr%T_O?EedzH>ghu!R;NJ_7Q0F9J6qXgdkj3OKiS*&pnaK9ohsd6QXD1VMKLKg75Je&xPN|Jrih_ET>l4saN)v zl91ag^77;Q6fxw8)LRrEj=RyN71G04k2Ju+68vwc;GNn{k&t~L{Ih59FIi$w&tH72 zkzb$}Z-_Y0qk&b;&yc}SL4kOAEzAt!$cNZ_uYCW27SXv-o88|c?Cx&|)#qIDdhEDINwE>Z! zKb6e*j%ARQx>Mf+Je%M;v_k|zeO^@|IR>t?4DYrfaeVH6n1oUS3O9RFbsX`VQ$rYble zE@jZZzAqVDXN#nf$Dl=@xD3VDzp;wgwkZu(FL+SDMu+s<@jq2?Q25rh`2gVmM z0VE*@n#RDLTYPb0CfjD!lxwFA_BqA9kbnz~*O6&ukqw~oxjiU;xhUVM1u?j}VwNN+ zBWW&KrhJdeJB)K48gA-obmb5$b~z(%RDA>~`z=P*(`_9^FWHTjH-ycrAKY%(2t&u#E#L6H7$fL%IS}KL!bA( zv|FmLu~{v{!==CMF*k~HaVejJEib=hdvF__9rn z6z6mcsp&=SMO`R&dJ-8YsfC2(EG2U+Ybr%)bqKv7`+xz&bD{nS>$xVX>L#8zm6`yV z-G{ zttS21_9w%dbc@&S&gww?Cc}QS({7VC`)MDl50bZ>@|fhLGMry{nckHBF3B!(pzJ$k zGS6;vWwRB%->{gA|L^bJpHKa}yP;Uckeav5?192U82m(x=yh_~rAP2UKSv4|4#>sm(lF^siB*A}67b40P;|R>VRI2Ahizy@-v^BJ`f|~;7 z`&{i}Y|f4j8|C{vQ}ZN3O|^xf@-T6SFk!4}WFtFD2+ItBIBYLwPj&lT=|QCWq|B8V zN_LQ~Q9NK^2UU=nGX^nG%vdszASd^Ls*XlGl&87Vvwc0B(vKoi6z9(E-RvyTkjpdg z?50j%-VMf1>LFX=YDsuE;TS&{W?o;I$s_yov;A=C7Fh$4Z^6nauPMi@ogPqF=t6K* z1xTfm>|!?+6qImovPMCTH6OMEClRq2L>~kfIaGCpMnXg!#oes$&J~7`8`cxu+@{E< z_IgfrA>c|@hJmRhdK}q;I%^?eV$h*VSKGQflvoADnb=fIOnqI9aQew215mCFQE>Yt zR}p-V=dVv{|FW(|p`$*&B)m_Je z4l4@O#5Xi5j*l%32uvsBWi|4-0!=#m`XEU_fN(d3hZiK$&2=v1V`Y^)2a^P;LZP!u zf~U17qm91?3hoTHamQ-Af#tlZMBWPdaZ28VG9_MBsfez#d`wymMG;;Vm;7s(s=|!p zEMbv!GF;x(fN2PbahS$77SCSB-={uxGt>^VN2CDl?j3@nl72|-Pm|oAiK&A54PpX$ z3H?N%2#@Gw5K$?hd}Q<_a|Jd0F8-T#Dyjip_gBQN-Y1u^O*-(dSZ7U#-%>+QKXlc* zSM*Na4+19Ft_??8iuTKWRd%>La+vgpEALDIhXz~8;<|xTTuJQ_(Z&_}J zFAGrPwi^{+*P6H5Oh}&toE|O`#IV(A`lW@C1a0$dF&|P86@~f=OTuIQD4;wVpmYOy zmd8~2UF*>LT}CXZk?=>-)p_0YPfd6)8R)tY_t_vC^N!^eHA7sTWA*WD=-y-}-3+>< zss6S=YCT6ElECOis0Jcd}MHmg9R_eceCIB6H*wL?q@fC zI|c2*{O9}O-`NU*|8Wl{YiBEKV)nh>Kmy;mqWe};O~5-KDF#T~ z*^pWR3mWCOFa+pEwY2`PHX&DVNWX-ru)+RbyzLmqO`XtO`kLxgE~m?kw*%s*yR#4A zZjw<}>hr_ceqFFP3~Xcj;qAZIx&Tu7$~YmgMKf_dD!o5iU}dvakH?nBxyHjyiF9jD zcKCsn=+Y%h))s2gUWD>-x-2wIssw#9Qs6|iroA{)mzGm=zQa5QgKFASk+;u@=7ife z7flD^=nb(jwW<8%Tk{y_`ZOvQJjQBO6ZFJXDx=nX#~$0GMd5^re!;rZ{etYndHeWL z&_W-05EzgM(Q?6jyO}-0t@FEnKe!ZBVuEHrGwBIoxB3_=`hkSPWf{Un&m^b0BCu7` zl@pu;Y}+2eRJlAwb~zrce3D@^gk2l&n8Kk^n0E)h&^0{Ljtq zA)?Sd^Xmydu8J?hXOL*IYk1tsezKcTX0if|6ec9bwDNulZ^<+zFkYImY=qkw$c`c7 z*JkPL*qMadue#n_r&({^v|?y(oE}K*B$zM!2{hvu3=AIybMKLEKGAAX*7@x*uuj74 z?4-l8+4ltIFY31JgqbDddl!qWm~Fjl7>zc)G(VPW8Q?8NdM;MC#*5?2E(fUlz@^M!K=#+$OR3vY^`P6;tS=TIG&0PTU&AqlZyH3Oz9RPqWui)8pyt~c-zM9 zNa8u!!A8fCPK=|*sGK>ox$b{)n#pmVJ`!L>G1ZfS99$t^4rxvum!-deNdsK%%ChQIzQ>vxbFkDe!(@zQ7 za$w3b7wHA9yk$OKHnKattr9&qjV|iqEvT3h&qtBZ34BU^aw!ete z`;9>h;>k9)>O(Ma?Q~?=XW`%{%_qicJ%>NlWC391?Fo58s3`e8VYRJ{fseky9<`+P zB@ANeq(no^k{hy}+a+#V2)(_3aDDN$Zf~W`aN16xqH*sD$1*fXR#Gda)6dlkUYYk z8w8Q%w!SjaiZ!<7wA$}>~3Y!BOELC}$(54wCcazdaE7c48R0ZD|M_WOl zao3q`10(pT1G%0mT%CfLmfY85Wf_Vg^hvpGIPBqh9hVpr1)XRuv>^@pF5oPqr`O)0 zxg~WL=s`yZ1{!sc*WpulFgp0bEaEJ^bT!O^GIRYw&36@oH)19!+;^c*^6A|%NI?bPKGiK;!1F|Zc6+=a)5yLh6 zPLMYDfgtpq`YvTgh|PEdM&5RBK>7(=osE}H&Fx%FMuvz8f|m7Q68)Cvj;BuC+d^eh zGAI8|Y06QS0~4-4_t-Dj!Z~78x7#)AS{Fr7uj;J}2PU4!SdwGpOO7SZ9c#x-jewTE z4Gr%oYV`4z6~h{ZLk;DzN5_(BZ`~w8hU8-whDLx6jyvd9f!6aZGy#BC8yIyjLnSBu zuHu+t%11qN)53`}%GfjdNUC<}gO#T$*1GE3%lC0%eXQ620w$wED3&OPQUP2At0d44 z=y%BdW9IF)2^@59P?Qe#pMeQ?99v_$Al)kjOELlvLN(Il?5OcyZ;_;R@>5hijEtvq zwZD4OxdS$ck5lTx4y2}}uTX<(^yb>c>!K4+M7TW}5pABC57K!?-#FlE_2N_c>1*CW zBKv2Nevue{BK;!672OA+EOw_^^s*yM<{G}Dncota->GQ+VK>)~gn1Cpctv8eDaF0X z7~giC02x6$i-KHnE)uSv=Kyqg!`QX!gPmDatpCRqoof#lftE#10R`_mo zjdNdCGpCoT*niMYx-9^54Kdv1o4jM74Ui)Y6RSqtLpBdkr4N(!JsYH;=>`MR1bDJ9 z_c@WW?!qAF0I{gY)T>TA&!M}B$(k`6ZVGp$@^D}q* zcKThTYhwA#bhD$D!wd#I;5DPA^atq7bQ7OyeuRn1ztHF5iP+>ZV5WBW68(xM@TTW~ z$qIdonTo%5%J9iD&(3?z9t?H|DEcD6JR??it4;qlJJ?bZe%99Lg`zM>M#J8Jky)0q z01Bw1mcerzwzBY)->wSS(hF2L&lg5fJo7~COh?`aN*8X1ky@eU1Vmt_&?2 ziL4(HqRa<=rz9PfYznQ~9omI%7RWxDw{a%CNZK zQFn*@I7~%=YD-XWZDdr%xRW!~kW#5XB|l^n3v91RXs!lYiZalsKh^CwO0xQxAag(n zJgct)4@~@oU((Axruym9{tfE=B^+3>GGveaEDAP097Q& zFe8&j>Q&%lcD4{~gHaCiVtqjDh!OMf_U4E%V)AIk_}a3O`Ei3tY|(hoabJ5z#dz`+ zn(L^2duZVy-yuGXx6g6RF-tM|B_xPZ!cj(lBSkeM-J4n1U0+w+uifjeh|{Qyt5Wmj z^p4-$MY^jj?z?shKa&;q-P*^uj8Lx3h_cC+$oU$}epDXS8H;0xm%-P1OP%jg?ZRIA zg_QPel%ifK++7o>p2Jn^`zg}&rl>$qm9gt8N4(58`%k5dP!=TL%+zSBlzFNYW6nz^ z$)Bm@pUTTvMp&wDP?mTupjf7BmPDOk40c;pgEh^jQvNZBcSkx>>38G#%&-DeW#9`d z39j)kqAf!0zccSo=YX7}PC2PUXw_`{#OzIg#%Y?NfCl@Mj*e_ACSOt9v)NOHaH~_^ z1z13wO|BwPk#X~eS_&wQj&_fIgJzhD=WyEp!z3o+1Y3d=xnY+NC{xDUtkl`T(KV#< zeS`A78#5Y@m~%Vjm>wVN(k8Tuzi9|d;rLDEnU*bjKvABGu;(X44Y)I zS)_JyU^p+f;}`mInlC+cUWLu|5h02PPE&8~AY_DC#Ys851pl%+WSZac6R;}bvL1^0 z;7P3rY_3d^mdQgyQ9+xpbCKKNva&ljyl6iOZh(;9nu6iTnoxuH$z+pQ;H|uQEh(3jqrt28TEYIzOsdjW=$O77*DE7m8)J_7c#JU zg4T7Nt-C&U5h zi-ksqAs$`TX2Vi>^r6F*V8ONe)^RFi_g7l5nB9{C+A{wiDDyAHu;8O28*dMlaPJ8J z;78?_waLe!fBbO3{LlUGzw@L2^YzC6>}^8K@E?S_j@3LrGGI$$cEUE2wPK-iAVzbj zwu3<#6qL_)R5g4p*|qRjN7@8zIz_@bLwIMj-x*@Y#v7$ zTYkP-KbQMGgVNPc@%t-aO`33MLykF{kqk-tc>rwQ&k_q7om55Z%MfTvaR>2cMdZ>N zH-hsoOtwW0l+CJz$jNw;G?pR}EoqGILtM}oOBghzuQY*MYwU)<8pqWc$Kj5LH_Oo_ z-UK3*N{;Gc}RyDcMO z^U&dHQ1=kn`@+|D;S6)$tR+|=FE#RjlgGR;KxoY&;Q-Q3zs)p{rJ<)87fwKKh3 zLm6xSCXBbE1a|N1pZO8q+4FXa`^6QY|HTyW z1k?EI2=g5%#yPnYe|#qvrp=chvu31NJZTg#T*1R-t;PI42MPDQjn8)j}Q)=`J8Ig+jCo zY5^)#fmo4(0GQF6v|v}tYoWIo{VTVH~iPKDz!sYl!-d=5Vgn4&Zsv>7w7n4GoB2{)TH1P?=9MTjS8KXOP z21m?YBx1=jZ*ck{v1`eP(SEGdeov=QQFCW8`QTXTVj+DtK-E`ie)IsN;yEZ++qI)~ zG^M46Sh=skW~rov^(kdg#chSnMx|`tI|l31$-~Tdzw?BXj=RYa!pj{^h__(+NQ&-@ zXyDNXL8N#?zXII1-ld4ic^Rf_i#518(yiABoiDWGn3Jlv3~~s5KomZ%;BdUO@1vCr z{q`$bKGiSxgzio$D3Lrh`b3UF+Sug-z9o{HzCZkukYrYc73ZehRxOBas)Q4IXtc7Y z0`&6FEid!nJ4u41ym|h4qT7}1G2B?!4qpB5whG!OIF)Epf9kQD((5MD+~Y+YJy&mL zu3A3(4K^ATH)y%#-W#2jGu!}+Nm--=5RIo>rgh8UO~brP98z1Yj(E^MNHU7Fq_!&5 z{koA`tm69K}PndPUzPI zMt>$~BEO9|XxSXK0PgW^Vp#_6Pd`0!h_}Bs{h3=UBYlAk&R4c5eNlc_C>`fE=jPHq z)O{4I>h$l0PXPD`LkFvnx)oHr)5}Mgs}Q92TFu7HK7H!$R13b8W&F&VOy_Xdncr(< z;L($Zyd1W~F(WH5#(v}$0V7Y;CkPq&q3BUF_$O$?w_(PS`#0-g>Xm*t-{MZryp|c4 z{%>Q@Z~{#)3dm-mEF|aBEs{%#d;A!K+C$8n=1?jA90^}kbH+gNoDuB2W^8>C!7uA$ zK7I|6zIRb_#t^Fd(eo_$M&Z*{;dhryD#9{xYyOvYX=()SELg-5X6-&<+N)}DNse3@ES(HGT*df!m8S^C?DY{+Omhd6X z2EPN)PZ}-GQU};i!H1Gage~O~{?bNEXXy~wQQR!h_|Y>kEpr!mN$lYwk9Ux*3I0GJ z^A?q#DE|F%FfqtEX*U0^iZ zCIh~M)~_z|)(ZlS5sM2&XY5IKrn9$k30Lc$i`KSte*#hc5dXdzE7Qt}|ATk=={d?Bt7`YR3t`%i+YFr=tb|x^8wWOtDrzj8L zz!7yc0XP$=7voPQ4X;XTYas0q>fMFTsz732CMAiyX2H)n&K1^DvmJc~?B`m`CyI~6 zLa>UcEHAqy?RX|IFs8EMaRx}o2K)vEj=)r(BwfIpJiKI8Q2;E4{t^^m2F;nZGxyat zXkINxiWc)QH6NjDzeE0Gh#WAADyO)VKCz&^BLqt^mDO$e8SQ3P=8yZtcD~X8PMimP zp=!a~n|o?MgrG3b$Id={ZI<9Ob8UFAd3!F-Lu}_~2g2Dy9D?ga?dAD_Phi3NpX!E=zRrQG2*y zSOM@-v`J_44ww~G$bLL$Y{u$Mw?vWa5lSJ>%hXfS*&@kU+#ld2Z0OW~zzE@JeTux{ zGE#7dye$1DD;jJMgiWjmS5;xV!LQI{>7j`)h;Kk%?#AU*RNpM=(;&_uiJDVN;tB2V zCDA4=sK=y-*rmT1O)G(a(r1|8+YkbKvU+DkYEMi{kys2NM+;B!05DM@U#;|QuQKb_?f=bbChv)`~|H1U~`^elc+=hNcg0Kbarsl8Y72{k z?GTGLU*0= z;3NJUq5hwz_X_{773;sNQx$6e80n*bWin61UnKJvit{7Gvve%W+Y(Y7%tEPRYOZ0@ zs@yw!S<9}R12$v|I=@x?yMOaLhZC6Cjr81OF(?8j@jGAfUh;g++|qT6>X~2TogTTq zXZe>~94~iQdU(LcfGVP>_Scrwe%eT81LUi}Qw%VB;fymuZVK{kQk=AV;Q*e~=Td+K z&V;*M-y5f5bI}ek&e~0`Y=-uTv<1COy`iQ;5FmzmoSxYGa`IO;0qe??zBl#0^vsmg zRuUTqX9$iP>Dbshb$IznqGa@iiPSnB?uh0r>iR@9gl+IT2VgLsiG~`mSsdYzuH}?< zU;7e%Fh=P{@+2aV+PMd-YCV?{EyEv%Ya!K@vg3YuA}_m=QfQrRqz3AtpPpAmK7Q6a z(SU-!>thTlWSKhNu1+BX;T9mLA#8!+Ds79BX!sf(>d-~b19%r5wH}IouLL8l+8GEn zOw5kOfKJ2E?6)s~WkYwZtaqtwH@`YR-0@^Z#BeFN2;oI;Rzb+uZf()6CFGzrv%XZ* zR@5#f!h5h(wXi1nbR0kKTUDX}Ub97bEulMRII@-HfRq3fqqE5(gJs2|QZJGM+Ypn0 zdzw|j4L&o>pGJakO3(?UvIzrrRk>~DIvMcY4HppnNu4Krn&fH=17mIJSyB||$-ko& z*TH9?$q7Y0t%_V@W!zQ{UZhxy2qzsi2;&@=VFw#JXJ@Zi5_oQul@wrwmODOYkJ@4Vx|+STcQm$dE@Al@ue7rglvMJeLeLHPgs`x zQ%@0A2bA|fs8|RqB>GjHW}kk(VivN9TIF@@5iEc3-t&$eCTU$_Fa-9f8> zdM;UvyQf9H0vBUvW!s|p)yOP7aCGh~>N8^M3s&(67eApeIdKVa`=)-L#kcAra&}1T zlortjQ*-oPmr$M!-zy=QEB@Jh1_>i+7S^9RFp(d@R7MPO2%3xm^Jc)#ccW0kL0|Dq zR3)iM$Xq3|Hc*cm174rD;^{T91QPx=L>NRWC{D}o7f`eSUpI!IW(iLg7l98e0uKRt z^SnuEVfW|WP|~)90$t)uWF11YFg$W5?#g?8&7OM`bIS`2DYN3Hj|^)r$}i^yR&#X@ zx%m*(+Q%Q@;Y{Ud8JD5i-3Tr|Y1Bk$r$=n3$3F&aerMi{Vs`hno}b9;)@8aaVGR>$ z(Qo#he4~`PQN;Nifc+Xzc#i_pQdNT4+4HM&fVi`dWjB5BI~_=NTbT|cYw$-!F+|{} z{5G@+m8e5!cpbag!b+snalVc=hx%A)WG$wW5i?|;%B}*zD2M>`Tua~%c!8hLSyEDe z$nwiuJermSoPEk?-@CZV$6T$wnPAk~WNCVNa=9iP&GySe32(J%?XE&f#*kJIXHXL` z9j&lpUw79(iZ_pqh!5}gXg&GA9j*Tlq*wn1ZmOABn3?};3m`K=>pL?8dFX2n%4%#> zh9*F*eFn<82A=q*4D>*O#P5Ps#NN4T=~aRY=?z<`SCeUnnQth0GwurNO^<^2 zXnZuz(e*OLVdne({tDBrL`}jF`G#s5AG$37B*Be6NW{&07#6%jOkFTRXhdK|U}g~A z!;4z0`oz|9HG%|aseQDBwR32q#a3fW*KEineL9Pf6{76nDJFE!$LkoSuP05q*Q4*B zdmE5WB516H1MM^a6VSvt0ld?32o7^Ao!BsjrE)1z2b;;zMY{$~<;SPo<{VkVv>6EL@3dYExkzKTA;ErD53Ozt65wv{Hm zm>N}vUK882qu*21qMic@w`*N4}8osU&Zv{zUC@3rm&M_I?YdlWz0;%Esxc`kc9JN>Yux@3@u~|QFJd>bAP67Ff z2jsX?TA)?EF4-qp6_)1A>L>JL)% zPj;?g_7xLCo_r@Y`Un=x;3G6<82-rSVcP(Cl)X)$PjgONGAvrMA`{y+%*`ppVak_s_$F)Tu9%>-W5Bg~-{Pf{0X^>dkLeEq+NsOz8-_($7=5Q%8*y+Am;V+zgd{ib5HIf)(mi*@%G5uoe^bzG#j_iv~y{z<2DTqv)A`9GB&?j8-c} z`NAm^GWC|62)LwB2f#=DYQm|=vMXusZll#EyoL?K5o|m!0Q^WvwHgxl7J=wU-PKfn zN~5Dlcli8-hO;rt=@H9w=7dvq_B&QwK7#>|h!E6r60|tS7Xg*xZzt~K@ip^(&+P!q zl-qu+32KI|g+Wsm9Y%=roUJ86csOlcR}L3RdUyybLfU{ODuT|yM<2RK|cfn6{Y{~B1iHy#ZZadS_fHIWDvA0hfGebpnRBzT4r`K4l4Q389Y(#v*;GxHy6!9PIP#?(sjTc3m{(NU2^P`1nf_v>>ULS>;jY1P%Ur#J<^ zPW`bzns<-eIiM{frD-tP!p&k)_kP8pe>?4@$9l*H3bxv8^~i0KUn9}42uIX~zD>(8 z_O5wok&XoV9Kv6j#?eWsMn+}?;M|2TTQPoU52=PLlK=Hl;KrO6yO-9byElU!bq^zV z(;(q8t4}AyuxmeIs#d{13S%`|W_9FrN)2!~E9o}LU!zVNKk|YE9gD+^AUv8nPUn~_ zAPBUyhcogV=_6UAh)uJh|u|`Q}%C=Iu)rf!jCu9}c5OwcVl*ey zfkj?A+eAy3@RaGQ1lcNA_fQVGl#hb@^)e%-r#i2;&TWI~!W;qA+m3>Q%d%&#cmP(O zF%=n5CsJEGq{$MHWPw|y!YP_Vdb&&UTUsyEkZ_gI; z9~FDPrHEMjy@<5uH0+Omo756HMEodwDJ&jylj?A+sLY;%wWZEcCZbs2#Dop7%v_WxA{}|qsJr4+ITV8s0 zF}pOaQaH8DL*+%ohN8Jhq?}YE(G$S`gDG^)D2Vh6{P{X`W9`6$z~qYBMy0cnvVI%4 zGUVF!{KlA9`j3F`k~E=X(Ds5gCkKG!1VR~v9&l_z&2t3hHo*}DxlV>M-z??>YITiU zk`qv>IWxEcnOpBwdYNbVvoao%`7@cvMu%)8`15b#IcNTCLV2j$d_rws0%9Q&<-pZ( z6e5_JMCdExV{Ttc&NCtql6qzPgwKFmEPQW=dp23_fRiS1%L^hU-THR+5XL3h;jbqA znCVIIwS)(5x3c%e2>(iR=mCrwE%nvr-!{;4d8gvs8R$c!4DDqMh%wUmMb)u?vtZi7 zul>!)kC9b(G^~4_5c#206zkz~HjVs`aqts=$Q3xmcEL|on3&H6)j^D*Z_A!U(qcdQ z>+WZfyt5V*xdIGxsVt4y|42p}s2CA9D@B#mOk?!#?WAJH^v_=~G(`7YaF;tV|1^fk(DMfUs1BolI;;IlHbw@$qL zAR_q;TYqD+9nd=oWUImOBg$e6`@%!qgT4IQV|jvu@Mwx>!}MC<)+h^#GmsOI6ifToQnf zWP{zJrQ<}DFv*U_IjDOQB06b)ps^$RkiL|viBDbaIK2fq)njaCwAo@KhHEr|0}+>% znMr|#E0{ujo2b3EB+t$TF6ie!4ZJNG_mJ+tGdyuo{xkpc@90bO{}1|-HgPriPHb~D zlQD4o2lg^{{&(!<3FWQ4F!Mal@pMU*K5++VgYbX{q9(9T%b|h_4vTB&hl$B-GUE>i8@KQKo7m4BSf%K1%cKv7jGJ}PuD6LQKl^1EyY6&c z^`BpT6L{R!h?|Z`_pEGJ_II>wR}Ob#q%TNpeusy2xX)DWQ%HV$hrqVH`-eofpDF2k z(oYO5zt(e*g25%_Z~2LU<}n=Y_x1+|qPU=VQU~gEaZQ=_i8NCCWN6tuxZ|$a>)4&o zCu*XUJe0ei1&0E!ma(|+erLWPi4Iw#_q-c|xX*x@szvGR*8MOwHa0+rHpneP`mm)Q zL?nxT(5FcD&}U6%Dhfz*SaZvmz@q9h4j-sI ziUl^3zjTuKWV2!Bc4C~o^kf|KTP$ptQe+mrp(NmQaqe_C%g9&KkAoII)Y0Yzf7dqH7B<|Kk4fn4g z8kP=Lj0-wgIH7}!Lsmv3ot?&C`ZjvZ9ln}2j`*3!WfyXfPl$cyrLIaDPdaTqi+PPK zofMmLimhvTB~d~%%4)5dYQ&Qf#ioQoKwptgMzwxO710R{m`g)OJoS-HJCPc|K^9~^ zzbDTU+BP`pYxiKjc-!W_R^mZNg#A2g7{_pn9y z1sFPNvrXBC*=($dk^^sZ;aLt**l2ql*gqd=T>1CeC2(+_6%`{mA$d@zJCmsi*ou}A z9uAF5izhG7E_^jf*&9UWO8S$dqbTAP?_wI7h$M({FB(*1XImPhi6dEs8SX$ViNRnU zm8<2ETWp3ofwo$OE$KJnql?ewqsJ(K+y)?K#CkQ?$dkq1+{NpEqsYimop+t9I8wa@ zh!*QjWkSAX#Tlix`GeIEkA!PvY%qj>o>cCe%A#X6-6E`#BA*QlFhjl}S3KCRl{0_a zuu>+$unJVXuI$SUBoQXpeYo6CZLY~8?MkE9dh3;h>ICs>UCsL;Ia*<^2 z2hhmCkP?Y7U*8f`CFqAe_Jg*OtV}s?l<5H5+H?i_sp%2TE2qIQk!L$aDe1hnuPq#4 zfx6r<#a;}NbD8XY5llDEbmagR-Oyf5y8h;qT~gSy_E`L1Q{5W6+(>3#H9yUiD7nM@ z`8{{A=~xXD&=wO2mm{4z+)=HZSR37Uy0$6EChvARh(Y72Ki#hL(7^Qb(X?tNBJNr& zhCp?-LlNk({R7K6VYsU2!Xnz6(No+FP%@+lUhq!Q@HlQ}{t)hg$!ebtn0T8xeSM~8 zHupwQIiT1DChA3vbuOHw>bP{Em=i-UN0gIgLs2n3VUMSmj}%4 zpM{fDVLxh=tNiz*5sjz}RrA5*u6?D2Pc-!uzbWK}FHV*f{1WaAJkUVOK&zh(ZWuaa z25I4tjbaJC9N>GdhbDOg$xz0PjDI%?o%3A28f}z)8)A`Dfqy5<4SmQNkt%Jce$uU* zANZW=@PBTxq#$ZA%d|$HS=;Gt%q&i?wzk%E zTbNs2T1Pv3AIgep(;AG^Ks(N z)~2VBV{-4X{QM_5q=}SmNa^&!E(#3>+ITQ)@bLvFGY*jal3Cz>7Z9Di`1nE(tJ*F3 zV>sAQHVy6vj`F7s9RV26iPM)Nc z4RaqGC}26qoCf@DF@~&)280?=|9JuYfzN)aQU;hu!xOl0%lUEXF9YIH!BUOUC_nYy zhzNS8CF3M*Mc+k{ZG3DDa76Cw>)#DER5zxn#b9*C&5(_3?aK0^Xy-W5L&4CS$|rUMe%>J6y`D^VXwfQkyR2BVshQTR<=;qWeFEje37(iW!Zn zB@6#3%U8{Y5G;^z6u`l8iDSXsgR<(Z4&26|wOuEfcW)lq9UN=6w)I}$j|FiOwRM^J zc|A2;_IQNjzl-q_l54CH#dn1tnW-RuF~#?zaHrRD%a?pkP^3P`dl21{>K&A6+)|h0 z5`SeO`)tbZ#~{=)oC@PU+dD~H&$Snf-@}Kz$@3XupYQtJP5OfGl|X9FFLOdawwLP< zdE@86TtgsI%umn2-$41xx;Nzt^+=1;(er7u8}NB2f`;g{tPwtIb|7M~LM%Zi5HTz` zhw4t&a@6P7ZO~mB);I3!&e#DG1|cWgpty$Hn?^20`5_YrY*0RHZoQrulnj#89jcTa zk^#9jlAFt|_9Ysl!e-CC2aL><=w^xQU?!$5ieB103e&bj3vuVSI}XJ6By)Djcme(z zmZ*=!a6S9ge$7GGTg)Cun>bC?LnyfZmVQ0DBq@)olA0;ka+!#lieh7gmJ4H@_F)=| zzm#0psqIp774zp6>x4@*FrkxPHbga|6huv_NM4Oh4N@gaO%v7LMz~7f516<=+c6G4 z%P~Aa%w_~q)3y$#9^c+Mzzs_2vJVyv zS)^k;1eJ|L){T}E5-CHg#bdsWLpFMY;t`JQDbSaHKwYZ-YSEn??M$3ZY&#R(>~G`L-uK?` zp1XIQuI_)jt5TJ&^{!rPz3cfs1y6a5viiL9X_kP8OtmIs<7{h7R<%LY$P;v)iG`dS zQDq~Na^WH~b1}rPLZiManh-1VfU?R+BBTwx8s^HiKUqEeJ1n%*XGN|dr3>?noV318 zl?B3F(^aR;Hf^;Rk>t+-!F`U7rpFr&6pgnL5qe9Z!RB*IFvPOTXW>*=B6$=`?1t3j6>o)o{{pM$TD=vM8wX_!DER$4Y;$->T1ILyat+GlB}n- zd!z=14yTvV@8Uh-{(ks;&E8~w20fLrh!4rWsbZgO3n| ztxY}&1wVnNHOjJ#ip;G7kTM9^*h!i_)wcyLH)!&?%TlPc40hVH3kd-=pByWe;wg54B?{dU?-X5fOW&0S7RU3`qJBg zGwUIBtQdlP+hTIQK+{Hq@CNQ3QT4+zZ*ew*cpYi|f|)vReY#*7`@+k=nDrxii8KD} zlE3gE>~DBb_k?TggnJZ^_0xs~YD5EG*qPCL8H7EmxsrCwyY!oO;0y3uqs7`p=mxWm z(YL7zJdz^z8JI)iS_=|P#(yDg&-v?@A+vAd z#QLe}hwM*MTkJSV7CtlDU7AH> z@Qu4Uvk{H!Q9C$Ijq>qLrCNH167iQz`x_sUdyX*=ZqY|-IB=+H{Z`&H5zL6J3RgQ| z+7<-B3ZQ9Av`#j@YvFrg5i%)9fZ1qlRRJHg8Qrz#g6|P-JoJE{3a*6W#Bl!ssw>x~ zyeVG%!X84~FDMcU9*OjuUsi*n;v~JVO&Nd=FyHh5gjfsc>yXcchg!EN#}%U+m}S{E zA3_|!afwx@5#bua_{5r1P5?DkpsU^SQEAMH$_Rh=jc+E#tR4 zSFZdRTPCN{J}_^KYsS2EBGpykrNY!XSW^|rfkj`SM;LGmqB%652jNXtZ;gV1399M` z-VMZshWTmX1ILN1D))J-(UzWvV>H3LixDKfBfk}*cLUD^P}BixMVXmR$<>qadLX@# zTL32xpV-|h3Jm!6vWp_Mp(Om9{Nu3bRA(F^LTQ@;-4g`Nnr_hsJ{`-$lFc<9I}#Qk%Dch}nyksqby z%&sog(bKVh8}1n;8BycZXjNhzv+vOhzgv8!*nOJ*uW4IuR4+-JTq^;r2}?W>Y-21_ zkYJ(qW6izDLJQuH%pohSWkUFN(=od?D;EqiL-|7*&$eI{IL=~tP7A{vQ)BAg3c8!6@{R?SR5*)q#g+uSHuu30xcG~m2_9A%HK?^m(cg>s z*fU3e7qxB86GGyjeSE?hFMj3IkxouHJX+hSGaWqIgsoHrcO?rnest`zHo*sJONIfp&Ifk=C-{-LIylVA~9u4;T2l<%{b z+1n5oa=4OyWvXDx6~8KQ3~Lczpr4ul6bfrPmM7?`YMBXc?Jmw={dgV~rs7Md%Vdj` zbe!&*tu}F1N*x9e-eGS1 zaY>5JKm-kLE+jsn&zd=%Y;gqc(GXBsrt5_RF{ZEjh*YBupl5Y1`#}MRJzL>pe?USM zPbZS5i+Jvc`srd?5kLdnjWk0c)ik9)7!+k1;bwVRpnEw07xv!d-K!-^voJ}*VwY6X}RraIC6Aus-TEh43c0X!Tlk7U>SutB6XFN#adNeHHH(yh4-CeO2tx zB5q-2ibd`Y!Ma^@=_)1P_>pI#6|Z%S3L#8davCL3c|cxCc}2uK9u6}p#zI_)@h=$r zYkcsw#yAw>*?>u`v7KDm6jdXkX^TTL_+?OgRZiK7k{D(|3}eXNC%)?wHt^w7!JZ*L zdixp$ddC@C`a>wPKQ%|A&xX5DPPz%UpA(k_B34Mz^lKI9;W03N4GB}U$ucuMF5xw| z0RKJHsP97_1OTRO*o8?Hi$YOQY%1h*&&9Ij6OS48R}?ETjk$<4TOYVF!bP56s$~#A zn>#1?Rktw#9`bQtVF7v$irr0C8e%QVm0Ug0HY)6{FR~Cd&m1|=JiU6JM%56rYFG^B zv2m7wt^xy5$jr*FL$RK1wTuy_LF45}ZXhYAxjBGNcBje-GrdN10z2Ma@H z=+HQ}O_^*cbyyvMKCLU~UyHmktTEgQ^|$7wW0kQ6HGJrC4;c{r!adE$=oXPWEPo3* z@S(IxCV<2ly}yT19_cU<&?YC3;eAlP$LsW~O@x8WBeG3pWJs?;W0Sr$>UunSi2n|! zUSnJ6gP*O{V3QIt^6ik+xc5Djizt`;MGPR>!+9)n0QB2^~LcsgW4QS&euv5Uu!9Bw4c|5A;{1>1CKidB~3GWoRiC zJ|N+z+_*)@UZPm2OHIb~s4*0kE?O#fC2pbt0P8j6! zIrItasvS%D&d9qK!h5X*%-sTHtRk{eYwjBnmhf0xrwlcIBsXGiW0=rQ|fU1x| zu=G1un#nk-cG??@8_;dY()9#HH8A{Q)i{_vV_~WY87Mg+U7Qn`y@kGfA_n-Zo#hEt z;=Q15RVw~60h4Y0)g3BPn`VYx%QkR?xq&a;u z{ow;bgB0Sex$1xh(NI)=EGH};G0M_iz65AWoEfjde4s6ut{Eb9DEXNXn!7WaQ0_Al zG?Yi`F!>}NIlnhBe_7L)6(ploE1uW2i_D3I5`stkAZIAHY-E`Gu$=K{D%MxOiUhS$ znQc`s)88uV$01@$Sr%o5dFp0Iw*hx*@^L9URA-cfYgt!bTraWvR;<_8&`wi$6k{`W zB>?^S^ywx3`iOLqH%=Qw-4x~QTY?2 z6puq8O57MUiNqY!5fjVd?E&1M{ie)!P{r-}0OMpnpK(nspA zn>>*^{Z?G^c)XQYdB!tBC|`?n?)^?YKNP@8C>;|#}6VLRawAjccAX5Nu;;J~#E}UoQ;NH#e}V>R~WaPU2^Jkg>HBP#M^xa6Ok`5Ss}G!K%ZjrBZvoR#AdOM zlTsuS%TdCw;7SbVqCb|Sshu*?7!;80mfXjFMl9;aXGtk!FAk$G8HfO)3OHu+HPwZY zQwo!k3M3n&{Io~+DEew zWqH9KrPc+r*iiaa*s2|E@8zduLl}0v3mu2&fm0QnON;H^-$^6ku`6D1F!d8$q-|*V z%tsgMD_@}DPXO_Y0(!P_S`*vwF%>BD0g~&J$O0*dOH0=>bx9u_`j%e7s-G8+XzvG| zi=z)tWDeNcd{Ul6qOG|Z(QEV< zGd=tGW<$?|aLdVx{dVQc>I8zsTpp2aFNjZ0G)q#PN(EBdkOg zjPJT9OFEWS>@44QtGp$I>nA~~E+IB9?K;;}l(oBeEA~@SQ-A6|vOBT*YpCUtH#*5e zLQkHZ%2$+GVKI35l+*1Lr0RqL3*L5+7Hg*p36YPEt$}Cy?&_}l^&}{4f3g}Kr5@xE zY5eHX6{F7TBqc3b^fpvdatVzr` zIDQAir=}lSeK*;r>IYtUhXccJP(0^MuTN1sNPF<;QQZantm3bE)kipy{SwlJ{HNek zLG&ItC634)I`uv5Fa4U$!(FaK{;t)d%)sf>Z)fF54ai>QUR+#6`ZF3EN8b653`cz$ zX9}%id|j!-wb~`Mp0paGTGw4QB-O^(7fpx`5U(BVg2~}%Bid?h5n@wVeUM(IR7YI< zLPb{wE~eb??e0A%8g$~S6kMHM@0%i3+lh+h^b9hsv(eGjJ9b`-77NVb3(-Y;Nt>i7kU-ozOwURBGjQn+foq)Sy+ zBaNTny|kvWLawmo1jSyT%fv2Rqx6RZE-Bw_AzsF2p8`buAbsvSnZ&oHdfYH$Qr!nt zU->QbKIz&qc@Dbkq_2WwmmDZM?3{XeW>cCnrIIn0r1}!!RE2I*ldDHXN_n6mQ+m5e zIYMArdnvn-^p$~^giI#G1hDGts9t*E)_Ys^@~WU8R0V;u1xq3TKp6ZGui-|_V%g-0 z1v5gLe|I9YU%7xLNt-GQ6=?`@9w*;eWZdjgbzvAcHf_p}xwBUpHZqO&6vrOQhC8a; zVD-n#IP~qHi7JswzNxIcLBkjeM{2`Q&o_UfUf8{_Tm!xk|78(RFqES_ z7#|2Ifc2kU1*`l|u7V|uT%Dce&D>oa?ElLhaJ7bw2ik9Jzghc+qzeR7Db3BuZ_@_5 z2HoWdaVJZ9^T9djOM87m1SD`vg+UJbk#6akys%u>Q(C- zi(i+y0`b0o3%~wuJn^&21c4`}adSBgW37-H$d9E= z2H}mM#e^dd;5*eTAh?S=V)jtye>k=2AUu!l>T~Qmxzo;c=DV1aI*5q=E~(swG-Az1%PgpVQxKF2CJpOZ*sby70u5@*Si7WCD6hU| z%PlO)OMW&6YdnUZ$6Dw0pzJEHN^YHd1y8PJbvbPp4p)7|5}TRD8{Wd#H}{8BG`}g7 zYE$N~c`Yn_wk!f)CK*|?&g}U{-wu-rS7fcdxHQken)YO^mXzWjTT*e@*eh;{-VZVS zmS^ftjrwE9ys?0lmJYIVPfB=XMV1~p5F5;$h`t5|olZvg?LGcny-j-OdfP_1$;*4Z z^TkGRlT3S_bI!S_JA3EVg{>fw;X>GmF=6(}AKR*}&Vkg1^da~D%B|&rVpD=uqDqPG})u$B9M~gvQk|xJNe;w2DVqp3Y@?GQR-kx`s_s zhQAMEsmz_$=Nj=l&ePl#-KiWbMol}mxhM@PgLVbtGQjDb#m?xN`vfp3y|lgH1uXq7xSYJrs}O>Nj<0!G@EvqSuyqF$@D)uRcEzG z+a*`6Z{S!vXyI2Dz@swZH>}_iYVUZxinkR*T@=syqs-`| zhmIf)bruXnPs)>-H1fv6!(`jaj?%+K+v?1ri!|H)*ntPS>1$cdtlk!9!cly@h%Has z3co{4--@FQc319qwsJnvuKBn!@Ff0F#(u*yt-Uq+9aOu*onf{$ZgudCaJ3E5XGXYD zk755Fvy}!Rs`^C4Yr=nJ_b-h6f!<_79A~pAnl_fw^l~fQm;CZ$Ts%NrC|~x3IcdHN z)tzxmo7dwWymk5va(O2eP@a#91;PJX@ixeF=)cQ=xUVU+*mM(_?c8d`ba6|D1sh!r zVCZRDr8w@fV|eYMD(xbut-ci~uYA@fz~qh6n8;Wg(m(r@oXX9x%gNx-u4#;q@9k)5 z@uD#hRporUcy;p(wKBsKX-VK{#p=W8Byu-y(1xjD-rDI#=)CkXZ?%H8y09Uodawy?H;NLf@U%vT}XeHH$0Y8~}E9w$9K4$uP2XKaEGt zvtoR#X9Z(dNG+{TA-fG*>tMST;Na@?D|~bKQyL*1du#Z)ziKv9%K(by2XArPr2F&a z{UY;qC`p~O-_hGN;N#s`hb+ee=WU74c;(6K_Pu5#$i_TryD|rzziHe}vJXvbeq(KE zvj^a=uyS=(^VAdD*}1{P`P{-;?Cv1r4k#2Ma`hxULQ;rtnQ_uhJ^J+r`y7%X!N%7w zsC8pMY;npM?{1~Lee;25bK&>eR+7E-`9;6l`&egAZr%Gsq5`yVamZ`K4Ma+(<%IS%@73D9>E>H#^`?MH4 z_KeU>!cc`27>Y)YsH6CAV~5J%U#`k_sipRz3If#(ds>Wqk~9dqd0czc2x#c7NTW8P zr0A)-!7P4^BJbSHk%>cK(i<8*@ndMhA4!TcC`!xqXHyU}hvkXui_#Trt5{K?)&?OZ zDI>z#QZbb(P>=}%NGKAYAMVQH%Ea_8B}&NU4TdJ3Rqu6U$d%S+<&MIza)wGYiE|{V znpw)-u42~nXayhIlF_opQWbP1inDuZC@R|`W<+YpwlO0GOD}aTR2clB6+p@|Wqj*( zHOeZ7O>Fwu1|9BO-+z}6Bc6JpWw`#OChUd9PKs{3jx$LBsnm{8;kvXbO7s11GDhtK z^s*Wxu8lFfKqW>cu?@SsHQzGM_!+dv^^fHJGz@`o8;ynHVr@-Y-cU{GqRen4IWjg^ zkVy*1P<1z3m|MSUV-#(g3=heW#9f1f7qIvU7CxH2tkiuW0Q?mSG#_=MhxBGtsTgezayA!L%RYBK z>}<66Z4g%k<}j>>RM*5Sd`}a_%Z@)RWAyWF)C-b?nO=ms`iS(BA!;?^F5bsqnEW=R zkaeiviryePb?7*Dnt^U!nz8X(^x27VE%EgOEymFNb@j2GDGw$gzImWBr?E4OCx-Qc z@uPhBN`Q!Wl!}6E-nr@f*oF0GzIp+={ORT)dognQ>OQ*@3A8Y*gHy!1UlPOe7kl<# z;0Z^s_GZIZm^xTV1med404ix?%A>z#)yPVDCQ8U4Vi+!#;IeJ~-^pRfVRIEZdTb{! zMOt|;WVk)+TOLx1LVe1(J={%tv2YKd!4P4|#bx9L>J#)g>~r9!;QQ>sR9YSNAAUx! z_`w#+d#)*mRX|TsOr>harcSly1U0w!OrB3|D>mjGE6_6zcXSk8SBKBVhdm$j6iuxT>UGmz;~i4(?c2L?5gzPvYt|5Dr;tJs9;eyh@R(EeF* zC-dJZ?&KUy&20bO2|@bbBp3gRC8ZDf%7ZPEChB;=rlU+E@s~ys=~}FBDJ7b< zQ-ut}lHf-DZB~o9PF`DKtXn6DcWi5Z27ll{Pq!jSa~#JR7s6i}zS5rAgx9#ov1{_k z3yc0B+%w6Yo5K#b3m2kTb^%c8WYj}$+zAGa+b?v1iJ2e^WYWOlK&RO&SRV(rKVI4? zthnJh*5^fEhZg5Pxbq>Jo_QnrcUVrubuKu#Iiim)MV=4*CRK%Gk)yTliD0Km*kh$x zmoyWa)ddlWeev$xM1k$4(v%;_GT;ZaCrLwRlTB-&PJEg@^A|?32ByFuD(};ja(6b< zw;eH7E$C0{7soFKR$IbN9QHpu<=I(nEx2(tErf#~>uvTR`8Bk^mNt_Nxaz~dRhvd|9HesEfJXmy%>%D|Iwr1|Z?fCv31 zMe!ND2Ck*AGMU(Tj`Hia>=>G$>`l<`7s=`>7)i*h9*P{~mSme8Qs#N#UiFGowk)_R z;3d?av7APi&<9mztUP~(*kS8My8TFyo_ry>SrEO0?9aNaNZZ}H?kKTP8*82iMvjVj z)|2wfu>Q&q423(4YwF#D3vd2gw@9s@L3U@R!j0Vf!s#GtfV3z2L~^Qf$3D0xR#0wo zTCSNeL|Pq-PMv0|u44s)7;<%Uot2FuUau@n03Ozz4Ngr0msjSflZRs; zSWzOW{Tn#~wl$Dl5|OfvU?z*m)qWqCFha`mY~bRFx#`4Ktk4%gAv0ZEhCRiz&<@-I zAm=gP%NBYr4!$gC+}C?H#&Cm+Jtf0!4W|P`c(7`aO+|zY>wR z25Y0B?czb!ziWk`pY?6!Pj4@XBkH6S88c@PvQN$c{lRpTp@6~a3ri%}QBo1@D%HBC zA=dV8&32+LbMkVNfwMNqq(mkC zVVH6yiHNZf4fZdryR|`)Q*$cZnFe*c-IWlhVJE#d#888*3Kq>tFCC_s8Y%J~EB2O< zuK)+nCYGKOy(=|%rs>XTbS{iiG2c@9O~tpFZu^zi~cjco0+xJ|yythmct1FT~gM@m1p^!7@wC-@GA%L64* z@E0Mu$bILZLNyweHc6 z4U#6%?${jL{nGGoaP9x|cOg<MPGWo`|Hwt2Z04=Hca(OI2om`Nwa|$xyXi%(gg}$siv2$ zV&>Dvz~Gff8JBP|;iy57=U}Q&`Ee$+^Se^0Nj# zGjNl6^^#SuEQU(_2NmH2#mr3-3IPV2kV$8QMK{C@KR@fO9vBW^Ka#710X>2tSKoAq zkI@9YLCUru%A-ve=ub%-XdGAybDs{D`wF(?R*EXvSw~m%fsE{Ui#>mmTeSUl*>^-T z{ee&L`eQ6lT2&q21!K5FfB;&GPbzfx#CQZe+%6U_{_xZcAak-NdeV`3iNAE!gu1CL`9#0H}N z^7!XkJOAKSv3RQLCw*rH*?)?-(fe;?hW{vmM=T%g=F&CaFfaHtU8lhemw8-p(w=R2p60JS*^E9y(>k$WtCO7 zxWOVTJ!BmpyI*r3|LyVqcoy^*fMAN1#-sMh+oQ9mYAfHv5m3EFHdhm6rp)!Fb2vV{ zKuuxDtaoH7c01O_<|JJ1bQ~J@!SR;vj>soo{DEO0jlYgA*hJHg6j&vH@qlPi@zDP&U z9ds70l|G%xOQF_NnI(^`>oBclqbbW;>4m+uz)))tMxDJYkds|^NCR%9GVV0!_?9p? z8vt*ksZp1|%OJflS`xP6s6V)}x^Tn8U^(_fqpsQrju)p#NUFaTr)RJx$Qy^tjXl|j zW$FPL>C`1FYA65!@^IzeA!&CLP@A-S^@EEkE5CuZm|(c$=L}w^YBK(OQxy*lr`&uI z2#*-~!*Ss6*3b7G&4las_^T6DfX5h6Q! zs#ZWauN3h^NBm<1GR=k2%S0~iUrtZdDD9<+1-(QV8-;6%rV6tJKYlyAc!nf&i-g<{ zA=QmH$Xg+VJd>JC-!WY6V>=mG_4+SGYN)IQl+XlEm@x|FfW#uUzTWW-iP*I%V$T27aQFNl& z|71L+&$q}WN-vxrNw?4r7r8o0prYtNV#eC7q5cb!@}wrJWw!ysdBZ^(Sx>^lZiUwg1 zQdkrzSRoo5_imx|dm2-6F%vRQhWJSXUcD3iauJVmEw2vS1I046#r?d$>HPfp^7@Dy zAi))bv}YcovkH&Qt~h!Lh=TzKS6Bu$v(p z6fbD<=^Ptf_;yJoRiI@q9}^#_07;$cllz^u>uG!u5}httnpjFP8=G^l+jeSVZ!UkR zi<^y{U*|)uVnIjfh5Wr=5_7!35UQd&I7f6{hlb_S5ju1-L}yF$r>wxp8QsT&;a89_ zD0d?Zx_l1vMVF4{8M%aYjpQb6b?lqmhI|xA4mAI6D*FeP+-5N$`aZ$cs3j3e-_6BW ziP37;g%h7ZDHiA#P5;5gxqSC7O3xar!*ljazBv`}F!KupI~3AbLl&FsEIw z@HK^TgG~s^0Qz71r=EbvI0nVnxHAhdLf<2vHCNT~C!`%HT#p}^mbKO=w!ojiN$kas zXz4pfU)U>74huL#~kGLxM7EWyg`vLz;(}D&tWvTrx zReS#_K+)p=&kvHbiIJ_5)4wv;{*7St?+vb;k)xxPy@imek)w;56Pdh&u!F0;sq??Q z{U7`_6`g;Hp-=P1wQ3vNMUUF*7H!LQ$Wam~W#pz}q9SxQh`(HG_=(h=tdsiEZDNw2Pp@yI3P3IO1bKmnKn%ZpHy;7Bqcp+KvQ}z* z-*^sANVuz-NU}j;1uIWY3X$~3VWtw6Bab=+3}D8A#BXEp$v4V z-X){_n3g^1czsb4defHA#$yCE&9nUJu`)reL}azqt&L3+LyILUH->K^xS=-JBOn(T zPGXCPW^22i@;pnx7;C9;7O9Kf3}eFAtk!J*x+r{fPqb;L|M@mRXvt3q&dz4sBwynF z@kTQYJlh?@w)YG2?IKSDnU5WpR&Mf=^$dg024n8SCIb*JjSX zj^XNDahqJgx&`+3K|#SX4VzA3zw0KZQ*q<&7`lg&vd{-($KB@|WjTxN1a6~$^AFz( znT7@0If zOE*~Ya`&IRYXz4FYCY4*vayp=rFpE>aph{gcL3wz0o+kBz|AWxvC4pClPQ z_6JGP8&tLEQg&Q%Q+8F(B1ycf&~sz+T}J9$^%lQ`6jkLx#g<{cOf))l?$D{@B$uU; zBq`2=Hv+%(C^LkK#~KjyEWKpGM+1*%uHJz*Co4iXWui5b?^iKJ*B#~)@z=wKnq%+K zhZi*NRs2$N3Y%H9o~hg1If1+M+(JLij#)sD%;`983Y9|!80bJ9poc{etmW`A!&PT) z6D-9*iIplJWt60rNx>^;dc6_yjKA{bEL^j|14PyGc&67jb-lag)Fj2uEIdLel=qK^ z7yJ$zWY%<_#KMg345+|JPF>id3B0_8m;4w5LI?K<7C@Ip3-R%bx+NE=d>%j#G<^{1 zo}hc49}Yz*r>9LpyN1X!&=r0Gur-Kqc=YNs!uh?9$+R)|!lB3!h}ka(u4{jy-Kg!U zvEla_h#3k1=;XnS3HzVsbweM3>96xdJ3-!{u1HqVBN7$4OB@HCtCb?;q=hNhYb6c( zZdo=zB$dNTR8M1#Z;iwR0!F=BssWGJ`k$r#0aBAY=E??L`V zWvj5PelJGI*JcvD@=)(?JFkA8JGLT?D449otL%})lOmQ z2a?|}+J`Hu>xh7tpn~l{W#m_vkbqPI{j#j~L74~&Q|jX6CY=SF$XyL+GGjIzfw#h# z#$slq$lK@@3fA;&&yHEvt!zTUULQ!N@K8K7zKMNi7@9Cu+2ed8@eE3>hXd+YRrM)z zW}@zzJ!}z!VK$D5+L*uUTTB_^!9vww`GnqCLX|K^;b!rz+HTQCD{#UR$B>)rjjpse zA3vI0awWX)y&RF+dl*1=+Xs&Fw;S3dW}si=Y@#I%5JS>UCjwXF@d?%{ttu!It`hL& zi#L8@d2KIEr8HN2J(~S4!yU4$XgBUj+01gk+?#V9>(;DrgB@Tmga~oCn@ed@wvXEBp?CJbDPUme z7>NCaC0>)SN6!I`f7!lts5|Hi7QgqiCz*Oo)NTGw`6gUOQ)KAV*!zJYA;5<;LS(Y0 zP1$OfaIP`2B235=IGn8`Wmav9^`a@bK1``=&JovLc`?`z9`wZGqM$9}_pveM5% zCi?(+JhA8TNlJf^CuscRF`uG{U5d3DGL7QDN-@QcuqTr0o#A=1{^G~nXwWBZAXt=@ zdda&O6p4JUnHQ2QVXO}zXAe_D-#E-K5DkEa(`a{*If~XEZ#s(>CHYQ))w{UTQAo{9iBr(k2=(f%gKIZ*B>UNd&3e7`{4fI|Q_4&DNs@2AHMrOV zL;Sx2Xth9+pgq0|A@ToYc>G__gWUh*JSaMunK;;+TDe#`*#CRUqZY%A5cC60^q3R| z2NsnvKUQ#r7Kxs{zUVIlt|myQsTO}$DCCWz_=!tYx`yob+r1C)s!0x!)K8RO*((!k z17Q1f#9IeiId=Ckb!{D;8hW#6=a9|+F}I*UN*>Jp z{=dh*U;po!0`NciX8w0Fg|O4N3#ysRcL}NDV&?d72}4=V22BXbx0`ou+) zYEzzViK+SILWcCO1B>_~Jr6x;6S;oy@$snWx^aBDW)^({ousg_xr|p9%Gw;x{3ITg zUX`ou+TVy;>gcMrhZA2lRa=5PHQuFer!1~T=M;bamG=9ywo#5_mj=pXkW~V=Qe_5> z*q2j|toYbRyzVl*QCFqT!L)vkABxQw1*u(-pAf|XG48L$nzBCUqi|?aw1UhaQt0TWKa%QnC0jWa}&U<|&)u3ik%#j@jgi#En1awS1 zJi1p48CY~8N8PkJCV{*9|6^#5;4{cP^j##T{?nnk@&Dlv``4J7*7WwkQ$zpSqUcP@ zmQ5tzuya$L(Pu7f?MV|awq#UA1x>Y?nm zXx8_dh)zI!xZxJ<9-NOt-?NyiqvW#@Wol#Q^%t;%-&p1wINwfx{EZ1PVpQ3Hh|j{n zU0r|#*ah+pDg=`xvz$uIQBjusck&Rc4=G5m;NCQ%0_e$8HMWExj! z`=^!{fnAs(EuW7VQc$y^nJGiBsb(F^XuA{&l9V321fWEo2M2fjii4Xt>Z^#zVfo!3 zQDP&dreaE(7&j?(_7|QzKk-2_v!+>-cDkd5eNjP|b5-W@dlf;KS-2%jJSZgtEQOfE zeLSg|;^@_fbnq-o%L%;Wgj?W;?q;Q$9D62~o0=b=db%7;J(hBepI9{QG$;&y#k}Tk zk#&x9=!KS$NvlaXd!-nAPnkq>X&o2gMN(WE{}#&oY2Xyyqk;Vj6fK1a3u2b4j9~qP z#iV}3(h)StgBg2uiIX|C>5GIU>|zo1*b$1v>r>@7_O&T2vb%QAbD(yc5&ok?&&pXi zvIYvu@I`B$#N{N>lsMakCE_cBk_EGA%?i(?8T6T%87v6%<8dN!bb?Atn*KD4ZEXg3 zg_p7t1UGZ4Q#cxaYwhC9cJW0Ql_Tafi=toEcR%r@Cba!cH~mbfJCCY?aSP|EG|s_9 zq!MvNq+4@T;nF#n>ZqnCb;j_po%h~Ja)?#AxpPc-rA)LvjJ7M%J9AAh2YyZKqzEKZ z5;isjZ6YH;W;@ap~&=QK7 zsn}OdC;?X(TID3M_|UimR5`0U>1v9qe5edVa!|cG3x({=t~}DDd$H7RbkGngi1Nwg z+STL~t1BGVDuz5~3aq4CL@ILf$?(RtMEx@Kkw-OKDI;CWOKeM@#mS3{rpprJ7I&HG zP6~Zaqyg3irz?kKA|f;4-GL__db4VaClbZlQeG8hiA`#gVrs#(Ws3r-;Bmc%rf`Gn z`wHXY+UZ_kaHX@ua$}3qRT`-XYd;~;llE{$^vQD#1Swl_8AH~qRY+Vh)#Z8V-A=Jd zYpOI}ZR8Kb+h%FGP{SSovDl0LIzJsT1ZFb@wjW@yQf{!Gq&%`XEsT0Yyx1fyhpg{n z+k3;E^#xOItk|Sp=opf3zz`%oP$0?Q;RI7}VBeMdR8SE5k#3qoEN*ClJ3=e~#UTdH z5xxD+aFfm*(7GoM8pHmVDYCh8EmOHmJaR~GaaxbFFQ8Aa>T=bivA@S2Iu}#BwTdu0wlWO`|GI~ce zc(#^4n=A$@`jf=DC0-5GB(8s_<|0}fWHyV|zXC?v#IAmM^~e%*$lf8MO?@%DA%SWj_}NQ$R!PWs+B!O{et; zr1qg|gl2d{l?ccA&tV?ZdIWArya@tF%ZmUJ?$A7^}hvZ4WRi;IJiLuBp8|#5=PONbGkChBCYHGBgetrCj z@7h*6h#z>27`CQwCP4<$Fhs5qVvUubNFz zVO{F9>PD^m;ku^Y{;O&)e_JB20;DFu(IuKsG;GTT*oH)1bPwpByUz!KiLj%7ydevb zpUp|D@ZOS47U(?FwDz9fvb&|bhPXY;nz?mF07^CLN~B*CHw$5pI9X+Wf;i_FxhoNa z+drNycB2xT&UchRI()I{oPq8NqgTx?}mWj|-Fb{r5`X#7Y!J{RiF-o0o?vfK<%c_NN#8dAb3f4gV@!(Qayv{C? zEiVq5y~fq(*TAJK9#QTeRa*^CiV(-^Z$L-X#JH}X0dMg)A1wug0nzW?ZpE#PKL7A^ zHT!JHI|n*GrOYvF7UE z?Alx>o?Pz)SnFr!enOo^ngR*lKCD3a_*kwDC}jQF{P>iMv*``uvHp@{cqMeY{8E4Goq0}z@VSO|rPLY@C=}3S|+$gLo{o$q_GntO5(V(n5>C=`Y{763) z52=YwV0!2gMBl$?ORZn?N z?Y_orPX)tM3pyKBQsYWOfiJA$fd02wPqHJvJBCeaQi9tXnWDPmMD|KNOx&I)U58ne zG;rqF+?H|%+=V4|k7a;_r=OgbSiBJbeTxql#F7G6Rg^$g9y)$+Ng}IHc?uNsoOt4X z*Qgs6B<2JRYaW3K_NB6Cx^WPOy-)dWML_`GZ

-$k&(>zOF)8B9`jI!WblQ+|0p zl>91H4NRTD(i~ne$=zp}<|Mib~@c3?WqYf+(P$lU<>n1(_ z510C6Ql{S%Dk~Sy|EHdOSXnL_^}DOgj?XrYsky2-Z@mf%7abDkqtQok)53BCH)GWL zIa4IXGvyMVGZXYl(@o`pH2ZA`HhqCd=7A(slyBgw)?J|?=KpnjNE=YP8b3c0i^U0` z9dHZbMZOYmqpZ6f(ER2wvAqSW1TN3XHTRhtR|)7JqF(+flMrg4~XzqAc) zrv`J2FIk5`-R{2Qadoo}0;qcjZYPi4v_tp8o1T zSm4R5ufJug>w13KkvbY z6%W>N{P;t4g$h5YVt>W{P{r490{P8NoW zW~j+FZm~+%F3RP$7ziL~jD1&IPJoCbGJ7<4?j`Ifoc(hns@FY1rsElMDd4PN=jB#&?sP(l< zN^d{j9N*-1cDjE5yuU~Lf!_>LvoB77VSfa@#nNPKwD^-Awv~Rt3@< z`t@qZE3&;DpGMQ`DHnwK;=H46tI+ zH+G+4YY|!p@*NclvdHOIamQf!jY*h0rYCIJe5inv8u~I!b@q*;(Ke2%jl|{T*k=e# z;o1`dZf*BAVD=tDKX-S~thgna06Z~Vic-<0s`s?T;DYd3n^8x9mex+?>!>VOtK67o ziD*y5FiDT{3ByYG$0OwGY3%@KQBOv~XPj)w8+Q6fNDcD;McX??R~9ha!X0Vnv*2=zvM-`Kn&%2 zX%^j*xKzmd(n9+IWC+r;lKBZa=4A1cy8cU?OydXj(3FQ{Q{YZn)}LVi2ut$aAOP6+ z6w%?oWxHhl2Vp6rZ}x3jW$I+~?|kaN&(i;OYVjX};ouk;e7>9n??0k^aAILKWjOpL zO67Qhco4Fe@sW-6YmNC@qzGKdiR$>aCm{E^vc}1Q8Uy%PPUqH-ch+1@U)dA2(x6?--(DPTz=OC=)u2ghYbE1y3ko;P4}YdA8Y*S< zShYqtWKcHwNP&;z&(?D1W0{r$pbJzBzY1v;n*OYe?_L>KaJvfMut6z{x z%I4EnRM$F&^~6QD7db(P8RU#G6D;2OHeX?sMx*}F3Z5(nDGv6fXZ_y)`1Y+fQ5W9d zDGB$#q@;glI{$wO#s5F(^#7nv{_VRfZ(GkRBYj%w4@&{ymtv!w4Bj`AiooWbs4K{Q z;~K!$>ckx~o5bU-Hrp3=G)0;aXFH|#vUeP5JvU;&P2Bm;jlQqi08cr7pV<>nFbPX= zzr5i-ew(T`|9ZQvHvTbW%jr+pQt{cvLYKdk=ex?p(}N6B2o0^Nlx_|f)#Rz*Jg08@TYbK?pX>CVj^KG275hxz@3=Y=E zZ=zx_QHpMdW(;<}2IMN#7m#X+KwWD1PHL&6j9OV1(~O9iEyYT!>ZeRO+bKL6Dm*LU zTgq*rJaX@%iY$c+t*#?LuNwKaY?fF;c}H5e6`-p={Szp!VKf-!@i;A&s?7s0}&R&YdOJ2I%CkP$8bWYwYa^ZthMaE z^%gSIhZKBa692TdqA&&1U;?ameyg~}j8$%N*w&$xRja0QB??sU*4e=k2iyQBM18W@ z$i@vu7c~kNvuFR6gFAmL(+zx7DqCPR+LSYx!QL+qF%_%oM7kS%aI~YgM(bqDt6LUZ z5LPKe+l2vYDs)wrT0dLl1=FCHuS2VItmE8812SwgibwES^}7ya8t0?*gsqZTzsDE` zto+9>nU(u0w{0v3w{2|af{XC9m|e_?y5$&r0fy=#mp0aACXuo18R>b>*Por+i1+zx zf(S|(OGr$Mjt$eZR?HmyYkemQH6ldB^rBy>q8dI?avqX%x@SmH20udz^gMurWW-oZ zEls6k?$rVu5xPrYL*%Lk$V>y{T%r!HW^;Q-B++#?A>yq33v9uSPhZ&MnALfQK^7m0 z$ct&e`H&^zLq$w2ba!QOX><0Af$9|WaZ^Ob*O*V%``{6jp!?$)T*Ah1y+TGDeY`nz znVBcFQ!OG~6N{%s-srUks05%yY;1GEBaJY_Oo#1VuC8GuuO2KG*<9o1YXiYfLB$|4 z71xNENMD9b9*Hi77U4DeF$zza*atMQKMCvjG=umInm))7e}&xnXy1JodL=D|Y$_AZ zYB7Vt@9~!zv?CNUskwxLunI)J1igW~8#fy$&Jd$@b>`|Vh1Dc=5zbFC+LH8(QMVmN z5mO+@GdDy`s|65jaV7OQ)M-1x|B+Fc=BL(Hzq5(We^GAzGbd&BKd2`ESwsHs1?8Uv zI+E7TMs`a75a;}hQ0G7EbUGFPO;XXEXbE3JfLbfW?=GhXx*sk~$V5aUgqTajCEaYm zIq6iiDv_vTBuOMF_5N*`yPvv+(-2^?5IpH&JjK54{C!aR<4Ur*?N&p6~^O4Hn9?F34Z`}4~l(_yddnu)PgoH^9N zq=SPiErTg9GeH?_%)}pCXkE#KU8B+KVqX)f9|S4Td5lC+C==)41@u)|LHi|@C~g=4 z3xVDvXE+yz7<5yr0nL5Yj_rNh^ayVod_fbx3In>&Zt#91E%9_a zY{D1~%c;8-jC+#eQL8@^(!RGM3rKTwSzlX`y+4G`Em+Ml!h$Q~W5EE>v3*Uj0GU8J zIAMthgEfe^(VdNQcXp$5~9lX->%k~p>a(WNQ; z@uyLJ#m>-fG5Df>G;AI8JBI*MbyoSuf7zTbnWYsG{>DoZ-(F1rdv4M6|4oGdZ-V<< zg!b(S{rQ(RbW&JjxpAw}?854)7mtS`%u?;Q6LJIfGg~@#okCn{jO5yDxu7f+&o`qe zMzNQAE<{GvRT7hG|J7w57hlcG>kV}MBOM1zQ|k}*GMDBsjQgfT?a^LSI4AT2ft1it zj}uzPu)Nq^KIP|TrHG$iD{Z2S9Faim#jT!X)?b}quC3$LhQ|dpMuSwwigUFd zYORu4ADNnuWARW6&LdYEGJ$(X6fmyCT~*LrX@tsKyxqU=bTg%~VmS?Ap>f9i(o96) zLKX+Pg^YPBB{QOxR4t0L_3$#0BTF*%Jb5&~m>Xc}*A_JpjTkT@$F}4>a5mG4<#$qg z-7CYXkho2U&Aw9KKY@4;c(^Lw*!+o6pFAvb4)Y_E!eIrTalwmNt=E6*SLN*-Uh@S6 z?N0LIWzDiP7OvHf*VV?9(J{cfaj}9hkZWNTI}CH^yF5I-^wpYo^(cjX3MDZcny=qBnnd8J;GKpq zX{?@j@fCVH_?g{X!J4htPFvRuVO98sE7UB4>CQr$i4^w&e)Z5K>LP2>+*R*zjgpu; zZuCJpUdDBtxpe;v;kZFHBe?sG)$slcPXFi3s``H^?qrRu^eh})|4sV%Z@^9QOa@B{ z>1)#y2D(3ggd%+1%rn8W*THh|wyepbb_bYxh9pEMNYBT2wRJrcy`#8lGh@+H%Ln*AwbyVc$M<^_OJwswH zBEk?tgs3qWG)sm)mjVRmos25-R zHn^#u`(pw9s14P$#C)0Z!acgcqHAuCr3kgj(*nSpuvMgDbmZ|#GS~EP zz;1j(1B>xCpop}CQ09z5y^l8T(LEJqxA>-*;KAH271Dfy?jSs3;ea_lO6IrdY zywDBNXH^CxIP#e`7kw$RRz6Wn$}&~7^e@s9VL(URG$yfekbUm}mB7pmRD;Grkraw+ zfIIQ#3A2#zK>1A!dct~wpG zVB`p0MSeyE=>D%SIy3;NMp@zNJYZ&^A{TMjvf25}#0t`OKkW(nNpoHv;%62i-?9Wg zs^|AAqJNeVy&&RCdiW_4WPfNE5599^+J2U|4)GTWj8y23CWCi9$Y$ffWx?U8!!FtzG}rCtWipA9pp;WKfo7OU@|jmz*@h&I@{n5mPh z0Tzx%n0k89O=5E7^{&XNNhJxBGtRD%Qp@l-h_B!TsdYaq1=?!yY7cq6BnnmJV#g|S zZ&63eOT-&1_;2(a%jg@z(iEw_eTBB=pE`B!_|@M^A$HgUuDKT9fsr~wJY7OxJ<;KI zkPWXXI{T}0A*v02TI+_@1UB0MSt~4XwgfoekZkn_yWl>_70t(-l=4Kpk*gzM?eJp( zdl0o4@*r4%dk{TCzlzdf+{W%O{mHt=UDLm(I`x}P)OF^1AOwV@Ql7db=_+xxKf?pY z#2vZZUktc3=5eimiS%nk#h;q2JQ3BlfbxFQhOcB~nMYIQJC0YUff}tot{YLm37M@C zjtZw8@pO9QOD@pPIZ4TPH~q#FA}u8NKm>raGzr*2n3;S)D?MkNJo{m249R(j6?g>} zUo#(F!=PMK$G%|8wMW2RgCvc7QLuQ(2baFk=aGvc37PP%pCGJ`lL@iQ3%aJ*xr@eA ziyC_aqWOP!)-eVlW0*#m7@6FhnSUVu0}O6cUJ_A%r>i80|6D5nxxM81AEYc1Yds4^ zR~w^$O-zM~mezB!NM1BZV-jG7>Gt;a9L2y26f_bMJ9S2R_H*>f`ePDU3=&xp65Ucbx8TK^Xjo@|dg5`xvR4TQ5%fsvuUYz#61 zDnEhnloGrxtzW{-lhJ`u33O~`WpZNXSUE%ge%XGL($=B6hzj#?9aej>`o>vBsq``< z)uNNde2wE}8FyrQK^Eu6hUfBPc%F12O9f#yQ*#;Z7);RKnV5JGT+8aRJG2bLYABT0 z`V?j+zFMJ=`nK8WC5?5e1Hl_Mz#82w6~M#0Q#N|hw05o8Z-rVPe=n(m&0%i0{JS#f zgD732?fPRed?g8b{h9@>Dg&r6&QiWyx}5q=~&; zKQJm-Az(2uaw2qu{R8xcFT4Zraw^H`YkFbI9e4|37?k?C2HSsKo#16mOlf+q8f$Luan<^i_4Hk8 z+i^dSt*?HpL~jq*{(>`o7RJKo!Wu@sjyXpImNFd~%Ec%B#TXx| zZ)*`qEx`Y+e5s-eXYi;;#}Nm9VMsW15Ps$@+N}t(x7`REHoDVb@X+XY)_{#w4ULeJiABjZ$!v9zl+?h0MayP~g5gnu4>y!KriOl#Cl z^G(Zm=>E1Sp82hK@;tw2d7h_=?}F4G3^SO_wna0Ap)-CcVKQ@4fTl1SGmH2PPy~?C zU^@C_PM1~k6s)NjE(PI^uPn*m>A|p&oq6pJ%c7(qPdCrljCCW*uR46*57J^0ff+wL zEqq@|NpyzpK9@7}g3&Y4EE=GW!$ON;KTmA}Hu8y~ADj`~EHg(ojE{d%RoT~lPCA1| z>zbY4%3*-UeF{|MH{Rbv8nC|Lp9Xc!*n$D1mF-wuHea`;-Ubh%?(841Hm&O>x zt?E<<1-qS6x{LPM8mA;~G}dH2Df;+QBpYhEhfGp4 zrPzPxWLGB@tT3`yLtlcK&s42D=f**kfkf_aF8Z_;{S6;VzOC(n>s^EV3blEYx{n!~i$9Z@=aVA$PpyUQ+e{S{IC9R>SF z9eMjoy>2jw98vqAj4qiNM6}m1?5W1}f93YFF=*DEvXg01C5L(28Yq`!Gq*$Vy9e!| zz^(igg3c7AOEsz5vaFAU!xlN!_RDr1u~BWsdW+5wB|tx=hgD{Zce))M(! zwE9UEnrk;b#*-!1GFU$hs`MnVHg$%)LfecR$(D1CRwoOB=Tq-b^P$?laFK(S zXL*YU`KcXdQmkFPWRuli;x6JXZevU9jE)OFWWX#Cva)6jeJlDmUT-JpI(E zylX`vN-%4Xx6SmG+)9;{C|EdaNSeUme8_UkdNW5I_M?5>ke!J&;zsXp8M-}+GiCf& z;@pU5t2=LaDwSTDs5=Mk>axh0i;tqcnyG@qqk}evC9kxr>=PeK^=q5DQqxcd7+g^2 zD_i-O34tA>o}!_nGr4Ayad=wIx|a0>1#nb}SCxyBSY4+NpuDh$Gv6K7z+OzC#J=#5 zh$m3S9<-~3*@M|w9nZCWZc%dSE|1XQoN$Ff!Q}(gDOFd7;e*F2L4Tm8`X86EhhyRq?SnTq-23}|eo+zIyngyneae`>XbCUYLDGs^mn*eiy zk2It(H&VXQUfqaq*E-Zlp2Ox0^5K4ClvO^5LgA4hu|Pjn9~cG3MExgy2MZgJB64my zuX7j|jDTT$_9Yo(K@yl5V zQLZ<2*qC;YFFh^9$!Qp2jjE}cnV7(mo?Sxlxc0DGv?Qf+3@|q(lGrL!{WFh-Oiy34 z>e}=|IXPhK4}W(0+x?6BwY2W9VN#Qgd56>bl_8aWEtgoJw8A&-qSNY`6BXMCDVG%P zXEtr)5?X?2374R2unu3;Ym#gj?*XjOfbsWGMBH5W+ZA8;*=RIr22c>Tu>g)JXdSF! zG((PRz#hsw&=bDYvQ@uCOLj3nzy=6TH$?rBfeL+0xpWv>c!c;*gno>o6u*4q(zQsa z4m;;S{oQR;Dfp+<9+NE(nXmPF=IWiab&G^l$vTbxa8|(DDz<5OM{s3*gp9@k?#e4_ z!vwyQcA*S!YnsP8NauDw_*Fg(?)8}FuFy*i!d5ZM7c|vXVFrtvV}!CuNH;`r3J?Bk zKKA|skEFZvZh3&>Y;n?Gh;mbuI8tM!GcH>q`X}-CsvKANW@)OOCTH|POO@Zp4IdyD z+5;De*85S{+qTERJYSbejvD^y_p}r@))oUI4p+m9$MJlVV^SL$@ZF`+Kpa}gZC3#7 z)ZwVJs}cWYS(U4iBA~5^Q3}Vf`V2AsE6qqY`9`jQYOwv~*n^H#Sw;$Pb)#3>f1t>3 z0(%kt8$o&@{AU#T&yBCq|3OjyBlAa1j{iSuGLfvFgNc~Ekc*9lwVjcnkc)wl%|8V2 z{|Yu66}A51kj*V1!MjAPTbL(gv{*(Btg#=jFZrXq%G9E8rAL9$BG_s4Qj)PrTGoU9mEmb?)&4kx5%=w3J$U-ZWlr3X5eT#jLrQqQ(GEq`;Ho2t z8q$1A?2uGYsjNx#8+ERL%xLlyA^2m2p1#y5-5!IPtvB9KGDTh)mOQ9`dn0g~I~u^!pa5p!{8 z%dKN8nUyLi;5loE1&?Lr1^5+tvFw!ACIS6?Jh7<9$MeNkz*2ak8}zOAFRgcweFpzo zMUacIVQng#SHW%h4oITs1MLb}uIv!W1DmMbu6l#PDXJR-t?;mt;zi0<-3!>hkvRfc z_r6;KbCGhNF354>(xgy?G1H0kmPjzfaMiHo2K2SBRd#{h5kPf(P^HzvndaJ3%+&xc~;bLD#53s@qTL zyad8n3$LirJ=X`nZ07O2L@=(zpWJ~vX$K)_K4sl_;`Xvl-|4Sn_Yh6JC}xc1-zCzr z$KSmr?tZbK^3J`>r|Cf6>!5m5Kd{PsgujGsgeCq_K%Zj*vlHD-=p*(dmoE_CO(K}A z6DLz0}wlIi;)XO$3%g0?dxOIV!m0GFaXd5`0 z!a+e5%y0%svxQyM6|dVR)<**-p3+NrVIUc?APW zFgi{@V*>4}p@}$d3G{d%VTziBgOrO={mVY8+hDo7+WPI9;5c9!C*GSN(JT%rJ`=I) zWJ5O$NogungvcqitZ4LRzR)`;L!EjubuNQ=#=_SOG>vdj({w6+&*WI`>s|Q^QPC_D zkw>TKYZT`$6EW*t@DA-bpc&i=>*Lea-!RyqP!+E}3h~5+9Oe6;+wb;>!M@hWD}|;) z1uhm%sGUlQt=e=l@diWXGl;@voTR-jyMiIK{~XBkvvOA?wJC`%LLxbNtp_GzFaIqoh>p5En6R>JVBaq-%zr;O6`%5S3? z+OdFQCNBZ)m{o)}NcI6y_A8i?5Er}GX*=Cs_u2fY;j#k5f$gYbS>p3s)ldIp2CwV@z28>gsIfVrT?*nRrT>qsN;o zvB`IHMPY{f!r)75)J~~(Mqx2`Pyb%=`wQ$h4qWH@MwqHq)#nG^SEvMX$ zzoMw4FSZ}MUpuhg>Is7uyW#oHGwyCHQ&(GUzi+zPGT&@pLa}ltAk$8Ka{aFRJglBpQp`d z@5F>;q53;QsKC-W%~q3oKEfY+3CXhVWzJ7ZmU%Zp)zApC!4>e{$^cP^k9z)n{F5&7 z697YwzsMtv|sUupb zGddEp)JVD_pjsG#8;oUxN69ein$M3PVXE7Y=WiQl1avc%p@26)H35qW=5ZDdX>pm_0ie zEmj6JQ9tl>nMs8NW8>k1YRA}ZeALlQf{8$}NJfOCs%~>syyFh-O08sGz`i$GU;Cg5 z0{cR|$wOLBPSuraC-m3q0wNc|Ua}OwPtSRzzb!dpX!V{I-bW;J54H z;Wt_QSRNAdv?8krvrD2#;YT3QUgX-VT04I1s3BOFF2}U$d@C1z$!vXE<#ASHgUs0`gckb1Y$V4H~#lK}8r-9jwun z551U%<|Ojsd~)MYz@qC?u0kH=U~u2M;sr8eGzFVaF+fiw<{|(?>K8%I#CaFB# z6{|feZV%*BgvnQtji*5YIf_;2LL)dPN3CQ(Urny7t1M=~y>0~yw9ZD{h;BxWQA#dM zNWgeYeuC(x8Rofx^HlWE-Y!RI;+gXL*@Lzl-RkauiQ~MuWW9(3A@Vw*cs1l6lL#G( zwMCMsRCefJdqsi|)dup2AKSzV^r&pA=SeBweLk?sQ1U1@njXD+Fm3|30^v{AvOcta z$k+fv6DvzKST6kerK}pfJg5>r^KcRbkI(?3mw2^6eF-f`4(XUsM+ADDH-Gd8n%09@ z_2lz>8Mc1%DF9aXwdRmjZyWJY-gJ_bJeS(oK*p zhd%h^1L;#2H-Qr$+y3z09eCl*>O3Lt+X=6ysbe5O7tT(y5nw|K=CrU(&@~pTuF=%o z9Iv00RUB9ltZ!^4X=pZX)$KOVFBc?G9~e%JBNoUPm_1@f=_JVN?8|XJp@~5ak`F(T z_Z_EFrBDq;q2FKZEFAk;4WH}xC#2POsBbc5eck=+qxAJRa(R4kB!{a$WcC`yl5%T9 z4irgAGA)T{laN@1P5e?yONUzu^-}x1I3*kTY37{rD(u$n0VJdL56HzJ+N7Fu*wObi zLk8ipbLSWm&FFIWH4E-Y$v16sabpG+=TmZ7@|aYu8G~j{G(SrVbhqacImvohzQ0#> zPLP-jW)`PexR#NDee(oyHc#vBOQOBQ0@ibsI8*XF0^L&qvcUpz$oe6uE^LXLIG2P% zK}e}&Czfub0$(}KT=xu3IjjXQ6i`mKVZmE*mch4rILJzqG>&B=gNorIgUH|XSu~>1 zFLX+7vqbfa+-0y>p^laQBEAc=NRiAUuRXcqd|il($7?kYmiZ9vLb1NcdTs!8O~5D3 z8&6O7&2{BFX3@SE(ehDl^@#x-qUX81vD<ItzOYE+2=kn$ z&J9p^%nUxh)-1xMc%GqU!g-*CuU|G{{ZoutSFUYlh`czJs$A} z>#UmSqEj8(pi9-zF^>GVG(BakyPw2fW8Xgcl!>c#t&ruHy>*gS6P?sEZ2Ls$&~ZOm z@E(l$(P@aIkqfP%S7gbPZjsh{ULD2rl{6u(d9EvOu*-}H!4KzKEt5Z13)FcC&1LIc z4I%^k3h14hN1im3-V!&sfiO#ecF`Ixk9x9yQ~QD^j$^mqt_vUci5wh1_@Xqq*R*l_LO;#}gq|!u z#157>8d6Hpqf>s`5_m|Qq5q9dvga5afbZ#UC`%bPN+uc{^T09fw8WqH{K8*OpV{Me z<*FT}R#EC91CRy~Qb?uvLPg5>IqHCLLcPKYh}qeJfM)LL;#tzLrmE^JBx>f!;^6nI z!M!V;fz1*YyLQMad4dq7K{QSrQv)H8%2h=ZX32U-GWEWI_IP4TBnPpmuZtFx5#zVc zzey053;gT)Q@nYkOw1_(>7E6R)z9%~pF+ILDQ(>?KWkq1%1Mb^ELV<`v<-@)hP5f! z8@HH90-Hf=(?MLB=oYgxI+c~5yUn8se6|Bh@Sp*vwm+p3%JsU4@09Vh9h zZrsdAqH>mWS%nPd8wP?a5_d_%({o@&!*cimX6D#vL|tW^9?+B2NE&1e zoN8KoGH0Vu&}byhv{aHx6}Et-Rk$clm@+rlhV+CHXG~d9l31%+&yL&EOU%UJ>jDTS8}zTMx)NDWoq{7s@1AQElej%br%ViYV%^D<__Ky zj>OG@jG|#Klc&=;X%Wu+b(bUUeIcLv7TO&zL9P^NJA;D*AKu1H#U2YnSPN1EJx(A8 z2fr!lnMKGVP`h<9X4x6xOCQvW2A}0w;Vhr!RbfwHFBQx}hz@eg1Y6Q6IyOur;=+87 zC0FP-E#l?(@Mh;slCkJ8zsE zZwaTmq+d%hqCs;pBPpf$u_VDkf?FAGl{RyQZ-Pzo4%yKk31jR&+)Gv`qe9Vx&0IFr z*%0cQ`3Ms+>`^`32Q30JzvnXA?zS6@yT%-Ic*opUCnK$#ddI#!tL+!74l6h zIIv~@DI(H4>CdWi8acuvxO?H#r8L?U@@$sp{dwXvrj2GodS!9{SPhAEWs(o%yXSNZ z7Qu3hifmn&!A{6QhU)E_3x%k7_%;EH(UJ*Hoj`oD6Pd8b*c>x&TxC|=nYh&Jk$!Bx z^VH;#US>-W^~bfQ#9&F#u5}CV;MuA$SXh%>F2Ox$lU%H?a&6uikA_JLx2>R^K1Ad> z&*YjHA~NdB8`^q_;H)x6V{C>7nMji9#(Jp(W+Hk6OJ=hNW+0A&jl2E#*cTk3nrSH-&CVL6*tf6zb8vXm~Fwr#AadBHux2k8{n^Ri!li$ zDC@wki?8U;W=^gcJy$WS^3`>m0#BWl+XUId-cwOwQ^iTz!~lE82mmyWA~dt@KoqA3z@5)JVh4 z?g_N3i#sVeX8G+Y?5K3DgtBJ#S|HQnj?bd)J=nV}YGlzkWDF)7o6HWbT0&p-l%pcB zEh7`dOPpjYl_sPA&eJd1zMza3{d7j0xbUq9dHQ?WLqk=F`T;_z#iKw&n~oCVRXJX? zpP!o@O|@x*d}sM)#0k2tm$-(Ff(N3Dx_f9^}(IXTH58J2k0iFTzpR zQX4&}_7UFw#W&O*INM>V%{fm_T~auNH`~%(>DhbkF09QrA{~j{J5HZToQfpdVBYt%2CftP&L4UT>|GJ)i533E)VgB=;W=qqpmoaROzI?+Qf%(jx zpSjI?c^DlL{G2^x^*Qhy$IIAtG%a=XmD2iN=*srBoH4we0xzgSUpT=$Mn|hy)GEh5 zv7RvhPMB@|sZs7U4oAS$ zBTcT~0Di#bnT0T!60H|u+sNfbv|?l@Gsr(0IAOGXah(fR7R9?jd*{aI^%iyK1T=v0 zV}Z#LR%U=^)vPP*j)?E0_tcqx)#}!FoA!GF$;+lbwwx{vBx~tLkQ9W}RFxa53Odu$)v4h(JVh&)19NDg zSm+&b(LF4V<%*6L_BrvBUL-)1Yl$Z3!hJH{DI&e4_aTa@kOHS}RG#sRk3IxriL|Rn zFsw?r{?iwC$V^6HuL}Winw2kgLb`ZHe%O>QrfSf*XxIaq3?X1!hMYTPmJr#2lO(SU ze&MpY_LSBs zqjeN2>1$;HE8(GpQ2P5kQL^>>4U}$HbJt#Y{lp{3k!xrg^{Jf(BW}!*p+=oFlk!|! zvV+fw9rwd63LV;SZgzVokpM@TgN7c~dO^hct0=8u(&Gk*^sEj6!`0(gT{3K>Pw$nX<@yZCR3^84tC} zFrQX*J~P0jjgPuOW0BxBQ(e-zjQG}DXEq-o=%$`2NSpi71~pe~M($bOrw zE&=c2XTGhc82eJ3q|nMNqfpY6Qm!mhu2du~QKHCG&Tka{?q&06l#0vE7tzhqITSkc zrsT6r>lax8SpAh#%yn|dC5>wqRQ_sc5qO27>0=_hVM#sM1$|Oc3!dcQ@!Ng_Ohgl; zIp}L8(26>DkRAjPV?+-G*`SDKK2^dzYMhCji{x0K0Tr@cT^d2)(#w@n3y7~%Lh>X_ zq)czGd4d$ovj|tA59*gHd_Oqji#!j&N(F)%V+UM653%ntO%`5Drbz2flLG!21?1rm zw9y-jTIRq2#N9Nt3ejI zJQUq8h3yKh@oDK+@meZH_t@%XP1f)*JdHd}ieeZ$>3Vm}PJ$ww_GtPCm8%om)Yt)u zTBY-5l%r8(jCJgHBpBwT2wCYfMkDsKUE;qoyGNJCPcb$&O8J3YYvnb_R6a0*KZDY~ zPYz&r=RW|X+Y~p2mdo37iJxYa8ykQ1uf;=~FHh*fM9xEx3(a&u&yhfvA0MLhN37#b zzOb3nVFg+O)4~;6w@4QvzhU2&`J6upd(LWEBzY12MlZQ!!mC@ski6)78-G0V3|v3H zY$$%ng%ZP>XSsz$Z_AYG){1o?guS6qahSP)+(rmfW~)Dqf`Zf36>7r`x~LkPfaf^8 zjMF#YcVfN#Q@nER@I)4u(209{;l)6zQPxh;Y2seExxKv|tyx?tA8lQU<>L#)urprd z)LnhHh?%q>q5Qnd@DZY|$>SY3pMCh`Slf^ocL?`ntmf)fr2`x!u32sMX3xp4oO*2U zkCbg6cnws~^0txY|EWl=;3G0oISxGWs`=z&#oF2Y zF^PP0j8$#(iGJ6NW!oYOzsJwXd^AaUf zpWNZoulY4RV5`3GpF$H=<0{as@fXzK5|*NkUfoe(6HV`R;}s^}7vq!`oMfEb?gUr? z*Eu52$f>h}VN`bd^Ti>gVjw6S|0uqT#nJHEVwCEm(s^9W)A^ct2xM zZ*vf-tf5N3jQp$V3bSmQ%2(ollF=-V92{VS1e}ANuh+c5R;&+u#3N zMw0oK%>?=Y+~9XL1NfcMP>i9UGf!jMkyPe;>iT zn8y(r@(a)_q>(h2*p439dMl4l#{}dNxPx@ZxIT~e!*y;T0~bqDqmRK^450)wBn1=z z(2(dDvpAFT?ckuV!)91|4PkbE_uWs2Djt){v%qo#_oZE|9+ zCBbMSvvdYnG%j4&dXhPzCB^9RaT}7kSeRF_GcSUDY=oz3#@DVKP4;t!JlV_q?%`zF zUvM0hS&mdXx(W{zOQR~qt*iINW}u_Uf8`42uQuc^=ja=j8$-w5rLD!)jLLW${q26? zwV^0hN@PPG+M3t&EdV|4gYndVJ`&mX9}vdUBj&DAY4%zCRu&i>!U|dA!Z5~?QaVXD z#ma{)2U8O;`KdF)SUV=L-hWE}euut%m{G~fm{Utq;UYcOkM!qeX|7TtRxr8)_dvW3!XGAAf@DqO= zrU!ui<0Xz}gcLrQ&ks6tO#`%}4AP|o0yro{H3fvv2M+X^pAR;Y#oiQahy0|R1%f17 zO&Fw8pBm5K#3U}`mWcf>{yAS;kSK@=PhfX|RY65%UfqQW}Qy z_%n$d?4x;RQnA27nBLG~dE1eBcCt+1NRePd$T=odWEdb}QLou#ZDG|-yS1gPSgkPL?o z;YG*HQgBzvMFuvM!+XjoJIYb{rX|MtTIMtWJIcXPjntR|Q?a-r;#YocDkZAlGxSKQ3#%p0km8!GOP2jz6B7!z1cC`qVAKa4veGOo9z) zguE~bveiV`|E54q7`0^6T^h4rl7hBLi_OKub-R>)8vTKV**|l*hb z>(tJeM6pY^9b?uoZD~aiZ1y`@l&zlcxy_zIxN`{0iApoR9P}ZOvYb1B zC5FexR(Xm$@!5JW4RG#!q$2kN8_*6`;2aty*)QfRY3ZghuI8u-ucUGml6i_Lf~KMf zg&Of>k;5Fj85&a)qn5?P?H_*zI*P|>1vf^uHXp03UcQjdJ0DL(6Ua<9-&`d0$0s-5 z4_&qGTVpg&>Bcg(N!@;nVI0y_O9->f>UQ^^QQfrxYa4sjFCQ|eTi!VN;?h<-=6Oic z-E+FhUt#NxgCywjh`JsL#N21v+;<0qtU{7|hoGdi$K4qI5cdp?!iJbdo1~)W<^Rm2 zR^*q$Ge1F9-_x?8YBn$WD@(ndJ4hE@WTwo)_nGOTGH05WXV28CtJ*mo@i)MWroil@ z(gCJilzwbeyLmZOcH-)`Z5&!hypnd%IEX@isSQ#5-1z}%fJ@BuNFl+JC(`2ronzpg z5^Tb_6zLl6&Q)q1dMDK&od$A;^ltN2#0q%R;Op6pq51STDNKU(VuJC!s8nz`xGa3L z0TUQfU8v&0X{ z1N0;F1k=kR-=njTiLD&Dqx6=B&7arW0wFKb@=w1mMkav17$zQ>q=|k&vS%A&;v@3d zcV=R1FCYSGbTI&m%T1``V6JxCySSWmX8p9puy7gmK~(vd(+GJ_ZG z_-g6+*ilax?$~8tPIvwPM+>zZK)O_JnUE?rO^hz9|SI(vEsOvjEtZ1pj$cK5~E8$Y&8pc9=i@| zrJ8VYHy&2b^E&u+MYJ>3Sm!w2{5_{=23CPGv_RuP@LUCx>mi7yaWc3#QH_-W$$@XK z!Jdy4>4*MySN5U7KK9or#}Jpf_m=lW9<>jqO)YP;B0l?v2}fuGAhO4t6meF)sqbh3 zQt@iHc$OeU5>tn753Gj7U(TkegYe^Q_^dML$qx=dl28t8Nf4MUedbB7*jh7jCg-^7 zrk^B97J_g$1qKYQSPEqGa)Iut;(;X+Gdz9tgfDTkaQZf(QQaGKV##aT-hU7-AX(Oc zxlJ%nYS%*0Q{!F8cnuNh%I;L6HBL(}yZ5--#;r*&bh!WiFV@bfSrBeX)3sIGwr$(C zZQHhM+qP}nwr$(Cr%w0R6VZKfE~Y0Ue?rDetbCtW#UB5rQPuVP)`61SJ9p?AmX=ZR z_2u)HC*lUb`|3}`Pi~n)r(}w6;mKnXyIyKeo~hrDerXOUDUQe&>!SW5ZSOB?;V*)s zZ{B~Mzfp<`5S!h|SGrASB^QiHy zvkDg<{n&tG<>n=l1pJYdz@HlFCF_$6Rhtp=8UC`qY_GnZfPn?%-_uxn&_v-qbkS66UO98K(Q|fN-EQn0kaMA0am3y~ z=thPEMNbiWtv5}&+1apJT*7>ldTrzJ3L^to+VQb~Y{#bxu1f|B*`#Nz@sYB1)80Yh zR2a+rLNvYl^U~^vq=IhqrI`L2WxLdQ>xVij_dG~m7JTu0S&uvwQ^_KLqfWoKH?X){ zI+*e6FMOGJ-Jx}({(K5ZKLl#o7cCe~>#XWFmM_2f{0>ZM=;9f(?5TAD`H2+D(S%s{ z>w{l>NHjlSjEuat^~#L~zi?`<(N9QXgFS;{){NAA5`EZws+3{jQgl>SKmHOaO9wBQ zY^|!FUhPq)*zFzza%j@y{D|@|VfzsN4HuqUWzd_K~XgfQ;jGaxIR@ly*?D)vGvzuS43gt9>N=ay~Liek(nxl zZM?D32;@y3wti&mPBsGRBJ##5B3gi{;3`=4t8h36)Rc$qA!P@nkZnr35AN z+MujWf?BN82K!bnCl0up`-$vILRymZ9Asb_^uV}(d$Y5JBS z{ZMq1biIvIpudZ$g7nGhpm*9l6gC&dFQkkwwjHnUy-zYduiHGnqfEO&auIW2@WTYV zJLErJ-*w8t8N6)4ChW+>&IISx<|D-ulGg0gnuIy16l4m)%`@Rp_Cs++2Sy9b<>v ztE{t{oFX(}u;-dk+0a*AT0Y!J2-v&rhXIrhkyjw%KE40P=s=0BD>giG3G`Z6%I z>O!{O=Uc00xek%8tQCXkJ31#YCLE3Wk(Z@ zG%1kGT#EISN!uBU#>y2(ktBz>0ID2{1>jtS>l3riCRsRT^((BSV%UPlI=L4lXCgl5 ztBMzQ|D+<7vmHFgYELSYBKcz_#z+BM)Q3u!&1vYCttT{&qG8826+|_4FPd2kS6bmV zPq@%qc0@)_mR7=yg}*!WC^k)~B+*<;X>YMtm>tC^XG)k{D0QDpNm`XZ50@DKDLpxs@y2AJ@)7_+O3DaLDD#R zPA_999uq|7)TD^sDM%{*kTgE?X7scaz_VO9ju(vhiYJ$$C;f(A0Kn1Qu4Z3&KUU&m zQI{Q&c8ssdG8I~xTi*>$pww6@W005a?m(yWb$ld7BbQEUcoq@;wDO*4QYV%o;i%O} zw?S+%XbVeZqAV1bT=3H|Ulv;+ozg&jF&rMG_gWnkwbR;bc3(Rl0Y}6g0`h;N=jE~4 zC*slHN5VmxJRso-3z71IsN@g0(Foe5*QHhYQ4`(?{T-jyPyr;Gi8JouI!vXJ zCuS4RHQnmRf@J!PVAdR7#Um%pfNOsU^QfFf74^W?XAl7OmLH8j*s2Ap6)?%(pXA4Q zr3V7Eh~1+f_t)w`Y(6MV=1T`RBSE0%p&;Zl?@VSU{uaqw;{J@w4RO0{mKOIJf>@h} zEMdAW6t)Ptc4{Y-y$PoXbKcsND;}H88NA4RXi&8CfOH?mFFdV)?k@hF>-h*GfF}!a zf%AoUVCGz6a7(ca_YzB!I4%5V`QOY-$JP%`Aje<=IPge~$QMi|jrziWL&*_SL!wPZ zh}qRzR6`Sg(^BhtipGO#i~a*_l5)*-c2dLT&Bze?8SPpi#3a8n}89P)AO(E5hW@kxZuGhi(Xe}7Tvo(_}K6+XZ`?s|Q@b$UXPe(dcB zMNPyL#}l&J-gttg;n8_k=&BW1?4-b<+wTek>G3&c`o#?(>q>_s<%8Z*a=17M4eO$GH*uP?({q`?+uYBx>nNdm`S7tgc|UGbhfR&+;3d zDAt|DZH=BO2hNhAHTP8ZwHjA3c*X&J{BR&0l|;#MBP~7tA<5JjXA)eyqgp<-JHr-# zc2WF0PS*R65e3i;!&A>x{R`IqE6l<-fz9ws>ghwkVpx0+38v=v8g!d1gJ z%DmsX&AZCXk-QaKuMrpnmJ}g9W#XUO+>_rCuOS|QKMJyY&dvaT`4GFl=NWE-+JnST zfV7`Ct3BmVJPgtzLT^#R6ncZogJ!DoghlC5G{}t0n_ z%3fmcvAx_>EBYR7NEhlO0+oc?UI*>3%g1WJEgE3&^COJ*omIoB<8=9keHS0aPeTJ4tOr{>QU_t0XfN;^~?0{uvqK3wyZ8opt-#S z6o+le@@53?-}TUc8|+`U4yLsFcKU{9#IER<}+dP0C4 zSreF|sAwLt*1An;=**=Zdo@ej#8fgOrF;(-?J0vK*erAyRNLm=MPEc7+88N{Bk0i6TK8@95mIZ{E$t5WGeHZ z9e!v8{~?l)XUy|cBy@B(ua6a<-+YDMR-C_jJ@W$2ii2_1i*n3&c3vJ1$aVx{Frcr> z#0fKqA5gIQDk$;~Jxg zc;8r`f0DGhFg0UA2}6)qHhSTGI(GxBGTFKak1@(5763D)G65JZNrBq1l|^Z0LzK?I zJY%ywU6a=OD5~ST7He7RXIwll{VXLyL}Dblw;XH3GgQN0zXE6oL5=T0p(Bm@Cj!TN zsmJgma8vf!)Y3}Z+DG%P`Kie3!F&S5epVtbETw^E>M4@Ggs`PD^GVlkqeKcKlOTrX zZB-WHr0YJ&^~z+54G|jW!dP01K}xl)B`61?O4&B_%j{QL5LqOsl6+F8fqWi(@9NSt z#rH&irKyaIC-rS}f;o$Ri07IliiiYzatbqzG!8`?HIcuRXiQTD+BJy&Y9xb=9So~( zHS79sZfjcH@s{AHyFTUzoV?H$ zk>R4Rarbb%nqI4cA$7ob{1OhD+vyx)$nFrc}`+4Gb z<{b|AQU|64EJ@zllQ;$|P2YcKLahVzte*e2whLfk za|&$I{*9arh8w&0!nWt>PTRR?B&pmz+C@|X7v!TVti+lf?sDl&F~5g*o~Rb8l47MU zz?2s2iG_0d;T4v-N}=>+oRINITuos~T1^ z-Ehz?z3`LGk8pF(IP;)#jvvA1a9v)*=TZEq;`{57m!t@LH^#O%oNOHIr94yD?5UYH zKfAJP-XiyRRMuaQ88Vc7^p0RBODZDm{<__izUt5xMvRDIeio=bbqgb zaNh}&_h{v=sgr9@9z|ZceB8L>Cn_I-XiF5IVJ@FI1{88{(3n1co&x#n(>}Nj&Pner zv|?ob%ny-Pig&%fB$vOz4{;v14DJ%Esv%&*`=T{0o)4Uw&==oS&o@CpD;D<^J!(E3 zC1H8_AG%$w^PN5Bzt&WMu>Y=Z{lC~#{a4+R`^)>Yvicv|$0}7wH^n9FpR7(BjB0bq zgm}%3Y0^f3F^#(UMEt*t?B>Eo5D+7bc}a|nx4084KPUFV+h;8^zP!mrr3ISs8E~d=ec`meX%JKkO$zKA9aay$2ltOuMK! zl|vk`0%|vXBlhm#d6YLjei) z6`SqW2;D&&l6Igh9=Fz;c=kJS16dF(NxL1bl6@~+r6XGiZR*=SqJ1yOo0M{EOLedN z+0WB&-q;iCwAT?%%`cO>o9i@q>%imE+~`vz!B5=)iZf7XV?O)&6^tSbDcDhtM2O_t zdNL*Y!-8{8Of0z}2E((lapQr(`D=cRf+8FlXb?q_iCpN+f@x|@V`T{yI@N|i)PU9O zVM+v?s(LQknj30`8c~b2Hp5R!QnuK$h5_ws3O$kWjTm2vg-QrInV1??8QybC;szwH z7)EVW79@x5f1Hd!5zzgj?I*GbP#Nj5&RLev$BcwmI+awdAsDit{M+MLm%*v_q%G65@1N&ls(yv)jrlo~D z)3FlK6>GF98K?!zslZZG`-|Gy(Wg0%Q3<*h3G<>)8F4BYk=8TFKISp8*R;icSkhP( zMt^xQU>-Fsg|#|QVoMi;=4*!`$(q*xmW@CjESC0W(?2{7m~Bl`F<@UX*dqUfDF6=T%E40>J!P}KQv!qr(E_vTLjI-+B zwU^x*Z%%S5F~-5KiaSpRQY})+b`_mEjm=(?o^M$ZZ}~VqlPnmRlVeB^4wPS6BP)~_8CeEO#oEav9 z+)!w@7sd)Gej$%+nkO#Mpse**XXA+99O@_A64lSjh4bqd}v~pdbvhS-^U+& zviG1?2X#eKF-?oZI#s=kH-34lbQA3;E~k7oL=|Kl1{R%sbVkW3Uvg-s2)PR5*&vL-Hn2OBV`bjFYxE&njO`gSq(LqI4DY)o> zz!LbAXxsf2;8GrD=*n)Q z5QWLPAk{ARnm}U<20OXhR$YOx$hg-+WVI>2^HAiY$C*+}A~f~$e$ANO=B{^+nV~=Bch(Di>dbn+9Qo z=ZD9!E7dipNe6BKT$jf;{ruBu%h5->@sT`~=**hq7!z-sz$X|mR%yI<>a5Y)OQpMt zzRAtL79c(*nw8n{_^xS2grmEi##bXY+|#G|H2f+K{(N-pleXzWD}?bYkp>vZSRg7L zXijbS$2ffoR3J!};HVA%16|HeE+kk*P?x(IadA{F^i?t(B&0wmKMu}xT&@ZO;7231 z-KGO4g=>FXCPQ26;VGJ5eaW`x1UA_g_=^L?IR^h&_HLu~E$~H){$Kpv;!)op#@xi{ z-9YPG90h%frr%N)=|QOM8kW?>`qN`5yln@R^dM=KLq{ z3RGg{S_~3Lp+yej{6{d7N5WV|;}N66+pY`O2EauzYNjx0A0qReWAP_M5d|G&G5-p@ zm_kn=d+fTa z?1YyP7S&g`tdtJrUI>c)#G4Sni6${E>Q5}5SJKAY#}1x~K|TIPDzQ?+2QX&(xG|-D zqI*kP>9(BZ{XSDY*rf4rCFjTYxr3nNqH>7UixgK;`l@`;WOsjFj-zfh^cq%l=aicB z{P#Dn1g(1oH}S|l0JE{#$aC#N$DRt&3S{i9ekYZ!h9#s}5(CVD$$)=U22tjY2JPtD zV=_&>QF)~&P-K?BG5r{_O#zU5kt^`Og4z0_(c7VftngA;3! zhmb!P|Ka7!nwh2e0+>32Wilhi+UH(J^8Ev-S=t9^BlySSGC?FWoi(3DI9<6&g`vIc3I4r-H|U}iY0FkBD3{-+96 z|BW!PFP!&lfm%?@Alx>JDq=T^F9PfS%)Uw|;q_pL0p&Jg$F1re);22bp6$N#C2G&W z&JgEo$ZCvlIP5L0Ciu5C9&Y(h0>NNaYg(MC^#wg%&gWqQ;5EXaV3vtES{weWL>5%vFC;Ypfjd z`ydY$>0uwpKJt1^oO_o*XJ}GjryB9|KEXEi0P&(Jvi;Gb2aV*zUU(&FP`ZKvC;Hc{I(28WMde;K^brfR{e7)qLz3Yi22Q(X zx1L#s{(Wr^2k?snz&n(pWaJXX&M^Lc80D2u_cb}Id&zRSuk8bB^)G@2*NO50tiMK2 z2DT0#TRtZwBt`qKGq)X>=b)acJlAKy#O3(Q4SiFL8^;+!TLK2R@zPO=o9Oyc4>f5aHegfmK*3H zQv3C>Qw21fkPz+Y-k`#qQyxsWz!S1(Fq2rD5FtoHk@@r~hST|+pSb_}vRb7hDF*m! zS#yl??|N_T|HaPezhg&;RP_HMH~)dg%ITXs{KLvo(6s!^%K0W~7$dn@FGRi2evmVZ z50R0;r4|sU0-Hmji1VjSa5gKxoDN=-Hv53|dcNlj*CT)I!`+QRn6Zk;f87l*UUQtz ze8{@tbbNdM+Nb>E%w&0MHNWJ`!wGYSPt7LPg^o3wx;TUq-dfaE5d*yQL*(-adu>wMb8u*?fDY#q-rq%$HOYJ zrbE>r1#jRRyAFg;%78%$UnCx%E=9zEYa8kme<75*I7mcZH7XXIna5t49kv}&W$MWZ zQy`nD{ib*ZE{InkX1pfRvSIAD(9TlClBIQ4`XOnz1^(OfY*EBQv*SVSGt2NwZrUi6 z;u8+p)WYrXfPUb@GCi)kUp!nb9jK0xLrH$RSM%DS9+{{%0|{V$T}pGD*Uo#2T6F{i0g9J4{BNBhn!!XNl$ zF1eZ_03@LRj_B7~tEEA~2VSL=C@DKVD52$kITvXPoEhha6*x#>zYE|-Hh5#+swAN0 zaC>jN)ARHGmsax!;F?8#VCk2$7Ni~e3TEqE@6>M=G?h&)qAoojdMC!OLL@TV|_ac)C2=M>Nl zOvc4#@o_sFF_M}GH-ZILgZ!`tmPR8Ul(PFrfAxnk`ak$y=8;k@O`{CrnS1m3=TKx@ z9{5f&-{)HcS=%sOVamhwN-$wyFjm!epV*kJ;40yENu*2R-nL|dCOn61eB zEG&Xdb`(O0S#YkkGS(V8yHM0OnU?w{UbYTIgb;6YymvwH@7l!-JmXD@K{bsD9c^Km z^}%~X^?(K8(pS3S`mPT>xMi2-g%#|${ju`>xCJIGB_p05bEW60WNtmgmr++ z7H{|S;Yz1W@Nh3oUpNR??EJnLlxjbm6giSvu{QPjA3)Qy*vUV?OzR+cjV#r4@wl|{ zm_BrSo4fPg&wzVJ5O(|f@96*hWQk@RD#yEhMYIapMyWhQXcSSVpD7^zr*&>GC#K)} z-@MxVw|VuySq%ISpx1vsMqA#lddkAjw`pk`I%A&ZtZn$<00IIC0wW=;d>;6Tz=Ed~ zfkc6~czr~0R+bUDs}mZvRKii=Adu3v9Td$&+aDS#EA^JT+F#RYo;#9cnm#=@9~X*_ zCzEMue;+7z$K%P(wwV&2t{Z?~Xam-?R(dNILxTL@1;{FyZhN2wGqiY*&N^%{+Bf{C zu#c-kF;hylK{%Rc_CVY=kF^Tq<9bVJokfNB4&9@ zY<}+t(LATQtgpy3z~nZ}gw5+ZKL?@880*d-P-b~w1uf7Id=G!i%(DLeNM_iPKlTjx z;ya639LRBchRyn_Y|up`nz1_7P}x$ib6E<1jy^69Z;G0#XxG@-Kzps&SWo91S7CB; zVR2;;OOw}Dwa`tU@Xr--qik8^27yZx6p0PFhNOdO&xRJ6&r)(RU=`C^GUO z9uG?sZgQkJM^Rp$t~P`VJ*F(LC|)$|DF7S8!%wGHSK=*ld9IAdNaSv^ei|p9!fukR z*l17ZRB5U)!z-GyvbDYt&{nUquF|f8rab3VadlZ@Zqbw17F4{jP%t!A{U}$ivZfX# zduVoD*f62C z)DGX0($JW97OEn_C2_i%FUp!)C2A@HQVuPRuYMQ2$c0g9bY*pYT;aESDpv+I{9R>b zYoSA5(N>4uw6rO*{EOSF`XAVX`rvAYHXufG*NxryUAc z+7K=*!2(*@>O6iy!t(l5ZGPRqcRt$qDvLB1Pi?Uq(6V_q*0A1191+2=RG}LRcbvf~ zakQ)KA+SE0nNo8jl%pO#t3uU)oJZCH!D>Q9q8&Oao@QS~|J+io&O%*Kec*i9n3RJV zGZT2|ctSNU^Pu**zIZtpWjs=NU3zM;*qnDmPkR8B|S0 zro4Zc60@}R2zV{ONSQ>^-b?I+w9=+`noL?D;=CMjU6oB;ATg8 zql=JhSbC(LT%wY>U0cBzRNTU#h`C*3ewjeFEVPIWFS-arXMR?ka64Erq_}ncJTeR+ zIbC%lc|02o3$0{k5j)8!s!(#X5#G5g@o|o-f=Nz$t*{DvNQHAWL9Y9+TqPJ7TE{|Z zATA|*v2;*_>{nKKK&3Y4yZX$X{k+sq{@aMj%j|;u&7DV zV5KrQZc!y~4-Qrq^7w>pxf)LyLr-0|C`@d!Bc-`I$)Kr`>dMTeB5&Ls65S|*sD#Rr zi1Mh=oPb)n$SMD)&+8(dWCV<(LxuggIU5RJ6z(UJ)5Y%MDs z)j7y)J7vO(6^4_iXdH&MeHV3c-)0937)`P1VI~EtTRtWhR7qb68_Y_dkRu0R~`2O?h!5c~jzc z`~`==XTV8K(MwfHHey2z=HJq4VkFCF#cWla7)QG<%?j?45mv?VzBYD>Oo-4GlDb9A zZHz&5(QnO<17at+O)ktF!r0Pg{V=o3oy`;U9%aN)moXY=M1F!EPvs=0{wIkk6GKU? z(z&8w9sJQyL+oRB0{ImHOQ&aCc?A`lPlRYTl_a)e6O7aVRg`mU<96()!{iK3amiDt z25MNBW<2`Nl;e?(qv~akN$_A_N8!jwd8w`Avbx)~#rlg7i@T-jr_dW3at~1Msb3K1 zDb9_q3m7rRA`jsvMlw2%yZr$etW3cd_Cw~?b`)^fmp1Rdr3czUQXMAj(=()ujOiW8 zO$p#fvFQko?-Od2q)bhgW>!|$mslJgk7k$m8eVRuO*PkMR@GL-vdL~@RP^y;uWN6Y zfV^D5vbzCa3$UzxLq4ZL6JK_WJgYUAth}IJwGHZRIgHcJG@n{~<+wI}n&^@5xH8zh zE3p_{gU-BG0UMvUR9qu^gFj?0ca8&jdv^^x4V0go6W%_p*w?oMHbi4zf3>baT&E%2 zb{W%#U$>Ak4-NLOe^PeY&#wo3S`j_R$7@w<6AoKJuk(}dd{+6H5MqfsGS9E_=Rwcx zad}p;SXO2b+s;C|0ym5(dB>D>yGUHcYDq-REVawG5I)CxZ{F4|{TzJK8H;%&~>{ z@%UpLS!!Hm#Qe~{Ab_LcyT92-rn4z z?=oHGWCU063|L2J1Pg2Lu(}Wis&S%{cEwj`a?gL{xn^?reI?9?&yia_7FY@@+HkXk z{|;vu@3gY`0_;ELA@a-H!T92kR|n(C%&fuoJp$Jh#YJtF9z9jT@q{U|0yEbwXSe#@ z<=8Ffq}2kp%xAo|W-u2Dh0O2$1wSp;b6FDyN#`KQP!Qj?Lb>02omZz0tmzifi1Y67 zy4$l$aw}4humr@*va8+9P}tlw>c0sn=?Hk|)_mrlD;UG&$uWkL*M1a+m$a)WMU+{b zT;fRcejhnNhCmZn{gN-q%HG_VxCL2JH6X6gZ@i+L?N~o*96*LUtI>#ZaTS9i?+~$f zABdm!E&1T##S>28G+}Blme_>&YjTtR-oDmwj=H3*q`b0Bm9DHy?OE0Pq&&l8iKU(sObqI!^w6elnZOzL}4i%cK z>9!mh28bazG=YaI^PPRJ98zNPs?2Cg?BqSU}Xiq265t4uN1v zdS7%coGHi2pKe_pKL9)7p3kJzo_1Xy!sD8&l$wE0XV5v!Un?&YGXtNv??LQOW@~|ab5hd5xZo4DbJ-QRD0WKZ)-ZPiTK4Dz<1^cDMcuTrk0wTO$>E1cwZg6O z{!D)-+^^EiJ}9{UiA!k!;&M-}2kP{0OyCy}#{EWjA9!%(m%{1y>%ezIJe8m&GXNbtz6xr6 z3yt0Z0q4Y%UuG=14k~(PvqNiF6l0m)k=hwIUHuBwKWGKpA9q^EMGR#bIVkw0Aq^T&?{!OSNemS5~Hk`erA z(<<@y@#Uv#;-rw^Lnynh5LPM;7=S&wI&0>p0of7&_$^u{hi~G6wES_w!hR`u9SLI% z3IkEAkEcfSx~e8-bbyx?6>@h;mO3n8hn4Y5--W5tm?d)zV%LBLyt#I)HVb*LIuA`p zkNB2>GAKqJ-D_eT-4K~7Sh*g+3Sz=kagB%tx+P{|jfy3J+Qe{8L4|heNbPnPD?EfZ zkN;H6u@o|ip970;G(aJ-?*Xg~PVZqCBoh`QP24CN?+^`*KicnY6~PVuBF?W1iN039 z$;{u;?mcs5rk9RcK%%{#tuQ^jj3ubiNm0AF8tjZoeBPDc#E(C=4DR#{s4I+a@p+Cg z7>D0u@M!OGJUJX2r4~_Wlxgabnhq!JFqMSIJhegEk@S$=FkaBEJ)MsLoJpST!|I3ku)?kbIK zDK+z%_GXg_ButHwNfZk|I@IYgP-r2fQ-QA`dXgAEv>3mcg?Q*TaFGuhorDR4%G(#_ z{{6{>pN`22v5>`49Tbl{R6#$Ulyk1e5Z0dbO)VR z;OQGx_gh_X_G6Sn5S*-G9$~MPj=7?CA5c{XR$L`5NDqy_WsO&tUrD1wn^<7UgxSKd zMA=wY7(|M$B5O`8p*IP$FULUac6UEg%sx_c(^|HvSVLJ=8*<7)uHtORIARHT(WxD5 zDV3SY&Rt=Qd68(Qx~X^~t_=TaMWaa{tKp2Bx%4Kbs;n^hY%yY(%vja!_EE_&tIYn> zgNVg9s}mO-*W z2pqFHoOo+KG_Qb`LK}+$G0&l4lWGgXI9@1C9Y?$lUfv~9N66jkR89mgVq9Bci2I1_ zpgUW^t2#az^T0`KqdyvEH3&deML{SHsT`Qm=wg*O1n+sq7>OK0(KMpq664B1+*h}7 z}uDY0#oiXhEY4&>djoqe4u{IMm}&K-V-^x^AP z-h!G)0G^>|BTu~*IXdORtp362cL&)%IV7P=ETKKk30R5%Q$_wzJiK2}M41APed;7p z!W4JVD;CPxwz^uKk_v6qW3T?+dTLbO%J%3H&&Nk@_(F1f5`CG}57xmXNe1 z;k2zAfa#;G3znDE8QSE+xgkvLy$ip(UzS0^L!@}!oclWgr927(WeVg>;AsCrCDEW5 z#|>*7R(#*mM5B3aHP|W$fTu#P?fFa-#9{7gT$wIT+B?W{VSr@5jDGyl>B}ukbVn=k zkmb4xfONEfEpr(?mOXg$BR<<&?V|dHhp*+3^H!YfKojy2VxIUh5rRuCQWY>G%Nt+~ z`xtViDMGX7$aoz@tPdo!tLC9NO+qHA`|>w%W{`D!qqBjReJ{-K_f4YneSkG&2DT13 zZVP;wTaogG6Q19iLu4Tr6cB{f1p8Rq{5f)1MSfbZREXkr z_Hym|Ox;WISHI3*j39rYHR)Ag;-_2gsc~s|oRedg=gl2_3|L9TA_y6f9bh;HG->D& z-%Tv!2NBG-uV7bsMw)wawjguVfvWuUJ?jw%^>nSZJ;0q7eg=V-zQRLYdYi;mE6C1g`^)O{lgffDbP$G?PNXWo=q015}EX(ThtB!kLFCU^NZpLGBP5N79A!094wtc1B#vnQITM0^m5_!J>ZFqx?)OE`uc1_Bm_D59@zNQBl4#eV_Cs+FL~ za~Dbs<1621QOsX=JY;48xb%#Zc!q9)1t)D;n`WTw0P|CBupGPsV3pan$R}QFNE#Ij zahXEMJ+(VLcafEN08D%2-f z61GDVz=MNHQb8FGk0FaHG)ov+T0C|pMX}gQTlJZ94dPfp*N3PDb?Aq4k78IC?a_H; zdIy_p&&V{9%(J-n>Xc^tvPvmmhnPPEG263BaGfexw200}Vu%3}Dg}J3;id1I zg=^ZcqzjLxd5`i3Mi$X5s}~e;=e8+YX~e)|oHjP#_p>$mFoOn4RCzI(vEx&`ONUZ4 zguj0o^=1scHUl?oS>kR_7vM{$BvtY4+)DjP11!b~=rC`g@40Rq}1DD4rYUdsTEHN!}r zSGL=&R*#&?-ADye6tebVNWNprZoQ-xtyV*A}9NB(MNV9@j6=Lq-A|28Ve1ji9r&=wZSK%Qn4XduGq zhMx*I8*B_H2CJT5`x?YXhF7s@Rq`0!H%sKgLm-}bo)KM1rUZgVmusg=DO-SNrKvi_ z<>`j6r7VmabuJR9rz+C7%hXI_#H1{I-znCXYqgz7kmf{neKAmOlddS}Dxe<5RA@Jj zqcNT!*E#1ZQ_jOQ=b$dV#*7wkpn}qH;cMo?PQ^0!4MHS%Q5@|xn~faK+4Xn`Jnf~) zC#r9`KET8_J5!*5S=Ur$n;Ecp3Oh^hCn3MNFFocYOqY!jx@xO#{;;=S`fjGe^_FYI z-BNfFw}VUK$#55T;K9X)<>emtNo+Wm6mcu(*PrsI<9U zet!OsvT&-oO4|kRgr~l_F9y13A^j;GMgUAPJ&{J6uXN?!AnH*)Yq)ybYB_LGbi23$@dhnegVY?}6N7gcpR-D9^VX6bVyuR-E zkpo=#0VZAjUZY%_XT(|DDtG(jDpDY)2!l8cV*>qn-YWybK#%_$9QITy3k^6(>#N)! zhZy!W2n`Y|~K+uTj-4gI!boc2rz4%+fQ1xvgnLprOXxJ-AHZ_MU^I>=hZ zoF4MBx6FlvnVcpO1+@#O*9XuzBI+#$K0Eu3T9T~lLVeuMP@O|8IegEszS2J^-|l3A zIrlCav@&pmRD4pM%m|!(r*wPXM7GfWL~W5^az><3_HM{+^>xOHm;vyqj_+vpAjx4u zKex65W0^lZiIZq&d+XK`WN?6V2zSiQ2N?ErGAO#r?L)k@aSPu9nyL5P`?Uc; zTc33cu>n%kuyu>F0d!OUu?y6U%46`ctLVb(HI3s}vuaqG$vs`ZhG<3N89!z4u~v6U z-kiuirBZLYYJADw9P$-*CAdkb_DtmI$33HCWLuxI%6V!04DK1k_{^}fX1Qrp^Wb+0 ztrKVt;u$Avm~)qQ>Dc|}D~Yv^)(!I`zQ$Phj&W`0_2?3_JI;H8wGQ_c`ckwz>TB@E z_-7ZkF6XV_GUwC$nbOzqYk23lmv>+1oA~7pw^i2;hY-PCuJDd6ZtOsqM;5NYJ-_s@ zxb$c&KTR_~3l?sROWA7IeBXgb&gvN50JPupO|LEo7JlYI>W-t?JLM!))-C%rG6q%m zu3&J6s}PKbf6mPhVS5K|?2h@}Nk9kXBLU*5SytQ(GD*`d z$pJPe-^=feRqYwE`6p_n42MVZ>A{0})U<-!D>{ARq#W5Rn*;LU;SJCkT(>lPFh<$) z)&Be`b-Nd}tmR?ooMt<>JLn8l?L@I#=?l|V-uG~VX;_mPSGW4ekRzFPDf-x11OH}T z;?=^MLbrhV)`og=#RByXv56CYyH9o*=di?V=WgMN%_lf}RCXEkcIh2&yWr%$;R&K! z#&-AON%4*Sed$xnn{wZF@8qoI4)U?%HRv73r|z4sN5V4!B zCg5QMI^c!@(5prNj$4GHX9jKb1tZ{%hcITxHt_*8^589CSYz@hn%7FJAD6!RC3j4A)7J1E-*^4hpV#oSH|I(16Mcs7yVaD8cNcv)=jHGY zm5cB-A{)+kO|f71PU@h>!{XI4+x^pdhC*uPmX-VBO*0$vZ6llVjWfH0Zfj`gfvbP# zrE`?`)+^fjXPEbX_^!vz@oi;0?(;?`!}p--aL2>+;ihxs;ijwN6?XdpzB}>f@QeE= z6VYOhAP^Tjl7 zmr*ExhEz&7U+ftgHTi}tkTjf0w@mD13J%EoK`7WZ4(-qqDZrbWU}6Qo-rE#xt3@aB zNgHqYtr`x0r^&$ohQ_|}hDZMc2LYrT$RPj5kbdkXitN!-D2`V=@}VS*!MD2fHU=f> zyI>IMM@asP7D4e#*`T;b2kRh*^86EWkjl59^d*PN&JwC#y3K3w?~%h zaVO?gv~JqRzVk=8ZuKYG?ADho`PFyuvnHQ>7;cK*r;dq4rE!ob!k8XCpP59map*AY zIhEc(c@k+3UXhf;5GAxaRiuujSlel&5}9=PF;vlj2EHevO(qkiLH#dLg0WIERlS^5Y&We-@K5ngR5#U2=uhEGNROefKD0X4RJ>f`7TI8AEwtTNDcO|=B`+RmOZalBG zZuqY(#kk=q{DSf0_ZM9&C!=9emW>X+F2535`IHFYtev<5E`w1zzhx+7`(w)V-d zmYaNc;+t}J)|+B?+M8&1-dcXI_|-TI|A)4BYR@bR7InMRF+0u|+qP|6Uu@g%*tTuk zwr!go8-23Y#`Elbu`bS8XWq>D14h*xHAdC@g6)^I8t>!TlZECS&<;INRyua&4_d1% zwr-%({52Pe@kHEPL6zGK31|CjIE4P(v>)?K+5MtU@|%wzYFMtDm6b+JhdWH+Du-QtdY_Xi8HAV$};g5%9LD;B(o$C$)^T8 zt5!uqs#SzSx>bfka{3M%8CP{2Nk?%Ud0U*kXKf5W`s0pq`P) z-cK=^T|6xzwP;diQtg;bRvC>rnNkX=gi1l8Z@|lv1c)QGrc)P%f^lv}sGgS#GZ~h1Ew{J{yKPQn1X-8>V`lG@@b$?~N zeb6@1QAVCM759jnNtI(qT9uZ0At_>#`Ur_hw`~!-M9T(^s)wy2(Q*nf?tH9uB>dSk9fwEb2~PChtyMrsK|BCa{*Yn9rTPSj3&S zSj8<@Ze4!SdDRyY!mbN5#u zsXj^_EU&N`<1mur?u;D-iUF|#g{MZ~t#DkYgM9v>K};#$(73fc2?@EH&7ZQ-R|9gT zg;M5z)cT&GaER^{p7hFLL!iIpl9GOEAm!o}{c@13zj3{Fng?|z zoqM7Mv_(L!gmkE=|9wO zYqya8pF%~e!hY}<5FiT1FMS@buvub5`Um!P`hC5E#9mfhKWZo$#%>oekN7%t>r=zE zC)(3Q#*J*lO^>2%DXpy(cgbB5JCQP#HSE{WL8woYT)br{_+_DCN>p;9C_T5eZ?toKU4M7-^v zYg)792h!KS0ft%Kuekmk@wRo>293YYL#}op)1p~keIZa~cRoh?piMzPZ3WV;fQSEn zORqH#{)@C!3u3@);L-F4wB>|_VWy9F?VjRiZ(Sjp(k}+P^2^r; ze$+&XG)oX?yT(LglUyvM!UyL+Oua5LQq3vn|!n@vS;gKM}Lzt8Xh6z&;B*!4eOW% zz zF5rJC-}eNhFshMq2d~@Zn(Cu{2x>;`Ov(oM#&3=6_~G8G)qDDOA^z%#Lw!HN)B!gd z`T`67>lTb5lrw{|W}}zmK{P+CAd?9_7H?~AfHRE{U&MVYxq?JSmVKzXRXAw#tyb{a zm&A5FBSLx>f!L)<1p+7q%k?wQ8|#n5wl~ zEnL{5(zll&V-V3Hl#7V#voj!QSH^{s}LX zJQf*+QA&_ZMIgBmu%0JA79$5gPav(u2=u4tGpB~ZM}eS`5YqUa2fAv~Jz{{!xCei4 zjTXWkzejryhZYkH_MBc*4;rYbm-31vC2aO%)0THcI#6*>;a(y+(0XAP>YgDva+cq1 z+$&WB63*Xr3PK%Pu+=2PbL~f9aDT+HO>($AYp20qJ#)yT-izZcYMeZ7w~5XKIAL{!N%UeIt)$&m`nf7b0~b90ap5xP(9xXFrK(wW)r&0?ZW z3*8N*i3#l>_^ErsnV{XyEO4<~$}t^O1>}*}>K}{?;UP;`aXZ+)qSFGEoJ&{ba|<0* zO}b>lJj$Iu*bZ7Q(O$grf)t(S2O$dmuSIIC46xG}_@IwFP&WJvcCyx=?*39J*K%`8 zXL`d@C92zYfr0g4;Du(SSypJpNJ*XI4KexL>%Uy&1NSG{PwY6zW9~srv<}(nraA86 zo(AXk>QSABpq?$0qPX`@V+JqfdJ&mq!vS{N0}!Vc`jwDF5%Pk)vM71POi)9+GiefW zDSckLy|VDD6oiQu#Yo=3cxgr@BF3U|qG4t#KpGPDwHyhMLNz^5(L*tA?SMmd+y-OA zrbM%B%cULCICM5QH%T%iI6#DaVN!UVdZH)`ke5Yaj?ff5|7Y(^wVj2TT5g7sNX)jr zUu9*SXjf=%dDew%Yx1)H&s42qRxu!CQJ}s>GayFZFY1h%ZfQ~(Ed=~g5MkWUOEzlM z4pi`;KkS$vb3P%qz?;5eAkpY`IKMW=V#1h*ulImti{VtHJZaRXJQIa8a;7Z_1n|-d zg&Od$et zY6lZgOnWk3pheY@Wdr?GfFkC+5w~jQNgl07H`y>BpxQowyM`ZYZHza}xuI`eMCd47 zJT@;(&M#XRT7Rp652Yz2(VVAhH5+aX1*8y$ry;oH{#fPss8M*DA-osw)d8CK1i~s4Hejlc z*a${8zweMcxDexbm;X@O&F*m3t(G~GfLwZa{Nm8^%uHWYcMl)4g*ac2WG*Qg)-sd@ zv?FDX3B$N&d>nGNt-f6@hmP8I%Zo(5g@=qR($Ey489aejw;mh_xOyPOSCu@OlxxM4 zh&R`iSp8ZqEz+zbXZfkmp;l1rwd716t%=>&e1?-GB&BJ?3Rjf14bx!kXo{xoF4Op$ zw{Wh@BIf`mU=FH1C~8$)je9Xul<29*=K|6<00fdoW;~2)`Oujq5PdKr9Ar zb;cSqo@>g6W|DG|Mj8#<9IkP!hzqVVqY3e^q#qt9g#(7j#~PcUq#+7url|@`UP_zD zp}CkS_D&<^=^xW;GEyG#RC6=Uw2>td$#|xwooF3QI<6l*9FBP^YP9OXCfo%d$rMy( z>xb?bYL1iAS613^O^nwwb|`cwko=Yoa(Q!*jai@jHIGjt_BHN z-#Bx4_-*<(q42Hgs%HK819~z2da)W!3YT)EdJo?~VrlzapOjlq?a;h7k+ z3MgmG%WE~4c9~T|EE%@^TQgMXtkk?~fpGmq7Sx@gXBVwe|Kw%-VwQwoG+ENrWQ^)8 z7^ReGlBN%asGb&8#z${p~WO0VkDmbj#(kD2VxSK_%Ov%cLRw>TK zn`Lo^s+GhVHWnGI$c~@O4p#A&ZZ9bw$)74Q4ImbwE?Jxj-}$o!eH6(Yl zLtgos<0s`uol;eYCFM$PF`83sWlFC$&X~UZS$#Y5mahos3?FLF`SOde{qpFLJ?-*? zWh3E6kL+>PxO8`mA_o5L>dK{X`I_2V4=a{##>omAZE8%2I$U{u$WBcBZD7SSUgN5vwAE@_RBo7Z#Hagy_- zahmg`ah!9}BL?S&dflyj?gAT?Y&BbX9YtG39Tm?cw#AGjzKRxd-O?7yowAKZh4ZWP zx$`WGGLHsMk#EVm%C$m_ifft7xeZI@Uj?;_=Q7KsuJg2W-bcbmpGVQhpN~3^0*@Sz z`j0A)h>zZn3XfQi3^bzNT2hKRv*2ZN7HQ{7n%!@W!M7Ex65bM2in`0?OKOdrk1E!2 zZ|Ti~-r8Jp-bx$!-9=kP-Bmo*-32@q-4))s-8J47KBX{^##;qG)$dC^=Mv}W9^r3A z*=0UOa)XV+pBcO`xA#l74WTGT4BnR>>-y1yx`a+icidD zVPP%b-O=cg!{IxM?YIA{sKN9Vi52_Rr1qB=;)IylZ_lV1W1?E8+M5PxRz*qF5%78i z;ClZ7W=%$3UXmkf007nWVeW zq#;2d<09!7b_PG@eE2HcrCA`OGoQ`-X({Ujd9c$OYgV&Q+*QjQEnBU$VB_B5E*s|2 z6Y!7Q0ejo$uuO}>h}EXFWvroc9Y~-PhN-jz+g8vphU-F?wy(TRZC5RDXNWXDtDci5 zOGc2q_xM}g8Yxc=%+0v_L79zHGSVOzh_q_JGa6pYtguFBV=x3sLNOCsRT;>-HGaSE z(H17Bpo6qht5}b|xtLt%V5(%<8L$cQtJFHgn?dw_Aj{4xv|FsO=89V%2&1XlVLjVo zr1PgkS@#VsmE;=#Vm{#`^iLlxV!!nhd-fcy-8BUU+PrbYj?X)y!NH!`?I1N_~OO*%A zcbLirn3CXk=(xdD?EI(^x2golVY!v>pEb(>Vg@^+l<2GD%9Dr>wkjk|m`|29P|6aH zmjOl@v?Fd4iP$Mbm)4THh?1iC9NrqpF5%2so$ApGaKBC8gwO;7n;}DZnxy%7m9!L- zrM-)fycqTjlr|Zp?Q1~*#0RxGq!8Tht!dn%nEZFL&lNHFf7~&$;KxVmPm>bF|6B?? z{KF!NAJ$J|gfC0HRz8;)X5cRP2WRrEq%$D-7i>!MZ?jT99wIzjfGV_gfFf%9N~S-N ztS;SC{|~C7ohj5v3LbZp-%^vx*bc_Gs!t$-8GGtXs50JEizjng73@?);pTNn>sc`= ziVNtrdxrk0EoY4KdA-o)ThZIlMHGc1jNyQm)yRSvvqpM2w0DSRRdibuU$KKw6|{n? z1NuUa2bs-MU~$r{fvI?hTtS5TG~9(-8`mJ5!r`!?7m9UStMzvm1&wT3k{{%{7mdA# zB z#a!|CVh+Wb#O&;c?}}e5-^6J)6)a%$jEovxh60 z8NR%1Z$;dm*s?!nqrvk~{p2zr?bnGha#017RY3=u3^1xx{Hj#?nX8~pER}M9E}&Uc zX6DKSC^7KBOw24<>|$1-*$g^mxWHcavOEe{qhZgU@6kx}@o$!_*WI*zw)q zx@Ef1;uUKTidmxH8#Yb2rMPhL33d4ER%wsf3Vv9xvv|e0(D+JrMB~j?pV(Styu7cQ ze8n{f`Q}+4^;ob$igaj$HgXB4H)}`E{zW3VvSEF@GP-TL0YFxcYfp_LTb~;wgS>hCp?@PBi}Gih)G!y#Q%GTfW#*j&h>$ zbNqFEVI1uWU|jN)c^B-$?+)}7d5w4~zw3HRFE?ui&TlJ+nAw(ztZ!H(JY}~ldgd6& zxlkPP!xfH_45ZsEu0FKl!;VoHAHrbshA`9!8vKNPt&ERebjQu4C?k%Lz?f4}Fru6`x<9;#WVYw6 zh(lCrZ;ezLBWD)E0V$F#(*)I!rT8ceTtgWI+hZ$AQz1f`P&P))pd>QLVa$<9m=ohq z8z^3g5F!k1JNJF^J0r>{$RRghu`5Eb_eS_JU@T8dj;x7U+@|G`bcKzq{tG zn!WV<&Q8`c)yaN-a#MreY|UN&*op0n4%z?t+SS3QS8^|33<(Ffsv-8a?d5+zrS8Y8 zLkYb~^0R}Qf5%!G?9u`;9W8f;#scJN(odUA@R1NjP?3;%BhwlaxEqc#l!?P5lYzq_ zlW~Qu$RX?fBzuyAMXInRY!*w#Sn$R+8v8?4;>?mCPgOnuA4i0oHm*Y80x*7eiqvt) z*`JAHEf8^L_4Z}6O8;7SLvLjKZipnt7dhWGc$7-+< zYJn!T8caT%p$mj({f9JO@5>#?NrmT(;42FcC7VmGv;v3YBu8O_D2i(|l?}cK%L#iA zD8qF8oE)LP=qU6SQjR1fRaUms^a09P06T=?Ow)N~+w!Jef%Xbh2yH#kS$Gs30wK`k z`HOWi56g6EO~quC87)I7L-0`*bqhxnhk2gkH^oBP*M;kYK54P;V02MNFKd)9z8;y_ zP)$sDj{>f6l2~CXevw%nnfgz)Ml*_WwAy%Wt8lbF5-Il<4P=lz+$WIz4opub0xPge z{?@o@f&0oIRTp(=AT+Al9Xze*2C?WSSQ}@ni`nKR5Qh}cdY8%$TwsYzMIs#_H7>95 z-C5UW2=P^OxPU4<1 z!Zvbpp&DbvF4<{gY<>7tF|!oOy13(OJ}^Z0;ERRPpdYHJQw`;%hcIHo(tYWGrF6sV zI7E6e;YHmeOo60@2D5*)W$P=-ssQQQww%w;dQ2|Hx~yWjBhAB=ub-JEGO6i8GD7C-*i}Fp@43}4O5mIvoAYN? z!=#E_8VhSUE+WHVU5I5|B3czWSw0=3S`j=QlTe=dwASnE-f9y$4xDq63R?59rlA6| z5oX9tO^&bJuNV`Yq}JA)!8M2KXDE#3aV-Fl8k!U#VPAl%W&;jF?Mgb5!9wOmint1?NHM(unBgbpS7MzIivV8-2v1M)Dd_AHN zJw)!jH5C$dW~a%zzS>6sYdO4O0aS%QNhf$5w44@Ap0S$hiP~7H2+Bivt^83}LY9bD z**Owh_SeUS+FG0Eul*YXk@K2v`{gSK7+hc~>*V_%^_g6}JG_9gOBjWw7+reM?HGbX zLH1Zd|K=usd=D4r;bsr|7Dyl3hgnj1KtyAIp*wGoR}s~F1I)=5^zi%ME*jzUGVI<6pRblMeAtzu-*Do>$l9 zP|1)jS^E>O6llK2jol5rg+e6m>{gN}qdzI9XR@u2U5RB6M$auUGP1>NyHD30i<&0h zw~t)4HVmf97MUe=-|Y$%0pjLQ1sV5Z*HCF3kDFJrR&~~H*L~<5Kb$wRcAR^wLua)d zX&*@=+tV+w^{1Fl(i~g*sU@5FNl|BaWS=8MIb@U_b)2wS9C1H!6nR^|<%q|5kS&js zLnlX##xe@7AUMQP+fY={$DG(az{44vsN_I$N_NS>Uav99LVO>#dtN9A3HWz1Jr*uMS_r#+!y$ z{q{h_V}pBIcl6Bc%KhtGTc^ZM@5aNuTZ|8H5A^NI1^O-4W5lcVTaj0e55QNsClhbB zX4m#q?bh|7;#KU8<-_*P36de~$|FTuWHdo3%k( zw@BsuHDcCV*FLd#2)oJ-g~x;TK9YCKYUwp1@bO)^#;0esm=FK&EFMb7W5{66L Z zTfx52C&O*fSL^-~p0dH?=eXV{1&NxkCZGyWK6*Y!EqYm3KKv0q>FiBv9Q#wHNWfPH z>Y|1U=M8II;tehrlXNw=_Fv7gC#m6{=$9 zwut(w(6oJ7au6*sK-8LvJpTRggmrC^= zz$omtgjM3BcUX*x)Ow^MlKWi4sD`7zW7)vSL&YL$Vl+%-9l)qs!ZK_O8dkq@Gt6vW z#HguaCN;B!19A3m|}%LS|j|W%kkb z1@_f-Gpl;s7MZ5pQK=`96OkuT6H#nYJ6JscH8-!}r0l(6m23mU0@HB&sFLZ{=>-$5 zzh{hJyBuq)hZ?q4PgeBJZnR9z9;}!xZZ?cIkDE4|du=1F3k?gaf89r0NAA1p2JQ>$ z7AgQ8oym3IlGN52EXF7Ii%5vh5deY*F!E|UX?S2eA&RWa6yv>%XIN<)CaR=M4P(ZQ z4KU;38FkVrhXK)vMw`Im@pI@I(X65VK8tL9ojYK*keY5AV>63s3?VlHWfjhoc|;894 z0OmAK$f8B3+-&FGmIwRGS7p= zRzKn_a+E#ds1BTyXnx|wLCoVoG5K7c^{H(>2 zU|z~*yF$M@@YsDtsDt}4{bC|e0f}wrBmi)CX_akDQ`r9Kp&rkDk$%9mtH>J3LI`%V zg~$=iR?&r4C^!@rZ)=hOp zqCr>qN}H5o^clO?A+Dn!6GG5^uYuh4D~NihtrC!z7kdC4NuJ*jHSwr1p?R1_3VxrC zPpP@rE4+4Umew)GIp9ia8n384@FuG}x}&@R)n$X3sHg<%rfn9~G1fk#(x-}ZfFymF z)w2%G_%YPY>aMUA%&42%w18?<`aok?ar(xn{GPrB1&P|{w1c$#M;>bN4XsW#a6EU~ zmHI-k6vX8HxM2xWCC}%imIYE}KyZh8Icl@G@3uS5ie|r9D8Lq+3o#GV>`um*jDQ(g z(@W*jDDYgbttKx1Wxt-aoVfSLI+o|!)_lz$q4F-cyJg!RY<)W zy@v6Hwe>oTD+YdecN&oqQ5ih2eF(>;G)y(s+ie%u~dcS_;Re-}O@vjwRgIa;KVsR*9T<+?P_z)fS zC)OY8@VgYuFH9tUz9lBoHuCB-FR=cT#a=2AAv8uVUhhR$IQ|~jh;DBrnGB5lktBuG zcGb*M$raxO;+<4#<_B4nW^Qt)no3nxG-jE^NMcW;!8Nr;0>@8iZu6iO$?`CD_oH%F zx>#DN$A#DhGu*oYrMvw)B_=1p{-LJ;bPsX&nf&*)0>P4DuH3y~_Xq?*3|=_T&(x?h z!AUl^{oEx(!4fhk*=OPb_iU8b`2=V-xA|QiIZp0#03@9UvIuD%>rsJ`oSV zs*@}N)l*va3@~ltakmC7&BaZ$HkPemm1WAjaSE7Wb&oda%Kp7^mez}VhduQbd1jg| z_*7LA`guul%#e+geL!(!oXyBPpfoM_qIORH6?36yz36msWKE=)woL@CN-(Wb(bngVOT40Yese!SQi(*c5ykJ2J1mS zTbSX$#=mYx-nSIx=H~;ENg@0ucHGMtvpJQ%lwA5xLo9i3zk~vW3&N4;7cPre=v!5ioV1Ii|^NT1P8~z%}5=+A-SzU-InXQgf1dDkrTAIdBAe8*eV+ z%jqHZP*UL9O1A;)!UYWZ%}MS8177t|Ulr@z;JDhx4p^>JunO>6bHNR^J{e1~)_L<4 zY~vg7iT=>{^}F@lTYT-$$$6Lc)I?O!thx2rYJE3SwQ0Z(tqQz!0t_Yj7H4+7R)3)T zJ^%ahAC$8@gvfzuu^&GQJpL=nnb!XYK-K?6ITJN^vN3ja6m_=wPg4H>gq*1Ym4GTJ zU$ReQ65?_Mege5FrQn!I__GF9W+H9OXyY;#bMs|S#F_nPfeF&I^4@=aXQxXMcv0{; ziIyDdC=oc%R{?m=jpwJQk#su4y172@#BfB>woZ(m*G=Dz)>YR)%PXF?`;{x}A6==p z`h2(*`zZH$m@!gksR;HD69^+kPW=I7UN;8(Hra^_O1!WJqXGH|q9~`TKEsoksy2j7 zwv_V6C}u$-RCt#Pb{5}=$gCJzK+sUZoOH7ujmTAGR-PBsR&yNP6Woerzx$k~0MF)-*SSc#D5QKO;iAI{6%YCuV!kv)a^aW+f5 zxyAV~6LU6;L-J-yQaSPP0#t=w#;aGpSqZf2unCf=^~NMzNtD<2;h&RdNCP`H{NuhZ ztHOxD{hXwWMsuvQeyIiN9)Fm;dmkfLlx{Y?%R?ePG)LG;oum!=11NA7+(i2>KP3>kWap!c;XDaAlRB-6)twRJ zUCHa%5K%$RvS`pI<2^0cGHD*$7et7-re?`9^bvOcZ~zR9gdNs;^w5Txs7!3gl^WMh zEk?~@%Xl-UR2Q%QVYRE*&d&wL(Mj7)zyiiP9|S+ljuJGdOjm+9*J%89=-xvxqY7{l z{3vpnN0Di(S@uRbwf1B}Yun);iw)O%+b}_XuPBhHD$s2A2P~d37eis%`&IY{xV2vX z6>ERC>r%&28)(VZ5wc{jhbq!Nm|iNh?&ZOZW;V~5-9M*vDvM&5ga+Pd9aL!<`>VR3 zY>VP9VlE}MzVUXR2u7WgmM>Gj^xq)vUkLW|c&#T%^a z1nVQHXj-3>|P@G=|_GY}0Oai8zl)DM4K-u*^K9<;y%KU|5 z@{UP$yTr`^sdI_u)~Z;rZv38_(F+UaAe$Mg>l{V*5W_8w=-_iI8s9GVBVBk7C90)h zzdmI{RwccRYU;E~>U3fn>rGoci)z^sjK;B7mM7hc`lEW#PM_xoT66A5Q?w`z%Q5~x z_Yw-O)kGXBTQxW4iODeCJ)|B1^qvMq-`pUFjF$%gwluSjH73lJW#~6`Fz?Dp9Z4E^ z5A+Jk4(XS!(E4Y|)b|NBWk;KNSy~ozDjnB-mPFYbUDdIc;O}gL9?g039tz(1Mav6g zZ?Z5%J$U=u>wlzC7s2|;u5Y(lHq?KWM%DlO(x|Ylvw@YdgpHB0+y6|V$}&pG0>8Zz z)~4cX1%>%P_~ixSb7@0&@co6$YYEi_^~*{KD#r}!BRa4O8y6MnzQ8_zdh8h_l^*rY zSNM)}tTSmKitzNQl5A}(eCj-Bqe{J;2 zTI>;%i+7O4U^m}I3FsysSIPKuH0rwP?wR%h75ox=z_~{cw$K(fNgcp?Jf);#xNUzm zW??-2WICvoMkwQ6gFoKT?|SHove+MwOuu;2N!ca0Xg3A5()3wZ4+)ZiW_p*c+c=m{ zo@iCEt3sKLrH+c23{Gv!;6#~x(PnIb{O#@g1xV4n$s)15ygMB_qewg0Z1}8pCJumw z^4CP^<~d-{lClL83x3cK#BI4&7D*#DmpDNmjISNZ~<-SImc- zfORH8Oti?qYYbdG&W!C{E%N=LD5;17?eg0R?%|PPF!_v*;R;0?QPtbuy|vCv+emth zu*KAjN*GWa7r&shM7Men%?-lkBgae0#Squ;f-J*so&Pfmd^(jqLg1GWtQuPn1@Z~K zl>x#NW8v3gaNeu!e(6@~CrwZAsGcyHly-RLX3Xu>S=#C`>PTeD^X5L7Gkl{Hts_*H zlZFhvl~AM+(bOp;n*{3Ea8gfzYQ|UxJbaXu;S-L*TDHoK)jQ>?CG^m2zM^^B#_S6X zu^S>>XP|1ht0F;?KAB5}tw=$>{&<3LrdK?DK7b$*LxbrZyfek;I!o!THo0(E~?fG03KNkvzp()L!r2wKKgW#OMGIF+30j!R=nBfBzIM2&cl%F*fh!0HgMMdxw*%%G zQYdjnUe}8@I^K^3s7J8dmh1p9Na4Ss|{C zXKCuMq;7Q;$i|Dp*`aoJO9L!gEp{vjBCYV}urXf~H1w0eGw$DWey;B!^K7smbjnJ# zD2Ltjgk1z4Uv~(lsz!(W!?4rBpoVMS!}57J=Kq!jX6%}ulwRGeS!p((deSf|8vEff zOiqEd&k`Nkd2VR9uS|(NBFTh$MfRYo-a+$XM%l_cM4o}0C!&uyceeAs$D^vT5Hx%a zmp@Hbg{bRrs2kuV&osjQ-Kjy$8-=Zy35GcClAHV;jcBOIW=2o2Y~y^r1?6i+no~eL zM&OisVW&%6(uVn=wR%w#6+XcKV=3MXfV6^qFU7w9-{_nI298b+`i4&bhi0lu&01b- z3E%_o=}JePF&Ik?4mm7riH5csNG=Mg4m((hB)$qt(nykW1a70{veMydUc0P5WKr3y z*~CycCuv!*tl305==J-(U;$wIR+4qr$Yfoj+q_`@kD0IXDrWs8^V9G5-5=!Cu9IxX z?Ry{I>-X&UZ+5=)PxS~T9Z2it^^d%QTh z@m$ZIx5nJLhB;bZvk^7B1a#H?1DwNM>fvHeUP}>*n{)`gPuWnkr z-Ngq`bgH`&uP+`9-G53B?-q2tkY`X1G`LF+fI6Fgzc{m3?B)68G>FDh+tl=AbjA8{ zp#c&^oL0g4VR3Q7+^CognS0K8!t-^af@fD5|j;0xF+~Q>~HK}Tx8RtwmgF? z{w8VCZE>YQ!$2eg$H1mp0+zRh&}CkTsLTe#^L#Lfd1`HImcu0R<1Of0z0Bd+@rheogJ>_C5vTQntRq;tc(o&g!Il{M zX|mz`kkUg?2%T>E1^JE z!dy_@zJq8y2u#AsEKH;}B2*4MjfgaIQ(s{Pg7Q>Py!o84L*$Q%+iy#U%6&*ODqdnP zwe-(*sDJPm`Q^X^D|gFU4UtKux*{VW{4q! z<0$)%FRwBYxjYx0wD?-h+YP49^B#oT0rqnf$$TY0@5gW3w;Q6)q62HZ?Y@|!G*@Tr z$2|;EXYA)ap3L87t+1aR^Rg>{Z5Y{R>b{64Hc>71DnC+o7fEuKy~}%B0MU6K7Bfdb z)l^7S%GSIf*hs99=*`F1TdvHmPOr_cw{f>uanBH3pTzos%`S~QG_!7d#9g4eXwh7B zirgo>G#R2wx+9mw@@;%X&2bFdDx!x?gUwNO(n%HYnZDn6y!iIgBonyHYb#sZi|cc% z>z#GfznjyvOy2m|u9E}{$*v?}E!A7xq!TCZD2)%%a;9gnI%yXM$H~7($;TqpGulH@ zPoUje+JM_EDnSV<+9V(sz}#~$A$KeJBL3u1`Z!m9swHzLNm6SSF1p~ih;5irQ|1Ac zEs8O>#f<1S<5H%Zge1~npp0v>iS`}&L(r#zASa%0 z4yxrIjY%J@8bAI}w#wsMqVUN<8%-Un6T+~Mh|H>kFUOZ>Hvl=Pc1zXNsM7=8fH>+U z-4=&;rh5WZHitm-U|6<10q@7t*0jq&gJ#}|$^a&r?5b)=Y_UFKt%ldFFhWHMpA|)s zw)BIOsk;Q*mTzojyrWWZgE~LY=H`YP4;0M{6G~2ChbvMxQ(u{oL%yS;TQMiQGm6O4 z()C^6j@%v%d$@txy#q%EKUT>8(PLIM_*4zeii=Dx>FLTcEw>#cN&FDkO`EJ?A2C`s zRJ(IiJ!FuM#i#gQ^!$g~6_daTcYJxuTEvGr0DOyjk5;drRZAV>&J1@!mnN07@I?0}(kU zU187H?h1mzkwl{8O8eQmjv9$`_=AN{3pSbkW12l1lx~?9qBA3B(z>2^!N$_=ttaDT zN>bY=F7!=h)t+ss=cdpd!ict4a7lr_Ax93v0^PyG5YflB4=mL!=;s@;_cMz38#B=p zb>1`fo1I^s2d<}G>@CM&%qRK{`889_0eu<59$;HLdt}0@6~Yc$?1ooo2;y?Rr~l%+ zkl`D>)^$@7p$jwkswTSrtxy~C!N$modk4pqd=)u~{z7MXF+5`*m46?*A!$XJm2tm< z@rics%_LjuHc`l)5%a8JW%3t#S}ws5rpoxy1j%?_rZ_?xqs3_n%iYv%ai5_mmrf|w zn7mZ)?@jup{@IDKQiI$-qhWKo<3`e2ux|vuVk7XinIq%<>Y9*ZTYV{&;3^iReO5ICXR2<$tq ziAP4(xT9RCpHwdHW{QdeR~6n}862{;WAO>Oxb?(*5c7DKi|o%apVzHTh{HL?7}>e` z{fs-Xll04ox`m;{Rta%)P~1jwZ7pp|3D9Ew%Dt5nv*F`Z!HpUk+sx1L(IOn`q`;;m z`|1T!_5B~)W>98rKeC&8SGR{Wyc*bK9ya^o_(^O0ub|)=`V=4nFsLUpyua)D5(z`spX2C< z84$-5Ef#My2a5!KZ&@4E4wIpi*bn{wQOymQQ+KGCi!! z_i5f-Qpf)uod7i*t(w@-9WhBf+a9Q`cNig8^PphHYh#H!lctKB(xu-S^nkVz&N54% zI~Q`_%d50|T^^txRqYAkVJZ;yeG;uFWG^~2?oeRMMNX%|SPn6TsuhIo>RlR+!t(*5GOG+Z@6Ku*NyXFQS zFxscYtH|(j7Pwbf95D8?RZJv%CA0v}&J>qAwY}uXv&a7Zr}n^)V}>pm`p1v9|I(fD z->N-e{2v8al`>H7KXe(z=*hG&G?4z`&y-te?I`k<_`~v1u?`aS#CNQX87`wPC2KZV z2Xr?>5RYTJyD)U5{=*Oh4SeHnCS@2yQt1!+|AC{Y-D#Wj`h0qY@x%T*l1o%2E-Hpc z>il3JDWocfl1#XO>A$E!N8VTqzpH)!0^V<(Y469j3Wemt##%bG!M3HhMuQ za+89wthD9WVQ9l7oP3r}phKMTXkxwclzpQeLM$XA@wBmte7=b$s_X)*N3W{2@|29T zZMI5G;R2`X5PY{ZDw5@i68Dd7PliIvH-k&YGXcgnPsrIZh=AA;Ry8De+$vZ+!b(Gc z!6{uF_1P@~2=7X@Jp4CX`wm@JN_lcMxwLiDwj4X>YpV1NW<(QSvd{aB#s$(ojQ<>1 zf0lG9CfH%m~GR2mL~5_^%3 zq3sZFGLngdg9Y{J2n7U*Ema(9ln%2Bc`8*a$fNz-f-rfUyv#4N68QOlXvHj{1noRR zTDW=qNOGp|z4HeUkVSliAKAhLu*g>gBD*A_p_o7MMl>=5JYE;;nlsQt`3rb5ID`)& z=Y$?AWwUEv&E9?q+Ulno&dJSg6R@JOgst&~G5+>*6Uo&zM6vZZb9`8cA8}zGiaIdx z!;g>}3=)6mq*bcduLlgN?B|C;1fFYREpcy=_k5mBB6^US;}ACgi&=cz=p#H-Hz%z4N7-$xby`}u$4CjL(+v67R% zgVTS0x#&BX>pL0$Z&S$sx_a?c!csx`w?$lQwARclDH35@=`PMjW1;XHGq8`XlOZd0MQ zICt^~c-1L;af_AX4x4vyVF#8v+=bYJp*l^Qj`m5%<|>2pfHkw$$O;zsYT8^;^552I zYYx(9r=49^Yga+8T3pAO{XZJKpy`Gf$#0qZl@FnO#~v8!%{uiTenw;EDz0w7JxGP} zWVm-|{KG9d1fsqnetXGmE%;tjz-Uxz`j13h`H!J#c3juytzaKD8h{k;!yt& zZSNRedB0_iR>ih$+fK!{ZQHh!9Xl1fDkmKTc#p&b#-s=d%0dg}Xz>5WS zNVSl}n&G62o6WkMT!@D@ZdwUXu=aw@)kC>7!nyd+9Zzbs^_Rfn%rmYWd!F^>;-A}P z;xE+NRy*k~IJmtRcHsWK%$slK+9}8EgH?>2xt0>aOAs-1b0?+M&NZSer@mZ;{T}A7 znDla0867-TB#RZW9~c_dI&nSh;0B#Nk`uX0BJ2TcXCPRx>a8N6G62?Xly*tU18v%~xEU&WyzVTQ_P1F;H<@h8m1f~&s`*q`t=KZmumth@okS9~_MbrH2 zY!V)uG&x6xCQQ`l@FHw^fEi}Md*j{2+JhsKFFC0K*h>NYuv!yEBpLhzuvZgTI||Z>GTBG#?~!b%Pqv+1u8|mMcXbFbt*q zOi%QUcifEP70BqfLL(Nu$T0B}(uynwKd@KVO{Fv;9_bBgcgicyRuZb=JzA=t-(PVD zOrR#?&lf=T>r3P6f5uA%zar4Ts);WBrI4=lrIBuA{-0t*%ImVo3Me`yS+4px<{}k= z;Vncqbug$PdBNyVkj2_WYv|dsVUWBWSr$i%A!hH0MtcQ}b(Vk|;5W!m;Y~A&!9fh9 z^MQ-?i>{fBu9ZwXem*}?dBHY(pR_n4auMCgz))XlONnsELHQ(MY{dH8?UWD~32AI*4>}wik1UeJ4pwR1v1sExnm34OasGqPC44bA4F5U%W zLBoLEW}rD1oRzu|BZrx58QaA2gchOhRSKmX(%o?V^t^=gqPZ7ala_=UMhfc7?4h`X zE4BgC&0D;?cA5CRaw!$oOUP5VpvX5UFou)!7$XmAwnv{Rq6uFAv6S&II=~@hn`HLz z2uMilrloy-(Pt*%Bw3W;+^4i!AY20fz(h^nN1y`Tl3p;gzflVa`xe*vs zmqG{K5zZ4XFosfM(jkP)^R$7^NN_H+TJiJKLvDN5QRb`wFpD<4h?!xR#a%S=yBi?_qX{DPQJOA8V$q+C~@37e7A_7p7 zLa09Ea`)qC@DE`7OHYmD@^~!Jv2JFktBrJKCsQ}SkMnhzZx)%b1+ZZm*9353H!Mt0 zcxc0jbui&3@_lm*f*4Rn80ic#gbM&f;{lGX*=&p91`O1-v_J*jCfT~HTC?5K%1N`2tqSt-BQ7|c zQ*WuVoocciWV?+KavW5Ko^Flh&{BZb0x3bOgz_}BShEaMhW1cpeLfYFg`*O?otMa< z(ah{=I(q1s1VnTSG|+sEaj8txL$_hN{0>M}Ynr5+(;>OJ1G5(0MKEWBt3jjgkK;H4 zEP4k;0#QksikE9yv8JZWBFkBZi4|G}=C%W3G}9#R$SNE(QGvFa6l=5aB_R+J_34{j zyonUW#&wlEWNFHhjKVw&RL-_XpII_)J8}h=g$4? ztaJXF zKk*_!$T8QS4~a(ilM+u^vX$(~0&ORS8KN-fpL!;Pf>jmN$_ufE7Ehn=3dIFYy*g#x zV{3Xw^2+3yU>_Xh`iV&(J{H3~JRpDy5 zDaXz)x8GdKJakB!Evj-?V$lHs-5z8Du3MNmC(N#QfPH5VIm0}CTi~TN%6Um7!zF%8 zShyec!gY@8$Pal2Vol02ciXoMM72`_$sfH-y+MR~> zGwXD3QlzKx;W4M9*aF;+@N{NWL4(7Ew7}7m0R#PY(XcP|nOa&e>Gb0j3$3+gLr^sQ zK&J7W{U3^2?{VtZ3B;oNGQ|~c@W5Cp(g=L?Y z?a(KsCz6DZAgIE6C+zLTFId7G!2AR-9!5y-yWcE{>F$oeMuOx^8} z;Tw^Jvx9=O^Y-M?fXW-*khhQtUPpfC8ooH#*4 zdYyj!n0(x_`y5XZySIK)k~3KDyT<_$8S5mTZHOY^uvYf5!~eIT)u$^|nAaDD0r#I$ z7%cvcnD<}1kALvKWDM->Eo{vMj1BC+0w9U>mkhn5pq-1Y@!$UVM?~yO{A-#T`Z+dK zJUq)5>=-5}mE{@`q8>;!ry3uJ6qj2y=(q>SEW5y*z)QVVhJX|v3IyMw^#{ey{_Zd= z(M}Qh>l^e;+m!bw=fl(8Ol;1#jgfY6aJA#vL00$`hXFcv9h#2T-+ORE%yTuu)4i@3 znPQ3(4P&z>7nN6utII-t4BLs4JhTe|qi)XxdD0an#Mu{j+H39!)@kuH7-*hotwmC- z7k4xb)}IlIMBB3N3J`0Ao?Nj)**E4S{o*BMsv>EQ%$^8mlcOxknxrISceMnVOz%vL zx3lAzbF?bPg{o+DDsS$i%*3}#3+3=-6N<3bf-r7>mVaT!iWbzbDD#(H%CIZ$hWB~p zP4FP;Sd2h@(D+{Y<2&NxsrqF0Wkz-IEzdq6=KjtfKzI)eIGtK&>kqEr@Mhych&OP5 zh7T@roL($*yD-uCNvVRB9;~CA#uw74gJaT2#%1dM@%TExwCMs4L&r<|%6r0Jy0E`X zW8!_=j-r+x4X=;g=e4+{s64=_Iir?LZ@xpF^(M+#E6n<(uk2pRBURK92yHHx_S4yL z(mPDk9^iR@6l~G)y?aJqC$l!i*9;U54Zpx4%23(+r*;=f#o${AXke6b8&P5$xf{-fnBO3;!55Gj>BcQ$j@%fcNp|Q+9UMA&P^z_yUC{ zKHrWe8Sr!LuD-$5r3(Qa((I|r6eJ95Vx7aJchuDb79)3CtGf8mi49<_Z7o)o#*eER zf{5vo>@R&z?^kHSG`e^S{e;VU>-^qfMDb|DtYpMd zwtVE5zR`r|m9m-8H<*n1(kCx1jE8A`5HFaq`?j5GKmjIy39%Gg4)X?YOd2SfxD+L52p;@H=<3)n;mU%Q`N?|ddL)5GK14?zBLGkq<(U1_3 zAR-7YLroOH);CQ%YzEnpKZ0wzuXmzIBIm&KYd%2y0G`F{@rC*o^iI?1yiVO$+NKZd zu`?szL=o-=;0xefFyP`i%O@F|HkKJL!{Cv9U)YL`6i0AF*IEZ!ifXk(e#QFn@UyN3RA?Zfaj-zzQHtZ-n_7TdMyh!X85=6? zqQCg)a+GCY+(SRbhLnQ94Zs3QSSLUFY|KVIuF_3H1k;{=JjkFbLIgwWSHCHRifN~Y zXZzAgT+!UP0h>JF=^{_OEe$qv1hd(BPI)|+r zgEL}D)@WLF2m3-iwRV!!GWCkuy<(1Kedil+1@Qvz4kzDIQx}x84KIb#p1bgpR{ju7 zb)7_zvy0ZuApHO$9HR-yT`N_5Z6u_K&mvNm)NjleG8`6+ zM2Ud^p%Y2Gm`x|*23PYd%Ns}3J85N>{%=k^y!)G1_zNybhxlhs{Nvwn;{O*e_&bEJ zs-^aYNPfuL0uOxqPKng0nc5gCk6D}IRTlCMbU*~CF230vY1sJ07>q1Y+@}_v?lYvq zPe4a%RMT`7f2ZJz@0EVghwOX46m~*J<*HZCM0a-ABWKUY^BwfJ0uIX|R+Q(@-As8HdeEM)$I8qy?ss*bUV?3tI$DT8!x)OuRHiE;CHkfzQNA za~7^N{p%?$FJligfci32Tau~WO_BifCS%kuu4MwZoqA&p26u-6&F;cM={Rb*RuUX%gAwkjjtD-u2NvfZ7_V z1wuvXxgnd75daZ_L5{AqDppboj!HF)K5qjS>fjJ%S2=3HN;iV$X96-t4Q4FeA*)s* zW${A+E)dM1Gtlcp#(*M=Hd; zb^eA7Vuc#0Jv}lbYp(QE`#Ba<5%?_KpAxM$BFqi-vxRW3oIc;YO+HKrSpwsR%nmuR$$LyPs=(l+U} zsSo8CgdCCuSFAOV@Td3*J7bDedajg4?oTXtT1iH>~m^Bih>`EoP}S2 zMo!-5mY%=&`G$`i2|Y2y$nprn<0Yn`*b+x;HQo}w2}19#UnV*OJ_d|~a)-zGVx?pd z4xK0socx!`8C9C@-6*PK2J+AwOh6LjD}>mkPBLyqe1W(H9+Pq){6^7l-4NzH0#_hh z#CvkdPiglh>pNP4SN0|JFnz`lIFTaB-wFMAFewW7Db?k!MM1kX1k|M5seJ=m{5ag| zS6ueu1kD#3o~?qf0fO(*=R4Lztxn+ZjM11YeL@?A<3ieGzuToaAYx+eW3^#-zkg}H z`_+Of&?xJuKtjvzB6i5*+mmm*EKw%Isyi=v)E@M|HbRXyqE&Xjeg0L{=*fpw=YLhK z^f3P{9%}v@@$mnmUHXT{dyIf2hyaX;->JD3w?2Mf2tx-Ym>j{Lf0U>^J%W{>8|+e9 zez_;yaX+v-1!EAny^-MU^X|aJ%Hs&RKWqwY23VEAE7tLa`#CUnU+zWOtt*L8-GWK!Y!olxia<{8i$h3 zj`m}bYz3y1^XAZB6yD_=ldQ=vi|Kq7i~n<>`0udj|96}IV;ZKVgd>9TVQL3F0MY8; z&?hJZsHYJk`yq@XDE%w9q9b=>PjC@tpcig>x{{lDP~F4>@~~k}QbSdvNFo_^yHlAc zg2JP5TrI~ZvPXz_)2l4lAKe+h`1StOsoUu%-zNX($2*!oU!}PDNO*7o2C9R!Ac9;J z2i-2nFiCK{r7#Y;2%zB^bJ$l^SThiCEX+fnhlz=(0a<089fvSvjEr>ygsqz-ZdMM7 zn})_nY^XYz8Lk9G@I!XJSplnoWrbDydmX@OnPLhpO7t{%e_cu=Ivz;VP2XXTTYU-{ zPOn2nv`{iU3SdVAi80PmgsMVq>A5BEQX+3}tww9E>-%HLdW!2fqdMac?Tq$0t*d%%2OeS6snE3aQ;0|bO98FsV1y}-qjgN#Tzfx?^vitV z;h_waQ!$)^qPszqitG=4LJ{a5?YvSuHA@yHIwERS5&;GKvV5a8JVtj&b8=1O>?W%w z*cyuzIfLMIEDMQ+7`^#uhs2@fKabtGnoG+pm^$tf!m`6WXdpP7tf0f#?Fz;Omg6)S z%@aG)sSo#WV`pf<+_d@!`2I;1iLPciX6?Bes<1+X6HK~&6)@)jfSA4fk80bV9DvwO z8Vqa{P$QRm+g*5ln)7#0To{`xjLAhsAL-4_h}%E)^-9X2fbU;rMIbCN2ayqk98}uN zr%!J6L`=A)#X}@lTdU=XGa2~fa(-#oBB6v2P$1;;Q@bnZBkzJ@gYYzxfQ~E~;(HV1 z$j@uqsOnr{Q!l^(3`3@P$*Q*&m}1P#dhzJ%^Z}EStczJQwETqB2An3}>42Nl5oWh> zyMyBlKh0R_5YVTKxGpSR`<9olp@B)5#$}`TF9ws8Ef( z>SoCfGHV08ifah84q2SAvCRpO0H<=`P4|y|DYoC2TJk!sz z9AH7sZp9z8wr^}m7=Q~=%6jL`@?p2vLr^*wfVxe&b)g++)74Pjg+|#7Grj@3p?9QD z45r>SxYUZ%D19!LzxOfj2{-_6vjb`>_WP}1?H0>Nej#-*XHst;@uYXrM{F678aphW zaaa=qU?=hF7Fvhh!0%OKEkMjZsn`(L(r5(RR1ARIp`_yn$Y#7s9DnB$G`Gn$LLLdy zr$69$$GZr@Atzs*;FKMa2J(`}4;T0QEAfCr63FFzC7y_XI=9pN|0nVMS9Go_Mn-nv z2TVwglsExOFb6PFtwAuycX<^<1;U#K{Zm=dQ)Og1mh{tIb^C8{A!+{ODX_XvUd=hy ze%{?(z^(lXA@5L1Unky+28_dV%ZQwrd#RUg$fH+!`B?*Jx^9xbIVEYVk=EM|120Kz0KN68`aN>b6BgBlHkJmMx8MLu+A>n;~Mk5hOGYl6JT;zUZauYl9 zea@oBFEf5rSLsxKtRuzG06U@x%mEf zbGg`B{GG5uFX;FM@%%U1N|maYeWnWP=Vr%GACm@&4C^~usYJFETi1o(iday38GHm1 zQY11!kVDFhw#|C%>lehEV)OYaCGy`vX$4<)2#Mz61gz`62Zwi?z-BYmvVXUi>-;449%* zM`$q`1jR-=n?VB=)d7(JRg^7^SNN3%q=h<46{kdCC)O9jiP2K^fjc=90%_e)MM;-y zY@-HHqrM(;^oG=PH2|+xn6O%!K1XrwvWYHe?Q1T6XwAe%X`PFy`Q?!4Z>D4CCT2Dx z?`QVhs(0K=v{<^kv@slfhg0M zOrc1aQ@SysAJNouia7ag1qhw>*N*hG@qYY?It!bjuwl9~RpPXW;@sP4y|^h&j=0Dg z^Qi+dHv2qdfzM!gG}bC=A1u)F!z7tdZasHAnS8M|-;WD^}? z)pNYCY_3c50MzMV>smTH5xQBlbGMoTvf7>WcjzkOLSCQ;bp_M_laf6Cn(F~cTl}A@ z&adR?D-V!>c0;h=6D0G`uye+JCsAbe)T#=UW`0E3F-OoEXLb9HJWip?3LmruK$fmH zy$`Zh|}(wV&sF^(`!00-;CTyhbCAGTx&l&B2p2lIQ*cqQ6=1sv@2cM%(&qVyWZ zOau1fq!_b~Bz-;W9K)Ps9O5XU2`w@K4xr+$0F&q&;o@G1j6bgY*@O@3gcU%^TyWT& zvh*xjkbP!?!^6x66`EW=QqDYB5~2$?;#b#b#3|&fb7)d2^WjBffTRy;LTu(`vPJIl z=j%J2e2~^U5cZBaK-`aYN)_hjAsE|?uYq*aAg;W;dMd4~99okF5^$mks;A?A_7e8&7bd z8}9Oybx;+XPt|L;aq|cL3o=ze)N&)?$Pe^6tVePR!sRg|Dq_X@WcshI?WtQ+KwHHz z$iOwDy}eeJTmhPZcvNyFHmc{XSbdfI+tzr!)Ce+_Ju{l=?4|j1mY~gWQ)13#SlNXR zwMpNbl8p)WLCLMAZY!hX5sK(fDNyX+2C6K2MA*Slbgy@F){MiFJq44&xRPuZ$%TR7mdlS*@kA8b;u_?CW4@LC+aiD-*Oe(Z$D@M5E{}0ziMK z2bM#?X|nndwpD2;(u5pfpw&KG8Mc@WeLXT{ZmC1zX(wekrsG=9bpmC&z`-_cTtQ6A z-txGb3kcyIf`bFTNgtq;zFr0OHj+j>fmJ1enFHQZZ=mKr0tqpFKPnV=lo)aeq9f2t}eM~S1LN-IvhFOmT2nD5VNzbU&qU!$VLP%sS*-1k~ zbbC2W=e^7M9_U%gai~2cn_^OG$Yj!-qjZx@+`J$1I05JWV-1TJ{-g#_u53GJ7th7c zBa^E!=?%C=4OLX|Xoo3XQ}0QJW$?J7&jPLZfty^Q6-CkKk#s<@wxpGdHo+=YF=SK2 z*p=qpZ~bZf*ev3S=f02 zR3~^6(pJ7Isdq&!}DT2R1C4+gx*Iha5RExWAo^ z7;&seZq`0yJy;=D#emTjJ)i9$2C5^)Kcn1^y#a-+JX z<)P2LC4OyzS)$V1xh^!Gz8hS|o_tV(j2;jxWvN;){U-D(QnjhSn;yfP^J)C(f&C>n zbY8M0C1duj4p?Z=sZ7P3ZAVvF~^;2clZ>M}CcW z27_Nyb)>JX_ID1!9oa}j23$pGdh4<5fEyy>p-Ei})xm%df^tx(?!<}jm5%N*I#-reM8_L2@_-PBIzM*R}xp?^(tqaPwl#+Q0-9N!aQx1c#d zBVSIG>$j_$ZJ|1*kGslCO@saZ9Fx9{Yo2JA!lFaFO<}P{r)Pu;nFn-!Fad}_pmHeV z87@Z>Wc56Vs-z`c++li#hC#S9l;<1JL>9zlYcRDTI2u6nfKWraBPNC4VFpxqv?^R0 z;9?!X{!VhM!-CB>DDFpbu`H5RbeSj`cO?I#x>R2DTtcDM>BngBwY3RtcW1ytb0nYM zl%DQ#^I-wSEE>V26moV7AI?yDA0v|qovIGiVlI%(fgcSR-dCwJDQ0TA)&-jyU+nk7 zWI0!l`dY;(hg&YKki-(@psr@(8-5;%ZA>3DRdTNLPe~T$zV_f-*fZU<{^su?-QT1x zA0>x7#CbD^-#2oh>wyv#E~z3j1i8c_NKZq22z_KQ_a8SD#D9^-%zTj#Fp>Wm`tz@q zj{iYJl(7Bc7`Pf({|CmCrEDX&AdljE*<4*2Gd3~%{2{wijv^f2vI8C&Z!AyT3WCh9 zZD}x6rPFSU^a(*m@&Rf@lpZhK{Yw2tI_%UD&^ak?J?}Kb`nOX(+$|lb8vQLEPjs3z>l-@y)Y| z%DW8hmcUqCwj&#RIxdl2Mv0n<#PppVZeTU=oHOdrcsVl7-4c_?3sm>iga}@%;T9ZO ze}a}#8qHH*dtb!{9cSooHL7kkW-1<s!xU0n$bXIQPgc3|$ zyn=bi$6_!68??e9D`rKDV4sU+E{s$1IrL zHA_8)N!kasgxP{?c*zxJ746JQice2(kc*kEpUCh43!Z_rKCdYTH)x6qd{qakKJO3t#-g3Yu~F&(euwhKM8v9aZ08#0+=>Ve3o)d5ohxK2 zQ6oPV$wpbr1YWTQvV=H`#(T1~avK}sj;LReFQ^XDTkgmaU73Zxzd{od8>?bRe+z1k zNi;U+2qAd2w*zaexXuv+cCUP*G$@!5)N@o?{q)VA*^YNsQ4|zGlCiU4O3^SUS4_1cU|}e9{fh` zn>3Oc-I)`w;5g3x*w?S|l|j3p60Kce$xvp#=f{Whw+uiaG@^cc@+_FKGh9|=M+|z; zg}Qfxk;9q$&3VjFOMc~g&-cIep3V|IkHud@bKL(A4RPbYtp>>bOU=|@Na$Zn0V@C5 zVf|-s^^ZohN<~WUi?91(d&D0fW5iT!6?z2jE6pq4O4gCm(hS1KWp2=}2>$$@Dtn-hRF`+Vb{!hWdfE0t7)o zCruPikRUKB4r&hxEKrJ(6c0DQ5%-sS&@nqNwjt7LZ0KXmXt_!ps_4>KSqfyb9Xtp*$aGEHWN~L`+QW+J zIkx`ZScRnvCwcESg`SnzT+Ffv1+PoV!|NP-f(r5*)?C2o_mE6?qpry4npA_0bUvc} z(mq%^>B78+R>0`ZJ&;yvFoV&pus~_sEO*VfNRS{4rfMnM8StAs<=)6I`Z*27u5A;4 z{wj6Pj&Xw%G$YAutQA038#=lO8D|nAWcOb8##Q6Av|}ovqpq_OIXzf|C_qwMm@0kQ zDoAuEhu;=sTgsfBuu*q0rh1)CcGO2Y(G;~NqjM47&8z1010ipd)d~%^qWEV~;89W) zE2bI>z)-r+AQ+Vbf-;<-KpzL0i40Ymki_V#JkmC4z4`0}otNMmr(G|EiO*3nJ9){v zfN`QNmz>aTuok-)BDb~NPON+Evx|aUSD1HIz6EMT9D#$9R1ewku8!;AehuQ#nD|o- zN0~A;>~vCe&L#dhLij|4Sa)kUh{S75GX5NecZGyUk~#lMp6D6NF*2LhndRYxYmw$iEGN|k zPr8v~9u|I5M|Ak*Vfx_zEawRQOCI)r@T-3ewzt0q+Xx@F z^0NnFTsni2F?eA0Y;4RtY*#unEl}Q(%}M`h+U!k=G|=~IlWK>NgX*;VcSRV2tws7JM4pr~G{32q zRlfxE1cDK!0S}UFxl{aX^y)+)A)8E@SyUV8F3oijjYdYXO<)~Gi_lfKf&;T@z^-SL z@emW@D@Pl#9}~WkA=nayfj&m*cMhRDzd1xHzW(UMFzjjzcBf{GwkRGg6sHYmMPd*t zCc9$VOEld68y#41N68-tb<3-Kt1#yguSFzx|qC_#TcRv*Ocl zeGXgIAN22+dQ2NV<(<{qTRG+a{8a5=)i)JZN^_W|ih@x-%wZRbhc!C+(Y-_h#*JiLs^&WCmc%nxuYbEKcV| z8{`+~b$b2k(4&FHk;2MwXy#fZew7LeFhM0zW1zCQFl~L1+=dCgOiY3v7>%D8x>TM+ zxAqFv!bTRhoumFG=&^?r_9*X9$(1YgVOClLS0|N;$KD*%Bhi?avKyXRyTLnX>~GAm z`UmF%(?Y;`mibJ>i_#W#`x5$bA(XvgAekC#E4NQYRXo<#io-jVbssFHwxf|XxN z*c7r;_*%_QA?%nei~Nx^A}LY$3;RED%W@7erhk9T%gJUcl~sHRP3RHe#IPTRRu@FO z1?G$I(sndGHqW72T_(+!Uy*){ir>jaQd{#AZRf7OhY!&d@+0bu5VkrY?HAfLwsHqQ zV>{y^t&c7(S+o;c7mU^3sEsHt)ZVNOT4_dH@7J)f-4LE+X15hu6}*nIRvqS! z6!qjINdn7SXIcfhX(gf`#}EWFVu;8VOA|?{Zs+9jm!ZC`y@q|qd_t>kSy^w)0m-^R zg+T(ZY7K+8PtGrId=ScK{9%?+5Kg(~0j$a>ok4_2vCwt7Fm>Qfm54);So!Yge=ve7 zZtA$BVqeXD^5!FQjE$OA0G^ejYOiXaI7-90oi76>F`O`S!vz|y^MWfQa1lbe^cZ_^ zztBA&mE0DNcx9s>&3<@1ShKg)rMudP4NiU8&nMpDlker}&qIEqaR!h8B0v1?_g4{e zb$|<8|21zwg#BkB^8aEN;=dre|0P8JpDCJE|Db3VoZI}3qsimq^~KSI$fxiuyAZj} zyY<-+#dUBS)CqY}1{IkV!q0_A&C)?f%m+F(n4bL9_C21w^#0qF;nzSpB=9pzzPfa7 zT(2U~1kBh`Zyiq&ZfH>XWlQS`WCd+ok&PBNT}#Ny)^R`Lrk7gV+p>btoLYZka_war zp>ICUVHOh(YKc(N8O(5ccOp!Bx#Pi7ukGkZw7K(GVuhuY^SLkN>8ypj%^{Qa$A;V^ zkI7wM>#Fd!W&v^8jr}cLCK|p7<`e!&hTT%o_4ng`WSBX_vKSXnPB09^M#qo1`*I>@*{_O~ zM1>GHZKg z)ct+IrAXb%9(e`z<5Kf>e1a&Laayx(iWr21Q}__^N80smQ25h##sEPGXWE*>q50}~ zRo_NPN(tooLJuS)h**&MK_BB#vZ1sjvZPaP8}i==VqyGQ)7N46?{m}lVr%K9p3{H+tPYz$8efEgkbl0QyD!$)GV(d4XKKs*`Ec+f58o`=C1VyHKD4JhTohM4Q_~}fV z6I9{-Upj~u{7%3o7=s8}zFp3nJ=JiTT&MiSJJ{}pjUR^<$0(mS5A!d~pr$^2Fu$G@ z$iUNhh7W#9!!dbecJcKcXh~-$-6R2oppNz}K;3ffu)3qojCrW{xq%!PQewKQZrHxh zQ80A%HP^@3a<2bTo<_K~wzMO3&|orxZ%ngTKuj~eU&y#jE2P}_KpLzP9u~(=F){;L zY&F454^7IR!qNzMLE}yYocVa>kA#z5IA>JmTWp?cpiOa_Qem~=5L*~?0p2+WBr%}L zp32eV6xrhOlyXUIToHfU)}?QWA<4N>M@g=vrJPohT2ORm6~elr?`F>#YKm&nZCV&N zpJq`eB(?m4qNoocXZ(a-e*y0cGPHIla0 z(9(U3&!XXYNl8rB9h{wERlHN>))3f9*pv*m#6|J+ltTXIz0on~ zmlV+BTX4T~v6RK~q!QX)fFr08z^mCfr8RTJ{=CUEa{brncTn8cCiWI~Fl14DD>2F} zFm5wW84|{JKy`5)DpmAJ@wUMCqJe1>B+-V`?BCdMhnuhWzB(c>=joMb>W`#`&8xCu ziHyjymgZ4ethf!^81U5lps4hFq^^(kfB_y4ks(82Wt_eWD%}AER5zotNFxraeHYY` zIuQ{d9VXdQjtC{Hl)48fvPTAuA!E+OWa+J5I#fF*&Z+Q~4awxvalL-;pEfOL%d^42 zOqV}~Fgr>2JE*pXDFc#~tl@yZZ$+3(wj|6wO#6uT$KSxY{G@an#O7gJ<7^2V%M6&4 zJvMYLW!zxW$jd%NE_^OlpP4c^a%W|%9#s%l{fYgyCAcbHc zOdv1D4B24ryAtg2?a=#NC%d|Xn~r)i6@AzXYCp2SwVt8cQ7qY8L5@gMt^tE*@cRN0 zDgyHmznH>pc17nfC^4c9l+?kn(Ej)+1y9tQn4ICTh`SqI zyZ^kxXsRXDT?X{^4Ntu}h)F!Oyydjf8pPr`;qic&GdibNc>kp+>4QAzgCQYT84%=n z*+d8vIw?-|w~)3W+vK!$|L8`lS^r@ko*4ptm@&|OLm zLb0>{f;7ZCkuw&0=5gz1jJFIqrI_sAKm%!`hbE;`s1fC<4ha&8VX7*e)a64q8a1J_%h>7jO6Oo~W0b5C-f@G$wi!|o&_Atw4;a!F{6n|M+;U5059cywT-QeP|5zIcs z5Ik8EK|t=)2%{AAR&Dk~O@-0ZTI8NpPfX2R6}wnBVc}89IC2VPbrAdaA;_c0@pH{+ zlbh#kad!|E#3}Ybec`*9ormyZKrUB)8F6WZ`3K^nqD{p~OK998BR=%CK)J(jph_3G zzRt?!KZ5mZH_WtDbHbfME97Ek9{$r$1X+iKTsg7%nBWK_M&?5T)u@m>#dU@xrur)i(IEX+skyJRyOYS<8Lk@M{$b})uMR0k4 z!gA2E?E+fy?IPGZX=O5u6=G;d>65RGvauzx5cS%>K6UCB^=&#*CP4FxvwMc89pd5pAr|NA<}_)DJwq1&rHi8dC9O?b9j?-v!vVV@j6pjH z3i)Z{K_6_|jZNG8u3zbguoB63i9gt+)RCxdOMRN$x&b`sftZB%1H4&a*xQ2nw@UDf zWLD$%^$4X|+GIoU2ZXxGLju+=zJlyY&8J*|NlUA5k1=MVRd4g1kscD9r{Od0RbL}K|> zl{)+;F?yjitwd+-_NlL{DRnSY*gqQ^4j>vv^4p=qz%NYPFLKcJZ8?H1@NPOLy8NYa z$QcV-(0Zq+a{^35)2Fc#0`qb8gYO3^_Iz^65DrCtD4i&6`H81fF9dHiRq;SBS|9yo z=MA|%o(|q41oDcICz8)kx>6tYz3!txCQmp$fz|&gTw{l@)2+VP>gnE%|d3ObwUDh!CXPIK?`zeW2CikN&3W} zVq`NqS0mNWVjvJ4`U$;%aosGe7|ec>Q8@ zI#LqV-N_5ini2kEz{_hayzn;wA;etPEwowWu*`gpN$kF}j9av^hDT=lOT$lo|5r@* zZ=AUXkxj-3ogagsK%inX+?BLOagLjH5?T{`Yq#yJ`p5a;hqJ5`g15l)a5}kn*R-o^ zMn6-W!Yi3QofAP*HeyfV#x~k3rB_r=vF_r&(U!#4_c&PfVxX#PG2DB5QrL2e`r5M2 z+G-Xzi1k8lnuhPQ<2GIse%A}*)rY8*NK0|ZP2;va@cL7rp;;#N%YxS{ylJ+j z()k0debmHt!LS@zStY$(5ph$lZ<@O@_WnW_tv$uY1XACVPm@4?Zr0>{b*s*xAh-`O z)xKt{6WPlJwUrq=Rxko+Y=|=Qq;Bc-CuqXS4h&31eTz#`bY;w8d-$1&`A8FS2dtuZSg7T(5VC9|#+LO2Y zou^cRndnrjPDUunOmEmV-~oGfL1z2LdU^Cj<94u2`L;N;d|x=1cP1sgPW{cQi%fvR(^4^K-}+-6q8gHy>y#t%|>+K(BKJ22G z7?X)rAZzUr%j4NTgsECYs19oqa8NA4oAL3zYyzJ@d69>T@F{y}Gf{1=D7ehn$yph6 zM*2NjCBVw@EBNAg5)b#o9k1=N&LkaPFP_{+VlUiYsWkNy;-pge8bnOcPInCkE4$C2 z$?tb14b3K_p)-92TFz2}&y)x|tgHTlyJ@duS>~uRil|egVtJ&9b3eVmDL}RW6v$1{ z5BJFsB8LoVN-_p#n$f5-CkD*RhMiwbw_K$7Q*3J{Qm9%wGrOKU`9yF2I3T09@;COv zk{-pl{c1Dtc^C_ay{{n@{B$puAK45w#j|C0w000X<8>^YCKfw`a@;t*Y#FbM{BUYC zK%aAc@x<1BGT%U3C8SS1A)Z*BY*v*XI{wI5Po_8yfxL*5yHp#nvm&I;UZ5dK7s2?^83g1FI+;ii*T{& zU#Rp|iY{)j(etAvZ}Hm&F9r2y{@QQFC{@XDt@)r_2u|rrg-MTW2o0{VF3jpnpIVg< zy8Rgzi`u(Ol#3sbE;&h{HDvF-5GXtnpBKYaDAx9z1%e%*@Qp z%*@PKVrFJ$W@ctqNh&cjGcz+wrK9eiIkVlnJ3aSayJne|X8A9_jCeibarf63m8SSK zEnJxfO)L#=85hPw<@Xot4VG`^B?XR6*nsDc^3w5jZQ{wm?i}Egg{2!@R?~;t8?v$LU;iXyBp0H+x>qfh8d^(S2>z#@FKiBo7#wv`w)7uROJ-z#~A3kD?l zB~P(}QSD?BvJ}}2TH!l$OBR&Q%QUnqU0-}#`1-uZnq^2u=?r@RKJGyRH2cI~#_a;F z6gdLC5M(O#4s-!;au>`nI9pjZx}DA^;N3F4St7lAff%ekQn7PRRv{skQzX?PAeG=W z6zv5+@wKRC+m`-ZF-DUe4ln#7b)dszr0pL4ExkISC|mZ+GWd#Y7Hpvq38rBD zr>1r1xZ`gI>#lwtel@4tDzV|ytmm{>W^A$yOG}fq?=wOcKWwn%KZ4NT@&QX54GR|J z@p-`I5C{smnQ7>XZ8kBFBtp^BvQwDc$*f@K?Xeh|R? zBx3s+`C9l{6JMD6^m`Y(TR$(O+b7J&f&Z^T|F16KlK+o_{vRgG|6*3kdKQj`0w#u^ zeB+HYH0`%QFY>5aFEc1cxZ_=rS7X*&&0ma>n8*ykfdtXlJKP&Ts}G$oH*~ySe~ElK zlw+X_*!co_9p-yWtlbZSAl7cQ^G%z@7H(EtlfG3~IFto)tjuDd}!fw+=P67 zQ@cZcyDF7Vhg@l8(!uHcr?qjBUd@?1m#MqmxK%LzGY1aTAp3)|R9IJ1)n(%QR6P2O zebu2jV3A#-xR;c__5({mP`=|Lf`p#27BG~1ht%lxkISWVCJvi=A9u%NYp>0NO z-Di5bd)4u2ucVLY^y|ELT0909)_wUntV(Y(B!L2JbA1~8Gww&L3@2IL@4tF^juuX7#4v4Tjqi$;%`5ctt zfJUj>D6LDqX(44QT&uGB!a>OBsrDw4$ir$x9hDJ~Q9s)$fmRW$HdjA$sVM2*Ps;$Q zP__rg^<*^53itEQ_W*7*)r6!4I?LADAW_aff8bOG&ZbP&*s!XI_l|jUb8P&0pDA&b zXG|PFqIlYug351I|LLU*GHFKmnBv+TK33+QW*WB6%0y`IT68*w&>A>niGp&L<&msF zeRyw-bVzQd61T{8p_-A2do}%OsAA{5-XU``fw6Phno+_I8;3=w4$pX6UV=5z1dAYX zBy(A(*IbLcwdRG93}c9u6?G|n)q?e`%;1~&v7gD-@8ZwsWbfU3%rgux33102SyC*{ zx?=`)?7|Ry-vl$Jfvj%@sS;K8PqioJ$*X8 z#q<`Z3>eD+Qw)(}yTdVFc{qrQy93a`i<#2MN!Yz(PSBEPlA_oqsi&#Nze&RzrokPS zruGsEtA`MD^v#ot2n5y+XWJTtZ8BGQMja2SQ19pqy~vIc`6d&vg_fFdK7RcTiaKJi zK~H@)ypH|b)ZlL>eShPR^*?fNS!+`(hu?)nR?qaGd{k~-9OKiwk~p0SojGzKTU~?6 zEg$RzSNkrnP*e+?Di=x>#f@zldRWwn#KOpa8{&x-pOl}*!-qQ}8kdU!qn-4jjKz53 z`M`r`?9J=V5oQZ^Rq4rvE0}&`sZP6F7$hBu5$#}*UO^vq*rLM0?SaieR|nOMgdGbb zHcb@L{&*3a`qAF|Ii?%OG!b1rPsm%J2F+-rTrm{}_$)||LZ3AIC_7-0gFI2^wt%Gm zGLMC@V0xM^6|Ann6+CI2HxjKUYT`vRLXb0tb3u$B%msgJE95j*4s23^saBHUd0An# z(N=S)N_LqeX!$4OI(~lhDmVl#xu3F(V^;r7d|lJ&2Rs`q3IbeCROJ@{GXU+Jfvf9} z*=chPQ*K1lZ12;|(G-4aHc?Zr6K;Mj#AyCy0*h(m=bW!W!Ay#@67QJrCSXd87R)CY z%-EUO>+^Inj=n`WjIRz0tIoRTnHmWzl^QOKQEN60^z&S0uY|6=_?Y1VjG>~8lzM13 znT>i?^}-8AAT-6y8FOcun?L!EPsBV1e62HeWho^=(3G=@+`Z$Yvxz$GG|as}N%_}r zu-epR)t}^i`Tr|9|0BjIf7(@8+x_?WlBuL6gCT;*_1(Rrw!?!kvXo3p^o7p?MIRnL z1c-=(dnKdh_G$7iJfc2fPr=0RB5K9-gVuUICdXxig$ypI;c^lSRSqFU;9M9l>19PKAQ#an^P$GQ(yZ2kig`l@ zIa`pn#_*X{*gB5tlb~el!<4g?!1R;P<29M!sPrh)7@NdKHp8G+L^ynV&}@jg3seW-Vsxaj z6`GNN5i7%`i{WG=Wc7p1w5j@y{P+b;*^oJ@uJTL9>=m3<38~o=Dht!62~;m9G9#rv zpKb+^8T!O_dzWCaXBYBG3!+70uQ-b3WQAz@53+Td3Wz(R@Y0!BtO`NS=Q!8uMG`~% ze)5BjwpxQ57t++YMT;X<530#B!-Kmb=WqpI+*jo+@&Xs~A#Te~s*KE{-NO8JY{?6n zgI}9BtdkYWVfgeswG zLd`#!^OhP#@d37c*!!Fid_lXX74&IU%>5`(43<>|{n=|AfNc?+w1R6&-f-i0?hA|N zcDlVH{K5hZ$dhNzOU}awW(jkN>p{hcUkHy0GuZo{d&rZ&gcBA_V>s_61RWcY7NY2s zYxEr~Q2?L6HXLEON|16oaf5HK`;jMy1TG)Fun4#rC%B)6CM&23#w493)a--h~q}ooX zsDp!x_66N< zgDk_}N2>oRC?zWV!#|~&YSeE?2!KXbaJi`q+(iJko0?FU018*w1%2d;#LB0AO8*wm zHOf^PjV>eIlfh0jeb%xToJQof-lL|`!Rv&_;n*Wi_RlY?YFeo{2eh>}(u86AH<_&Vj3>G@ zl9xeRDs8K`H&CyY?Jv=wNP#x>O~u)tl?_^2XC|BBON01I33k#G7E!I<7!6IcNHKIw zz>c!5`fbZ^)b)p}yGpc}dz1^NKC~+k8c07O1`nq+8^cw`Iv{YHuZR^utyUK?)eei$~xLA(1C~2qD+uQJ9jmC-$-}?guy2b;qnB zY2&dX&CcFnmeVqRj8uhS#qCC#yXp%minojUWV*3;PQtXv?L1V$nF#Mml`m9{cce*Z zfPYYT9H9jh1hGm0KEB=)NHov7=OZ zN^o{D+{q#4yx=P=AIi>NJo4RT?ihSOUEQ#xa&)GT=auvQj1CcmL9Q<9;?Svx;zh6H zT8wpQd-@Rp;_*Gg_r5`_Z?>ZWn zorTJzTti4?!WB(?Q^3o;v(k%spj#WrjQPQLnX1n(465zJWKTjWL}K1BT&ZTTiNiP0FI?HN9$5M@rtE=k z5eEn+_deAV01p8^awp+yOc8LKQ9E_sSZNR^9vE}kzilXEX%YIX&xr2-r@G7Kztml_ z{QZXd!{O1`(CYi2?~5Gw){ESrpr8Vv*iN9-PM}u8pc8v99@aB?m|z(I^U25FFc0+exa$Q;SQ-MxeyQ#>2wG zQ?1IwQcKvY%F~%c$e@CwKrm%_v`|Y&PfJfr=ktXCf&hpC2qI<@e2Md|zrQLE)89X+e^j9U-V`aQ=b-loO8?hma&iJyb^>J<2Cdq9 zo5|Z#Y#z(_d;)SGesN=KV`Y7DV{e?veQ|;vzdbc!(D%1Ihxb0ezP$*=_r15ZwYPTt z_qDz_$nWnSF`%9fmJyJExREbxp{~a-zr@r^hlzO0QPEORaeZQa(M0L#YJNippN4oG znqNPsqJD|_eE;uN5p;k5xcop8oN}5@W|DdTCJyvMtujv>e$Ty}aF* z4n*Lt8LxL_1M>WK`W2K%kxem78DM@XfwOn}yF5h0Z#oF{g^LcQbGmN6-4H%Md3XZV zL?S^D6H`g*tpqTIa2ipLnb8^RZ}b8B#w|NZ~UuV?=+H+4cOJr}XhHUj}Y3k&_v(w9H}=)!op&v68>gCDcz zZ8pkeq)=g`JJBY#dSfUu+*OQbW{0q08#)xe(TTV{d!E@UAh1b z_Wa|Rv`3O*>co}Dto(_$NuX(rDUzmF0PU+X4%)3Ljp&lQ4m5gc*eN~a>WsG(DN}7fXU%0`_>dlxfy5L5Zq~hp>Uo*M(GgPw_tSP2L8~Fi6 zIaGQv!Z3g@I-nBZH;wt>s-?B2gf(6N8ah+LZcn|J+UhJ2HN%O_YMfyNwH`*zp50nq zrYj^7)N?G#m*!U~G7&U&UbobyDLHg%@s>53x52zK%T` zswO;8{MEVdszTz$!~_dcI>pRF^KzLCcRf$}_rqlpDO?iuxeAGnS{Xw%)#}yXkS@G$ zVPGzXJ?>F%Z5-;ctEKFCavvu5yXd{CyX#r{y~p_`9x@ssDqJaDDdkkTgf6hG?MScH z$0BrWV;5(p0Fr4TIJ)dxIKjQ*x|endGLpkDV|j$OZ(Tv<21+2`g(2J8{9I+xGDdnr z9zqPQ62RZN67hSL zAU>C!&F5+Df0q=>zh8R)SZseRvPk*W&!K~`To@#_mXM|b8YaD!$Kww`5Ic0=uv7#7CA2KI@E_HnkX968?wXk4IW(>@f^zUM zE`$yr05VaHVNVl`hW_0-XOK=ZCz%XrL8q~>=BUBs^6J?1PgTyg!tOL^MZO+Y^n4Rz z-jAXY0sf;)1}<+h*9? z_;}OJ9j7bU8|Tc<8uITd+O59<9nOu`<^>#6St>DI=^KRw>Bz`D>mQG_U4 zw^Vmpws!E#s4+EnT6${7Y$J19;L4^f=vfVHsA(1~jz`oKi!+8m2wI)Fe zHc-S(t$a7$xa&!nTGd}-q&E#Ay%D-f%bimUI}ZP{^8>cOeDxk=9Td<~@1ZwQrg@um=oCxB)jM&I9uLfUT19qa z?gu)&ReEJVPUUmOcSlRJi%rt7_AH!Z9Q`Pxoy;5&m7!zYMS?NK8;}_eB{B*c83DHt zjr4-`p^FE*Vd&}kJpyj^ueol%l6r9WY#U=H!dZ>!$r#hZD1(Zrq1LY#alyTVVU z)x*5(RG+?VQS-v5@hWTV5uq+p9yM|2?_oC=>-XK*F3nM{(4l;?WYi4plgcS(9w304^o53AW-Pf9Ff`;Z(pBhkxJ!yY2Er{kbW zvZ3phbuUlgO0V|&w%5gS*vnVg&P_YIe%kSp@pQ{!1DXwLjix?+mQCiiGQ{We7SJtP z+oOTSD6Ves^-W3Q<4YryAt)ryWO!vQX-lw}S`^v@d`<2Tja%M-PmR0QI*sD5HY-OP zpSJiB#xur(uzM%-z}<^4OhPOb?kzd_?XHhCvl1eF^=I6JPQ`wr7lk!R<9BwL=>?)- z0~U8kJ&LBlsQ@iJH>5{!M(SNg>C5;k^ub$oY7~C>TG%Xs^&6)`A_%>R^AkA~zkxO6 z1L$3*)MLYfkP%2X6EWFyb@@>{tb8puVFvp?$5XZ$qFE7RC6DF?UJDT14GFYKC{<-| zVWtTDAV{tNik1=8fwEe7@(xfTN?)LTZWBPMa#PR~!IQBW`RP-J)i&(YCMwV5xKG2` zbPI5rmv-QuYgU%4A8cC5iOxF4u9{3Y>XU|UUwgC)2Q~ocp@Ss~w3Szo#e?wuXPjQ@ z7G|86VQ`!gY`HI>ldWt^C2@>T6jyj;+VJwY^SXluOha_EM$a3_s~E$+JZypNn6)do zz;S#@b_b&o&^_eTYAFeisp`I83Blk*1n~})_x`C9_RG%!o3$>WdL1$JkYX<@{eItd z$zOxhwg3-?pEy+V2JT_Y`phcL^zkyetdQ!_wysotWfi>y>J97|o0)MA6k8yTe+$45 zVQEMA*)C+Gj|Rq?u=6F z5i^h}00_0nwA}~c&i;UrTHj{^a=JpNpmo1ID@PV4ADzl2kXk96`HZ0b%ZF@Fxq~SV zQeLtwbX+yLLw+J_D2+S(& z%3c9y_oSqezK1`_ksiImBhUg*-^=ZW5jqC;GtB(rx(EYKr8W2P&C7wm@6bWl;%4p( z9&=XoTa;8fP=n}fiI>BuNaZce*K_XY>Hx)<$%lmPxZrwRbI-obaGzvzzTMlz!2v++DgHId%*<>M zaMcunP01MVAlAbHk8H@eT^I4Cigv#ZzG@`KHWg~)`^lr)Ex>9Sy=kbJDKVAAl!3#R z0P~QjYV0(WR!>=gIeguxi=G&IkP%UxS#AyzaKl9DVmve1oQ0E^l#V^4g1K2!!E*j| zP07j+)2XPV3R6RUGi|AAliG&V(OBjrh4aK%)#-)$+Je}oh76;nA|`6y1uzf$azTxm zMMjCPp$S~0jRpJK0MiOnWnqRH^`2!x-Eoxrh};z+2?Sbgo}Rw9XNF;jU0Z&$v?-|d zCgH}6*VDqBJ$~N^% zpLPyfg;M&-nB?&UXGlEH`muxyW<6x6bR7@@7aqG zD}3qShp3S?gTT3szAf737g0q7`K6;G(aJ_cD4LYfL}2^;fYu8cxsSqV7=H^NPd~^o zTO*~g)3%a7F2%}G1Q>mYK2uLGXH}3EeF~sYn20jQ1e#51+@JZ{FUhL*Dk8Wk&C2<# zo~d7TNP3fT2Ys_LF0?!YzLC>U@h!c+ki_2xe4bT5g@@AaxDl52`K+Q};I45&Alt{w zp{@_NG#-TI{+v?i7@;!S00;Uzjo?UjvKVyy0ePgy9E(WaFQ;t)k4^g+FEc}KI04u} zSiI6zwGdL!FVt*ZA`}Op9j(1t)2J-2V@%IXgy=xMv0tx5@*eSovGHqMw(!!BLw)bQ zbieimAG_i38~xzYEKX=~oGm7`iL)6PS^##l4g2Y}n_=9?_vixM#+k|}$b*wCd~`^& z%Y9~xQ?>OATx^g|oNCuA$t?&m;?3v4@vP&J&TQw!bb{A*p#?HZ+2qsmqWU6WNj}mg zSGW&h6`y?7rd^(3XE+nK*=B4mgf+;P1$3e%1b`p0v)peqxf`UZ3q+Ik(2e+tP0KUm zfniB$re+jUDDTw7QMzFqZyi}}@Mm116E3QCe%z`4;K#H{F7{Ip{fQFN;$)uaow+$A`F8hp&3c}*MX*|5#}eEZy$?4t`J)Kv-DYByhsv=PZXwG zeMM|PN|uNoyaM}plUX^DkHFsiqBxH9f8GOQ=YPk_JU#jmuFX7qK1OO$8NRXH4k&>-2Mc&j$_rT<36iF>A1Q3xsXnjF^yK6e9pWb2wsu zaP%JG#BCgW!LD~WA+in`O_aRG4(UGoxiifty(mrdR#j{LAcDLq?zd74fo*~ax%2xn@UK! zEO8l6WZY(2|72_H^zwcN)x|~w;Yv}d@lk|D0KdR1%s~mq_t5DEGJclrjuUku>=^|| ztN^Y>?^B13Mtfmy8F!|%nuB3Heg2iJ+nwA-LQ? z7>v1CX$a~q)rZFE-Z$q>=!D82H(G@|tHfwNXgazx=n$i|LT>6bL3S zj>%VP>25xKk%=PBk?|`IiRR%-C6`!u(7f6+Jf0o1Kn$XJxI`1j{rkA?^B^IzQxu#^ zy;CHm3N@{bxSZK$`E==)lAZxCv1SL;rimnwMcIi ze70qyB5Z=X?xx@(ZcD`-#Uwj>Th?VLel%vaRA?8If?C1sBo&~(c_IT*#+U;#4`+#N-w5d5w=2OygF`SEpMumlv)x9h;s6yC;Q;4D%0k@$(3 z-5zzW4{&rn>MQe15HM&MZa3N=QyWMa>jbefNcuKPKSnkl4isMLMZ%N3WWK(;;qOq z73!@fR2THG>s4XLV%2)P4)|=kx=_&30Fdb$1~L{FYT{Nk6E)nWB>wKY{~*m?ZPi$# z3crzNad%2pC=VfQ;c$WP4~1Tqx91Y&Vh>(xwu%y}{R9#kyDnoj?>vSEq^nDUq>d^L zD}y64pSY*(d+s~qHz9%7+OPy^DdCFrpVF2gW%=xfM}gNWjl(0OwC>nO0>$L!9L@J~ zmC2Au=spKH$a4vHZm(>|)8H@C~z?c{Of9 zYZ~l(vU!auWSv{|m4&$gRl3Mdeup-WdvA>XvHf3JX^=PZyn}j*AtI{L^648e=+2JO z54uNkWRZm%NE!}>b89+->H849^ub%AFj80bjl2;A2_prxo#_PBlublj!{|GsgZqy! zf5S1LuM2TdpE$<$PdMhUWw8GlX#Q=v{S!1xS$~3N&p$x(ER0F7%IwSvcMWb7pN$W` zkT^y`o@mD(pcyBzJ`^0q3+%%ONHhnRygL&|2$h3Okv~LzW!aOV%{t5YU~sZ}^UG(B zrk8)b&k=*gW>y%WnKHq4weQEZ6MgCu@Ch-qqy>FSEbB5_=qHgw8-Y=(xFZP4TfJj% z;1Yu-5-2RxZ)J)2LGOw81JAXrk`Pu;q=3Aa!C3Bb-lyA=$TT|qJKP-+OdP5B4nTCk z1<%%StuowZW|0LgYC>lBg;<9>ajy**ygt;ftdRJq0O;mD^@PbKNiSo}q$2T9>hmRb zXsnG5nlmc)N4$6zaNJT{$|aGTPBHn^_UYj;uPIX;hcO?526WT5kwcchgbivFH8G95 zU7#MfLazYaqf47RA<%f&hrrZCg&P4qfJ`8=YibD(gm+0=Z4y_iya?H>>?hZ&kVVk& zUeCd&YCBw;{mI-8y#er*t|ZNv38iL#o-`$Pyv=BCf8&8~@?t)URE@d3xm z2+nHj23+Y}>qKEd#08PBLs8 zw+-GN{-EFym?ppH&;6lY?uqN!TRU-Oq95i9#$R3arYbCthNUr(hE4h%WHjmwQ-Mb6 z=StcE0qQ}t&|+e&>8*_h$Ff_$Y#y`On_teQM#bA6_PD?bCd@A_D1rNGi9q^sn&P0W zTwAA@+H<}IvO3O{(#2Q}4*mlyEPB$ZG?`4PjG{(bz%9rFy<&X;<4^Ri@H=|9d*-SW z8S>=rzQ*4tjkNg=?am%7RD&-%GLv%7eV$s2_~1@PkhTVshB>jzkKUBAL*s`!yem7W zG&W5k(U8w7K+_qO{=97c+nSt%9E$x7z0dwzt^W_IRsN_!{r!ahr|yQ&lf8n*=Rh9j z)(m1yD{&K8iiU-_f+EF)YvP zKonz2Lx-Y=WgNqICwMC(w|GeN%8mzabI(%^^UKbU=UqAqiVIDE9dR0{b5#Dc;sW!n6$GG5hDDH>w?mAAFbxyIwqI^BjODeYm& zVvqphsiZmyBo&%g3AbD`x2zkPobnQD)2id6D#K)Xr^Y?-Cz8szeQB^K{9^|Pv99zw z6)E4S2qpT%vVNr5;bRIAH|^1-AZ^tdEQu-%>FPEsC17EOrugVn!*x}b-5@PWdiVB{ zw$psuwlnp9mj&`9hyy>%#I?B}rfUqDz}KuszN*Y)Yd^j#FP!&~ch~z+dlu@WlwHVq zPhOv`?t21pDqYKWSJhm!GM)tgBrRWi1~eM5CJ?RB^zt~bJ8sqamXqB>-Q zg`O0&25U&50{6#nF{`XhjZ&j03`IKSPR!xaJ%1G05?rQZp==ZPn*1pVima!IHDI72 zlp30}Pm4-fr%jV@TF&%0*gGy2-;({-)GO zHL*6}!k*oWhkZn8-(2`hl4fa3lvPWqFo&p;{fD1g+X?DH1d+(Lfqgm6&=@)Yk=%47 zweRTUnAvBMsv12`cKv$AscMkMl6DP6QpVKryA;TxqDc$&_ldHhtsp-(q+3 zovKbKFjwa{*V#;_W{@8Q(+A2B8SdP03~v1$-Gx5EDA|j6aZz@5T?gpX$?7;V*GGS8}!jTG@<4^$afzBm`rA5Fy!%Y>Y`3D_oOi!|``M|Fw@C-f#pIKHlb;T38~$@u@=gs(GGd>04j|l2eE z>u)P{-d^rlrrZ(4I2CFq2oX3 zyZFDE#NXWx|4mM@QsvxUQwi-O^K9MSnT174BWye}H67@(kf=CrcS02#^VA|?zO{=+YEcJ$ya-)&DY7*!!H*7rKrr?aAMezJH)7Qm@_fadVofd zdYDNWVq!&vwS;W=!*Z^rIk_d>3tN3P=!K}ygM?%f^09r11?auxlIE<~y`Y#@1CY{v zQ(=R98^(;B)VWzP;ge=A^1X+^dD6p;VGG}l)NnH$N8-uy4fcx16gS9_vD)Iu(J$s6 z5}e5!S4&d-=l#s3Fbqd+#toh#8z#}4Ha}B!+hOD9xg{PkB$kp%oc4Udp1n- zWtlX?zX9SCGFsMKv_La;?w$aS261g8Dtv9%n;W}*`?=DemG=G~Wd6+p zLr40OS4IZMHTa9$bV{ta(HWS%ux_NGMwKDrgVMM-(N<|k+%k!*RK;3vDpJ}K9eK`~ zEir1+LWN0V?{NkYG4m*N^(_^2?iQs$x$B+%$}y;c7`ws zH&ys><;z8UefvJLqp>8m%{kAEUEGLbnCA5nCTz4?9YcwPz`{4>()3!Y)F_A9k>1h< zUe!Pi>-ir?D>QbDN>qs~+}tXy?J&z1QP@s+cdBCiBOXq+?dmwiiXLB{~~U<%4|`WCY)W%#ym>9-6hQSQS*a zFFfkq4X93(Cfy$R5J8aHLIu_do#gJ`x`>N_>r71tYB*YSR{}cgDB;u}9L>e-9<0?R zIzx~=a3C?a982g;)0Xd=auWDGKuDs>QABv_*k@#$TJe2&Y{N{7lnyhVF5>`+@bLLG8dl zo#jz7^*KMT(;rJ0ZH}Uv&bckwa!x`so~ZF4u9LpWTw0un@z~t{iFPwpu&9;*gv9Mv zvD5qFWN^L~-;a5BCkR)y!xpuTbH#Ho?!dFLckWl+QbprY$Ew^x(gdkKEDAR+)$t~_ z-51TK*ghBU!IHXAo*CxrWAwc#{}YLdlzsQAfd(Wq1IMSI^BWa2*h2xvcZRhFt!P5C8~^5mFBB z49AM|B)^*Hi;_<@I{wDB-0G9Gc*3v0u|VmYbq)ON#{ zfUTn#0s{w!7ZvQrGK2cQhPFmF7`f^dsI)0u&VtgqCyZ9%v+2gBlZv!+_S#8IGIvLx zhEnTh0bo91U&&Y{#Eh1fFLtXsdikSGbO9>1p%7{2{@A8O!&1SO!VT0r@e1Asu6$sn zFrEb2##6eWk@;SzZ)dx~33-rzJ+{ROPFcf%8K3X~rp5^lV_w%+!rqYY+ZDo{@o|Ete$e#(8bnQ`-^s8723gN!2R}6q4vOV7Yy$K znk(mafA5_PlU|yB&~^gmZ5DkF>M-{!4LYAqxnAe~cNZDR?Z+Lxc5>pYueQM6h(vE< z3D+nzNHRAvx(M|x+51FSFiE4@6L|@ah(H-aCEXHB!S1Hs)7a~dTJEm{r zZRH~Yknrp@3wkkafP(>Hc-1z=fnBt6{0&!|OOvVm93Mj7YvHtwX59eHpz{>I=_$KE zE8s>RZPg&VOa0fbNA(ru_D)r+hv=%F>D}$KZ^=AXFmQhTUJ)zIFrW1Pi77SzlpXkM zy*tgnyXVUr>RAYz8d?|#ea^G_9M|#(FzQHDQ~0#n9+WYesSA-W%)_tpDTS!rQb$Gs z1P7cD-8}JcK5p!gjKhdW+#ZM7Exzi8*$TGf6l0p3btsy(%`m+jzx0-#NVoD0FIdKF5|Dm?VrW-s~le$W~u>jqIL`^|kM}tlc zp~0Vgs5w(H9O6vu)kGrHRY|8sHS1tBNh4ZgeE=NDqG(^& zM#61S&iDvUb*xGVXh}RWTZl_KhbfvX6i>v{3T!f2nUSCAX)jprCT(+qxR-0}V0g0S zh5&|1GZQ|J3PZFdNp@TnUSk9pkYXqRQYEoJZbVfmIG<#I3Qd6_Lylc-IZ-GmK`5$W^DkZ*U+#6FdKuam4^t zkdNQbcP4&rP)KsDUu6+$}PHc?a$-b!p(2m?+-5>P=Osbj$*IKvzBtCBY7j9TC*qa}ZZc)}pmp z)7rak1L9vLGE;QqpwfYzVN7Q*dR6cAXPT?oS?Q3f8NEPE4 zr8yEWjT;j-h(q{Eu|2@;+koP4IzHjH{mCKRk!XogoU;XaqqOl?NPFd66z#(JIwT(c zS5ok8mFXM3F{}mAZbu01yyRBsC^4-wJ!PMG{MoQ1YgwM{@!Nk(g!SuV(KfnJ+jm1Cn zZ79em_`tHU;XXM@c4`2z5@4|j@ZtOLWF^<#kgH;C1?xnsWbm7BJlrL6l7ufnZ&Cv; zMs0{Q3BaeLsSL)GkC~?v)jXTtfGIuvz>8PB0*roNgf(FKDnP!YF4E>w#*3qhbI#Eg z>Z$ia3b>24Ak&;iy}J6MoK5%ub? z*xG~g>=|jJ7Aa7|_mJA9X4Cc6l0g$)qZyhaMeHpz$#oB)r6p0W#*IRDA01%}kZv1* z2xzR-^&7Re(5yjj(!>-JoTnsU6=NP>UY(GeK-H$O`)$MpMq{p=xIbV!pJKuYe~;9V?PDf4cQBj%y9G~ zV}If4P|?K5Q`})YF+{P=99)g9GCUkAj`w)G6Kp!cT(%vlB3qzj3j8Ud&QW^g;IIwa z>yd9t{zia>bu{;RxS~5SQ8Itc`;Ohgexa{A_$|nk2t(&v&@cO!ADh{X>Z47km}+X< z^bR64ckJ=bnavw#^S?A(73NDT*r?g21{^9mWel^d2pLNI()UIM?Kt9BR^F07>XYQp zzfEREVhPB?K=@0`h`^}ZX5KNo*#epr15AgA!o)`sOWzQ$JHg>Yp@w(@g=gYlg(YmM z1nBF)zC_queNB_j@w^eWiao>q0!zRqT(H~X59SarR6VuD3g9F7Ybg&v?;{u@cz6WQFFJiXKmD%98vMv&d|nR6*o+T6He1KW znzOSz0bBf2VXJn7U|D*Px+`&a^a5hO#l|A)(4o6_g<7El4RUjUrd=Aw8MO4HxPs^7K?S z+NF8RA$?uf=hi`jT;6QP^d`;ndbT9g94Dr-XQehClIPO8K`IO7s>lr`od%EX7afB2 z@QjzCgw|ynnW{{b>%~AwrRKHL<(`@bSTxD2d*d9%lawsVf?}UL1dd;uEk-S9+e5N} zOZQKL@MouW!a1W#_ES#WGN7uCs~sZs9;#DNK{3{}PRyEEvS81PGTT$8Y&dP_B6@_% z4b45&P%_&bEI5jUOkii>NL#RSA%yh5lR<-tcv-o*I3etv<_P%vS_-=25 z_1qd5L;15P=11O%yuB+pB`hXWr9)3ap{tS|CezE574qk*kI@|1LBdFLWZkD74zK$N!2}Id`pcr?w9TubL8onfBfig4D|Z5D1`zaf3qwBH$u75-yK^ z2%?p=3!p^uy7@vdT+8z9+^0iG_iI+@a4nY$k9bHuVQ)j&q!DU8tB86XR={n`7f~u< zLP;~f2?8d*qeO>%tRI%Zp|BxDB*dONTkZ#$b)5G(P^{(KG^~soSjh$laPM}Nx1>Kg8keme!huVK!DEvp8`M*~M zDH|J8b3>cIBIA#EC{P)d|8=~9Vd~Q&3v?ZHn1FAmEwwEAism#nRiPGf&OCS|bK{mP zw+Z)@to=mOEwN6kL%C8O^90m6s3$g7zjG12WjbJYU^lGj=|3KdJTd{*yV99?3nOlm~3c=F; z#4E9C@Hw9P$}5dB-pDk zaxtpPgjm}&r0iY+yw_skLX^@;2J~A4x=zBBX1-e_%11XXc+R)NB9Hte9gX?r6A&y9 zhExT6Cu*^EW*xq1PxuLQzq1ASP=dH=jW1na;d>jtHs0=M4w^ur5a>57Gwf)Iqr{cn zpLC&GN2Pk~t{Y-vVAFSH1tCNjuXa)OyKE!S8B7SihXEYDeaDY^vwvv+@q~OzU{{1V zpMBwVC)nwxaq`r!0{9_I&9iRABtcm?^8YGywl|etnDYN152jI_Zo)-w#_`m51e-dy!|1Nj`YGD)&ot#bo0BJ`2it>~o z`oJ5U?K^f~B7YKf#jg#}D4;@GFapq zaa*4oRH=f(55;O)&Bq7M()n5ie0*L&4IoPm1DOfLDec^hz?2}WnKqN*w-5_^l7Xht zZWtp}O+^NY8@ZG^aoXBFH?jlXF&|A06mVK5qfQ={ZyTG`FuIYx2PJiOkS}5jOHFaS zm;ypAK1H87k8U>P9CTPOijzzcNoy}(p;pra1Q)4c0GVZ$;X3tgq|0(0#xePfN9fdS zlptDjL7+Z!*VvdfQPvi1J>jjwwA?!^7Z#?cXJb~I*;F+A6IMrcW6pDE);?k|fOWjN zYJ`IqctR10?-#Pgl9pyBRgD;73m$+p!*#az2Q#2gX$f%`rjuvWa=p9WGvo=MY3pOm zYIxu6Q4dE}ovNk zOf8~kVNIbsJH!+xG-=D7D~!4OzpL9?pBQ$a6;MXWz)sh^9H=rhRySuT@XgINs65`9 z5qI`iO|!_?%JdxYaSg!}aYHYoU3tVsXoR*U^%ipWM|36-TD0S)}HOt>Zk?R z#cr+eiq!v|552 zncxm!x2GgoVhA_|g2IEo~W%KfaOKI~Et2}fFO5B4&vZ70(x7a29FT`}GMb_^QhY(o193><=g zYDH{2FmE7uf@KLuN*d+9-Q+}=7h=HQN)W%MIHv&fdWN%^_v_;$eiu8s(T8X_ zM^Q)SFd3j}oKr*u?IzIwg(3_F5QBMVJ5}t|Y3gx$xl9Uq8^1AFw$}hQg-}vBwM*mC z$bR)Y9E~nAc!3?;4|o`w#-A!bf;%ybd~!P|G-MS$U8um9WnCV7#+!;Z&mGDh`C^@J zIA5i^>d2VF9t@{5PEtX^OwoFz>JL~kN@nBjtVl~MoLO(#VNaX(U1baCcg^UmzBdy* zIoSE6sHac%LGO8sbobDD&G`u4t}qMtr0bK5RG&93_VtYVnK+bI+H%dDZTQA+PIjnA z1{7qu2_5T%HTC8r%n7;P#bU>InTF)~&(X~2qE6^qU>~rm{b}xH*}W^-e1AM z8v@=ev6S-M_q^lWWf zncBUkD48@l|9m)8&!_Hu)<@b4s`lBwmfy#cIJg2cOc#ZBWP*>y5C)T~hMSBt!Y9LM z!6OfEAv@wyy#xtZq^z=G=nVKNk@7*@Je}+-<;O1O$vSzes4Z}!dPkZc`4ob}%4kf6 zFtLaJHYi*PCR)S0)ArDnfmaC_Uj@cR^-ouQ4Glau{_ndimp{u*8b ztmV+dS&Py6hur&-B!cP2jDs)}YZ_JiE?}Z=LC818oy4Bl)$*trwOy=zF2(wqydRYG zis%!3G18#!uLE*n#%*rCy4U7B=HmVQc!|)(hUv23RGEjDxANJS83C#F>nw9rgjR}T zZ$5w;;Ui#G5ggIYO$?d4qcP5BsEY%eq4GhGs+rQQc?mf*S|H=|ZTs_Bc3Lyml9{Fb z03B04?9(#>r_SkuxDsTPIU}n}#fMDNET+E6tycI8_D&M)3iS61HtbfWDDj^cFr<&Q zLDaU!ys#VTrB!Oq!4WQgmwYIg?*z65ygk3fvM653G#ZXc&I#iB;k#A1kQo zXL2K^OYn!{NXR{l2cHJyu0hjPpMJ|lcvcB5izSN@)<=aTuuPWUWH$S@LirJRzasv| z;RjPXlT8TIl1r*u;a!F=o+*tIRmAAbBr8I#)QF*G%-#&s2$M&QJabvP+HOnFuAPz- zwUdwf{&T}u7qNm5*=S|?1LHbd9C-zWS`3-B0=YG(P<4K(Q*moFJ0s;YJ$hqojdFm3 zD~?tKp6Hmk;OsBw(xxhb#El31ZTv3^=Wi99;`@#h2h|5%$PC0VUzl>g1#jx<*bcz- zS;)_Q?YF)*eV4)Z4w6;EAVtK*Q=IM<<07eAHTQGKm_kfRRzHC};xq zX=Pr?&M=R>(HTjod=|8UP>G+fs5ce^=*`38b$*4pVk))7%Veuiu9e!$yv>UIbt8S- zC@u0mnEM~XQI74Lwebo!FzqBhu`lP$Af`r(9(w$Bel3YKay<_`l%4K|%oB7ilk zUa16 z<^`lvb-Zyrw@|B&qFc7s;r7nG8x^K)`!+Bt97DDM(WxU?02=)g#(3~c)H$abmk0-V zBbOz)04#;cI3l)s^kg^pLnWZ1?#YNQ*u~-44WnK>u9@Q zWx~)KtJC*-27g~|GOx_0+wrBZ9Vc3C=wyxbU%*rmI6pdQYhBLvpGrFVD6EEVaE3JeEFb+{0hQKAvGpLlrhJ zT(#eAoRp{n-0mo(v?j0FsKukJe2stp$Sf$r=yjZw@A)CWPP)J~G!i#QE+FrbbBR!P z`L3GNq_2}i>A}BG*%j-@IPoib`NtB7k~#)74Fq@W4{|Y^A)w|}*{jSS-5)hAGQM*O zv!)LO?TZF{N{}f*LCeoAhC4!^&sQP(BK)n#I{4y_ za+5JgE$Oe5nU4K-9h^Xfg8mJmf6^@fsFnW@gu2?eSc(GiY3B?iALT5aZ4F(FE&k}+ z3siq6Yd#Te>7+|yOhrX>v6aLgSZESLF$>~~24oe{P^1<*Pzpv48`@Y=m=zs{lNnvy zBQU)eRh()2VeoQ9CO}_V3eW{<&HVj1K0pIezx`jw?Gy@HZ*|((FGVa5Vp@&H4kl!{bU)f}*=PmoDViOT}zb)1abQM=!Uw z9%hFX-ls=xb=n`&)9Biem|0hjDu*jKBYN>ou%S<=Rs&z8A(kDqE4$l)VDj zQPqz%S|SfdJruA?y0;$hdv>3T?(-DZ1`t#-QRF4}xS(h3=QQ)Ix70OAoo5P&8RLD2 zKNUw2X`OcoQF}JeOBP8rJiXRp9Z3fdye+Z3^fw#h4r1|Z4o2>OQ{wCBFyKKKY!^sV za=r?8ceP}Gqbu5Vt{pz`fJb}dMtTY%y9$_!wo`**E+Ag1qgUpj7>I`adHf!S4c8{` zR+9;QyD3cXi%aT3By2Vuy#<8nL(<78vmb2(>_8Um=%Qrm`I^qmqb^=R}5mU^nOmWcos3Xekao5(mfx zSM_v?nQ;nc!mVUI#hbuF5549Y)fuBEa|P>g)oHsNX0S+WV=@DTb!s8vjL?kXn{60Res}vM7lfT& z5QNjTdk6zaR_=bLiVZ*%!?LVMZ#kRY zR+Rj#F2Y9yF2HIbG?^PMiG}oH^9{?MPRYGVwS+IwQ(u|#m zj(BZtIgslZW#2}SHHhs;Z!R2ePi?O0kP?Rc!fcw2$A?>pklchN_6YQ5&`^<2(kEGS z(pB2B<1IIS@RCT-(xb8>G5Fb#N3XSDfIXB~vCtv`Gii8s$jQCjBtd3e9V@dkp?p%tBWCus%#;uni%A}-Iy}<~ibYZc zsuyAhXFnQJ=99k>o7&@TT%*)ISw_lp-?>}Wwt`EWe8g9^RS^<_ON1ZeG;gS0t<+d` zJW0%01{ru}%{#hUsUU zGF?Vokg4UdjIV(WluO4bWdh=mhZUAU|majczwFk0BNjJ z?BYtFa}XMUX22ZOnanX1?=1sx0gUKKezXHZjBp^+5(eOpVS4YSvHQZHO1j%c;ot6W zU$@3b6*{rSPlp9dg5jGdg#(B?QSIOWFxrs0srU3KGw#EAgZcQ}qQjx-&w5Oii!5eM zw!tyhmxykQJubp)MOua9YEMzrs~>XnzM(nGi00hP(X#T=<5SQoO|sTbUfOEaKKHC{ zR5l-6bg^5P<8OR(TD-GZMv3wy#|N}ZY?@M?56XF>P_;}2)Jucl!YdTsrw z3_Itr(1kHFg??*}hdluEPQ#I&F9F*Qkp`zXKqQ}+v~$zFXGhNscu@Baa$3x$5`Y3K z8NHcUuV<}peX~otRKeG{uSSnVb0xs7Jo!!aXg0NeRn}eVl)s+V549o$`ufs>F+aML zw!7ONvi91I?NJ4O3R}$YQ$`zc#6&JqfUyZBRZYbE3=m^SEV?@g5syKy!LMR9+$Y&N z(S`&ADymrFQnC}T4EP?=1LB#z21QuyCt?0*PDvW8CoCsXntVF<8lK@SEY8Xn@d zPD9o zd~x1QXLas41G-oqjVtJbEO(n=&pC>OrJ=ZNszZlD_ecVMNJ=r|_Gm(H!SlIpq%PCI zHrjE2B2F>{Dnl*1_^qdoOSDd<#9*ue2li(pgljmS>>Z=XQ=IoQ6(5%?tYjj!J~mCk zn-9zPR%{QMy?t03mFL_@Q`6~2 z_0pAiG_MBO3ymXU=bf5V<=&-D89=FjucB-2rGmW+H)W9gNJ{}&EjgdG9la%wty!t7 zrJ|h9k|bcy8w{IrK&Unt8q?)&z(-?Y3k;=VTaKCxBAEy#Zef5*ez*iM@g8*IiE)0( z-4}~6+|}>zIzI>B2shcIlTmG+5q%_meWm81p@EB%f!c?>p~JwOTG*Mi;@6+tOC&VK zAxQru_~bBs6!WP~nOk3TD85Ev_ePi^?E$C^rL6KN9hjhK?B@g@2%Hl~L67+oORGb* zAjbifAqsQx(yUwHR-%(HT@;ABuix~!b)Z|A)fw%2oZZnxPetyXZTN0 zb6LlHM@$^yLDVV#&5k)ypfa>Y0>E(7F`dX^O9@i2Y=;fa1QFNzXi+zG9M67_gy6gg)AB+TY{!dm+{vu_6V!&o?euSGM1Au?qa&&&9sWlO!%TVgg{>^*g|c zFsJ(xkl!^R_XQtBZ-s?B~3iS*`) z<&*Yu1Gs$GAc7N*@l6xHyS$Bb8*E`HUahvx5|TZofUJ&$#kJk#Y!>g~+Tb|!7OhRE5J>*%gYoLoW zeAcYDWa_1#GSKCRhu>hi+eVEmKK7$blKLVaSU^lt9XsV9$8R30cJnkQKsHp`gf^fn z`*Wh9_WMNm70u~)=FkX-!p#qnqVIKuUEn4Hz=hU9fd#316?FNpmTlJ^dt@&{Zt8jPd231uIO^vcRKpE7Oy zQaCFa`z4JkIn8RJfImWhT~#4uCrMTGI@HI?Xp;ywCSg~JPy}pJb)_@9G0;iWh_dfE zHq`*_HX6O~v{{oE`Hp@5B!UR!B`u~0oSaE5NjNF|S@dEIdXoA@EZP&&boo;uDeD}* zZlgJ&PiE^Yy97eIq8UnH&{VSjR zNl(`II@a+z)-8CNHsJ`qe*7Wui?fVj)9cv-hLr9Wk>pFFvYI?nm8DE z3r@6Kp!4^Iz4wEr@cf1c0S}s2j2>%5k7Z!r#584U5qx~g)>_+tj>-!bYM;$XM)n9o z)&Yn%!=J+#@bPLBCwD)WrvPN6$+HKft2g zQ#nkf&i$-Njb@R?)RfaZAM$fLC~NRFOFw<;vN8@scq0Ke!Ch`}baW2p0l|w1Mnnx` zNDGzCq>d7o-$T4)(YVau!xFyvYMrXAX2s#RgRq8kt;rh~WCsRLT3 z1J=U<^!U}jd!{p=_!DJ3$a}OZN1r4%5Ib5|pKnW7BDZ6VQVE^?2ssT=F~gn-4N8$X zeEK2@wr?Ok^vpOEb?za#Mb_qI+54ErA8DI6e42z{|}I+DrbJT`Ld`F68I>kHMy6GgWRJ7~Cy z&w1IDGC<#>T7pX7n<%YpyE#{n1rD@gu}S_=&(c7TbE|qf(74rfd9}cA=%PEY$WK0! zcr;MMC`Pr_U~!!*lAwCp2)%%CC67XJ#I63Wi5f{nyzq#^fcS@#rvPYeL!L@cT#MAA z@F&xsN+e85eTO8m4Ofca?)(n5D&*KAyiApCUG>%8d@+P8&ZJ$Q%@2uflE!qlfCQcPB!wZoy2>RxI`NB@J0l?t={JVu-*2vFA!CoS|s3 z)ywycyoLmMgSGfu+K^k%DA6^2d*GzwTnxPpRc)6r@h=f05`=C)3}44l_m+FfJT#zU zl6y?MJf@O??X25Q;2C*oR24l#Wf>y0#4EXuF)i;#579NFAxbTs@T&84#k4j5)8p@L zyW48K#33MPy8Z^5KMVH1eEtI`n&b@a+<*DT{kb)LlB) zY6{oO>kW99$h3`SlT}`XH5zb(9Mf*GDQF2Zk!~3!S&B-XWnVF!3cua90~whSf&!0Q zIwC?=0+KpG6V|BqSt+}%fW$NtmQHo$ojX~Epg5m7CqgUwoHf3mk;oGn(@9Cl*m}b; zWW-4G;+AOal%ppirkp-G*tib<-FtVcc7Co*M3J%6z{zV)eB9427V~LSvn}L#cXA@t zBfch2dqpjR#PI=i1NxcZ$6guz1Sj936fJ-$#0fpSmIq zvSO;!YKo|>|L}RhoX7QBiwywClg3R9QobRztdRC5u&^9dEJl-jN&5&38U`zb3kd7Dgp6A|MN4Z44v|{Ea z9b*4VM0gE~iuM9Z@rts*kmR+ zkn872SG-W;chr<)EH*&X>q26b1%-e@>5bk|%x7-Ehy#2NCrc6xK_Y!Is^h&o9*}sO zQvg)g5I$bQ1SB%DVY4KBBgZa$FMxidS46#uzY0GX=S-4h!4)&rayBy9kj2FNDR;j1 zb5g6VVY5<^NOKut(#cceyqlPYGC3wj6{V3vU`5p%w+wvcWq_~8BvM%&*ju}_?w6zE zOFlaY-s`gR-3kX&sf0?m=6DiB;1eS>k?dlgREo8T%z&vOPwzOaq_S^3t8hO`_@K#h z6Z5hTk5Wq3gt-(zjRt}4T9%?YK-b&L+VC}p7sM%Uww?%?0I7jI>8+O#VS#d@M4TBy zG0rKW{7bL*OHYNyvD-`$`#|AT1GCLmG>lpRAF)&c`crJ+4%|Cue7M6r84+ln&;pjv zrS;UYfgWJPF5mkPUYY3(z#tc#>u~*~2vzW;w%FV`vM1n~!n3;TDzUi&Z>b}B74n2I zHHnXDoM;ZIFj<=fZv(h7yfX1OCkD;Jg9p)(m|7aVeXD(B7p^OV;7^TW^&q}CxCHLk z7B7g66yVe}1wPbG2E}h&68>tDtZfKr(10zH{NG;Te^$PKIjI1wd_w>0AX76a)!(J;h-m}ruw!5d@OWZE7T@PmeiQ@x8GJQmQCNl%xV60@O^Vu#Qz-t3E z`JFY1jSR-IjXL(c2B3o-qmCWPCGsg|u+O0(Ifrlo14r^DD5prXggJk1I@4f~hXvVg zx+L5oZO*F%{rwIKJ*CsoS(xQYye+^~A_yUz(5aG|PN80lZP?0jMW?Q>ni7$HrOzpW z!3}%vZPo^`oERpoU^AF(cO9A;4fPy?m(0c-WciMj!t5e56DNrt7zL$T0?3&h7qHIo zGH-5ZfN@=rPNj~6r`+xriTfRf^O(ergkz=5kah$N<#*+bXNfDijV`r*!@^KABJwnE4*7c(tCgJyIFR?vFPce>q2}KdT{(>290+KPldO^fLKNiV zhVbnsI)J430t4kf$!6Y+7uAnqsU+Fw8}Dt9i{bJ;D!x7h9e;cmP*m& z6Y}TCZj&CxNiNUdv%5bbXK!kOsfpunsp(H}i2vLE*-p;h&fdk|&eB-L)Y0|VDTF_A zRDrs!3YrGGH^Z@+lqR@p{(Ry0#|H4j*~M8bJ#dkq-@g)p780K@rH$HZnlBWjA=G={ zV$CbOyxWlxP%Vte82h$%lXXv;p4l2ITs(i-qUe;S?v(MQn8sPKy+h&Zf<^J%!Ic@qIug5a@0ai^6cT-Ux zOD}MHcgprOT%CvOIGXI-)6%xp*VqCg;lA)y;d}Y@;jD4`lxBQcnff47hI!wBp(tz( zUvr{pWLj%Oyvk&> zVve^xOD_y{K4xm0QZ*(WLvgyu#TTo)pAXgb*T+O-E2gJoq_Q4Pi(5$R<}>34kU&J1 zq@jnGTjCcupj=6#x3$<`aB0`w4!hkRrTdm9_kImCw1BNBZ2}ef-bTa;@xy=f_9Xa6 zlD$elET-!ASF9>AjCVcVj-Dl(tYm7QQHna`zT+u)yF0j%?R<61c`G-=$7EFm$%*Y3i{|4liszc1+y}@6Jk7 zBo$iw6l8plc2U?OKz}7&=^$|DKr=-3C+)mGi(Ynkr?OY* zxab)!uon=~GVPEuyt8XXb>t$W$lbd0gZDopf8my56MCO4$VuTCmap22S>y-_T~NCn z7ZiKGiXu&-XO1mqE$$9r2zwW=EP@L0fF=R8Er7fxwucDmMtqXpS^U)vc}dKM?G{?P z+PO?IKK3oQR53nISqvHpg_6)iG9PlA&!s5VBmQxo;LB|sKLKFKI58|u0wr9t7gk!- z2R=O6Du0qDclxg%ov>tXhB8$sV910^IMM>W5DiO`>jnwcr%^d1Xvhg$-WHp!mpQ_S z4s7{l4)k1{?4C9~9HbPgTRX-8Uthx41F^6jAM`Z46I!UVn{q?zCw|T=qCCdRu zy%ysnG3lNGwS;pL++(&#$&|(+XyS%x#tzA*bkBbBV(EM8xwdnDp!oVu@-D@{fZ}=nGq(~k~=97j!>(*GGbctR_E z#!rxynYPBAv${pSCHqt0Rov)Q1)NiS&JGd&V3O*60TAp&<{%ceGytE z5E*B&l7xPVs+szC==|Hxl&ldn4w0V@lMC!j*+RKS-nlpWif#UAQTf1UriaV=)Mukq zk5_8ViKzITafjHfHSUg=*DRukXYRnUSMMAoylM(7COp2wJ1p?~0lrNKVXy_PG*ACn zY5pzw>1tym80+qVj^78;kDPc5gNy~b9TR7X_ikE|B?t;Aarl#}ac zVK6~SWUF+8)>2HZcnIDba5j;~ZyoA94cX`z5=Mz+xrpM42 z32cu7VN*S{vc)gqU)RDJ$P6b{a%{+iwEG8g%eh!j#Q2RNdbtS5t_n*Z18o_@c%t@U zI%)9*V8KpzzcrF7NJph!BxS_MHj+8Ja7KpE=x;;yaR5PJUi$BB_38z+1Q{1Rm z;UvPVw%C@ECOPf6J6F*92S1RtHDM$wq6ZK^7_o}9AWNU+lHKm)NYiU#f2l08Oo_C@ ziLM$F*r6zhU@?Q%ZoG-CVii6>8E`E(m4GLWn0)r}+5T>bUhC^s%qGu!);7V*zjo8M zd(izFVsAh-W*QCq90>XejpOuOZ<{I@)u&Hh?)*y<>r&M{csyr^e;MJRZues>HKn`U zj3C06rUbc~t~Ibv>@5n8S>Tuj(P>=e_Cy}B}7H|f5v#yWZNusW^GU<*Dc&=BVowRdVT#ZtLpOm2&B zjYI6&)hhVRadcZ<&!eNA)P<8^lm$HYlRT44KD-PsEmmVtT+9Ld3c-irgR*Un0MJH* zcK_=Fw;i9*V)n%#1)XfeltcHV8j_k0do1Ue%XoLL73J$c z$CQ!>PkmaL_?}9v{lU{ppMpFmY`E!rmBXqqxwn!S8`*==c4 zct{u(iHiUh4h&VvzYvm1TANb!mf;s+SkP`%_|dLbwLx{ z;2$*KO|5Hmv#L3SgA)=hhpch?*%xo*6>TixUMv*eCnvGr{`Oh19~AmA4}1e+{o~a@ z(SKLY|3hT`vMqD{zc5+D@=Jo~d?EypXqh_`lTg>7a)Lc2EybzO7{XsI@V|);7M6zc zNkc9Wm_#eBXSG;h5fRrDDi*JGXCi(3VrvnuTnu|?W_Eg!?i_vAeswbNpaH_D$YQu& z5z2dtV2F5!z{_-j91TB$r)hv4ElSlqhi*uwR@K@5qidBVLRAgfl3<_W&M2mI#Ln}L zijfif68Ii$?`P7jL%K(4wBPns8ds8uvvouFF18Sh2w5AV@tmNfU-E8o_ zEsgA97(Jl5X!9qEHp`EubEK4+K%FjVak$SBl#rR2=kVdG1p+0l88y__3Ao2)XE{bQCKcZRz zi&RGpZwernRb+Gi-b+R-si2Z9KVz=EdaUp(GiytMnXUsf^YlMvX6b*2s9%{`&Cc1? z!NK0i#neQ>;Xf4VAEmwgzqg=g)xL(4=qWK25Yf8Xgm$B+W(RTnG>Skno0nfC2ab+s zkX($uZ3W;4iRKD)t(ioa4=GCqfKDW_nwtTapwC9Qcm%w?UJwnyE;vM)a*0c}P{m!b zv8T=zC9t<_U5seXVp!0IWUZ1XnaT|TIe9d^X-OPG8uhxAjWvB;nan!!P4a3^5_Xr$ za)E2w&Wzp!eed8?ces_0r2(2lH?S0y4y9DG!}LiohKbE|@+n4hs2Eb7W^#+<&JPx8 zANu-nv@mT35*4uhV`Ah0ian!nfZO~2mvM&6)a@q zqy`DMTt!-?syYf`o-HK275r>$G0A%|&PmEi#+_>1o0ZB-p22D4r|2Wsvkg@yIy1Ry zP4PX>*k%l(GB=Kuf;X-ivA#l#&?z4dyM;}*^;@!=)WzzD;9N>q`driPMZPqsWG6F( zUF?Ks}FbA6-^MV#I^17o|q zdE#7_nZ~5G&($!8^CZ!=xO{{}!+x{<;Z}*b-rhsrgrGn>C*(ea5QtZk|EEiy{TSGF z8g4b`L8K|1o77|1#qY>uNKCm|UH)sx^AhLA_!BbfMHtxRv&_qiO2O5AUU9Q-Rt}z- zyuy9p*J5`lVFX0avFVA7KXbEkBBM@nZj$TcjQpr;rt<9o$>vALcZfKipLSOIGrsim zFBepTUOqXljay8XbOfmZkPt2t9}SNKm#Y*8r)3}4r3jZxx;!kb`x!I48ad7be0q*X z@3)KZbG}TU|CSA6_J(ltf!UV(A4SQ3-L-rcu?NnQ|B3}u6H}8vVxj;T6Vrm|uYh)R zE0`+(&+pD!v>7l!+5O2{;=xTf4E+Qnh(+9%=?@z6GuZLgo`oo^(EkVJJGEd+?hCU% ze4Wm^2i%8t?Ra|yu2W!B@HimMu`mCeh)Uz;cA!nPJ8BBBfs*1vCjo zNOvuP72a#1cdl6tV8TxY1E_$Q!$P=XS-Td6$NCWeu1HqW9yhLLQyiWZPDr!ip2Ll% z$I0I+0kyV7N4=k3$*r#;zpfmtaxWm2(Y7WemTJL+Gk$jX*b&)k@`f$}@IcmJ)H@$-4}ZfH`S#ZBSkoT=DmJ7 zyk~Pt@hwG!UPy5!X=i~!lWeHHtzH%fEMweL9PEKWKL!_8*|%}zC_Dz*t4zwFWm;*5 z?;YpCls2VQqY%VgiVCbjl-76;1qt7G5IpGZmufj|@AKluiXkLl>-4FA9NjNQi+5v6oLnzZ77|5aoI20SvYU!tw*Dfpc(4Gn=zzjK=G(2PMagm@ z{WYCP8_BY+DStt7lK!WqH#nZOr`Qq$Dxs<*V@6BM2uesOf9x20`oR(s6*Z*kXS_;7 zG#1fRK|dj9EGcKG;vDqu3Q9ou(T|u-#L3-ra|<6XmLU)SF{z%WXi#279kX`@-`PXp zRMAzGM-~h7Wtz&QafzC{?I$>IrBkx9+wFlDi!Q4DIdBo>EC94aM~A|*2oe-l@M3K<&EcP~z6ih`P+en;630hOu_IsjRrSWpp6 z8UxHqn2d&an}LFPQCFf>9{l;8!ZS!G2rtn^7u0ngvT;#%nD{p^f=~Sfh-n~tb1|I zYG?%%S64~s)Y2-qCBqc^`6h71d1#7tPf?xlc7sSp*j>x|H=>qdxN3f~fuczjZoTL+ znLlxpFI%SOQ*H}FdXa;niH$IjSUzzEe!>6dXKI^kYO_SaUA2)mKry2pt@^TO82Ocu zt2k=Um!Ze(h6!GzRAj^Suu)#$)+v1IKoH`w01=w=4K`8HCe0A_+tVUK&SlY91viXo zdhY{^w5DUBaMMfl6-gN(WcS^&Bu{@GDGuOiXgE^6=rz0J#5Anzywo~NaDj2q z^V(fPXCzB!J5?rmYv#g{V%HJbDd8238yt;O5rP+6lCc_I`NXK=XZS((4h^adK>qAlV(l9!L*& z$I^gS2@R`EN943 zjBda%tSN}JDl$~~j=umm&pH+6*)I*K<#WP37NiWEQAfWEdN1vh9Y`2NJcpW77XT&P zemV2giL!@Ps--s1t31M1l6KDfwHP&%jv(l(7Jf(@!V7n)zSrtv0%HMm{y}(AyY9}C z6-NM1{A|fQGQlfaqGGJ007A18f!!^V8uZR6RixL4bJ%)knW~VzLK><}LBs>}YDesRq>Be?W zGRA8epMP^q?35%=OF$?U{|!oisu}-y`NH(SjCUAaT`X-FW$ld(Z7jbS8rhis<-}tf zEr$pygdC*L9I=M%2x*u{ns}>@8qOtTosg24dGN!6B+6_91d%+In2wGnq3uzxy=3Xd z34%$4QP0n_=4E2B2|=5PHi&Ndj)kK_xPScI?RF=B6!}W8fjdw-IHMaNSW*P zI+RLk#@7~Y(|%<SOwEv2_?ISdSvJFo9u}C2yUm$Y9eTYe&%S!WO))Y`-)2jPpc&FEB5Y0Ke9M zOVWR?yZuWx?)R4xb+xs1|35xgMyxh)-whkEwqO!RK_MrLhcsiQUA+qurHov^DJRp7 zdMIXfN|{ESQWadoqg{7z49?i5rr4)<4Rw$AOuyL}XIqAwb8WVF?sZl>emr)UH9!eM zuqlu7kq+x?cR8=!UUlpMjR<>e4yv63AO`kXgRuc;o4Kv@hv7tM`q|$IK>;{-8m$_&dYx^GCxD z`q#PvaPKFP$wZD^SW6{nj6N^I^blh~_25XIf@ezDEu(#@>)x@JAh2NBt5#=Ni{d+r zBreVa7m`lMnbzInoiNa}VKZ-@`^FqO)NOh82vB=)Y0gEXDI z$tTrGoj2`!Z&ZeyhiER>8bv{R#{zd{M&ry(46PHz(cJ3!N7z{_AHSO)*BS?03T*2P@H>2@JtlUwxniDQa)80MDV@UYIX1%4| z%I1?RgDG##wNDwJD}KH+mJEs(rQzd6jn3uml~hRGZUyC9Ks{Lxl^P^M^E-phnv22# zw6u{8;}ZAb@=?1ty3+CZ(0qDbV=e6)=RLvHLcgbe%3AYPfDPJMFY;!L)A{eJD@_`F%sUQM6^D6fZenfCla& zf1g~);HQOY9PoK@1afS=d0NCA=evcSt#kxwfGlECE9{gsQW#tAdyAEyiBF_k+tFKn zn#4VGU6wCn?4e12FzF)3v2Fi#bt8({CrEUSaxftx=3s>8;G>#`t0@v7W@6?*y1~K( zDMo7Jhjzlr+iNpYxy7JFi0I(cCNVky$;F0SYDQX_>MK87E)p75cfLAZUIa!B_r06b^Y~&_7@P*0wz5c{vS$UF*Z&F#Kng`2Ump{@*tl za5%@s^z(lV5i>O0J%Lukd~OY#!*Eh@@&>|7;1)8eQj*ljLFk<(iHOojNEo2gJ=W4VWr_+qUzy!b zAL;ja?w(FP?#o+GK^^kXgC@dCh4=fg*gToxEBTtVIP@pacbM2bc4<*OG3Ej<*gg6D zt*hlY*1nE%iriy%;O{1$7~WREZSpudv;**ZlA}tuoAGO!m3rlHXRVvK`~w_huo0Tn zIDjt5jl;W9OrMN|Gc)5yGYn-n7!X>w*IR3vwe6ZDdhfQ^^_o4i*dCs6y@})&h|``( zKZ78NpCfxyr4d?w{@@RBUv1-^yHO#dM zyG4eGB^95)w~CH6Zb&(xoz|Q@_JkJoV>q6$SLjB(;SLMBlk~!655~cWLo2fxd_?le zyMqZO+(~{bO;U;av^1y@=5RCa)~R>mERKH4Ey>ERC49`R>3Hlam^Wk8SZz6j%Ly-d zqo6YQQ;?I?!^<`>s#qBxR7l$BfNs@HCb59Vi;WjRCOS=X++ z2eiRF_Iuuy5wl1`JMGmreUxI~hHEXn+EC)^6~bz=Xr&NGT?l%x?lQ|O_4V^zFPIdz z5swNkhUzujR$reu`m%=H8bghRW!RxzHSWBN5hv$#MA_j1L9Rvfp&70nXAFz~hq}88 zYU_y~1zw;)30^FCi#x%+NO5;B5ZoP#d!SIH5G1&}I|Yh_;_k(Z7AO>Lak%A2AMX4g z?%ap_a+xq^PIf=v@9v%hlbn<6(#sJR;q%E)D}?N&8TE@``B}a$@P3QFoA!<%4mH7c z(&NizP?rnA*8_3{9cKo+SYqNHc`MoBdqXNc(3nE_r=w`jlM}2MSDbn&S(0Xi9cKY39aTw~BDi!w)aG1+!?Tls{?jRMcij z;TCb&PE%)Yb`bk6^?hhbVJlzfh!qfp&2y9+%BYlSLg>ZYuvUlZFyo*co^VTHa+(hb z-xv@KUf-3Ga^HBascus2kI@T>I;n<7U$8em{La!G8gZwOvDeP}kZjqpV5^hD?aDi- z-SDkviDh%3@p|ej&zocwqjyPRhi;setgeGRov)LWx2*~jw03l-fFKJahPDq^LPn9{ ztL~z?=of`U%kVGi_HWA3OAo;$bLW{%YY36H|tt<`O#JclXKH?nJThv z&1H6LVl^i7*XIQTLf33BGh^wGeK7+kPGoN7`k`L({n;Ej>o(-$Ciz%+)PnaRR*~DZGU=UjVrtkB;dCdRkt-d{nf0{k3JQ?PH|1}a!T66D>~ zB2O_f?6&~UA7hgftv3n_7Sc-f7q;m3Z`WPX8_@@!(y(LY#*WL=J|wKNq_o)%g_dk$ zMox8l+@e0r9*dGYZ9E9BGVQV!!eX0G(qi4Ve3S(I5F_ksdU-jxXi(GDZOTj6>|Lve zUgiE+d6{;+3;+1~&$#K-(i&n0U%b&pg*y>)8X&xMX+FIvnL`7U(BXu4_|{o$&o_LU zWtzsGwl13y6ljdOoo<8q;Jw$FTTn4J^KIF%G(e}KNsG2?_?DGx+l8QF@utun*+;K_ z^$x3T35jLd|5Q@Rn`7fpZ`x{p5IXvrI;A0M-`s}r%!1e%**#9Op*XK-alPFaYgq(rZF=twN=&KANg6A6_~!O{5sB7X+&-?c@D@SMYqdmhfx5md zu4aHJgT>aCszm++yyL@jTQWs{i(swX=O=ltYHc?xg>k?IBM$>0dfm4a_0XU@)4FVf z{j_7jB;5)+#>Q6rp#X>9B>8k$>&+U>vW}Nmzh@zk1NM#n9Mq3jW{x`kbgpCB71s(^ z2HM{Wg!Ca;-O-1i&Mz1H6lTDMt1KDw5>^n@GlqI{eEhWSf! zSDUsZ#Q_P?KBY@WLxS5~9 zJS5vwZd&PPK7P|TVY9lMWN#wczD(gz{OK>o`C~%f7Ca|}TPuTXhOH_zPZi?vVf~A| zE7X6HrzZI4&%`E_U%KN^L@U$KdFPNQBt$&%sA2aEA5v)ek zCmu7kQ(7^v|LAfKV_(O5iOj34d-V12XM>!lcdrcsWe?GopCNgX8rBmgr-LyQIP1UPWTpC|FIExu~ z8WH18{1vz=<_PX?6l-1G+(Vzr5Ag}c>TIUQ!IZpP!l%ER?83)7|87J!Qz{qRx~XgB zOhhu*&ngPa| zK4*$*kLcTRkjg;$n_q}rkB?_~TaM@gh``(iCE@ja0wn%y5z%=*x8l*UHxc_DF5W-r zCuStFvExT`AxoOWn_YMKH_wiSL&-!n@%IJiKM5KJVNZO*t~=U%fEaduXlT%?^w6Ab z{<~iHw=XbOJTijO_|auohq#Gz8MV-UoZd~T#r<~Sa4r#sTCAqer ze{Sk6?9RK4MkD+6PS~xFmuCAwF$JZ=YlQv_J+Wo0;c@@%h5Pf3$spm`T&YHD6VgS~ z`;w;bZ@7(P_FMMPmOW>_8qAoyJmX(2izke;|6TW`?)!qNX1#v`I3Vgv@m@CkLpi2)tn~mQ~AY_8$SUMt@AxivdBuqNiUzqypM4|QW#n< zuht^t7!njW^`(;t^1g30^+u}0zJ3ZjPW<|F%CBAWOQ>=9x~*Qp{&=+9*R#ffU#Rxn z<27&P$!IG$vNMmjyRiai0{QfXka&aI1sZF`G@&;)`10%uBW4IUVG;*(h^Cn=1UM9z zS7BLnelSKv7;A_%-fJ>;DqX6}1sd4A6wln*gFQ!#u@FKA{k~y?&xiUL?R2-#eqT$p zz*|F3$|gT##j{vdx6Gc^kl-*Lanf<^ z4W$PN^J{Xdk*QF)=SjP-i`BkRGDX{o!uz02B-krg<)-9!Gr)P!V_4VkS)V-KwGoQF&UduA-%xv5&z@E^fpiG!v8pLz zQLTH_I`&B5nU84Jvt*#u2PzD-P1xNS$#^5Zz2#ZHN9`wwCK|fM*>YOjK%t6uh+Qva ze(uB6PsM|_%R3{!ijSd?=X61Rz3RO}Pjr{}pK7W{;!pl_dTK;z$+5uv( zo?A=3&W)(~GT|iL_5HuqBenL zwExfVk&UlvFDrSY<y#vUsujU>A6jDj-zf_V&l>=eF|xhxR+izHi(dWvE;uD}WInxA#jdb)&k$ z_c04Wfg~rg8o|VTI%xHJuyXW~u+M$G^Mo})3sfW8UwLn#ETE-Pkz;~)_nESvof&}u;nFz$) z5r+xu?sfvsa1<$+&ey`cfppkJ*GF(+M5qkl4jW7X8O(>=7lY!uw`wIG6kz?}Q!g+G zoE0>P2kC}*zob(k45u5>0C|^z+`(DlgVPZ3i!%(xEJh3sm=*Zc9;^!&Muq+W^bqcN z!-S225-=i@Qwi`n&W;qUT^EQ9Z+{L=0pu5h*n76N;V)jC0ThiGqmAJ00H_Xnelw`L zd#e$?OFi-v_FmzzeCa2oqbAlZQSo=HRU6?m2 z-4VWYAb1rr*aqPcgI$=M8i6tJcl=@P#=y|9t7mkS_C**wL=HBG)i#3G`nH7NK>CsQ99LPOKJ>FSn4d8a zFYF3|P87dS5*!dV7za^f7*PRTm4fKd&bSl<*rEsFw}?<kU`7hQN0$4D zW@Z3(QM84BQ`Qxv!vv4uCP&IC0No%KX6i4@vTA%x>coI&kXbw^0@$9t!U%T28ciNH ziwYG7A26_>LSKU=!?sQ9szFgzGVWIgz!9vzJ=6^>GpsG z41tAklHkD_5Fx;hhE4`8Us2Zp?AieGd^rbHj3wx!0z1SEy1*HT=DZY@aik$Nbf$Hx zz$AED*x(?%})`J8LfC`XCOuA-*K2ESh#Gn9N zm#yM6EQ3Cp0G<{%cnGOg*A+5xl>r~HRJ@@37*_kSCW=FkD*7FSpmz%qd_Y&BuE>Tj z{iS9I^cf2BB$}gAOh%`ss{kl!1M*p*|6n7%h%F% zQLK6?onDj1@mU`z2c`vmmIfZe^*;_0f)8F-Xe&0MQPWn?&@DmY3FjzaifH+7b!`+q zU*v1(X2J~VqdnmIaf6s}U3QikV>=bFJr3c1bz?J#7l8hIeo+VL``^|W=!^DuUr-h3 zi~hLP1>U@P+-d@E9?Jy{fj9q^s{?QTE7u32{#ULIM13qryc3btE$JlOJ?e%_+%<{? zV&neJf_&{;QllEkIy}%R{x`wPxR+M`Y$WW6U}-mB!&DphO0DB z17Z18nEpim-ue7*c(k9MZGJphh<9J!{p};~?h!d$`mRwt@CcuGzZ&z}H>E}`&|zY& z4H9#07ka-+Z9ij7dVXO9&c9#G>AXNA{XLIz_r>_ze-!D7Qa;g}Pfs-BiN2wFqH0ex z?uq&vK2f|Un*EO^KGEWT^j}uJC;IU6zoy+}JXQMfRH@_DQ+%nXO6>pQ>pjJ1eu{5Q z@I=#|==?wW`iUw%QKx^@;E4)7(Y1dx>xl-U|JQZ@e_cm?swDca{qawg;-2CM{Oh{L zQ~d0w_;>%hPV_`O|Iwr;TK$jy>$<@cUHeCko|=aJL<9d(=o8I;qWAx@>O9fTfArlG zrF^0f|LEgkKBR^WhW$Ovl&p$ue+T477i{}jDUPVXjHVG-kFsU}$ezg?mt z*2i5%FyJwd6?%QdV<-sADO@dN*P%;293`tRgmC$waLtd;_(Z+@&c3|Wx*+nzs3 za16lT@$Art#Xdf52O)ku#{OSG?;dMsfo}dQm4n?qw$JIMW#Hq}%>cKc$J$E}0oBJK znQ$_i$DEE}EW$@!4T^a27}OZ{_Hjf+8Aia5Ev6*gaem}+0JpG5-VY&utbSJjl6lM$ zpbyJ`%p%G>Qu*JOeq{2I8RP5#9~nEETg4;O3H#jmxSbCZP=3r#3MXTK%+3l{#(4}E z3!?uooC*x`$k&K=XdXEwz^(3)#X$t59$7IwgXxjEftB$dSs|$S@yxo{hjBe-4`d!m zedL`)J1md9hA;hbxJh}4QPn^^3-zV1CASKy6B#$&-N*s%o98NqnH>;qnwQ9E!=R`)H zauYz8DJ!RD-nSdlmj0PP{4swrA?-S9;PkpMe!osu&ATDIesY0|=Qj^}`Tmf?K9O`X z95azs7pF2-n^5Lwu?wMk?>>|5zFqmgj&ylBKPg3Nsh%2cWhEPPRa|nCH1kj9a@*XI zjb5$U#>tms%d!ss-rVX)qh--^L^?_HT4K-;Z+nkf&M_Z+DJF&Fq@)?PEqiOVh9WwB zqt2YFx|XJjvbqiib@ihQY^(fM3L_jw=D6gp1?Cj#a)py{0a86pZ9OeDLdI(LazheE zcIHxJveMYDO6hXD{qiz}yx9!Q!Nk(&WNF*soY7Q?3}u0l`1Y*|#VN8{vmX(M`Wl9(oINp(3(`Md6g zL^i3YyvF$J1ZxXSvdV~GsrsEcfGU7hMO-4g5pdo9RCETGTp1j}Pr6hnQ5Z<1%QkHa zj72Lmk<(LhDQKnnq5Dost%2l7P@h7}VM(4K9IDx+HJrmm#V_@Dthwa(Q=~uImFJvE zJATGrRrYolurg~hED{8)>}4}&7*~~9)AI+pIg5LQ(LJ*|(~Peh+OTb%d~j^P<<;6C z7;>qUv<|_m)k`mP>5$3w{cg$mPD@)a#DS!2XhzbmP3YjlUFjX}vH@#s)V`jF9l=Kz zkV~NpuP#AVWvu3$$!6^+t(HfPy#Q$#H9=`boMv+JW-DtsOC@uJRE(RQxr;!B0s~29 zFkTAy{WNXO4{(6S-D>Z)7LS^>0na(^P?tNEvz+!kTLn{P9#)i?LP{vfjJbh&NO^u< z1!stY%O}IhI`0xgex2{03hRL2WwQ)|0hecT<-MhPT6zZBdNOaRP;rM?8G0HKra@N3 z?=^7PGIcBklTWY--x5iRFYViz&FMpSruEK3uE0mi-&<>TgXBP4SRI)shtxKozj2?*#N_X?X*vW_QA0zu@u0~4 zGUi;p36inv8-0V1wz^0gx_bI;I7u|VIc2RC_~E2s7}uRxR&H|7Qv_yMdtIPsofS>d zmY`J&IX$UFeatjt6s2-jBVAGd9(S1D3VCU6Bx1tKsQ4H_jqH1o_}2$0N_Qi;W;kkp z>qB>Cl8%)8ag}t+3@aNubF2vxl@w2}1rHA{*%&8DRvy7n9Y$nwVqSMiMfB7Vq%^Jx zF`ON6MvnurgMTSireK&?a`AqL8BKjIahG=;#SqQUtwj-{M^tHK2)V%2DUBQ`icLlh zHhztXP^RJD9a6W!iH{QaIySMlYiGcBF#Wvj@2bxhCcrcF5<75pSGzbGTlt4XxM0Yj zMms1(1GjQ4$J%0Wql~j%@Q;3h`l=udB-~UG>#kO%XJ1U#u>B3$gWshM8XCedQ}t1{ zkZi$&(VgoDss{UJSg6q_k>t!5Z!H>G^^|0YH>s>A@)%fF)CDPBQVCe*HDlUyku7F< z8p~AdTE{l73HX=qEQpPnYNJm@w-EHXR_4eSM|pm_c(XCcRGZ26MSS|BQrXB^8jo}u zYiWgM<*)EjfwQCi?t#76661l$IPmojz*?Cu5STsfnJq zz$#dd*a*w913>5<7G}#_V^f0<7PzvE!5BZk?zQ+mTt@woNQ3AC>V_HKK0_(*d?waG z!+u05j0~*ANM)ZdnzD&dWc4g?dJvyYjTmw5+=m15hT|Lw~Y1KNCnY8)oW0d!3p1r?HB2GySE3 zhL%nYT|o}bYE~3qpWud)^Z0D019{}!<&>o0-Og%ZN6YPy_gPZHGrVwAR#~@NTE02)(oiNAggTaUB2cxzMK!upQ zjh@!Km{vq3qHVBLdASSL#c%&(s?zr+wL@E51Nk3`;6SZhRE3M8Sc@>4{?G`XZAxR+ zCNdIwOv_c`>l<25tWODDC#gvCdj1QlZrm4~sRoj$!TX^uY~?u?nV+9Imelo&A338) zGMDem6Aigkgd2s4puh9aF=kep?G84FuC%P+scyHiRdFm$aC%2wb;63Iw^@ec55)AzOP3SVFd*Va6PZ& zRlL2@F{M)@uOYiL)=O_G?xRgQ`4UZQlF&toODi?gbL75&Pz;PjqON$X-1=%w63 ztJ{u4_A%q#`Efg^-aKNHPR)7#{%r&1AI$PJ?iI4rV%$cNhlx4{<>z(#HLBhIVQrt< z1jnM~TUS&)=YNvg!9M6E++KkM@@c0;IMkcvdyV+N<17DHu|9HB}n>$&tP`t*B zH%MY_^0uz(M^w`I^6TPwqFrtE;Q06#wv~UUIJfQODe}Z`p?EUOxX%LAX%=r??`KSe zh{W;=$|O9b#yoi0IasQ{?v%G1-=9PmL@x+SY(?OF%oC`}P{S`pz*$IhTqQ2N+8H^; zQ(grx4|mJaV2leT=Cg0j=D5vb@`0)omc^OGZP3Dh%XcYhIAD3m?5rtd zX^n|CU|1q^zg@LdrO+?J_tqmoGkGJ$(NgzvfL$6>98bi$p7SI4g6$%^0HsBZt%}w7 z>6fHJWY;67{mZEsHNQq8)N9rb3z_jAEM+qRvU>rZM0 zYKv`Gq}XEQW^gX$hv(ZRM!`xk1FYT!WM6t;o}!r`Wy-|F3#kD%%T^E;605c|Hkf>X zAtGBB7An?`1bzJeN~2qvI3xuuKLIa96`x(i$Lw7q`woeexSsfSxt}%)!sM&~7iXbM z9elaTmMS*WTBTi_0ESDwwbx~pWeEsDeo-4j41jm?jG|=Ai>HFFb~5gj4SJDs>E3SM zxDlfTPUcOJRMzn20_IJC2ZBi<89k=$uf_6&~$ZVHvIi3ET&4+%-D7a_)>^w~1O8qwAB;a#a@WVNNmBA-c z09p2CyA>}B|5;t|Z|l<2>xk_NoG2>yNH5F;6qmCWre8op9Ua!##GxTti`mHyw%~4+atjQ|`5?mDpX*zz&Z5DnO`eGQx zsXC4lV|<_u3a*Pi1Hn9*JR^to{>~B~G&a0%>GIBDHUv2p*v9@Mw4TZyoi zj?2mu6J(OL=fB#b8AKq(>VC;V z#d_+fT+Pqfp&Am`CM|HS1p)!u{#mVSuqFXuqy^uiCCX&WE-&8J5CK{zb!W9I&?mxW zbU6b+39gS^I6W1Rupuw&h0A(KY0-)ZjJ-h*`8AsS$G19)ci_GuEra#hbQHxmwo>VA z{9jVNgeG}&NBE3YOicMo9!-dsiVAIQy{hkM8Cge8Dhvop%Ac=!r1~X3n_d{-5e_HT z*4gXN$ieu7FLIH4_Fev{{Q1kWnF+j$MS_oesSa3}h`Ks*jIF~N#W$gD-lDKAQ5N7Q zU(k{G{ddFo(KitZmAfgvs#OX$oX*IsVV3L6bUCCSX;;cI3i1<8o$;@B-|2+n!tH}Q zJZ8^j3whP0h)E}sR)TXSz>L$3qE*dZXwn_bnn6q?9xWWU4&7gBAbhuC44Cohu>RbU zPL`OBokiP?qTq?#Y0{Ok0w_;cxA}(W`KN7?^KdKvorZ|p(eFJHK}bld!NqW_menXP z%bVt~vt4OY6d*cfuY zLuTdK{YCD#fM00e2}k^O%O;z(siCKq`Dn9`ZS68%$qUNS!N zV&?>Rh3@|W1fOistfNavwC3T~>>@_`wnO^R3XG~GHmjq6m zoKTnUjLmr&$aqzk-h@Fj$@e5RgqIWTV`vxQLPtCf*~iPrM$;Dy1Wx(FIf2E2*n*@A zg{GuEHr7@x9O2{O9?TPGHztaoABy4Ryv*9Ea~`690F`KY!wiI` z$xpLP$=8#;FkAl;~f9zrZ+?)?`uUH!!#2+;r7d}!pURN?lhD3TUe2zcw` zs78iTL)%_fUpd)1Zw}~7xfWUa_$@=ZeN<~u)9WqFhbHIYe!N(hAarjz?8^+y-hfDj zr~gdl1U1W4{Lh~y_|iCbbs;BaWRtla)f^(vX1O*k2_8RrUn4>Id@MT#UypxfFH~`* z7>B8}{w~rgeQn!bx-Y39o zWQ%wd;cb5uSF5J|*%5JDZDoBSZ8Xp+{Jxtl>+Kgypsq)2*2C3YiWfYQ$%K^!Ri?drI6Is8kC^{rgC)-fxA1q-(9v+51ZWb4Ln69Db7p; z-&32^QJ0QUREO8o7=$Iwe>E24zwV5vr&r9q{5pS?GDZw6wctnR8;Hl)@_bq13k=i9 zsHcsUT!6=Ok_L*4jX~=}M$}T{f9Mv4I7wJp2Y-W1C(vG{3*F4G@|c{{ zGAHV&uoeY)6^JSG)Fi#4yNi#MzGl#?NHTk6w@!`-=oM=%X@TtyY;lF6T{_JHqvblW-h}$fxaxCnZn&j zhm@AAZnvCU2yds3eK^16G`fo)n6~)wug*O`d$pXP*aV$0S4L=J&+v8OVfksmJ0zjx zyg8xg%2Tv%Tl@EV@BlNdzQLvvnlnv~G>Oi6S&Vy1s z@danW&}K|R2DDXgmd1DzgpEXbIATob1&K18R_sf-X=cY)`r1*(zn?TW#fDC|)Dt8N zuonH%tb0B8$vRhW|Ayj~TV^RQP$>|r&-HG=bDJL6b7EeshuV5wq8dzGxkM;kNJL{6Y$XdxhL9eP=2X zDq!i>SCGXPF^T?~zm?EcX)iWkk8u7BMOe8A3E!m0i0eDA^rZT@PYHqDK(5N=m%(-q(kVOd!+ZoNe#>z3s2}^m3CroF0If%MQu^+9#{Ok z&j-f7iq;1ye1bSYGoNda&J)PWkcq4l)&MrG%ldLNCm6jo?1U+Z8AjF3(4)x}MSv}h zQ2ouCKE%G~rww3?ZckOKi49wormqE=@(NHw5M9Czo67SDKKVGV%%84B{yjRf^hp-o z{>jam#k*zSX;}E%6~tkUSA}#x3P}yUIe+miaBLn_0R=E`K-xlOt_hSOD&5Rr;fE<#FCWOF_3-y-VHhu^Dsy3uL9tRt?c zFo1jv?&EbUM=&#Rt=^dQspXrqi-fu0g}`{Ug-`yA1Gp~cElniP8Xry zJ0(=%Pw~{zavm?wNr#h{#_(qZPUDsVqWTxMzbFi8m9FO-}j=um3nQ}z&RrIU&@0+7LEX?(TvnSK+ zqe7#<+wDvdhjD!P6d>l7{!(BGOF$EtBpa?npQaOmB#lc*hD-_o3gXxw_$()?7MNUf z-9*e6n;src_#))P6j>IT8ClhFUY-;QxPDB;>Tz`#^OzzL()ecK`lhE{gNx*ooO-_ zbKeTw!xKWmDhZDaCe|2~*mlDzbtFF$A|2YpS9btw;nrk2tdH8@$stKn`@2FeBwuS) zyTx{oCW}oiFU9b~oq<=1e?ApVyKzR5fCxABng{Lcz=_*`FxrOWcm`I0Rg0G>%bYzS z$p}|LY9D9GOIB0SR=)p6k|uY6^9qTTvHTEl=s@p|jO{703Nf2T_eW(mVWD+{1!Ap1 z5|qy96^aBg4>+UBEk2eJe>Mz{D`@_d%EH}AIt4<_4J}w;91)_lc?XEL3xUfpGlbRa z_3V7&f>M7PI%PseiSwiF-Rf%VN$y|jsdV|4$m`)C>fKX%*(zCw$HI}QP>$6deyI4% zz!DW#r7)os?kqI-6?r;@t~j@z_!l86nTq^f3;N+Oo&(4_k}kSAcL_n+G4HM1ZI!M` zo#3-yb=(s_p{0!`bxUw5_Z%;tk%oe0zE5jS>1m(#8(!_&ZE_1Z!y7hYNi6j{YQJ&} zFHYIKQ=(TM@JZwUE~c2UbaPM?DyX|UbN#&Kw)`dOh7vUKVGZ_K2$s|aHNP=ScF8i^ zlBXZIk)}sop|TBRsiy6qvZ&}-WOrI+S;!e(qBfWcvda7>A!iefuFu7!6A-0ej;k|`Z#adwW-u5~-i%|X z4Y+M<=1w5&t<-4q!I%mx zvvs&SM}6V^R~}no@z&Fuy=it@X9I z*#{Q>+fC+61ta98%8PN)0q+|%gYRsTEzrBBzJ3~5%RGCwX!ApHpxs$vEQ@@ILN?&W zvRFq3n~HqsE0bmp5+%b#&ud@{=KAcVBzj_dix)A_Z|We(1?2s$oDVMH`ZZ?2{BL{^Rv|w<>$&p|W38YkkYedKCH(h_uogM0(!dY_ zrpr$2rd!Vm|6Bz09K1$veY%k{Ttl8y}{_7FvdR)O?%8Kz@l~Dg!CvAsVK~T0Wxs*<9u0opL z_LYIq6^qKMfxZ!*?S`AKF5(QajMZ5DB;?_mtpB^f&Ub;iewW$zD<=16#IZ@}6exn2 zo^-TCJt+F)r(pFi{@4mnTCA8fmj3Aq=3m$5IFzIf4o&^S!68j61axXbxY$lVBQoTe zED8i}`a&pUBY8@5kQ|n*|2&U|T343Nrjinz+wt_0<`NB1OBd4%V`oxWe;xEDurjY& z@$a?KjMonYXtQ*`JZUnwIa(ah=<=Q=ABCifLK1kvGBNU{!&R_Iy?@#I$YA zq|gjPUwuvbZPb^b!9$(2Wh8m8A<$M>WMb6j_D|VK@q@aANff%+hE+^{C>0c}?8W-;^OqA$MPrI$gLQUIOB-UPS_d3-2+oEK%dO+R3 z{2X*)F@42wI2DWu{4oK=)u%p5)`FTU*$p5pRV;s=3UY5w=4JM!Sa2<6w85{|`eZF{ znf&d_9IaJgRSR|tAevC}Y-|+xQhaa-!T<$rT2dgOM$0fdu7qQY&!PbPd)Ks7*>Bk6x7u@XK@>ecycx>j z6O{Cw*!3$*Vw!OGVn0$=C83cF9NOqXysZxt>CE2j&&{c9ru>K6ePI3tJDndPG2ZIG z-Mt8~gdJt329uSq7%mxYo+p?z3Ngs0dXpw)A-{=EI+<|i56f>-6Pd|nOm3TX?72X7`|)ZdI#BKVvrU8! zoB?`$giQf&fkhWjfpg)?e%&2p1)pY>R0HCi5$1bD5nLNZb=j9cV1Xw@a!I-M(91mH z&;0C@cU!9atbIWzoD{hCgj^==RA;tfh<)WSY)fORxwbt=$tm{w;3zq! z;2x^^{OyDTm|uuH^<#!l~rC1AdHv4>-=7z`;6+(U;nVm+rmCt<&>wSxk z7SmwZueps^G1Y;bB(3j5#xVL>ZAY>5hjPvD95nFNgyEaMJy|dZF)*ZvhgOj5e!tjj zWno{S+2d)wJZr+Dl{9x)hxi zC-vAy3}E)A4b@e#9DUl-%W{*5%e9PM^u2ZmBdx|i3c?+1eBnPk!(lEwoZ)r$%Yr@r~JrBuh-hF;%|)NVQ< z#Vd)2$rjScJ&M6=ZJkOu7{ULlVVWL6X}*!{MOiq4FPGJb@lU@p%2SU0sOMR zbm)c-S^cv(nVNNDW#|-?6KMBt5;;E8o*@y|9Y5EDb?7fBuc$|xbFgIMyYA+2vMl$t z7^)Ftzb$*68PuVddd~-Or9@<6h4SoaBrU8szPhubvALqMRum9BZ%jxqzUD4`b#eFl zdaQs~hnlN)T=A;R=jRC z*XG%ksq;|tGn1O9p>tFHHNcj{t(An+eIo270OXjD%uK1I;E#YIi0oM@_J6^uk&)H zeeq$#2zI_bICuXu+uKR(hrrq?Zj~Hm>MnQP`JSvSrV7=KsdZOD+}rEx+SXgMbAkcT z1ip>hhIMbjO~PwLI)60I{Mvfz&$e1cRcTX^4L(kcc%q><_DW^VzKYj$1truAscNj`*ZZ$_QQX{ggY;@ge(!^hGN?i;R|#kyG_zjLli5$HU!DrhbY1ZIt&wHd zhNMJIy>-#@`H7Sm#%qrN?GRxc$zr?s?DQvQW0^?gZ+kP!M6O!&Y?7;6-!7Cs%uH6lS&MuaxJ-zOX*U(Z+=X5q+z-K%*W*h3LvYetPTG~$5nM&}+MRQE* zC{z8hpeu`xU9Cc&!_L*`VYzyzRjp~^Ie+;I_uU6~;be)0qH4|}_nmfTmQM5$$2a1! zoFCCe>4OBwKoK6LbjF7czY_C8E}*tbO|&FutFhRybDO>y`^JpY+TzY(Eho+G4ygT< z46)RL&nuF19Jj%({i^KErmHcU1?0d!^XO;(nH-$HbU@2!8K+f=YgOu*1?djLFBc_L zgmnICxJUK|OUZ`po4D$Bbyp8phm-_f!|l)TL3`zK0r$O}ct%*f{ui}M32(Ai4@T)u zRgQrH+bPGLZTlaF=W=k#sg=TRb4>6vT<~>`TAq(!9%Q-{7^Y?=ov`?DY5S8z2A9Sh zx-7E8&h=#11OI*rU2ZK5W0W=d3d22CSf-1t7=^`v?xAg5QT%$s%*(Mm16zcvaMvwP z>hn>nWv9ddmc<_iO!`AUE@~#!LCTpR0X0murUY(VZoOTFPaW1q+C5#}Ap_4P{~qGo zNoItdwp61QaqQ&+ClOaTT@7hJbTDZRZOOzs5HB(RNEl^KE2TW;e73wKU~9bKNT8|5 zOkR8d_q7hd@S1<|t5ykn>b&(VAMZI>hHQk{f0jebGrRg{M;jmg*}c;Jyn?mCo?RSA z*(%|icRJx9lc|VT^~be7bT6AMju4G)axgpnb{wXxUUSVCCxA9*WNuEqrQRykxj1C8 zGL5v!0UPvE`Qu&ZUDqa(LJrcGgXE0;&evGJ=lY3XFPpkMJ|DZNt#hOty)Q+8zNrHK zy^~%!F*?U$GWDK-%Xz^vHrQl6MGK@vswu;$f;`SoZ;;f{yc>TN!f!G~Pw=)b8{cez zX7g1)FO8Vl-f(2C0Rt7~(uTs)sew7PBWJf*-bx|`yj+Q@c&;FQM>kg8RH<9Y`nR?YnhKz=P&x zisUWv3yCUKjS^;V{4@Y7q)8&TCIXHK5g|aq|D*oR089xHhs44^N$7x$A$RzHboj;A z#UP>hSlaxO>#C3*d@LP)39#S_vCz2z&H?CWTGn6ZhinoktMaRXbK!CTdghEg z=Q6krpqM!$*SQF;2e4vZmR@fHG;8q7tQ$hk@W*sozQD=xf0cmpYGlE+@RtxZ2s(Z; zlVM4X;<_?`h>=A{H@8L|oCNO;N~;a)4wUA(tp)Pg?#fm&sTDhy!Yu$P%!awnh44&* zUwO_tkT%8&ot8E@42}Yc0i@&i5mc#vt8i|FhrxLO^GxsJ7F zRj*w5M|`7-CAK1TxRmuDt#m;H0|C*siv&1aQ)Bky~d4 zIB9vM!!g4+&C6tXGeJlG@jJ*7<83qi zf*>I0_$`Ez@m6=89w4f9nF=2#2*^EFfEY90>aX(wI<-nz-n`Lzt(m;0`hR@Wp zgJyVK;?mbA8X0wy{dfGALoi`FZFIWYK#VCFD+lv2aP4b@Z)$+ZR?BBGealNB!l9Hj zbge5rMe3&F;b^pG&NCxR6J*xr5IvMYq&nDVJR`DLcFy5-_AJxa)2YF)?6DtUO<}hjBhesiO()Ki3Fp|q<+jW>JC1{>91dX!% zbcY<37F?*fv+D2|ggC4r07lWsQ)sBCHDJ3~JwRVItVkmOW!nnHH_TEkfOoqYjWDdK z@YXXi8}EQPP2tKrF`E)2tf}}GD{+nE8#8{cAMWL??jR`Tr zJ@am`How4;dA*k!UP+we$V^gzXSLLnj?SO+)f2YoZe- z7G|T`8@a1L-)koR7jJJF7T1?|iDE$uhv4pRArPoSf_rcX5InfM6C4sCxI=IV?(P=c zN#P!#sKQ-`e|O)Wo_=Qfx$k}Fx%FwEZ*|uB`QCdi%0v}a5ejlj$PZtp-QTZdLKf8h z5qAZU`*J}nT|~RrSTO*Y#H}Aom!YGEWxxoP*eznPUMN=HLrfX8Q=(}0857b_sB*!BT%zbZK@nHHMb!*t!Z?&h^jf<(v#I7%ApB$z4rAO8!Z!?1VBr=!-Fm@dO+KuWh3%+I!t{`-cB0WoKjC{5TMVz)#r&uWh0Q=^Fip=VXd9)J$%+utnD z(%g9731<$fPcS3ZeTtDTh1=_(f!qM~C%=&Z9CkE6+1ps=XD4pbyO6USwWqp`psBsY z=b$q~WCaOB)hC;g0DOJoyX3QV)u($S-F=jiXW84FAmLE|q6e_@rVF79LJ*X54yWWsFXr-PF?1tNGDOkb7h+vC&G&(bx6cVG2iBq~xj_wRN@9B`zG z^jN2$L^{#qqc1eCFcejp-Mz9gSj$O;k0&86cX=1dM#Y{+(^JSvB|pYJ48Z1exkWYU zjVB?|KRQ$Gw`EA17Qf*OORb4t6l$K?-HssPN<-_(G7yPNeLt*-ezbKq+^-lnHn&m9 znIk>sIy{DY^ye(Ce=L3sYSb~>MDtm1*p_Hzb=M^#jV;ZqCv|iWzplf~9rbOquZ#(8 zJPZ2U*7np?ykW^;B~C*z#Zt4^$lIJ;bf1}q+0iSVz25N<#+L%#wzWs44#ex?>BG*f zO|0qF$rPL0V^Ry_bzkdmpY8USe;*s!_?U96IK~;j$PeB+Ta74989VCHN*Ri<`mShN zJ-(~d-_KCTn(FGs$5Y0TfZEvRi^*fdFpIa+w_DL)FULrt*wUVr3ZhRyFEYqxERx{O z>cL8>qWj!o_7+LlpffHN#89X0m^FIM_?c=LN~V8&_875f$cus`(EK1~f)zj3(-X}p z8j>o(;G*NGl0v0Ch8zEmw>f1rmiCY3FggCp^6n6xOQu;2_R;nke#ARfUZz*qZnwkz znY3x@!S^i>Z%mX^#z?T1*LN-O+>#3>+`;giqTwYj3~t$dSgyCXk_ObJ7!>Z`N4aPr zCUOQ_)xie-EUGDT5a)1;tuwZWRy8&4chCU@2F6jcv-2xmA2?5r)aRYvVv2uhr?E;IKS z@7--Y)cPQvM;SlYhb26*8;f&UQb6efKIII^EMcO*Ea+2qyj7P3agk0soaY4rOe5bD530W!jMI)JCpv-|Di?xF5acdh!G)Etseh&vcnd>$ zwGSmUKB&d?ae6f1s8$x-2|>}d4`nn0+&jvYsIBt~&?(%5%amxX zYYU15$6OjpC6yB9T*FuQt@$F-SxR-W+J@&p<2OVXG`fMuD;p_PUFi9L8)xX-QL3IZ zG<5XYJ2g;5EUBvDhOa`br6dUze)bzTwR}u0c@@v<28LBOelOvbgY8rc>)YX~?#BOg z1ZP!h$!R1NycULXYU{n%Xeh8IcW)}2$J1mgEyQXYnoq`U&{tz4cdsg|ptrV=gKbsc z>)UDPxhH6J^c{ILtVTx3{p>NuZvIH8suUk33>DYblhUXw&=Q8yXe;0}NUPaUTveAf z;LNj@z6}R$SrRwBYL1kI;b5`*}tHxZdOC*w6 zETwhiSMg<8N^|exg?<}zwJmu`W^t8bkY7cW8OY8_#kYcut6G;BBn?m9Tu4=j~}A zT5_v@sy*~!?s-Sw=d!STe$OA#LhR*Mx2v!9VW0Aj66PMU?wiU$VspXq-oK2G+m`wy zLA0eZ6jxu$K+<#D@!q}0RIN)1k|2iCVv4J{GLXbvUHn~2pNM^8{%I^7j(LTJu0s# zRM!2(4Am}qh(P$`zI7M=Wq84pD_EuSibzd}PJR#TesP{Z z&sB~D>waKfDUV%l5$k?_{*@|-UUQ>*UB81#6<+Sr8GKy1mQf-Sk1hno*7k@%mm6^d z=Txqxl=#O(j;p)${oqs)8Tfx~j?JUs^Gm8pP)rzPZ2|8b<)R&%|3C;1r)A`=6Z_n> zi#=mSKB}3L+cygh_+C^n@K0EK@MecW*8BI~8fqBiYeVxatOZ<&8fksOmC9de{Nf5mD2`tKNZ5tEoaQ^= z4upVmCPnt=(q?6udWdXQl15hFeXG!`$P4rMk4Go|mC8=EeuV|@?w$eK#UJ82%L?3G zZs4?wE#o@d3QVx5_8|n^Gh__&J163m$~<&_Nd+%le&Bf)+X5!~hQUn<{VZA;@2>?P zDMaSxSv(7v80L>oj4PE->0T_SzAwB@DD?Y6?&3Z zsVvU?_*!lia-#bJE%T$h-0J4ZVx@8}^CPF+D(u8gKPyl5t|Pv6a&!6RGZb8)&|m)O zYjSamk~_dwfZ&EtI=P`M9K^~&oWdvF+@cf@ROBHn;gc?I=*kC^vJl26gW}ZQqYaQGZB)3(P==+W`bp zQf6R&*rLENh3E%<(_nfI*pfRNaJm6Y~sT(!c4i44F zmMbuha+$~|aR>_zJYtH1`0Wa83}*^-r|;H@r9iB17>Yq5-m6J~8}xx{1fo$2BO2um zO&~L0fW6=nfbKNiX0Zkc+yka5h>DkBO}JU0J4d%`>?$00pQ!-+*aesat`6uf+-)1X z`l>p5=;#%A!4wuWYxMmNo@f!RUPS_Jl7)SxS5)$h- zb$}=Ef*J&x#CBkR*s6(z%cHy}F#0mo3CDa1{tbr#x}p$E8}dg251V$uv7dpD;dUwS zF@E%JlZq7%DFw2|VgwFQ9-~$FZ+F1|1RcT6dA4(jRScoP&3XB9cdNx>BkKG)Z7(B0k4{_Qcw!x}r#4Pe#qx&~ z;L?Gg&~dJBl;O&NpWvsUrvq?hpihY3Pj1u#`6&(Is~5K0;OafwDSymwW5U@{#v;;# zI!S-5Zri|Lop_RojcohC6@b>@r#4S7;j$>#@r|;EuHki#PaommdOlDGMpKFs7^%ck z!B?jY#Ug{3w};@N+o$;OSC=;|aQ9vh7o^}g*zsu{4))1SO9YDd144f=(4S|khq4Rs zA{=BG=~*&VB@P_h{!K@DbV`Q%!fVdhPY3cR+ft?M!auc)T@UvBHgqflT-e5@q1-!_ z!HvDX!H;0_e6Z@r2R(81Cjg%iwuUJKNKOf2yTUww4y{W9$G4BEvyV;#=(0CYv2iCa zZkQr0ydGTo>p)M0Tkj~JU!Us7J_mYc4+TgA*SEW9K5d+e;&NTQiSdjpCW#>ONsso7 zEGDG>1hMMC;X1FU-rCLnL;Gpd>Jhi%OuYXZ1jFse z2Ev^Bu|Y7F{#YPPw?7sH^XgXt!WjBhKrqezNgxdKg*6#w*Utrnf%>^XFvR{UAk4JC z3IyZpcL2f^`W-+pvi@Tr%%}et1Y_!_0>ZTWsX#F7{v2Qy%@g!MXp1Y`p5_U10Ky44 zzku61&R#<~#a6+lc{(_F#CcKs`x2Pxb%!H)bkK*(uR;}B;&W#y**DuH{RZTRkhgn~ zfMchU6U7YlLpH%y$%)q4I9R5+y14L)fLB?EuSqE;qPe=dU^byrF^nL-xR8p7Db}V9 z1Nx!m9Ue49_<{ULOhi=-Bf;yl9#Z5R2W@m%7Z=j~;@O?(FI3%3IN_e&7+W7yRA{lz zF9^0ARgNXeHxI~g`m#HTwq#Y-iC&J-Qw26B6;pi^T$;s}Am2Wap^dq`FvV%Qy4c1Y z^173Y*akgn^rL0_BX3Enh?3Pz%}z>W?i>)&DqmeF;1qk_?MA4B9$EXXvi&)>TvfW@ zox+OOLj-4M9mF$t51QyEt}fbenoci#aGNeKP;i>gFT!#6Jnu{+TtJU<{a)EmfGuB@ z04ygTl>l5P6qSHiPBJP16g*o84m7X5?%E;-vY$juB8vk;h%YZxaEUzch$0HJpWMcy zzpZa{b(+NN-f#{`E`$@-Zrb8Kh^CF3s)K3YCRLctf=S{{%_;=VRVNgt{U9>ZAd`J)8IIX8AMxkVQqdq|`(ewv7>_pZw?=N4W{pNOfE z2iGj9xo0+{Q#inem8)YuGkx5vO(;KH9A0>Y5*)sA|9MFxJbss!WlvPi2hD{l`tS;m zuEk~9Y1g?x8Qm*8VzMl#CMKFD&4|F-br`U=7o~$bsL4IZJ@OIMrlAAn<@s*F$ym+S z4|FdqG1HD*U7V*Kufz?nwHY9R3OVt&eOl?W$C>0&@$I%J5UtDbzAzKGCZ2eEnL22H zpxSE>tNFINV2at+F(d+wp&Y6c_R;S@g49H=u5R3_y8`_ZVQ2X1*e|!yfA381; zaHVAg^bzKc?Z7WFIYuT0`+QNpI_}Pp}Pt?`>6wL z(a{S%|HKC->Udqvphy4Lw2qknYQ_7c(zAW6syET`I1>>K{My2zWma zj*E1(%v;bm-H+|$sjwVRTQG3#&yM(9E#{!yW%m1Awj^F3xsV;t?#WR?&)<67`Ho76 zC$#l^X?Jj>JtkVozQ*RBsam?Pr&+_ohJ*UVasJ+>l zq84G$_*ER{zA^iL-q)LX!Xo7DNm_3HP5D%dulqi7r_#Q7r`^7Jr@_9u2-5|Mt$%R! z@+x{`Q=PG>9x@r&z-TBvgah)WnhEskZEi|mh=(!VEyxi3`;WOF%6ZnE z^48b8qhF)<3nx*XWuE5i(d|Evr+uB)&u`*8DXWg|ajFjP(W_whBvps^OomI7o1=Hp ze@5@^`m`^WBdefIZ0jwC!s~_W;=aHAi_cc?40;alSBE{0uK}@_KCuE9_g@6Ah}uh^ zaVU>P)2bj;o8yl*w~(iC;B%^D*u%h^53~K|6i&r{fqeN|3Nsn zP+jjY{nMu+j#V|Hf!Bm53tJTetwB6^3Ln(?#lNNp@(>xYruguG+a5%le)_-~5O) zp^f~zyj~*_D!jxtpctehX0BqzPiaA6 zd13KkUSY#xFX~>9UToV*zq+fCFCdH55^sCz7PiBcgQ%LxKfz4_SFE_m;}`lY?(}_q z>3e#}$BuOjfLWU+G~@af+f}~)7#5-Un{So%6x#>XK`gHh z|0V34w~ou^D^aeqGywjM6Y#}0%K8iKBA(N@DYChKfnw26ph7D0dxtQQ*WM{kp;G{D zr;30)@vD*gUAPqgdQkuS!+SR?+kaBL&TFr_EKB07f87?; z(%eHNMR=8-oG7GR!m=q$^Ig#CaI2mMO)lfaO{=m|P1o7%ozmS10LU{d(#Ka-&-Z40 zisZ9rpz$4Q0Neuupe>%Z?a7+LCTw%_O1XG>{mK2@Sq$ZxWtUg1Hv`JP!6P_=6PTY-t?+}+|zf~gI7g}*H+o@n`Ck~`VoE>7xGhYk) z3>yaf(y&iv-D-fCEwd54KRx=g!)Uv$+$7(MG5N^$Ud8Y^4gA_W^#e{;taz?4>sX6q zb6?mQe-5pT2+4obL)~8R+08yl5jRK)S#6OT@m=9zucBqU4uK_PbOBTGtyW9X$K;k5>htij z{!U;psQE(Ts!N`x2N)#Xw*JZ4Okzl&uZJ6D{^21=N<*@tlI;EXpKP6gY`vn^;5*#t z^_2>MkY3*~f`FHQs0{>Jh7a)hqpSOui&vER*unal8gBFHCO8o><=p#-jcnl-y3`($#x((uQ6c&Xcyp% zIz!US2b|Al1GEaPzF8O2N-_o53!vE^?hfXNxv85tM{R21dpBr~Qk@&W>4LrYV+p^0rBjZDRO{YcA0O*|5pG7c%D=kUD}ji)baEUJ&vF^>^~}6u6eoF7?S%<+?uP4{2c1rL#~7E; z;3w`rGA+}l@9f-h`Y*8*bxZbv1v>wfYQ;w#+pMzrMQ~MUSi`zH6n430MK)pe*YnBe zw}&;u>#Kdw^Vi+m{?paJ%BOP_$OHygNdzNBmxfLZMF13u>5g;ai^E4ehVa4LS2sv+ z$E>c1XVX`)+dzy0Z9^fSuTy8MkHrlXLzxYGiUqF#_eM~W>b9%eI_5U$u=)+DnEUJQ zGDj>Q+;&}KdMF9n zZ{plExyfHXf}}w#0^CG6JYsXE`KI?ci^16tzq^q}-ktKZa#`XTZ0I$fVjsX7$2yO3 zg*Z1R-EqAab=4jxR~I-*U|*he*^R(&v`!25!0e9qBq6Up=L7>Pi!|fFi2EHvq|MlV zK2wIU^J_v+Tx_l&Pa@m)&AS~Tn_sKqE*@mx6>SVJmRHgl81Oe=RKjUBt=lzZIgTjZIx0oW1D(#zg(E zvHOLe`$bI6j$YH=!`#Zk@MzhDVdRWq3UwH=mULZ3;a)J>wnX%I(Kyr|ld^bKrHORxm?uO?q?7p3|hq zM4C&NFrPzbhc6~|Gzp<9y=DP-9xXDR^q&%)nO*_LdZ$bHo?(ZSOG0w6?1%57T*@uZ#HWb3=P>hc3)h zt;)A-7tRfSUhstmEdyeoKCJ^>lmuCjA8#(o^z((ahU-D^3XFg?vd5)2c|SDf*erGd z`!!^(I+&k!7e)PT0W&BZ(uSSXLa%0J4+-iMYL%9Zk&yTg7@UI2iwQ^=y`)uObdG^P zvR5Qzk1=30<;7vwxQoHH3h?mqaG3->P>wt(#m7Y-*BWeMBdTdBAN(ZAeQ7G{27lIH z1&kk2Wnph_gVgY0p_T!G7xH|_a=26rhSV43T5o7Gp$Y7Hng~Coh$pu6DI9OOZ(Iyc zj0~!si63@798oO8h<YBPIkWVDN`xkR|?+U_Q9am41t;7^Q=LaB-t2nw^*;#p;JJU;=zZ6%F4lY)%Ru1;`ynlDG3eA^VUlr#Gi^EoL zL<)&EA}VUhS&x%7CCHft$Hc1U6+m7Md)ZXCcD15SPtx!k*Arqu&@m)fGV<=I>m=MV z(*P%UQ>{7!+A<+B&@fA!T#rjugA1aRq1O9O$}ygP6wTz6{JEEj#|G%-<3Lz;?-k@ zg{B&RHqYK0N&hbQ)?z<7bNlLJ*Mnq(9WR$nkY3|ueYcYFFkicouG8t*+Y8AxEf)xe zaU-m5W`W3h~W(uT~Nkd3QPHMq}w-Cfv_PlArf=WTPH9 zELT=G`5H+4n-q3^utMYKhld$Ji==zdKJ z?1_Zxt$C^sm(a}W-`^B*_?w5RsVrdr&g;|fs`bQI1_MKSsMERoxgAGRDMASXLU!aN z)^R>-?MHzn;j>Gn z7b{$BC8o-WP%0$CJJ6tQe3PU+K4|gUbbI*1msgz31<)6s@JA za=>g37dd@C=)>WV!iu^45w!-|W6SSCZn*fFnX5|Ge)8ei=Gf9$&*<17QplQ37Qr*H zZVq|12K!P_rX%Gj^N+y;o9r8u-eqRJqmpn7j9n_#>02~4lC^=RO~a?az-tWF6p%qF z2U1tdPsp?w#2uj7hNNZ55G@UK$81cPktWTO`PxRd#t-|(xsg{!_f5f)fr3)sUCyva zGbMBTGu`8Oy}A;Yzr>u%#H_#{3DI%Y!+XrXT(A?iEA{x|f>{621?B$BF8HsR?*B=F zJb(AO4$ajUDNLMayZAq6g?85ScaMY(a;8-SLlJ5w2=7^EH#Z2Qjz zA6S@gHiEIARJWiEU~1Mua>|vXiHR|X&lc{VyZrA@(7KUV*k_tEgM-w7o`8(YQR7pA;-_xZdx@ZF}SBGI^{G4ZI?x4R?T5j1~XM(ujPa$(=r2|)UN)VT5V zTHxc+Z{isbGwN{z3+0gD-85?2Gmlc|unnkhS76SH@|1@o0$cMVpyDa(M;RtRd? z?Q170toye2qJNP3tHElN*US0}3b6v}MNAUN+ys;0f$;Qyp`l|2N!W)36Nc%VO3D#(w?9b~F!j#8Ua0x#@}luaosxnU-lVYf0e`XVxK4| z|0zZM-?7hs+OP_rckCSPE z5XB8en`ER7SaL6 z9LAI`y~ZV&4U@r2_GViuOm*(;bjaMzhw^B%7@h=Z=?9bDzTJK%=k5Mq>vcRA%=gE| zk;8(1WcIJ1qx>e3e*~#m51edazek}*5?G@XPa*PWorStWP>S*ERwNb7Nrb|U#kIjx zHKzk&jA=Sgp+Rgax17cLS4mX+5uU3=?&UIAq@3xNEsh@?RVA0jhXydqn+0PM3a-hW zhpMlRnQiDqa(kUNc*ZoLX*x>BgCCSI?%|Tw?hl_0e!8$k_5gL54DxS(kCD9I#jZ;E z_3OJ8Jq{oJ=Mf|W>t9}w@$!#K*>80*E(lfgo-`N_DQ`*cQuMN#j4G~t*xTiU^-0eO zkbI>>2Mb+INxllA7ieJ)S!OX@^1M1!SH#n_>VWqNS42qhYr)o*C+fn9tr8X2x}ssz z8Dt3>*>G*$15C__esvLyW!2?RA1#b~mD$bDzWep>R!J6r-bnRgmEOqzYL)*k)%_pU zd;Yhxoe##&#&+he=FVC#V#{X6FO9?BLuOKR4OY(w;?POM`Q+h0ggPq`(tD<5juS(Am0@ zxj!u&@=0}~Dv8sf)#^6JbxCu20u)a!jIIKW&ZT1wrAm*4!V?2um;Ip&(Y&2J##i{> zb8ClN1>YPGMr{U^`bxZ1gPTN;u!4mJH4d6=n{7B+ms(FeQCJr<$olyQgw&dLKh{)CL%tW zSrpBlKdyFw>O}qh@3DTMB(PdLv4xSk4u@Cfk%7>?H9uYq%XCFC+p{&Rhqg5r(}vxn zQ)% za!X1>U$LqvY3U3W7^Vtj68WytD*$cwUT9VYW?F5(c`EdpTe3dOBvI79W*iB<9XFpE zWZ9G6FE! zp;S~YI5AjSSt^IL($%*W-{nBUWT^_BQ0nLeq2no?*V^O|jv_}ZCPF-`(T~Z&EX1~N z&`+qqCaua5^OAT0M@(mkZ zxbmaOv|>*8NA66i2=CDJtj=_&#p5^9``WR{cTI7h>vnL9Y8YGKlc72i%!@5yClNwGm_J`!})MtkDc+b?w6y`;rwAbt`d&tWof5J#w0`+%SBg%;k%46fQ8?1$b(6)(F34#CM2f2 z3tvfm&=uYUCnfjqs@6r>D;W$gYQP)+KU9N!|I&fI?6!n0*tZ${_#sVjti`cgYlN$6 zzwjC_J_-pC`7&rWZEIc~ShT_q_|nzw5fI45h%S!5UHANpXlt>MR=gc<{IkboX4-A% z@mS`&bGyA+A~*?V#_y7`Sctlq9dh(j#raf-U(6v9M%&$D~l8~mzu`Yk(Uy+Ow0E*xTSbWNFY`LUDJBb~Q9FM(&4!aK`15=LL8ZyBsowH) zApr_yW|fyVuyD}-Is}0TRy(SxG^5=4&TJ-*&$7M6SV_(3E>AllIkhI(^-zdj2^nEE zv3j<0*Hc6l`1n?qIhW(PmDdsv zBNcLddd<3G682@xFp!+pPd^NGA@z#}`^a`i2K|NA0q7}C42dG4WoA-pw;L<`lF>8mMxXT> z+m6}r9xv?Qi~gz+t#3q@A^6>=D)1faS-^?yVoe%(?-zvLkarHR*ybLKvma0NMbi!i zwZlB|J@ln?*!+(Lt>S+Kp4 zXKOfb?O#0R_1H9*SYQCZ&=TsOM4?@3-OcYpd&fLC-!?gfCe(kVGUd zSPI}MG-gkD2iolQY*iF5$M1z@9eoe{133YTH&4&cH&u6~QAPqa=+_fFA zQWWe|7Ws^6<;K-8If)sAs@+mf?f|~t@}&&RoWs<=cWDANd|Z$+uDIiM#&rvrpZtS_ zQ{=%S*Yd5LRerzm1JNSsYZaT*B*)VLEf4Dgiie3xjxnWbi+~`%S&6m<-g>vyp1*Ce zlN0)<_P*f4^}itZ?**;Ge;GMRb9)za?f=7kyCTWpuZ{Mwbt@a9CC&PXoWPP2I~D`n z58K-GfynA;@ap&uW3D92JZ-|&!e6~N17;*mAfck&ROY}sJFz|)%N-Nj*0htd$CP=(kw*6TEV zUcjI}?G@lk4JX2JZCjO|Hf%Q?Jp*ff!(KtK^30D=GG@}vX32}GAz6I(6e-rV zp5*+4r1H3+4TS}R2Byl*cH2#OVtInM9p4-vDfl28fP|f;+0&7tAAUwR@N%0-48jD+ z`8w2A@u^YuC!g7$`Bo$1l4+35{aVN_K#?jBP9aqzNlhP*MC4x>?+7?O|E+KDUgXWK+1nV-VZ1TviUt0JH!z(=* z$KQoxgPkrx>sznM$(ne~O>sPI!Gd<%0Q9$OR@Rj*CRE%rl7)?jOZvHxPX%xChRXZ5_b%Dx|BI<#ORb;)UK5r28+*D;0^BBJ` zLt-u3Z*C>SmA!%HedR#htgF;)e(#^BHZXDUEjt1W!8hY^Hz^*zL$beh><=~n$k=|46If+j0RD* zYMug%+x^8CyAHoTC^R_*4!jVM*&E&o>cW8X3;*V_AoJ z^Q9ab-7Qk~t{8^sr+n{C+Ic5^$({erpC>^u3HJQAefiZlvlY%S0XX|V_HO^ZiNZgp z&i|-!R7RB%#Bs`{SH2M9O=iB^ABa5t71!S{Tg&JxUT0Ga_5P+^_ojNG zecPL^^=jgl(R#@0{D+~Ee37mV8@al#%{$qbyISl4JqjmmZ1(Q=*wGL(21ONnixB67 zE_!Jrt6|+3n+=`#N5X}avrpkaM&G9+Z>+tWmQm zxbx+=?+MN}TQNsRwGUYLdEunu{ONM=-}{+lEd1yl+kA693Z;5Yr~l~H8zQzZc{unC zy+8#);Z+l)O{MGiM37aP?98Kr>7y^{z9n4zZD>pOYg_;B1y=MIGyb1Cx&I!mRsKH! z?{02yV(x6AWbFLc0TVOVf5QKdM*1U~Z{mD|=-!$G@9>yet^Z~Q4gw7tnl2-T;5d>w z3MN7iT3!TcxEZQxGFn2lZiQZb1xMrLLKInp&S>3N3{Ejs-=&Uutz~OHo3aM$3Qe1a zhL08P&np8~ zOmMW1@(O(?fl-fC^k|D5TS`zn9cXn{$nrh(y|}r8I{mnyfN+q&My@>PM5-pa_Z=6* zImCR=Q90_~g$!gHAs^B)gVbA)uh0*kF^aK!y4opJ+to>~Qn1j#`jAQzu#OZRr z!_K*fE}-r0iLUKs$*4U#reS3rGPU$gcT|h(_IBOgUvIzU+!2J*vC0F(9?gO7PW>c*sb3ub_AowfU(CVxhsEuZnXRQ=UR4ImwoZ#ZV?t$iYtV3d%KqR& z=D_I}@XY07nd$KE^t_+5r&Au=QWI_Zw^2cm6=qd*@Dn}}Q#=TBy2tYOl8%ISUY95j z_uLc}#V6qkV?6(Zzm(_##7mpS0V9U;VE6gE;2f-FOp4p!T*t?y$ttXk4{g0729+OMwC3F*9ufq{%o*wO!nZ+lPJ3Wma4|ezOJrw}MmGfg zms97AxZoas+FQNNotAjtKnf(o@I+?^(ObC-fx~*x&QGddo;9GQ(M5a0_G;Zo2w4&meOC zl(~7jOww%ag4-t*s5LcV$3EdwI@p={WNWb8hVT+lz}3HI5|L-`D`k>BEXG*#twZg0LE7T*lsq) z#+zl(Vg2-=c`o`>V7k%TAF}T2wBTKLLyz&PL{}(ZezJr~rx_4jiL|qlglDal0#@@d z$p@ynWjG-yw`ym~eLS?rd`JonLEsvgPiRB}{O-!o)0to%;h$%*7EyC&AaQhK2pc~i zT9*21Ci_s9CO6m+4Hd{L5)pl5Ea# zl9@~vC8nO9dOu73X0OKBy%T+^$%M}$TqmdRtz!1@S62RPOZnzy5Z!yCp>7qf9BrHX z#>djF9R0zf;@V5_YYz(Z^NlLc8e#Lhpa<;+lj-kn&)x#4a)z@+L@+QrB)RSdN6P$G z7?cDgxHqu}<%L?T4ymB$r=;H%EqMCfL_yRA2!?$Dyvgr|&0Onr05in>?Bdl6<4#m+ zKR!`a5S;o$BLq$IrQNEFDeK+{1ef@SjsJ;~C%em|?((}_Z2mQlMumMQ)WUfnF~YyG zZEUr0j!XqojBWPHj}@7VXX5cxMSc1QCUvGFbG*Iu#F8jpS-9hr3Px=ZhLc41>I!My(v3iRyFOvK-!m|`{#;%Pft4O-5Ym4-osQc?Sc1o<=$oeR-kAO+!u+`a z7&v!yP)_J9a{VYZbus;1WFqVvN~^i|Wu@-V<7^PSyP$Ca+?oQ-=Pk7-CICtu^5j+Y5E5bS_Ea7xWwiF;Y}*4EY*Ys@CL2C~kVgp)m_U$bY| zwc8B@P3*$H5=s7H&uR)Rz5Hczhkaww&gMO-QZA5`p(pv;Mh4Srbk8H)zB?B`HZQHu zkcEHqn`SsJ_8V2Vz#(%NT9;&Yolfc*Cmm(%cxfNATQt~E6IWJUv)%1T@b$N)W!IV} zO{y%rrs$E0YO74#3-gM|>&s!3g0eqN4J5)ohV~r0&Kn2e)D@P_!*`vVH%3(LdVQ** z;-Jh~JekzHUqhN%SL~;`jbHfVONZ1{uo(}cusNb>n^9Cg30WMO;5zTszKRQl#W7?t zNeS(7rT*?T)Af;AK5M)x%)05aoM^vlv2$^xJ`O~eq6D3>NBvyJdYfYx)hA&&1 z*{zl})es(va9_blcB|*GHHy^efxAo z$GPX%7vH}XbFDGwm}9)}GxkBZnxo>9^{bZ6#3-1UAS2@ta_eECq&h=HVJ*{?zknaS zMEN&TL^ga3=YP2_$jk9L{+I_fn-41}KyHi>Ad9o$A7qh*COIvnPPeP z8CxtT(8pn@l-$k-1Qr{7!{RDNW^JG4KJ^fs!^l3oP21(ZY(e-VyvOUo@8k~8z2&(k zgzcM9a5deB8p6|&HYtt!X#UM3Q)}yVhJQ(m7EI}5LDr`Gogc&t-wETz`x+S!)m}!h zpKTk{{&Nn0@;0RN)3zznzHo$AAc0)E3jk9{nK%g7a#`G~p;w#sC>NK%n9o0hhc)EL z#!By^aB|cD^%0LWBGV|6t&v!ij_?xddCSQ@mq> z#u&(+2Kkv>tF}&E7Bt9_9hA@* zu2_QubsKD#=XxqaKF1X}X`4(9KnH0157LaLYSpA}Wb^^T>pRVelvEE=I_cqT@FvA3G8y zb+P5mIwgD+g38WG)9L`uif@53f0Z^Yrjnqsa@~quud?4rr6QF(yd*Vba-Qd#yoWip0?usC68*=>Y zyu}YNCRY=ikYRq58M1d+8nhiwqZ2uNyz+Hg;Fv?EY?Kb!RAqPawpCCPBP5?c3oNWY zyO21~1^DhH%Uf5s!R;m>vYO<>G_%u2H^*w&QVT&xfWgv+*)GDVsVA!y%T}3oo@!7b z*qe{T<(|WuU?%kRn&V>GY|2G!fKX@r;AvtJXr-Mtz^EoW4?I|iZ1CMFnVlkyz41B) z7-As9CWhKaHy)d7c(UI)mG?#q@R}#lez%{W`xvqr{wQ4YdejJmOK3!7a&{ow-6F`u zG4sG;8mBi~7ifw0mO$9ti^U8QEQ=56^Bhab0w#>zU&o^(EUm@pLBjSv7fhbpqt0E4zz- zT=t%uJqUlI@>!PM$2T{0*Y`@|E#y+bhiwt?F3Hm$b9(p8*a`N5{=D>x^%?aE%~xf! zvvtbz9@v$WGyiwHD{CvTDQjdM)%L&i*QAjZmrCLYNhgf zx)a&g#_5iaTHkxy15`Khd+-CM_gGupR+BSj-6K^~S4rYS?(Cw0Z;l+@8D)|_Pr>@) z9o3k-yiq#{)s%9zx&#h20}^crt?FQZXkzFzrNW#NIf$nV3SQvm1+*;6uqSA3I1WEKHLVJ!fXn9u%Y%4rO4~#Z zX1*|>t#^FpP<_+&!K!D`fuuudJNR{fpeT^OLeI;W2-K}FMThZN~Y+mm}``w%t1Y|xHXpTQ01Og2+UM!O1!bU~DXa#|e6i1p1jL;sL?mDZ ztp!wOK^Y@MFeHr56GixK%M`<{gb$;?pWoaz7Lp4>ckwZM%)0Ofg07-b5?<>ba7gPQ z3}u_bPHNC{IZ$fOVgODmKDO+sBkF9Y_3!KFTN}i(L~)N*%kRoGwfQ?wf2|hMq_0&vUlL@%ptfepFF?S9FT~?sonX|B8l` zx#rfsIv=tL*V2O~U%N&`BkDp$K-$RW9YF zs$6kZ2L2$pknf#uTn4d#^q|JixZC?&?bwe@{9O+-3)YeLMmX1n&P7xo1yRN-N233HVYJ%4k^jy7Bh@ zDuX&=^&-}O|*x} zO5?QyWJzzKj(0!+b2>f3L6=NzO6T3LWSEMd28I*Ljh-4hLH9O~CzYMeCCaGi%5KTS zy-CPx6!UD$s!-3bDH$D(KFqQdDZ6vxrf4jX6FkK27c0o-CCq*gSR}VEDG6XNdWaW%8ztT3o1Ul%M@D( zzyyy+xMH2AOW=kiA>~-R#EQS<$OTvqfcH7)K+$-`AbmZjZ=Y;X{fA!sq zQ3=#M1~iG+G-vygrU?`~B5TwaW-Oo15LRC_Y9l2uS=lh`*LT|btT;D~Cv`^{v#s$u zZW{kFfrz6u95VsAPSR;{&{ZUf)%UQlqDSjMN)WlR^T5)@Wi8^BZ%coF@bC1_@nLHO zcB~`*w2i)iJy>zG-{7+&p~o1lZoW%5e8ac3(P36dyk4kVLD3o@=sZa7%AGT@GM*G+G7+IBMixFZ1aoni~L%9 zlnVd$hW)h$C!(5Hk6aVqd9&9x!O~=7=XCAfP*&@NvokW>5%k4poK}IscKjCE&=#>O zQTXd4HY%uYcc%>(s`x&HLOr$9*`0xISWW(lE6@VNM;XH_R;ouV*(rE>KDHTFqzB>a zfIC)YH}O@!2Ea-57rrF+y`5uKwmABkx+4cwHvMUk*hzHBg)K1K*+7FLeSycl_50m=UNbm5?5I=9y6Q^P|UmPpgMg~EBKx3V=roYy=7j! zWL77{M>TNNo(N}zx4~sg+NWW!1aIc5CRytK40v`@@u?Qv++Oi!Yq;b|v#-4=txF+= z@GT-stn5KC$EdP(y8fgwHN3eo6r{IOx8&@bj1ZUsft^4B9J<`<4hRxk1>pV%ffa#W zOR``8P8;B!>yI(UG1{K{#wpF77;_wWCClVbm=U>tb_MvYkkzXvkv54>9r#N2KBjXx zppfRKSbq=GI1yTBqPf{uFTx5PbCQ&cwxPLnzr~GHR;yyOddFb{kNv2L;6_kO(V4uc zf`;qR(*arc^j>d6Yww{L(S2#IQK>b9_>e1XLJTcP-3P3*ic;3B+=>ymLv54|bk2ldYKLsq*>0fc`Y>kus2 zEZ^47tYqsiY@m7nsm_EFt8*)y`ER;pvAYsq$7H8S zZDeB9?ld=rgKV~vOqh=V%M5k-x#PS5PQFK_bOk}*SE5We_vv2<4cb90oN|?kU*%)E zvrQ~`nEHLPHlB4lQtdvNcUwI0O8oXp@b;yf-71j0e>!3M0BuwFifuZ@pNR^6Xg_bCI?;VazmNU|##u5rU;4Yt^nqQq7~@d?NgMKTb9Bx1%P-2(XIFbIeGxeT#|hE^-jZ|^*P|n^MUfvnS;O1c)c1# zRG$99i3)cJe=Bqn$e7Xqv~n;^wwYpnKB3N zusEeFbz}+W^WDzk&JvhPr8!U>)~9FTI3=}JpGrS+#T+`}`19I=^)m4SKBi?@^-CG9 zx_|BqIhQ+nC;2Ff`kh_NG@Ocioe_Pvh_6q)&acae_jP2aISPB)*3Tw2CV+;0LRFgg zAV2Iq-wqv9DJ=2?eD9Ze9HZBOp^fxA`^WbWJxD892eaP|sXIrK@D0}a$l$0LZe2-{ zQ@pskX-ae3HYZc$neCZeaTaCHnW((0F}R@mXU)(gi$3;%e(jzBid9p++}2xvCJ&h& z@0qI{mq{KSuPc31cdRIUC}Bn?ahho}?sG*z&@}YP$G(5{y@r%qGTB<4X$Ke`E!%>6 z+Pt2Te8oW?@=T85i)m7lv;_^Hm5>kKqqgNi+Le}Q_ZG|kz!9d&1_$^8;TjsP5n+gq z`Tc2+#<(fTTqgF1zenI_y8WqdzaO>O$9scFN5hKP7RZ30$Sj?jaIYyPC?Sz`!#?<+ z>fq;}0+*>os&cP zywqN*l?R6SObsXSkM?(bzZKqt`9TRMHjj{S(x>gR5pEG-6*BmD7y_Tgj`604ubXew z^)d)DEMg@0=wsgNHzK^PJ znd^j2v&`}wlD_5^tw3mtS}6kGs~Gy~!sC?d^vWTGepUc{4i= zkuISXjwiF>B1#TZOd4V$**&ZZRW6OY#4qyR_KCeYcgu$WfbF<3i5pWVLHAYM=7t_V zARk>(n?#O<-y8s8ZZKCR2{>3~+f}Me!nPKpHTEFpWY}rn@kVggk~e!kSWABuOwH!8 zqoEDj&GbTw(4wGXDGv66!GHlYQ@b_b&HxYrak3_gWwxvSoaamMMJcl@G!=sTpKKyh zbLfP!y08f%g=LVa3!$rX`>S*7tLU;HEsq>+y1Si&88KQA}7A(qW?#PydKWG;^>9im!7kU&N~N)IF-E=6r=RDaX>A{yrlC zRt!%KFR`l-wQKsji@AO&Z+WlEy;jdYr+b4l@#Vt!HLrTJkv;wg-guSXf-B~1AEtp# z$fwkT;vM`SvY(cEHDvE^WlCYhLbu90$@)mX2o5`u1k}jz<5rkE2qS>mORn zhd>g^Uwx>@xjnxUBPbMwgmQ%>t|G?=XU+kxJk)RlP!#MyA-|-K1NeIvJZA6SJUzQQ zLAy~il^DwOPW9#$htKugyi*zk+=>1g-IrM@p4X7B=@`Tg7q%EeTRbK=bg|P+k^$p? zj}>N67e^kcOZHvzfp2+<*r{%SVM z-#v(Sw`btPxTY{h!UjlXIZdS{a=nkt^qg!WgC+|F=K_DSdah|2>poLgnNiUYbwi z5n;9cYl2;?JTk(XAJ;$PY=yc_<#XSCbrTrKEJ)k!;D6{2p~q51&*Jm?%Km-18<7|95J+blBzrDN-$pXc@B8k8t>EGw^0Z=uVX(0;5Bp4}B1!*w`ttc;t z4>kxc!R&H+bXlGH^u-LNsH<<7rceWunI%c*Y8sJTpanJL*?u%Pfb~R35*?*3LbfK2 zE6W?Ea%^4{U9z{uErt89MSrXwB-b>O>NpCIs%7nQFjqJbUtn>FvcdWT*w;s4BuE*` zvD=sjujy7P?%l&HhFF{Ww=+nnFjkogy$+M>dfg}Mg;!6;Q#tDPlj)Wgq;nLfF9=FE zLrW%y-_faGrZmY`5;5l0`w$il&1EE9NYe$WojbTb!60__Wf; zuvp!r#|n;GY7#wRvgYZNF<%R6k!v3lxstnNE(z^(s#!M0y(}tA;;;N`9+Xqi!$#!6 z89ZOEG>d>ClI~xn)$wDACrGr`WNmFz|Ng5fA+{;5igL1w6C+$xL#>fmqqj?{gwUh<0SYqb=sctQvcfH5C> zm*5fbOnkxj{SUQPQAKxgj3!Y9MHUf={fNm?JQz;n(Yoj0_0UQw#zJg|_Tw~?tGct$ z&LIPWHYVkxyF3+v4u%JUdAzvT3*%0~Vuz23IlKM{UER!i{2c14S#qtSDNkf=mNq?> zv&7~JY_5(*{P2#rdq8%ca+(S+7V%9#T%tD1fJgIA#FJGYzN{s2jW{QmiFh`#Y>f?M z?Ukt!-*g#}Hgtg(fld!UIvvQS)S%&}l!$Ui+IUHrGyRVJ&sRvZLS<3U2!HFIzX972 zfhZl-L9k+=16M)v)PoBQ0M*iU=va}0`4`e*{iADM6Q79}jS08jF$w#cpl&~@bkuVK zPmF3Se4WNa=MfuORGYMAf+~dYC$d-P9#;6*`s(a2+kxUibx5}I%plwPQFX{>?#X?c zaEu+Q{zjoQVYaA^!ia6)Nx{!KVOzh!Gt`Ehf5dgM<$V?7x3A_3>OZCq{~FhN|5xMs z-_wT;wGCAzWt1;mj6=9R<-}?rTFDtbe)0x*Bo@0sEDT=zSP)uHz|hWVmd6m63&Joj zEuZCj;c*r5#vXSYq#fhH`=7m%!i_`~!?RTZKMKSTaH7{%AX9BG=KVY#9g9 z!dD!ReiSHh9!vFJs5I^*B+8MI60#T#lR!j#hXKm{`P3 z$ndu$F;QW9<1!?c)TmOnE|xaaEHph?+lW0Az=#f3B|&)<`Z3VGXzCj0fje!%sPO4X zu2i7h%UP`22AN#oF2dw7E5zW?;UXWUYP3pzACm9C>=| ziF-R<3OX&lX>$Ui?wYV;w(ty1jdVFp`@56x*Q?@7Vm}0%e$r7Csz?P63Y{m~YV_{p zHFA}E`}QE`=Q1Y>K`P5~G7@Ea%eW28l`}c=xA`xwNXKv)%gNwP-JHL;ZT1vRBs5B* z0tLxN82vF^ZiilyQy_ir-w-11pc${pX6-ZlJl8qse3T|*W;M@6x}TDrb7(a%)ei8f zvo7s~$vXgAQNsDTi{>&HtvCLeW9+oKk=#s0S@hQ6LPDBpSHx*9CC`YmxS*(GRVeGA zkOt4Y8g5M2x#9HCs@=;Q$LKqssZBQi6hY@OX`U(i)TD(Fxmtu;qTNT5f_eHNwi+yq zR!`EmMvb6Owp=mZZhgr)7+9XXg`enYMNGMrmr<%(6-jC2un6Ne)!TSR9PuvCbte2W2@|i`&TQEM`ugJue^P9vr=%3m68N){CHTVgf29sgRHv z;}WF=!iUtBS%fn)lwhk&b3XEW7UTNOsPLdTP3<{bT=q!@G(rLr!PDn3QWi6382vst z$?W9%5~JDdk_jKKvvXF9R%xLQabd4cA$NGd-w1!Hox8$bow0|&V}MXsW8>misSzpi z%#Pk+(J=scxIr-=E4#QcR~NNp=l2fl2QkyndUuo?sBX>7bOcDtBo*BfHdExOe*cc8 zm1;4`rA6Z9#<{$VXmDwMx^I36@$eY#lr(VjolPD;EAsYYNSrxyYW}rA#+XR6oF5z| zgT6f5|{(L|Au zox=5?uxx1=^Esn4^50EAN3T_7*d5I5KJRXH`cSi!`w>P#F}S0#EQ>YP{D~4ryC8GZ zG>Cs*4Of*3C@?>Wv7pcB0>M)76U+Pj5@ejv_6yI4wrM;9SIf1-0`m(tLjiY|?n5q} zE|y0reU$Fg%+nrx4A#x{@}q6u#_ovzJr#2ekH$K#w*k06hW+#PqN$)7s?BnlSia)+ zyaJY36G35;A~(U?tMbU`Tq8T(&nry+251j^as>zXcZHTqWC@^@z*5PjFjL6OPp^T% z6TTRj8!e^d7EDx?pEZ=0pEbqLCe@fSx9GhiX^lAsX_(fbew?Gostqw7*@N+n@yE1m zDR(U-)oGpLRTX1)_f#(gK%gZ((GYzd#2DAsB}qQ$l#4k-~D z&l1>2<=*EYk0-(_H+ub7>^*2jtuwGDo$DrbR$XYsW?O#vOKMS%dY_Nb zqLk#_HQF$vbHG(HYv&E(ABRsPXx7=)H{}ZHKT)p!6`%Qk1|s|?%<7-we1#2(Ujhi( z%6G>jqvs)bxiFn}Wpq&l`TPipaE^Rb)k~-2!9u1coX|dcPUYRIXXEArC)-N^v>Yp%Br{ByYRvPAnckG$9Tjm{MaRrz zN;>YynR)ZWim!c8Hs|kMlTw`$hCVwB+&N9@KCSBEs!~jmQpN^tis|av@6*#d24IjpN|z`5S@A=}SkY9JnPp7O>q z?0v$lDzrX+{Nv?;k907KecuM~zO#q_SL*+-nZy4TL=wwC-=@-rIkEr-PeS2}bh<{A zhE=7;PxD!!B@F=vqJcpP!pb5_;DL-0W2s_G=iN(7)GJg^?9STKZO~`AT{bfWq9n4P zpm$$ccOR4Q?++IczNG6CecxB;JF|Y<89)k|9VQG~m0HVStS5z689w9qenq=y3>V&$ zri?VitWDAqj8kxbxjA(3N%{SN@w{26UI-gE=ZH$uSSKfZ;mQ*{avQB+a9Oyma!JLn zvZ7l|rn4@3f905O>WT%!xsvj@1+GrRWEsP^fEEtW+&gTP`|aws zEQul7NS8F>VJ}iH6(H6aSd~@>hjDonQ}q`(1)grb+0pO=nG#dc$A%~ z-X22yl|ni~zBw+Ro=Uo+U5vn51});w693#m_ILasi8#~(UggZv!qB+Y@F<)MyV=iw^QK%&ML1D^R|nw!+v)({|2WnCr~OCV%GUCq-(}Lj zVS0zY=BTYwB0>jXwqc8Cr%?qE1rT9UC0YZC;JZ@IFxN;udNyd~`4Ym?#Q?m|!0&Q{ z%wrl@t7QJ%_v55T?~`BWnQ8y-9fax#EkJ%UkYk{nNMwOWI_?oPD=u;)nTTYGDN0K+ zrVA&R=Z@ON6m-ow`-vzVP1r?pw7x)-ATW|qT;ss$g0sW$2bHEh|CUFm3cAq}GuVi; zyl3OI@Kwb@d*V-N+jjI>M}?gxySV^exM&3I8r4ZJ2Jhe$6N!+QuxoP3eLD5|U+g%J ziTU*sz`*>A@#N9m8XzyTkr<;5CY^H8Tts|XGm{(B9Y!VXY;ApUe{~DcsvN~Kk*zTD znq7hUli23`M9EfFxJ5GRCxoI|d0Rr$9c++fb7mtwSgO&>!NUCSHm~1V(A!OIlr3GO z+L|7+X}_(LW>smuLU_-K1R)3`GzPXye61qtELMJCQ!Ndkl=Y^|z&!OW+66<-u&GAq z@Fda*jHPr~CQ$?uW^figma2B`DS%2;**0WhEoJ$TF9eO1v(ZeDD0P@FoY$!>?(09Y z;7B^BTseS!s3}cHML>Vg^$}1=&uA&yhP$K^BdjC{kOwocXN~>?f~p>z#@q~A7MrG= zl`!XSmck-h+h1eF0!ycvr1SzZ%(yoLEfC15r~!HYtZobR9{&pmorv*t$&E(nx6i-1 z%LCA(1rfiG3da8y;2`!tj=ulO0sZe`IG}3bsHKehDZ}J&HNM{jYgWQQT04uzHIgV} zK+6Bx%?fpq$YPbi68q|#ktS(Bm&Ua-nN>)MGQSAD3)(|OkYD**zM%MpnQs0dpi%47{)E2&YCVlRz0mA;$Usc{6vx|n{gk)oQKpyf>lO19Na>&jFvajQ zVi2*%3Q+mRT{Ap{8rMa-#ScWv#Y|J;-*Qe{;Gz~g^x7kYQtc-9r>{ss%7v&at9v`!O&Si0S zg?24TC!);SnaiJ!Z|I0e(@>U#72D<-Io%^p*ozl1rLo)xN7mC9tcZ~}3Qd^P$O@*! zHP_s6n2j!fo*S89Hi_`7TWA#5>*TU)t&nY(Ns6nS-bb9$j$_@`l%h-n@94W-N;9xgBDl zeqgz~`QB&ZOQTy~)-if9soear!cLyEG#nRFkwto>p6nEj9};aYm;jH7M0A<8Zg>OK z*N-tGY2LfG_03nNnJ<@fHMNFdg(I=uW|A@UfH;APLEM-}wyC8|YDDY92u)UUoTZMK zj)$*_gvSkY7}?LPKr7KjUL|)f9H|`i(u`(QFV%3tQd`d-pve~{$J{?Qm~kj*TT|3r zpHr9qHQC2n<$Lp5L_@d~88$L;uIhN7g5)gQ{0zt!w1N(meBldE=noQnC3EDKic z3cUi~Em!rvX1k=|3cE^@CDYO#We{xo_g|`ZN_~6J(ZN>|w?DebZ67!musn7}V*0Hc zC^Mw2Yq;ufrPv~Ee|q8%DZTUe*_rJ@ahL6cuov%8a#!l}KZ4sS48#VTFwodeoS#o^ z?bIsCDv0ceVtGfJD07$Wkh|(^?}mk#7%WPW?I+baQcc-#Rmf?S?36sGk?^JLqhs*~ z$5glq^hL0j?WD|}>zcVjmHfy*8v6oYTYMYhCy4rJ3{JVh7Wc0BmI%>~P=iQL!b`Wl zDsQG4Y+9Wi7whO8fw^L+hoI(86Qnnzx9K3Zbos*n~h~lYJ2pgLH2I^wX}L*#wy?Dz>%t$%81J3Ji1%U!EnE= zH|kCpqIz`A>+$Q$oHL3LLvq)=)SVo}s)4_~PK$ao2 z9XhC~>|Fjn8?R4dc#gOAK0^!k5WnFk^1kRTdz7bJi*?%x=73S*eI_|Pe_QqD{>^xc zi+)Et-N*0;y@<0~1IBc@P(-HfFQ2zYD zVhU!~x26D^I@6wOtR(aVMc%s4NKOvSJ(P&%*H7NzPjlY__&g~U%No72IF?6JM`vW!6{10%R75OM*+B%khb>?=l8dN z4KHXGGhGn|EfZDW$7ddb|KP@jRl`vtu|5GS!S2G&^g~&X8XMndXyuu58_G>bXoLae zB7njzS}IDax>UIeqdPNJp`uC;8_F$&p&7DKLJYH)TjJTUBoX)TxfaP%;5>Q__x?^> zT`X1W9gizyk3NklJmtIsnF%-|H{BlMZHOnRni@8wo1h=Cmev{1>trWO-Lg|H)Sb92 zvt2dAd-d!Da|=qf0p%tE!>4bOYeM%kbHFEh+p{X?2b<-<)=Y4-+VmG_=QH_b?_XQU zufc-n80>O9@H}ws(7ZVJ=HC#1$-c=0eyhP3fDJ-#u3?yAy{O=OhV+?UxpG&G%H%azGSoz>(Xy34$6;upYCA+H1_AE~lfpJh(#ip=1+Agd)Syc zPoLVX4r6Fh9cPTsqqd+48Ndn>Ctq+|V^ zJ&w_73qL8=lpnnPnf#^0@inJo&QQO;{w-l@8SblY|4x?hF#hBH`d^D93jgDT=|6Vd z{vXo!zw*6{;wEH37*T>`QBCyt`+e}c!7NQ9B~`&$X81{@c0ZXG^9q?4ngl&r(Z88I zM(2@(Ez?53(Le0bj@BI`RPZ*Mv?U~U0s&3%@XY0a}DWS z^XsLKl1=sxOSDF`Vs{h;%%vuWOPGV(VnU75XP^%?~xelq*N{1@Lqm_S06%`Q~={B`}mx3nQ0q!&<79yLwhw(8DcNY zduQBq-H18)#lxegrzZH)oBkKd-1i9FKb-Is6+4uQmCp$#19gqG)2HHGvfZp% zPHA;x?xtt}Azl$F}TEe*W+r~P@=g(KoFsy93dl7Lc#>!B#&Bs-e9 zFdAXp@@yvNluMUG8Z-0f_00trki)Vbyo)eVMXsR5;GTv5_Ts&i$UJFkbxqd+2UsIKhRlhS$zXMLdY1>}vX845H z);(r70<{&hWwMry>>fl%n~iy)oCB_I#f_eiz*?h!xBVl_+P?Spm*P?OiAA&9#uMAP z59ksl{tuN2cXRhSaw*i%mmac!4*L=LfL*78VQeuqo8(#rXTYZm{hwmER&DfJ zD-#DE##l8w{4@Y4=@=v1X(R63+AbHXSKP0$1MT1q%M(Vv{q%_ue>_*i(%7>g`m}h> z1Lq)*WLv^p;+^Ys%EPW}zq)!;4wagIhS{Eh2d$un0I!I;l*LM(5D2H3)LnJPxO?rl zSP}ZVFZ?iRj-Bi#Gy69@@>%jAn_iW1^KExs$(a;AD5Kzzto&n<{3B?h{pAGpnQ_J% zrI%S!gX!c2i)v% zq{~`jAdpOnx2~FGspx*eN6oy2v+pc=3*!5q4w?se+x$T7}fA68J2f!&oQ1P#ia zi~O8hk!#crDK}@&;8Gbo$Qo);ExWb$`imO;e$$D!sTU+uay|kHGjQjKo}CB7*2+yq z1wz1qHxec$1I^*8GS5w@D7Hr~HMimFC!$C)P{4xV5%ugrqVsD#gD*skF@^kH*pS#0 zulCwv3n8A_Ce}TsP%bn}ZdkseNk6rx$Tpi5q!GQ>CxE@vm&L*C57^0q>O83yVwWHc zV|~~U$|*$}g0_k{Q6nNr&tikD6XVs`P?`JNebu%8>gOmHp(__HVkXQbM(j8~mZp{b(cB3RYN1flX*`SwJa1Xs@~gD;`sJ81OWsHu8X-L*$n0Ig6D0wZ6_}Nh%d&{3(uEvKfEX z7-R`Kg;Z2rqjU1v=NBL)uBqHcL8dhwUqUj`%4?Y1 zAo^^U*Tw-<&{c06XA(QLTNpH<#ZXToW30t`8_gO!b@33+7^6wXOZ=GO%t<;#@!Hud z=kZNxIZL;CCXEV1yF+_D(3|u`WQH$aIKPBh@PZJK(8;fZ3H9o`zK&kg`Z6WvNkT6$ zlY0zY$1L_6O&x_nVpE75%K!r+Ke?FcRqTV#;pgqoJ7gpX483RDVJTr^7{sw-At!Yy z8*OgFk?T+TUV9q-Q}$jxdVQW`{*Yox*L7vGYN$I1F;e%@>|FLAaWS0b z6jktj^2PtR0Kxw&9f5x$I|o!WzXwgBe6n^8+bxhZ5XRb45BNG%oTtYll@Nx}o0S@5 zEJGpdk=4gFH~G`F#^a>(c4L3}=5%viPXpoRPQCxwd?sYbOq%;eFen2RAhN1$_FdZX zI?Cj!$nk!=ga8unKpzk`l_!af+@(^0-i-bD31&l;3bXaRyCmzwQR;;kg)O|6M$QL+h3 zlt*tEt|n=+1aqL)+B!K-&OrMbTNso}18mQPlZ@0=@mu@`Qkx0a$;cceGeEs*Zr?cC z)KLrZtZM5Kph)c?cpAjz4qz@J>_u3v;QXNC0UsGQSjnamUZZ;J+C*2k(>#nirpaip zh)6aREhh5NYIcE@k%FMK7O9+&4u4+0G2}4ikw}$&wH@m9K^+qY!Kqxf5=D0t%*W)T zoTwU(65t{*IU&1gK0WKTSpJDxFibgIp*A25WLi3Ag6Lev}vUF@^oXIdS))fjWo;D)JUJ%R^xc1rq~l44qXl)_DRf| zy~L|cRAa+ro$TUeNSshFW#}5_Nia zaB5%I43`ksc6IBs;|ZR5Hr%Op`(+F+p8sp7#vCxBXg6wHWa8!JrZ;WwaI=~8p?1s_ z9!T`?!yIt+6!J78lXd20DY-T0tzHZ$J2C8ZzCy)J1ru)D|&%SUeH z%rTWeq#S-)x_36Nzt@2zx8V1{2q5Gsg^Jfb$iW+s2Z8b`dfbyQslR&qr+0JATY9u^&madyk_ zKb+zNPr38rDabs}TuPl70Ws4JW{*IW>vwS*_e(iFq#aUNeXd|BCs4ENKYqKS62^Cg zE?u`xG5PfKNAHphz0Z)0!0MfbnhdS7j6j%@bTURz^IDwzJ@S+S#v*5k!zHPnZA1}B z-eg32!TrakqPA1!F!g=d4nhCNlzR1FhSiDuk5g)a-wuxU-xHAjKUW_WE5&ss6z@8E zC~Sq&h=?ky8LDI>%0RR{=%U*?f(RHZb)lZ6bL%$jbZLSSrd<=0dza^dm{TdR8B8Bv zzCQeXUbb_~vZlVOEGg^DiOwUABkm*8m%VCT9|&7ezi@9U^4Q+U(H&?m66;-Mt zp@9wnW$aUHe&soz$&C)hvVAD-mCjdbfC zF0$J`EB_&hQeadv)_*^)nl#b zr>elSECC@GHcFDWDla{EB(kZb$u!T-qgRz-3ks1`I!?uga;E}Nwx)6WZD{?Gcm_FZ zd3h2a*o=s6+q+sHdAwKzJ2Z}mO7r&Uro`a}TZ2lmlW~T!@FZ=%*xWz?1m>{KEp~MK z&AZ4xa@&Rcwd>KtI?~&{qAwA5%O!ROmJa_ImX64VV5@VAXSF`^<(X?rUSfkIv(CRa zKh8id9AI_3<>Y4N(D+qv+Jd3SS*Je_0{GhtcYw>G&9P|Csa#8YM83sBWGw8q18F?4 zZv^5FQyFhabkH)6YuhXBMcNv9zAsz)@~Hj!u5B$xt$(Iox7A5cSAvpVaON}{V7JhV z266N*T$rCLL{?}SFGwPdIRA86zLf}7_uGu-g?V=$afa%DnC$Ls5_Mztl>pBC?h$Qv%-mUJ4AKylBaPwn63 zr&seR>J!&kdZnfPqPL*&@Y#Y9x|@QkZ6b2jAXPfcQO2$-3d{ces#2uC?EQv0e~Rnw z0c@U)juI0MU$Z>C};sUvSfhcQirP%a+2SDH4dDYaByp zME?;vEUP7K8)N{Vk28c25dCA2v0M4;#H=HH$=8-lZY54w(c-taBra3V$~j{GSpj*d z_%=q29_J(W{)MCEF~%rjTk+n>GZYe%x8;eH0`~Igt}C`zD&e7J=~LzOrKO||nvGuU z>#l3U(oc<5QTh<}2>D_dOn^g-dO%#Ua!iZLbLJQvt^lgBlVobXz^XHqb0o~%&2eI8 zykhN@Eh(<-NI~Wp`El4T`aRyx?o!?T$Cgj=UW^qk5>x7SR<(0?cn@%#R>jMhPMX! z@IL+$5NYzE(ksz!5R!a4A{HzlLiF{J8I9F}zsk<+ zLu1xgnJ{9xu&Tc2yL|om4stmkCU-9DevWgsf|EPs%v>MJhX5Pp{@HVuIA9ycEz?oz zsqh-##sa;y1?cehodPnLKmR#O&RjRI8nJ8{DoeMd!HT1wvusQb77N<3m zHl(fgR$N<#y=zQi`Kx2BG3`J0OjdX4y8#Ywdu>vwh8R3&YtZHlSCOqIb}~s!&;d;A zwixKvw)(;*gsTn~(&l#F#$qqScb;lmbs&!(m%Gf)fkjl;jfV;SB%S(6>YdAsJV;hM zQ{*8MiFi9~3)t6B_^zJ?C6wEhN^omx`v%AB7SgpCy;oQ)Y3w1ieLm;Sl2%B=;gJ;Z zL%XY;rl#g=@y#YbhiGl#`BC}Wn3|NQ5MskQo$4s^#duBC*Urloo6Un08AGmWG_6=y ziAiq%kf|7T{HB7q9o`1CEV`u=W!-Q2FMp8x*bA^~Ij&UVg%%nxxG7j^#yBqTA}lPzSb~n&DGGucegZ13 z-ZsE&5#Vw*dZ#8j(f*8Un>oNTm_!5=2}yAd75Gj`wSTTjF9xq+T%7I+rK7@OUI0-H z@N!Y`X$*_PumWbFKH-{y?jwvsQLx#EOmMLwNCf-N%Dmk{)*H_XgG%k=Erm7ewvt>%4+zVLllR4o; zBo6UC_6Br9(zLv7-Tnu- zt|n3P4in@p@dk2Y)epn^QIxk=j{7UcDPPRKPIA=yK}b znkd_mLxnSt!X*&ae@=U#OyCke2f+mj?k|*dEu^D&;nRspBpL~thd6Std)7T1*=QRJ zql<4dKu8x$EPlv^V*@eG8Zq|lWk<$!OSgB7!C&+D@b=`BMy}3Jm{jyn?~wn!y#Al? zNY2up-^5Vg{69zu#lLqzQfExm7tF|M<34?vPJ{?Y#K8siLj-{1=YZt3={7g|&!VLZ ze}oXX+8qu?gn+fuR=&v&+S4GUl2U?c-f>zTdL44uW8c0^MrC~&q)Xz1=p%E;O(r~z zgeAxj(P0dvJK|fLmw}g-G-)o{?gah>ln$LkEgI<{*@aVSvzsm3mFpz(k|_XLM5&rr z)A8!`*gTjlENrd&mTHd)n|4xx9i}dcS9$zI#p>Mrh6DFztu^M!j+JRvdE4xr8?>Jh z!tbLH-^NOgnOR=Dy%Er{AMXbWb%TU-S|;53w2SR;nH~$#^n7&?X%qv@)x0M6rxf~WaljuzW4c{c1P%NK_3iLqN!j|d`f&G<3 zX^9x{FY^yV`cvamx6KIAM7dLtkrVlf*+~uhj8N;$V9(17&@BGPAJT-!rHc09xOc@9 z)=@1E_}0!W)#!it6u5@=WCO>}B^?uEB^B4F7@lK^QfnTY8_^N^XNPlzgM&=d`IXVp z@QCROwq?<0NsH+GYk#2oH`+<$p}Ya2Cb_Wy%ia{-v|cChQ{hPc79~vBpsn`!v*5Qtc%BhE0ZShkx3SmE$`rSZeZp3dlH-&;cYd|q?ez(_~~&Dc(0m;tX^ z5_qI&btc#uDDQx%ap=nt>A@o`1@tAasqXn%1uRaP6k^=p;coZawi8_^_M7i`Zfa@REgQ-dizU2m{rvdSwNK?bVXqaN?%rnl z10N5HA(kj9r}V|)v19XX!g)e-yX@oj{==proSLtM=20E3o%ig+~-MNdMysxB?s5{2H{n)!_Ha#wX4T}XNhAlgC;zI2*;6wZFq!+T1BDL zqU&O5FokJUjUh5d+)4d_vWcW6WqVzo(>``JD1aYCyP@ON)>tvR z#S_QIZbl`_$Gu1=UnqZ9$7mIbz7;sntG;!%?8_;b#A{6i<34}YW0muY26ruN=WfP4 z`IFG$VKsPu4Dmjkjm&XtbKHwXo~3(BA2>msi-AQ?EV)j$#Ax>V)+U>G1Fy}M2fJz; zG2|Q((@Fm=WmC?VnqN*?=xTSdc?(IcNI_^ksT1M$W-^7iQ-SQ)|CNPEq@c3L>o! z`Kbg)M_qEpDY2+XD|zbcN*t-0&aw@sf0VCyCeYuBhRy7VwVpmx}R4{Th- zjh%}2(AAFAr_{JcrX|=5#6$*DS*e3tGW0iJxol}mnz>l zOOxpW)cp|DbpycT4IHnAC$O}agu_iKZyre~nKiW!Z!3#{0ObXM<$f949Y9v8&n9vI z>Gjz^<(1n%mjvM`UXmN0`GkjZ19?nQyDiaIrtzpd(4F*S@my9hR-uO6)mMH&VctRXs%y^!!*~B4TK;B3N+xo^ODK(M$#j1~nLrulP^>=;e|15E z69*Wav#;HW7|lxY@3e&miB^TAqz5>rxHYtTsUmhv-Z5&cCjdDU$N{ek`8H_ys> zG!~`~4B#8|+kQjW8zF_6rZbS1-GWl8PEj z9ztk6^!8A&jQRXguXOMSRj2f~yfj+5nM>?r^{T_ww>!dUvtgPAS>a63rEh#=R?YAk z@pEl!x!m{YpD}mR9YXNXBI2;nVyD^pof4ng5rj*8q?p(cr&yFMMQ=ee&HcAtxedj9 z?4nw;?XKOF4JARu-ZaKE*sE;y46qLccq=}fKl_iwxn6wmR`@3*gxkcTT%=UIT!ar)z+5{IF4xrnd>H@PQoaT;-Fn)W_9v$Q<>>eY zEhp6S6$hW5aYuG!b)*#kiG%j6rwB}Iu1b~Z6D9cHTVQyZ|?S>#*}G+C$w4tM|=QGh-d-z;$dfjzcUyevE)?91hv`A(cxW_ z5g<^oKsuw?{+!|<2m8dv#4BzUb->043&)=NggH;MGuY2IM~4YdZjmPJ>77l{c}`_v z9W{h-{lsPgt@BlVA_p%(_}kgr$9vt|8Ga*#)aoCRhVwD*i(I3g%Anp8ncpWhDVBrK zjiByFUOtusyp34GDjM*c(z2%A&`0sGU(rEVXr++*j687A(8>rD^uB4d+Q$#(yvO861AU!?S>NcHIJv?t(Lm&w%89W5bncnOJO~U#JHfc3nSC%p0a|Wl_y|961Uo=iCVDm&h<4q++-+Bfbt0|?4;@R0;H|HPiWD3P&jrTWUDRhs=A+eSRBktXw}w43|t$=od<%fUUl^+PNA z>dh@HJrtDaeF#T=7wB0k^AZ3Ij|5)q4>)${`Sym!S#10zchJE zr^!7+(P<2NY^SoRa*jERka;O>1I$CjyB=zG6r${BrL-a~eO_2Efx0rnC*fW{fHtzuLIf4`FBd6-_g#= z@b4#uP{G8|+Ro6yRA1NPZ#`u8|Iojwv?-6EjQDOPQfsgbQBbT?rWApm>*%j0<}1e- z>i1QSSM7B6x1A{U`WbzjGuoNG@t+Oudzz!N2?dTusiMhuNYAs6>4!BalK_&c5&2>mQ`Tl$k^MycVWb2F2{Z&YaR`~sveE6wu?$5X<2^jew+$_@(rr(t%lAF!4 zO?qc;9ltXG_{W&GfAWb2wNb1^2(Ti!M#gpy>HK!f1Pi5x;fJI5@vWefNP5jSyM?-# z3pjteZ@mn3$|zeQN^@W9z!{yQzV%rQgvhraic8~+)(F8`0|(v#X}AQVL);flSjf0a z3Q;c(9w0T<4%5~m;~ma(FI#hM+1q=gDgS&%9XAnj)xgeE;Hw-UB}x4e_c~+$I_>pR zJyr$VR--(t8Yd=NW#&z0&`{WaqDO?-Q>a2^J~Z4HFisC(oK8{1-x`HEqAoFuof@kW z?vevn?8Z_I2XhBP3r2hHyTjG)4>2}x#0K(L^zmM__+=*jp2?ciqY>PCACy8IrMf3s zjTl8#ouC{k9a2PueT}j{YOU6rsGnuG zqRBG4{i(*ar`Ytjxd1Ax!TiY3yFlMGWTVe4ePpp82UL_g(|l;!wBe0OlE_y2A!5aK zaHEkXonsk89VT1QeSF5UCCNMA9NA2%l@>}!iy!wK5}@i!HOwM%UX}Xk=h9mDohI{< z1({}QlO8U)3~9|cHDJ}D^tBO6QLKMB{Yrg0a*`-`R-_bD?VNi~C$^?(@()3{)4eQ! z@%;A2u4y`7#gKS_=ot#5A8iFRd1Q&DHR(+FK+=4+kLsS_;f>WL_r5E+1`Da2CdA4| z9hB!UArWDC4M1=+qJjCc)iqy0k4D9t~Bo40mqtTf#jiCI}f$d7U zgNaj@&xz8honl+IU1nUOQt_tpN%2#A*QRG8`uU|T;u>*EZefJ-q(BcF*d*O&jWM00 z++qQFTYFstd*7ov2hocm5BmIaYRzz-{Y67bTLe?`LDAsF8T}=Wmi%WC7Qwd6GqM&8G2^6E&IF* z@V~?toDVAn5ZxO}m2}%+gq30ytNdI%jK9v2Zt)R68qxLBJ#Lq4ijD)-=#vL77GVZ& z=kaTIBW9}hAA+`bM+bIHY-PeH>Yg!LenzSwpfS1%z93M&?{=MSVZuN1Vuj!6`DscK zHx&_&pCC_9bD9{Z96anzzmghMNLgCFgq}D2BIoyK(tNcxR#z@GO7nNGPD=G`?LNbt zUJ;+6)U+jAsVkWFtgdnp+orFODtA0CO#6kC@nc2lXea@dD6A}B|4uFrp`5L^QE9#4 zQpEBs&%8eHE(zKoaok7QyW7!utCcPo1AI;98;ifg*|fAxN`xHbvge*!^Az7Z>5&*f z%_NN^8*MGT!fIEleUk|K%%11k4K@hWwQzU=?~*eEdk6WZ>u*R>)g4SD<#R|v{L>-% zFZoLUS3{EU-}Iphg>|VKFl3n%@p1u)pxRiwqW}#wt8(*o;F__EJ5aO*^7&#rJedc>jq_ExYuNLutL6UI9 z_b)@1(5TbFt7<#dZ1&Yf07Vc)AOeP$j*)6J(~Z(r%cAg-#yhk$jdZ98K-OH6qdfs0 zaxcSd7XDU?IA4IfX8VNgeA;X4FGO%fP}HO7+3QM}5c?i!--TQf-DbuNou=pe3+^C_ zsF`1^uz+SB(C3!3J`t7%7__LSLUl{br%~Dwk_^CTKY*KQLnK7bnY%?cIjX1i(XIHc zcY_q#kXJ$%+EUG=yq2o36T5=nzy*x|F_W2HZXD}L*slh&GevZ$rtzT-HstIYC+~9G zc?t?wqJ~_GZLx~l*Bl|0-Z%|4B!q^9!9u5-YnBJobVRy}g~P8DX3Htn2xHdPs|c7K zsnl?} z?+p%}bo`aE1SsumSl0@6q$weLDg=|Gimqr{30KB=16_WHUBWVw$uMVZ0t1_u%f z&Kib!S2h)7PX$9`qW$yDI%&ht^VgrNiz#D!A}-Ut@SLRKsQvIP$O>(CV+A4Z+`jG= z2LFyf?~Z5pG`+lbpq#`xFNF6#BAHVRUOr@;k^%}Lq+z;u`d@&B79-Pnyy+yo848>H z^{MzTvKqLQlA8ko+wcY74UD%T0>9rR=U#)gnk0(0Z~ZMbK%9*|KIHQ-aQxH5!1=Er z#((esl-9F1{KSj~GS;S64u5A{Gi24x|Ms|iT~b0~m9bInw4iY#Rj@4-7gR9%M-I^v zA5%kA-0x(Gk&96y`HGLCNqkfgoY$`q?*s!3aa;V$BsfL~X?-npx4V-~mtU}Vq(B8V zX!`m>m#va58v+{OtrBg-vzZl268#&+g4jc}tyw_(BfH0y;9(fhj4jzv$*f=Q7LO<6 z5XuC)o7F{?!N(gM%C#bMBgM2wCVWIX5(2{G z0Q;U0t*Y8Epv>x`E0B8}Xb+08#IpU+yo7b{d0Q0|^jMF6-_t5v+pr$EmDW21hL#b0 z?W7HV&Kga)`LAo>TN4lE{4(T0E68!nkzBK@92<<`OjI1-bwXlDuF#vXU>b+ueDBio z(A-4>5TdnZ5Fo*;RYyztdA?lz+1&$IX^l|yl7jn2)T}bd7SE>q6aktpydJ-!!P0T2 zT2~}K!D;;s#U*S@28!~JHr{KSKH}>jYGl`5#I{$X666{UJy^5wwI|SGiWK+#OPGLX zE+g(CybcKh<(WY)7DtLr)Db+jbl!J2jKo84-tF10;#^Rc3P(r2WVKrYyMYPS>syWM z1dSSZrS>?APBYcTzgLK(m{sjge46t~K0(BPn)Cm0)A*N~Wd9vN{MSuGM%PZ)((rRT z7j`tX|NNZ(&AO|sYNMct{{DVvH=7|9^lN49S1>C4kp+;+?dx|Dc$0A>_(UI6n%|PM z4n@{y4z#?&Sj2w8kkkygTl7c4_~g{6$VslLC8>7UMx_S>sX?wcuA_@3=m#84an-0| zKLbxbJUl17-*2*yef3P zvAz81pvvYRi#!m2#8WaY<&#zHdby|Chj@$mOSY!#&i?y8}k|;qVRe}?vmdrh98P|QS1ZvO@3tr z=X~%%B5;Dbh=gn}+bMA=l$C+ETGzi|It^mDHh5#_NU6_FY0gknZBX6PGQO+@0j;=> zpXcVRo)vpc=7>vASvC{?y=TOLrMyW(yq>atjn@+{#b61of=1EdwSTT@jF64RP$ym!^ z2Nu?H#+oR8(>)`!4pOK6rRrQwF(faoyEXACXi~Etk9W_1K95-;7afxP0j)*>H4Fbh z*>39+&{~OPQKD%uNFh7mo(OKx)Mw{H9j4ix)>6>aEDG0|l_{kcjfZmz3rnhQTtk$C zXvwAT&t&N9h&K01SH8Qe)XIX?+&tikV|H$xby|u!l+w24>rZ>5NK#5D84%SntSG%FA82l35E7dgiHYX8 z$88LxSKgl!Gi=lfbQsv|+B=~GMF`T)xP~?yuV0Bp&@AtVCrX_0Lnx9G^eFQZibl14ZeJ)Qz;)xN&t0i~ zsoI5Vb(hz!h$&_&4z1x9{~eQqy?TL78#i(=f&^v#{^)Afl1IJg!Ji#d& zbKWT%b|2?!tuO0G;MvHIU)M?mAe_G37wb!EP+c_~*Rz$DYGkyt`Y^cg_|!e&`oLVv zemT7I)tQ!V-e#t-lwLn60xgKxBsg14PC1)MMl&~a|AMoNXxe{GKhj%%xzrM5S)uVN z&{y=;19qqskBIk{=Ck{uvoF*(tZ)~p$n8NjGID1k%Vv@?rno5>!?|I} zlsvi;MPQ|krJ-J6K`?dI{SW)axz)wW+S=UWGMwq<@n@FOqhpojsf8tSd9y3a>oDG4 zR&N=vL#m9X^r|^=P(`E{cg*%M$f{;pk0nR%$7Rlmsitd0g~f<8L!IORvkTY2Oi}oG ze6HJIW79^mYwae?VX}YnKt;|e4PC>@!HE)ytYm0y{7J8k0s1P-sswXdO+`ytUR6m; zM;_HoXJb*GxXoropi!$h9W11k*;vgKpPQ0r?&!s~gAmt;m};fY*mIhWC(M2s-k zHnFkga)ra!i!GRKv3D~^-NGF}Zb~R~dd&tJ7wiDsa1XrK3r4$*{hAyXbV*Av=D`)B z7){^&3;5b{2;`N?YxB_dTWhNkX6mWl4IEvH_V9X=g=Y?XVMCgW+0(`PCH*j&KZ$B6h3h zGP}cv0@k{z@1##7W9~z3M|Uah=Rw)hu@epVwPax_ZL|_DmV|I*#2aYH?Km|= zQ7o~2DavR!g%Nzpq=9DTL_L4XK4R6#WJX*9=WV(cjLA_k%s54tv_HlM5eRudQG=l3 zPsx}p_^!&{?w2i#%4l@_EHu0>gGpZbe1aHxn^uW}T4&BTfG`T3-I!T*N|&cVGi5v!PT!%B zRWT_ggGiX0o+p8rv&4LGZ0M%SN7E2tcL6pK4$&c#g~9}Juj=MHm#kQze1sHoB(&c5 z+$%75b%b7oIOBjbO^KhCIiwhPGZ>n}9=6g6f^-W{mzSJJBfGy9OTM0Wz_i2WR->i& zGb-a(r&jJH9(#zed8eM`?+WnWicKRwez|HRbGl)=CdtllL@sMDwuaFP)6}(v(k><| z2dqZeIr9q^^9km+5-V(jWXn~}9Zu&LD&NE=xIIrVVrg(I@xpw_o|5-sxwUZ9Bp$Ix zxOE6*(B9G?#0ilPqa^IATsc;ZU0;7gcA9U+BEfQLcOsc;#9;ZVh~3jf?{{f{xH-msJ(>p}Jyf8O8U1{dKR4{9O02Ip zEI&i~)4(4y{$=0vIDx;GA3BU^^2WO6yWSY&nri@ucK!jytGB{Nw7#8?RI!%sVtma( zmVVM)OgFkMSXzitT{+fhh0Kr+HR<7%k^v1G~g4COk1xYDxQrCrp1|2~` z-OCATT!VodlQOSZLyf;lWqfWFv#B&dPA{vLBqDzz2-E#6Zp4d_UZlb!bx$)$%|6-J zSx0VifU`X?Ljc=oS5hE^@nDbX4F86XVMrHlpN@wnCyO*o)$Ipe?zcaVux%j_DK&H( zmC$v`O(Zozr2XL^Sm3#O9zi^Kq6&VOw&33d?2o>CpBr(g1DBTv9PajY2u+$vQkOZV z$6GFbcn?=WEG%>gWoDMKFY@H!>EX^FB|gWBRay25e2CXp$7aOA9y`-y!1^`!--Pn}>YvOOtI6`DNmhcF&)2^th9_2qL%>Eg3k z;@Hd_?q3XL-0j4e3D%q2>%tY{-b;(`LFCb z|1KZ>GramAyT0Pz9-F;OwT;af`r46wMUoXDtCzFFS1ZR?l#{0k`6090SC6$qbWXjz zeq$cql}*F#5&|>Gg76VH$gpbGKEzm`lESc=!e;+Tg^zpvxw+u-A+i{R?MnwoxFrVU zOXSXfK*_|g%`{cmpU5i)?3leU@4g>R}Y+BwbaFfp{7FstJc#_{Y| zYZ)u6#AUpErC#YQEis{Q&rn1=3ygb}mfc%7a>2Pb;I1MUuGkF?yPh(NuU?TvW$lZ~ z7+GwCL5wN`xg|i`XAaO65>`90(p?fffM%*z_zT(7giHnP%BvsE^O%tOic5ryc$8l(lFLA_K*}e$sx}1 zl)tYo6)w38*ibsoAz%4(v5xQnDsWT)CNV?%i+#sHC*F-th`6u>24$Ep_D6IfFXa?0 z$~Em`KbV!=x79OO-@zJw1Q#)qt8l3tfwkXc)KVJxbpEJ3sf8e%u*_Q+Dw@cB|VTK@+ zp{BhE>4s-$_1~HUz81r1KfOTwbs)>76pfKTmq)-qecvYZzd4Zqrc(XSyJLa!v%UPM z>8rAlWWEWH~_CeP^numPJzujOryo{fg-<--HR(E{jUS+F5~$HZid-?L#2CSWby28SB* zEAG3-3xcoqMBj}zP|5cPq1>yuGl`14y2VbHjU86wZy{!P zB~tDzUWC=x3X(zv2aKo1 z3?4ZWk{3D3nLRP*P2hK{2Xwv5y%!E$I8@?Rdu&B}sYu6TGNc{V+0jD`#o|(Rd7?xj zSzYuGb17T6$z(N7DcNYyq#kP;jx*EzKnr<`&&-gp6()|7*ne=|AZ#@eg6|0Qv&1qq zVu&Z;=pv??naT8?0YNc+ZSW z18&ZD#01TlR7uiNoq9%3B5S%9b7m@FDj8GGqTtEBr>8B2*{V_ygoiNw(eNU{LDC5p zM2LPV=iGLRcq)vxK*0YYcbaRa*Jm9uW86!SJg>J9ax}1&rOIXgW@Ov8jY$W%$f23p z+{EGPwqP$e7MDoqZdM$XK6KBoT@8+z!O9xTL!@@tYf7SR^2$fK~ zti>Teiso7rngp~CxRUe;(-fH3OiW2e#pW@{$13@=Dp3hqk_g4Dx@NAb&&HLOQS{D% z*B;W8U)jXJ6i$VAr!Nd7rtzcENldBFJ-Vxq7?jM6NFowlgRU&jSYqbb;pA*w?<{Z}vQHI^vG*Izr& z{AhbojN=d%>XdpG^Kh;@)P#Ww%1RlloK_Omxuo5pWunj#XR9wBmq#Wv;^oG8mY12S zDnxArIL-~6%*@!B%?$4IL^{V*m1kgRXcdKGRxYu|GK6SY&EkGi0{FK}`)eC6EQdbz zTav~VoaXkbgloS!Z{5XIS`6ci^gA9*A@y z;2;Qw5x|@7EWplE7z;H=;&0NA1cx@`~f>1s&wrSf8 zGKStby*BR*Giipd#M`Qu?GVTt{lK(hBmZuc>AWRv;{@Ul&_BopG%j_ z1yV<16>mQg|85uDwblof%0VkS?q}niz;1}4GUK4e9U*4$3v-E|si~EB35S=N`@zYZ zgmXCXDk?`^sTOHk4eU!}M)&NRk-J!$lx0Z0xq?HNbbT(y>dnRog9X&i$%r4Fo$e<9-cfDylT zZ+#4M%?T*W38+yF+&L^7`GGVlXR-v;I$74bE*L*17$TaCsHMRlVG<{`<@5WPI&hI+ zY*TrtcVl#L&(pPLtOJZyI5^`XTiXSGw+C}xjJ}H>S+TKfCZ7G&2n3~ZvAYgZq9J#! z*kZ93nwwv}K`Dx=wzf^nII?ZR;rpwTV1eI3qEnptPsC{{4}>AKfHlRGNYzOFSbV-% z?=?42<$IKgph)=u1RQT&uwF!P4uAi3vdNIrv@e!kN2p!=#>}Fb#j==1teesRamgDJ zpjHIV6NaOk8#6mSs*NYy-zCz$4(NVoD(B?^jKw~QejZ5U2TgK}k7*tsA1W~QuX@Hb z!|?b`lRnU+8bCYo1@i-l8$MR=L&V$RTg?@f- zj>k#0a(yeU!*-h-U0!z*say>>Z)UO28q}~@R$T%QD-G93sJj|Lr1!;q0CuIH77wF` zy5?uw04a2E2kii^#kB@fC$m!;JqUb1J&1U;Qpj%HSLL3J5NBnqFWDyTt$%QVN^ax@NE zqS!7jK4AMCUBL?bhQO-cQx~Jq(J5Kvw36IM_+1HCyFZ+_Y#qQ zE%elBb28XTbON8XM1u&<+DL}Eje^!&a)-^Izqb&qH-{K`-@ab1vLUWj zGs0lis^|t+5Oh}ExExCK9OF2ycU`jWcZ)_flUUFR3ns+15Ke9(LZ=rN`)aYUC z>)*uAbiw9Hj5tc}&W}7*F;KxMCkg2+&cT&s-rui@EZYlw6iC5vXD@s2cDLQH8*v-qUdce0znnVK5Y`N`G} znLzS4hufCGtQXC3i9$}~Cp%0;7X{O*cB>SAPh=B3%J#oP5#TO4Q)S=B`Dz0NN2wD@ z*^w4iwwK36GGYayqCSP2FF71iLXw zJ2`Fwdf_Nr^Ddx+&Pja1F>x10otJ6OMjNh9PF`=%?+D$LrG2RV`S;r_HzcR))wT>{ z^2}Dt%~U#E)4o#3AP}?jj$iYzttfnNp|FaLR+ieQO zgC(W@=^J{|8Llt5FG~=vR=Jj-rQV{obR58Y=43FFY47Y1dz8J;on(q>jy5-2T$U-T zAZz$gD!}3*wg?4|CJ*v846GZG~Jt~)Tj6` z_IJNDRK7V){5A=rFW0Uh%CXkCjYt=;jW1*?yLDW0W;Q9`76Sdf35~c+G{2*NQ#(gK zx6SO>q&gT}1KDM16K*LPS%uZH0+8Q@bGo!H`kh9Y&90<;Sj0&|XdsVu*>wsgq+0_A zwizaEk-{Cqf>S{&lA&C~Xag~s;V0~-3LtyfWPb-T-H;Mns+&zi=RNr?d}9akho!H$ zK58H6iWj z!Xb0She^u}!QD8^{7(YwdQRmy4?@0}RV?A0sjB5ze5wtYqv^DrcByN3Dyvx1u2sL#W_FSN!|sy6Nh?U)bQVhTGMs0)RB z2d1HjzJftC8d}6{<@c-&FV^C#E{fFJ^0~&Nlgf~SuKe%=oLtAQ?|8?XKWx zP@c$3Oiwuu(eNKQzl!1Xs68V=JF`?}jh-l1N|%~}DD~>%VYG48_4%5thaF}fblWx@=PfBg?z~~mP>+SMHc-8rSrVJo zI;Gflb1Pz^D+_5u`M?an^KE{ACu%gN!}0!bB*~?^IwxkF3?@hh_1xJKKD-1;AsCgC zJ&B&wP@EC<7Ep7ueknu9)s;ucdM)=+cm?Rf+J&pvGdKzsE9?;&IW7~D@o_JPB)MC| z9HnH@eb6$Y@pLwGr1G^5R|@Gkzh9JT4R#%9aq?zo&n8)wboTLu@ZZzbTc%zlt@0#S zZ5Ju?o7HtR?gY^)+cWZ#!_jDfHG9#argB(=?t!cG4hb`%U58V>L;;WRuSkU|dUtk- zd!=EY!L|G4Ad*-}@e{_%e%V9^_T#E4_Al#WUzcskSPZW`IL+`3Cl9S%PCS?X&8F{rB@26)yzx06Tr`)EWspZ!wg)y3e`kdBoMAgNew(PgXK z5bNoL_9;49g>MCZ&T>x2Ro@EWS}S96&W7NPjgu2=8@%d2cu?y?W4(6!)^FTE!EB!DeEkDjog?@##H;9Ihs_)B+mYpf>wXSc%MoRdMUQHJyY zHKTGJ%wO?Jd_m&=6iln z>1C+pWvwD*(+2@t@y>yifra8t!?tsl_BeLbWeaOFoT#X{Zpz3ph1Aj)C9E@?270HBz}`+n$}XLLGCSdLsW3 zCrx?c*2plP{B?VimjQg4kDQpj0yqjt^>M6C@2|XaigC0uLU%$F-SI@#UQSDZ1`ox84jkF1PAwrExQ7zxTHo@p3pHE=hx(3 z9eM|IxBnU9EUgmJbbOhG7U_I+sD1RPjRx$(19t7QzkWw}B8lAE6xrq(mg~aZS#yX- zX4e1NsLMfML-gUSL!zB|-;AvsXP*a;>}0D*q_geu4Y_(%^cPu$BL_IxRY_|QhsNHs zpiFqu>EYbcaI@#?Tdi}ko_64NC2czru&S5z)WMMfM5u*92|WQxNHI`0FA0OUqKH~$ zal|EaPhycG0yv?wUR&EIqfWDUpFdr!d;%q!Cu%*1aR+1+HDu>SGi^mKv&d7mo=KZ= z%d@Pv5vDZ_xFhdi(^WWTaue?@HeKX*Bh6SUY9p%>BLOsB6o}YrtqWHI)1_&4OLs;S zPm;kt#XLr&u^G|4$UK_$i>v$dR`rpNy~QI(w+_wgr#RBZ(|e{yv4@HbV^s)q4uA7` z%h0bf8!U?HtRb~YGF-OkOjSblYI7%&4<=Mf7{42)B9JRc5CJ8@4h}!~rM{@$D|Mt0 zceqi|ESEN=v+iF}iQ~CFod%a7L%D@*q)S9`2Ni2oNfmp6M}VBGEmD}UM>tjqX+%aD zPjRA8W0GJ!@FjGJ{^Bjo7Nz2Z50F+Oz;!G}#G0S+`Jw8MY${MzE~t_U8{>EsbH5~( zeije4M1dDBg8DNbi$&}wGLc`~9=#Wo@O8CCFZl5wLoMiL^w{mGy5nfjz=ndI7jTX9#E2IRf-j+z~wfbD3HOooQAxPN@Zs8z1u2p_yp1fHEaTA3(-!d(xR z%GOZY3ErL{l558RRCh0wN-D03BcdVz?FqeRO(@`buS~!SV;U{GN+&!$iOm&#S4zGj zF;2i5V>CHSxH?ONtctmpqz^S;Np#<w^iPJH^lag3=)w(dN22NyD2No2K;fp;I zoqMK`g;_=B*jl_pW>?$Q-p$oRMTGETQ_uQvi;TX%r0wYz-6NS7S+kYK{-@dyaYYUBc^s-2MHNTC>1 z&gRTUkcKkDo~5-y^}m4VaF*Cc7o z0z5b;5Mds|;BK?vz%dk~WD?0aACg+ef^LdF;QwDp`w4 zGBzpR+M9A^oWnmt9_>kfD_@kSq7$>YPxpY_kOvy*M@w6Gg0GQml|otYD#pLISbJD(qK zg228A0W!N-bohuy60H{OlV_1e5|$&&PRbGCjvNJ{jdXb0?KsEgA9l|#wkx$`VY!zY zfZZaR81Nrw+}d~98i_Ue`hV#y7jHh1M zb*Ik){`q?mI0ooa@l)EhmM_%9+FN4(|^ci{8=wBX#&(=yE z3lq<+e#zQ6WICp*W-7#WOua^u2%i)dZo@w3268kkj^~IsDBj*Uw0_cD{60N zaI5c2P2^XhP3K&$K#=~)o*MAH^aK2%nQ=N_WW4WSFSVN(vaht%lqT3UmfoRyHWqTQ zr9n5horOF=P3@SW3qF1AVzIz1D~sNlgwM?1WcQM*?>n#Unf{yUA{S3eQ6_a7iqE4+ z3y$n;vQ?XBM5?r$7#hFS7+Z*1gT2wUVpAT4mxs_xYE*#2shya?^?@oGSlFV*jv-f@ zNtVwn{(3))AZ~E4*O98E9$L+!+-dCK?QYGKx0G?Ls<2fDgR4c;jMfzrx!OoVPFJQ! z7O+7b$m5YLrFg^+^IXX+?Oz~~Fqr+jbwHw%LjO^@Y zQM^)oJlC_zAn~20iH&n~o*2{BzZdXSP2!BzH#S!(+O2coF=Rn=?uxf!h?v(3@es$q z1;Jv)IU58FN?i=@u)}4XcakZ4mjTfeND#CD8Dkl>U9`szT6Z7`;UAla^-S$gadR5P z8XCk|+-u2XwtMm%7H)|1jP7s0%jvby>v)?M)OL$;KR9)3;~l&MZT94JvQA&jCSdg1 zJRRb5i3KB~w*R@^%j>n$OL(*G0NCD>!Bd^1citB4y^dN}pYItN))P%zxCsgp+!uu> z#BPtJ1)+Q_vg5heaKvnPcXeZqxKly1lGi81J}dKf)$}^5iV1>NxYs|b1F2X%KDH zRZUAI_k38zHV?#PtJgwl=9H2a$j4N(0Bv!qg`QX^3;4u-n!*XBfFrStpBgA+{f!An z>Cm$Y16aK$-18WA!_s_k)w?o6J5mRe-kp;=Zsz^g|lF+D{ zF2l0s8LI7A9!K4rHh9D8+g57m{z`K4NDislWg=lm`Cw-fSvygg*&hC1cmN~L(}nVT zoM#k*jbg>3={ZSVFg!(<^lVufgctoVh8ybUDl3>hLneU=)Zs-D#YFJHF`Tsuc~W3; z!6`hYY)kr+2cSO~K{XLtg_Vr#yXPx==kA-VToe2#ZBpX0<`gXSZLN7)eFZgzJ(q%!T? zkJQ&xp({?sPAfD?FCt_WHM`Tk#55P3cVVkI*9>H&Rqd39v&&A7#L|-8jE0eQdsce| z>YI6neU?&E(K8NI6(O~tT@kuB0@s6(?Gc==i~_|j0wz%UrM7x~s?V&y-!Xk-(Mu-1 zug`|?+l5x5S&ev^W0BD*CfvapS)n9TgVR$hMJvhG@hMi&57(l<-`dAEpp*Z~I>afN zi>4c47Vb(|^ML_($*#Jq>o-0@yLP^~X$2dlsW#y@^wW zzs4|s5U4%}I>z=DU7{#O({E_C1^jkCiuE;M(iVuE{rtPi%B##nLwxZ}L{a`-xA-5; zp_Lr%yd50vt&Q#e5A{~p6IC7UkAlNO>4M67aI^T43cGz!q)}Ka(JX9fv$dTpGun6Q zZ&Ial7UPq}m|gjiU%&G9w4U2T+VW!92^C)#`n(VRWj~5^3^`f5x9|KX+1w`^J^?;? z-K+s0_ZMF_Li=fi@>mQJkfb8nDNN@*jrH}rWn7b?jtY>`bVr@*AXP?>|* zioOt!Rq4R$mSkxQ#IW$v3_4P;EQDxwrV6%k_#@8%@eunrWjj7Iya~k+6UJ$tQfZ3O zx<-ppdV%$3l#(QLtCe1Z-Gzz{^AGe(%;ddGGDroBA8}gNU3vR9B-Z!0eHlYzbV>#avWsahGyK+0a{#Jm4pryKGvPtXxWhy25kL-E8;yAfWH_LA;(0iS=V~?(84((uwIw2B5-v#bMh8iI?2HglR0o4_?M~t}g zQX%+Ah~`zhcrcAX1~5CKnza|9I2AECS83O^J1(0%6i$=MMw*A}pR%)`ROAI3^^W$h zE7Z@-%x0(BQSqO1J@M5oG{(Fib&iFK;G8&O+-1sfRyNbguQ>dEPEiEl;Y3q~Y_1Eg zq7!&pvKRdAI<4CwZw&N5ZVFu|Meop)AeG`n%0+nnB7im;M{ZCafv2U)ji;rkT;{Gn zytvDbiE=!*rv^~%Z?Xf3mb^}OJ5`kqTn!@dthgZ;j#nq7UV`u@or9g{nlyTwEr|HV zv?myyFoSSh@;NNqFsrM{WkXYAyGA!W*dTSNg`lUFw7{+>QQF5r^vHQeB`N`@gT&t? zoi6F7#!t7dmfxr>xtf0mp_LkTj%*#5kPB8kF1=kB1@HNQ4N6&fMUHz|KT$Y#rwA`8 zbyM=LGr3Jo`0G9U5G>8*)i<~!uwMxn@8y+eNZPw0xc{6nMdjyQ@nZFoQA+H?Xdn%F z-NI&@EMnIAl{v5sms|T}eiMr{V^L2Za^;!LhRo2KNZQLq=A^a@;qWx=UEcqfeISwOscJc|1yl2P)Pd2c9bk8g(cn@{pu`0U8#Jnl~~w zN6_>@pVAfMU`0;Xz%w3U51g__|DoGv&zt2Zz(Ee`?r#e_knFCLr?2c~bHslwF#lZ* z$Mc`Sxc`Hs_#bdi{l7HzX=w)B3c_mJzT#D_;@sZIhB8dW5TeyWp+<1G1FiZSq$`~r zZIZ!)1B0JIhD86=)wcu{2aEi2>1<+ko#Er;ZF;(2X(I%pNMto8F)xJld~j;ReENPZ z4xx>D(C)Y!1Pw|JiV9%|iij<-T-Bd0!cBhd;KYg6XL6dFa^M5EoOJT#yz7k=8A!~0 z;uR0Dj4WZrg}d!C#DMbyA3>ckuAw^QVeBZzrg}!saC_*eh^?v=#cBdK)UY!+DXFZN z^{+Yh3DQ5P|Z&&swV#{WO^H_o6O@k}766Gk>gecO%TU~W@O0_zdy=>nZ zT_)JjQSlA#c@9z+y+Gr9yn;I~)XXb$Iveg3hM;`cbhHHOGT5M+9fO`|-vQ;O@`0M2 zJ$<(K}opU>EIN_C$37+29yJIF7QE$B?kc!OmS^t;>}l0K4L})epbP#$;^_!wNy5 zoiStzsz}E-#2Q}mdDKkLcV0ej%g|Ek>y>Azupk2Wp`5F)@R+)fQIcu=!X{N=su1f7 zd7eOg#%T^gsuH0Vp0|L%x)RSORXG+_d8iJ#ciQQ`aYkd2!Bv~C&*S`~c?W78XkF5< z&F*oho4RV;@O#p)*@o=WWHJGXPZ-qK=#aCd(uO>Z1vXYdXVaUJq4a4#IF39Z2-{_Q z5J*~M02U{N9r<(8bg?ZB=Q7#)94_T zB0DXdN$xRGgQ^Cb{7gpdj0U*?!OkU@B<@k#KjPMbaBK_XN+PzOczjGE)=Q7m5!Nv_ zS2xiO_r!{Ts3M)kY%ZsO@Z7ENg!3<|uay5AVe8kB!};G*eHH$b)A27&*Z=HB^DpFk zRWwPoKY(sHI?{A>cCBswsq0`kDU%d(+E8=Q4p=ZG zwtC)+nl@FlhUNI~I6>Owo1PhU30;!k>h*%9V!#Q@4)@31FUy}mSbbLrc)dy>`t>}s zF?(QV3?3$Ed1puW3VQvR-+tKb$^^p=qnrxWq8>cY3vKtRgQCJYt0xNE4EB2PAFnnrl{b(7V`2L7eWs9%Q;#c>?6kC-s%HqY#CuCWKT2QGPaM|ha^Fr?p_~nHn-8_O8 zj#vDC<9Pz&3MtDPX){QIAalZ^E8rZG=g?)YH6X@W#VYJ^XuKij^@LyZ*@3xdlw%vZ zlbmj>3U4-##H*rWxkRsM%;6^z+)0khL)gQGA7of?f<#p%9^r;_%owyo0u}c^GUZnrxbID&=AGJy{wM8wj^4Dt<{HvViohtDE5E3IAl&g5o!B4Q<(jw(Tw%kq`$BihY!kg&>DAp>>Kyvm)4Zt@?*W6ggp=6(@M|)4$ zd-)KdjnnTe%dvfgmgJ`R_jDrrwKPE_g=c&LC6%lo_tbZ8KnqET5Kq;y$Wm35xDJ$} z_Oz@dL;|)z={oDx;#m}ls9oO&5f+5YJaS!SYSIl%m)XL!(KP&mBt^4>-LTqsxS5SR zR_{Z1rJI2omaGf;3SV8E`>_7agGpzR;Yz4Gw5o1HSVdJ-$(Z(wpz4hHi`5kD>r8fI z@LJ1OA}C%LthZoY2WgjnM)zpPLMe%pG;&|T%$!n~w?%^-yyQ<)JU;6!Nsdv{j~d@|6l!Q^bZN{=szV z8cWFaWx<-&V8@B)`WUA_vQ%B55ld)*eS6o&z&8jqZXMGLAkzU38x&8?jgB1=SFo!C9A1nZ%J zceDiZMW;zQ3i$y9${)$A*vAkniW>lY0!3_QN!GXbq!kj*)u{uX@l8vXDa`_JVYCevq&8)D;DX_?N-xV!tjn`VaWwc*tQssxJkdH{*kcpa{ zwSvj$UK*>BP58j9NDo?^hDo_91J-~J@Mab?CMGbY;!}7>On4e}2PdW69sEtl#(GR(WsMZ|qT2?r|%|ET>S6Y0>bTB>xjgch8k0i^B+cUow%3SaW zM=w-t8}|5wqGcnR+xv1-#BVh3PW-{2s|El`%Ne=!2;1Mw;qJa?HkzPmBB%WJrs~mu zE+C2}2A^83G{S9Vy`(v|N2XGg1v!wE zOh@w#l!f!FnxF+IW`lkcG~?2X{RJ>yIFACE{$KFuIieJLE%@iOY2*+3)7=~Ltjh76>SUCGvE%r!-}U} zBcTBmc4rn@DI>=Tzi$Ko8{-LmfgArSA-9+_7Rn&`S4&Zvg{`Gp`u!rIY_nZS(d&0n zZ5`mMKR;!D)AwBoxUV}0DIituDfp_rlU(Dp?5hCGR>zQ_(Py7AO>Xu1UAXZJz%rK$ zC0hKc&y@*Si*OiW_z!-OJP5+>ZG&FwX8uu^@mGVZ__D{s*A{x(_*r-!HuZpL3j1Mw zYZ77w$ySL%Kj){SS!@YJFn7>wC4J8$TA<3n+d<3mXhbGGA78g0(?(emvudZ4QAW{8|(N+;Eko$BC| zHbc7CVD;VlL}zTA3%KFW2xI{MVVpj5O{e?iwu<)0&t3dWR?b((s}aj|R=OC?dVwea zOH%?acVxX6K0WToWL33VC!m=Hg1!c_DH*F@7WeuoD#z#k>940N`}fz63rTVTP#}H1 z`YFtMqEfMF;XYK3iLEvFkR@z15FtI2R#Us;f}PAyGjuehf~NNOaFseB{rx|QVn*QA zCJT8)F4(QBZ4)h&aWnf!)&H<9$J7@iqcP#OmNYnHxF_a2LL`*lYB7BuJ`k~!F?GdJ z+;piR&fWqJGebdvOX(~AOhH9sjlpZ8c0n-b7MIQ_Ugn8A;F9IV-0Y1NEoE)tlA24Y zPb_zf)Ivrw&Olt2@9@hACf}oU>(HYbNC<6Bb<^DEiJu*nT(2$6^7sf9l>7D#YKR2n zVZJt0pkH}26sq}acF`X7Em1@uvcTKG+oh|rERgLzxTP)q#)c9f+oO(PK=ol$NJ1_7 zl`<;-_n{ssKkZqLH}H7CU-&E$Dux{Q%m3;2f16(XcOLA26nF98$Q1uwiuq4uR`L&7 zbm^A)S%(!c^EQ%rib&!Sg+VlWv5=IKG*ci7Vd>Q@gY}mMTAHEhJGkF%pDdelq4J{D zU!Ql{zqHXL28HIFtggqKGi{a@c>&!%ghGPDB$4^D5%CWAIQu-`oa9uxU0B#3&WdO2 zjD-gB!->Or1RcHc{cysu3!65N#P?u5E6Mm2+u??r?O{E;daW;*v$LExv&S^ODHtbX zRq1$IEir!N5wfMz@3dWJa}UYpS~~kAJ@#L%Ua|-iOVVxJCBvaM)O20|ER}|Hs*P5e zP1p8CDl#yx$#WTy%B+XSZu3`I*pldUOVyWmN?93_twleD&*LS)45EX{)A3yR- z?9QNgV^7R+r`u3mv{_-FLejai{l4rx zb*`L};!>{fc67#j?2$jpaS7=d)Q~{eSE;Jk&)W>O92n8C{Qn)t4R#x_PO?JfW z!cV-+nKc-WHvqCATseHMMxxj&_uw_vrrj|S6hg37&DC_-ZVV|Nyo`tPeaI;J6*@LW z6=u2tN4CUlLz>@a1&SU$0`54VFet>0_S}us4m3u>+;i3*r*tloVxI$*Jrt=sa2x+8 z^s*mr0d6y_G3AtdG3cf!?39Gi#cJ5rcTc$AqC=n?;9+b*N6!!>{J2U3=7oz&+Ve8p z{;+!lIG*`rx^>e27r$u?$$MnpjZ4I#$>_&DmGPs_i>2(9X-U|T!X^Y8J4Jo~Au1)f zk6#eC9w0A0Wtb^S-JxB1g%^3nV;Riu?2~`Hg@NuGrrO@c+ctsu#T56HF#<`qM_Rj& zI{zF?_vNQSNvp0-o3 zAcZJOF(gV#2UZJ*AnAMKlbd5XyoIeC(pePtR=K5f_(FeiTrrFWNr340~v^I6=9hRC{a*d0BlG z1AP5#*tb=jB=V~@*_To*tdHZf)23`nh3Z*zmM0&J$Bi|BKysUnOTok-$5Kj5!Mn8i z6IH-{vmTlq>@lELJn&Tzs~WOPC{3>*YGkq3= z$heR6hw}lOWq=O6lS~3zv6DvL4meh1Ro3&}NDN#y6>8F)xG#y<;ofS!gZ4Kbn#l%K6GvR%_eO zO=R6be{5Svk^O0^WeGABbCiYLted)S{nE|oZ^{gQ{1n%HY8D=sDlAlK#HO3PClTPr z?vL9Cu8gACSV~Q=y9kh1%j+SYRTBuwo?`L{Bbmnorlb`g@GDUg45U%5a>H!#^*~Ja z9NYfHSEKo9iC9D5Tr_5!@&F1}8@2bB@?@IDKjb~_YXXy05(arAirI7C8!(`?0p%@L zT8fBQ$C^R%u)U%-OWHMDvy-ujYV`I2S>h$S*9O*>mXe`NnCA3L&2|Uqey37DOPI@s zl&@uNCr_tB4#wFwk&hHXM^h7xX?GRkWKjW2+Be~RmK9gw(sjca$4ek2XDdw!Hp>~M z%;7!j@$vDaz!v+)?3t#37syz>Z&K_D9FzGarXLd1cxEl>M;vS;(Df464MaH3X;jms z>Yc7*W?7k|CC$z1K=OSX!r22)TD_O_S!OgN-yjegz@(ObQ9b)3o!o+2taqh-w=}Ty zNHBgVTQqYSW)Xzjmwawm6b=;B=W`LcCg^mRg}lq33h};n-Lsqi=ITkfOcrd^s%sHc`*2 zZId~1$L-Z6y9Jy%<5rPEp*{^B+x0R^8zWTg@#tr9-5KL2Y!MW{VdTLT@&SUlwXC8$ z;K6Qtb^N_4NkU}1?Gkl3*-wT+pvcA@i~G$+M>?o>&CX<=t&V7OJkg`B6PK+a8xa+e zkl3NeO{+{Qbwb7b3EsnSkP|Wnbw~Mv>lMsE*PtpZIPwp|QTkr=PsFx2&KtQtANFt1 z0=Yyd$USi6*RiF_hX)BeADS11s!*4;Rb{@nEni_5E z6Ap7et;PxU`U4{vH;@b;k~j~PbbWc&uZH!&0phfO!U^8--)<23;sZ>eKKsAP@WxxG ztXchRVq+`FoNg|}pkEb>_*S1$G^J+>`;(DkBynBmyAA0tWfy%b$~w@ERT->xXi!5_ zs5k$b!7X=8<#o)bdfJN^pEdgPtY%8-1;5r^%2sJ%OOBjB*K6?{B3-!LN=ag9ocAWZln0k!fE+n!2lK!OKpKV0t zcn736cow%}6tBambUrWLcEt$hn#P|LCO@Yq1?Wk*NZU47-in5Ltn0Ur;X-?pM#0dr zLu9?X&(Ua(3Wimdnj{fK&_Sn$Mx)A)gQc;(70uD+5_2=3r_rwwhb8CywB}>tiJM8l zk@v?vghEE}j&dATbo&v3)y^T1gP(#MMK2b6)`~%12%Nf)Oow@)%*bIBvKl#Mg1Rn- zx-Jg;7_AW-P0wL9!sW=_^1!t6QC@c6T^tQv7|fVN)38vKkkX%@UPS0aCHVx)L^xtl zO5jRh>IL^^tq9E$=^CEJ5x)yW&1i0OuOm@$l-~`IC765({TAMryjSJi_KibRvMzh% zq;LsE2XZ(0WVgn_Z_M`KBOT>ZxsFH<@p#c@R0ajKVvr?)Ki9ammW*68u(__qN z1+BVvO!ulkx@(ESo6)IJc~qaVTTUZS;?|rlM$wqN%|YEgGRsT6iSg2vlY`bcudLw* zRrPGo_me~GXL9TwB!-SYsz&T2{JYg)=qz(rl%m$+0S*X8w603gKn|;$NMo=eDAaeP z${{L^XtL!~O3cw3*M)D&n!YRHT>h`*Gw66Ex#edc&6cDlOZZei-DbJ?E4&ySre)NlD0;Q5vsM zs%r7jYWf5q8yD2ozOaZc20zkMnXVBqe~-NU2w)LZJFG7cP?^^MmDT<@ZLT&VnrpqN zwkzDJKjZ#= z)U?fwR9(aX8LR?Ajygh#&k)FK0OZ*PbnOMadCS+%x_6+@n0H8eNZoi>9i7b=(p&lc zX^}gn;h@}1{cv$Zi4XNlwN2Kp&o^`!``TJpJc+`UC+zPd3rL{H_;Cq82~ z@W7uXSdygLRm?3 z2}(Ikv(>r`X$(|}Mt%wV>XZZ0Ifr!F*sd9b1%-VdINBzXrw}qaAA{GS7Xno=5H*Hx*9t< zN5%~3Wq{Bjv)8|njH!?O$k?5bW{8L4qAA391Miwt+NR8M5othgVy)0hGhvY;*4Lcm zkS{G60tzpTFUW1}Q*ulQ)WjZ)jjoWu_VB>Apray8Dsm>rVn=}%Z3~88i+4mA@2JLa z_@V=)Ef%%foc1YjTWeQVuS^kN68Titu2)ubBQUi~tYe3U@?kgr;G`SewcSf-o|iW& z=2sJ(+_h$vKo2+9udIC_Lq#6KOCiO%Qgg#r*2YbfPpxCkBH*n>xmzCc!&kM}T{3MV zXeFO=E(zg4Pv(0Nmltn^w$jb-QHpJZUW!LtZM1&E{-OY}snUTLp`VS1f)3YbgL;-N zkl(YZ7H@zS1Q&=0Ur$>Y#!`FaSu0_n!jT5mhTOH|$*osn*s-$7JCApeBB}yNbX(oI zsI#KcFZW}D9!NkHJhmi4`F1=!tNo&JVm8LD979ieYGZj`$biyyMwHlRhTJ6J2vW?r z5H0Ujb9j+lL{!}>InC2RC~*|HTBSlN;I_dM6-;jshtUVr?3RoH63thmOxXp$uK)as z)@r4eyz;iL(?v_f90ZI2&Np8C4wcdl{J2GJsM&IA%-X$#;?5d#*r5N|U9U3&e{R>8 zmXlYS144Lvc|*92$fl@{QYp>N5u!P7xyWqhMNv5NrA3euSnQ||o1IeRK}NjbN5JsX zZ+N!9JAqJwf6>M0yXg1u@rtHZwbIDCVpLJK2dKkyeI{t3e|v?#1ptf{i5phv@$m32 z{h$eVMZ@*O(mgy?mL#~>C7-qWDfN7#Sy4o|24GQ1?SWK zqTMW)mve^56`2CjJ8=`06I;wVE7kCt?rk5O99B}(FP>2le}U*mW!9_(Gx(Y@i_;w zc^yW@6&(j2V>5Li!KpICDJN;VRB!abKeg8Oy#|*QzS|AQ$BIx=x1Z{aq2s6`ITV!d z@oZv?ukZ~m#0xH+jaYtEh{YTr4xn011zwK_rnxAIxYkSqdpZ#4ozdx0=N9LeOB+-6 zwR7Rg&Q?bL>74gM9WpCB_AH3-pCWkDV6=}yOPKl98HEyl4|T&E^%Vq?6$Ve+e z=>L<_udVvCI9)&Y#S-Ue&#=DB83uhy;Cjyx>E(!Jyi^&x^rI3@gAI0}96@of2gVVG z)>}vA#x+A7S4E3I4p6_t8uq5@)%#0!Pnco3xSk`-T@&Bt#)wmx#2Xoep#W@WR`R4R zrRi5B&Wc+*tb%g&N+#Ws*2^SRndwfwn>T$7#^u~ z3Zy;$Bd3DU>dRrYtJ=RJNnM(tz$zK`Gas2qifaImQp#`~)YmG9tVy?2Zdh z7YZ4dG>@nTf&<*GRy@Kig;iUeThUp&#Ddq2&fss#DnUz|5Wi+%~P&9Mu({LwK z6%jI`(grGIdy{sYw1(KV9BT_tT;|)H2M82-Um(J9FAHrLVqx+QOx7mL>6e_k%$M8y z3s0bXuhag%;t(GOm<$)?em`D5C#I`jQ!08H@?`RG__`ALkrRD_OBlgfXKj8>ZDe+{8D^eoUSmUpwtOKtB@}b6o z?<`yfuD0$Lwy7G(pEu1Tq7chwSeL~lrR}gDRfk7BNAhdReA4jb#|};dq={JAOlklb z=q8jqE)28ZXESTH#if)8sQP@mS+oS#LoAP-ANzxpu&I?qi8}K5BlB8?o15}EfWVtp zP|`Bkw^ROK&MG?S`lKK<(+C5rRcgxiV!FdgU;RjmLc6#sM-jd4ZbWv!K&!Qy6R3f<^-7bs871Ib)z;(y~lV|Q7E8ok?^BJ4>qYd9ZAYg9dz-*_y=-yk*=8)3< ziu36ak4SF5YPZ)P)Tq^%t>d9h?3YB)v5Ma#&?RgQOuJN3mUJ026e7A#9Dz+iw2lO| zF;seFUpe;xcU2h4T#%06J1&ePA`??v!v2Xsli0W3gIG@I^0kvCCveTC4;%>=$24Dh zO2*{Y--b0OyK8=Mxe#?ZP|fR*nyh&GW_mLZBhIW@j(Z-h0hDcd`7aV_T>2iHLs;WK z|K?LGbK$3Ie(fwRz9?`1^JbsxKiTZ7TH8C>ng7e6>Yv?|uI67+QVI^B#$qVQa!Upk z@WRr!1~=0+R7Nsr;+IEccu9R@aMN-?Ej8=w%dI^>US|zwH9IxnC+3&T4c|6*R6Azm zg3ANhZoc#T5g- zFZs&oA{#s6iQS7PJAkPTS58PEe-Y~|GZwqa1R)safRjy1B%>V*B@^j0!(u)x{+@1V znUgZdJ?1~VkzWD(xsRd^jNbDx(?-E?V*rV)z zzzyM`sr59%SjJ6NLcKu1y%%Crif!RWKl(K&Y+tRdL0e8YN%Q zG1kG{61SCjm`kc3{i(E!Vg@p>Nujl)lLK#;L~O;o>4J4`$xfM<<~zO!r^AI)htoEU z)MSmwL1G-y)$D9dFMcWIn=iA=1dOO|LzIoGFwR1aspfld+ea-hkSs2_ki1n|3(LrH zp;Qd(!29@{q%AZDFGXY>b$qvY#nEE)x~OirgREI^8yWS4wUuaqa#IT>P|?=dO3$JY z6H%3?1aLi)ddgPwV!3fzizV+a_JX(r#p5+ftiCM?-y<{3_tOdNZRoJAE-a9>0pCoKi~D zUS|S(lUfJtb73649{7E#BFAZ+PDeXBJ63o>R(*>hPUDsU4&8Cj9{pFo_)zESK>g=u z9x^nVCRuQlHTa6UR=qkG6-|aRa||~+C)1Qudq;VBdz3DXzzBW#-V{B)^(!V^SyjSI zW?`w~D3)*32F zzz?1O**3`Rg4`OB`QY#8CDDh(58}06NH`>hLBzps9t->&y~s^UK5oTRBg+NOf&hM?c5l|{w3D#)x-Sd4Whc%I@hm1pj%Gv~b2Pji1x%zo-964w~- z3_m!k+_5H^pX$@%UF5v52SyGIFJ8ONCP?t2{w&twXz}@FCvd4#w^%bnmzQ3c+w9bTM=$|TOqSWNST{X zodf7M@9f&r793OCM8Q`BW$Qp}cA0%+{c!|L*uTf(;m3)6LD)zygBj9wY@OcL25&YAQF6O6)T6clw6SM z`IcRlEr{ZKP3k^;v|t6dxt^Sqb5kybJz~vtkUJzwrzDWVUEtJS0vKuh>jgf0;%<00 zycr}+B6-hQdB>2@E%A<5=p#|i-_^0qLYvy0;3ub?r!JzWMV1-cVy8$CBLC%`44nWY z6!mr0ZzKG>>t5kMx$ghvqW?GiO_qNY0S#qU+%G{5gS3{GMz2uAVuc3o1{o1-%`y!0 za#AV0JW!Yj^{Z3U4~q1)uS7x4%w@~GcgQ~=hVG>{8`$`HZ(qrRUf`ndx<3A+=yh6v9fQmt()a-=M370}gw^tg}7zUF@Uv0G1`-UOV3kY-H zG--d>;nG>{Ee+dPWpNtm=MW$>e>(q-x<}>8P{vBTgukcM;UZb+n$Y-Cqu~zpEmNsD zNlPbve}~^9&G=ZWvh03gWKGfKAf8mjgK7OyUc&a5NUAgzEQaBl#^2DRW_OsrXI z6SPqkLG9#hvT1_sMUi&NIwWFZzcxDX8mSVKe)vhK1FgwP$VMUgwc3;a&MM!Jy7n%R z6I^=s$I+E^W0mWOv{)M{irU>5p;Pj#8nTNb%z;LtBcE3r*z%N?Q$*ey&CX4&4gB@_ z_Z)i==IFO13vnIWn9Q749J)99*PcRkxMa6qW&FJ}T;iUzfGjWMGHc(n??>jR!vPR= zZcG7%$scSE=D$L=Brk#Y5fhD`5k6A2dN!<>CPyf(S$c1{8^3Xk-hfWN3_hGGn#%q1 z3oIBLn>1%7@PV3U2zGI{Fcgm#ZY{6D|Kv5SCMR!VPn-o-Gb? zaypUMZyR~B%cJ&ii8rl!YMK(u#*z|`x+u|u2$;u>cpSaE;Do49t zo8Rnd=RCqFt6;*{C|mvdyO$Vks_~O?)Ks^tk9vCJYlBZbM+>d~o0EQZR99-ZJj?-& zF4nYP1X)u~PNzMZdVN6ya{T+EnO*wAdgl@S9#wcIsB-(rmSh3kmCBZSV*#gF6pCh$ zZ~Mu@Aba@H@?9~TMkvkPnbVV+=VP)zYcjvrC!%o1BTw$!2xH$@mZ+Nb3*Ugwg`$@m z2LKB^?zZtaR>bHa45F935=8dfwt>W-(V@#v@BDA&V7{s_if8MYD?_5rn4jcIaP#16 z!r#ZN`97=?HMr9AkKfgb9c!cy!vzD61V|nk8qZ34a_j;rxg@&L$Dr{>pigNJ z$X>Gu3=;Km;}(8A8Ra4EbSJ*Tm~snPKVVm^NF_XC|Fm2OK=?@*KeMjGR|{~gX65Zj z?p%}Rk{I@??!U#hUn7mX((L2Q?THT-N=fl!^#f_+;53a%%9bTYlhE(NO$}RpKuz!C z?LQz$K%F=TNrd<#V>*Wx8_c^KrUi&;4R@3FgK@$wG+LU3VuFVa+3g;g>~VD)F^SB+INRJ6r1;%<%*pdm?_ zRGEiP`c6Oy>PyB05G`qT+TZea?$1u%pmwo6sfVc@pa;_KC7{;akSlZclCBJ5;l+`C z?P22IG@I7aEPCj7EIvs?Z&}z{73h}RqvH$t4QUAM^1deC~*`*B*1Nm=HEG`rj=j zjJ@)~KdQrK$Li+3?TRoRq67oKU;-QoL47a*(k+ueKSMZ0K>ySwS%-5&$E7X7^ADsZ zUaN{BvL^6&th%xxwY`pu#;m2KwGrpFy7|z>y7}owqxH0AW?X8Xqsu8WVTON(xei2?GVyPY7($W`FkMCbX>w;ke#xT*x|)?Z6YV|7w#Mof5QlVQf=soe6t|qpR%K z32<qTevH*+C=UW4iktHv|3B83!2*B-w}gVN8dEbZM~LO|cPYF9Z+E zeNFlUN>hskOPWPA%9tsYWM3OACPe80%+AD%W>(E=5YCT6{Vew3X(WGa&6gNWQv>@r zdYSEESgXHJT;FDqEnp1;1`N7kZD4jM+5awD zEhZcb_=gpAjP5{A1nDCRRlRe#d{)&H+#WC7?YupnrcJTxx`(+n3oBc8s3@pxcF-YR zV*m*D3lT6yBiYKLg}(NL;T63WhICPJAxYXl+ufK|n0Y3a3?^z8bF3dnz>&Q7CD*c~bUJUB##30RN3#mDL0KTr z5f!Qo(47Np3*x2(n~?!#v#~6|0DA6gG&nJbtPmr2L=gs3)*&=N&67QIo@8@vmIjbJuVzRvf`4tiV7sRv>xBj8R4iW0aM5S7OzU`mIHVh(zgl{vp}xS=2Saly|@l%l~>un93uePg%>!$w_MP zSc)xGDM4-n9*4$Lh5-rG88!xuVq0nbX5KuLIgleiRrVp8$gH^9H`ZNUX{E<;fMCP6 zXHuz|tV-LUJR!Zvq)MBy;;B)B3iH;%>BB6EGo3m+jq_R$_lenielT=YGgKEt>aH)` z>N?qe2KyAOXqt5=uo4jHP&TH|w2I4=uc6DY{l(dL1{npFQ_9;U;c|Zt{i;;_n;A!@ zY2;Ov#tdPv&ZjTPUe=GMo6iR=sGi{-8n=4Bz9;<23T$r5+)mx_uQdF<{p*X;UV0}W z*z3uNaQ{H!lkPW_PVjc-sk<^l@RvW1-2=z5#UW~?NxIc^a{qLC3KKgyZLmw_cTflH z8KzJzo4UG9?G4|~wJLh7P#V1In4}7sx`igq&%@f@AS-@iDH!W{4Fj8bgB0fT2pati z+LdJ3%JDBU>l2QJliCVQR~bNUidJnEz&Zu|>`_%MX5g|Zn((Mx;@TUam5jEXCSBm!2hAr9dD zt}O?-b_RIMWMUM#>>DmQ%OM-u7XRagv+# zkuxol%tmi?$zO<~*M_3sfTsVVv=>+V*v-Vz4#{*EOV;?NlJ2iYR?^1aYK#-^PwWo+ zS5bV95mC~ld3$c!R#&Tnmo%k=ZWceTt$0e2gq*$!cBNG5>Um3-_hb{o8Wt;Ddq> z;zSgTEC^3$$4(=~;a@OZgWB zgOIO?!#8-Iw)@cRBFXX6xGvRdY8Udkyi`6P&Z7^NxD;*X)`7?rVr%e4wTj z&2ED z=NJ`{1X9kAniDZC^6TBSLt!TkbUWSGNxX$ynq)t;dv20Gyj{`4eurXcp&l4w+VF>U zqZ;VS+T~5%No@LqWZdapl<8GT(2*3paqO8kUzj7!!f^OH=`~gb98V&mSGh}qL^7QY zQ9SUC@nwF>WgY*LdhtcIw8=2EXwBuf3A@JyadACEK?>J&V;f1!+p}_fD>ET zWk`J!zAoYsT=y)SyW1Zz#jMMqm8^j-E%LzBrf>bA3#i5k&|z&WC%ja6ugIxqaUauR zQqXxI6L}_%Z0O3oH$?+m=*37*V>&d9rqS$9)r|7W zX&L1W(KJ9v+cC=@Co(z}DfS2N~Um!;iP*O{y`B7~__ zj?Je~iq?${H6lB^6Q&7NVKZ=g-slIR?=UP=nL}GE2e0mnFsc+}CihEC*hABX#;WFJ zd#lS?{gHH85j?BSI^8XSJ1&5LRV0R2WWLM;00nK_1K9RNEJxhRe%j5cz9(?qc%Ald zpGYbmTRP6WYVvcBNiEN5u8BnNm)QQgrV#g{5N=USy)?ZvIAyP(nr>6E?c!N!ja-qI z9cp3TAW-VjzHj7W9%*A&0H0({wZmld#8}R_YUlk$(5GQ#v|Urrvb8U3lz;6x7bW{E zXK!2ZP}Ko#;O`(0M;PcV^7B6;nXhj%E{gs|l`WwEci5Ne{{j2T7&x2%C;08sfN@V; zO!NJRNhe7_(1X3-jK2BXOB@OkNK)+PYqKVRk&HG`2{HNiF+hWYGBoYXyP8gyG=(gX z?1z>tXD#`QG|#HmI@T|mH=C_>Ds;TIE$uW{pSZvHK&Zt(D$<%VuOGw-8{+L_QlZ+EuZqXC1MK^7UkC>~sT6&7f zWlrHsHp>@{U5{RnUwj`z;Y%J1UqaCrRTsY075Uto1(NLO-FD$insg6xZx19RZmi^8 zISU`UV~xa}Cz7v1&=6kH&obq;R6A3d zU@h}#&D&61)m34t;H8EF3EWuTT#Ua|Xl*_H=|&?_!nJ1FqZV-bfZv(~S;pcA2dvc@ zrI4n)23|@cgRILtS^~XQ0nVwbE9=#{%k;`n&V>m!#vtbWaA#Y;%B%lgPPsr_F;bZq#Y&pxBVpfWbl;5^f4p zHMXYBGj43qrs49*bPw57)kLvA)36%95sAdE){ecVl`}; zqD6=}vvN}Kf`wqEHXKaZE))78j$0H|9?ZI+W#MFWf(w!cyJ8j{Tqv5Qvv{x|Krlq!cv>J+FxuOgzXeMZZgq5?fxD`xNuoX5XR5=O9nXx%UxrwSkwOEcv z=@UdMLWo9+wh`kekKs{n4&ynGYg1+|KBNpRM7FdPUyMUwm5DC0A}f}u$`aT)KvJAn zu@TP-=N3ApF|ZG@*Cj8sOW2h**d?BOi|d4fw#ym%j7ukV+?>LLzoz|ENM4xGW@qd( zz?@F*dfJr?4i6?->rtAmkJeH|#(c*un+4mALeeeJM9~@{FoY2j!)#Qw#M@_nU;6{o+gT zrGUX7L*8p#W%TJYCMs}OO*vmJuzO~zjmbw=SI6g*?VdUocf-ZjRAc-X5m$1qE=5d1 z-i_+VZ-a0Gl_m38iWs^NTfqtJ?)*k%=v$k!QQEaLB+NnLw1@@g=W9cn31;YKN?M>3 zScF>L5qmi&=zG)3s&*U@fr!2t=e+D6UY-O(cuj~Rl;UK(s3Wxe;1U@(9dJSbTK|jOE5%QUl;0OEteL2wU-Befae_~j2H^BGVo#L$L zc(R8Cf0UH1_kT9?FNbh>AU%q`?cTY7v291|bI2cYM@e?LuYHG|QJ{e4_S)V4tLF9N z^m=T4kL(rf-3o>5ocmX{#zMkT!6PcKIB7zGA^<+f2U20uVYLy4w#;rAH)TNq6(;LB z9w@98MiWOs!3w62CF$;mBM2Nw^=Fn3we*H+V1&72fIKp!Yhs9Poe{$Z=raTM6lwZc zy`6BEx1)-lVbfD_(r*xxcS&hR+&DgY-99qYQP8|GhA@V3>c2~XrRtq_;^mEqHvVW{ zHg&lepcc=|$_%+-V!Htf;mHxmRO33n8f9nimlHk{a;@BHCD}e$8?tX>@czx88#Yh; z1@+4HsxTKTuQVzA_k-fVPF!j-d|0~b0&a&XphLitH+|IpmLulAVBfxrl|m{-+q9BX zrcQexU(n0~nap@1ha(Q9RN$C7e;qZJ!{&5c;vgDx;ozD<` z#26=nYs=7))@S4lVd+3U(kKMS1qo!ca1L+jOm3-RQ`wIe=&mQUwNATa71z}Hc5Fts z#5Um7=@)@&;uARGm3?pvs89Y&F;l>g;kM_x<%5Rpu43ty_3K*3+OE&y83XR(FH6BX z1mkL)Sv}#*em)RH(+1q`%KR3&gOJhIZ`#1}AUntiI5D6_A`kT#(uF_{okHo{AQ3%ML^tHXJ0?2g6}-kM-N@}Z0)u(nvDo)8H-e99 z5oZ2=?=(l^jV-AxUbkz3Z_GZvs)ZLuwP2t-ML_u?VO#>5p;KC2w&mC^%3dVa6QIg) zIGZKcXOo%!W8Ae*X?w2Mn(kdl!RA^Ukd{8gC>^B;493UD50X^CoDF<%vTrwzCzw8g77j5YZd z+_@Ig%0w1!MG=>$1K-yKh*}LYjRhar3IY1-K7eTwV_78@k7d&!mcPW3$!T#KyK=3<(Hy#6*OY7bc=0DT5f4WkiKl6#6Zd zD=3P~Fiur)U{rocDZ?e-ZBnUZq`0&ASOq>nu?x4?x9oUQd&OB?6sSJtMTxVk4~f{b zeNY>H>=b7XzQUI$`{q6}-brm?N*+EDox6~q7XjWBRzv4SToSDf7btU3qq%%7oAE&+ z1t!y*m8LQK+Qs2%mgAZ3_l=Y$AEo6SA(oom(xO!+&zAxx7-mnMJn%>!AU4E`r&WgI z*k`zu!2$S|Mq%#|zotwlp}1JnJy_Vb#>_A|o4QDEHupAqt5=4tb(-|Ci$))>LpP#s zqf}M=onNY0^UHW5HY?D|)?0sKncp0er52E0w6vYF2(kP3>GhwFZsgaHp*i0F{)x^E z9F1Rjn=PjfQ(fqWS?SvbkBXgl$(#09fMJxSEvBdGlV1GYu=tW%lWyN_In30AlTr#( zE76oIR3)6!j<~+4sa?Iai`9hJQjYMq;gkrNOV_8+^nF`i;+@}Su%aBzu2kl^OY+XP zO9W0Wr5xIln*IROCFWGoYJsguz=ZQuL9JBRC2}nufvFLH1|lUsGQ;MYL$B)E+8&hN zH%a+vri_1QmhkUovBWIaEE<;o#M+t6%;>xFHCS@f&iP7T6FqQMCyV>ggODdiZzf%D zYrBWbZqtO*ey)GTt)mB`I7Q9lWH@DcW>BNBMR6;h)bkfb;|+2mk=y?DxNIA#A%?vK z7BcqPtFC3nA+nB^=nysQ`Y;(d650U8LUb%Pv?il{KAeJY470kGr`YrR5Xatut7p;+UOiaGIBxjM zsn_I;f4d~&1r2RJES()OTW=e5`BIi`m=o(V6AzQyJf}ptmqa$)(UmcgrR7?cb*H|q z#Ey5KbqE*;D{XvHm@*@e6B(7O(Mr=Z`H^dUf)})LCkK)p$gaF~dk^Iw++mzm zRk}IaH{-_riLP(yrcfOGGecbt3|&AMi;#HF@Gb7C~< z2j!XA`Vdgf__tP^o-oVX{bhN8Z@AxP5a^1eJS8c%isrIm(Be+5(YQM^WH}{JJyxuo z7m8aj5kH&%Qx%%07Teq8iE6uqbiQb0FCRM;=!x_C;EuDLEQb2~=vl2JRZ ztX|k`SG}5x_H5D3qo22WK;tT_*)OkfuIbj)tEpM^@r>;j(<{M0IJWpu_^9j_@YC8Z z)LUvfMtN2Ji0R(MSVBkcfUk$h=+zXK6tD7{HE$4+*PG#@na~Zt6hf=9#|*mXq0uPP zhdV~2QM)p%5hq`Lyiu!Mt|!=}u9Nc1n4PKyrJDT3v!1E?eR}`o&KIxFkwN{`Rwv&x z`W7+RFY@Z4weoroJqVnbAto zi|7wdpihM|7oJKG%xtdBY3g+cbX;crPE6k`F-A#&08Q_LMj$u2&=HxBKZH+g^Bun( zyb^?*31P?tk)3%l%HS6#J}Gq16bNj`CcVP6iu3)3dyQP_f6{r~eg7y+Uk--bs-iqQ zh$dju8bl+tYbmvW9T@^h47@rfRbk^w7dPA9Qyp~NL8*8>mFUo6{g89Qqmd}u!VO>4 z;Wc{oNpJ!$5pj6aEbniVLDJ*k&;0?Q(ChCatkwA?MG{7Ki=T6!b)T{Ff!Q z#GF7ckC7)D>9vAGh%XZQm2>a`2JF--RqBEMkKTymhfL-2wjef~5$Kby`Q`&YU5ajO z39()~Ve`NrjllYiMt$h`Ho+QNi+wDHzan@pFTSR^_61Q46fBc)?yucerKrp3Gzw=E ziM4sON5)K#Rj?t25z#3aRL4R>F?CR6q&pbj^4CV5whqZEj3%-z2{9#EM4fFUW_QCA zf2yChRA=pok>k~-i4yf(b!nz~%NfQvWGuvUJC#?IF9+u+a@Nl+Vf$lB*g~oo;;?UuXp0hw+ zH*@?x()18?=?SBXT~nM>&$^>3ZQN+yvV(tXIZotxO9?~jPTY`>3&gWa0{hic%|sd z@I5A!0a~({4(T6nQ!F@4^EVz&$tvR9Kl?3z9G4SjsmZX_q)$MU9p-gf@}{Uw`FC1A z9;rBmmZX0KDm&SIw(E>6-ll0Wy}i8Cn%v^Yt&hq&wd3@eFxp|Ha^spqi%s3*>GOX8!P*~8R<@dqmP1b^qkO2)HyLIw)%AAek+D( zfCf|T@d^1t_48@k$wCHW3+$9O$23rRGzimbUZ8{y5gIGjQi|j_&QYpR{qlwsN!7-& z3r<8Z#IHWcZ5?@_N7J?*znYkoX2X3Ej%!Q)wAplZf|ZmmWk}FY!-oOqcmR_I3|C1@ zb>C8gSNZT&yI0dTscQVv|CSzkH3M7L;)>~+EPRT-;b5)j3nVwiu@ zi`syuFdwdAiVaAoL0gSBDTb_=gx5B7ovTp?rcTTnRrlK7A!!>__ro1pZdg_iWgT+8 zEg zG$lzm1K=g?7e0X-uEtx__~W2;dcB{|+SZ4M-K;lTyDNPRTM^0Gj*<&J#SYH+A)fx) zyzFbSF@cR-0)ky0P;1`MMTbbRtYT%WBl1Ssy=jLW(`<5Zuhu;)MwKC$K$E(K!Ciy5 zA*EfZ07;j)qp?&*S{Eq|i{}Ckqt8Ezd|HF`2)WXEt_AnJ&rEl3Cn{danZbXGK<|=(IyqFuj8NDzJ2&ga*!}JNtHIAo!NA0cTxP zgY@bmB1a ziW}}7>Xq>o;rfXX2n&%0d&n^A7-=0}U@%JSC=#PJX%aW0kN3S2ZJ8mp2AVz=24lZr zOAsOwgQj>jj1)GRNqxBU09KWOLSKF~H>^(*KxrzU51m6M$*MrMbApEn^8hIrh)evz z6>pOlhiCiil^BUf(AdgrAi2vXs|)VJX6i@23_*bf32OMO(5$YXy>!d$FK9!mw!`MF zt`5!ij#Nsc$?C1-%caL^>@*AXQRPY8tf~2pMhiY#c2*V}Gu`Ch+>R95izskP);~Be zAm3Y_sRKU$=>PjdD5(?3o1S|5EWo)VgkfWiIxf*#=?Cky##w&Y#e0myUm@kl*G&$A zeSc2JG2-zapCDscAR&G#NXC7X;^85wZ}B4IRbI!wzJ=UJbjR-+j4KS)@^LBa%qlKC2S=A}|?mBSicq zd^YCnpd~>MCo_JV`N%JRg@e6S6Wa3j1nHt{nay9rhoiq{yjCFeovEIwiDT47l<&ZB z1wV>5v7prky<>`~YPPNvufp(^#8u%H;=$Z)uYWBgY1EeG-`2v)B>Z4#L!}TW zWcXE3+sa7F=@9hETJNnD;o4Gc>P9`mRzfDFQ~7WzrJj;r=d0VfnnlTKGVZM4U}Ra= zAoe4W5KHhAvCN|JvO{^>0eJ~6LS<2%0t;hF@{j9u<&MxbR#r(=>=@hE)~gmo@tx zcd)}hJy$EbZdgINZ{)Si5zBA3~e+yvrQP!|1V zp=Qq-$MyfCZhVBL8KuC>5q=hi0^1hn_^CWAkQxa0# z;!H`^lS0kM)9Sa}Rn!V}b3~ViJ=m3zeg99sHJ*H&7I%i>9fmdVWZkLnClM-m=VCdK zAF$5%3d9m8un#*{7*9K*8-uD;Kn(q#M>i%25RChMvY&|hTXe(l49yvJfl(I*G@~mF zFx!*HVPi;S+XMR)pwQHf3FFi;D9~GK6qARrGL!mLZiE19AS>+BoKr8c<@Jx~n=hat zZj9HUrvt6c&c5n^W)tiw(D0|M=b)&<6;j5v1VVST-~Eo5`*5HcG)hJ|ITi*BlR5Gf z-Yk)(#xorP9*K_h&OR)@FnPAM2y4M7c84C! z$vXq_OOHv~sr|eCk8Plx*=Kp6?_KlVNd9!$JK+;NhSi+{>e|G|!#|Sv#upJ1J@fgk(kok-j4v^t8o|NX3 zx*4(JsXDxvPm3|gUQ;M!=oircKAdQg6UbBvxKf!ncpR|bqlrOcn?W3?YK4Xq zir(SyC{ScNGJcuD(KqUz%F%y@e@xo|gw-`FV1Bjj2f9LdjS+FTf7LUmqAi*PD+}8)ECCb-Bx&51$$0Zy|DRp+a6eF$S~w zDpHA;=c;ERnJ!=&U5(_-TZ4W67@4}Q%8l<4fcGt;&O&n z%Bhz|Urh&DpM9u7o$+$X!)f^$tywacq}mo{w>xOm*TqV=AQg^87yb2ZiizUk$GA!h zclRK*m<;4;Z7b$&?=_&Lq-Ewyycm!O>4gDC04#y7JZ4) ze9&hL7X^PwC4b^K-S@C)ys%1r>DAx&SR+@^zJK-4eQ`>CQ70t%S)KUJ&H43_l$*Yl z$QmE`jnDZh)YqHt>fK%;ht#`=cxqwYY&ihGR}JXeRn)Cp;uL{OyLU=m)+`%=Q)k|e zKMZP^<*29T$?8lY3#{r@`F?XkxLyR>ubjepFMf=UIT=TC-{E|$9d~2B#+BF#$Kg4yh~*x1kjZ=*2xrQ$tcW$bkgb_d7JItEI$h$K|Gqf+ zE3EQhq{`&T!s8LTH7#DHO$gJceKK3$`PbQsq2N64Z}1?~0YazTG40j^ZR1goQP5qT zvZn&oU7ZA-aG-X;*@5B)Ns2)VO>ZvEpnyhD98Di&Ap$;ix2Wn~rFJw-{V%?R zMfaFvDMwsi;%MwiJg$Pnd8K1Ut_arCKo_#%<)IaW8+bf5^4Om}#oSkjBIUa&?g6$r zY?^H?$AC>)IL@DTJJdm(aiJ5=6}}Ow+fzN_X%!oCOx8~lp2^-QPEd0{=AvjF=P~#`I8#L_CW+PrN>tXkxZ{Fa9~F#~85Jw8wQI8YIJ;y;4wD!S zz1xc`H>~(#xkTJ2#;1(}1<{jJl5$2wgXtA`=SD|Z?ArEB+RPYWO0I0GM#&n#bJk98EK8Z&>_l>^k4CH1>TU76v zE_d`sro%ZzX`F){;#w9yW^H!J4^5AXL~M&(l2%zoCPj%eQ-h@H6{}Wrw{!J}vOBUh zT}uZ|PNM9~?LN9K%Qj()#a{Dc$mDB(?>xf_cF4w^t2WQ}7gw~;?(6o7*I?;C7>VaA zJea%E#s^Ik3>!kCPJ}e%A6fTW$!6^lGR=0lvPIua29Js^RJgkYxZfb4s_3Yit{X zbm={I48;`__(osF$@2me_c~3Pc&Az0N)u^Pkh@Qdj?)F8cSuW4m_?L^*ogk29*6V^ z4Svt_UG;PLH6$S}Bk?Mp7|y-aS%C&MQ<>b^v->g;DrP`{>u522%>V_oWVfb(mxhNm zoa2f(rkDKGnV?`n`O#bg`A$O1Jm8ta#-H09WtHXkKaRu3qbEI?@qm8?`e)LOAG6-)allznBc!bIgrY;t5J+p)8 zeh!r3q$UB7t=MRLhBRO{;`tZ;v?RNF7OjU(HcMf_H}C9IRM&ripz8%RfjCtz4OEyK z#uh5Fi`3}eFq7VImGR7qB%A#w+V2~h2zR!h!otkV&=*I$Ph3_IO`i|976#k@!ya%YsxRZ%BYRSCK%Ga#Ijhg!)zTxuj`3Afw`u1Ps%O?Jg{&JRu1 zpPLVQsV?Vo`J5*!C4tsUb#mh<$>X$?6iQLUE?*_jX;}0I6{qe2uO*N+8C_rh!4X^R zv;`FZvujl&{r|WB|JAbf|E2x^r;qsGuB=&!R&w+Ds3Tu9Y)dw%sqVXba77!P@|YA< z`Xpz7a3fOKYjFDeJnG6qs}$RT7P8@)Ju6nmVGQ2idcATx%M97`$m}R6vxOfyM{b^; z*-mToz8^O)7`-^EOc+B$EU)&IG8Ge1YN*;K7)EWwj#(y|B1UQYY03;mJ0ZOhsvake zm22(R=Dzm1V%#YY2Bd!%|#oLeNF>bY&YBv5Wm+AbL ztB$xc7Cgvdax>>pB)7Xm{t16q4_tj_;G6ferLy}H>?GX8AmH!9nU!wV{Y}tuLv+_h zYpYg;JV+>o`Wm!*#@1J>()CpAmHKSZxGqaE_*IKa;*=O;!TlAwMcj(qa#KDe*UN(+ z00F%S${Po@UNn(3Pa1f&Kw}L-S^a?5<$})#(C0&~U)I0J`bN(0P^DJcW{@6gY#FXf z1naA-8{Cam$-U2%36$!9(GS{dIXRsVT#(qDjT2$yJab2ppIoc(mHzw&9rg^|orZ?~ z?w2ElFF(nq{V#W#{LFRiA3n3UW0qwYxBTd0UanrhxWRAl-8`fRo>h#xYgO|(!*kV{ zrlyoSJ8E~%F?^^#?oYzb8RQUZ;`%XR6L_TVaUC?j+wltE_>Fn_)LO@JhI$I-<~TwL@AWbMrjl?6<3u|m$lOxF z)`MH;3cAA3>&I8+`;)B#baz=-F*XrM28z3PffiBI9CSeygyS$I41!!jM+7ggsr8hv zVjKPEf8%rhrx;366`-p7PYh-Kf5hGX*QwQiYaH>vWIg{ewIWfpbFnqHur-shGdB6p z5muJ+zdbCE;XB^m)KTYPHtM3i!JoDvyg4|fW30(0WMVoyn5ZB+wiI7?6Z=j_j8rgt zz52DI$Jl*TnSd0ou(t2>+IiHK+<0xitDx&}c#bJ_x#3;%T3rv9!Ow4)M9Elawowez!eZ?!qmu1fH*%zAg z8_bipsy1@u>8vtc*_GxaBd>M8Rf<&U#TtpLoO8t_n=G45@x;nC|LT+0xA>t-T;Q9) zcGa`bW0Fwu+nTL-Q1-5WZb(yLPW#|?>IjsO>4<}hJA^=TMRe4%#SIbP+%k+4y?wQQ zvnYvEa9gPKu4QDPopH=k$t<0FQg{y_8YUpjlwcHRTdBG|yi(h=2x5hgOkcsQz*2^; zg#*gWO*!+~PWN%(wrR9#6sawe0#w=6k*PuEmMU3QAMwFlQJBTED~Js4GDxfT{+-y6 z5Hh`GSSCtVEN7@=07DqZO69stX54Oz294;=!dEz|k)oyahlFfK_06qq*GQUnNapjE z8PB*OCun*wnlC?Ogu^^{#6BJ=Fox4U43xjp(hQ7agQzG1WW|ha&~%LJk)Kb35pnYjNgTlKzuz@F8MrCXTYHPshp+WmLaH^dkX4%^+JU=To7 z1EbMCJj77hO>m4pjP zUwQI#k1ue;I<@*NA>Kd`O3G+>21;xe3O)HIysUTTGpVd6$4L_B$=|~5?Ply9>px65 zw-b8d>zdAD5r#0fP3Cre6#!h?=Y{+Q!C1{itz)G~Uqv{?I9qX^KzmQl1x_q-^NP+! zT4HbF{)Gi1oiT`j z!qMa7kvA@0e$|0cE@y8NGeA)*^-u!p1lFa+bLw~4*~-6AcGHL5^xh$tm=kpY>#*x% zBFoemor6=f2C24n$6VbC`+Z9;#622JhwM`GB?j@hI%ZHaZ61ApTFf~O%d|HTx2U#j zEe<#GtsK3wyprFwGhiXL01936YcG`}Q=vq)nf;2jP3H%}>}SyAqiwDt?ssWk^ROS; zwI2E^!fPxO#@!RwqF%#6f3dr*QUW11dQDdue@?h8wdvTV#sXeqRQ8*RdVA|(U;ASy zCFhowYy0iH2?FksLWRa=WlP1c$KzGB3sx|^i*e3U9KoR3Dz&p?+5#t-Fa<>>;{OGOb??W{ z>vN1@vFx){GQB_eRrdC%5N{&1qL+3_$e7I|yYkN8iZ2gTL)n@Yei(RSjRU+o4bGF{ z(?dL%mYFZmT{8OR8o8QWo?x0O6sd{cwlY=h-Q^#{@}5vR)oe9gTj8P4I9txsh>XT? z;9Abo)LJ}(QOtD{fd-16x3D)!^(g8hb+#`66Rrym+g=qn&|=)TfkW9ojzMWLhwoMj z+QX;=MXoFb7{kh_YK7_}9~8WOffS+)WxMkfyaPv#HnPr0usR^`?l|6_M28ULK|%?; zu-&C_ZRSi%8BEg{7jk$yv;t3m(+`#9so5!`{*ZxrdQfYG0$ae9@HR8n1u$!Dn8tb>rgVqC&~%jN9N{+rOX#fq<=bGr}Iv zlO~_=kC*5<`@R(x^Qya}# z&?T*svZ#p%D6XBg1~G_0NO;c8(LXRHFkO;FBd>zi#Fnq1K9pnEst(bW2hA6Y0r6uY zD`5Dx0eY4ZJ#(n|76ComsC)s&w03wb^u9TBBR z^dSo4h)SBjjHvt=qn2;c2f!>0igbbn+T=>D{WsAIvy6XVL#EUnm_o3 z!%sK;GPJB1%VFw3A#^%wud>7H+=a>z@Sl;*C<0|E>g%i@#dt?{SaIP-lEZrZ= z5|I=#$QNX>N9GNkB8^+sq;*_(@KY=_`FylB^O^!tngT>+Je|+RpTk(?NM*<**Y--+ zY16$a83Aux-{zmI>)XRESf~HI{4Tdca|s>3I|ciLE%E{WpLxE6eyps{{~!eS{}EX5 zUtt8<|Lu_brw;zlb8NE<+FMx!nM3>Gl0A(C)EfjV!7;$f$pMD}i%h^z0zK*@8G=KS z8c9Oo{>`$}ZaGp2O!%*VKnE6Lr`(d!;-XIMqKlf&^16%KvQ~Gwubr-L2=wITQOow% z(}>=y%hOqT^}nm2WBd7h1`-eAcl=xp&ozhdY2VDX6UzHDIQiGkzLf0e*jNuR(YweN z>?{YeXV|Yo)i-P=aC@hPiUbevwE*{3t6RF$z{KS{va{`kz-NCcHvO^Rmvh5_M!EyW zlRz@YM7v3)LS^ktg zFvcRE|Hm$MMm{pNR}^%jOL9~k9+Q?eb#P=NZ{SQD7}J(LWE}LqP-yrAihx*}+Pi9b;nh zBYVecx~vi@n|5d39|Z1^*jVN1Y zY0HEGx|-U}o#wkVFW0-#qeK0{+QJNxrZc*{W{w6DNKG5pv;k~Qt(ES!NW1AIcPvC0 zLnf-YDbVU^N~-F^9^tp->mHbWLaPT(htqU)86k1n^;FK9=I%PB1_#%iRZ~rH)FZ_A zsjN=Zj@au&B^I&u`4(bJSiwrgG&$TIapqCw}wwi+Bf%U>!B z%5XL2l{Fs;RnIaowf4erW1#-fu{Sn3nj zLdxq|AE?XIk3v)zR2Z+YsRdo`gr=Ibo2iqQ(lv=}dl|V2JnIcfjgaU4t-gMS8HR+l zJxKiUqy5MdM$uVUoLi}_Z%oFBiTwIWqXd>rIT(o6R5kcBki53Jh*Vf3y>&Q*DqGHk z_B$ag7n^FIPa!5Rq3W*~ZP+NmDqCbnBNpW<*rugy(FS8xb`@2Xg{9EbQb?jjtCV84 zYKvU>#lz$^=F+q!b)8K`5#cl1pz5;ngdqnee?+#bqI}idhn3m}ENG-^G6PeCs;cU$ z++Ddc9ZL6j+&ksSwiv5Yt}gY`lwU-|PRF(CgBE}ONH8{2$JA~9yJa9Nb(Gafd(eb6 z9+oGwy0FlC2o+4a(_la#WT9f$7^h1mtp3XT5tXD;r9@lAOcO#0U6BR$BLla*QU@CV z;c?6`XThaHUu|hycq4CXDwLFz=Eb#`O3T``SVgL`Se4Hz5hS)SS*@cXq+(erdn^=e zn!rFP<*Z{QWku@7pDLkL1*dXtSW#J3efYREUs_>lk*0-W8RqaYdm5{?s*Pqznnj+A z+%IKr>a?2P&Lx1udV6zQYF?$Kc34>(R6Lxl=_XY&Me_#!JyaEu9oR%W1h-h3Rwh|x zLkW|FL~f~Ny`@~Gi&9=->ieWUqg_{Cp09#f%GSK3%<9$@^k{`;FH>4H{67f0hv>?} zZe73?JE_=7#a6|t*mf#T#Wrilwr$(CZ5unbvBSFg?>MJ%Z{wUXzQ$^NW3}d3ob!3- zcV5$>{lXpD){7Ncm*gV+;8<$IN_-Ous(%D0Al^Z$t*~=&H0-J_DaV*Psd<$)=f$6@ zYGR8L%2%efu`WxHm~N#> zOAD8#+|-;OMzK==eg^-xX3f7Z3_gejYQ?;YrwmM7v6@K7RGmT)vT0`Ht;bf{Q0!X{ zQF30kt&I5D_323@Y^&R<-D$nW~QRI2v!hB$`P`X}&3A)zCut zY9%doPN#k8enxgBQcefUMh-0=lsu}k0_x~o`3COr3k(^9lLu+-4|n{PMvf{A-MZrT zbSP!`TV?CAGE% z`z$^5KXNOpgN@@!YD@3Zvu+FjG#);L$(U)mYD=s1M%IRlU6RdL-hWEdV1dVaa*U}r zVyU;lD`_r}4_Zp^;{hk*UCrF8^Si@V?5xzh7BHT+jL}fh5YT#x+t-)vjZ98zDHgSC zfYPps#jwQPhpH2cQ`PXlpZ3U~vdjyu&MpmSPzRFT3CkGBZ{90^uPlx>Xw~JfX>~(J93Zmksy(6X(r$0h(=3WY03Cm z&{jky3RVvfBs67}`uf|&N^7+?E@TRq-I(1-jS4TYGFZyRcvxgA0smYhw%srhwj!93 z`>AtymYnhw2M2;Qa4%1$_+6R*>QhYgpHDNO@ViuAqkqCI^>ox8Zn~rOEKd5MXs^I$ z3~=RN>~TTbLZZ$mg2O9zIwHZn&yw*w3Y9aW0yV|oe{SfnG7P{mwn%ZLaV z@M4x{XENlJ&PznAi0vDrFs&rSQWzJDBHSg?2}Tsp@uCkzl(^Oy@La{9%1P;9`GKo4 zUf^*@X$!5zZTXg#41YVImyR5B^gsk5r}IO41fgkqAYQ;pP|U6g696%!^9JttSI|r; zCZIwl#l1+TXu|o_vBo*bnL@b7$mL>4T=ss?K=yWzCKKPErrkLS`#QP$NqJM6T}@Ra zOL}Ej|K)q%y7cekAvkx^TWTsDp=itBrIU0Y((TCv|43_`vz+;ku{n8)<(@7Sq!?C%mZ)=6z1_kK{0%w*{Yr?5g8%d6Hnqd(0R+31~`T6ACs za7{*taC3v*cX9>s4BckZ?Hb274n!E)H)2aDkzNk2>CyM4>78PYOLeqzWp$Jl+ZJkj z__m;?En3k=8H-*yWKJ1i6?(EnNa@LjEi!Ih72yah(QWnNP_llC+s+3cd))rvL+QiD zMMJxs&(iCJ_BkA~YKsX{mjGkRjyOJ@*VVIVacg~{ZAEF})4;tCj>LoQ}cj#NFZ0s4*i5w48e!%X4a z++hg-dDEK>arts?Zm7R*X;fBX3Cj^4QVFEo%k$&pJzk4G-6+A#jKO7l{4@PWNmi*? zX33J6Bj2>75BrbSm(yR%m)GI3Z*o&ZFKKtrwWz-aOTSy%B3JDjXcKr7=FvqIsD_b| zV^`Z}URPkGwM7A>*`zM0X$mK4Drfkx{P-GIU3HCk^AzdM@H}>Oj=PqcSS!d}!v?6p zhdT4RO~u@e=uFHV92PI@VYLqztz6WQ=+Ydk@+lW}RxNEh6^{5X%a`}^^YhDG@{$+~ z)nU6Wkkm>dy3iv0thB7ogR$=j>=Vwkw!g0gGuF9RDhFH0evxB(Yl(*o2r|WtOzHZn z!Qai6WEs-9ojBHrE7;mfTLT}&jxralq@WUm(^D_guu6W~$eX~+o1m5a>_Gj~RhI_e zNs%y`!K%A`ION%i+9qVJ!ew# zwGyx@I>+SS*IZ63YjUc^<=~k9$Oxu_>)aU( zedg|e10cGithx6z-R$A!&iQ-`Ax%B3m7G?2eT2MUpW0QTK8M46Vy)SNhZ720U9*!j zXpWpQg^!+3%7OirYmNsdvyb9scUxyo+M>E?}dT$HezvJ)i z4X`oAD81lNXKq7p1arBMI0h;uB+sb8ckV>^_V4$GiC9~BsC<9C-v6PI~RS+JjR0F2)4q+Vnec1bC3(Vrhl*%vL zcMa@x)4y0PG?;>zo=%5~XD@Pma~Dx%iF;?mAk?J+4pUMP(=!*ktW*RVkNF!vGseCF zq^BV%Wv}yt5H95a=>=FxE^)FEZDlW8>4>v=KcZ%c7m$G98@3UpPFTRM76GER1MJ0M z-fZ-M0g7p#S1J;U0V6?g+znf_zneW9z;C4QIW;77#7M#M7b`V6t}NKNeddn?V;(D9 z0@P&W@wIuOHlKkRw)i~JOT&2dAoD})odg}(K%d!GeBY7lOW#~3Gu~8bJssYIKr8VJ-%sHCZHw=Y-76ovt5}yt~%%DaJm#u|o!cLx?{Y%ox0v8M^#gmM&}IW;lY?f_X5`52C_s+0vcgQr5= z8m4N>iA!g4OTOGeI3wDdU$DY*^=SZRU1<4!4?O(>pM@!xhEz?gTxr~>A>-$jbdO>O z$~n7dn=)g$yem*%l@iqDLDawF4dM<7B#b>#Y>il?@9E;rec8WQ_pou0O#1V%f_fY9 z?(jM_+rn_gY$8g`-};C{gm`;m{|4+)so?5yV>KTPi<~l09vJ6Ci5j?8qkVMD7WCO< zlqBKG+O;($Uu5y~P7Ks|;ZO2bu`6H9xZC@1_ykG&--Gri?)ebaEn@7c3MU?Z>Fs!c z5_~D$#StwcsAvTmqTqVA!Bv8A!&)pVW#a`Zft||J6#6D|+$pLR2X)fv)JZee5i09@ zVdVirq`mYj=aQXaOzQ)@d1kXwwGj2#Trx=4BpR^xlnhO4g=I&v#pyEXmP8iiFO3IS z!jz2uB(15*+h{luC9%U=$YPqvREDso1{9M+wDUSkg>CBbM_N$q?z9%wJm$lm=6y@{ zlpG09mL!)hJUYQvK)m`p?Hk!v%o+a;2mZ|%d>{)ScJ|=?E-qgV+X~bT#gb1zN^gui zjYZ9bQXieth`!-Zy@;+Garm^BSdI?3m;oCuWVc=CO(}=Rs#agpD=~~frlQtPJU1hT z?Fbi;mG$t>u2v_?ii+fpc-==3#;Lv>$-gGh_pAO88cm-_Ek1d>oZNM)TOj~Eai0hX z?-Ofh(CpR*04C7C11tfNdiyZ}S3od)ku_3i-Hf=PV2lu-_;*lpV(_(08i>;Z)|=b} zI5IE!u7ek#FG;nVGH?7|q8k1$-W0ep4|ta^@4qhMc^9(m%PDfYt#zg;n>s&f6PqvO zCD-*-2v7Kx`(C1){}7c(PMGXD`in-av>VxxY&g z%2LX$M@lO_QD0L`d3yQA5iR{e-Cy>UwO(8xK7~W{HPw2aL^((3^x8OW)eVQPE9}-d zkBv*Eod~^5UPAY7HI*r0nrgxYRyIANhB?fUXz!`Ycnn#H;1+~dZzh_f3e^EsbSupM z+;}p;aavaHMs{_&W^kA{_0$0rHqvtpU|cFCuX#lx`7M zfAMv%uV#_fV93bkroNhvW;oi}@V87j+5yUbh2ur^=MJn=u!o7rIGBa<;%>dE^VUFi z>ah_M6F0$aJ>b@5KwXyC^AWRfI*QahIIJXs6o+J(RD@w+<0PC6v>++Bras*G9pU($ z4U<33L?{oED547oqhl^z0g7rRD}pXD{+9DuCd`?ks>LaxJ%GG=sd{y6fA=ny7*zkA zALR+%KeE%q#)uHPUkn0S{y{R(tnEPE<-qj^cOupeHU4U?M-MOfCm(hvuouN~SsoJL zZTv4qG>CYU5Ktotswn73IYs{U9nQxH!##-e!Un_|O2_9=U~L2tUgtO&dSQ#BPHJP_ zh_ybaB1MZe({eDRp!ovQjK?-Pl-)T+>^z?mTw^CM$}-syRQe^jnfC5Aqjb= z>rT1!evwSU{oD#nWF&!V5t+V4 z=KhT#qj~EdItt7R#XkV|01p|rNb(5R2Yz>_dr7jSJ4~F)9q$-mad=_Gp?7a29)?-C zYAKvM-XA)@r^xB06h{`$L zC}g$M&>^5f(yo`FPZ6%Vz$Big7STxuQCT8X*5uH!80pE@f61vCpJdarlz)o9vxtdKs*)CS(Xx#E zYZGdD5f1qFv)EM{B2=?UdYh@ej3YoDkP3t7e%eD-^ zV(yan4Cw4@tD0VZkx+Jz@VuRe0?ob;%#a7?h#~Im=Kt{*8G_`SE8dg#H^o$qeZ&EA z_N~&_e=kb5m72hc$!>NWN2a5yx9PK}BgsK7H8jq!jL<2A*Q+y81 zzcX>0{%dBJ^eYg8wm5$5;lTjNNk?F zMJov3yw$f%CCBUa(h!&MY;o*X(8S$BG7Ow+Wmpo@CjTb#_8|tNhKB2Ab=hzDKQJUu zq-JMOC_lg1X9X0>k)qsDU}I~Cwu#WJ`FR=M)eq*stFRaRgy19Xftwlg@#j2j*(H1-1buzZ0f@Qm zOkDFif)FFIw&7>yVz`#F3y2-kt9})C04&CyihPh3cyqb>Q<8f^&myoTf&^&b-&>S` z3gPeq`;zWZ1^qMjd!y>w!;)38H^t6^aQyQ;xs7Zc5wk-kFjbc)7t=)X9@m0l0pt{5 zuQXxIs#2~&e}p8O16&hRA;C5T6hY!KUI0gK8mf83uc=6bGF}yGP**dKYqHLwvwFN0 zf9}FolbR9kTbD^6fpVM)cYe~hEnu&M7G;AQqu#*{a9JKFHGAMKOxo5R&W^s8_8`p$ z{$;r){`h0L#*os%T>UDGuYPP&?lmFEd%rgR%&}6eg`JAprFV=lR%;nq!;vEDsGs1> zvsul}l-WZbW^zg+b#@-Wp8L}W!qQjuV^PjnrmENo6gBmp={sJlp5c*UK%ml%Bz_dw zMkXF#Q7J&{o^sP`s3Lzncomq(R%h{p2G@Yr>xa@QN>?ISY#yS&wFzvbay`(U0)~>N zjadX2`92A?RuLB=X`D;5NY5W#oL2qt?UAAI(V7(M>wZkT zL?YUG-af7VBuS^B_}zE#@<-ajv+>}iqpVXfvBbecNOMl^yY1{iB{-d%ptR@wcYP$Q zmdMRJe~z@p^^V`kq2{MmP}Qy07*#5Y@?_056kvQ1p0s9Y8!IBk^2mA#sv^ zn`+2aX*ATd_lB^x3wa1d6&tTy;L;kZ9`4IEW!u!RL&_9SN!LY@dP2x_19-7MQAX#` zO>6wuAX}tZa-UX&PT6KXk-!f97uqaN%R&5@dvSC->Vgh&hGv;0ZIa(@Nb`vsQuEio z`-vR}<@NZcw9l=rb+f=>(hz*6_03Yp*0^RUw1$NTo^w%x&PhUt>DXe<(?idM*&l4D z%K{wi7XI+Qd6%=C8^@=$4|Dj{G*!qaYdA=F^VeiQlE?U`y6 z>eRoCSID}t)>oUOQ@Jd2jWVtrz!`OR20tHof$rNyE?EaTBrM5fc1X7#3g7dm>1zl2 z1Mxg5_7L$HR;PIIkqeIGjNy2WLF*k>q}nzm;e#2q(zYM>xc(2(!=&-Qe|*s;!;$_f zNh*SS>ySDR++u78V@p@DzH8~w1`80}Iiz(d%ERGH#e*f~!^YZ%do{SkHLY24YZAE@ zar7-Ed#MEct(w)Dg2!*Gy%)E;fJcbcTE#4LmC;}A*tqiKp7!R>UwAzC&gjjLG?vut zQ|5RxX1-K^flu?IP%v>yDltJQ=nK=ISZHvn+yd`OFFAI0L3XUKVm*`0AsH!8zDMMq zIpE;#S9l1+CamR}F%NMEn}k}Zd8Kh3&kgA&M00#M{YqRPSZ%fL>HFQ^KhpiAbRs{x z|M~9F#=Tsyc};VSZirREryz*hgw*r< z*TPF|J&B{*LRWj}(Yg1gw`0KO${XGw9Nge4Ck@5!%bvHK>A=bN`OOn$j(ei<~2 z+El-{B_py%$iAiv+fjv4tsp;gNreZO0%6F+5_+u`L$9X`c(oeUo_G`Nj7rI#+8Nts zk^IP(CCe|-L#jnwP^XrEO)1qr@0s83N8%U^-OKPx}wmB&IEut(gwfL}j4D&-Pq5MT~IgDc@g=*1xhydK~EN_^&!e&@sr-gpIKBLB`I)k2FjM`P1aS$sRn;s5Z zS>q~mB@F?`ZyCcQ&w3vZofYX?4H|c5tFmYi242Hmd^e~j1YaD5I?&UWb}idChLD3; z1&d6wgF%J?6QA92c;J)*`F}f}fV!+@XSnEA0gg8o5@BDS(A(|aRZlyTrP%plcw1xV zu~qq)bTy!e%1KvJdRIs}wvHW5WA)`8ZjQA5ecGsNsfh0n`Dr3-wpynm=-3;lG+hE& z*+Qww?#(`+u0`Pf{>upc;ULR9g*TxOpq#+5Cy#n`{%bzA01$j*6`ykH?_N#*D|+4y z9V#q(=K8*k)1*2?h)qQ!pimD2eaXr&-jficjI&?X1%0x3)w0bKy)5{0w)D!^6#k?} z$u8)8aRd145qY)bDtM>dZQ%Z_>&9%p^t$|Q*ULo!Q1 z!sWY4lS(&s1x!*JqaC_ z9?#bzb>BVHD28uOt*Duz(IiE!f)rxjaU*T|Sm7X~Vw}}3u--8?{6o&SiV5npReo*$ zJQQhY*Yxu>v2GZEZa=a_mEL&z+Zy!OoEe<*oSOOL@-sS`+rUu%Dx4dUcRSxjRvmkP zq3hf}e4oeOsOd;ZAx%4-?to7%Q*G@~Si2p!OMjvYI3dJMzMfUM1bb znEVZaKgXDGvJN%nP0b3|y1qk=_C9f%o*|QAmQG@m?lIObKNO+pOFi54cyp$DSpc%U zs@*BKNhHnCyd0fwtN{rt9D9^)g%(w{@?=XoD6s0tTQ`Dq#haOz!gU)Elv(@)HVhg)rz#hGDazBxRONo0WAIU~F1cFY_%o=G0 zLK2pk4D((UG%LN4td@KRJRk8}Wj~T5pHOPGKTy4^J|Sbu1qSx<`mfpH^j3^Pf-1Wr zawD=+gVs|4BNh&+H69M(STQP1O-)nP-TYd&~f!w>2b>??@1nIDK<}gYvylSMBVso-0?sapEJP!5p z#bK!utCxAtDnTBFj32srnBkb-P`Jb+t9za}q|5E{rnWrU;~_!D$k?Gx)ykRO<68ef z@Q{@o?I0+`W=CbZ(f;?c&SAoazezS$cSSF*#0~bO%Y7k>uipv!J%_2PTB2HL*~GcB zwFO_r28}U>U%1kNS!0b}wV79DU0q}HXbXoD84KcwhfaJ$(?Zi?32WXV4fr#Jv` z%|MxEF9%f0NhfC+_laZ-_sp)z0T;4)4iVR91a=)G8QiG80i#ui#-S`5&g72NQtQ8{ zB}=W5s;(Ghk7z=1S<*Aj0P~<)OyiDAwMLVKOAS&iao2Kw2&V&&H8}SHQ9;OPH37gAP>hgdBPpU^s>_y z4$BfJFb>w#_Q1=Hcq=Ofez}=O3uJ3M&@vWw%R$csV=PG^>|yC*KY_$$jFtM&wh?kKMu{@YZq?C%R4a>IK$n zRzO~d9{lh8fohMaNm8Fg-Z@?338Cu{(&X(*QX*(=hPEag6o-+%if!M?-GuB%uQw3& zdgNU>>ppJ4Gj#vdf)zP62JeItFsQ|$;3|l3Q_skl3uKCmH0`hoY5y1@iq18~9+S;J ztzNU(B9|u}__S=@kOLs4;X+gDBTzL82&4^kz_5PsSl|eZwTpKL5-Psq3AgyoJjoAU z9yz!gVq@3Wn`FD@?3mrRm^JT|B&r<$x(}y6K=Z<@Dht#R}xf|=k(;en8=|c z4uYOgo!qW-cY=HCB+*(fTRiqP*kmz-dWY73Dc8eD_7MeYH^BgZU6QPp@Jo+B zvbZb#CD@+L_H}Ed0-|5ifOP(1dCzB)4ZZSFS~3|BU%DL>b%v5Prr0+=!DE@%?6F;< zaB2UAz_zm6gTGYJEa?ieYV6r-TkrVV7qVi0y&t8zUF;Rg+Zbd2m9F!v$}8H=TtC+A zj>0?d1HEUyyFaJVj(oP8g6WXgqV}naP54a+ujGSTuBaW2urQ5By5uCjQ7fg$rJYn) z@^HdMq+R@3lJm@A9*bY8UEx`3=45Oh!4u_Ft*hiAohWvD@vjW=nZ-P(XZu6fwgksx zcfH0n1JyaiAtJxZRS8NQ%&EvBJwNsF8TTCyzeaX0N(#cG(w(qZWTz-GoyO_N1pAl5 zQlb#Ma!NIB^Ux{!CfO~WL%NfTJ=Suja=7)%=27!Y_Y*0Jcvj}HZXqpcMIl+0m^X- z88YjHWs&$i%}%*^^$nM?dFwmns`lrLg=BL0#`-|1d#UF>+}89K>H~2{H&7Ky&M;M7 z+FLK@jh=O$4!C#tMs1Q~7zpaBmmQ-j?ape*W+73!O` z81M<34GhdW?)u4e$#j(pT7+Wy<@z!eWr!W-c-&@%5#BpXFXQB$=#X3mq|8ZOZOo~% zU>eQt8R{cEB0#&BQC=t1#Ukt;L7 zVXvOlOPsy3AAFjXEq(AG04}wjZ|M&RK*SGHE}0&T=_RHRjt}@&@g6kS6AhsbZ}yA1 z8ov+K=UQ*V&fJ}EOy`{a=dY9?R+<--2Zo!rZY1wnJMq~TqfFZ^V*Y?)2e!fuy_K@* zDK=$`=8{d9!4<6E&6=(p4dr9jQoKK+bH*7RWmc2R z0JDcrVDS$rXBU^9@Nc6sSjUR$FQTu!YfIZm<;!6+qW3y3QfJz#38&R8wuR}&ZgQKS zY0FsfH5EVQ?~*DrkxN%07cROmKP%}rx?f_o(&Z{z>e)iHk{kfpTJa`14ORfeG9lxFvpCIB#H(>4OFUk|20rHRQ zRfT`wVa|y6sXtf=O8%iEJoo^OKj<>^e4?n%{|&#qa%xulL@d3!X;%2el$;6dT7FRR zi3miR;lt~hmbw=i@~k+eaBFwsUljH0bLiP1>_3uklEx1^)WULxO16JH+7sXI9UfB* zJ`P2)KG+d+U^LVA_sOS7#cejYlTWP2j647%UmE*(qC~mq%yEclAO5_n+o6!IZMie{ZB**Q7a5~1QrY1rsLkZf6i|7jtq5t{vw4zq;D zdwl-;Gxu!1>Y&ut@2)bE12<^F?#99?%TDx#{eCm4dz>eyh zEP`;dGICns0JM3(fanUs{QKxZ!&N-Gp28ZVwSzcNmEX%_n*G7(mfg!%FwyZekh4}J z;oKZiS$0;*4NHe@GBNzCbnUzoF?`>lN6+H2wobQ>sm^Mw3H|5$0m`t+tN~Rc@n^bz zTj&<_N2S01L@h`>t(b4h_Op5^OCR`|xz-i6iN+l4JAwn>6^Z(tS-k(d5k{s#WH9$I zj;09#%z0V$6c-UA>m5+bh;LKyB_k59c8fYtJ5tI%g$4JDwYVS5h=evSY<|0_zY%xtb`%sko;>W8)onYkqerc=LLi8e1*AIMZJ4*YDXOr{1P=N>67mY9xp zd*8p0%f-egZByPFYt3wWyl;UqG#cuj#{j~+GFArqYhIcdW=Xf9s&qHxfo^K;K|8va zr^V}7-iORS-{N*j>*NX^?Su5!un_VVA6$Cc)9B@J`XKB4n>Qwotr!pQ+*NU!nrW2dtcaN59W#85xYNBGYzEfXA;}rRP~x;0gwI8n4PUO#v_in(yBSv3 z;Y;BCb?9_p!oqvrcP@Z1!$sjr@4#9P6sYXI8Om|b3`&6&k{$d>;*IvwASV27eCJkz zaI5kIGvY@1uG?e(^k?TLR=e=I8$~Tg?m>k`zv;ft3LJsHBVFAYv$?>f0BCisMCm0y z{qPf7^_C1W)%=Bttb<4#(LUgY?T|~GxBMmpYSy<}UIB$O*0e?W;_u4(Q$Y{aP6@-E z7jLDhBZG)4WAu`z1ilRKze2x1YP9bpO7p>XRd4)cSwBOr=3Wdw?);}Ck%~=@HJ?H1 zF7Uf;7hex}et-BNj3RgXA@_f$+Va7e4By+=-;!3c=>;zhUmF(O!s{5kqc-E!4A>0g z*KW8Y5V36smqZB++z;ym8TNJOJ+I@I-@f;OLfN)QRwqChZ+JOI&9_jG^~<)fex~pIClr@_*$0ImE|1n@w}MXsK7L|g!f8` zn2tGXLIGgKY|q8L3yE*1`{t_QdA%XJ^_KSOWy*PW5>b-*t<_ffB`{#{AHY4pK8LLy z=Jd&>8GoRoeI9%xMW3iGXX8WYpln&FP{%-@Nki(NS(wbz-iep2dq#@hP>G!@;g=_; zFGe@v0H8nDq#Hq&wUNBD_u?kMpB_fvfs>n}5>3)oY87&V)KS2;tV8q^eR661CH=A| z4YL?_FYCQcFHg^FSCYN%(K95JfIHmU_BNcQ;tGXWNP`b8W%?c56bq5L!7wxpf@~^| zd7S`ie`-$A;7BNr8_P8Hg?Wbn{CyM5jsNTCai7K!K-38p??@Rjb;91)10I=EglkF1kM#>nv{dJnfXPac zJtN6U#*=ww)GmJcZrIiUO5P~ZEMURs3`@A|svYqcguq(;KH4K_j_?~FPM=RGS#xKn z&>22-8~yD0A#j-gD=`;S;~FkG*4zOhz6=gGV}P-J4P8qz9_`848k6|0Fkwe%ulcAy z+kU-F;f94mLdU#4)k;<#QsFTIN=?&PFgf@?f6mgiTJz78&gfB)@PpXRGmbnxq5%xu5GcIomJYdR?bjfWx zSf)24_$U9e40WQsr9K<^G(ZF#LAZB%e4|Q7*~7Req30mRoY!FRt|}c&t|8$XRo5J_ z|Dg`|f)~`~P;rBqyxyZIX} zqc7Ty+tSf({wIr2m3UFcvp=|>KCSpY^CNcF4#L6H6{{?t-oqFsQ$|^k$+Y8-)$L>a zi?-sVSs!ywh~5zb^CEy{yaXB^ahQ;;Ve~wL^6hUPz%6J6>Nm_-GxFk4HthM$NU6S8 z&K{swpzjlxNr9P5bQaeGI0o2oxjO&+?p6Nr=1eNXD(<%Xz3ce_m1?T9M8;OeF!OFlE#?btT87L;K$@Z2I0)$|K@ zUv4uOWIM;BbLyKwCfg+u0vQALD`sR#$fqR0_4wzeqr(_cAf`rhXn?wMj8rn^qZY+g z^rE>j_E_xIDVP`E=ZS!7NU_&_^%l??-67e|2!%-a+$?^nU@gaIeab9^JKtW^XYVhe z0#9i+;>r0b#0UR}PK0^w!m+_wf|+2@r#mkL=_mCb^2&_$Xx5HlwOoTY68#@bev$SU zuMoU9Gma}~E)C-XnLo}Jzn51e$_VYf$;WlDrH>`FevGN>jS4VY6%ZKCG-Huh*b9+o z@9U_PajUd#;O_j)$Th?=s;a>cEgt`{C(%DAOK!JpXI?$qg~ZMqAP^4WHtOlVNR}qwk<# zi{<|&P+QqXH(AN_wb}WBCP95x{gPb@sY3v#gP!Eur372svl8xKz(Nc5tV~ZT@m)|) zMU;MzdtVa#W@S?5J!%R18vW!dh9_Hw)S`{+%$+A6Tpte(pr*R(rR2vH0ohGLd-GY^ zn<4>j7Xkk+sJcr>>Sq@P5BNcQlN8t6Q2jg*Dm z;<3tqF_a{af(M=BCF*$Uft}*XrQ`X4Qz~7M=Se|ZK0=^M^7dB7Ca(5ppZ0K8gS<=^ zfI8vWEtPzs@cr6j!eprb`BGJ~Zv={Wj|42IcK?Pd>k8gx{BKxUlNzF&ouadgF8Ski zTj}+o;=e_uxgyt?tNqfGY}Z-LHR3Kf*~kHJEk_q!womU<;k2V%05r-Pc-I8h$$Mo; z193Ml8cP3T1Xl-&t-EMuOqh%hAocs`*d1L#{pk$a>rd29uie*Qssuys-4I*%{0}$p zl4x(}h&S(u1t;8$$OK_>0g*RFt&9SA?3g}uCzB%o`s|Qq^OW9Nr*{t;f}g z=!7q@u)DO&3?5e%aE*6;TfQbG-@Cr3sucyyA%EobrCeO8E2jAbj;4qZ4Ml-5sMX=1 zuIUF?2;?l}e9@V|ACA#K!m=37uFd+Ob50b{Ke`ZsIk0hJK7Q2$2&DvZ68I;()A}kw zz6%b$xaR-0h^UXfnf@qFckO+@FPEDXx7;_h!D9jWrj<*W4cKF|cM)28@>-u<*5PVMFO~6_dCicEvu9>%X{Squhe3!^h9sVWQKUaTYe+kFMKj%Ja48C!IA@PivVM z3=NA1`eieMGT+FSJVc`{9$(?ZmN|dC^D^K1FL(EmaL4!ysKJ@P&q7cN@PRS$^BAZ= zrtP|7ziAo6H`=Y6AKyKX^a=#__Bh4M`9$*P+UGm=cR@PKBhC#R6+C`-e!QXT2$5nV zCsMU!>*qC?n7b)zzv+Sk?qIG!?Y|O6?IEvvvUPswxbHOIMz`Ejy5u!L*z(}zlVj%# zh=3#VUt+B0r$bd}GaCHJC?rhj3*SxdI;|uN;r<`>{*U{T<2gzETvu3Ce`s3Ie%#tAnKDr|uUTEVK9SD!wrBBwW!QfE$LPLFSU;K&Ul0cF z{XrBFPg9ZB$#4pE1J}i^)t1At4Lcl?)G3#$uIKVCn^4h>|K*jz^}wl zp_$wr?On9VuLy*jEQk0m@E^p&;t*OTlK(6HIp%-Tjl}-9`R@M>vG{NIs7X~@0bK~= z(^OkiOI?d)PZu>J8S6J~cPeS1HhMh#Fzv0&D)Qx?bMi&enf^`RPJWpALm%iu;jYi! zReQ)_o`LO`^Yq$+UAI%#{l{@i%{OW4qTGFT_k($yz6WaC{pe^wIz73WGlnw;Zt%L! z(G$*<24Rcg9fU1=kOg;Dasgk%(8rPg?;T#|9GZ?P-Hf+CUe~#3)Dta)YNj|(8OH0_w!ib5i8!Ruks4-?2Xl9%YX*f4I#~F0v-?;SeI%S&{GJ^87 zEKRu>zvXy@b1vs2kKDAf&M$&WmK@j3C7e?)%I-@-mg zg5*l7jh1_LCvlnWhXwHppob04QaSCxuyHB(|K!22?#413$7sX?fr1nlEffZ&S+q{!UZY4v{+UYs{l-vl3_m1N+kZjQ*iS{iogg*vn z88gZ}#WZaeZ)~m~#(Zc-($d{6a?eJTWzNrqM)(qqF~CG4^g=qtI!`8<7Nf`Tge*8l z<%3YJTqbF73DyN^h0G%${JWOjANXS_8FZ}}ojvUT)bx@=(_h0cm}T?-fm!~4vw-@4 ztLZPZ;J?c@E79hQI{M5c!Kyq~`)ZthE)o)3^Cya6(uROGHDxL0fP zk87TNBq&Z?@!z&}k#&&`C-ms_3Gl@jn^>B25jC5^x@(E-{ID_3zY|=C<}P!!klx$% zlA^{t^?p^Jt_^5SyL8rnz3hC{pA*|an@IeqZz0KL+{ixfh$;b}J57rhwC-Z(j&<`Y znXM$^0!H)Qn3HFrSf3^tpZv^0qKpt?ZOqD?$ekB&7`YRjcU)-c%ANkp9VM-(ZZFZt zj|6>Xg(E0kAQ3yq{6%%4>iuz_7x)P;RA-@~HI)8!`NJc!UlmCfOO~LI`JG)$PeR5l zK81gI6xDDPrG5|1Zl@^sn)wZ~5oyP*-$h~hTweFb(%Lc)m+M7v?};yzIz2&?`40^kih18BdjF37y~K61ly zy7rVdIvpe1k)D!ywAMhO2LssuYjq(K?h)|}SdGTB*9DQT5q1X3HAmu|8RNT0aT=2~ z5`{Xcu%M@m#mo{8B_(r8dRTxD6tX&(SX9Q)6wTKF8BH}pe8B%xu}!sWR61W3YxF;2 zUEKdu#hQLGLe3U;woJknX5#;KENzb#YBnzZgli}gZQ3lSCS zOXKs#sK$5$2OcQ{X`V2fcswoogaebiGh@o`w6Y?#-=g9EzOB%lgGGWu5ayI87Oc;}ud0ji)ew*%krtkSu=gs6lkLO0ftb22GRwJKp z>={s2+U)sl?eie74}s#?+aVe5E}DH)d_6fKRvsWanHW<4i?oW-bv z6ATl~z9R@Q4m5rd?;itF?!=-JNyd|QS9un0X|;?Xty`mNUR|zYZxcUJG(kw^&`hlx zsfC9eX!YuzBnqksA)D=WQYYihMcV(gMTNpbv8)4y5=|5{gqchI`>Z80(Jp$#Thjto zZQ0z(Q#_W=6edtc$k{YZV!*l|L(9rkjd9~eivf5Of{7x&o3W7ZW{{DoyzP#bq7pAf z<~o0T2iA#XVS$t_->}-;mt>0)S9m}ofv5F zCl?URq&&yR$nk28JmZxCOW${ z5#r2>r%5YbjTM*(Q95bpAM#12vEtw_BF|PJpgAW}LDI^R0Mcq8jieYzZ(Wp}@y1T? zAsz$--KZ00&l8q|C2J<5-nnx6{K5Z-MY7|Q=4zPKO~^ZPSY8;Fk#FUOVrnL=EVSup zVaUSicp|TxvXc0^j)$7Byi{pSk3*h=!owL_6GJ$N7&UH?Fg0>ThO}!%#J<|TZ(75R zxTX`c5^rZn4okWGs8k>BJ|bqkcVvGxv{HkL!|i|@wA}*(383omYaltD2PRN^ze4H8 z3sayMMU8JLL!e*EZrcJN{#NyqbF%vrjFTGG~)ZdcT9WYml z1t;+#{(m@o=jcki>|Hdh*tTsuso1t{+qP}nwr$%L+o-sblkPs<=j%TA{zl)s#~%Ct z_g!nR^DC1)0!=~+0oWo@>Yq~P44PX&>XcF@L{|Gn zQQEArI`?J1%a3f3X&a;h{HZysyI2Fi3ybLu=*Huvx>TOwv0Dv1xdr95_R5C1=Gnba7&*C z-$B!AjxZ$=Gk+_ka>Db6zr_>Gz=|e4mdY`muaeL}gM_ISP11uy#j!&8dX-TABa&Mth0!8uLii9zv-n zz|E?VNyG|S&BV15w)AOijE{xB>vx%uIo-k^QKg_=L zU>yHCK7oXq9OSAV%p3zRsZb<8tIQ0diUw^5dNzhonvce%sB886$)cJ^0C$3*W&xp< zMs+KP>mR^{897RWj0l_I9W9KcHYA7v*xcp=bOaNPq}EWG?{x-3>4H$75H?9|AR>hV zVZbW0C1KMIW3wfrvgI$bMIpSJerdh>cB>MgKBkOUljOfUXmc4qBDZ5g@x-=&TBKgd z2l$LWad93yIK99#9Yb_VY_W{a?W}0`JTIe+Ie9f5-PCRXO;y6CDwW3>{c!o`o}%i~ z6P-mkR$m$O1n+^J@i{1Rp;20`q-QH}_o9-B$FUiuEjK~+T{Rfix z2h{5B4!h8G#uIb8rJ&1NK$L1HiIL3KPq_Ch5OofPFoPg`4e3$?A;*L%o*~zy9PupN zQ7$vpeDCx8>Yu*BGq*_R41gq1tEnu%q7y7emqmBWejS$C%?)na!BL)5VK;GvM;ns2 z&lALaJTFry{a#jOYNv>1W9GtgTi>;hS!~cS5EIBSI`0|_D39s$Cl6Mn4$`C+C{&9g zmG}266OyAA47DR7=6>v~lF0CFmzpF2nFOc6ET~0(ngqY7Cpi1ZcYuq8*rp2t%_*(mZsq-J9!Pj{z zU=|Pn0QsnYrPcpQLH@^V$bSL4f1)`-Tbu7hNXKuC_nnboZ1*>?_YY`StoRR79pcj2 zfZ7gW0b2ZfpoNkONT4b;E`?N6HAAk7AR|s6V~vTfLe^p~UL{`MK2krA zz$a=?~7=Y4C6sg6)kcg7J5&@~XUmL>T9b-h)n`Oj}I!OQ#u&VIum!n2uYkb=x7 z){r4SllH?7jXeY(%02Q#Mq~F@lvCy0S6q6`Yc813vedJ+m|m%yn*(*-9@%SAoNz6s zQ8c-mfZ`00IH5^RPs=pT*7a2R)bp)H^oWuH@8@0CKL$?j@sv$T&z2sB3zkM*&OE2{ zlDkW6BLj$xr9MhtmSAn|QCbh$0x2xwwlG<)RiYP0V(NfVM6g{Ms`qo6nCu@7Sz|b) z%G>DT-9tpboVi0@6(5HAI==5Rv!Q+F}nq&+u&CW zn4&LFU$4Q+^vnMCT_(FRd@6SK>QHw#9g#8X_Xy7lQ1)45C`>8DO$ z7nFs~8xa^({~jjuJ1>^kgAP5qBRzC*Y;NhV>5T2&@RJ6Lm9NfhNm zP9M8uX*v`JQ~t^lf#G=^L-3^2gxG0xd?`F9?n?VT(%*>6j3?i_={HeH`!}NUpJCYC z{}oY@bFj5DcKGM+{&%ioX@{kX^0|`IbnlVK9&;pQuA!x%pq^3~!Ym;!pfC!zza%e^ zxW;m3NmE@ceWYElL1ylrBr3VnG^c>Mu>jVTU&OZsJLWI2sqaS*Jw@Mliyp#ftQXP? z-OJ_md@YfJL^T9`Fu(0M+kNsUyYWJ|=WDPP(5n9elQ&4b-b+9bd{k+RlC{-*Eoc+e zIW&YzKg?KS@W0{NK3!pGhII2TYW_n<1We94NV~bAfbWmc}T$O7^({F%f4PBIa98R4Imd zI5-Ms3vkkVm++RD$G zkM4svl%Fo6&Mf{BMua+XM~OOdQ>KjG8so%98mpO2 z?n0pG&fh6>m+w>H=ngJ&_QW6@SCMTKz097n)7X^E)gBnGmF{D4=Ac043_b)f)f{BH z2@OMW>L6dH-Zlgr9;vFdz0u(8pmOTW-%-xk%`u~}$sSELB+bsGNC4aT6unA{?1iuH5Y(OIRho|rbHgA6W|gV)5d0Z3SFeaPh@lr^mND( z#P_dUq&m+tB-T!X(M&gcXdM9`#l?at4;2a?1EntDEkSf|)AtK!Y zht>V5rKT$Dg*WUcWN?LU8JS7Ik{&&-8V>m;?#2Q9u(0V#OfqVNCI!_^`#rn8auhE{ zdNXroNt!@mK>+0}x>;;feRc-QdLn$5%Z?bVwVtPiV0dA6i2#$jnvK*K@TDD1A+zCHv{u8dxV&&Z1G`vb%Dh5ZY&lln-_Hdk!b zhe{iyUIEQI+*LwA&~As+!`Q|or=+fFF~{zhPUzQ&UD8?pbkRwy`zO>I%-lYevNl{i z(&G2$vGyFn~ z57lPHHXAY}Zzl-i3bh@1_9U|Yneh2wSM2!Bq<`L>tM6e5c~gOsS+F)nXu zD1<)Th!|>!1TEx1j0)7-Q6M42I*=kqW{oJ1Q$DI4ek%E*P?0L&@F-Vh zg$2*(E0Yct#;BFKEVXw;%s||)3=OdS(&7ojfd+1iKDG^giOmE4p~w_W6+g&Auij(c zp{}G%9HDY)R@4}?%wlM!;Y0Ooec99zUIK6&Rn<6n5&&?43g|!;UUcU-8aVW zORFNnri95E)>8QVtxdO;2pcX})RPjmg0N<48J6o~P>g%Q4n0<>{B>$C-CFrUJ{AQ7wzqwo#ik#;W_@yR4V9o#U$+$$D(P3^=Tn5S zu1M{fWLYF^hV&J#9`%7^;t>5fHSj1C`{lx)vqeudPt(1SR9ipM@v=roTob%^L{|r} zPm_4Qa94Zh+k2Vvzs%C;?>sDr{y;1;;Pc`EGijp7r4d>vAb({*<@b~Wo?GCYBi*mi zd;$LLvTl%1ixUI`0J!_N?B4&ptl9pn%lco}^xsBU{!9PpobU!GHcd=LY3Ve zXwG*7soxdQatlZsVI`3!F2|h-2D_Cr5MrbKGx)JLc>8(a-U&PwKN4n09CWBhCo?8s zE}n)G6DgyvNM1f^JXo7Wzm1+>ty;1%UejV61wqhSWAHI0Op{(`Z5eG!b90Wu<&AI| z+B^n zt@F26lA*y8TJ!zDK!E=fF8?2=BK!-N|5a%HKZ8B9l{6I><={VMurM(PGX_72m9mF|UQqtX8mQDn6`-GIq-Id4vxzbT)nl1pQfG8=n3CxDhDS+a zJ8Or5D%qmA{9;*i10mgN$r4e#+}7Hf*X_`DEl;?CRM>%fy$Y?bLVnXzak~;&<#gYi zB;k5ODq=H%>OSUj?%&7g?;2#dm~7sv-pXA_3gmzhGPc9Zx0^9uU4cptfw03^f%<$7 zE8L_(bI;^ELonvHjLf3%{tBx|GZ#zl2vTbWxylMh{&CxWd$jGH?`f1I>CAtq-xSGAyki94b*OX2ea@Xr96l~*a>fySb6s}(kwYH8>Xs3-< z!<9TPS1UA$RSB&z3MadvzD-Ret|-F~;w@+16m0-6NE~V|B0?`<|T|&{4&QSyutLE0M_Mn-!ZCpYq)>O%O1__ z8+q%S7#BOAY7$`ZPzn>&ZfN^f~->~23`!xA~AA!sFU!5fXfc<~{ z^Zc7jq4|ycF}{(%3ypg=yUe9gqJWlJ1ob3>b%3}rS@qT0P`PC&adW0*rcF_ES9w=u zjfyxn?U6zrO;eLxMhTjSKPwE(Fhq40>*IYNd^4DaumSL08PE%!r!8S?ibof;B`bLmO8YiQ{HmsPuqoMtXKrdiesC$GvJLVx{5jA$y5z||B{`V|3 zUOL%l*exZnpGUfST;inlPJa1v%S7%}Ch zBQRv98!Od=nj~VIB+M{tDl^M8u3EE)(Yun;nL6!fttT18%(&?dOe1kuQWrHr%0!`$ zgC1KfF&%gFACLTlcd{PDW8Edj9h$^TqMRcnAU`gX2=vdw%rSURZ2stlB&8s5iNAAp z?>fe#+m%jb1?3=YijV%T%E@Bf7x(nYkQpxbu@LlHm`|kTiMg@6tlE3bJj*96zU@tSG{X)Z#ZnVL*{KaiYT6IpQoy zzMhqp!IUYc5-f=qzp8UAA)Awz77!2|4+wILwh;sGbkSwCR4dg;b{|BOJLm!mpH7BaZ(!9p|9lPkhqGawyR?_f-`W8)uJ#W|FliNI9cMjg-9?y3lOe@7~)tc zk`dHBC32l$wWX$+_t53DFQo12UJsp4xT&gaUh!K%Zdedqz8-;xvL`%LePH+kUyU{L z2m!@&zHnEQvL{+p+3VZ!+-r*%wb$y0K#|=QN0ALbGPhE^)8;PRH_b_(lVcp}~YxG&WX#L6s^iE=1c=PK`XS%7D=>u+(~RocUNXjx9wd zM%sd~BqUWc2bWzsX7oD@%PD({V$&M^G%8zTI);g~ECS>m<-oGC&iL+RrwQq`_T`kJ z$OIiJmq7L!D=VX$o|)ANjdv#raYe8FS7-(9&4x;0Q=7)qrDhS?s69*V5QEO`MIENL z8r<=)=NmhpSFPR7&kYf;086&q4)IhF77y43?DHA7t=vP*V>a?aISVA$irG-CxZT#d zdBr7$fzIAtZG@{!>by@JkO*BzaGi=;w8{GQ#nt0Urlz{gb9C^sL;q6S(sDl9f62fHtEGPYr>j!A@`2NLrUQ+B0mz5{{ zNhMz5h(%L-By7s%%4qE7OOZl!oeTypq8rS5Q+J5~rraBF1Ip zxXz>L!W7(PdIVB!5$7~2dr-Lu?Uvw}(+x1XUZvz}aKY**ylNbUEJI7eKK+nFF=%Y# zI%FjzwR?^zC--v)lMY;O+r8;#{*Xh9#}jeV>rSmwp-+^y1${vv8C4L9+M*v(93o37 zuZL?3lea$uOn4e29F=mn5QuD**yu|Lm8`*57iwC6+Y2}M*{eIYxHC8113=m>Zu_2I z<*sEtMzlU=bxI~nPnSn*g;1l1|1!)KOO@2>J~>fsAYdGAQ)3k=20-s}s`XT;8d_XptD0N$PL zhdAUeolbP4502#Sz6~^&&~`f(G4Vy77=g#4tQ}41A?>Bf)#jZnoC3c@_X(g(Nor$T zaw()YPq4j|T~8Ki8YsBnYrt@UCx=V2torpzxoRgY~}x3jd-Uf5iuC|4;^Ph~2H7v)NrftQI=v zm=o~ib=s;IIh8-i8*nz+Wdb1jtBRXxh%C34IU)AuLwHXE1P#PL1(~q>XHugwD>BocHXT9LH-OQTGR5x-JksHlM3e z+BEJWx4I9tK5;%uyNJ+5A1`Fnmn%a^-kDk1+qnI`M9Ax>!UVqSesx^l;eF3PW_{k! zj=mhYw+D-Eal>%+FZ!Udx1*-W+~=Z5ypsd76mC^OxuXY=Ik$#bIZC%lcx=1oD<43; z*@|{Kxw9|zIJ!o6spwym)bEhKKFR$(BYL`~>uhRI(x5wtWfEs5T9Vky(@I-nxZ#iB zVLtv7Hbm(SO-0U1lGLX?yUBbQXK%k$K_+Y>$qrOf{m9_CDR-|}4LbTt`rQ=pG}1Dc zrWvdm`4i6hi6rVU{TEw_9yOTmlKOJ^2eV+!A2ggq;Dn>wIT}zh7OT>`^C=V~HH3(l zPP!g3NT)B++F0q?E3=mbQhYWb*GsZEj^$ZNc0e&D%popm!tGcNrN@IgwwI^}5g@H% z&cqFAbEZ<4r7l!nicn>5MUGaSH_WW@-L^(_>h{CqXvj#htXtN3Ah!_ILM5NTtfzuf zvS4vqrraDd=!cVjZhFXBEyTCGFQ%JK~?=a+XSMN92?FO5Y}o< zXOBguuOU*8) z0KRFBy8YkmY8p+;ayCq`4Jwh!&bqqc z!C5}RAT8eA1nP00mO5i>RV}{oKnzqQG^S3I_bzs4d!Q=LzrK?w=C z0moL`35h`9pzhv6I~i1Myw|!m@ECa2k@fT#TsD zAe_uMA`*zk(sV-Xrm#c(^d}0PUizPVrU+qib{HMNaMctWd*eyNH|y`OPtBd#Z}EvPvHJ-{P>p?1?uyRCH-7?{jOZD{RQXveJ0 zlbVs6cuu_oybF~3%4U~xTI6ndOYE9Yhgj9T@Mx=T9YRjLw!6eUZRRh} zNfd;T@$QxT&_$xxfb#SN{iinW_n1t<+3v??z;`*}8>KR{u3%!%Gm6tQ%kiJwWXd+h z^RlveI69X?WZmU0h))Ns5E8;OfTx7gD>Rno(|Upg0$|nc>V!+{8n8gU&U=2$GR+J9 z5q*Nb0L9ggx0W$yvyno0+!@9LWj9FB&>#7XeB*_6eLO zh?I)SGIU$@0KPy=NEn$T3?+sz!G&Eph(L?{{vst>gSrKV??|!Ta>5_&H|P`=bGl}? z)X_@->=UsHkKG?TAXhoetaoz4I@?MVScz}qrJAm{Ak>?y z^~A$1rFKJ%c8e(ZVisVhOK(~Gu_d(@EgumPXB)~u`e4E~d{wsPi53$dRIW|aF3{N(?mfYs7fXgrVp4W9@xlH@*>)JHXTzKfx`*O5UH0 zbTN{$wtZmr(N5*{b}f!8cTRQ~Y*C(!ZmR^G0_I(wVIf$#{L_prv5mVWn9N3X2M(Sw zR@ub&l*SX5PHbH<9_RWla!`p6HghBxLm<3TAyj5un4}Q-5v*t=9=PJul8&1s^=a8a z0ph8PQyioV%Ns30eo}yM&@LWW-L`!@Ei}=n^<$7Yyeno`jC*#-=jMKi1g%#<8N*ApVaKXk6%^pQ2qK49DrT9KP} z@=<$BFW-TUKk&|2|1iBC(m7##CeIA*kfZyS@_Ytz-^xzy>ZT3%>hJQg2Y&6_5ZL9e z`GEz=zS%AP>b)3rjDdT-3VY0lll@s*cukP`Y>)xpZFEIDBz{bk+4y)ug#5&mqy~|p zTrpteJp=KlW(zb+r0kY^C(SjdG1Zn;K|I`$J=EFt*O6qpBMbg;HSmMNMa>uR-vmE- z_H#HIZ~y=}Uh2BjiZm3=ue%3jo< zfnt6IAzxu6A6T!G?=BOGr|;*@*4V^KN;B$A1L zn>32MZK~zg%9?8aXq4G5G{cl!UM>kP?rg4|88+SP4>`yONxgmhdWF6x+1u{cAXAD$ z=7ZlG`(kHTWo(uw@~c}7W~Ghq z)FT3meKtVd8YH~=9{xe0J@5wD z(H3~h_^eQ}3qk3nvQ9}~Gu7Hf{}S==_mc4ba{tAYZ_QT|_^;dGKXK{L|8KbT|8Wmw zD@@uf{zT?sqvIN3Cgqk8tSnJLrHGU%kf0U|3IdWR64s9|Q%Fr5Z?ZpHOTHrPSCv;2 z0t$!QErfU73PW`nr#891nBsVz`FQ*Dhs=)^c7ohslOJN1=8}D^&}1(-SUZ3RJ(|o` zwEH>ei9UiZs4KyuCO85$l3Z#?pya{O9#=B?O`iOXs_^DQZ-pSK!{@Zr7X0;ik0O6A z(j-F;<1HUoo34a2XUx1W{+wQckv+NI_CvWYZst$WF7(lfESWt0B11n;P=1W3zZBwh z`*lYKrfX_FwdF=SSJS`Qi_9ZM8b>q&@hd z45=S2vToh(oglMe@cz(rL!oEID&@hPfI+I$&7*7AY0p-*FoM~=8W17PCL{eSxExGK zG2D8xx8ntJUhP8HA<@`cza-Ufad7Xif1&C@#RANVpv0=~Zc_sz_XPA95kJ?n=6n>J z(^sos!yV3=g%7aJP5XxNI)3{;+<~K}$<>4hlwOlL{hm*Fe>()m)q-l`zE@xH-&TL! z(q8O)!TA9>I*oScPBr(&D^{C{?%n0)L$&VA>4^Kzc2 zS=V(Gj6>kuYfrdOI8Jy@jC}vR&%gn=>;uDP&`*UTz-gf;+o#!%yc~;RROjpuwtA5z|Y6%K$6AgT_n1Ez0xM(~F4YzVHuk zf|e8!5m3%Z&&a?wG|^ys9L&!HDc2QnkIgToQEnYsG74$8wW|8^-i^)uN|3`b?1*1* zT4tQ$9h53h2@1J2{~d){x7LIbW~6{L)pM34S8l2>Z&{23UlptdkC}_5N0js;rx0KEWoFa|jA!8F?UU)gy$PrMJ9A3Zkvx=nTs%`( z)EGdr>Ua?Qbn>*seX%0z>Ao0s%c%O(j%-Q}!X3Rg=4}1OFzC`qGxBAh3@Ds_X8;qs zq*NFo)1RBelw0^r05;z<#3PE#okYTJz%>dZa_yG^N_t{=-C?C;Uk~n;$ZVGv$1o}@lfi^?uGop z^E=$(zv;GkFmuJ##5K6qP(HltXVhQyKQ6UIvO}>eDdK1AZWX|a-*W4827HHxz zkWnO@#HrYt48zKjzR^`xXiA~6u`Z_lD<`Ee(k@U$=qs=GnslCvB6R9U4M)7azNo`| z{VZV53VA#ra}<6nM#0wjJr+a;34YLPaR43qT4m#=6Jb*;>!IKlFG<%#L8!v_d;3W6pPVk$^^a(+VO_B$->zAhSY(+T7Msv6xP?z?kus^OuoTL9IB%HzxU{NzdOeZ% z3@SCsreckJ@`h= ztqjs8VKY~Oz*posH_=d6uER^*_M>@sRX8QH4)=Xtkh3cXHSM}Sy@R4WKnYejs5MX` zAk~;d_zS@N_INIY%$iTce3k)ur^TJw#_Pv157|1H(&^jj z8=4u@8QNM~+uAtNefRH}G12|YbN;6$_7A+7tp?+zw4D64!-i*T!uUEPB}Td@NiYt= z2q*z0{u4-?7#(p63|($84tl)Lh*X9Y!CbkjqoM70;kibc!uf`XHnkavekAHu%W|`& zWvlk~^^>L+Uq!XbcE=SZ&v#c(>bMb*(Zl=E*28t@iSG>0v)2|IozGjfEwCEliiT?L z>&wvR>f0~ZzCd55ZMUaO^<$s?zN44&;FX`5Z?0Vfhu{51dp{w4M&Q28OOwBb4^OzC zp-?}HBXrmAEI&ksZE@USOtHrXE=s&Xh8DlB`mo#*(Rzyat#N%v4{=a#?k~RkG_h(Q zGWh7-VXSnoBLD8^zJaj}u3VvnFDb(vsSc zwo92Xj2kA*4h=#>G&0|_7URuzi)BB~dBhf$sLxWST4HFG>b+HL@`6%HDU&qkf(^Bq_ z%HZiPYHjK1UD;FS?QLk8?bqn-ZRy=jkXyoYE@?i%{{z!D`y=jFX20$@I(iz%T6>`> zs{beRDV#N|5ZL&BjK~5JD|k^&q4)5|-kOQ88M&VNN{5qchuM4NPY-QxL2FS(Pt`vq zEh8lXl&C%#jqlEGq=EOLA`JX?PJX=;k2K(16?gj0&$4xL-ggt;jmXV>s zGD6>6K?<%uaR@TTEh3x}X?z;Oa(;_DR?)GO>tUEknvwnX>;MM7)X8WaJr7D|P`L$Y@g9T@aCv&F|Q6by&&WI}FF zQB8V)Bn6hLiN}`I9yHRUa1;W;(8G-q{t>o4@t*ubdJl?KV9pd@d+H2l|A}Lyr*1zE zZAgiUe{tDl*M|qwBnsj+%*0Qge^4*tatY})y4Hf)QdCMZRf>*5m}~9LFQ7*L80-e(NMb?CFPXmY=vNa!#;mn6 zk`SbaC(JTtlHi~a0(h7uVd*hz&=!HDmP+9nN9|ybN|+%7%!{gDb_#twmuUZaH2e$o zvN#JfBH=kVGI1W#`nS7_93JH3BH+r@p_7X0Xt_FBC8Fx}7n%tDzGWf|MO!LEn_H7` z2zeQ1z!sFkDCmS+Gm<_u(<^misuIHv1uY^Pmwl=le%<-Na&4k=E>_;W7PvgM5plqU z=ver+)IeLzI2uSri7;H0;0x=5qct=7#Rc3@!1j+O%80B2wIsO*X>J8&x9kEXYJ;oD z>;kEzvVoJK#)7SIQM*>Z=K;2(p;WuM@B=piySh!Wf9NNmk+Wn{FE@nQZ0YY6sy;OKX!03#%(j(@Kq{?O~pRE-j9jJ5a#$t!88v7@)8pyFi8IF_cD&8jT1Js1z{xhqFa z4-!1Z5}f5A&&3U${|yd~DTRsL0xju|!^i*w|$)KR{k(i#`Y;F0NQ=il0vT%}H=g|!-g zfPww#&8fs%e$MJ>w6?ibJhrdAo2=!JPcQ9Z9hpkH0z8~9-aDktMX)w4irV0+0=-pC z9T?z`Qa#oy;HEhLxm=6R1aY3xjOU(&fGv;2z z3Fd;lQ{U1tqt0)qCw#Q=%US7{XaT19Re&89mBWyh6Bn>L24@&-<~NcZhIo=POM#vg zksc|oEI5>DE)_pF$oYs`211)J*)T;riB26pms@=2h`1pMFrJs*nZj;P^fU)c4RKzx zxXcpIIb!D)xd7=-q}a3#!F8RmaV)_dnm?^?=BP(^Mn8Ne*LGvcnUtzu_zKusw7@&*gZRWnrMN{wwr5xQj4Sd+QRIZ$u83`Dm*Y~3O@7W3zLY@6;|E>KW&8zE zoTH8lp?gZ}Wcp*f z{8IwWex2X7qnB~@YC(xNjM??N?Fp2`{25Omg)5U(D@F6h8(;-ND?k0v;Y1=+3v8<$ zjF9T2?Otmow9aY;dwS>{u5c{75@OoLRHdXtJ30N@ijlFEaZ_6@opG{pffuNko4FECjnb zDVSkeU?O>OPB+l(E~3S`Gkdg$7udz!Y#a2BFjVut3b*X~6Oi#*WRf&r-jsWI!(k}$ z9bZACH^%D0Xd4V)f1q3N#_viuL_VUV+{7U|yC1znnJ*~6`fKlSeFEX`G`*r$?NDo> zKyATMY{QwmXzp)o(qeZa5kL5;2j2@IeTy>tL>Xgpgjvrzat++jl>PZ5>Mkg>At8Dp z+2*#eW0LR4iDY6K_aDlVF_MFiyckWtn|FD}OrjN8JG70jM}M^3^e zN$@@(*pO0Xa$W#h;Zwyw-QZdgQ>As>(R>B7BE241U-A94?&q-9WI5Xgvif)S0hS}i z+nu=NXNo1qSZC0eFBoD8m>A-D37GhzE5R$`#V9{xkij9IKw+fVe-CYqiYwZIJIWGN zK8PD>=J3muh8Juuub9*B>O)^Ig2L&QlTkfW)u9<3;bQ1=Q@t91~%*9O1KlMnde-vD*mdN0AEPwfnMeYYCJ2`7t4TN zqhu_=bT1&aIgyOYrt9}sXhwp%eMWYI1l^>Ti1UMHe3O}*E{~h_OPp?xzG|a!n3^+6 z7GJ<;VQ+Ts_~9@3(hy_MRLwe0lk9_o`Y^w6vda+`DVZB=N;F7Y@I^FcU}vxx8)Zvw zBl&uXG!GkjivMN9pRpEURS&~!-@JEVg}e)>P(y6>$d8@E`w1Cy`XhPLNAh?P0d?zl zbkNn~u=S{g)k&qBSn88FbKk%ZJZX5`Fr*grfv-3vb{cs%S%tk&m^}-O6l4wzD8^(0 zk+ol=B37~>9Tc$SivVvKfXw57uEY{MIZJ@LqhgF_TzIl^J#^)dL?X1pWfQlZ%2s@; zF~NzHV6zs(fv&7Nd@}uuT$2lfEp>gtd@D^v_e-z7kbSO`#e;rh{EBydtOC%~gS>71xf@Gq5IEO=R zN&l&!?NrSZ{z~LDpRgs2g#O@$)UcLQlp&-TOmHkxpC@5(7wEds6pZjN<(?u>O)L~m zRnc&)4%JLDTu5Fnr+rRP7EDyvxg@~YJdk4Qyxs)*i_$a48@U+65!a;G;f0QI@^-cn z>u!chf_d61WfFBEnuYt9#4}wO(-N+3sl_)A9o8gA>=jIR13TL1SqgiWr{ewD_yWH< zB-*C#6(G1zog)XLBRA!yT)!(l91@GnHA4v-UtKh@xG5RG6LsVS1ts5OCCIS-*3>E6 zZZAr?Dj3{edKyxY7h+>VW^}HqYc8+6m$ZJS{~IPSpj)fyfbRW;V zxp}Fqve@2vSu(xZDFMfZ*VOoXV0(&I9qg+Fj`g1f_D)RbPRuBWyGM@Jc53^~%$de% z)2R1R#%{e$$6E{=woW8kyoqG{K_1{w6mok76%8SXYJA?jdx<3Ix^D$jSdQ26bYD(yU z$UDau2_T!mK{o&-lK81r4G!=0mnc^a3LS7PQgM#f zC7g)JCoA(rV4@QEAXo0&c56&*!3e(+Vo&hcQ9Kv?Y=?VDeyVs zJ>vI;+gY`yTBH*>PE^ZArwu)rS*yx7T1vQlP^48ZY$N7JN0aSVioY#Xic6vxkfi&$ z_JTM`m{xj6$2rBg-ReTOV_7=#K}_z6os_IHouXG-0xDUBv=~sY-AJ+&X`jjx(%=DM zI^Awp72=3Xa3b~F>ND8=X|1WVEc=WWHxt$3N-F=lA1*3_5yN789?Gv_PxmeX_BP%M zpsz4%5%u%(lk__y$kL1Ffizlos>>qLD^RQOE>+?e;p^`NRgxWY_sT;ydfVj{T~c>z z>BObVY1^bO)*Whh>6T!3;YNKVUsVjGxJZonP&@l&#ZK^U9)xzwE z1sBRaf+c-8+F_bUP#-kb1=D3xhk3Z-LZ6`2qnCr;zo(+io?%yQ!UF&u;<`A_eT z^S=^K{x9#2;U5x8ax@q0cMF4%=_>{hqWLLBS^Y~EfDkdHP(MVJA);tZ^nTwSIXgh8 z06M?$XqAf!QS~qGoK`MBj33ZZ1cX9huH{7%P4YqW5~kuLM%CHUO^jzv@T&aiHdV|s zmYG*d*_}!GvT7Za2m91UHEmADXH_S~We=cy-UuIPZ0QI;(XFbLmp8y~lF5c{5N(2{ zUq02y)sc?B8V~I8*>2^Tpam@QacrQncf0H4U-DfeI{z*y4b@x|Hhe!f)W5Yc{HLA8 z@?X7~e@aRsf9+w|R`~X?K3ia5X!Ohce8cn*nnA5JBF*wuaH#*@!{E@rolrxPMkLU>-$JR+x!$*r=^iaZ*t-~vL+ zO!W7Z?+)W0HSdAG90us`B-#Uq#qC28$;Ur0w>>Y{rozTy$xe!{lhE@{CW-tSE$0FH zWfhqQ)yrF`PmVp-bK`c)3uDw|2akO0Nn1GE`eUjzo%#2xTAK(JCM=ml#jNd}igLOe zT8`rg&LnG9rvqh)i@-2@HE*=$MrCm`S^XkWR!dR=rh@$t6iDBJ@uMjgldHS_Cf1zYZN#VxN z^y)WTNmrfv80OefU+^Pq4UvG7NKv}^H3Wp_{mA9uX$`Oxqev5o;D<@a^a#i{*H3$K z)hVm$7AQ_d>7a#<)MpqS6%DY=u**8rirFC4(5$4N3ii}kP%-WfL5{8kAw>5RV6ue% zUyQv|kSI~GrrW!1+qP}nwr$(CZQHhO+jjSE8?(|k@~ce1L1rLB#+rFciIr+DQ)}JUn)fM3ETpgbuLNmSLE*hEcpwJ z%mD8bPKe8EyRIX77u3K9-`<$gOT8}O!#K6yOi_o5!!FszPsSPZF^o9CM(q8E_ooXI z^Ev*nbwTa_*}A~=-}+Vlf1AkvOu%aXX9AY*bw-Mm$>Uv?lmHJHUSb>|;(*B83LgT3 z7zyT2NF}{Qs4?@z@C2}eRzf5mzN(ZCig2@~h?eqjX1(G_oMv0emg~*grj478+m`Lx z$Hw2n>)&m+vlA0WAmN88kFy=GxsJ1+za0OH5(nLQJq}0+JNcozg2j%zDm0PXFGLw8 zNFYTLl#shbBGRYnN^GIi50RDLO)|5z54lk@ZUe{PrA_br8A(s1O&Kffq3Y64kef8j zW3wDbJhl}l>Qtt6;+>H)eiK{!>d+_IX?{r*Oq)xTS-l4-t1_ld80Q*rVyqv&h;d2x zh5;3Zj0=>g9ha;d()Cj5+md6nPm!lI4h2ck?hh?9v<5y@8P(2^pRIL*vQQfua2qBm zFn5}vjrcRut4$k6DKdAO0gdoi28YLrQ$%P@9Ub_gn!T2&i}0LUfK;3RqAzG>7-`HSX?lA&YyyplSVjendTfCQHOzdAry=qhDI| zPWG+P5$uPsJ&OVE1kkVET;g3q1%D^VqZ8@`{K)Io?|DnfiP32`W(nogufk>B*J3`4%h|)L8_8ZP0JcPsIXSzz1`JA; zQ`Q}o7T0uJ^9Qh8;tYT{Uj+@=LW@IKV}U<|eGr`wTi=Nz%Jet;YMJT#v*8FOOd+V)1zO*2vFC|_0>=ehNlZ4w<+hs25@rOQV=}ZT)^l| z5vouR8v9SMBpR`-(PNaG!V2F7f)W+{smE$4cU+?E(dJE@%v!#(d~|8?Hgy9dv$)#;P(o@&pdBL5SS>4tpd!s^H#H)+uzi0iwoL7!9BtGu3?ncYFIw5-CxDu zO5H@k6oi$(a!H=6HcIjg)XFF4z(&WuG$FO0iSI+JO)tZ)T-)2z*`PerVnj+f=w}X> zkR_`5o=-xKd;%WKwi$&v8~AhXOoaTMu;7tU1LC`cz+*J%x{VrrI-cENWCfPRepdix zemwfZ686z$LYCMRAiHPoJJZ-lNwZP+9p`jG`t#G6xF255gcLAh75U_g% zpy`*tg?B*A4G-={NcP@ElMcoXb@4|pe``7&U-fPZgaUM$!R!NR=i>|BFV?Fw3F@ z+L%{^uO?H!+_9#bGH|U4lX|a*l^K}K65O$Jym?~U;7{4Q#k_3iT>kfy34Fo{avS=g zssk42*x)I08Uuu^IC_tLA$26Mj!nYz2@OPhf;yG++iM?ce~45QTrD)Fm7=7uIr^eVKzTx_as8w zQ`LS1g6!_&c;`B{T-Nh@48cDFevIdK(>Z~tooP8HWINXL77qOsxrb*<(zynX!|3xUe$N9 zqS?o_o}6|=)}TMQx9q8sw$is}jnR^Jq;K^b!zOa1d;5=RN!^;zj7Le)1jB3t3wV*KmYMnnLD8!=)`BSeV~4H?NMMrD05+8{H!am#r&5Li z@oE~8Q1=?#cFg4t9eXGfgbfkUZu@2eer$EKf!Y*ZoQ8Kx3n{DGYKNdX_kvBHcTlfy z6Kr6%Q{U$Y|66C!AzEjdEvwFwkvYm%Fk*pJ+eG^YjeAno!UHi z3v#`dA7!7v0zG$2a^0rP2z(M=67%T-*3NOekBouyW>`|ZZw17 zsfE0fM<6WbrX0crcAAW>Bn$R9!)K3Si^EM^qnJeXo^i_nuJxF^qu6Dt%VVrn28}u_8g?ra-xb&yyq@CAjmCy5^5ffI>6xVp2aPl z21-5{VXE>#T|!+g=8?9DpRpa4a+L~63o#RLcE+e`a4fVkSY@5ezw)1YUa!I`kK`3& zS#LO5ZxE%P2=nQL_Hrh9DTDHwhx)4f^P&~-7pDJ(RDY6QnLi26>l+;P?|zA<|Fyh7 z{VO@UjNl`BF7yoTIL0~G#C$SNQMM1XAT9qmlfYdzzg6#wroL59v!Nv|ifx_5V3E65 z3{u?0mX$Vc*;TGj@}17FYiXoVnO{ztr+*|BcdZfg&hYNIR1EaeyCWEB7EU9A%@DJZv!AFyZ{mYMUnmJ~ zsj?>|J|9qg9KdnilDB7W>LPtjF@p6dLuasVKFkx$rZkqc&UJzOm4zL7__R5bl^6X{CE&RFDoJOx6K>S$$LjL! zPKo2>_5$r(&E@6!;<5^d6!*p;JQhEh-1Zy-a-n^sdr4s&c)?;PQyp`88NPUeD@i~` z4~e!NX8Y)7jGM%h6++7L{O%OQrVA~GtT*sZ=dcPAaN(AolG7zbhP*xGsEcjG zgdZvDl6?qM=dXqwJyf*Ca3dm5W(rbxQ7Pkz&+Wd|h@s}l?}jnygqb7K3xuapstwxO z(YdS_YII7lA@HDL2SOs_nqB7{>~;`>h75ui4wNQw5uP~gCocQRYXM%mo;Xg|eiQxs zg8G94`u&3l(N2HjJiteK?iNh9&3`boG5@(T&w%aFno@p+NBfQDJU-#_J5W`u^IqWV zJ;`EeOI%Ng?cSThzfl0Z(M;t)YGY{#!y&A8XZxNiAZkpeXW z#Gp#XPwh49j#>>Tsa8(I)AyO2QH!PWYg_bZ2QJCB+*q>(Hbt>wGEpYFalgpUj=_FI$wqjVT zcfy?SRzd%yF0MlcB@u&GJ6L)L&OgBTYnp*|Gg`$mI&BX@l^Z3AiTu<~!3U?H(n1;fSs5AuZedmTsRC_f%ZA zN~^Tp-1iPVj}b28Ma_H|O+eTo^8=U$WE}GZUY{iOAGoEb-WGY^vWTrU+sFNdpHa3! zXBeuAXAQ8$NXa>1iV~bEGo8V00-<`dd&`V+o{{0m6d=*WOtHjZR+=KNOBHHr(XL$P zZkC=ZBdzhLU4Xo>gt<`4l4i3kdGfHyyqVuMB4`Nn1&>`CC)Mb*P?k^|Uz`b8#aoE0 zpzIew=qp< z2`2ogc!kw|Wd3>e%>V_7Tf0l93d2^I2~&1IbEi!cBhS zn^>wT<*rI8HT!1PhM0$lBL=&rHc+QD6zfeo8PUqt z{SLoeo=X+{0;UBg*bzCTQ+3Lb#IoEE;(OX@F#Nkb1|h+x+-}~DqtWC}KUBIf{I7%2 z_9R0#ZSMAU)TeDL7hcv|-C|nOStv8=6Cjktb*@cs`J^B{xC|gM$}S_CisRdgD1b}a zE*7cgk_Bg>^+4#W@Jd6~r$zlSXr(uy!oQA~rMwbQ&FK~lZ&0!vsA!H@sjKdIW0~wX z2sAH!LMmSuy#G!q^GNgJ%?j-q`Xs`3nMxHUxbu8v@^WQ{nJjapqQs3ZF}rhF{EaW| zk&?aPVQhZ=a|Whd>?5w!5?8MK*~ILITS_OG`Gphhyzk10^Sm>I*sg-wU3LEYH=0s!h0%s4_xln@4ia|=BAhQcz6;jyZb@Uj)LDp?B8EKDLe7x6$ zA8d`=Ul$^d*=AnWZ-(x5-4b%0#?U=P<#ca;qfjpqOni z6v#S_@q+de`=c5nhMlbkI7>!8b`P1tp-WVE9 zuVq8fnwhK2>$Lfh@vRQ^8C{pmCm7p=Si{OC6&AZ-)~?0q$|W@u`=q$SyDG~Qk@#%v zctw$1)iqv(rCeRM0LZgsS~l0XM8=1l=_(5JZlOQn+NwpswJKlte&PY?=V2SM$#sRU zGaK|~(Y9*UTIQv~6~mG8teCx~M6Qx2>ha-`TsN1m*b`lPb<(W-s%f_6ObJh1M_xbK z*n`uWwcw`-ZsOH6*v_BAS#Dn|e*)W7fZn%=wk1zd&y2?3L@oDL_aymfc=9)60VT^V zO5JP?%Q`m`<5~GfsdtenpS#79dCQa;kK`aF?=6aYJ3d&2AZMgWIeIo}h9zQGG;}xi zTSv_4Ny?_GT+s=W{{{gG@8`2G)2A-8XCSw@=ZLl)gHgoD?>%VX?JuxeER^%oYioS1 z+fXh3$+?<=m{&uV&+!VF^$UwSIh$}3+qIPXu3hBFtCJb+-vTNH4?fwITc)(vuU~9w z6>fFZK(4uGD1pedzU}M_qJb2%Z*lvR^f+LLUTEsk4nfXJFCRPrKYz(5Ab>CYnPt2{ zC2m2Lk0Rw7K2fv_y#mv32g|j*eBW=0PTk+ko2Y(Ss}nAj%sN5y3_ak=3YrfQ|KHzm zKvz6Z^d{7SSS*Pu?nEwRSQ-(6R=Q=D2h!M>7AKf zbv@4j=5KbB^Syk*ZxPBRy~2%;sb*2Xl~xOye@uy0@G|j)tW!i=lT&P!n~Sk>GS{oU zdXWlS%Zcg`>&tdVr}RLEL1ot7>EL=&=x2~wT5Uhr!PT`!l#G_AR&gcEQ_6H5l+)+4 zN~Q|O4P_FeWx|SUWkC~|vr1{-k)+B+6jl{U6-SWR$*Q?xG7d;sAL@UKdDM4H+P^y2 z9;F9KXJjI{@`JSUk|v=b6}hVN_l~1n5+Q?7isDTelu%X|){!`6-if)tnsx(bnv>Y; zPgACGoxy4bqo7k>Q9ZWxLr|hzqPOsa>;#+yuf~H`h8*jd9+ijFG%H8nhHuXC%*z#t z-Q;e(RGtW@Pb}>T+?8OhBL^+8aFcw73L#^agIjJ~TgaP+pv!p=I$PeVGde}jJg<{zw{en(~PCpqu z3+v2e;+j=H`riS*eMfj~U^H4Ca7yy_2fcQ*zfw{Zf%GA6eV+gDp1IyXj|W8lILwgq z_9~fHBFFYRRtEP|1(`$t=GTvYTjm99OrZkfgj*n|NM5coAd|~Ol;n;ljL-Q>W;U>^_IX`143YElWu}29;X3)VUB?LHK zG&p6dkvM-kJgRxg$LE$Ca=-%n>-jNXp zqzm_l+(L=Z$rnun794*-f`AAG_y>?bJ!zos+JN~4O8%g;6i`M+VHTvakx3Cp1_6xt zQ&Xr|v+By3!}(m+;#ykMl2d`R)gaU7^=gCoWnj+uch_l-=QZ1_@6qXR?$6(Q0Yb_$ zH5JSJt`v^R)mkpxtlbo^rTO`INvR9ml-rV=NtwKaFQrox&&DMmN|gC;%9}zk;m7=V zUvc>^l}#bItqX*PW~mZ}r*g$_U(*apFN-|IZw=LnS7l7OJ+)Jr30b<5G38A;zHzW; zp@JK+LJw_eXDTvk8p-Feg1){@-nZ<3-{i46sPkl0@C8BeUTh8Pm$VR>|8sNlnH%392|IW6o|PXjrd{?U#QT?n&uHZ)K` zraE=*q^*(l_s9NdJ{@Lsh&Pc{eic9`DhL;6;M5Wh|6UeHMyGz0fvcv~bM?5QHL(Vt zX0Aah+kw>47Pwe*)`GGqEq-~lJo+A|cg`DYe+!mrfd66laj0-51~Wc|Oeq(jUW+>v zFA!dRqYLRFy*U)=u*2gpc&4=t(U7CQmWgmpxkB3562y=;I_g0@9efsr{Jc4ek5bW< zc}|Wei)Uu8KytQHyfg)x72L*!Moeze5GD?SOfsvvb298!g|Q{enh zp(vGki6|d}mahbJTllGoL$p$%M5IBPxh}$LSuPT_bO_PH%6jWAv!Yo&;C=J-c(;8c zLAa#;BPgw|4G7larqc_wI=Xaes$uxC0KTazk?anv4HWY$2>gEqSvpBbujhI;sx^1hYq{|7_ zvu%=RnL)|Ap=up#wOZ2?WF<~AAx(N}2nza!m`#uJJ0wzEG^0an4U{EK2sP3bBdI&> zE(PYPC$~>Ax8PDwV^-moG2g(^=8}jJ&+U#^#r)M~Q=Ib7>1I_MKD-+M5wBdihPjnqT(6ayTNv*!Y%Hsk8u=+ zdN8wbs@8qjXN3YTMb&)-t2lXu?Yz3PIDC4AK_~1#4}dxXbc3IC1-IFSR~I~a_^T{PTZyG-%$*w@F0@bztIA zKNYyy13sgCF)>fbL^KoXSS(1y6mL>_Mjn*HlEXDH4uS20e&9&?F&-L3w zZGm|u+*P(!gpKkfHc_m4{nRRn_LgrkPXSo7^YqkMv_EhJ$1h+-zAA6$RjS=C zB5%PjEX%VX`6~&cMdi~;UPjXr2h$eVYx5<%LE_6xsXTC3>|tmQG%Zg7Y7Ru2Q_+;j z^hg%W1I?`LXOp?#4fT^+5ADY21-Yn$GcP2iY+-!MjgMCg<86~QIV}Kf083zx*l?dt z4ZdXYKcwg%W2Yaz?NZJ0!a5^pyF*}~2RKUg)%be)rkRjBoGT-Uf#yDBdf#?7`nqk4&UTB2_S84zzZMYJwJ zFKSioZHHyb7i6{d*#gdrcaZb51UeK#y%$$R7Hc4%ViRIVn5HSOm_P z)q%K!>+pTzHF9G%cC+S1Dq1KkyS^imFs(rcsEL1Aj$EmwmVlU9U0ER0NqWoKSB_m- zO&QWDMHjqyPtxv+!k{6DE98dWNmYy%>e)9;3vD2}YOFBLw{U=$&{o9=;<3qt0?TGA zk=2K1wN2m`kQ=8fRuGAGAI`^@WY0Ot7koRt4t@dR!~Bn@z5qRR?h@q` zE@T`nGiV`bNFG~CfXm!g3t}9B}ku>fyNYCPxeA|i>==+p^liTW+t;5=|f5MN!|1k0SUxbz6wi| z#A+eN%(`F_y}@`?jlrN;Y%$RV>`sLNhUTN;T$*ntId{~V9Wgb?fp}qebT9D59&=`! zIWG6FC4---J&g9O%$ydl7-U-t=8IV;D$FJvuHcee%I(fzb4u*O;kHPZH#E{I8?-%7 z_5mR0^z4ELxA>L+H$cvjwr?1+Z<;di(9kzz>P;ngy6zsDcZTyo z+RhQEZ)EL$%bVyo^Y7W-!_XJ)-?P^@fWA4fcOc&3z9Zisp1yv(hq-s6AEuw*k-TH} zcRUWG_oZx#ua4=#rSejz1ObZ-C8#^qJwm6-0L%;445hV2ZV#A__%f6SOv+)oQR^J; z(CKYTJSCv!aND%FiX>$zH-F0g33a+B3vGzqoWx4e=darNG056Jn?c&D{cse@_-vvU zcK-ss$qK@-rj|d-rL5937-lP>7#tz0Hun1i3EwpiSiZvHec}aP{kw@;g1x1v#hM;U zQo0a2o6CXp?cEh1DEpD6sA3TBS(=aomBL`V*v|T@MN@PIn9ktin$GTYbo^y0^MuZ` zh?PQNU+Rlb)H0}j=I+Z<4j8Q-Y0&vN`6E?vCsZlp_y0K{wL98~>k|q9AnAVt$o!w0 zg7&|oDZ~tHZ2p(bP1v$rmPZc#TGPgjR&dRM!YI_PKicoSV}FXmu!yVy)e%x8Ly$ zJt_;r!m(y(j&tYSho&~J&lM+`Dubrs!7Ko$R1S@81`djPTBWD1=AGka5lh{)!)SLKyzH!%_xDr#*%VIFK7oEbXJrG4iha zN+$~^&sEUyL53|ODiI@0d>+Zspwop`SH zOaIaOZx)-aXgksA-^y-62;TnIsZcEGSF2E{keG6D#7R|DEOnIyF;$-tRw!=nfiYAG zc|qgwK@W{X?>vPmapz}gIFp}xl=?Jg66>rt>xWf~9cP8}biU$PKLN$m9kc8&ZUuG> ziDeUPv9OxtjBs9{vfA59tdrD>S#9*O|n>*_0cc?5OT0be1E~MY8d38tZEo$wJV$Hj;46}^VTX#EJvBIaajEq z_Anot19;+JE$-z%@%evGg;4%?7Kw3`|Ym{b_$WEIS@yidm600-l@bnTjGMNbT8 z7vNa(t-IOl2ZN=;M0l}_Al=YEqM;bB>3_DjH49VnNvx)(g_ShW#330{4vb94>)`*O zu(WBbX-RRpNZ+W74Q>1E8nkz8twuPtzq;jpZhwB|eeQnt_t)6c0Spf?fLI6fK%N7$ zu@ndXhJDlm^ZU^PbSC7#$e=lqQsqN+Rv1h}E|!b^iJ6!3`PIf*LE0fp6UD8#SL9)G z35>%m1#M*v2F@=t+8rNxf?{Z9dz+34K0jhmX4|9D&TYSxscdrQ3Qe_f&v;=aSq&kV z)Gg|)@#<~nZEFnMe@pqs(QZ27*L(oUX>t&?EE?EA%{wxm96&$nj zclCL=^7(IdX=uk$*dm0_az3~*#dLgyrJNtSTu9|ux0IFIT+wcyGH25)F^^zKb<0*5 z?nJ#}0hNQm_gC6(>2493oZ8%Eb%Efo<;etGs;^MUoDmxwbj)mi@BTs6TE}HwIq%n? zlUP^jveJR*m%Qum>cuh}UrX<;qYu&w-2%=yPeFIy2d+&_>@w|n{zu>;9ay9DTE*Pz z_dh_a4sNB}_vd(74wbFqcM8{~6jUjRg3#T|07#M}o^roeeH!NSp99>vyWZ2vYR=1! z&eN&h#})?Vbk6~{&!XnXWiB?Knc0y|Zc21VxYlS}k5o^lp;Pq7&X4l=G>5-q5O6wW zx?|TDl}#~#D7x1^12{hHS)Ojq+2A&g(254e&c;UK57d`EtH$0RxGGpHV!jSHQ0^u$ z|K`SJtvf#6Q(tEBnr&%hSffm4bG)vfpZduQ86Olfx#eP(%xPoror|uMg?&4+^ZV0I zNoiP4lkzJZ0XHKwH+g4y}m zA@lk(Ovegpmq^5jkQ770z&0Vln6o0J=Sw`x*{e7xBE=or51Lo;?=gPW5aXwDf1`?| z?wrtPEYT#!>TmnbLN*9052CJ9h6PEw<7uAE*98mF=LZidE&doVb>^T^wdqv9)eaVt)|{sMrFgyP zhZyxA# zw95wBs#l5S=-f4 zCY^>sit#?bih-}Luolg@q1FucOWW%g77wV12W^PIjpN2Rb8vHqLIP-(4ZIP@wlp`w zR0U-w{^l1d*9&^^V-AkBNDpVqEc_)C62^EZF9HC{v`b1DHV$UMa0dZmTs_pZcy`nc zYCyqME~>OXTY(Q9Ff}iZKgg716TVXn3OHi14HvExH`XlzWufgFqSFpp1)oVzOZ4!e zV?qwBrx~+59!9F@mN|5EAEQ$!eDNQ~IU+-OVyVqb`IAJ_1g<--pY0w<4KwC71&NFZ>A^IK- ziH^cZY1$l^kdhFifI&3o&Nv??!M^9OW7N@JtW8N0mooiIA?m091YKk)$`buET%M|c zQ-p@jLa#Y=ZX#MouQ_FovxHL}`Yh2%!PpzDV}xuw!xBs>E z4`O{Li4l)hc+0gx_j;Tm3zHE_lM#+qL|PZ9n|Xg&J#5r6Dz(zqy~*up)ZZaCFL1H3 z2L0@THcte+aTRaOHhr*yc>(46r1Aruer{p5ZW_ z5-9HDP5UH%pm-iIALFL(aor$Z6SV7M-Sv6cqkJ<&_VL-FuM-^SWO+jbjxeC(H0;wL zL-=Tagtm9+r|<29v!KK}^adDcQAFEE?6b8%$=bcyCo~R#Y5`>(Sne2JxxEklHUW7z z$=RWB(%Ya{TtUyVPjARBB)}|_601UU7Kg@GkN}$q?r5n}9oSPLL$Ia%u~@zJltwSV zPqr?5xa&y*bbRY}{>!4s(rt_5|5x}g_Ah|@zn{zht>8`2#L3CTTJpcn<`NAkcV(5t zTF%!LSR1!!pCJ-p=;IZMXo5djnD+R@e}D+Y!S#nT=AAQ1ofmN){r%~d$uG%+g1{dz z5m-1c3keZX7BE!76z*GkMRPz>T)exkfcCEaY~AQPFW)+bw?D43IaORPmn*!eZhv2X zc!ZS)B_@vZ$#9ls!4mJ?C3$mYOBtS`y}7OConSxUJa_Za5-&tNDKelvIWm4^>&`<$ z#N>RPQdkG`)k?;#CXP$fo+G^Ih~DM$;%~jaccLE%b0Xt*@v_Z(3gy_%=i;@0;*3A! zILnuUhqs0KNK$(?=nGF8e9)u{gg%19kcN=Xmexm+`=ig^xs?UFdXrwerlLD{z;_s1ElJi?t5*UsLqP1`-yjOaPuFiYmuEZ02pLZ?p*pVtMZ-&f#{wAo91{&U(IY z5VMJHu^P--`iH_?uPL~ao*;L)Zf|npOfOMbq^y9R@mQ`Fj~@3QNowkN&`q?Svq1eW0tO~TtE^Nz7J?* zN?)EZIdPFT#D%tOXdRWuQjM{TWOexhP1=q8;=n&?5M6guV-pc#$)SM~v~dXlnL(GR zi3I_gaRRiFNtA=G#EHtRj|;q1*J@{<#{{Q^L;*9Rp;?!9kjgh&7(aYjm9M9m*UknX zW>?om+$&@T7i*8A=xC%ux4bbQWSsV*Iz&?VnuGz%)ItNVLp+bartI4FU=8+$6XdCI{>f}Yfg4Etu7eYj=yr5`ba ziFL$(6Vu8TID*zZfT>fux)pXJtPmZwpj%#Bc$XX_o$`)35XoLxs8Ww~L z`eRrkZ_#Wqgb38@w3RDq8IGaNKCt%a=xZ7!CTCIKa% zh`ECaGx>Ay0whqNd>oen@QiQv)5=cScg3wzvbgfTPdA0y-pF@Az{QoB1#Qa(rem93 z!_)<=R&}&^Qlp8o3X62EmZGjIQ(=j|qPno4+I8~!qP$1i$ZxaGufTKr^`V+@)dEdn zh&G%Fl`(@nVucU6ztDmYDH4y3V(PKoV}(!p(&3@=uCg_knj+Bvm1Vfrk|(Ra z#dV>fp{1pdA^fag?UE6lb&wOLNh_z*wt%f6Q6f2`r9y%vWdY&5K<{0|e#d!@Pgb&| zcnPQ*idLL2eK+-aFS0*(F@_ez*M_GD{?qOI1$=k*dNkFqHy`)vueT5<2jpkK_d|HM z^ZllLR}R`=(fATzncfvmJN5`^pCmB=$NLTGihy=}L+p^&bNlMvd7Xh$JQxU+SqGdJ z%JE*{j#4A(%~;!9!w`9CIW3V>W*DM6+6<4uLAP)a6n{t#+38rIH^-)Aa zcE@uyif-wmP2)ul!F{Q9OPQBxRY^7EJEOev&O2mfQMw>?xn3+F(F5F_l8ty#s@b@M zyD6Lj7q8&QMq&Y%Sfo2~Gg4Kk`z+ZQ1YXU z4u0OASXmLr!>Pq_krby@H%~ z`+!B;2Q+}CU#S(X(^2b!71QO&^A9ZAx8$6833H5FoFS`b z)0X5F>kDi#_aXCE`pC7jo4ebZOotmp#L%~N;&##* zWE&1s&n-nGH~bf~m?9O4uQuFdIIyL|5ks1S`7%fmxOXs$MOt2jy1E@GfyI)sD zP<;t~rS40FSj~1s9npKAa3z7#z-T#0BpO900rWb<9%i0W5PtQiQAXj1_bXF=2s&2b z;ZQ^d6OqLRbva5j|q9hG}ygANbLyv#~Mc~OVk>t;Wi03e` z=~A=nmN5_M7QKmP5==i>BQ;0X#n<($QO0i2#%{JkqduY0@R+jyhN?CxTTw@V)C_`e z`Zkax>57RlJ2};rdX`JdFG}6yaGlAI_)y;6{ zS!lFMOi8}NwJ;V7QsK~Q2o3!}Qw>RuxNz+kK>R3A^e3m#N^lA{)f0~~A82T{P4Lx? z_4rOLtXb>ntjbH{=iTL<4C+LL5dBC~EeV-0$eYK#F?G%qwf53)tH?B^P5J;Gw5>f! z_K9h5)F+(G1;k_r$52BZ#HnZ4ui1DuSm->%{3Q@;Lrd`9#&(aM1FB0OVw;yhXZ{3P z3Upvc7(f{=Pa*i@OZAnZ*txG~yD+KUcYj{>JuF|htqN)xYML1Zy|kQ(#`4jq{bLQG z_Tf~c?WUf}XFYhQEYFZ6u!Du3eU8~a_5 z$9Jl$ttR1zC-WDyb9;J^e+Qfr&;+(SHWepI=~@gsf!X0KzO&uw*N^O)zb3U-SyF8g z0oLPYXJ8y(CT45#_~fU+HS9`^@VuoDi!xyhh-P9u(N?5e>Yg-O_-n&m;GidoW-oAp zz1F%r1UZjl=@@jf={58@6)6t~cB120Yn;1kcrtc{ki{#ucUcI0AeSZ?IEi+d1td*M zH|w{N3*>4_Uf9@{ej)NDr7k`7ZbAc?^zph?!b$pCdM%axFqd8NlB6i7~7OuEy zy$}>v*g&?7+)N$}t{{p7N#}%Kb7bg3bG9^#J?!>CdviqBGyc(n4sAY3TYN5{cap?8 zUg`oo&iGUzd$_DV%E$V_eD;_jd&G!=DVEBeI}cQO$i)1Wsw0EUiA(O_1f3_Y>J2e> zvhU2IJG9CJsJQh``u1SM8*c8P%$>Hc-|Wsxd+t9n@^gQz!7r${2V2i3`^KHw!kdbBLgs8Lb9 z$4#Pii)u`*kzaY#G={K|Z@CvaGTABGp4Ck1cn38`wNb!5#7z3$D&(GNC8xcsp1}WV za7?#R*gf7%mU)Lg!2Fd5*(>67FUuT!t;F3e(cG?rJ^5TQ`0~%3>slf7m8Uu2xvcn# z*BpSWQhHZt3HU7y^~l3K8C!1h=a1TdsPOc(&xtuRSSSuK8;AOQ%Z!UNKYDkniR_!Ne3!C8^(&b+qQsMzFn2z2FlZ#EOod}%~4 z$3aeg2^C-C9sQsirq>BS=p<--IudTpC3JL_I=&1FQJX`0_e@~dz$1u!W-tuaC6Ro> zC{)g)5xsaErugtaSVD_j@T@{Fa)ape4M4BbBbHrRi;(zGRj7Rphx~SBQ0Y^XUiyo) z@}W2E{Qb93l#kr>JZ$9Rqsy@Lr=onN51|QKWf>zh-O4z;V$^;?|2X1(RDw`HIVxX) z1T#j1&^Vg{6|)Z|Dw_14@)VwKm(I4)CfSU(67FhHpk}Z|l#0PAoNAY&W_tvg(#RaF*?pzryyOO_0=E;4FJ6hJdYj@TdFY9C2Z~vl!{3wKEh7wzg9ev?CZzhU zx;0}qa!gJuqFsCjg&Ht!#l7KW?!`brXRtCFPR%GNnPSR-SC$haV`V<&wNp z?^aQxE_EJ=|6&rgCEgXtgnVmR+Y_E#sY7F?kmm^=X037OaJ?RJZI3FoGs2Q#aXx@=m^b^UC#~t|UxQ|N_^oI2k#m%NC zQV+&%a?^81NXhc*K1NwZE3VX9)5Zrfv@}TH8WbGVERda>844KY*gF1?xHx>b_?1BH z<2*NfT9_}?;fp+wcw`tL{{P_Y8-pz2l5M-owr$(CZQHi3F1xDBwr$(CZL7<8_07z^ z_r3Y?#k?DFBF_1FBKOYRD>GN-8ulaui$BYS8v)0G2+RSr1n6DX2O^pjq{e#=kM`ej z+`CxAW_qQ0`!e!+S`I}6xNG?s^9o2>@txBnlH=sC8vZ9mZ=3lSG|RU*R21glRb;6C zlTOJ$+G+o+$4shudd({*@jkJ96pGIm%`_B*DnJC?)D(vP`eCgxr@-*A36P`;j-MFY zRO&rL(f=c$2I|>JNbZ2K#|+)6w7-1OpdX4N0EUr*vpt`)Jb<94{@gDhI%o6x@`t%J?s$^AH~aNzoNP z>h>t;cn4+w+Kq)AIX;cZZ5pEMSckVacZ{4~g{Fq9(?9JZyx5Ip)zz|K1>wtZ_}L_t zuj#%`Y0!&x`c^GTAoK}zhCy%)khyUdEE1CDRt-r}`mPe}xW3NM*;CY=R4-Fawq3j2 z@dSr5y4ZAwH&QRMbycUNU*fG>i@DeZlC4M$FO4}nRXKY6Zsq8GSGDoi{W<2TeL40T zWBRV8t8UbXwe1BN;xF2?#UJKGp^U6mZNaEwtI0f@4_5*8>xElGb)W_?y6Pl{9V_&_ z$3qL+3fG>x+@8{ZUK~oF@}KgnVRY@~>yAvgZpu=5$<(v6&U~(~oDqr7$v=u!bu{g? z&NdsoKjPaOUKFPIbsi^XTO1XxbE~JJcy!hX|L9;l<<{RQR2xZq=NsNs=i)XEJ@9-i9hV<=#2s!L4=KW_dkm;I z=_PE(ESBtwvGwXr_Rgev*^1$?Aj;yERw7~;I3^nH*%>=?A&vAbvo>@ zRCpX!4LNS^@~KYDe~rPN}VhJywR~*tSd3Wmit~@GT8`wsnhs4_5M%1?E~RpH|}COvHEa@44qDg zUc6U7s}1i<5V>j{3G8UN^>`NfA06GUmz#A{V)Ek$RE@7aRQNeL4QSI`GxFWLZ0hZ#1x}w;)Z|!T1 zt%0@uLuf<~XX^3t)|5}1rnVV&Z9o22|vYCFGD3-z<1FeX&@bPGnTD41gf)!=ze z-59}C`D-(E4^~7gc|*Nyj#8 zurRI6As7~%qd|^8bSg^vV>=W~47v0AQFiV3;5pk-VX<` zr%H!lX!{+mGGS8=tUa*SZaC$xz3(fSs1>EysMcqntU#$07*gc&BY?b}ti;sMWDh?c zQB*hAZON;m*2$%)QavQU_lJjLNjK8`%0tsvDRuiDrpm6pTnkYvJ0G)7dX@yH45CoP zlJ7LjkX(PrS>a_{?zNY=BzK&sijp=$ObiP@-~vENfdi4ZUVf19Y31qWVSi^7)(rns&ATD-Z^VaEW+^F zYxt|e1)LL0Ai)SGHW*DnCOOxF(2!Hk_fK9iI#1-%zbMeF)(RpZ-Pw)iH zIad`!koA4JE`z42VKC0H$ADXbxyNB9X6eF`6&ha|=KWkdLx|2w-~?=U1T@vn{M(Oj2&Le8;YGLq-UL- zr*6b)|A%Xc3*gTPfMvk15CBgZ0w zdO~!Dy%_y^-3O+4HS}@1u_bkxk82w#VONL=O#U|L^zRbj>N|3DINZ8EG z*+sxLK={|`N5;%)gP1_)JemHCVWI`BT;6;MgZrevk!1IzdNNUJxc&|PDJIMfTNF; zgaJ<+Ujr6WvSn2HOLL5wmd^Z9aeF9q0~BTjoiLX!{b6_cD`>)dbtaxHXM2*){qfXu zCEqt+o0Xe>t;3O){cqp6!J)f9&Ng5TEbJa&_JhL~y2Q)mMrMZGS#37bc5z$=O>qJ{XiDIi`>6Q=6v<(X zlQ53wI++wwHIUA${ajsTqR{`PD^2HAl9sfBMq)WMV%wQ>bm60EZ_R9=&K6 zFprj^S)VZt61F4C8wcmx^hy)PemU4xHhTmN5hC)? z@^k!)UGL>RH0cRattyThdX2l!mNhaUcfUiXe$+DOHmCkZ>Y>jnX5RLhNPW(|{uHmxU+3wG7*kM*qd2xEvBeN`FVA8>!|dPQot28gQPcEKA9_$> zuzsCkkv|*ncnttu${qH@V1wuec^2XACwP(-WB4=x>{XuSX=S(6?#MzN0tfHC3o3fw zZ9YL=b;8X3vf+#vE9o0G$cHjwEQ3GLng88FW{8&_|}U{c?cf$3@o^T z$UvnvOhAPe3>YmzW^H!kdW1PCOQM||Ph5t+F|X4?_)@k_N1vLjsks9p^>d$REzCu^YGog%wm^uCoV zVtU`*i-&d(@|#?Mdi$#*i_?v>q;X>u_lTzJH|=isk>rby4r)i&>YSWyQ!M%+B|ibG zq!ET3{WJSQ7*AD5Lj^b4a5kiZ6|OvAO7Cj`qtLILW%w@Mg;r!o(ujm= zw5aE8aJIa<&5$*svaCN}YVvL7hO8eQmq!N82tPm30Xi^#>ID9%R&2OX={A?5Wd+M{ zAcG|#4qAI+t#zLT>aYxWlx{iPKLF8*O4oH-B+t`BH)B+5B;mdawfA6JPC_G`3Kh}v zA42n{#*>K{CUAbxW{~jc4Jeec&rwYi*fZ!C*eFF>9={V(m5b}#9eXX8_XzYM@9doD-=w0{AGc0X zmJj`)B+R_go}Y(dzojl8b@E=9$MLgb^V#o-(yPY{1~aj~@>P0{!IMdN76Aaj=tb-_q&Ix9Z_Q>~} zJpl^VUr=Ub0Q=*|JJ#Rj?p*&#?*1<}1<}906^tF7t(^Xu%V#QXTYk@fe%hpwSW9VF z-ajo^t4M2Va{wW;0ByoiEc!=xK?SY5Su@TR5S`k6CBQC&2>o4gm!ZY-*f}h2^Bs zqXsctg#CEHVV_#^C|}A=u$+bLrJH{gyftDv33p3y1sqdaiyIDviSb4^73aQu6H@lT zix&cl$qF|@Du8mKgc9yRu^XFv+;l;D(&9PL(QVOTLKD*8gK=ByJ|q#`ec`fW3^@Cl zhfGl?NohpqNr0VP$;rGb?2n*M$X+Z`skU(sre)2N4n;ZD5Fan$x%fWbO!cBte4H?- zF`XxW5f;*wk(!CEwsyq15gZl}ML>l)EXOF{Jlg|}$cki?Fq@n%2aYF-kI3hm0OGk35!8LN#Il~n=?=>!Sg_8Wtuj`xnDPT1qP zw?sDGDlG4KWEOB@X`4{hmg$j~ZyT_D`jX$X{AL(gh4k&$g=%>BE>V|ZFvGne)mWnc zor!n^`886h`9bzjs?>ROxWB>&Hu+4vf$e7~n#FwxLDMiOqd{;zTXI~>Lz1UE!HkZq zpYJE&R7~$7z|?-yu#`tyN>15(KCRFYZ-w4@2mIktAPJ@*4Wh8*4o&~!JSs|TVcugUmROGehEN+xC)u23KDt88(0!B zn7vs`q#!XENgTR%mUQrT#{P?n650D5K(E9V#F_M1K}98JXXkm{ZQSf1Hgx0kllE!* zk#v>pG}7Zuj8h1~_k)D`1O~Iozm|~^tBxXmLpII{G*?h8H%+;eE!umQTewgU-xNI_ zarQlbHX7g(SB~4$bl7>9JohqXh&gCqKSYpd;h;&R6#iT^(=2yx-KRjHd5pI&+tG6} z+;UDuq57IU*sfnlxQV*-xYiDR?|8&=vUtblA%Fu>5OiP0BQ#rr{Y~Hq~2Ps$|jpxR-2a2wLKVxyR(Mqxs=rGV_`YP)q^J%qw`~BSX`UhJiu1D>O z@KOXZuanlpK8;sj%*V(}=-9p7PVY^AsA&qtt=v)XLGIo#L)IU?!5EtZu9gE)SQ^F& zL=_zR< z(rkp2)UFbm^4koJks(DBaato$AdcZEfmJ2Qqkyz>Gv{W7;`qBI8Baq47b_bp9}}4# zZ7TDKR|xpSu{ zom6&aYh=dz7V^@x=C=)T(+Ris0lICxS&NY!CP_4ds0~b~MiG~rP_CtFfnGJz75Vq2 zaq<8cu&niQlOAjx+!B=+H=Cqi zlBcTy7Ag{nwELBm+MQc+_Y#;zw(Y(d?^VCg_A?h6wM>@C&Wmi2FvJ>cz_e^s-(VG< zM=!%Ze9Vp!uKh`!UZo+Pr41|879djH`)#8u zi-r$Ktb;Qag^0Z3mgpSqX+R+9TM5%^EpfDUts2r!wA^yw*7B7H6R)V|2{Ou0x2T}r zhYMKkm+<-bH$>glI`bu)CsdY4_SEI56;cp09(l2~DmKb46#i=cceZQoiD$*ieI+B+ zNm6XH7up|qoR3)~e*{1hV5t*M1f$dJvMY}18JINbB-T!e9o$kQ0v+-zW$NV4p~bz0 z#}lcmaV+=qOW@DcA%cV|U(dWTO#zcxtURGLVw$bmi#*Ti&Ew+m8@lF4UBQoiUejx` zKZBp)`$Fu00JzSV1s=g&m1?@qyl%BM27b!QCE&G%yai=|Rh@9-MH*M}&cCRpFI%L`+Vg zVB9DSQ~>#_U?mJY-hh?kYyjkJ07lbbIc!<@UhV*8Bklx)D{cj&Bd(YEnPArWd08w! zCFA!nrvNCismG2S?Ntbm6wvw z@A?|4X|dE6JGm~x9ORZ~UDxaf(4Anq908wzGM962x?-L{1E=~gBFrvW z1d6NK2V*`zOnDye^qmC1z!uSOAp5>oPInh+`JlS)H7_jrh_=3aQmnd?gMWr1J||?( zcP7@)vyq=Wj5WE0ugyh13?Z4^7Bsj*I4%UAoja7B{j77%N>c=F#H^A(yGlBg9Zg_t zBAuE$Ww&6PLo`TI(OJ_iJlpUbSp9OGu8H6j^No~(gtH&Uvxp~x!Y#xIT0#5VrjQ5|n%!xaL_Ao24| z77J8W8%w29>Z0a7Lque1?VpI8+|M@4`J3NtfcST?i1j~u*3F!)tY`&oZCs4q#J+$2 z3ydqQ%K*^BWfIgm$jiNeiA6%+iYMLd5vRq9Y3)VG7NRG`Zzegl1HJ$J8U^L;iD8(k z(?Q6Od!BKcn#gcmGuPG0&ia`HC=H8&bKz;%lY^1hE_j|e5Y#JQ?#)Zba$rDnfYi!l zZ{^fyxLZWZC4`t?Pszh1!I{m^E|-f!(>RhNv@jbR&ulKw)-foDKDpDdxW#8ra{?9( zCK19_9Itd}KyIH^hzJXV{_s`4hzabI4TS5--`wsm#Haiag88Q^Bo6Zdl(80$3&F^X zF)P=}CrdsU)a-ZYLLi!GiZ(S}>2J4Ef;8=qi4$O&>NzrwsaJHT&&Ny!)-M7EGcQ)t znfK95{%cj|cQm%{C2@|_Z&{gk$K8Qr#Y8kZvYEBKX(ciSvObnvh2S2-4nX5@ilB(Z z>Mm7_hC4IV$0g4X=)W>28Cwnn!Efjl_y5d?{X2Z+``?_CsIiT)gZ?)l`>z9=l<4P! z`z%^2s`UMHM0heN%taq%i{-2Y=aPq2eJ6e*kt8< zO^D0(mafjv4886C=n!oIPLn|q4U!Fu5;0+^^#y3lM?pcDmhnRi00*?iNQXLBwNpN=;sfT`Ooa^ZpiE1p6o}cra+B zh_oPRChf-4vZM%VH?#H*|LAq)r9l<+X5N1!vyfaNe#GBL;`6sh^0%V_|AvVFc>s+{ z>bCQIa9PrV7cFuUu2P}KK zYn_QFo;{of5d*CVL(M`b&fbtoNs@XP2!tZZ%&A{4v}*sRfJ=T#dMYGMtzFpyHYaO; zo#>MvZF0QEE|y2G*nXPGd`0CLqy!{`69pY%?aE}qHz!Psd96iZ&&Dmhw-3@P8V{*0 zz4ANkZiNPR{_}2YyFeLyMcPzYuXQT0M?{bSNW?eF=n$IYEp(f*$~0xP^Nht42+ZlG z+3zd3TpK{UC7>jv1Q5gk@%0B;r2q}eodte%uL80!cmFtYm%m%#k#6aWs^#^j(1yQe zXuDar_oyT2l}g+b+;#{kdSJ*+Ngc1qdqHsa(oH>vk4``Bj&ad(60_R$!O%Z6=SL0~ zHGuxgSihBj|7Y~%-(6nhKXQ3v8$&BwM{^rfT196&J6i`Q0evg0e{=l8*j@=hdbr@P z(nibj0M%_iT9Df%stB+%V@cGxgk~r3^+c;Wllp+_qh8RP+ySfdLRQC*D=<1BX7fld-WGcVV|RUV9F#?5j`wr?>b z1z-O93J2W1XrA)pJIQ4}Lxh=;{i9#zfkt#)2PL}B_WqA0TKQ9CJV)QwJosB{^8SBb z+<#j0`wIVcb^rBLDQnvziXw4aR=b8-^Q5))ruYD_)w%dlL*o*&*n~}*=Ckyf$MOlR zS&2*$crI&HQ}$xYen4IdX1^(vRxZdj!iJjqAf2VIP6lKWtcpDzO>J@>f6tkE-0dB9 zPyfj1zvQ}mc7Sngp~9tfUznwnPl}*)XPPD3q4cu;t^g_{QbUUd6Fg*W6@i85?D+bY zSMs-4?&?wAgv9NOrpwq8IRJ$;b$s##?n3Y)K9C7F@yXMK0F&VKgrP2$Su46)riwHQfVL%1Y&B?X%0+#vk23xpw zp)xaXG!|`bWMvh%i5IEVNS}r*bLo0}L>@-_E{o_{l%l<$#ko#e2y`P1J!&zgA$g9_2CJAKhe$rWZLE^Q|XmV~f zLs?lm7R)t1$)u7ZJAt-(q%Z2sehBg+`t{Z$=Fn`W%8L~3S5?bZ=_=Owhk9#aD8!m@N8k&=RzCo3FhSL> z2fU~}%i*yIJS%@7ZTFwZTanbn^4tes4`oJnFZQd)Rto!@$4sUEQu4_?B`eRnF^54b z#n~YO+hMNfd_S4MaJG?WINJ^=7(<=5!9VR5+6GelXw#C@bMN#iZhf7@=-ty3(<1^p zX~UMjg5}hg1d8=8ah2Hf*#f@N8#Ix;FB}oD&suVY<3zl&_^4vuadOEw`1Q;t;DIqW zwH<-zgAPVSzl@ZK3QxE|)P75!$rk)6EchfdJ`3APnD7peMQl}Vjc0CM(;az_gJ4v; z3rA3hgharPFhmze?)MqmAXoDms!2s+d3yu0@}yAv%+3X^9m5P81K5o$raRp)ShCdt zq`m;8jx^UcxMG?j(ojXT6Aa*evj%vYvTPaR(IQ0lL~$W-2~in8N=z;&{@URKnfsOP z<6rs(!Ob~pCrdv7O|oTH;_wv44^DCh}=Lh#MnI zd{|BN&Y+qH7t9N ziu#0=Bnn{2J7uyQ0ZO65B(jo3$DkI6=;uJusawuiV@cQpTqqr0b3KT2?E@e zdL)r_k#sV<^tCx~BJf3MRJCP9!Pl()BI+kt_>&YVmLefF$^)=LM-8!4V5b$aIH>*X z^zSvh31595gdOijK~KrLB3%lJxr*L`@?S+PHJ2QA*6Qo9;Ar zLrpOETFVkM(etTtT@|}x&VJSZihL`9bmCCa%DkRBJ02YrwStS78n!RDbo4+zJ#ZvpO0AZg5KP@c`D#AA6j5Ll64Fy) zh@|js))vJvoP4Tf@nzH4RjZ~pn;@|_3}0pnjqs%m9(`l$ai_jYF~G z=W%hcL@0=N=G25#44T5mtxmq>U^~hPV^4M36L-?{<&o94VPi;k+oF^2v7rdhrqEdX zX5X%jg-yKaq`qBSm?$u)Ow%NEuCvL(+LyCMSrVkIwNPbDXUvYlZHnjLfC>5^yg ztlxI)49~D@O)erx*#XB&TrsFh4+h=gsP^&##~_T#w+K2acH)DSZpv=H(!H|E?@+v| zw{0_Ci0sIQY!y4u$jSD?gS0|HwtLjzZ#E}FyqU|A(fX;S@I1#t#wi;3hU-bxk<;bR zg>;{k?;3;aEoFPGEk)mYFjPCu6h0xY#19(}%tJm+No~{NkBlvb%Msz@<<8#p^)Z+- zm)^yM80Ee+8q1ce8m0|*WS-TQA1OhgO&+rnDLV*^`c9Slai%BKc1WM?L+#)kmIS=6GA0hyQOiiZ^}gI$X_+PLL@ znlzZEf25a|DY#PXvQQIEQoMG>L|8XuKz}{Sb>&z#y|rC%RY;@P8?&bK%L}z~{ET=9 z>cFYrw>jxZC+(D4&ui7P`Z%PHgjM3a8$v5(e#di#IB{?ev)O4J!Au(;Gf+3(3_VvF zK?1z*LT+P$QL}<`y*odo5o^Kx*$_T8LK~+ti&YvS4}%vCcL>x*Mp~LG49Dcv zw+)8_f9s^21F^`Gl^}{*>)nvWKuua|0ls6#m0F<(x?O!Jd?6LG7bbQ>*ieK?kShkL z2;~*DP7^4*Oy~e?ZJ=GyyN(WC_?x+XaO*L&Z#Rk+{u2#b=-4rvD9~WM3NPM(XYaCP z=MhgU0#Xvyd!}w>^cIdC-LMzSWDSwc&sLsesC$?`5YY`P;eBj!AB#7CT5x!rEv%W% zF$%ZcR|wo!bQSnbU%)AHd%^n|gtu(k5bmQu5WeOG$V-Db2iSKAPzyC@xt!?Y$G-SJ z0SMXX1JCg0Q@zwvRbBe+rHOa@X4fXpw#`tp=geQ9^ukT!cz0b@aURi5Ja-)>jk(I& z2CTTS95kNpi4$cmoDEzH*h?QwmppEz-YdTn5C^h1ES=t6qo@`(RAOLVhu_@pWdXEy zdE5=U=Bh`voU>Io*>dwrz^*{{4*_)zH4oWAl7(+r@hC|;;UnX~*(RfbZY6Hvz`p*& zFXjd}P>kMLR$Y7(Izj%D2Uo~bT6sszT@qS5ZzIUr)dW{Pf@lP3+(w=&#x}5+ePGV` z{=cR-I>zG)Mx%%RU z8am2LNx%R7^*8ZkcH$Nz&^v^WN)J;v55X;Y@`StZ#xwX8l;nm7@&FLEYTwHH$pBP; zU69;=oqozW%FNUOk&EG*pXAjNT=t8G=%=)wPaRtyHvbj69c-9X_6M7Ur%vt@BF(hT z5cL2)ZcDC(yXR6}S7W3t^}gV<^(WUUe3IYu7v~q~U&+)UP17Mg{o4T*{k{QlS)r!FIBg*Jqx?^G6gqeN}86=_-Qffc4$!mIN4uA4LHCmksx z09bxhFFb#_j`S5W&AY2>G7bb3T@)l<@a;a+HS;(H(9Hwvhj^H|!_$zh(v$9g zV5Yuc{IS;W6zJ~-SULZrBbWhZGRoKHGkq<$bDi~%V)OBOCj0oc zSROlswIXMKo6VxwSOl_|Fm7yFdy|dZ7TPV_6<`;CZD(A8b^!r1Rj_a&>>Mzjeo!JH zgc#o-Sgrwf*CBEH{(M9txkOIWsf~NiY0s%YA={nzIDX|f0$9m<9Kp;jzmwP9*n7q= z?Va{vbgm8#tJqWoA`C%9x1D26FO(T?(nn|z@8dK|rjl>k|1l&4z~7_*7ou!4ZZZBDSDc)8ibUyww}GvY zXqTT~WZb3+q;m~zrLEWNrPu#f1k}fQf#AL^Pe<)->+K@qO45iPJ$x4+{Z`C0eBhdm z?lNv7t#|)YzM;;*rf?a2CF2%`b$Y2OK#>pBkWi0Kn72d9w6LE1#K!qv0iwW=z08Jx zSuZ_~P3YPD=g1d4NrzTtBECu;z4_vVBVEhM+LTPz4Zc!=+7civ?dobVrWFgxfA@zl zVL$o3DLhPew8db-vHuUXuJ&JoYw*;Hu9Ff)dP^IQTk4w0D)vs5PF^u4=D|7^L)`d{ ztcF=N=QdFSJqiGsm25~V^BT`M^P|Y!L;`7wNGnb{G%F~BZWH7PHl$(O1*%NTTysKF zS%dM1c}tb~(JGZ^#MK^J?RlJO%0%r6%A&jmYk$&IjQ~(TZ@{psSz>ytP_jh;N$eoe zvD4|GB^}RUc6}bojcHqiyD{LFCABDjlbkW?WcvO|XBu8AgV~@;o~c-~{Da<&moMb; zTU6-&J&5v-Ea-&{Ebaq)z#RO~y(SPFkN$FIo=@gzG2>8Dg{iO7!(L0cqY`AI4eMNZpPBjxc;47Zpq`Rby7PToN=L;6?bUE5EkAIZE!Z4Wkf}kxod-uFh2Qnm?%g z9}6SgUqMX6Xu8UezZ=u0@_ofsZVC&$hZ-c_qT1bJKi=#m_Z3Cg0ezt>%Z6@+=<;0v9)3wyv2Z2DqYpZd>(6~4(3W?V&Qh!pT{@;UjT972b!$(|dV z6+4GESQB+fiy1I}^RizjnFU-TaB zSiIjD9u7X@9@5P?nQi%$815Cq&a7{KgT21Arr4DzyFKOgsV1mO?>4#b-kekSu~Jh= zMft!_#;HusM?lPX-25628^1l#-*xV&xrc6Gg|o!dvBH~$Fc%wvH0JX>>faP3SEuYg zrn?Bl&Ef8_RBr43`CC!CcK70S+8CM$6`?aj0ZJ{=1~an+VQ;sdsWNT3AsnGw#{y%p z@ga(-aWe#HR50b(Ef$h7;=vV4v^^i%si;r;S@4#+LhM&mM!Z7Gs`A93LM@G!-T^{K zr+39MO?pTl+p#Tk*8sA=7wKUnx+C zH4L|-+HVP{$7y}${aC*`Kjsthr`U!_5Z@CfkdDdfokIU2iVQAQe}^OhV}7c_*yxpj zXq1~?lIN*xQ7kP!tpx!YO|ha&yiB1PW+PynA&WK-qgyiM9>WzG)|gE<2-dmDeHboC zL|;K*Ur}h%TiJI=+PUqoTig!+uRXwyNZDInuL#v&J(dJvihB|rbhGD={S14u5hLTKf}{xEkk6bBU}yBvGu zXej7fvPw|vgB%-tN&xMH7#9Q<=r%~??{RISpf7vLc?)tW%W`QV|!1o3-n!r+pFlSJiW+e*3) z@m%50IMVR8-32x;IDerGC^y^W$NLi${Cq0)qp0v~)ABqt|wDY;1b1S&S4Pigr16v7ciZbvw-sfn#Q zH{xIpa^()2l>-$^=M=mfK$#T;s^>9k=VDBW4ht?1OD#q5JIZbu6ugH@KI)1w61@eI^gC#=q7T=vC0RS6lYGpw zjB7&a4%~UQIM`Y7P=wS`2|sFf6buFWD%kdZy4~{Wm4ZmR&-9q)h*mu8R z@bGE(GD9!h3%YfT+SyE0`vt?=O9~1yVdlMnrS~0LLs#!4n&}v~+@(zAK(&6HMj-_U z-b-S>RIs_3u5WA;sYVam*|SJAeq7?=rl?vZwpm1a{s<(9S;2(qPd3~n6Ckiprr-Ky zf||8ghEX*7_K~Vkiez8T{+t2tN=}Gl+-ta?zOr5#I;8*=%nY1O=eH~0QNzu?zqax; zP$%`cw{pbB|8$QvcxC=78&Mf`^=|%(J6z8cPihVg{`%8GAGAX59Vg7TB)P|N0Y@+% zK$kBZInMarEoT3B zN&K8I20?8hx6ggj|GD83*MNom3Czx>G)R!NW zKFr`nRY|;9jCd2Eb#gQXSq)=~o+)u5qW^fT0`PZnC?K=Pe8M2Q!F4pORY0tYY;+QK zv~@u;>~`<7uv#obfDUty=!ONKj{GzzB~~Ga6Rf(f%mZKM(|VvKIK zP(N?}*B(oj2OJ5zo`V7d_)Blin<(_(5nD>%!(GhQ%ILqEZj}nsvg>?s-U+mrh7xH_ zeB>qkWB9u>-;8(QGJ$X97c#7XST>ssWdkEm!gZusUF9`E1hJ2wAM&BAa6Aiyr#LRA zCdZSWjP1U*Ri8grde)%s)STpc;(s;6)TuSyO!YzZZe2UUx^hfb2Z?A71LBL$VN&d# z(k;jn2&BUBhWpRuO6)tvMFvwma-)YnNIeNJw^-CK;vqG?kI3>O)-A5V<1a6G3#Zt= z#hqmYb0g!9>GZ@YXfnQw4Rzg;_G)oFAO_4Q@lJK0=2RO5wBrg>*nlvIBW+)D>uP_i z#Xve29G4Q6E}T2}xiqpUFFz)sO1-+Yy)r#6WZ7b*wNJm;5p+wUqFA9a+JR+fNt;4+ zkT!e{V}S`1N&zuoga&@|2o)fW0l;+26s0`!^>MoCg?}c#RHNu6Ql;0{{uUmZh$gJR z0OwIByE{)F(W;5_ANSP9+8D&TzS0KJ*&&u|knbx8cQf_^Jn-@Ni5AZ?uE~;q8P&73mSFDEK_B4ezGA}LRG(9vuc3mgxCVt)<7+T$c3B_?0cZIlHG75Vh-+m|7_SN zLBCdo>uE%8L2o8g3(_?9;_D^aAlVOuNZzE;;VICAxQewee*UP5j3G-2Yp0M4Yp1-C z_mbkeinFhdd^6gp)`Q`x+9Bi0*#YA!(W7wzTN5;R07uV8qJ@oUl_h7x$wo2t6&WG~ zur1EHK!C(W-tbZxG7OlbC1VE$bkpj!;lekh^CP`Yj4Vc`8e{}8kOj^f+zdFL4x`RS zb@1jNa%9L#-eFcGm+U*8B(LWzC~Q=V!3i()@KhX?Dp9TXkb!YNFV)#(coQ(6Y=9aU zBaSk1E#X;P(m(Ua4B}fjk+D!&S|B#k?xVsT?viQ~WsOQn0#jdCxRq1tIFrOYn}Xv~ zD-HTqM?-Uu#ULW{=+L|tYb@9!k}~JfT`&7pmlOw9xjd)!xnLF^F^?Ih>#7!nyeA{B zP!pY~M=)t3jO(a?yf!fDu}h{uv>uTA{XG)m-J5;lA0SS4f5%J5uZ z)xrp>e32-E;ZcIDIRs&$$Vh>e5S%(;mi(izidpB-VPB+Ibxcd|UhvXAp=maYi>r-8 zNkOW9aWk>OiLsP8Lr>{grM~?> zXyJ%xooBMGi8!0A!Hp|kf+OIz#-71-2Y>Jph;s?VGzkc`%Kh@dHG zEsW4=L0WQK1}Y{ik}=-`K_(MUf}(U-uzV5?e=HIh!6Z@)TDk)UqdLrQ+Nd3EM{>3n zsJqm5aWawyZF8UlzMfQTRJ-TF!X(n)?(8Re6r-i2gadFV*z`3o)s*sUW9nL^rlmrd zkOihbrZuf}JKUhl{B6)$?ItJQmFR-~E%H9!Y<+DI{Bonw$XPB%P{Q!ZFH%-8-ixI< zC{S~c__#5XyOPgc*R4XQF|l|gm)wp*YXe$Yc>@gwn*nCY12y&}G5S>m#u{U_WP~dF zUG1-I1V!@=ocVcxq={E^`}QvVMJ09Tn?f~LxLNN@(p?fz%3S%ZrK)>#lIGtoJow3J zd5LBemO~HB!C;j0A}Agaz{M0xd%(z)cERC`CCPAD@E3a?@m7B-7a6!K#+8L;atxx} zyx?gi*z#JO8qF=d1zZ`r3iig`#0TMYl4{DnWy$s^-F|hQ^Q@GtM7owfQ|QRwGIxws z956JLJ#%#R+RRH&Ob9tk4zk)8hTHBkqi?I+VqYlUYUdUh+rVv(>=uZy5(p))`11`u z-FWXZ@XFl^zKccrRO~tPzkzSX+J%=#{IbAbp5Jq4V4@>9O>r#*l*$34-= zzHFHemrhm20j2gWYgeE~L{R6Za9IqEPs^z7k>wr)lPHNyLW})VP(^j-2eVWZ?{?$% zQIc8Gby^;WwZshrMNF~E|HIikHhJ>yTi(@O=(26wwr$(4E}LDpZQHiZF59;KD^LB; zo^#Kc{a_;Q9g&gw0y6W8FV_03#*RO$k|JXyEO{{{+>YbOXrLN({TjQ)`IFbE*ian# z8XiSG6XL_u43*jT-k%s9(Je{%_)!t1AVaJro0Orf8$r22Pdf-`+=rf&%UD>FiUA@0 zQtbATmb^#KkF`k2^p2H>8Q4rL;lndYs8Ew8paz3#j3tY@S6~$<9)!>$-(jo#t(jajASms;7rQUL}i?7u{APReiK7B zHrCdf+nTEC4rx3)zkXP`3Lwki0dzB-BVvMz_4sMyfJJ)ac9?s$c3%|Og)9{pXN_c%wWBA zn-0FE#lCc)%3$XV%{t$}L$T+104X}l@Qs&Kz3rCa2DUf?9e&)Pgxt~6KIr4*IPUD< zGu!as{8%t#><5o;12wKnV;XV55vaqZ@#S$yMIq`l#n9wXy-!3j_DStyjh-3~=JqtZ zt%~f~65HL@VBa*m)-uUqo=Bt1JQxyvD9$6Ph=!ve3M zoZ>G3DL#)x!Gja-*NQ9Wj$$;SN-VE%mGpK1QNJ#%=|$gPY}25LfWr=Z;;t>Uhs$9r z2-iIV21v=301g9pct@^)EdlIBj6_Fv51@Moc2l5{;Ew{cXsRg?|Ib{uke5E+566Wp zb`SUwS1`~lDm3sj2w--G%8TB(r^p<~sYsb(o<9O6aYm8`+OXTIqTZANjkYKs`Xisw z`NjPY`tp}Q%3VoK^hAf6OfNnX@Qp# zLPNglOg-PfaWp}5ivGF5!pGME-GWqZ!XtIy<}>RpFUQvT{iNfXe1;lSMeT57KW08 zdWxVCjpcxFfrG%=a{8hC#_2&vR{Wt_bkopUMsxRz)$Bu<+A*)2d};)K`Jhx=l!VTz^!<@A5GSpRI|z> zB1`&;*cW45q%;(gfLdS%Xn-&lM0kKOEYGjmg|UseAR+DaZ{X0L=Em>MD*skRhGv&O znjcDWYeBy+&s3Y1*4E7Q-X1hk%$jNrKYAQ(Ng>v48TYBiY^QjhvmLwta6NC7d_At< z5^|<}os>kRIhkg$@U^XwM0JE7)sM(wdKQ&PO_L!-yfX)U%pp%y5p?-Zk#MHGQj7_O zyOG1)&%^VIrZe&-Im~cvbARH&uq23$ZrWw>9g-!8omjn|s^e0yjYu*{!pAJV%>O)L z=Zo5981mwdNg5#oya@A3m_{Kf4nwUuU}WLT1WAAAk|q?UQBNXUP=XG)r7weFyMN(@=rz2jRvQhwLvcAi=82%rBsYRR}I+OvLq)I7J3rfzq1isUES3V&N zIXRf_MbL|$bmP3~eK2#GI)9@&C5<02@+!tW*Tnu5RwtWAP31f)QN=93IC_WQ9T#zk z>3a*5v>ak47i%1cig$}Fsn1nDPSH8&+f%hjAU#fzg#eKsXd66mXBl~~5p%8%Ue?oA zJNl0yNfF0e6cacf2QLRvaWT%So9HlSrA;a;<5@?AFyT-{oc;w4K3*VE{N9Qhv(K5T zh$3EIhPk!Z^JH3N=&t@IS*w!%ZDhi^YFd;ZXIIJCz&oqBYF@;+6uf#5w8}+>8Do0H z&^BR7%DktTW&R_6uHAe?b7^+VstB`xl7SmTHKq4;*p8C&c}mE&mI4gs1_geuKCVEM%N}G`kC;2x|l-44Y1)e%j<%y$XNC?oVfgDKVf%pbn&j zJ`z_tS7@WFZ!U4tst$6>=-gI<4FnNXRvE|3ufq0Stjjcv34 zW{mX*euS;2XBlwi*Cm@Qc@#_CRYy25v~QGe@Q9Tlz8s*V2Q7|8M>ehK7LyhtN`%c& zY9~g_G#Lk$x!kb7;j65x54wCbVG*h-4#q8UgvlsYBx#%^$~ZrDTd2PT2Dr+0ml}Q1 zJD?C^W$j$bk|5IC{?TE^Q5h&XG&492GSmzoE()>h5HviP3qYr|s!@YXTO1~;6UHP} z!3jn_PChn7QoT+ezc>rpRhLG*=L}2$UjULo9eZlpni3R|QYMR`M(S5$znc2Ib zi9YsBY9roS1#_-0754DX#)Yd#KUKBJ4AqFt%rwQSyx$iX|Q=tKR5Z-k@=q z*rhYI9>M}QMVwWo%xb~3$8Z+4=%jzc?pgnYSeSO}1`_M^Qo#kV-H2vQvjLB;0@q<@eb(e+hzv*X!}6jj;b0atM6a{tiR&~^h|KUc*o)~ z0t~uyEK1|ms4L48g`qi_00@2W1g|ml}7ihF+KLy%brgP`H|0A>WZYaN2f7Sfv{QXxz zc7BOteK=8J3=x9iqfIwe%AU6bwP{nZ(aO0=qkM(^Ub$3?O5B(VmuU-aWT8`V9>nBJLGBg;AIpWp&vxRtDexeOufrRi)y@N%oD9k(!oF;q zNEtN|Z>Pzu*Ss)qpiH+g8bA24>OPPxRyr}9sobY{7g)FDfolNE$uGC%xKQ&XhHu>@J*wcGmLbtsiP(X=UK))7$0cOmOOONK?4){#Q+cUs8^YIiEB7 zq|59odbG3pUG)0+0u|L$;&N#(T5m$o?!xdETqD?ig8G#vsxFxR88zg3p4T=H%bJ-+ zGax7+5e3Y;3fKY)_bdU2qp?<4$K?TG!b!HR=p6g};4oly8l{t>f~Rh(9z}%;4;gu# z4oHh2MAd5N&hIMI4em6wg-kQwan6qHEF?J8QrmafHLGVy-Qmt}Pz& zH?^rdfYzjaN+G4w`3kL9xzjTG@G1E5CdA3R?s$u-T;h=9&)I^Oro_SZ$BZHg*+>!T z5%HuhIbnxMm@?PA{IOdDK^^@YguWMi-aZlsypB9QJeMx#^BqqZ7q$eyFp-FGec7tK z^^oDI9~tBimX+sbJ`VF|JKfCVxBjf?5)3B>1O|&c513`Tec6IZX5^2F6Ng5%oiT2Q z-JDS^hVBf20L!uDqeNS9b2zuJBZ|ksVpmGHpjri8ch`eTI~YC4QWIE!ivAt~G`H9C)e762F z@)H*J1%&?duBIkKKbQSnV6GV&ife*BKHyMUkO~>#uK#nsVMppz^p_XKW?*))2ODsl z)MK}33qST8(t&Q!yXs%W1Iyml+G;iFi^H)+xYJ|$kNXd|xdw6PH9;*D#m(JQ)(4p5 zG1Rr>#f?kIU7QeMbawb%PJC@2^g!1+oe&W>vdt_JH#q2H#SuL9c9K( z`1E!E^CfTbhz9Y9)AMo7LRY%W-cr3OV(b~8kgagLDA3IqB@6H+#=Ujsp(C|st8eb zD7Lq6lsr|jnOX8v-T3b-(0i^?5E+yQnABmmQzs8!!dB5!uJDqi)E3|IQ}0y2%1{bN zg2j$8hRjq(G?~Xi?G4}GKek}eqa_}FpMa2=;GW)S9)u~j!JLW|svza1c51sNJddKf zqaOhv=`%JRp`=)~PvST;`A2QelP#$Qs_h4W986 zGE70v?$|WKzPA9`K4(C7kZE=S$pd%e1J>`tlpXt?f~E(|EU})Fh!dETN4keUuT)*K zwzE02K3I<1BVT-{z)v$Fk^@>hYa?^yMFw!DF(ub?vXJ~rix2obAQ_twn>>-ThK&uU z2oKQu>w+#*yk#!!*ta6m)tn`S`=);{`dxy9hp<*|4eef}nha7`kpUvm9Jrp7c60y2S9#w`3GEprg}ueS13kZltGSF)7jT zgOW~loFtDwk7cfHIFtI$V(t00O*{-hv-m^1qsA8AO`B_4oM z<_oy}vJb)@pyi6u+#o;VO6Ih zV`^q1=VBtaB8t99}-Av!@~4BJ1h_ttKZzyPme+kyD!gIpW{b27e3u7&ijy+~A*H zoH)~F@*Fu3Q0kCS>Y@>CerGRMuh49BXl^J?x9L_-Yo1VmHcHSmwyK`E_1DRPKVDAoYYB z029gs85R_J0y17C!tN;8r=0DvH6=ASFiybR;%xU-PGq)0Le>F7n^l8e-wEb^wK)L^ zZeL_VY*du=GI71spCQ~or{=OBoQ^FBk4Ga zXm}@juQ#5!bUGA>hr-C^GC_(g?;`*>&MASA36YdX3ekfHOH%!vqm>K^PE;7io)bCO zlmT7=a`OjD?mN1OMUI!DJ+0Z6Dtd%eJO1pDHYzE*jw776Qvvn=v0+sbSBwC?a%f0T zFM|^HV}aQAL9!zSD>5+}i0fEH6d($ivZN`1X_dIhzn2k$_YL4JX^SE4wb1pQ?-VEP z5jFyt*gbO%W-ps#^h8(Q|61$y$+vuwSsV5d4R(*f-FH2K_{8cOzn;5(;qeIBE_nt3 zF9CRH58>R=eg2Nz@wNJYjm-n}xW$aBmzZ_)+T5Cs4qYZkmVb+Ms@&i6Xfp6sV!X$* z2KrRM94rKsk^8xb_cv8u3dbruLL%^S;gnAs=AOP;}G3e|Q)Ie(W* zE-1D1*6E5U|B>N1=H*m6WMkX#;5F@(E%Jh!EaaQPvjEqNm}QekNx|1|EOq~36GHVF z_89>E358Q~R^ZE?xj)Fn60?61Ly+4Efwqhv1yx7l*AQ@BHyZr~VTIxaeb&+w|BI2l z`0FP(-L!$I&NFMFjtt&+B2KVZ=TEs$EFM1MjZjX@Ul^L;YY31(DUEaUUB7{$JvRWLkVit_!HEne8OZ1Ldsz=XHUc(5{Lw zoPpe$T&JACa=3NC}LNoG?fpB9e)4210B2{@ll# zDz>4_E>#0V?58~&$fty|x~&;kg`1KBZF=>&*U2i{%Xy%4-u&|UN8kXSev5^H0tB?c z|34?P|1NNl_)jLX@(#9kCJs&(CXPb3)^^TL|E+l$QV;V)HpB5I^OSaB1d#-mAXk;w zjGw992m&!56@bxUrI7OffkM_XV5;wGnwAA4p=DJiUf$TWR3Klm@LS~khp>2VnRQna z?&DL;t$XD)Tf=G~ywm2P`|Hikr0YlZ^P5hF>*vR72GG)e4kT+YtbH;{08+osXxM6P zBod_m)~YzT4!X(>IBwEysy}6B;%ymxPfWxvg#DcbDAY|MIt)3ka?oZ!MdDVp<+yFVXJEX7m zG46ADZB-4`9Ml=s`o&_uOTysABb;wL%1#%mmwYROQ8Nli4vaM_`nFT^2@jTSJpMQ&n+2nX69^ zDTxX$|E*;*KKCHps2RbT*jibo%wx4l8+a8D$(A(fn53?G)C@i~rl59E##-v<7!eO5 z5?$Iol>aN9o}SQ9rahgxe`!KdpRf_I4l{4(B6-8+#QJnUZ$LtBZZJsyXim#hy8hPG zhwO?fR@s_-wrnL-d7t5JHk!MnBT^bS34PiufNF3Ym<0a3rYhQkBQ))zekvVZtB7H; zGKwi1lQmdotQj%hWzX%gmA}**~S%Yf@#XQfqT9wx2}aHMSOwg zq47kihDUkErjyv5Tpkiw#MaM|o)*lkMmTM#Z7_v3IHsPOErDfNsb+CTaR0xm*l7ZrB0hA(( zTO~ku@YuSv@p7C^jer^aPW)m*0;OcT6KIqm?Y;-LBCxu4xQTiz{)*_WG4y8`% zTkEE2Jd~ZX^r2BFo|xb@f>2ip-QfKgwW^~`xQ_sbr$8&g4}{r%9JEkEg1F~|iv$@$Z8TgZ_SV(j=n-sRJR3F5U2> zEloYQ8Rfhti2(b*Ikb54quylSweDov ztz>a?JsQ4;t2TiP&d#)V#HV+>SVCN;q9#AT?3L0>X8%S{B-aA6&rf1hO~HMY#CE?G zTHu+^#XB5U!HETwE^ibCxif-H$~^{pHX61!3t|XR0g?p(pAKB%(GJu4v=5}cJ$K~z z)doe$H87;NvnSRf^$34l?kRU63>kcRNFAQd{q<{;hrgXW#C@ImNYSs&3CZyk?5Hb~ zhkH_6Q>MY>DyAyU_l~ukG&g&|NJ*W())aejU!7b=Utu0aS$Z$J>sdzMzVU_g%D9gs zrkr8{eul)Bh2^c<$O81OeNAG)`hL5%+7=?dv!2%tXM)l$*J20K%lWg_Ernu(r8YLi zkJIOm9pc1`I1_2L2+D{ob?!$+s3?)jmiUm?tl0dkJ@~KKL4lRbtYI>3au>u@74$*g zL33Rq-slgnA9&YL<&(lM@Jq2S6>n!oprga40?m#5?!C^%bsRe?p~EYV>=rmL;52e? zF3Q&gzIf&k)O^31cQ@!kdQfc}dHpipgS#tDz&VcZ4C~D9xBjs4CJHtHN zO|9~fRqt+D=e5f}uBOPVpq2NX0h;BFbjZ7pm4lckD@p8jyNM2ldO}7gOdEiJfPpg0?I+A^q_PjSgx;TzB#6iMk8t=X91J`Xxkhvl{yM{WQ;iQVspff$%Tm!J>wR8@36~*JSqQ>4W54e6gY?1j#D#W?`9R z2D6NnCZ@#t%-}d`tgH)JMp;IdiOU=*G6)K{LZ`y5FfvMEE;EEM0vxyeZU5WPo-)0M zh!|epnAfi!rZk@V%ZAlFRlW$j=5o@v*oQy-pB5MS7Lf#66u5%boN5V-pr1YBOq z0wlcs7Q7UN2)WT#^ylDPiLJI6w4A-&dG3wr0W-jmnL9um9WL+|UyhHi01Ph3gDB&R zV{Th@`dD_t4L#=O6AdtkhVfEhkhyz_fouA*pl$xlXO&8in_y3Y3unX|NjJ9QA7ZQ> zOc!z+7-_0I3V;mY9ve^_0HjA&0XS`a0zyjM0H)~Mko)TfUSyFaB>eu2v18^(*^TKF z790>2Pba2?RZ*$GN!d(Okr01s5LHR6u$ZTorKYPO?Q2pSNK2!qXgR-?op4BW|e#c!+Ybb1;;r5uK4c>M@xUFFYVDF1TM>fmPaP32!O<*wl8>W^xup zXpqGmORXY~|6Pt)Eae;00)yc(d{&ODIEslqKbc8lVD{)H{>DLLU>uKl)MfG2{{u?L zNzDLkBp4c3GPEtw1cHc*r?O~-*olS3^ClvhWh8ni}{A$n%Rt2(zD+=tC zl(m+R8k{{m#*z}oVmfo!2@?v{FxFx?%Yh1e5Vk&Xj=~rfdC7P(12+e!w77+or@Bu+&HJmGT`iHJBp>iIogb8sSp?ylRh~*h#94ttOhi7+4d@Uov zZJg$qEV_wg#k)e7sX)UmvN;*SUd~$MHM;X^|iqw9m?P%iw`TYvN#K4_IuWRCYDSYs!W3>ax9Or z^|4xrCVq2aaen2sG}IEd^AwzXm34M)_OKv;t3Q-qq94rhTbqYF)u zMGoU96LpGI{23}TQfA;h3E_t_bBkVy?Z|L9#x@2|JPX6BF~gQWxDEwCaibg-C~{sp zrkqq*c54l^8uI~Eh(jckZGBEN%I?b!ZLv4YP$a=<0dCZaT$JPFB35`yip|{~DX>y$ zRpf~-G&mv%ot31BnzYL+TU)xDRSpm&JK8AYY>U}u#RXmZbyaq=V^DN0w34AdZ#`WO zs#GpUA+577#hh*{!$M?m>r_$)W&;!wn*k$>NWUY!C{VbV$6fj1g8H;nbtpHxkP0*z zB^sboxeg4B=A_NvoNPvt*F84JF;!+FDv%%aTl{rS6lW#}WN|$h^7X;hr~tH#kli8I zQf?Yatj1OWkl6;pe6@8S@_jLGF3^L6=!%HdrB7=O!ZZEdngTy1j;=-^z5UGw0A>C; zyT_2;eptxZBbI>8#e*)~eu+N1TPo0=qdc^pxZ19C(qsc4s_&1R<~Iu_Y5ztb9)A_7aJmheo zhp^sk%=ZbW*M_@T1+F#}+kWuUnahVlIl-7bDE zan=Y1F=|RS0X*Fk04tPaFcXV5>xzw1B0duua&np;oXv8R8o$iPo^7Qj<-?#^AD@}< z^|IbBsM`1p4yc%y89L4G$!rDgBL?6>8rUHN7dd95_BykXM}vC z3D~arJO%(4!PgT6z2~Z^4i4d`hD66lV?!7a1hi)z96S>#RTu`+9R#Bqr!nb?Q*8D* z+9+th{JMD^^2dC?viq@7b>4iGgY z!f)V3gCgG|M+xDyq*3kzc8HF512i4+PIg*(iYJ0!NrOCT0XwNP*lEcyg|+!7ZT`-S zh$N!NwTf16Qr0Gh7!K+%P$}|xe;Yc+Ok9y*p?D8 z!S01sAx*OT9X6yxZ7JaQ2-QN>+BH{VYTa5C%=<(~Hn@cIn~SAX9L0VtMbR!1xuIkk zRtiP`J|I6geuQ442lM$6+=2>D+u=WPAZ_pAvoJKpwLEvh+1K~T?8#zd=N7|33Bj0B zBBkD0;X9N&LHO7K8)1*|#(&BEdv7+GOo589(gxL1%KeYekD4ahnx+W1Dw;j#MAL;W z&Q4q>?6y4Eb4{zmr5t4M{sfLnxkN}iy&sGH@N?M9xz(E}B(3<8Rq#coU@%N8^bu&^ z{Xj3GFovthtcB=iE73Uq3tfl$2RCiB9&bn#H7F0AL7iz`*@A{Cr1??@^LbpcxtRcI ztUU~68yHMtzI%D4KvaG2r{a#;#Lw^Rmy}-)9h4UlXg!QooFF>_YdEn8FSC5eB-hXT zR^~0?24px0u6WG*)=TyeqM~HJ+4pHsiH=znMIsW&DJ=vm__Mp&F=ydv*@OiXF6;+( z1#PyNiM?5OtFZM0+8hz3GG-r&*y5?A;5Cf`#9F0|-Z@7WL&qO;uGf9FA*cLGUiZTL0+dGIW{LP*; zd2ooQS{Bo4_((k+lS!w}#@oyLFtA9V&K6Y5Me1R9MNuNor!JDicJN*H&UhGiG7(-L zV3$RxR$3SHAlzYWDL<}Cp#k_?iePS9CcQ?=Tvj_SBd)^R4M*BD1Zc17?k9^${B#AH z56zNu{0#f9oV~VmP@UwSNx!_sGQGx z&nh4p9zwCz)GMx?(m61$UH-Y*|8qmp2sgVffW*w#S(msT{xx_X(E4)&@r8VUR4}*d zVdKXO-#^o}Y^p=>LkJ)sX0rcRJ^3G@M*iDU_OFVvNJU2uNdTFrp;1R0tqkNASQ$An zxyHIIzwkG+vXM;OpyYPRxx+3hoogC-L^mi9nsc?~bv-@i^P@ zYQxj@X!#nC@5e!%DSi+rum^Lb{%kK|GEqhmQ3+9vk%*YU2oV^4s>w9cXZu6|KL{r- z6FN$F&$DVf%q~+Q@GjRz6$GDMVT%eaL#-<`(fJ&d;8hUIm5WHcQy-*M4u;}1_B4bZ zJ+w(ZOYmU36?pJ$_)ri%^$&wZ0*LS1A{cp@xwsg41mIny^!J4U5^?bb_cFbZ|n~;+5 zj#c-1Egwm7RC!J%I3=wwfj)yyG-<)b(P;r{R$g0W_0jrvIINthb?QLTRTm!=x~OlK%xA)9KD1z5 z3#)PK&flhl=tG{Fm8<`FcG%ulo~PA10zY-~(BUiXq$eHy`NU;5&j3B;M6xYNq0pjR zvc*4`p-E_nWCBD3l6ihI;NYFjJY@WkGYV|7mm5*N7v`1GQ?^yY34cvOdI&`6_b+j; zkr@G}TXHW+jeF*;;j9%$hUB?;y=Z3-?+P;JM)d%Z4^*NQBVr3;*w@-2q!r=FMRL$* zIirx*I;@hqQ?)`aAzg$ePT46n;S>Lc&^KVQ1|1r}2duPS_pLAAA zjPkY?Hve1f+okrVq6=)lNM!t0Xt>?ieZ9w zl?N)_{DLNBYyQEI-eT<`zK}*D5u~tAW-aY=L2vEUnslBoH|rDh(y4g<_+!do6aMm| zR~qN}E&D$E`LpZ#4afT}r)B#`?XT-#g%}JC(}B`H4vndhTXI||1fAHCh zW`TDwb+47w+tB-3faabzy=d0DcN_*gjTuM(BjYy0m}w}FzHOz)tsp7u^)LLwYsga( zfo-IRKVL;Yf*(k8Qi87nKzz_UVwmp(z(zzRuPoT;qsB-KMr)yDlj__|EJ+f_hDyO% zRuLqB|0Y_PO^-OtOE6guMJfNyo|GOI)eK=$UAxkrb+7{6s3EZH^qEn($TtEVY{?cd zk{>9>Zo(+DXUb?`JgxiWg~42m;mlqNMm1$h&fv_q9Qm z2h)S3)Y+6AefmH&>;0Fb>ROPuV#uOIY%xE*!P=FSTwxg5A(=oI1VUuT@gj~!3*Q2( zpoM8q8?i}vnm;d9NqNjxR-vl}lflaO&mSMZ?!s?37oU#eswv6gCMJ8gpMhGMhkQ@9 z^m|(`@VG<`@>aS`vV94@k~_WXPgcl@fccI1HZrUugykvq{4YE2k)CW~pL`nWimp-{h+`X-n{oF7+ z&N#L^zk!yG_23U}&)lFQIFoBj^Bi&Jg%fq)^fgANZ=0j#_JV_-nwG+&e~~;XiH8=; zf!;vj^bB%wt`T!sx2lck3V4EECYbbaU!g6~mg>ldSC+>ZDa$4hSAbgz{hZ zgmCAZI^L=@A)~Muf@(W{9M<64wIXA_=&UO5v@S9fi^`-)UjYImGpz6|880k2S5!b- zc4ex*<}Ad^b0Xz3DXbKmd?sn4OHgBCrYG9Q5i%?6aks8E)%Q`}Dts)lW+Kqh#X6-s zay~V_BF9CXDiJoLKu-ICt6THeQ@Ch)fGT+)WK3C)9LMs?9_EmH?DJtf$k|RtZF{`e z?w#wUCtP7MXkifD4}^GNI_`YL#XI`SFIY7ZsZIdUrABv|_w?tgdwX+zvuj`zuC(h% z)=7SJz@Q0xASDLZpbDe=!qo1-A0qeY9ddWx@e%=VxQXK;Tx+Y}R+_;sI3~-9!7=tQ zj=zRa7TI6Jt^&o}?4>o3iCLM02E%_nBY8^LS3TsL$T8)IqbO*KHt#z@MF~}c z{jIV9K`G7%jLN!0U4C23h)$9O2?=Hisj$?l0EtNE<&>P_hjnNRZ;b1^I~shPE#_W` ziISox`~hQ?8A@%GV1|)IjG!a7*uj-j*ETTG)INZRfE@`AyUjl-oYg}6ZkMHpT3r0} zyYJi@+%7AxrJ*&#M@-}v-DUqL)dAu3XZ+n~ETqrMw~uJg5yRaT@tLuClY1lv>4jq1 z_gAQYV)YTlBV+a+687OLmqnC9fN?L{AE;e6NZ1#YTMH9)SM-fW3+gm2h?E*s@1x}Y zoZc}1T2=U^nrg&uFR5LKOsAl0`ydTlJWZN6!MMs6{E4^mq)W#xo7mVC1y@j%J-%7& zpId4>kAG|C0E%(L!T!U)G$x{l3#1!6*FAv0BhQ_i*JjgVSCVIXdDSluD?~V3P@S?3 zZP`W0hR8k;!dbr{A177_UmlSu+^R~$1cTCH`+6<9W6%OPRyafS z6W2S9OM`kQ)M_>Ag|%fbj=IU;xKh=2Tq}LI8w5T_p8!a#`_tS3Jv#$#F+{gDLAOn5 zQL*__d#0`gIGdSR7Kf%_^VJyz%ZfuT?lS8;#|n*#E_@KU}YZN zQU(l*8a$-EKJ_c1xhyBbq=~AG}W6v z*XOLcd+9{ZQbc20H64Hb7qwh{~xv7@&5+xDLEVd&w=Wp`lKzE2=bTAp4)PU^L#M;-pwL^-c*T%(AuyI zuXe^9e|)h$I0W*z2hU2xg-(O+{E=^~y}({Pu(-H(+rx~m;)0}#t@u0B`w#I@HkbDB zHv)H8B9Tz>v@Cb7d++P#qb~P`&-o*+h_qBELvMl}BGS6aH-7%SUZwhwRQVbx*Gt6OCg3ICTUJzb%v+QRT9U@} z;uLqmmU5MeO0x2FrEH1BR+Yo(u8dNPW+V20cB2&bCN0C4nj%c@zlj_KIsWM=5y5H}unxX`>TcvMIsWy6K%|pB!#kM|Nl(A|} zaa-eJY*(#v4!B>_j;?q}_H)iox17+u%qdJemY85*AeF0N9uyYZ${4bh2U8@H=N~jl zq77s|pV(FC)*Q}6jHG)oHxOr2kED88xqBSM!8dO4yw{M`#kXKKPtjo+I?A=SWS7-6 z+A^ci8OHX{eH}^+u~^OEjF=&pj~XfUi&4_*OAU>zB-akuJ%$GG-@FSCm9$pxF?mhd z&D!FYhwcZ5)A4sxg^G&B5x62V^w+{)WEzAfw>qltdTluJHf7~~x3De3JJc?PVQdfK z3J2+FcH^vMZ_TY&>QBc~_NT)A1eyA~s-ICcW#BwX?WeHsE`+}*kh{e#` z?z|@JmfE$8d%6_rG#SqMSqMXS=d#cqE-a_SoY@Lyr#1qlR@^UR%*Q-7n=!>&TjH(7 z0HYbz!;I58>W9;4aPF3ci9+)xl}nS&^2;OlL#c867)iKmIMI^cSWE~kyP1E^hep2VgqzKwncF_(3*J4Sx=an`HT4lJgaKN zYtao?+t>@4GuK^cK{qH{Jbp9_Vkb(tnI@u{j_cNw-J`QIq0#V&%GS|wrGK7{1UV!c z*!wib$s`@f@z+t8L=WIR75fX7G8aVL5??(+=}<61=Hy@RP_i&VVDJb5b8|Cc9i%^j5#M0QK&2G#1*J)g>qZmi zz$Jn-mqCqWkjx17x$~9rLKs3E#R;N7jqAjNTp`v+cfe>_Hl1(~;%kh4CLDBI5=ZUh z5Vp%$7F!faGi?t+KN9-4pHFoGyN(0=wx;7F@&VcOW@FI?7l?NvYvj9zO{Xhez-TSl zTw)EHUBtVgX6e+wUdxsvp6Mmcl}?0y#`*mCr@_fr`ODz*O^@mQzYe>97t;Jkt0UEK z6^)78e>eIDjz}Wt-mGm0YX{&Yjf<)j$_jIZmjVcu3GhLJO?EPV`sg3Ix(WC7(heah zP;)tZc(FC?Mh4|f(SX^UT{wj8O)lD|KscTw(#yiD$kpxb2?y! zR_%DS*zi)TqKjHKbf=wPJ*FSH(45yDJd>|4&pv+POzhJ%RJ`%ETX)qtOdLk*5nx}< zpkA#&SBQsO7XXn1!=BC?@b!(^D=oNU{u+`nX z-NWhnd`_iEbo7+cwN=lkRXa2%Du^_o{;D}_(>{Pp_0Pl}e$dM(*jSW^`W%C_(b)^+W^BvXpr{oy6+n4Yumuf|UAKYDtNae>Og-y8_UHR48Wb7sbmo z)MVdHbK|6b>t)T^67~#5*BD3VJYhkxX@B{9G-ocTQgJt@f zh{LzxnVRTV7IyXsc9*{+GZRkltSeY7kHEJ~FXmaWq#YZ$Y_CR~J1lp8u9ecDQC|Q= z$OOfvTeKnwDvGtD=uaexovk<>(eZEi>+{%X)LnDHci6~0QKo^V zJsw7Ij(m}9@~)iu#Q&kXGdHk%DkoyjQqlmv}R=h>OaaF!v*QHs_d~=tVA!IYfrK^j#`&i;bJVF3FO90m~l?iFDKxZ=-tK(LWjjf*|yhIlKt8XKtp!>8Ds zG+UUs9QW$?TXK@lQx8I3=56Q}Kb`d^bl*fZ6D!EdNg*Y|Yr|I9=F z{kYKi|5+Q^+L##A2{;)2V}2%SLB9}}crFkD&)(;%Vrj9`tO%8berr-}_6pk|kg zi1-fVjckZL4oZOxt8MCPy4|^&#rAgjc3cC5yXS(EVz)Y!gn4AYIOL4RhOP=}ktp6V zhfKL#6JQ2?0Xm>av>b%8_P<#B#^_wTY|EV3wr$%sPHfw@ZQIF-?VQ-QZ96%!(fO+G z9k;5+=-XYl`}h0)+T&Ss&$ZUvbGnFd#@`78G;OXLs<~A**2|)2O?qmFND|>mh8(8M z)$@#k&IudDDH#1u9u}qw%X&}L8;nuvtwlXaJ5kmzYRW@Vd3C8M@DPm}mL!AL`SqJQ zS_wIr_+5aC4Fb&&A(lAyj=I1o2ZC$uD13s+e3DBiO6(qw6gd_F(O_tV3Xm!#2W86%y6K#(|>psmo! zF>9fdpp!6q;>_K0t}SWd01@b^FGiMX=hu##+#Jm!KW5@{{2>EZ4~E5Ti`G$ig;?Rc z`Zt@dfg=8}orPHyIjC!p4z4WWfBKn*+gsX~XpTVx8iC4$Yl7-$-NFX8H{=>w)yXcUY8g#G26og zF7c8(NJXPk*%;jJ6w+pE1mISMvY^m=VDy=|A>_?lu8}>=Rrj_8OjPn>kxZeS%!9Io zqG5p1-->2rl!vHQr0ROvIx&DY^QtCE!bYy6KlLHT8F~{U0A5{*yF{9Gb`{4o^B!=o zhSP&vl8SwKYM916c~yiWE$O*`i82RQ#zh;P=Faft6280vcCm)Y4nK>ry`ZE?3vkADrFB)sUXLwghKkU?BaT zUu<5kYhe(8SN?;jv2F-cCgLXb8Bcn_(bV*ZdB%ys9Gv4H9@i=FDaRbotL&G{=|8@} zaY6FIo9qaKxLHwq$R5G&8qB6at7I9U&bS^#;cCy zDl_-gs?Joo&C+6%mNrd7+50Lv?T^mC`Ex=n)r$3}%1Y*m3RsUf5zFU>vdUU>CQ00k z`|jT(oqrOHTMI2alpEh-u+T{7T%7X?U>j{VSlcKNI{0TY1yTFUJV=z(C)7I z#?Dxt|IBCy)}1v>3-J`}yHR_gr`bpBGp)o(C?hpa^BNg9ZQ&_5c3@UatvBm!F~RDC zCG8L3b}#9S0>H3qt!ho75x}6AvB@1ZkLe%X^;#{=VB=S;UWA>t-^8I9MUQ~kLnu)r zBgjaZxt4AEmU9d_s5pi^vn=bfN?@dQA;kQC&eXr_a8BMhGo&e_T2q#pG*<%ZPp3kT z6CB3NrJi!Dj#rez_AGuKND-S)F+G2;B-o=A;I;14?u}fj*#Ssk)KR4OmjIdGbq9G9 zW(t;q)ERD!Vnfy%Vt`m*%Fk)4#9o#L!E8hB@G}9q6sH{FSEUa$2hoZ$VJN|mG>6ER zRm#zwcNa)%pgn$+?`q;a;@$HIEMhvaB4E9;QO3UO!~& z2O$9DsPv#@4=6yK`p_l8&vV(Qm2>Cqf^jlU!b)J3op-*P>9r~;IJG&FOZK%Lb=*J^ zg4nDZmDx#hkciN_vLQ@$ps)(?RCT91?TL5mthU6$m_{)vcC#D$oi)5n%t1_ilM_Om zXi3Zo9G)=Sy2bv!aPm+Ue_~-PhUA^`#NXEdUhs26nb{_v4>kF9YJ9ysuO8q!ST`-ICqR>zB~(z z+4U8K*mr!{peCIx@MXjCK@z3u0#e$SPH8nwG;dgYi>G;Ah!x=S738Kmsg=><*#X*p z`f)wK$vr?O`k^i1056n1(Wn{7MO|4oi})&|0z`t0w`6ebPI5ukAJWiL_x$o{p3 zcinC>m0D%^@MkMjq`)eF+jDO#C@*t0F7d8=N)>5h{?Y<3z);S3rH*93BL>nWH^3Pt z-WkXyZvKw}9xLBxVSYr(Cjk(yJlTqpzoI)~k~;&5 zJ<&>5JjLst82WhmbG(6Ly`!)$ki15C2W4E4npbJOdU=PZFJM(xQoC|wL?!`wh@L@0 z-ytRTP&v&8W+d)l7SOgYwY|y8#rpJ}Ko%W>JnGmMlVl!3-j~wIZuGGs<6tezq7qt3m$-au3aPbjws!p#HlNdXk&TzReWU$OR zlITaYoZVI1?Ecg6tf+UAm&<(jqd;x<-#TC6NiyG$@6LAt>K}pkUkS#)>va831mnM) zu4N+n_~CI0B%SQG1hHoRGDkX}JZ~Q6&oJX*Sb;)EpW7m8b#Rucdb;ugvY% z@#n?k9bkk(B92%b;&jy8o#t%}T;HQDd5`2vO=q#0aKc3e3yo6KOH#2-Du6+M->dhm z*omT2Tbm23MMb7{Pf&{{y4%srlClb#iwf=2Qu_cHo)pY-&^8)U0Fb~^-71OZ*{v(W z2K?NYsNNme>6&YkTzFZC?-LjFCT6dgL8xjx#P%;LHiZRs-~N38{j<;Yzmk6b|CcL@ z;qP4RJ9-52+Y&rj_q{@;7q>Uq63m|HN*Gxy3`!P$KCh}UoLK(af|lDa6p_dS@R)(= zZ>QA82O!NL{(VXybAg@ggPD>IJ$k1}e0FJB2g;Dp%cADzREihuNvyInXliPzaokeM zj1-#7OK#=Hf17ZUCAY6hsl~aFFl*4rYVBRr`It)Q8#2d-4Fs_pp`=K_g2> zL?Bzpr_#49U%0O%%!p+h89x_4mf#ql6Qzv!%!tgXA~efZZQ-I3G-m@3wkjsr)#WZs z-uNJgfZB<#(m8MTD?x|@oI~M(xj)tj5#1M++Gro2ggvK&{VTsePZIn}0K1|PXN+0d zYuUT4Z7sK+dLh26X0CC`j2YbXVY0QY$@Rl-sd;|6B)q20-`s3hb!w@OJCT-pg?7vi zoJ+Qt31kb2^UDx6C<1|05F>V=xwr0?3F;ge{_)&Vx^0y)b~~d0VCkhMMK7r`zRV9msmxM;qRM zS3U5L-SXedX7X=VVT*jnovX(rK|#id{K!I#tKdN3#Qx&=_`Sr`5Ho(Lq=~8Y?CBV$ z`tp&U6~AefDIz7SGzwBIez6LeSLnVeudgk&E!s4Fbd@h^SbtblRYCC_cd^-$CITl) zX!1T!dLM6IzW-UhYJEBc!{d3S0l41jhgI`~rOnbJ*D|t?pB!YTb-@0$=T_{HK4xeE zsECBa4nd}wa*%uDW9c0{9zn~6Y|sVdP}>vnU5+Rv9C}bWM}FK{HtGh;uN>D--2D+u zm2SmA#n%%cY9oWvxH<#lhp=aI`h)7Q65{sZxi|!v}kuN z?2(Z#TGTsB!CFcjb(ofE^MtghOivnAIg_0!cJZbq8Jxu_4s}tH9%Qt`C|X&D!9HA7 zZbilrW?$5)T_p$|W1v*k4m})h)hJjvGk(b`Rt`O_D;EQcEkhBOI5Sb_ZeyrmjRsWB zRmTQ_C~OW7WG!vc{x7d<+U>R5pU_pt%Q%AlF_*SC!9#qq<^2ZwI!6tLEz6M%2cC>3pH+rlC zDJ8C>-?{@~bs+F{pC=cuu=3s1*g%W4QFiLr*k)>+LOHu4rH$FxTCH!4(XuR54H33e z73^AD49F@fg#=iLkrbH88?t~us*&@X1@LCTokPU8cj@pmfC+Lb2bjf#_P;w(Zyzf5 zGw{j8)Q<1~=IGlJA07W74jL<>vD6?c*C?R*cA@F(lO_{LW0u2h?}tbqV9IiwJqcdv zt0^z(Do#0E+4}?OVR!?szmi?%Gz2Ob*3`4vvf19Ri4pq(lsqoz?{{WMs!>qIgAC{5 zM%1qEC*&g3VmuNOkB?PL$oP<4m@Lk|0~2GfO}*tUM0dW>hsgN5dHBOWMn!)nGWgEO zW|4K*a(oY&%3`>YF~d@e9{KbU^c}4XCpv?yWTA4|YmL-P>$?3JSrTzKzYg4{a^lV` z>knYW$~dC@ci1msyGUU~kRUORX;S~I!f&R5&+L*_LYgf4AaWm%ReS7wS#8rOk_xA? zI+Raw=A}{(E(Ai1;c*5vBv6Td`8hZK=sC2@*d1<(Y7FT2gHm# zo;cQXaAoE8VSHmnIjdDJrX0gcDCg&b(V_(-8?#J!mux~Lf+g0vh{ImkIXSsa6ie^~ zJdjR*6M{{M-LUT!c7zz13fIU3Cz6i&G1}%w{fB&&M>LzD1V#~ye)b3Z3AdeC*h=V>6!C@eJ{>$Ii4|M_(y^7?;5&`Pv6U@l1({gzmTt77|Sfqc@f;#kcks z{93pBFiiJCdVv@Y`LzM_$cUkKgrQKPyi22^s=Ojm7c}hf!sVd%UNz7g_2YU`!wTc* zRR}Qc%~cHL)oHIAa8I?pO-#fAtH9eh_P!_pePVd#TIL}va9bkvb=SEY$pQNWorkZ*2ZlT>#Xw?TA+LyQ@io8#&T%8 zI9W*W3Q&98ek0ayd(>QJy)EP#8uWVo*`rsDNfdXoGu&_pXn*|$N^1g_0hLElFYr4i zL&-O-PD!7=0^nRy@~BAn`^NTr;utWP@$wz3$PCfiZUAq=r?_(_IdQ#kd)oN zP}s3=zy4sR4m*5YYZ#W7z>CW%8=t0-CEx)~C)b%0mlO5)?80PlVV5cqBg`Wk>q-i0 z&{ZM}vh=nVs9l0+4=XxsBU=hVh(QSxjiJ-a6a1)XkErSQ2qUCi?#j>7n9qDgr)+$^ zs5=oQh1R$i%pWDQ*;iYJYkD$2@*t)7b!oQi^nor5{5fe;<}!0L)yoSDs!lgTm4?#b zjlH~?JZ!5iV}}TJbgi=2iY^P#K9Ak7xN&rHWurx*Os8{r`WEcaXQOwKNiH+8f%o+B zLx%wlkg=PJv~vyskFEjtN(_EvCg2}U{X{tJSV(R7iP7;&9QFdecUs3Wp$52-W?(2e zf$#z#g2RJn*BG>iklWTbZ7L#ywnBYX-IKZt1<4H#M`6e2CE@S+{P45*kaT`Uwhj9}P1~2s|nbS8ztlUd;k8FY}BKro}-f z(*Essggyw}Kv;l$)J>2*)s>tb*;RhQ4f;mNp79ZsUy|?*7NJFgrwgoVzpS1M>-Enpq>D?WzK9gr5M@uO*lNFlH3oNz- z9xrV$&e3EaTdxdvbDw&fyD$Tbi`h|aT}F0S5q6&vtVemrrZj~%5*pXI`JzVmctm!r zT@S)>@b%Gfq8?$ai97Cad|ZJW0&q(#nFFc~_FT>K@IQU{1=Tq7q3-V`_Ah~GhbE}b zFf~UAyO_?HJ$8;8q>-|shGERRmuOjvz11r1Z83#xEb`n3#JWfdzQp4{)#LfB76%Ow zd_B2`(C)4hdRNL++na`M^bFCq=SDOynVIb`r_jz`d$U!`aMnU)rA7T<2qH-(y>+=? z7h%=Pp96$(QITd%(E@KXD2`)bMl%mb-D_jNNTQ`ZZr0(!lM3ipk;ZSD%fZ_)U`UyZ@ zOqTsr3O%byGjfmDqoAN0gvhnMke11Fi{InOKg$g*31u_zlJv<0KLZyHvKzr z&8=ES?>oABwP=up_Ku;ped1$BJh$OTySx4tlP}qk8*xG@tZAkAq?5H5%r)?`R4(mS&DK6#`5R_?MRBA> z!N?lMUCpFRkQ8sOu%D}YdwtlmeLF|X%&w|;i?MtX{B1i!E{TjH&*Nw528YH=PDf}VPpcYnHpULn4!gRz!pN)c6)wDKCt5$o#b;+JX*DoWQ) zNi(0j?lcIin_cbO;mEV@eFJUG5ND96`k%FqWvn~KqKCE|4-#vw`CFL#_V_r9E$5&d zD>IfN2fVCVwIwj79N_u*xq6@4``+|eA$_EICYH9=4!8))6W75X__HX@4}ouWh5A$Y zZUAsd8#ReskMViDkRaDGYlsuZohwR9S~tK(s?5nM_du*qS#Bkb9e9!nW85;pDJ7-v z1S`8_f`0qE>WGU>^e8&t52btA6^=>z22IduS%t(dgGOs}$w%eFmV9HkbcL!O)`U8l zS+IX?_aYRqk<6qP7kt4acaz-HA%&`fe^dm0q6mJylFw|j65cl#<#pp+&CKe`%EI;~ zmx&q;>1;-fVUFkcLA)FAiq}Qu6c6Pf*(Mj!9pWh5>V|)`1MlGN1i+29^9Dc;Bz5M` z(PtpC6Qjm4!&mFqVh+&F{rUNv0Bau$J3DzH#cWB+#S38aLa&;PsSMUS=Csno8vY2u zPZl*yJ<^X&KA=V3H%gJV5hAx~p4ON_T-<)*`ZTQ1$&NnnPr#5ZkTyjuEfO>;lSaun zm@uO-N^tEe~3Qy4w2P@e(_B;X&@Bfb0OLqu-Q z4&_9xp~;9`_rZI8Q#uwZyAh+vJe|i(X_!VMM?9PhE%poaQ8R+a2IV+ei==U=bJDe}Hju&R%Gg8>M@&PJ0nCgb31vfXe^BIuakFJmH+Vooc zy(sQhatv!K5F*KDC|m<-p5nAHDNtcN*bW+(z}Y+S;F^uysg&(b+h*ADOWT)V<3ba6vV_wHESp?e4P8Dc3|YwK{ORgi4&` z1$I@@ILC|=oX4j4X&cs3Tcv7}Ik#^{#wPW5#n`CzRdqRa>U^?@_X)c5PtA1pCN+s# zT2sEt3zoAMreza*8X3#mnee-@h_QB- z!i#}wqpoiS$}1vbwkM{HT{%Met?+t+WY0LE>U1!r5}z3{Y}r@Q^hnE&j3L!(5->h+ z9j;l@!fFyJI)5lXla}pG%f;FXA$0+r-)OHy{fU?Ozc_e{N5TL>&$OSq4BRsc09$j53{6ybEZ~nM0KwZdoL_ zK|Lv)s}#gV(o8?xPOj#DnsmpGk&5*0bo4@(Ur$a<7hoIN7OIb%?cXvbL^?8b=0|a@ zs9))l1%5ZE#`V*G)u0k-`Rs1h-Z4K$h6zC}?Awf%HoXR>hS>0EpUAdaw(p7j*TK%< zwYU8&1A=Q0Tu>tV5Ai6kF>ro9;xn;pL!P;ZxbUC(zrCZth|6Sh*lRIH-a9hq%^>pN+2ati?wp){+Q0&GeBEmxDTzZ{r!fYMH#VPYMQ|n_&+w&lvAnYrX_qK4njz$zhD& z#P~Nl-Lb+YaCw_7ntkG@RSrO6_$H@rayTxHw2QL3@Iu|;Iy20#SPGsqIqC!++IfbN zmf6@HTDK)V+!^3fDt)85D{} zs!UsN*j{cAyWtH;)#_Qb97!g={VK2_)k0ifakPj!p_?UZda~y#?7HtcvEx4hwv)E}{z&-- zp_vcA1mBZE^4a!d&FSs{o!XwnZS`}XdP8#I>DAp6OeOR7H5d;l*9T!4VXPY?g%~r5 z8dK@euHR6uhO>>Ywx~`au(sy9)Dp=7cN3IM2V0V(z0=5Zv_zbxjTOPqQ)oDv9ajZ@ z5sdxFJb8ZX7N*$gmwd*NUzHOh2=ktYHEz*GGo5k<<7Y<#-tbQMan!DTq~agap_P8Z%^~%AagBf{VhsUHy1ZN-9t!t?^Ld) zgrI@k$$rXQfF!=>UL_iKIYq`Bn3qD{X=M&flOjf1${i&>fX-OExY}^XxK|$6ezQ@?$t2(B(&&pj zD_2nlC(;vNt60YJ4F30PVG|?A!(u#u@lQSqgRiC^vBLV<@{2TWIAO{LQxLVHl6H-Fhks}0EB1UqfXp$ zfOZbpPj>?8lnT8NEg0NZ(3J5=y-qDC>s!R@G3TAsR6#YJAGs;h{++jy?8G$zUDa-v*%%85e?$;?^yk7Xeh{L0rwQ{_8Qim@0BRK4;SBNU}6tt^seYpe1S2~jV zU({N*pz6cx*S5XspwZNz*{U$ zl1;Q#%ebA(?FS~|GIzEd&d7vY^L(olOHZ6of1Gj5v2gSyuhL$RF&SR}V8k}{@{J7s zo=x6Mg!4;hwLBjM&D;g@z7D;P=WXE}%~1Ht6C>+l^49Y*bUVnq87UYv6ugtW6Nig-z#X4C?~|{Jj8aa+)|e&DagmI9aaaY`uH`>zNXuEL zcy5}z1N2~>X9Aex``g+tl@PX#91Q>!(NQmqP>^XP?!ocjFeMLqmOc5A!U4(B-6iFW}nqKnLDh?R( zh+B=y^zIP?G)p^7%rd`Xxb$7!M&ajhuMN;`>+qpJqAMw6l3xOs2#PgJQ2F{>E4T)ODz4MS;Qc>W-J((HUrP}Q1QpdIuYPL;ICX|C( z*@yoyb!>-KtygY4O+8=}{h8&h+~&4=`N~*rN}_=diOa0-r^)OqxXMa?0#$-uV;SF@ ziZXAZEusBjo@ldbQ-DzeUFsvcz6mfthEDXKWL#?1hpM?;=yO?H^z~LQS8v}tctP34 z!^YHkAaafN3<;4r(NBYRwV1KPMLVgTaY}lHrzk{`HcJ~20a1j$v(|x1IAiX&;xb9n zN9qhddk7bvk8IWlb5Z1W@4I<7RPfNA{me?3J#VVzhIHvNCU$DU$G>yEYRU3gz4qV~ zh*RncpVv2u+O?neE~$$SzQfh(A$Vn;!S}_{b1;nClEM^A`t(b{#`J-D%oreNomcje z0uX~A255?NqIZMVteb=@_yxC4k(BgW7nrjp;n4kuWY}eK$R*JlZWQ5yWS#e-q(YiU z8udlG@VJPNvSG-3{8z3#lxPJ82JCm5L=H82B<sOyN#Qdngok0TO6@i^Y0icpyEATj)Xp z%A$_k9tJ)j7Uis7d8ZHHzgE#D?$?LX--Ft_8d>4`LQ5#Yo>;$9M4DY;xZIU}JK2z<3aT0gJ$1rF0L2%K-8$JRb$gN0y=zU7kIF;GxQS_|=WL@dx@5M@n zik(PrRFK)=*LN-l;jd+=)-~6dO5X*|M;}$#FX7+l~haI9nf&CMM~!o^m>hoca4owm7Vp7 zU7D`3ey#q3r6skUMDVU>rBxx2r*J?~i+oqXaiyS`4L zBUl6$a}X@nJ3-t;(c`%SGbKjb?X){>Iwg9lyvX*6z}pYB`n;3;EmNR;-t|#Ln`Sf#*v!QvDPi zHM_)nkPevDgf)41_AtXQ4gn2Nm`B(CL9;;FhHy+K%;Skwsa|}hAh4E)3cVd6gp!b` z%+z~AHcvz_Qff=r47v&I6}y-zB+z_PyTsVLyXYv9a|&wOrmTl=Z9#R%zxDR` zS)ymE&>ep?Y_`Rvu1LmWX%Ck%9)G zd1qKcN|RNdX=>#&?TwNy`bbX-9?^e1&xC}ts~vXypwGgZ^IXqY}8Z2sQj`& zJ)G>&_2XYo{8}c)JBuGyV&STUF->2VprB5QP-i02-+M8Ym^#XAYa@k%a%bY{CfKpJeu;rt00YQu&8V}n+;rtLW4StMX01_|zJb@*I=rlyb z+1`oEv5U#OyW$y8+~kT=bXxHj)Le#LcuSKw$=uebPsSgj)!9KT%f&|;vxzW&7mqdA zhWG2zo$YLl?hn_-o;^MF@+;{65+5RBmpSK}F~ccANvIR&EY;`v627P0Iv5*SfTIy)S>)2ZI zDyL!p{!;_ZGYlY0uaezfVkm@72B)6NHkI4JYDZ|ntBy3n+trg?(`>_{$23Q0)zj2b z^ZQ4nW?8O%REG3*>7~IyJDfXKrzXvEOrrb_tif{@81L5T4y{_Z4vp6LEs2tBz1<*b-6>M`lw-($j>X!mDXz7<8y-&Sn@C651Ba8mrA zfYX0UmWhAbeyceZzuz1hi?|sY+c}xr+WZ~0sub64zL^HkIx$N)wnv}?)e|5EoSL$( zA3kwXVFE!NQI@bEw=kAzMvFs7N@ulScK{kZqIk!xe3<<&z#k}RH}wrno<|dAM;F7g zw%b4}qE%6f?AANdAg1=!0U}oDEqXioJr0r*`29af%zx!~Z6d?Nft16b6lsWh;P*#K zP5{=;e|#?n>B0cLb$`jNV}c`NSx5s)UE&jxWk!>qj>?b3FE-t#t1xoB=?04Mz$o~$ zh`FzhL>9?bneq;1P(h`+Aj{8z8)qN}ZZt`frWnm6QR_~cY{ao7dbAnJh);@>O;<7J zI6P?$D#ypNL zgH~s(46q=PR%5jg%)Hb@Loml46bQvF>UZN6sbg0N&#y#N#J}{rGBAJQ4~bfc<`eDc>Q-~4SvL*+Ur6&ufTvO%)!*VAQE0Gs~>%okF^tQcT$ilb_OvV9DK_h z0q*{YQ%p_o7=PV}Mn(#8_um?m(SOp(|9|1Le~E_wdXb@MXJ!7Mp>#@8-(q>>PaE6u zB4^;rh(BPE8lXnxVfgU*h%m&52$96pp$_w~=B62^J482i4##kEhRmNp{1D+#skHC% zLypBr%t65zs5VoUM{iR++pSD|zTR)J_^~(8b0?$tftKbG)eWOXvrvgLc$q$|Y{=BX z0{%vwZL{#`bZ$PY_2({S`Be$374A0u<*Ne5E0mTs#Xw)_i>0cKf08cB4_iGZ+s;!l zMR26S3oT;CiD?pJ&VdyHWgTu#_lP`G&9lsHWuO|-uvMpR7gTa0(47jG{c(V?cIeT=ql{*9Uo zroBu;89kgU!+)e!y^GEk)D`6kCB+0tRCk5eiv|@Naj!o)ITh+-Vtn%{gTH#1_WRm9=m3C~IKp!b90vu!t8~o=L zST_f}7wR#g9S7i(-7($><1k#Qbs=l>Y<+7grKILpoNf@|ZL{1hPV_sj`pb{(TO!&K z*^`9aFN?K#E6L6^@I|XO{=GOWITPJ4+JU7mrgnl2tFHQzUwuVk3h`}~_+r{Ef<_Qp zFdS|6j2jXGOI&_PM$?I6V&{L;Cax#S&P0F9=V$-F8npbqon!b%gO>jwg()4>5bK5f zP&8&V*1>TAR0F9^dC0{1Wj{24Sa(9H`F6MMhA@U5T~gx|PA__*CJwe5p0@6?nvXZe|00J}e)bFR^Zx$bsR;$c0WCqQ zB87oz!+>y+0&eykVer+!vysby#KvxFkOmm5_&USid2G);lz5$EbD7Y0DPQ~DdLJNW zAJ$9mVgv1j$UkyGj0JjL8s%w5zB7MOlsQb3#zS-x$0O9E#z7XzD@>e)s+A)wl*cJZ zR%aGFvM{=>%-Yi7?OH_7B`GRYEHm=xN)iBrqyS+j5yQ$(OjIZqmGLss_6l?%t|^Kn zloRyh^HMBrD%_1|Aodrao5AlWe_aQh)yHFf^VU~;j`8KDnG`xRV? zv>QBf?QdXo4Skx>&!8%|q_1#q&QdXQFh|*Yz)}s_A0@2yYeo4;&kF?=q@}KNGCC*p zu2X(>>V>5lKk@Assc-rI=m4@i{D>KdHp96xV|gp=vz`ivCfnx9T0zNU&1lLx@dLHq2JLU@~v?MO6w zBgVyeuJtw+BKP$qA4CoCRp?4PD}lqZ623+yhw(Oc)_y@k|zv#?l%& z8O2=a>Z*q;1$%&;Cy>&o>&vO_P|kF(+)0y#^3A${w{FS0*K?V;F z+pD-m^!&0ebimjJPjBpw{?Bco@9&bF% zPhz1l{AN9O09(me$CAzeJg%wj@C#LA`lDe(@FbyZViNo#>GZZCd z-ntX<6})aIZQ0iF8U;+c0D}GHCm+R<99--${M4Q_|5Zl4k0IthA^*sVf4S5-mw#@3 zrU1p&h7_}WdEpEc%IbP*s(HVj`D)KCRifq_Z$c}8kNF0Z2ik|-S^~0TA(ag{sRUZ; zGd=$aC1a<!sSQCkUJ}FHT?((C7@zs0c{XSM=4*9j?b!kBCfE6gYt#ubmK2eS{I(0XLKjwC zb*rae^VKq{_QPHy5j(8upBZbXHd65(I6#*JtsG!3=u3R9CtiLtV+c-PegzB4eEG*Y z%9Gi|u<#w)eyKMREG3^Hf02ePeI2i{Z>IVK`X8CYY?dx=9~jnQ=%wL@EmLEk~KIDi%hr>zHtb~;OYux{Xu+k2sHQ22%jI{OzIS} zi8zyx33`tE4jF?N6;;IkL2sSOYrUt7>M_?bSE}~M-FB|;kF>t>7=a1Xyj>&?>XF@V z6A`D~l{{NzVFbt$uGDAho1SxP$9p>=foC7HX;!*NzC3m7IzlkI}n|;>B7@ z7JZctk4?u+lTApA)XDPeGs5fUNs|InuXY2D;^PSC2JVNRhD|*Uf$g@-NXcLP?xpxx zZZX$1&4evE$GcINYrR{KbX z=IEKTEmt8vh`5WV%v2-G%K%pid*vohQo_jgeR zYjODjHd-sPQEjwYJqq*=?7ZvIAL!OjP^|MpR|g8xld{tid&cc&8okA`1un}2iR#Jn z=gpaS^7h4!?kOcx(A43>eYRtgYvpxnf9P?2`s=i=HqJ-}4<~;MsV@nwFcO5Z&qEo^ z)-aC?7GED0E2Bkr(QM#bEfPw3RA&OPQuEaog47wHM36lUiw$tg=Gu2Qp<2h!jbp8Z;X!sHFvtTIIn`u;W#;`xA+koRUewXG` z1~woTc}{#ZVTaB_QU&CgKpj0x_9p9P_Zd_bwp)oKm*PT@BI*ymGWw=KTimw5(UaU8 z^>F-kCWI0CC^c!gKH?jqXshN9?ZXY}ke^(FOR`)-ieetIbxG?uv2Y3*`*@8)@U{V$ z_wLjp{IXfLXbWU(=VbE2y}A4vHr5x`nd3dmCx3+E18wj<-He0mucM}%n@Fdy@=)Fh zMn*@1TlXtPu17cMKRenQ=)^ToC*SB}@OFFQE!jGg%3TCFLk_ACMwB;1 zOlt57HS1d7Iio@X1aV8%IDup|m&DY5@&|gt0PDysYIHA#p3g|_AiXQ}!a`s*cq{zc z8Y=*os8)mzQ^t|lbM9z@9xxY7B zKy)MWUKI2`<0!ecd)#-nxOso~P-EO#Mi=R@pdKZ{muN9V9|xpwPjdll=Sg%vKA z@>D46o=as$8S{{bra#)0kFDrazZ-@rbqAsilVqJsykOa4 z<#{)Q8K*TbB3n?Vn*VNn9t;NMrumIzL~#FzWdGW8)BIl{*+0;|XnCoh{q*qO^NliC zJ|OmBi2k*dE;5TK2FfVJM5q_Vy^`7_3=Uev?3hrnJ$djy+k~j=(RpG`w}x+@rjOD5 zD5eCng3^N6NunGM52#Ed>@dir3>|yBHp%1D>zS2lBwaGG;;9rVO}9nbvk*bsbZ#Qx z2SyuG-DiLAm&dn8aFueSYqv7Dl0+3vQMquPm(5Qtyc9^I(R`WHnl?SPIL~s^CzzNrIhR1?Qd?-(WGeTG495kH>az8{___!I<{eXA z<00QectZok3I)-`&_B+P$a=D0|K`KlD;?a|{p)h@#QxFr{C!~S-(BT@jWPabmxHmh zp_RFjvAzwRlbM6@_bdPJ>4lt?zRiEGN7PSUk(80YI$2MN=gr4$0-*?Li>MLcYt753 zY4TH8nf;n1At1uY zn93Yt9{V$&t|r=_T%Vria=+MbX#A9)rH2qNQtUdTIDNKyrU@{3q3`U7;MgQuL`316 zLF>TEqu3Fpad(S`#^rTLjSGL>)vEScGaeC63WZ>pVCmzN?Q31^_Z}GQ1fU52Xl62w z3jN@YVyfXH-k>mKxJs~V<`+uMS*)`89;D^!llEKulqqbq>l-nOvf|B>uUg2kQ($7u zFpddzEH^(*u`znEV(hTyE=g}~%vj{yw82?OU_RGs)9h&;M4tuLc)hP&(j6IKaV)`< zMKb=G8!tECuB>?cz&vYObl=evLJ4dUEUbYyyI{28guJUH{2fn={t-M)WZGL`Lre~<5>_Fi$O`g>KHxUQ= ze4_dyWtvg&wk7y127SMJ{SPt;e4UwjqK~z-p74hF5}POMh+`T>8MP#b!%@PnPhSr^ z(FxUt&);MPe7RERsL4m@d{i?KRYOHMo}$qxHaI zqu&WaX)|N%8RZuR>1q`Tbw9DE91=ril8GqJC6P{tqLrAymBoD2yT{U;v_C8zbZhw9 zdsL%I`6}=YQenx8*cq8LQEsfqMRv@ZrP?LGhx4=xk0w5z>+%8V9tlE?S%x~u<;Md1!LCE>2w0qH2+A?cv5UHX05+E(AF zirf*gjEp^Wju=Dk24qXA7Tb)BJ-80J)!Pnu-f`F-WC*#{|3-ZTgv+aRjllGQo(t~O z8iLI-w=eNZU93KFspy}R4(nU^k1mXk!v$Gv0bvY~m=VfETrZGPLK-H1%#^Y7iY`P+x8>O~JQl_EG zg&npnu68|_brk_%t!ABKf9A~l84Vg^P0B1L&{@byJ4F;%?IlR_f}a~VW__ivC`{*H z{XcccGCZ9c(v(z{lM8%HpiKq4^-Z49FN@(3V+8}ZIbV8`59Z?d)bnjMmLajIH+?{ z(`Uve=_^ExfQm#*syy0mE}#`~GBy8cOeJ>r(Zq1a?@AS%zQW)B8t17j4LGlBUeV>0-&@gYTE-6{)vU(vNKzjsB zogMk&1z4N)Gd3$&4W2SplVo0LFjo6n>DB~Db$U)eiMG=Iym?sUS`pTiapbH9gje0O zWQXpnP@d={eS@o`LY3iEiSY@BeIVAM*i&MQ-|l|Zd3t|Qj?5XPQx?ju5^0iaLw z_AM&DM7o}D@O_DZU>5dbmc;pt`y=K=PclRBTe9l2E)}leJMV^ImKWm1k+jokAg>Xs zc;(NHLbq^{SKe75pP?{-}GL=Ts9hz(T!;%-KCzCVN|m34{*h@bQ8U z#Pq?fLIf1ZW)HFkTfj$RMwy7<5+ssDyE<~d*vAV5#InCw^63eL9R!E#YGG^imXN1# zUJ;LF_THcDaOni2$s`_Afu94!747%)nQW7&*l6q7SR3Xpc;-&}D5!BESr|GZN0Lz% zjtG+{6>sgatC(&4@HWl*l+!|^)xsv#f^csY=-i#DIPF+i^|7k^f3F1pAci00z3BM? zy(ckn^4XMFZQTxj_uzzv*~iub(Y<3rKtRh%Xg)kGKSAiD@01_8cLNVd+>p5!_^um8 zk-@=mhz3fqDsKP3SUblc(W2&DpEI^?+qP}nwryKyY}>YNh9J3_S5r3@kH)~`dOq;aOKoURggn;`sW0L;PgK&IEX#o`Pp_Zh%10E z(X%#!ad96(mSA;KZY0(h(LrZuZ?)JE`acy?6X~EEha-;!@W*J0MQ3d}5qA zgjj5198L)?7dTkbc~I~=#>hX`FKv;Pqpy6TOdC;@@E?f(@U2@Lr%snYsj6VC|IWAa z{g1+x|Lj|hO|5^RIsdE&bSX;9uKyr%EIDDsrStrYsSgV>F)&Xkemb@qu_Qbr#_`FX zqZ=HeKIGXkiN27ei}nd8_r8X6BXk;(z1T~<+m=Pyua<9LHRH{oLm2v<^{BH zSe?}>54j+7LM7E91RK1}Peq1B>Jngy;~bf%n;K?AFrVFs9hE5!5vL^3g@-B_X+=Yj zhj!8mCZT2}2!d#u2!fD?GmhPu!`IQsi;r?gG^lwSx0-X86@AOFe7<{Q^tX74398NY z&WLlw4W*$G1u?a|lf`$F8F=UT$6yQ@h7<@>c``^C7n@l~{!!|3NEo614)1Uhzv$30 zO^UBxJ=rzLZ^&Bqd@Te!j8)_Po8kPqtEB}7i?iikYA_}!9m+?*vR3BvGkAJzLJB!jiZ(RKk7*TvNf@Fu>RMkQq^_abtSZK z?Bl)R`}p{ndH_sdh(dGD=YBoQ4jb);dH#;%qQsbvgx2tm!5FO2IZ(bm-`(I)b1^2& z7Vz7EAUFg(xBXbYJ%7?c*NZ`E$-X-fj;A-E}r>5clLV`o8X1}PT;yP{GI4Draed6l+c%wlB=X)X08tE`R!O!uLE zV*5Xh*{n((7Uoc{94Jhi*`lnInGR*Q9NFm>k?Ty2Bv*Bdi%@Ow*~`$I+4`+KeR&tQzw9SC(y*a$7ZwOAMR}JLRnk14zU2 zlB_*wDbcpBGvE0bzS?5(wrHW4=5I{bn@cLvicj9fHt-3rd83N+ZK_*GA=iJ%CknHy z7t6V=$DQ`i3vAo6{u0asbo(ovGz*+_n<4(H2Gk=r{UYd5gu4~^u z8Mr2Aw_Ex-$j{X`6`Q( z?h6YI9W9(g+)4HTD@I&lI^~W$7@#!A%pr_f*_;eNId2A>etUG=J!*8>eROo&eQbCm zLlAXzb|Yc9U64D5w;Q{TH8(Faz#9=wk>4CE^aKV8`j>WZMj=;SdKP0xpL0T_;sLs7 zJW_>T&Te0=ZNPtqgOli*4(~w@O60>2nAf|G88T&GE@rziTNj#m+qygu#^B5{WBmr}bOB&exO5Pqkbby?H~k{(XUgss*Km(Axo;$yB_p;C zBo1xH_d1(>Tws)#$MXu#yE_2v{($PY2C|*A=>3CD0t2?qG8W~@urH<;*G+0p^-e@ga)cWBAW)d(|`dbdibrM8EY5z6(+`pP$J~cPss9Qi~fNKmF6RiW|vebILBV< z1sJfu1`Wk$pz@|;zZYOmh@Ss@A55WM^oD9m04+Btd)QINB8BTY`G#wn&4zlHik*V3 zK|CE8E9KqY1G}6&)?%>$qo~FPt+>OK9P0SY54|dsGZU+P*IyGyZG&&y>B1=x-G$n| z)%0mUrm^=@-5v)u(>}TLu+|VLLiL8I(D%oVf`VygvFc3!*i?j{!Lk3fT~+`8VpkPx zf6#UR52LDf?)Z-j?%NO1 zxdPuJ?DS5;96B%CG}}JgJ}H(JUz+{L#mn(apKQ$W#gV*@Ongz`r`_{LhNsW*#(nGY z#@FpkP0#O>flvm5R4{!+on3te0f7))MTTPffyD|0nNcu1ZlebEv`&UDw7g%-_ zhmyG{;HIU;?yj;=PJ1E) zNU?~sY(cPue{?_qX`OH%Iu!(()r*XY@-&5-fK;Ch&h)M}@Nr$`4nQ)omXaO#HMtu^ z)+5EF0a-#FbXV_(F?ouSazzmM~OLKxC7zj%du zzi4J)$E)2kF9}vn0{BMh803SE%pEMIvYTC>{GG}XW#Wf6$144_odNHb1ZI2^ zPr^P_U7@uA8OCvnmt{ilND>M`44gwrcH&#z#Ji1xyfHUCy{X};|N1LE?X_Huw zC6R|-=dEQuvt3TAz-C=Bv-6Tn!_$kHalHrTFyZnyDd7sZDQ`XxtgiCwqI2<4c2H;V zh-mVKxgswcyN8SgkvM;a8r%j5)&UUADFvKN7=*2?Zm)iFe$3_Iqs%!ypnNpwXW#6c zlM~nh&NHtaIucC`Lf&#A*}EqVPDc#NJmkj~lAZAJj-k-=RYVj3em`j)&URpFyQDa! z;bRGiP@WmeWN6<+D$-LQsx_rIUG~(&U2xeM~DCj2Su7;L);2c zNE>AXNhTbT3D)q%h#U|siwZCqrCJ%*QzM#JSF@<93KlIjXZ)=VaA6n|nQ!b0iz#P+ zdj;DQ1&dG}{lqQM{s77tlAWXW3DLiGj0)G))A$)N`a*m(SaTEjQf1igIJgo}QY77gm04|-S*)j>#hQR~TpoY2EO_!%gFQ<%%4 zDjv*6t}rv9Ee5tVoo!?Pc@Ji#S9@-cEQWo1|HM8(H+N%sOyI8PAAY3^RE2Nu2j8cO z_V4}5f6PJu&#Gzv=~Aa+Z0Ka`!1%AQ$|ZG3uk|Hoo)r)Eh>x&+qI&TJHd;vstRZmm z`~JSaF!DGu7^EPAzK%%hbx7+91Y_=Uc;1zlCxKUe5a57o0)7H&5KQ6XezP{UP3I@s zvo4w)(L8?x1=g#A>-l>eua_RT>odVFw%hL_XTEuQ?z4Vae#bhuk1f;O(n8V(MWGfa zH5*FOzEgX)Y9CdRU(jzw#H(A)JLeXdK$m5PmrbjQyMTiVr^ zJHUpvC&c5Vt9Dk`X684vn-ZKi^iR~5Z`Kr_t32J=b1m<{AzJm$u{~e458B8UuEwaX z5V!+`fF5Eq6c!X06c`j46dIHwstr16w@g$W!dKjt;@X>fGDG?4{C@X`$3O5%(*?=5 zidnXr7C&R3rijadS8FV{>!fFqH5E>~<&1oZFk*xA%li717!Wa{jP@r4z3UeBs4{pE zBA|sq5xVNc7!spP4C}V!RH@RXi&9#ukPkMxja5x$(O9gZT}$IF){N3w4%1mOND{5E z|G@Aow%DFST|>DxJqK~J1abCrcFZl$`8Z4JXd06w%LswA8=OiJByAwuAQJg$ExB`MzN)jQinjn2xTU-0n{M}AJiv}(P-x0R>Ldg7uPp-!-%HMaeX(32+et zc^V;nc^U@!`H3QmX)MZCw=L46y9(@fgK@b9h=b{D3GrfxgK&|f3^e>)kCw*F=q%Kx zl6YGm(9K2+A9n2Tzx%gPCv+kK&tV(OBwF6ILiaPJn+g};u^2jddyn&wF0*DM2p4u> zk@y8*M6m4X^{BEC8oNu~Q6t5r@(Gi0tQ2askPeoMrUBWS+OcG=lnXQ${SWhbN}I)O zYjT5nz$hf{*TU;zP--9`9pNyYhEK$tjeKb|ppl@Pt~TRrW|;k48An?=5xvL6T*#o8 zU{SB@#AmtXbFL}R!er+GIG;sYsZI_!XWzbi#f#GNxL2844T}=knE&_>LaUkkM;(h7 zHQXxcQlO*vs!I~V67UvGOyQ-uS>&c9=-0t!=YP1VAgSG zonad!Sap$$nKCS+js=*wgNRbZZ*efiNnhad>2=I+v&e&TAfUUi@&gG^J`gd4ae86< zbC_QA${GF2&b->Lr*)u1!0_u3Sbw@0xM<>9OOCmpB1noJnfGEvX9PP(j5XRjV*!M2 z^>f#YudBJu3Zi=I+S$O4n$28a`dD` zke0*|p)SCzA?I6XNJ{KR63Jo|zrjs>ER^=i)rN6AMCy}e>Xa`}k#ROzj5x-_ztqYf zm5I32u403}njVck9kQ6@3mD3H5hpN^kidVH zeh?Y`n?^g7SV5K=h;W0@78A2xNs<8hEHSoy5ZcR<+~iqmFKcKa4MRfI5ECIYW8C50 z44mT;;5nCX`054-?WQcO+Ycz>VczheHAQAY zwKM;ZwC-LJs4!SS_eoKx&?s@Thj4=0QIVrlHmJ|Aq^a9DI|`~A7vS$}s^|FzfY|tC z@V_-Nw2oT4Mf(r-v{`!gQ9Kg><+g|ORa$Rou2v%sv+rsbdUIn2q>}MF(L~!6$3pHT89kv?UVL(#fdUCla<^fXeu=B2W9YgZq^`39l<}#U7s%+vMqg@ zF7;)NU1Y^O__`C(_!B4k6(B;!B40l11;5w+-#98F9a zu-93a;XfjxKEcvtKBjE3cgX3n-ghZZ4HPwa8_c*QC}eEQn^45H&|>mVxyoZJD?%sD zqO3_AlHt!I>~?7TZkP0MKC~$Mx}IIrd|u9PTRuE%yjB(2w8sEx$2x#_<&?99=V}eP z3;7Vk$iV-jJu-DKf#NfM~}rb`6)FBn0-VU>)1l?FxdPve0a!LI&30+D0K zEB{@OTE*W8;P*xZO;cxpFIl-pB3ZeCuRP*ERt~GL1Ktf?*}iLj%&p{;jkQUZMSL8r z7g!a(%JerQRW`7|94T)#-kBE?Kl#h%$d`j*nL=BMG443Soz-mNw z4t+NJh3qT}U5~?G-=WF{==}DU{VfeNqNv^sGQYtIDNVycU<+(EgYU>Bj$Oj>H1MDV zR-FrpP6z<6k_#!f@F6brsMjwu^vO~JRPH$Kerb=%CrttgHPI>_BIV)}IQa}k>H{eG zG~u8?c8=?@^1j_E**E&zK243tvpA?Lh7u! z)Cm)b69ytj6Sx*f01NXoNMl=(I_|8=XJT;9?;nJ@T zEV|+4d%bre>cSE;KyK)D8Zpgn*yNob3?ruI{_t{Z9kb29Y}Zt1Hp5tAsWyXHXzgr< z!4;lDdqeE8`O)0R;~d9_kBQK0FmlJhusQ`2tX~syXxUx`fl1fzNqgk%?m|xqJsc{y z#>1wkNwqgwj=Brhr>R_=Bs;Nn#{oa8foq3o(M>+j)iBq6V>Tz)>A>`&gL? z`&gl+f34x=kV1a#OYtwcd60-R9BR|`V^E0Mm#~*$?f_&iZh;F{|1O-LMQI1JsfBw|@~D|m>;s}yq!xRtAMj&oyF=-!#bvYfK*lUY8!FnKjHYU&wbF|BYJtS9V! z2Bpn{AXJ`O0@e%2pH6^Ls=}mkrE||j3fcwg-aX>*oF3l8J8q7m8YfDU!CN-WA9(jA zzh;Vgc?Pw-ZI4P_L096bv?yk6kdg#yB)AiY)hk&%Q4d3NaPGfKO$V(so}3wOL)~o*a_WA zt_s^VjXP!MYT^#Yr37nMK}QiKE`1lFjPn9_Yje^`Mxf%+3Xx}{e;39R>I22wQDyUc zg}KeQMaj&SBToCiOnQIt`t|T-r+(^D75U@pgl$j4xTVDJgOtAF^rP6tH<{N9Ej2fa z86P8;x(o{8prbGy4I+a@vL}UxFvSkBS(LiiYIwj#)r*uT)x0qJRPze5Z8lVdI*mgalv>}h z7(C;70T82Fa3oSAq#}hzJ0`kV|GlWF498M6h}y^KZyt z_fF!$%`oQYI7u)6@u4mz>5b4-M}UlTeu&6WDXz>As`s#{RHb4MVv*M``NUo3S!t+%$=2@^7F$nZs;8ua-L*Jy)+FCH8g7X}?)@pk7j{FLS0Z z_b8kdQwK2biyV&AKbfcwIHT&Zsv~8cSoc(wKGO)7=TXwmBqNg;35I7PhpDs$PHRS8 z9Z1d)KMh z)2QcM9g)T)3tn>#@38X>2d~!pwLc94%UZv42+tgaMYSk&S@wW$JpYsrwwP7Fuu#Kq z)5C|=n6Xz=La&faH9>@)S4MR>`ZH0n&LUV%kseH#48|uJX8KO6)dTBprOUu{_raT- zC3?>w&}4>$D>9zr#}_(Q0-!joWDfi^xjYQm<^4=lVUVP}BS!*Mzj^y6+ld%wcHeik=7FuhQ?j zvfR3D-*>rkJf&=3N>|mJimiL9F}TznSo)k#CXHZi_~er1Px1x`M6rkcQ1OV-tZQrG{N$0FJIk9zXNWW7=hy^(M>z70^r z%;{*`aC`Xi0XL6?RRPQG@f3-Q`Nq_@U@@GGpw1Q5tq#Dkls-@7{p$;jzhgC>j3Li- zfaH!ASyTfNuIVYUT{d|X;`oTVt2`FJ?$DC_F4e+ok5g(g!7B5iXZuuqr-by~8^vc? zo5*Tma{YZ{WydZRH7yWA^DH?dW^Gh<(Xp6P^A5(NDTWRCj@5kSo4hQ z77!Ib%YA{vd4o9r>x9uSPB(f1W3VFQ(F@8O33XvkGiqToZsS{%cQ$Qk(o(wDl!wj_ zpL^AR>#k<|6TTO3Yxz&e zYIs&EqM*2-dMJeC@m?bu#n`8B&&^EF=Ob)|f$)dRWMm)80J{BCWem0*6O~m!WO+=L z8qzFb#!erqU~XQqzPKnYPszSXCZf{u(49PVEI1D;P~SelXAl|>Et^jsBI%7Vy_fhv zLckTdzmLX13bU7RU-WBupy3E<32r(M7rVWcm4%mpf4r*QfZNg|-~zOXREY_>9QOL* zL$A?N#lfU-1C#Bc#8NPD_BeHF-^Z2KP&tj7zblXFl0=MlvlJ`pq-V17v~;|aS|7@c z2A%ba3*|^tKfB%>cqn| zN}p|cGo7jX!cnH6)QVA)5eH+jX{2+IQlR^~YHba2bYxT8XqIfF(QTA6METa$N0WNj zA2!-389LrhzP_(!HS#b`8+CqDIcKUFCrPI`9{Xw|YLH2I-2qi(E+1@ZgJ3x$0IEx%<+KKNXo9ES`cPqo)01lD7huugIH_r0;8$B2%#J^qI|?4i?6i{nWT+ zYYZXd;>qXpdOAU!8W@W=%pq!n%u1VNt<{IooW<9gT;4n0rS+qfgD8tukZrZJ7ixxV zSP^ZZ<&#TRC7me7TkQ}&zS=cC&6p`VmCK#+&a)`UdO~v@nnua~+ArWK#s0Rt>VVrQ1CDN6y{^4_TTa9UBV03FwDTGRkRUpPuE3Yi zP+qvG%pbkIu(yPOyu*@S5RDfBDrSP)ut(6HREt}|s!$(5yv#R@Ts3;7j|fPeJ~lhb zohCbEH0W;FwrDTFKIS{pnG83SnFf)Tlp7#E*k>Oqk?AZH3d3Xc>J*{J)3byZBHu|l zP0NCgp{+D*G0OB=^fd~IDy$flA;!RjmrLZ=L5&xdR-$?N1Ewtwy6%Q@#wI@V52VIF?71(6cR2QWR#yCo1C@Do*YS8o#g@CpzVkz zVc^Gex4Gs_p?+)ohRNFJ!Wx%4u)elsU$iyns%f|7qx`t+FW+FN%_j1~_;M!|2L-#Q zz@#_c_Ewjd7pJ#^lQ!kyPmo94XzRQmcnR`^O7|q#GC?un{h&({; z{6K^&1nIJWAyg7g@Dbu>smFVNMb!?se8}B`(D2>j4TAGMNY=NbV~|fUi;&HhNi(G8 zG3Osbn7HFzgojJH@QJX)q^JnUU#%yM&i@Y1?6?N{o&WvV3c)e1jZkp16-!@zuF zN|b24%ju6@y5G!UgR9VnJ;Q>Juue;mq_EwGU1K0gfp2QPgP>%ru6ON4J?Icq8+{Vu zdbiXT8aw@dOV#8p^JYx6SOx#c(6GysW@jw5&(?;{=8yhHA@fH6 zc7o*H6e|8~E&y%Yr#Y~kJ|(gu%W0im`SCijg|45M8#OCRQY0sH_iTnv}y!S`zefe$9|<8#;lmLp1m5 zy?eo!PNSX{?PyJ(AUkR=TMn}m^-sxK@^5DD<3_=D3+IxqA=g&aTcaIpV0CPE1%Ed*i_1t~ z$?oFsdV7=>>r9cQVRUPYQUOtGb#re=5RWi*|So``v~PaWQJiz|qt zm9Y|<4NkNG18vyp&o_IFk8=&_lE?|B3zX6%x>_Ji#voI3C&*MmW!FGEWmckX%U7LT zVc@(`#~=eFeT!I5U`JI_ves!JVb?q+|65{MT|7?N8n6p!s3#QUCzyr{Zi@>*l+#IK zhb#wh)Q1NA!f^E%CTDul^iH8wn!S1a$3QKP+RoVdBcAb$tJJ?ELOdb#!R$lfGok?F z9EskO;Fp2hFyN3%z}7W8T$dci!C}ez|3t6Imb3EH{B+t9{$HxJ|4&t}f0Il6^KdSC zKzb!ECB3w5cRjzGkR$|&l1%y$bq0+AiIH%T;=zge@rmJq`j29aqq1go6vANu|*6!W0+w1xUCFI%)Tx0g`I6r(74)cK z7X)+Hgit-E&kN_KR_k+dhVSzflG=|gI=^2Q8$c@soX4zd5pY!bZQzI2xCr5+8y{7dj_z3iD3v3BWh?qeO#$ukGD%>5$uc#O zAqNVIGBy4o35xPkHDO`qy6QXwW@O9KQsx~K19j22GSW$ndiB7*WqLd1WL2dV)n!)t z)>4Wz3-Sn?@L`R8;W{Hx(fWppQo^-Oj)GF+?29nhl4jH)PlHSAsarEsc~?sc99x=l zX&2Fs_4urNG^q24lC}Ix=vyUJf@PItMmzeZ4~MtUBBp`ixjjT|%iU6eIVJKIYP9l4ZoH#cHZ z;g!eG#-s9$yqe=Ws~j<(PHn8u1tMgyOjVs3mf)>zI~1T%hN?~FP`FaSSqBX_#}=dR z+z&0Z<|xI6*~_MP2l+%eHO+RiBPb1SshNa~&d6hJ#fJ>%uG|;{`K)D4T{T5J^QtPK zkJXk}&B<}V9V=*JZ6Z;c2ov(1aE&@F!x*t51ap^KhB%WffiLYdD!QCH2?LMQ(HRqp)k{xdZ~LuPrh2??E7 zcvyD#m-eW=WPM~n9AsK@s-$pLHGl>!6k%L;gl*)4g9aKEngPlm>f0;kR5Z8R+zk&1 zP3Lgs{amQZ38fQm(Qxm8Ytv98|89GmFhF`bYyG=Ipyj0ieTD)^=d1|U75#a^!-d2t zxZ`I2%dkiR7otM{y9&5R`=w3%d|S!}VL&A`Q7i%*n@ z6ehi@f)_2(%gVaEYPk^kx!M4LK-5r{)bEL+6;qkjWiJZOj{UM}GtTm@J~c~*7G45r zb_7<0shXquTC>!)z*c5pCQu$PShTiWH-IGPP9vN1+m-coFtk1O@$x@)` zu8Hh2Efinsm0d*)$tbk2$k$45}l>eoW+xX@n+3AAoa(D;|oLuT0r z*?WrW24&A_tZw1hhBv1aX?SqVI%i#W_t8AoM_VCg=g)h-rcb39R_5Lcby+dOgbbCM zg_Lwr$qX42wZCB{DrQ~KG>}?zR5BvaTIy#&EuRT9>Rbi;hT?jt2hd#x@k3+z`99Ul zBtO(s-&FQBd(h+P;ZSf(LMIljwQJg|S=aFpbgYulUY$3)tJ88xdUyx*b>gFK>Z!V| zx)=>r7w%CQym55$XDaHjL5X%+fnMCySLlzlf!7DJp&w(=b|haoV7E8<0K$5# zK9c?F2Cs43Rdx&JzhoCvN04R~<)rjj+b7=uYKh6&3E$1(X1cKU_l01#b#ng76e2Z91k6vPKs$iiJzG`BA zG=5BCUc#KfpgfOY$Xz%kE|+_t*+4_m}6#4tGmgqZo{5GxKM(WvU=) z(3sI{WPDOKer!sL#+;y3RaRQT2OwqOno5XQhs<(`vUUf zt0=A5R#VjM=`>N7c2-ZC@^)9>96pOMCacRcFmxC87QQSWKdV1`^O3LOS}pJz3GJ3+ zhKv5_s#B`3m|*|glqG#em$D!CY`mtVZ9a694#98jcc9iVK)I_ve*H*RA zuIEtEQQ>fSl`yj-dx$JaSwUHmV$HOP)_{OxkQFZb?nx4(z;$X37AP#ZIi4X}#c+P2 zY=Yf2e&S){ytLLHow^OpR1JR0e||!iKTasD)J9}$rD3~JQ#e#peP@Kk3Oq<_W)aF- zZChWavSX;Y??JIrz}DOkq;4^gM2k1993s4niDX11Wp$}y26(lM*uj)Ks-cstpHE)2@R}Y!9 z1%m1TR0@p^c;vVZ*ic_0C60tdWZ-j}qK4r^2+tXVSrBF#v7Ml%<2M9hbx%ZqfLX^N zpcwND78&a|{M`g0o}kY@*vU-kt&^d8KG6mcz}N4Mn^-z{8-Kiw2*);PlYX02P}hEf zR!E8+$6ACh@a0~dlRlh@K0Xazs{wmYv#8k$6Dhc`2F zw@G9C4Sx_=ongowR};a z)yhaKbDRKPUr@_Lj~<2iWxgV1=xQwq*^sdTm`$V&PZz=Pq(`R zk7Py%d@6KxxLWLVRAC%Xm?Qc@x+H{GaQ=ki`#!7;Je5 z^8;-2ruuAHeQnsG?5X$@J4BU!$9mLUuo*kRV!bKYm-}v6Z7rORwk=08v(UAOZ611z z8>NlBpeB8$Nlz2GaMoM??NaAqO!X6sU`HOXZ#cc85`?rTu>Gk5Is!if5c1BV1i~Ky z=}w8F1dv~e%S*#iyX~+5oTUT8z&St)Wb?>l`%)F);W~pt0RYl)c~&d6<&T#J#aEjUGFl#z`54@2DHrn*$R$@ zdq)lWDu-(Ng$=WGf_6rzWx`4+=p7Up4b_AIvlrii-iGU6)Os^2_Z{QE!=mLCVwf#I z&ef7}G-pAl*E%N!OMWlK4e=_fuT=&$DuAdJ{McG<{#(E4+^kk4-U|MxGuSNl8^qmefL9Ej zE-yciX50+?!8z%uDdZh{fLAfzs;XQyHQ5S$;=1gA*c5`DNksec%N#%eYb7JLQIR^R z%N$_r2o=QzgG~JH`-mF?*fA~8r!kRQjTy;O_MD2< zk==$xzHJqU5`w8fD&kW1uRZ+Zu1qCat-!vJmUhDAtlKX6UH@3)gM*#~KR}8uybD>c zak6nWeIs8@+qm3P*Aa)HGeO~Xs4{+3;i`{%Tof@~mVWF77FcjLa5kA35#g}X-MKS~RYhl3kpn2CY)nlHfzwhT?K2`;pLhU7BnaC7_nTQXNJw8yyFry)E zzorK7Nu#Zb$E($2E~wmo;V9KN?BG)p8ug*VBS3hd;eSH8-@-e7_l4jm3+Pg=eiKPq z3NT91rbei@En0JQS&I+Yxr8(BWJOQZKpO{1+LDZ520_h;8BCT>YO@+lM3dqOb8_uDgy4-3T3xdr`DMvbPv-XAO z_LRU@xE%BNqsF25vDp3sE=VTzhH`x|f`IP`9CP5USf8Gto-i);s5>w&5Kr~A`}yAx zTqE5O+a|RAuB(zaD4ytB#=4=r^|o|++eQPclvV)mC>ecUz=2Oa^@kUnR@Cn_9f@7z z@fX{4i9N$tdc1ZlR*Z8+&1Jx?Dp$@d>fTOQO5=sF41=;k;S6fve`yClu=}zlQvHxpVJ5 zy*VUH?)w&8PyjiGX_89GDJaGaoanF=0BIWQPgTT>mF zyVHqJgsQK(mClmzHL<`in8Jz;=`Cb;C^bWuF* zjiJvFjZhzd#v3+tl@chNlBDaxP_@46NV!001=SVLZv4tr_hcK|uVuS!tjf|~j>&sw zqY~$`<|g}_W==EYRfXozL`O9%p_j%2c-ExuJ=rm4AB*UA$1qcfnwKH>Wmh5Pg)|QO zCR$_=XNka`;HpVJDsx>SbIwS51C+<2nTBf^)VtgEEK7VJxgw`FR4^OG)Am3{RWa;w zC9ftkLbh>wz(-t8xgMaJ-`z>7ubjXJvQ)B&liEDiwXo>Z1oDHOfm;gp)NHc9Qhs-` zAhgx|BpZzTPUm;<@;-Q(CK9zCTQGpr+OQlOyCf}MMlzH&o!Vy2%Is^X8#+*PkfwJo zUOs|BNLUb+nnpJj)R+*T7!$XoZfVKM^iYhcYAW*0S$6OMt(eM|sbS_yfN^RocJl z*|qF$M7!rZ4Kv61>1ndK;;zd4qBQmXPHK2iRGrRUeermw&LR#}oo>6w-7#nbl*-vR ztH}Qz|M28u$8K@}t&-+khK@2lM)*Bn&Ez)q7X=e;W}5g{p|-i*P9rr7UUrtGlZFH|v2X zx$fUFQGu`90di!v(ob;77`JE>V7+GD8oC9|YThycxQ2a`>Vn#tw+YC*j1#152HR)b zNXww@nQCnL{#STyzfy~Hu)J}=s_KdAd^V=mdX2vMNA%B~*EN{Eq+>E;scTqcscXtR z*Ij08u|4O|$l3_mcx{Pl!8=PczqOcb!MoVrlw+xC-ZO7A>r=Iv-&Mh#-&Mk0_DS0O zq2np}&S=0Ra6-!^_?~)fmUA5=-_u=&q=@qaqMOD9^eT*63Q;1vLHk5na4wbuSt@T%1?Uh?t?T(imE!P{~ z4w#!*tKyQ^x1yU?9ys)B*x(gzDWi5kg7q#bt(|Ik!_8=dnJ(djj+V$0xwK&Q?U2D`CuI4BLGze9)GOzRleo9y>eS zH8$7iXh&8Kmw|#TZ#JRP_8g(n&KxORM074#S~b@wj_f~#+%mVOnps7wT%EZ?M9C`K zC<$um(ew#*O4_0t+6$pKQ#+zdNq(Y}epvK~cSBTQ;j46#lm5a6G?hs3W^hGt$oIM0 zRDOwSVCzE!tul#y(gxrc@P{|0rGA74=$%B#1J6Rloy02rw!+9>1S)k_@&zz2s`D8R zEdBL)p=~>f9y3{hzQME=8HZjk++M<)RG~YnH_AUSE=V6J+H%&a$eryS;vfb+VlQkR z5i&%Ko0o6qpn80W8N6n|5J65Zh;2SIqQY6x6X|H!A}>UpI+_%b0WjzFPo%En@@Z<1Cs-rxFrXyF$1Z4u@Z{v6?IJCbWUywnARm3jvj}2s zg4G}d@X!9dMQe#&)*6cdm?D`(56PZ)5@$%lbiRnkIDD2~J9}`XuxM|c6rMw^d@kcI z{y%oVx{GY$7zF4TIIE4+7q+CmgW`VjmlWhWl`>KA_U-LMg`DW zRz&^FexLJ%^W=xMmN;1Q0GlJD7e^GP$F3{L^GjYT>Cb3$Xi(5G>#;RTNFsz6Nm~^n z6DRorgsPE`o0UoT0HpD;hUH@e5_80!1X0xilSCpdM$ojXI1L~gXy(ZN&UR9IBJvX5 zL_>Vg4q{SDD&vZgc?nakZqa$usTTZh$N4-5Awyw(lK=Z#R38)z z*K_c;?j0MqWBs=7oC=pRhGUBbRaxSC9EX$Bma!>`ehDfY_$#Wxjt#0{ zp6CO~w7|_0Av?OD>|NKMlw(c%#4JZp^qq@i4JVc4%D>5gR*Uc|_;Ziv_>**cZf?^s zrh)s2ZJqFE*THPmNsM<>;ls~I{U;jjW5Xv-~4NnXyHBnG-6Wf6$Mhuxo)8o z6k+?cV8nYm=$YNa>oJO?%?+<2$2UUUXD79=k0HD#R-9%P7Cktx!0yz%@=hGL;stx! zXN2PCvE>-}tTRpmY*zM|nWyS9HBZ@UV3N9SQy1}gD{ZiiV<4@XW4%AZ1myOE_aOhZ zturbqA)H4>K9s7cP!0+-GKvU?7IZV~FHc5@2cLi*7d8eXHV6fK5{8aG3%?KfvnC;f zpS(@f%2Q%vqD4a80~r1>^wFcL#~S%RoPASpW>L3o$F^HbgYhT zJNaVU>f3*vbF1!sIS;35R;|5i@7hmuuC?ZxV~$}Nzsr;NHi9(yTJ*d-L?nvD@?=SA zGBhEC8nOY7T8Rr-CY}nDW`|uSu7$Mbl+&o$qO7)yPDR2Cj!NA$OSNw-3QI6K;?y?R zt*J1sGD$UV!gXlG4MkYQsD@8oc8bQ}K&R8dp{xdC(%DeM92(cn1Q}zCQyDEiD#{Eo zmncY}3Og1!e`Hd9IwTWIfs=?cr$Ph7e2|OQaKKzcR%Vq)D4nBY-l1 zX0b!Kz*cEw^56tgVw45cM5eDn`QS4#r5b3de=lPWz7xfmlf+(AB9vtS4w2YYpMwAW z=Vi4-Y2vS9x&QiDMov9*QEhiWRF{-ZnZlUkW6UncPivZu6{{RagDom$A248ZnfS*2 z*nn$p27>qxDvPEK7=)o4PaLM^t}zpv_+tBFL;GI;UZ?i03uH_y{Z^qr`8YA{==<|y zQv6$7i}9Ihq-o1AjuQWX=m4o1KU}`Q>t-;N^_e&peN`+^2hH0?{;--Ov3^CYR|oB2 zDGR%NWr$k`?VBaB?>k=qI2@q-AS$x!HE$QVaZ11ax1Sltg6De?a(Y@jHW>evQPxG&xHp=W72w#xO{N937T^fHDVGcA?3GmdJY)U zc!!gS#2$w>?9HUN+{7EbqQTJd7=&F5y{YbziATBK0OF*}vw(L0H*va6hf5}>B;zWs zd1eEL2A+Ml{!PMxu?5h~g5rhjH zQxc1yEa!ta>&)b#xnHIou-c5SKH0uo+F*t$@yah*PNl-cQv}(=x_&U8Ia~2pc=HJ} zq-P&FccB2hkgyeNciA?)kT^B;jjb-w5;`svBcxD&JiSrFsXws@P z31~y1o%b-Y`wJn$*0SBc>H}4{zG1+x{DoTBu_4GEM^%eRy^Of;@v;g%y{a&P1=I&% zS{a52+!BgJH){ehy@(2jH{$o$Zu6m29}>M*z7a%BsR0{7m?Rfq@_;EMc8Z&k+zE&G zq%q>BF}S%cbHEn(XIa`2w?0^?B6$bC z7yT<#!3U)m`ny8G2hN+uFCqbn_Eqi`O{Ca}2Wc=L1-8$|;0F<~VnhTiA39LD!`q34 z2#$y>1u6TDnm_1zgdb;g`;aQ8msBy3^V}lFT7h=;QY|j>h1!nrwiM9aVo1AtQgSb; ze(lUM0~n^Qh|~BnNIh*~X>P7e%Lm_Rxuk0!PB!$5<$X@Z^!>kh?3d>@0KNo2eq4+H zPbdY+{~b!<|K}h1?|LskoR`{BBbz0W<;$Vj197xAia5x&omB8I5X_-&4qVi!Fr%OF z*=ET#b{>n{2*@_WB10Ow6*{T3f>G)^shED`{pd>7D;qY3I`;N0H@?2MwQX(no4&ey z5Bb020l&r_Qquh1W}z1l+9%#DbrfeKF@lZHp@Ib@HB z=e-SZ)p=ip*Aw6XbvUtj^de9^aLRS>*rzo6!Vqy3)1AXWJG{bDqcUL+_cGyghllAI zXO8#r87(HcC4+FdHAh_EybU0E8;Qa6{|VXiOQ@2YHe$#+^~RjI`UeHWIirYTIVo55 z+38LB(F09rklZKR<$_FdCZ*CW_d?r)qod8dg4b!18*}n8_*;_-X>qE}Yn1z9vFIAm znShZktOgTgjH(TYnzRj|7Z`SZ>a6_Ldq-T1#C3aVm=CR< z!k-7rbsXv1%~>7vx?o;&yapqw@Uhy4i)oHpV^j?kWdsXn}?@L&AtHoOYd>{&`M2}V zvX!#1&hwG`_X!*D8j-P*`NRq?Z2M=(cR%RkqwfNtPSF0-8d|F|N%M-3tl#IK!iN5a zirGwChxTwvvJUzc+jv&bVPATyc(L;iLM)ovSg@X{UcNn7+r3H8N{UGH)Ms}RU07*u zZz2M{R_%X=R#ypcJzu-~ldL?~PA;gmF<>7(KX?b&R}P{XMH?hUL5OPWa*>%l6@Hl4 zbKyTdRDJc=CBe>CQ4Vy;>58ZP1W;6x3TFuVbbR$RQaH+^oZPFKsS(&}X|>ovM2{W( zlejPTH#RxkP!nf|$blxwzpm-p=o;4*3B#hUgogm_^(ZTG*Vz#9??-fO&ll&pW(Eix zc*p^Ilqc^WTl7WVVO}7+`zy8Z;e2jhZ9lN~!ZFI$__t2B8{d$ZIySUCTh^aQ$uwveQ{Vuh~K~kVXI?3XO7_!|q)sr$r z;q=p*K1|+;_(J)z&-fG?8ar<40@q{vx3qI%YAsuz-oOYjoVnBpxgwW}gDW-JC_H6A z;?t|hj7`~|Y|_RQYkSq}ZAaR@n*2E5JK0A!{sH`GV3he5FdkBz8l6B9@4ez9G#4Ei zf}6+Vos4yQBau-Mx5Vm(@epT8axS17S@z&qFUtqSthKmh1V^#RxlGT^L`!jOGyNd2 zj_hFV*bWnmvPI!ELO+E)Rwq~G<9<&UVjIF`FeN*E6#Ki`r=T+7{@j*XTRnsO2qv|` zUSV04DXGt`N>s|oa**y14cr61*Apoiy=m%o)-DoVTFEV}Z@qAQfflNxO+O@N3-dDU zNxWZ`07%v}im4!02yfD`x4w)cG!G`;dbbvt?Ws{Mv45_;8arW?+n^Yi?zHj5a`)Jg z_TGIV$&D(Q=P^^zafetuKa2Zg*{XiJ9qM2pKDn&WBKG8dJCW<)k>8-t-@^m?BkA9V zHssA&^Fyhc_s|?YP@dNVUEyzk%Nk~}{<}&3!kaLX0reH6Sob$W;26~%;iGXJ4V1J_ zqK^^IPtR#9OrFHB-n48J>THN=jKU)p^(Dfot{f%0EY7vMM7SNqKfjD|x+iunqHPNo zO@t;&s^dEf3j(U1!v7_>vXt>KwYW?xmzbohAbek~N@WAhI zu$Z8{(rZ{baOU&v0fkXPn#h!#mhqs3;h}?DNO;eW5;+SN6zwNTox%_TP>j4dR-vKu zmv*c=CZ#4Og(ln`-d1V^>*hnmbE=jQZthEo}fg zXLW-#UER^X4~8HTRQuZKayE*LDw`orz4D#un3OZ#K$6;x4oy}$P$A>poi+d;k)>IG zm;fC318dc_F*zD<4|(7|g%ht-POLm%yd^v?BzY(iT7@!^z0Qb}1`RUzWT_67G=U$^aGF#<^w-c9;>$N>U z=fN>9JO+*L^&v|T&^cZ-0L7jjeO#Wb6j)~-Q=6yEdY*H*Oe z|LTqNQt2fWAUq6pE1cIAD00s&j9a#kbtg+J2xzN*Wfn}zLQ%pk$esgF;R{3AVb$LV z01o5t?N8DMKp^G8>xy7)*uHE?sZt-F-9dsni&uC-JEq?$r#+j-JUQd!D>);Fo8fER zF$-4iL(6vZ+m~1EYbMsX=x;eW8X@s`zmD37_ z&sM*>`w0&_{tM;aihZs-UD{p%Q}wI;XB_NJ-;MewV}RnwP4z2m?*#APps0Fa2(2(5`85@` zegKKuTb531{*7rrS|ee|#2eThIrJdLoMzoQ`X|*xTVde08bAa@2PL?&tb0aPKA`xz zT>)0r!*W~8k=!XO_x(f2+uZ)kM$z^P{7*{8#t@&Nc7ut5dbxAagPV2D*@D-ic_Sq# z>ktN;eWtvh(C$gj*hd~3csM(2Kb%UI6x{i}c=pf<*JO_EqSvYoo8yVGil9fpMBT>RVT$Msv4>^BttJL>igvOe(X!g=%y}n(l zJ3`+1%JKO~*~Wy;th6EDA0*aZ2J%RKk|9kF+9b`;_n~n4d&+Opn!@B#om6^t`(JT| z;=VQF?U&@i1o?R1ziie!@7k_n&a0xUb?NZVFRJOXtEzRfadq&{t95NB=&G}&@&mpg zC`~#oc|$o_ZOS8?RgTCsOFVXPl=k4$(Jc-VH_;6ogkUPLNb57Wk!- zOP0cx+;%*EYrRwYM=7}E z)A%Ts+1`4%j8ms5(^cy&q?BMCi9r`WU zB9H-)mE|0@)}FNGegUjO%-}kbPf$VW*u}pF4{PgA&hYrkmCZ6C^L_>WkUVi`2M7_O z^L4cpHnw*5R(4mm7WTTE*IJr;s~%C9`QnS95{0bD4KskCaoF!Kp%s!YM`H-MFDIqf zY2BMtysW4)E^+W;(Yh%d*A;GQr|zU3v4?P19JXkBX$-6u{F%;@+t3;2>tZPKXO_oU7CNUmOiQtIAGmQ< zcfI)a^jbtBBu|->R7zLaaYKD6W-s4b818dx=%;+INnajYJ`1)F=rL(i6AuDQ}J1_tAcz zGCLQkN3dZPg23_I7l7&z&Tebtn#+ImL?y~??uu8;3)cN~Yg1**LEu0J{}Gji97HYf zQ9&65@lWv`&92M^uBGM&*w>E?{S$;BU;_3c)Ax{gkqb>mAA&AS7UQ|aE45zn7X!SX zoRPWSstVD84wS?@NP>Ro3<)zUt0-!dMAjk7m<3Fd3w|d2<{q!eFmiF~-T`>E&m`xX z!W?4%#xG*8uXb>GQy9nyqgfc}YXF{tloOR7slsh?@Lnu$KlS+F5Sf1H18i8o9y8)H zL4vRyt9rVTLaeGfkn%O9pm3lZCJB7#5h3{7t>=hx4TGp9dxKp;kc_)Sdv!B5L0pJ^ z)ZIY1m&S0W?b!0r5-}tvzcN}-J3b$RZ;R5)20Xd|{lJ=ci}Z19t~MAgOps1vV$L3X z9JDi+xcb*MF}3K=Dc`a^Tcl~TUYWD;HTpXK2KXS>wB#PZl|z3drG50w_z5_dC+wt1 zyR6nVC9XZXmcZlTx`t-q&ukWrQzWz^$t3t?T*CtOwpu`NZKt?3IR|jZAOFl(;inFP z?7KGU*A|SFtwx%h&hJ{Yg%?7}cR~HM)r2s%v&`%g(|*xot;$|lo?Ec~K?)Jw4rfA_ zgZJs!3ofp@-L3Wj*MF1cC*N)f^Z@zdD{#MD8xNb0hmIM)mW#Nay)mxiY>v4!$8k;U zZa6zKBU^9urZD1ruKi#;S4Fm5?(LU$8q{lh(8 zZ-5|PSaAbH6-V(RLS20$Drh<&AltN`NTM|u#lN)ZEI=AH=s`_tsX_Pk%TY^5fdQ|e zKwa67Ly+L6h;u}*gaW%Fe~wEk>Tn;%a3<6gSwH$9CKUGAc4JvT===TF$`*b(hAeeK z(q{jki>=NyPZp{VKBATL4sHZt+9{JBmmv+44*c+zvbX4mo$?;V&Z3p;4lD03!aakB zP1&YjgHCa-v)c_$;1EzY-_# z^g;)fPB}Ya2}X=FPB?Lr#(RLw>(g*sO`?K2HY_PRR~lXBMEI^_9=6VvCYsm5U||dJ zxFz&X)re14)@6lD7H#WnFa37mHfcc>qYwP+b-9B#n`6Cp&yX~-jvnL%y~ZpLc?LF-Xa!(1 zrWj3szsTSp50z~|{2m|1Cc%?uMw?cOVO1-FAO(L>{otGm&dq@9nn(0JaPvZa0AkPl zvb=@&g0mbTI(^gRhx?BEt~yYE;k-*ustUVgl0(fV)%I0|*Vn-Rjd1 z{{fnehdNZEV@Xdshc-h_mb7T~<6-?ahIC$rHw>$vTgidZOhV%pQ&{>L_pEHgHlW+w zNJvHv*9$_?%#&Xb`^3rrOq& zeN-wF_L|~T5ls;88lVY1$#(f#`b0_t0^+YDs|dZ2RFwOQJMWve(u!wTM*KpbajT1Kz2d|=glUVHK)JcJgNie8?<+>8>ra50?rh=e|!Cosj{Q|QZ z!WjDnSC~rjwpxX6*0D&J^e!3PXp%umGH1hNW(U$ezC@RMkUmW>Tn!j(p^vU(LpCnB z=q^69^4qV$jE280DKbCmNU!u2I_&_Uj|om$1(2(Kklmock1_i?YcUtbKk9>h8!&o* z&W6vy4X!~t8bNhO3cd<>4CFW9?F@3V7h=Hp?7jA?RhC{EtHxS+gVyz{puK) zF>9K11>|ZM{9r`WFeSaXM%FMb*&35;l}-~IpWIa0q-=#M zCe#85WN`RKKn?icVi^;NdmMn?7yikSRP2g;{3;e9kXwstU}4ShXO6uTV{FB{q4;eC z_hFxiJy|<~z+TkWF8rIuWRG&*l4d0geHUu}u-(=jBbGGzLWA8>pCDRt1<=+?+1#(8>&aytWU0Jb_Lp#{~$bY#(@GRp;XvABlMSs zIN{9K{JvU;^LAs_<$+GRP`1Jb-$Dvyyq*YACviBU=b=Nw?XWkEn4n~>AkmT+MGKE( z<8j#=M9)Y11%|Xh$qmlvhc9ynV>JXUImneXgd9KuN_NsSQiQ!>7j=TihdzWAycyxQ zQAWKa#a)dEQ()~fXrRXUwudu#M@Q+Z}@Vq z({%X3PuFsiln}g<$HM7krUobsl=J_#4Zs^>hZS<2%O-y7iLpoGASZOKxY+NfIA19o z#O%Jrqp^J)ZGb2SH)<O`pZ0=tuxH?t-$LR5(#b-G0##R85J z)iij#8)i+SML(}Kr(MFaNShnuqtuCTJv&mXjCg}QZP?Yqn^QD6!#mCFs<97hEEo1yqt^}J9V^N0OM!U(!fa;nX@`U zkl~pouOwiB9HempzGR=|m1CMiMany3MqzdS*h#7BJ|8?2W|J_nb4*FB@Q`c&Q&mCh zZ}b8d#LCa|nPpz9#f}Zw)aKMox*f8frSiL8ftinI?iAPlB&rQ7XadvE4GN{02VhMO%{?`gIfx+lLvoSsyb*evR0Yo&b!sAkj%+T&*8Ja^u4-NvT$4f0noh=7DUorljz8J=SLMc@1e%FogZ zOrCvdW?P9%$KUNd_fgaQZVR0)FR&V@hZ&7%z@ip#>8(m?sKclt;c}P>dDU46y`x?m zv1!^Wf{;7P9DD)*c`c9dixJ4YccbQUfuR3k z3J6(7*>1u5@uNxhf2tHn{O>9S|FM<2TUnDVm1_1Xu%(i`&6&6 z$m+}6#KD?oEZMHt0&NQF?%TG1-d^`PehE~VHG)y;B=$>(slu1z%rqAiH2lV}bdEDl z0{W#X1ON}4~r9#)D(rI*%hk}bUMH{4f$?h{akS#Y{#D&ETAbhmi z&#cF0@nF0<6ick5Jrg1n?=D)-SAypWag#_xVncG6No^AGs^P%H+YR(ri45YQ4D^L{;st@s$mM?Y^DlsF^;>mKV}@4R-GQ z#lmZ_gCSKG6mdqn1U($4nK*TaWmewp{bwKFv-F~#P@BlJ%v6Zd?Ohn*6niKkt_S{u zxdeFYV(1K4ck!C~unx}#|8e&_E_bceluHy#G>&A}h}n(pk@=DJktGBEYpt~KYm%SJ z(qWFA9iGWF?9pQui%~&e2!lysG@6Y)1^#RN$JOa!n)ULyKAfj`PBb@BBZ{-W~j`JTUD8paO+d;QG5ic;7347zhgCHAU3SI1X5(hl&#l9#o#g-`2#hxfM#cVAR zk8Hg1d&Hv&Sg&9-TcUK=#Ry0Zkbx>kf0*T{M2#t9q=>rr71*_%nP9Y?xumt7g=lz* zh6^k3k~0n#M*^kzzx24t_Q`09!ahH~_5zPl>DyDNEGmOd3#9}>%sA5|Wb zDJ?>aGoYt8+T}1_Z&5Q{Bqu?aKy|PZ{NphGieNdHMrbdH+o3t90xG$i^oN!U)7?<` z#PrZ;8~tk|E(QS3he)J#@zvq`kSKfy=Y{RcL-Ni~%qJEoZ9~hV&eai{`{%~_LQ$`( zdIIQeLdlW$bC6bQ1thh_Ck}JJamd`W7$=6Mw}#0Hiy}tbqckh_2^{tX{9Fi=3yJ=M z|0j$o#=itq|LF%WLj6x+EbzYzDfx>`rlO~NK=A8N%b@;s--DRWV+FK0k+hb294lvHCiIT zge2{*G_5*`_|XdlVt_51ar{%(@$F5)$8y90t2mO;4pGPiLte-tnFpq^G?uC-E&$`js2RMHk0Yv1ING=mF>71Fb z$c!zo0a%w5UpJU$MOqP6+Lt$WNQ>@eoUNIiZO|;TEI2nIIs9Ho>k=ItY=K~5ifHes zi{JCugaQ3mt6#9N^e~%q^NH<8_ng?gYEL|8!{B0 zKv3MSdj1+AAr$FOL(1KW`@z^+TEYxSyMkMS@<0<24Y^jw5_L z=l-?oR>E8~m{wmu8J-V3A?YqWz}k;9jFS12q>dTRZkHQab{iBpythdnh=fxq7hjq4 zXp7J`%LTP$8s|8gB+@aQ7oOT?h7|C7X-|AUYQ`6uu;#99M+bt+Tr`=Xz_;|2HcYDgH2H;|UA z-qez{H`K5Bc}7b{SR`|rxZ zgk$Sx(U4QWjG74y_6f8R4=3@&lf;i`kP|vy@uSQcJE5ggK{q5MJVi$dt9Ih><_i1N zj{@`_Rhg zb$$8wd-4XWDV5e0%m0-32zLvH{qq*5jT4XDrhv2^ZZRgJnFpuTQI4qw#~1#sAO)hF z;}E!4;5 zCBAvI#<7AW67}TgT9Z3`>7#ak1fV^AENYQQYgLN!^GHa`@3OsdHD533GQK*nTfb_? zSi{8Ymy@;U3xmD4d71bSeNh8-TP9JJ?!tdOKYYqpqTy}R14dwtw>F=N8vz9bM`$4l`$JQ-@@;*w!_dHAH!0(Q+s zeSEhF=5KJR7aqqeUG&wimfhbxO{;9b1o__a;xXz3*~&3tcM1neru1r)fRm4rkPptu zE0Yj6!!1!QpqgKKAnCT7#991ByhmQxpjK-ig zMKOYY3rGAdf%_|N`<<;n9JnUiEt>j0Iq+Pka>Zyq3}V>w&j>NCBFkVY{|dXi+8LcV z1I{6(J0K-Hut@VSoMWn)tqC8OugG#=J5`G6T17XIA}`(H`RrkfqwH$Ig&A_N)>8%3 zWRPSN5+4#++3+k@K5}9RQW%YOd4f6vcFLc=P`3}Putz(sOV#Km=^hCGHetgJkP+6$ zvQ6j)m@FMBL;0Wgu2-f{2W9QL9_=gpsZA4o5dG)y*P)4NodomaM?2B~bol#U=5P|$ z=5}WPH`7e)SHU$`p6fqc#xiWO7m{bF-@({FeaRRiknXwPnLb(%v~V!o#k=HfkX_BFes2Wz%MJHgu!2)xCDo@BH3Zr1#@mV6x|r?@Y&}9MQ*TFBC|D9u5WoWGw@Xmh+8yB43tUdt$ulhunyT!pyN5 z4;2H5UQn&@L<>YAs-{bix?l`M1HpmdCA0{m2X2=k_}y%Vjd}ZqjlzmkQ(Ch7);GSw z%+Vn~QQoW=BlLdg>ohU^sKW6*L*2W5fHR6vKzOym)HucGewXkkp}~1bm%kUz>RSLZ z=~f*o+Q_x%_vGK5YLDQGKb;kh9*B;lH%0Q{awW0CYt!qltm#(zyE>DBmzns{rweY{cQK+O9 z9F94K5Rt?4ogCPxbh$f*(Z71C=wd51M#9@5jZt<+t{hHyJ)OGpU0kTBJe`|Tle>62 z!jtWDK4X&eU7G}c@!c9YbS1mKI6GjSTw4|)z25c{Hv_MUQ~8I+|B>oaq<=*vhx5E~ zP{lhh)7B{_` zwy!N;k(2C8Mt+yKwY87uY92Y^Xm%5GzZT8mcAyJxvH=w_v(U9WdksrPh@C7tz}wWQ zDVR9WWFJbG#}}g7m}4#G*;r89M%72Lk0pvlu5dKi*g(FC5Jy?+aE-ShJ<3sYVnyla zF6(IF37{WX*(XH)UZ`fo=Ry+BURe?IIhwI^h+Xlh;ikjQ-gMG{ONGx_Uy=IS_}L>n zt5LYIwIOZ4Kbf_O5;r?zYu#)w&Q7SyC%7@cwy=e6Z$&_4h#4)BJpu=F+&ql8&#t$W z3Z`4x+|$a?T2xr-ol9Mcq8GuuHXV2+qZ@{Xm~q9z9x;k~BN|0R_Lr*D)SQc~9qIg` zDE6*(ZRkt@2b2XA!4|QGi^3GVr_lW@=qXWt>bltIDQo0Z=9(jkgLNXiK zg1}2NQ;r%K06lwV70Xp0F=OlCSQb=gW8V^1o!jr^A!<4JimBr0Cj*J- z97nH0HE*=`yR%>7ZENyw;%CO(l8kDk-AYqf8ihI~_TxzFX%Ypr<`eMOld)t97L(3W z2ua3_J+;HHCPI#4Mq`$Z^p+N6kHjs&24-|Jh+|eC%;p1S(}|603T%ry0m7s51{>si zk@x_g)v;uO7XR<=3|A%N_rOTd_`HSw?d|^S-^s4IITsmY9g%i}CXHb&5r!9Z?cagY zVIOx%_25-QetPnO)u;6#-_#;w#&m8nHMNz+EHlYfu?s|g!z0N@0VSHO>tQvFE9kNQ zZ_fC1MQx4rJu#$P?@Iieb4@PVq8+)F4Q%W@wjTw9W<$eijl04GL4-WT^+P|a>}wC3 zQn5FO|6@;``M7mS$i|$wCv;@vsl3q=6~fp+^?R9okyP zg6bKHXm5j~e)17Rn|7bXa#y)sPF~uEgA=I?wkIm}`dd(w8G<jQgr49b>SulhIi6H!O|fi^GTu zZrNk?h-2oD!>oT4?JR22on&wj)#5UBwLAW9TO)oq8oInZwdkKR)mX;j)HR`~YshgE z%hIY}B~vVcXsNuwR^4cr2-+gV-hK$4mNE$pc)C5a`7f^<;*?&pOty^FlyMNows1B- zt`I#lwEJ>RzAHg?`9AyINn9Bjw|lzYSC>Z#up6dzUF(+MHD;}>SY7_jm=(|>Ecw$c zu|hd-_bgwegeyM`If0>Y;1V0o!|^jz)oq2BRTH4va~{Kq8tJW0bxEmWy0 zK?K82og|+YTqP8|3RxYasZs>n9A+1)@CQ`(Sv_Q7zJHAkgY1|5wBLMr;>f`@(|F^} z%hV*ZhHr0s=CUNA&>}t>nX^Q_n)B9W1>c1otZO`{Y}V$;YIL>!^u_BAlH<>%HuoXi zVz#W|C-QXcaMxty&mZ})z{OYif%Y#7~AW1Ph9gY(n@EFyefWXBkjTh zH(wQ?>F!REdndd9V*SMoKG}Oi?hXG73;Y9|M(&L#dc7S)_6sH=QM!2wTdE&_ShWpjV(|89O2`tggMt`xQ6EVV!?z;68);Se2ao!eI*5E zC3DdPY4Ui-q6L5io?sm`0=n9RUD33%$V9x*pSTr@ux?Sir{Xa_x%*Xj z@LMn5RfpzH|9YyUrqQP2(!AJet58PJ%XLeg&%~FS3M(T&Ek0-k1E%O^w5YJ7IXUZN z?(8K1=YlY5*5>T>J{wz|Jkb{lm3gY-I1geC8e3oc__{oWYi`o+;oJtdwk3oixw-(nya(= zdR&&*k?vGW%NoP|v~t@b1Ys@?58TU&@azAh6t~^Hy~o>A#Uw%q+v2H4my-?3F=&DJJUb~{*157It*4T`1-g!w^ztB*Yv z4eRsW>!mRFaFlmK$3LstnKwzJ2qZsR1=|xZ2#(*`(r5x>HvB`#7%%1#T+}C8kd_v; zr7$;Ss-1bkQWMId*{?7+|H(dNS*nc6N#2+r5>F_r8Xw?8FDn3fI!{WS7ouBGKt50_ z)8UX=QK#H%M?t3Y0RGJxJ5_C8|t1=ML*@Dn)atp2y_3sgtozf{t?Y-MMS=_BD;`Ejaz zYZV!*$V%DhC+Ud%XM~Yv5MG*U>=2HbqAZdo6VZWw!p$GkotZRFgtl#DSo z2lX$ZgwG=rO6Ib~^ZtqK>`m@G>{@cit1z|8NbqSg<(i1wwsNOGaVQN^i#$f!^8krE zFhbc9=E*(P7*vE9vdhR=>LhO|DH#DXT9A^$g^>;kO2s8~HM&L*aZcyKo^ZKU_3dLD zGUB(|0v{x`fe1v5vf5{(Dq1{=bvk9lRseh8$c3~B!u7s2z*heA^I#%p6NJn&T`bD8 zkD5@vR-_u*)+f}!*ppVsInyHj3NRnV5tEhG(wU{P-B4{?cdnCmF36}xhmBTQ^=Q{# z#llDX*deD{Ds;(Z?5&Rl&(b2KhPDy@RW@L34~4HG{R6fF1Jn+rR^%srfhM#OL<}re zPF%Ps^%n-h7#TC{b051`j@>+wF~Mi#k2|3Tth^z9FI>q!HZSl`jQF4vCtm(|HXuX} z9Mk^UZPTx{GxlifIlBmD2fD54f`To9hS;z-Gkj>FV%AuzzX$=0zuf6k?XdbbWWSA} zj{JsdA+Jkw^1Wiow{OTM;JbLh;gdzv4;!MnGu%9-J7J``NX{t9w*e)-Lh~(!+*`r> zV4zV*SxQT4MPfQMiqO<)J8-70gIak za0i6JsJQ+_v4ZL8JTX6Mjs~;ziS?6bhQr$0^Q5ip{;|!%vL#bbiHKOD9grxeWQr+E zpk}F+%vDPnTZqFhO0Pws`(Q{@DQAQNYNZM_6Wvh7aimXG5=rYx#WOKzWT=ekR1Ve2 zbH$7?QCmsH4a66u(anjKQJ?P)%g3+VDF5tceFoUxe+VT1mBSV}lVpbw4E?^vLGL?J z0>F}Jghp2MlRwTs-VYvO{}M7meqe@D97J~L3wXtU)|4=+TZjm!&UP+vp+Zz?HO;#x zKBkM`Gdgmnm%@QOg4twNa%emArG7y^LQnjFI8saepg3Ybt^W*;S&(N3iB4s>Wj=!E z*6x4~kcS*9-?GMm{KE`SgQ%Y*s^TIggD5>tLc>E&5ngiGAnVee&%H)TYLXct35fJs zy4R3Yrn|4@UO^#um!4*zk%ukaVJ^djbZ!d@J0K>KH3F9~;wMCu+y@Wd63dX^ zDMR^#=**AW8zR}y!3|S4S`0L9+Ns||_kxQT@2lj7jvr*vPY#h8U-p`s69YrMRDw%zKJa(fR-U6U_&QrTcMOxoRx(g0xq_2MS+RLxwI`CcoMbHZ`2%Zs5kpnf}k*aP-eLtmkkr_RX?; zL-Pi5eDcSCN@X~Iev+Gmf`+HSltIn6XU(-i-a9d*?DJNPxbDgEW9i)SYsH=nhI)bc zAu$1n_PNBV>YG6wyOLKY6%3d}EX5DM&D`&O=C`xP1Zb2pps@PbNLOe=OVQKyB*Tic zj{EazPN-Br-M!LWK&(ogzL`?s%3`wjHq4#Bk~!!vhJUQ%qb7-pxSS^8can!Qju-xm z;E*@XcVEOjE-0mJGZV!(Pr!j1%dcKvV0(ChO&WEilbJ1FZUhdQt%7el)Tm(>On_EZ znzXMe9!~gnC6oDnm^!~cV^On8Qxr;EDOslxdzOBVweYzt4QITQ89ob`?J6Ja5E*`? zBs)pl!#1XQjq3Bf!n&kolKy7+r4Hu$vj5n1f}(7?e)B``X7FU_+KSVqu7^KS)5Z2! zUaez`|5#o2ja&VtQ+mP@LzgSEjclxcgsmHyLmIGkXnHLd6Tlj!+o`S-;n)w|guELP zY4=m2o7WCj0he!oOYL8`qQi z2Kcp5UK`e75-v&h$LeIK(RG57Z`4&IO#3gUEdwBEVvIYpzK@U{iat5^Hv4 zpU()B{29pBf2Ci#3Xp&JNHhsEt^avRxWv0H!^n^;N3AW&1YhbDv-Bq){2ur$~=cSCdv88L`$s z$?zL2nIVDdfm3kua!l94qc2i-I;~f)@j=ry3C7A+(!!(C^Ttch#x`NS39-_jXr=E7 zT~2_dn%$<=3`$HrPBU`N`~yC2WY!q+8_PoZA3sY`KcslLE;<;YhTm-vYG0v@(lyCU zuqn{qE1a4i9^#%=()gB-mccOiWrFbC_r2?i*C0Hq{h{Dv` zITBd1*nL%kAy?M9qryWNB0k3fEkW&#ta%UAoiJ*brg54ozp{R?_T7;C`XSiNxpNW0 z7+wO>2v|dO@~@^Bry)W?< zy!mkCJWj-Z$_6$iC4GOndiHHyIoa4tOFR7iCKZZb9r%X`hrDFR?c=xX2gU85W7KN? zg(*^g!${*=<2#Lz%vNKsdZ!fr98zO$ZrF3@rutY1Lqf;=}aIQh9 zNWl(m#a4icVvW2*P=%MQUn70$)(kVhLeP}d0__~KLJl!~`3cDq<~@v^*29G#!Zt-S z!+f%b&SQQb<(d|WF}k-Vu=LQ6bBs*&K&;&)?>2FaTCNPARPDL7|5)G&`};YnT9h?% zz8QznEgBef**mP1YmyKU1D^0b~b!Ys4i2KH1Te=|2>vwJ2wr$(CZN1BPZQFX+wr$(CZO{E0(>)zA{iEl{ zMC7U3l_z3HR8-bJ`()-?iz3loXSf;XBExgAi@c!RHEj2m8bf=iS>}=_pr#v^c@hfQ z)VUBhCcanYXR3l$HACd0N5OP5xitIg2=)CxhE8y~C2gy2``C3i(NCb)k@NaZKimh} zeVD(%)gAx>EuWo!9Pg{zy?*z!lD%{p0BJ{Gj0w+o4XxeXOUo83^%&pMNZ)_bOb1$^ z^iD~)bqC0Y`%n_A0CMIaKa*h5%bfevO;{Glt@NYoV5=0SLa-9Adn(5UYjj#co+!72 zQWB+V#aprARH}v`##q=zT2axcmUkIVfWOpN1DmP%dU3`~z0_CztI3;pxW;V8gb!s4 z6<=E!g;uK;sJIeg4|NZ{4tWn##sbFd67{I$C}POzsA9^}>%=aLxr>&_W6F!ke* zta%&~RZ6|aJSE<>KB=iJ>ng!qdM_5kDSWZoK zJsvOgKP)dYy!|>;FW{$P6)htf5_IvO&BZlgE>DO|u%tYo&8k73YNjA7DMlB3^J zkz?jnwesp;Nbm|NWAfgXm%F7=k-Kj!z4x|S0PTV~6WpFWJMBVSuzS%}NO{{*O?l;2 z&iFKVwEiY<9PAd>In~RndU7kV`ZzAP`eZ9T|7b2de%n^0d-&Gs9QZDM+x%1ILr1UL z$xJWs>60tc$v9J`i^VS1NoybH;jLfaMqr<^hT<;MNpTb1MskzqAqBsn6;QCS?vL;o zt)I}w(xSbIV6AoylU;rVZL4?GWRRyk0iPE~rJN2`4$-guR!xpQ6q>WD^yyX`Pbkg0WCHna8AAMYn0athk@DUfL#@ zwERLu<0)CEh-KAejZ)(&o!WDoc3$g((Yun`QzzM5KLum5W{8@}u*qwvy=IQ`eI#WjvbYDcJ@8r)T*MkhIoYJ4ls z1aH-ZWBjr%vxVAIA-U5wS>j zfMPyAg+grN{|~plolzQ=`gdNp+>Vmf`Ujx=pvK!s=x@7m?ib_bBGI${bXCbPUC}VJ zec4ZB$Hi%UxlioAGhYLC2Wgy%n8bD~qFttQ)hqFr4bD_Nh;Ni)##VZGADCy2U-zZS zI&~(3P0}OD5UY1S?_jicSGQ^>)Ja!Bc-xr)6h~lx_hlh++SO>m--p(Y?F_bCl$-dQ z@2k9x9G>~1`tWIn^Y)NS_mGthGT@ydEj#F_9XSu3(LqSeZ%Fv^@>?I-2Nh?%QgYpj z5PA6@jCzy>dEzxg%&T~(BvZpv+gq3_fm$oM#wo!^wAfVzW@t+mI<$I|+PpDIq@c@* z7srm*=#LP8`;bThRec)KLX7FAxB)ozad`cTeLkH0G-<`kY)8_ZRGPMrR?SOS8x?Cm zpP|aqy%oWsxs1}xON*M*yH(-p;$4H0%F_HL$>g9+<=o5g86|4hBEu=vHH`}EI!+%{ z_B&RtWGnzslQ(h>tY6p$T-gfLJ{>jK)P_8>045+%6`ajd#J-so2zN=ew|vc9xk0E_ z9xFi1!pI>{HPWFHgl?J8Jwi3Sdl425T*r)XSnveE3n0J{F}jb7UQD_#tOY^H5K(pi zxh98Qng>SB$k!o#Hd0{%1&wX0*MnPlhs{rg{SRGfUlcp;FGX4aHzNetd~JAKQdqA~ z7O@@f!EUKLIq@%uQ9goKGUD&RgPhn8r1&3f@xM5I(Qes}6>%pEy|AUZSMiyZIHsrT zbY`0Pv-MN&dnZ6Hq~(oA04g3bam~dzVM)j4em>MDaovMfIL9b)pDQXwF|!~m6BbF_g|xfxnJ&*IBopc-{&&T^jHgL8Edb!&mG^20hMI|9B`(D_)d@) z=my8c`C`+2(h_{s@9A$+I2tJ~qkZU^J`;b6FgCkI4W+qO!vgZ<{z45F^g89J{q7Y% z|9~cJgIri-hfRzpe+Prq##L}k#|qs**Bx;S745S-fmR7gO0!_M9w`BP>RD>j~8TIOIa;PhuYQ15{cvN!3$jHngq16!dNSOrs zeXoXs_bJFF3Lo3}xGckM>P?wyO4OONEJgx9A_dFO*TKgY-5Dbn9rK8qI{=d#9f^9)7ZUI|3B4KwV9Tf~FHFabr>=i(8N$C&8+eFGX6~ zo>0J^{ueZ?NQ5Al#_wy5F|{ZQMyufveNNLpX(|0}4q=Fx)sQ_iUkkalIt)u9ogV@# z34j&qK0mJA0`W*B#DZNnci>}AAzU-%uWR=|mK?i)_)o&kh|F@&GO%Y+97;{7k`4!< zYD_NN{4n81V2@X0AZcGaSWvE+k+(SsB5@4j%=XM_6`f}t1jcxHksX6Gtp!n(-z^^J zxDLGQ%H5cW$s;_BHtj{*Ig1*2zs)Fqa_)r~iLQzhLaiJ^%?e!Y99-=fv1*D)J4>#m zjUKDYUKvc=CP93sFeEI{W?^Ya1^>}T5Uom@dDR_4-5o=wA$TVbRTr{Sy=We5JTcii zq-B%GQ$cxzkhQD^D|Eow`ZfsYDK~M9F;C?iZh$ zlaUF*H7)`3Mx~pU1cTup$HYYbdhU_poeZ+8)pl|2kt3vKmGeuHEI0IUXxwF@z$7Kc zLc>U|X&AI6CAL76`bK!N#400!7OC-gpmiFg$xwU{Me^*mLLmB(jh3Ep_f&+aS84Y3 zaEj(O{>3{xyLDo#`LhZ1M7avuZ2;;wtO>ih4oDIfIAsPnB^!dW4~SDk299Z=OnMS4 zL`pr0c0M9)1c^2ws`k;$nN{YnPNPKq94UcwQ=q)Epm}Ye{D6O~1kGVpACR=FcEv$L zy`kIUESp0ulq?`%F+aQg452Zp&rQCOz-L5Qq>T8cNbH(q-0dbZhF!tPiy6Jz`qdxh zkU-^-$Y`~(lNW0Y9JbLD_YM@C>A^T4MOnE;g8hSA)lBOp$=_vyfGAvsyqg=J{qA_e z6SSExlE0BCz37dO=|!e?12EW-fO$Sd1}2Q$G0H!~4KqS0nqFB3Sz{Ef>wlSA#q@5j z**WAsaak|prm%fkbP!waG1^9tznB(AW~7X_{0@uE7_V&k%^HpRa?8=hhm%4|K}&Sf z5}B(u2JX=snVT{K-nJ2*E7Mk5xrPAb;7aWcay!a^;MP;y0OcScs7;T}ovOex&sT!b zsDC3OJWslpO*+6M6uK@I>X{7xj3&6@6xebM;Xnt!r#lwRPL=OUWSb!zjG;gmhv3qR zqOcwcRn(<@BAAJzm7-PK81*-oXpA;l;mJTbfJAE%O@UP`y__sUzm)k9?}=)`Re8Ib zpG(EJyU!Z#)%(|KDcC!bq36gmbq}k~M#jP3mxRK+7BWkxkivYsece-b|6pajz!N0~ zOXEn1MQLO@rtyNZsfY~OJ~~hjE0rZ<|D_6}s%2d5oFWDl%ZPd@HO&UDKgm+wGSKwp zb7}UcmCmTwI}Tg{HfMA(&>cwhw##Zazpx+X9h{ct#o9>%T-)8Cj@t-D*u@_ftsXpz zJUP1a-Dte_(UgjNnk8-0=^`3}yF&O^S_0VO?%Sp*cNUNVRZSM(Man%6vIzI+4#Kpq zPk4#lmjScU9XYa; z-E(sf2S_?~8XA*EG`c;V6tClJbN`-+~f$=oBO*F zEfq=kD+BWzbfcc>Ztm_ak?lvs$CYWKQ+N)kjuBqmR2+7b%#ME0l+J$>#z6)LS94E> zf&=rTV77WV3FiUAPWRC98I-X1!hV_`@fnU8VPhBnxyd6|n)Iw_NrCEb$Hj;EadMfB z0>R+hCQFY|7mv}`EI&UIq2SvoW`2fcfXha0BNiW>HAt&JCB!BK(Z~wUtiN2VQbt9* zcY31ZVW~}5!+}C7+3lbXgvHPAnOnL6ewmdr)%#Sw{@%bUR9V&p&9=(4Q1nHYHv1e(qDWy1v$5&A&}0MLA<%@F|Ijv zrsQ@cS~wo{I26DUnXvrN*~NVnl;_}SKA;ub(5=La28)u%)sp@xRc`JJ5%3> zgZ+kr<^qn)UoJuqtd!Yzv_KJ!Z%x4>H0Pn@Aq)?)^dSQ8tOPoA`>q5!eEX_o0)dZ8 z5#x-nRqxEq@&KkC@GK6P4m0%ihu%&C(<~ISG>S)H<9P21}n%vjE3n;Ka;R8{M%5@ik+JKkMSYi8w{Kz4t~(Rc4MC?`?k#3YXZv?+}uc| z4rwU@0uA?yfMaNiv0uvHB_0W#%#a`);t&rB*!%c}cB0W{aqkB`Nr!H=+dpa!m7aqZ z9igGqc`e)J?mgu#OPxP`m=tl)T;i~g@z_TstCf3RVyxodg~-#ll(=`4Rc_VndNGp( z@c}Oy_T+^|kVEpC+VavC5&{r~g`kDwSY*ej2dEEP9&}#yFKt*o;BYIJu5yK@u409@ zWqKB=XR2?~kCdN9oJoL6A7i-`wkFXOx+W#~ZjRkFc-!V*AlJ+I24gKf)l=_hUfBj1tNl zXNS&a9MbnSqR!Sw-VYjL->^vB@e~yfLobv}V9;GPkd_Y+ZS@FN$g^c3wJdW8WSxF# zb1irH`&8C2rZZIgRxqUe3A)ezDO4~v!V=9kgt<7BHY73R zxNlsrSi-~^r4)G|wK_C7guU-ru+=h@YGutR%fgCvAITLpA9*?Cwa;smcl*ZyObmz} zPBgBf{}#Ok8mw38jn5wP@UEuY=NGP2s~5L`-Ee6lRwUY4k~{Wc@Qy4_ZMY-oOLo(* zm||`9FmtsX<}nzR^oHN;S&sb=h3awIPYU8R|1Mdz0bY&(b%=H>rgPCcd;EtSl3p9ANO{e23mlR!-3-* z_sQJL*x}QRt@E?npdHOCst4!E(ee?xA&-$_e3-A$_JH=d{)m2aYllYY=Z5~x4)iLw zL#q3~82!XtyVThv--U@~M(i5t-zJDs8^Ql$h;Ji<;}#d4oue}}PZ7!oJe{b87v7n> z0eEZ^V&@4YzpuUQ?^ykDn9f&h<9*TC%sXI*zm|7m_+A`%gSCRsJN@SSPgg9<8qq;M zB>+He(tqxX{jX|wa{n_(l!%LwwS}>Xfi06Tv9y85Z*e>8{|#}hR2-KDVnF6OWZ7q@ z+S0xinV#$iNvad7iIvvITn zACEUkr9+K?77MC;d0v)EgyGWHe);T)Cu?fcbUj#^N@_tMWj-Mt(x*?{A1$Lihi>#e zhh9}dZ6)fU<+Ib1pqi`c1qikzxB|YoDvxo1Z-!(&5i`r>rYTodOcWM;Oo(+DW3M#E zIK4C@#w8c;`OCosAeEZCijCVtT;x{~jcwXBQXYVV{|N5N2aj=hmiietnoxmxL=~TM zfl*3U6T%nCXfX|gJwYU86`jv~TU0WZzGwC*_fJIV=jU%F0RjM&{Q%|UrGP<@0l>k* z0sgBhHt+u|BIKw_XYx|~Q~2VTpgz8Z6e1#iEE;iaY=Z;@MVO!ds3;2<;vGOdtAvu^d~lIP zMi;sF-#i+dx$lXrPS3`8{YI<(gZW}6r{k&2`|014Y36)iJcFym&T9BDi_4=D+w7!wgADq$Sg+jrPnGj}XRr41@4}J;lt{ z4>#YdSG$|r3z}`FNpSpy+jIA%B46AYvE^{VW28^~nTZgvA_t#wIhm`-KwBrp1lrr8 z2K1HOsj)HUG6;uG$dg&3f)j+a(!pGel;uc^(jUS`#Hq_d_GL!%0;|L_U{B)y#;weC z0oRe<_=0>Vto)uspGDer2f5qeGP+f-Q<2y5)SC`i_ME@>mT$hW6nzd0&6-?^!Klr?;_2_-s>@l4h*x7EtVl2fgl7U>oPe! z4q|gNZz0~=bIB9NVU%=^=z^69KOV~bEbKM+h`cFbcjSDWN9X~r60+yAikIXK_?0_C zr+VUi-_}+BXftX9>>*)+_j-jNU?ZyB)d*NLM*_rsA9 z^a6nM(wOFX1k6zXXc!3bH@($mCg7~b`B|j3QUKY7Tu#yrU*<|zppUQ|@g%%Gu~^)h zw?u)RVJ=)By%jx{cPeh`qN_DISybXRYyEXw%t%+R{tvrHlrhh1+l}r zV^4Guf|1#D=)L01ZhayCR#sv5QN2y{>)f5nL>^Oy8(MR_ku?<1J5;xAn6*QXkeLkA zedG?hRj_Tcy039hR2In~?ZJ-OWVqQ@w>P^kaXhOsARBcpZ$`o1lUJU*;jOo+_c80j zVm&$Q78+JmR3OrO6!-XW0J*FDq*K%m zJzTI<;Z)(Yz*nIGfCTUa@&tN0Tzy0XL{Nvoj5JtrOao2i#ohLT7Tr4)DgMR61R?U% z?dWnPK^+UH4w3u=xxomzJLN_rvFK$(BV$YP7*hIXx#Md?WTxRj-q$&}%yYto&GYOUraLK}2DuKi>(Kq0RoDIduS$Wy~(j=9;C(u)9L90qDn zp6ct;)wX=MZ*%+8t#i1GV8&l4g|fxKnJZRsa!AAVZ53EOohmN;Folj*$(#1ZTImg!Igl3d!9!tlQ_@DtRQf`C`}_I0Ir#Q$`OmNN?3T{a6uoT zDU&G%mPnv#;movIHcL~Hv4}2o%^IjZm4a)kR~*LTtc+wOaML1N&_4KzTdRwNCEO{- zY)(jy$%0^*hBbNO1YzGFjIkq z-Ww#{1Zg?mel~N0@j}NVHtlq+g~=l#XXTupy>J2#V`@_Q)7hgs)n(7h|B)xVokE|F z^uf|)?_~(EjC5rg7s$YC+j(1J_gYOxg@c4Nx+0$Nk%`-`8{>Ls2OyEzw-tcX=~=y6 z-`src;+yUT%sYag(mD0J>BjOazI(syRU*^((Y)Ml`Wua%C=Q!(hyBB7c+~0DNVBUs zq=lFKdZg;j^*+Q*{Y$d`6wR4ZPA6-8u_MFjjf*UN{xO0vc54j-SMJWQZ@CgsII_Mg zOYJZo#Iur)Jo{#4WdzyRg3|-G%X6jMEx178J|*YrA;g~~OHp)VuLZ-y!BJ4-3~hmf z`_I{t)7e}pyinMM=s+5Q8eK*OZzi>B-I2OA8+I-yWq~ARu2e}Dx3Ub*f`tE;Xkabj zM*(GmH?nqJr*z|H*=3v!MvA?8fO-TW%>H%Hyn$mZk_|q)5a9~D5NPk){sDM0HW^v4 zc8oY|XYS$wm`(phb3B^5>s`$6V;vB)~dYt7AFu@3u6>zPgS!9)VMM>umVA#z@Qo!~SDhM0=^A&G`9ElE-cO2U! zA!v)slXe{6XdbZZhT$_Y;I}B6O(@fkJp-bsegrz&V)+PsNM5l9{(BkQul@m&g# zwc;tByv?`mm@MK*nnvcV;|f;^3s>2I;6Y6Qn)PX`*Dc$=j1G+DgtR;|C0lh|Gm{<8 z`DA@;H-|?jD}k@lg4@7c@!OCHuL+}gq0L^vEC0sKalWAko$T9({{R5jENu*^PEQ~{ z^464Nn*b2)#<-+RKL0d+7)V8Gb-hFy7p5g3Qwa#s7oN5l(CY)Mr293vLnlcD@q&;0 zB7E|Jw1rqdRW``0YCcu|R1#1#6^|Mv(_mI98JRL;grepfB28myWdVjH%8G|=!mVoX zS>&ZDtNzdxS#B>AG28{SYpQ8$!nw5_^HOFM-hGLc_Bn)8_C7h=CzriRox>Qno^gOv z8gKA|zA>ZBs~L2emBe+~Dv6K8<0|$Z=EI01In8SVZbu~vI{(myQlPln%hoacJ(

Ko9yOE-=Zg9WRh?9jmhI=<}yOH_0`f(Ip|hU+baf* zplDsqXunSVBdT@mZ|f!otEpSqYj+HNkM@>PwYg;_OkTXluDyEkrS-UEjv0Q5r3aAL zaK!Q0$;=>hQREc*9T`2*TY!+hfx7M^y*s_GETP}SqSoHcw+QI_8(J6B$ zz_FlNgQG~?Q4wzN+6jyNI zY=@~+*F?KN!1nQ9Dn_&+f!goja~Jez-Ou*4K-pT{{40LfXNgru3#F05Ny%b4Xkba$9>SX!`w8ee_}ZQ|kBesM`SKvFz#!9WVF{haFm!v! zZ&AOgaj1NSB#fR8=kvN#?O4P@G7Z8Ytcy?pW0?3uX<&(D)Wli6*|#j4qa0$)wJG)N z7m(sQQ*6vq2go~k@*4QUyje|8mL&D-P{3}_R+$X2;35v*kIuLV%9lJ!8W(yG3^Fvs zys;(iY|ztM6H2qhzXTOs1%L`2(CV`O!4tAqBC}b$#hKr+Bt)b?f=36YCf-6h#l7WL z!5@*$=D6YbfI@|KB21bUoyPWevT7@kEi$Hzh5hj^KIyGMMOT#Mz@;+DRW7CjStXL& zEbFZSM1ud8hi_gu{)RwCw2_H3!01lnHeLcY`}=1* zb~5dUW4IT_L5?gJgexPGuxaTuyaH%Fe5}uQ8|aKG(Y;5~_1jQt9dM9e$SM)<6vVtn zRDxPG8AD+9Z^T` z$@!uzKinxYCGhXgEn+`>pMY_aLdWU|WyKTVV%`^9jQ2DOjTF<>BlxfE+TrgkhW^k)2pN#Dfh`Fb*I&D`ysI z4JJ5OyNBb#%gqPuVQ`X8rwHsiWfHxPTkNk}KP$o~EDZIKK_I{zDpDt33dc5=b)5u;a=-8Sio2T|mSm^=8 z!^-cCnWr>A4`qcNrZTnA=5vGw?KuN>i&1Eu3C{0&Z7dl@b@dKeQa@o?gwe!ci273A z+ST;VeRfEw-rXyytH|BCRLUB38LSV9Ww$Mt;9*we3XxPNjAi~J&|CvX4&e(e8UPT_y3 zw4rKZ!38Z92Dng|hAoJLzcxBY=+p{YiU^{y`Ks>s z!Q6b&2gNWs9TN0-P0v-4Nt>Hl9`L6(L7$SXX+#u|LnAd%#&OWV&qhW3X8!8L0)?1X zglCqg*hw9S|85uN(P47kqNYiY9=z5y8_{X91WI6PQevJcOVdjh-J(sol$<2bxVo!R zNOaX`o6-?lx+f{epA6rn=)H`ptr>~0 z1C4IDM`S-HNSu(IRkz0}SH#|wiRr86bR5+@4B};!Eogj;$Gj{VEjvy9tG#olG{<9` zcAM{9pOkK;dWXDC!P82Y*Lg-!*{(V&AC_3~9)L|j!OUkp2@T}pjYbSJA-3-vCrF!h zWG z+S~lu8Clt-<{UO>894l>jdqI1vGjK+8AqKeor1u8k?MWjSZ71|RYN5O4gXUaS9Y^a zvA%*MiNY^i<0h)XuG{xws}Bm`Yhd+!C%#$X0Ke6=Lqo6C*M-x z+b6f=$w)Q!WPV2CBDWGiB#B7q{F?fP(}&4KA9ke-}V{Q zOauyg0F&iLBKm)68aLKPhNwHKkbUjQZZK5QtyuipUotB_BPH2l=H-&r{G8Vz&hD8k zQp%}yZC{_~#8`+@q&aOT@wEL4JnBAe^6z)yFfW5`@cptYN4dIx2hemk+Gq%Z{Fd45 zVvI`BE@-8te?JL(?FMoux=%$!pR4y83@xP+6{wg zC@)=?EG~0Pm{d84%=V6l>|-IzH)BjYAk_UUb*gZqhwY3r;Pl{?y)^_+3dNp!hN$CL zwF4%24*o641K7bY7p18W^2;9e)0hNvi(NKUUYv~kFEl}|U7rx$ZhkE; z3H5$quIR2&0f zH(WNZJ&E;bp&lufWLfm)>(5{Rtli1UNStDz001&S>-T@;ga2!VK=^-_5B^UTf`47O z3srRF=H=0SWHG3g2ovyq0Kz$qy~KYZCGmr|;x6#F?nc|KkK6?~9>sNTydq-R>x7dz6<(o3&ghke_&Spj)XQ@w_a zLEB0?>quC9Or8pknLJ&i;Mm#LtF>Vb-tU|tGsl?DZGI5hW}iWL^8_=?YEw?yVgv#s z7n)xC8+!yr6@zw3L>`)oIqccOl$7^JfDyEu0^36P#b+>DwpE7)iQ&}xqk77-S;~Zh zdIPEBN%W(dyinPp-AT!6ZVJTUOc)hr!CkFey$~ zHMT|RsZqzui>9LPx}Hsut>Fl+sM8L0cjywi6CN#wu6C`Z|U>sIp9Oj9Txt;$(A!}kt4 zrjY8GRE1f|j|m~Yi@AB4MXXK634e(`MC5;K|4ZCUWSijNH`(ndJ*U_*#6~3JF%bpH z>#cBcLdxZwJRuAz8NDE_u=t!f_LF`}drcU4c`T@#tkJti?X;YclAQQ6t%*d1gW;6f z!?Qox6g?>pB7<}xKkjyfq5l}7u z`HO~^%{BsBO+zmr42b?VFp|K@126i)E|6BPW*H^~r`=`g3q>+mIqwDOTN={9vkzgb z2V1R9d{eD#Oz-d0&w2n$wYVX{Ng&y~t!jZUmC^Jx(=I%#EIPQ(tP@Q)+6XT>GPCvA@51&LU^sfA zNcC5s+%-HJPsV!Uja2fNSsoVEj$ZO~mu#+@={(*`<~j62$m-G6P5=nt>hO^O@sff z%)pHd5zCJ&h>saNWWZ<~Ozfu5xLasWzqGfurrF+TUao4>emR%iG*+PAxU$*RuGLuG zI9>Uu(gwO_d%ia8v(0gw-Rg8LgWeaE-~E=rbez5X?EQW1(B*VB$@cX&NCuz}=9z*= zYfu4BnHmBa1z8<~@{;!l1+}02=)P9rK}$Gj8xF0`une?BRZyf9uQ;-(i9wmFAU_j# zy1VN_$jZd(g3Xilb3Z7UQxZq0(%BnSLaQ*-qhZ=!gryMD@KNp zl#XmxW02a%limEe-j5Q=19S7uSbl__o{Abzw&^qx?Xl835M@>Fo+O{vNLBtCVc8-= zYDB5Jpp8^%NpZekxQQ}#aeiDlDP?-8dETBSrK)`G9Nco9YFTCenkAl9!M2sxg(jHM z+uo^hLorSEl~mEgB8&_43L_XvgrbKYX_?ttKF{YZkTOk;#{84PF)P^akaAl&X&VKm z)PR*?>6R|G);!iEvFTz(q?l(i@jg#hgy&wT0}oS*fPz(>RE+7{yaU);naWCE(|$J& zG~_YKqp>MqfL6Jz!5|ZpvnCesb-pqgBS#xU>2Suo=koA;dH%U)O<@NEicn;JC^GN3 zs2yqCg^~T@jBwjt>6SZbXD8_v-noS9P=SXGXxKu&?jq2;oD}Wt%Tlfg<563tP)fe6NQxnSg2RZ^!`xl8Xqv3fnce%LYMaG267I? z3BF1cbZX4f2M%rO(lRFr3iPMs_8N6n96pZrWS6DM6{IXb5k8dJH0Az$b0y9s2@`q` zhL&NGd)H-!Y#ys(vZ)+7BH68EQx#^^d(w zXtpXaTGnS7w3aE;KVEOwxcHmkHQStGKowF9Z?8_YqU{*xa34fV-GE_XQ6{W5)b$up z-J@)%Zp|ej-?buH`_AH0Ygj&1&IVK_1>4+OrCjX{86QQPQJWpBx2}Us%Zw#e>8_G) zd7vuuFDB$Nc4&N7=r4?=L8s2nTmh#l^RkzYjrf$LsC&W=lj#x|8;mW6>`!-X`B*{N zti^MkOtDfLCi28ql^Jo_6>KM1^4T^}%g?*huDA68-!q6%gCf)_hoBXxmlwwN>-1V8 zTcYPfoA2+kIS3ZmRhx^~mc1>fW_8~U*1{48WzLZ%Kf7=v28h$l@{Ouyiz7n#HFqhRMT%4ES2-y;; zE)0nnE%q&O>y5&`Bbi2Rquvs$dQ1FlIM`?*o~cr^uTog-pt&k-n-0>G<~OC*w>kb4$hzJQg0wjw>`Ta zC1!iv`AzOZIT}Uf*AjP!^t^YoSH`KfqIopL38n-(+I3{k1U6P?;cop%_I|SG6yu> zMh_Q8B%UQ^fD4h}RyJH{vT<2al5b}Ah5(+>JVYbQVovm63h}GhDu<(7F$LgC&l<2j zkA7uBIJ+>$1YUez%dL*1j1D43KHW}6y!Q&4REb=&#Uu-0Q?kymzUEdw=nCgkG{Cw3 zGU$$gD-RDL7n~6cZr+~2i}{~QGY0E^Om0G4uF_DYTEB2wN<_e9V=V6qt{x9{x`5VV zgCf8pq+1wj6#b0QMzOHbNp&NOie6pAf|xZ%;;W=$t4MLkwou81;WuDwsJIP)>%V(b z0N4caV&Ey)NR4aU3k!kMQ1heGK&50xl486~EIm!LIVh2}YlsrDLd z_~3e=Zm2Nd5K*dUUWQB9;r|pYxF)VeD_o*4Mk`&iFUrbaf-J4zx3d7`1j>Q#OkZR{ zqh<%&1|h|_H0Or&>HFQzcH6 z`stAfjZ2UCq>va+9hwxzEpBXh=cSB5?7=Lahmo_eV12goFIsg&Dtu22M`nWzk2;NitAaSWDDb>MOOTw_~VVGqX+Zvt`Li zC*DF4K8TP`r*@38F09kY*fqo_AE)lrtrRlAx5DM>gWzl(x+%i%jDNKP(F!!P@h#U}&lErRru*$rFu4);XTUbu@#%Owo9`%R$EdVW>ND$Gp+aQ8)^-d_{z(1l z#k}bQQHNSK@Wugf-@%cWT}9!oKAvXqx@zDacFI;W#7O|CAgej-e>orAuFV7P5!@Z_ zK?>&v(=2&oxbcBqXAw92%{zmKJvA72p9_8@L_z)Meg|?Tw32`UuPra+iyXnqAFm97 z3|E&3m-%E8qq_W-frYndXxP4EhhvaqD{y+?c9T74C@^gQ1}O-R|I~ooe0U9z+=~%; z$uu6`;944yNSmHXEH~MtOhQS?DlqIB3wDAod`FBa51|NuzRXJ)n zdL_r5^dCX$>cPcz1qv&DNK7%B^kGHjmEqCt6&+UgK;@9C55!9;pck6Jj9DX zkQkCh>=p${mS3(vz=-j9oWgPi1{TR-1wsFe77#Wm2wcH%Q-~*_TLN%%ji0kblfXVq z;m=GU84jJyk~1NQ#`6AO+{Eayh~QTBQur@hgRfnK1I=o;I#E4p>90dzm2(qptnO4H zyPjlKu1I&@Om{qgysk0huLY3q*5JL6wt@#Y#$J7jcQRgQ{6~YeTDg`{1N}ikPEXEq z(Z+@7i+bP%oD*-Oe}I^zTw}k*emC_WkzR|&Z3O`C$Rh7|+H-Wk8SUz5SAhD1lBiN` zkS@+bUhjd4G;VIll(=#={dOo6eIc`^+7UEco>|0XXbi4e3N2-EZWNUUjpkx!zfP9? z#EGo)7Xrf|m55;A&O9FX7YZKbl9a|tKOsNFDJ+7;V#gCT<@LYVh}q%(v%?*_gc1?lA zW5Qv6lkGUG#0!n>8MiC9k9vy%U78~T{$vpQnF$f?3M$4GPNgr z)S?I#(r@Nppwl}$MI)TB@4~_xybp?feQ4hy$0?H)NJMbqUqjC!Q^QZlxD*&V>L%=~ z(WIB~ITs}C`@3m7cq(D!TWMrHB@Z!r$Ml{V?4;V>SrxJinG?c<8sbpmpW~^7a(e_8 z)Z*4O!u_rjYVAc^n~=WG3&KzxhNkl|iO;;;?Tf$r-o1pjX`~+?rg|vAV~zk189J)a z5Vc+}<*h7!eDBvS5 zu4sajOhPOi)vHn>3=UTfSo!tD*uNt8zCnxn^$b`(U~Gjaz-M6mH9${fP2#zd>aUea zTa`H8|G6lvSF(X)lPKGauqmkN3JTC35SW^qL#a&7FQn3B5Rp=AFbq$wG9N^y(U}b= zpvg;qZ_(tXUKDI?6rp*_<)=se)L4yR3>7w_FVG>^rV*w!r=tQwhb>9%drv2JbD_7c^2YC|asX zIWUKDYOCC(Ht{hx9M6kn*=rzmr?Ltztr&F9lPBSz2!Pr_N`?xe98EYmR}$;+?Oh|= zRZ>TE!#VLL?mg(YH)!9nCk%k+Q;Y~tQG@N#s)%h!!%wpgFs>t>-qAzp+kBDoX7Qg9 z`M468>3bt^FBfBVcfza)TuuXDUimTSS~UiHrYa#LR0Lpxc@ZE61jZ|biO9gnc94Qw z_>L$J1{5}i#*v`~LM){mRcV_f=}8<8B~?=onTd%;2Bzhq2{UA->Tx395Dk$iNwJri zzYjvsG6uFd2)aHeMD~6qDp=E?i|>T*eNC(haUtZSwa|$*KB+xT{3Pp;DYZ5=i8di% zuE5l0Y`vPUOch4$(#>)>iY18BJ-p*=`4BbeaLUf_$`DRB>PepO3j`vl`$m>OzYWt{ zya@O?YJZp|GH4Rk_~mI`2R>ktj!al5#;sF*1>)3cBtTkipZos`(QB-&A&Y6XuM1O} z6QMN3c_8B|^_IwQ6krEKUR@c`#xc^+Ot56JG}5azx$^=jRc3COL5dz>W&UjNgf`Z# zhtd%upPa5>#jkApc&Jjie3Vp6DXv~b(mbAmUwP8pU3ac_30kpYH$V?~5-@55GK+=c z$s{$*(K5|%283P+N)UUgusHzcE1aLxuNp}y+mLo67){bgZW*@8WtCrMN>VYCIu*Dl zT0OKKAHjod(wn6T3TaWC8cJ3#}lE)|3drU(>YA# z#Ae#@PmK}*54@hpn>+%7Ygq7^BWo%^KvL$G{%ur^gGBdNCw#&@S z>@+hoGcz+Yl$n{Cq0G$8T;=h1U$^?r8_kvaN_(erAL;x#CzP>r#aaN=c=%b?#^J9{{$ClX9Tg*DD_Av0qY(rIfo&$k8O` zb*@aT{5vMxDU8gZFsx_bxP&6oIe1hdCVN$ZoLMPq^@}^H%{>k7*Bh&sNH<%jPB&Xs z32%pj5m)i^2HasN(Bu6$U-TVC+X2J`AVJQVn7QMVmTX*}1^$309>m4`%$|2m`rZMpfZVL z>KACIL1to^=~zFTXgm~>H&xVZaT?}0m^l)6+N9m&E;1k>0X#bZ65Gl|+>_aoo6XkV z7pbNkd<~aHl#pSGJjTv(igA`L<&m8+qI{J0ugigz{;be%HpQ`e2-+c%!|L7%@1@DH zaH%T|(b;bc%7ocOvKj1sVaqw|HdtI?t3W`fk1j(?Jg#xX+IZ2tu!K=$hdXdq4XS z$ys*3zsUVce|1Co!`;)&bmcLG)2=C`W_e-}ou(P+WVAHt+GdgypRsB*H<>(axteHZ z0{olNc4lQs?w=u1V8UKt;-SF8Z9yKKu^N>jQE2ie&+?}%{nFjc4b!#@m$O!?calB4sXW?R}5k7S}16asH(X=@b=8K5!uD!|0G;U zvKmyj=Co9Brt7%VWcT2+fXrgRV<76_BC=-X1H!NDN=xittpF3tm6k!+33NPZVzjG) zNx*4R`8{fj@%4D#xSPL&mCxDBI#X%#OyoxwR?AZ7lnkF+0qJ2H+ag9 z>n=xbP~G=a5=#GQlw>zw>9(#k-tQW=wYv|D@b29EfOW3v!tvxXQ<e5q)vQvgS{&M0&K<^4vP0p9npy*cn(~SX!_Q zb4N|FY-)p0ggy-AWqc*4%lM+6X_JUvz}rCDGR#pgx0P=YyQYUP-ncah>9#XyvKxLV zM@=S8b)B(V^*}EuRr*P$N(Bo>TK(g0!Qd&0Qny>H`c00!@|Qfc@=8n?`uGyHLrfTh zqv}^@md?MlG){n|9%~??)d1T;W5w3IB{o>VuDuPW>|CK(m29-@J)p-U)YV`CYszWmDuRWo z#dpR=!Z0YwYtVwcA0eioEKD|^h%;a~K)eqO%heC*$;G9AP+fUC6B|niOGCH4^6Rjz zJ-FV4hqFPq_Dq|Qf}J{pk}N`u2K0zk(EcU#NU=~qQyeDVp6I3@2_e!be=JqzOD1^! zgasjSAfJCaa#3KdfthmypzNPWgt7u5UDzC zep>W;#S(LSlJVC?Bo;#p6X~hRrYOU4=D+%W22JppA}h3g2=bapNtMV+=+NWiL;~2O zaA-h6NXplr0#EiEwTSFc>)}r}YKEd$JY{)h5M81|z}b!(552*BHUoFH;%Xs152!aq zsJHn?yKIbLU29&ed2XU==f1oYzxBpwa(Gu7c-P9fL`A;k5-+QqsahABfwgKuSxI-T z%)4fH_5p4iER0N>yi!oeBgL1hvK+b{#%rhY zxRV5&%f8MVj@=G3UuW4e@kiWmQ7pLSRr&xweL$GL7h0d2nK&cl9T>@TwjCc*X9U+_ z53-m%Q5>S`B#=TsZNYp%z7FiWZgEG3)IcZ|NfxMJG;mqYo=_=igMNmqI1( zX%aB+I11g(R2ziM1PcQE6BYndnVaQGQso5pkc0f#axImbtN4iCsKf|@h|>z%T>Q5$ zbnsX>9kOmzeB+4;|6JCv%dTbS&P&3+@paX*kkMo?#B&n627@N}%YA;H#-gjHWiBEb z^_$7G(+bT(Eb6ztX{V|>)nbR=zrJajH$`LB>`%L`QaZ(8)u2whHEB{6>GYllvFKJ- zH9~&f3G>gLS9nCa@VbGYi7i%A0@`{Qgh5NPoIi63|4!uUc6E<~@dUYK&DpUB z*#OFjCcNl_0C*|1^$m_Vu(b5d`xcaSyNb{)yMRJCX?o_4$%8^7_+6lAEaNLyqFB0D z))9O^*pC8&)E_&QZb|cv=6Y#jYT+wEWdc$_wRAQcO zw`lUBN~1Qt2HM!Qj~PXrZNSaZXm34?gFIufgZCOgk zLgrpWih1! z35-iZ1k8rJgCRpHoXL1owwKf7G+w#>j7`v(j&#WB&F1~|0i(a!LQc_!-DDvN0a>i( z_;`ovt}p_brCH3fl%Bpr{1|h*V3ZQmv{BR;ks`gSoR8RkAKXPnO;2Rx5)Q5HAJ!)} zSJ>lhrw6;_Xfk#c$j9ZsFbSuiYjaKmaxNTOCogG%v)N^B2BE(xbFL{xO8i?<61U zBXChZdzpWf2WFf;@OqH2*8j2!=H?BPqqe$s=#bCq`cf>2D>SCk*}iZ~PHyb(FMuHi zam>k#;PG6?klQ$HvX7#m_QNw8S*d~`39 zXJnYStH}`QQMN6$J#Mc!)#ER3nw5z1G|cVQcVoGIfsp+6!+LGI?$7Y0+a~SQEdj@Z zOE^0XY6+<7chAsX?RnohaNNn{`d?jX#mG;KGX3xT-iKr?*%)E=mF$)kC6{EGpOH%U zs>4n&@Y@$y>^CU1DMvac5Sk0J;U7T{p6v-~3{U8jYzPHC-_T@YQ#{^((PD9}Gdl^=t=v4|?(VO!y@OImj1(9GlO zK5#Va5&_c)-9aGL&Ja9mL}b1YZBP+T_-n8MYEZ?gvnah2v*g}v#Rcq(^of#+I2pH# z2Ni2cH6^+NNlU5{rBL}q9>g@W*rMZRJeA5(i4KFVdCK^M#@m4|5V2JSyj*BZlzB1v z%-m!3EXJeKGr#g^epMClv;`16a=Va|2@z%M9L&iR6Uf5{C%aB{hG~tvNogPYiI=1R zJEK}sZrMXxDl7$wa93l+s)q{Ae%os)YLW@UUFi0$OC-06Co84x7kjBbsu%YUFLA$b zeJzi#HOsVwI2Uj1h|NAPa)JpFI4;ZA)@m4`q-0U4SLr1a{CCVO<>LM+Tg?I5lT@HYq$ z5wPgc`L@Q@AM36RqwO>2EP}>YP;EJ!5R>XSwt$VV{rFqc>l4r;JYCtYj2Cy!U4g)s zIddlm{jb0$E3+wF7rV`|KyL{3X}&bA{EH5c#rxoc9H?msI_H936VVxR7^6LGQ{aiz zue%Z9Q}AsuFc7PBIHzEkPoVmP^YNVQY{9f#sAiYo0|80|aae>wHbTiwTw7Ff<0ttI zse}J<9AYO3h5WF=jw>hT3oop{ngaZWAMOi}q`$Ae1PUj^N2IP3_%*@^#PCp&P7r7#E~?jWQ)?i_ zQ(hiDR2Qx|;~4ekpZCpHJFsw8Fpt(Qe~UkVOty$S>hSc%C(}_a8vhYik8vh}=M#5YYn!)~OQ2 zOSRh9{o69&5O?y8G>v+@9?Pf+09&rU+O{AL(kP@bivAD!46?V)bF^{R^pYH8Qc6|F z6t5%@-Rz>~=eS>0y~So}MhtaLwRnJ(3JcYG^RkuoB@ETLVFHwmyB*lThoeGh35dXY*Vh!>{WDZBUwOhUX zOVt^Uy?@;K1*HhSoc{ku)%icQYZCt%*phR0vNE?Z7IAZO0RE%R|KDh9(-Bn#?bEt` zjNJSU0vyF09f?T>?lctR4K%np&tH%x7z`rVy1qziVY9Zw92Y!!UV-q#&He+g6drK1 z_ib9docr$JrB`n+a;7`Hrz1GPkHtE0-^k%9%klcPwa4+QtHbs4?ex1Jxi*Xe-FH|A z@wmT8%fKH&9Cqq``p{x_tl<11;I6bm`a$M_Z|rA}z4^3_qu)b5iWY0hLe$$wC@&O*i5A_vI_O*xKVvqDsKm}drZ@H3%mMv7R#KN z_f+bClPF*fzN=TslHqoxuMyEQj7^ z{b&jR#412|U>)~vx;^lln?kfP4g3l3vnr108E&Ek; zZRmY#ZTS5J=%?@S5Z58M1oWXy(GviWoW46!Wf;6fuBB1(cd#;}Q22 zhbJ*MINUVbyqrIx+E$j6HSQMEXRWhoE_KHXa*hndS0a^+%|L(ohpG)o&9dp6<;r}>n4mPIZF($_Nrmo z`;F*!#na#ETX93y=^;x-D*~5-FICZx#R01ILiw`CxaRo99W!AGH;{~nc>!yT+E$0CUb8sLen zH5M+Ytq1Gp z>ELbc*iqB1%11)#JIN7RfkmU3Y^@X|PZxA%h0BCa!sl8f4ZU<_*IWS|z*FrM2{ zZ>~-dTvcZkmuaug2p|sHQP0?4OojWi0#I$Lj!~U9e8i~=|3&bAr==`hNz?rT8R7M< z{<%ZsrX@d$Rg61^S`a62%x2s%{J0JmgQx|jTIdG0H2?;4MQ$ZudyiPUA&7PN>43I_ zU3Mk_)z0JenWYicEPab#go2CEuroIM;3G>>dUYR)--zuJ7nI#j)qNBE*+Rxi6Jy?fgoQ(OF%*XE;82hSoh{5saOAFxwyHIL> zRz93ljD77}QP&7=7(-}hP6!I>nXFfH@kt5r{a3=yuAtV0{Sr=B{J(4k|1$x}{AUU1 zU;p;a4S`ldwzdvN<~BelW5@qWLe*;Kc3Nuaf2S9`6O1REFE}3^Q8+w}#_ZA7C2)=9 zs!g0zxXZ`p6S^rGnu)a>a*cRgz+{wQi;0Ziq;zWl5B#j8BTqF)D z2ofcG2n(`;Nw!cJP7@v>Vjkh!*DC%qHk0#JuKCY&>IWu-dA zhPL#+2It=U(Xo9;>I=27$1EXsBMv|myFnII8m7&JvTl&)HeY>@$*uotIc#N`ufN(g zU{Y?B4Ba4^lFbqdMca`?gFPBcp|=xtjkPn{Wj=f?#wIh_Z2B;^~4+z*QO7V%^> zj>%XhqDiKUiDI<17^FpfEP|}w3sY&PP+C@Z;dJe1hAY2|v(}(c{ASf<_H4A=@ICX> zN}K^v!#EKM2Y(#dLN0+AzkjZVpZaUrhnyVIW|7yffZ-vM7U zZ!s=W+X6J2CGj%sJjoN|a~6#vivwldEF{|k;6l>d^&n{`Ss?}?s~u|08yaDUkDdmt z$;E2>ePjhZ1xx&pXIKNr_bwdfI9fN^cYyP%^+ilHr>jBZ`A0 zzqFZ_LZt^=-ktugjNGctE-KTa9q@?RN1vphr7MP>Wh+x~fI6^_4&uX#T|D#B^eUNg zpyXZ7)`%%1Yxyu0S4eunVi1MSPsZZVQVG)x#l&gLc|r9%@t?@5JV697iz}P&9ry@! zFg$9_Z`E@^mWh$#bVtW=JPxG+6CmT^A_-LI(@*=!Y0Y(qJMpGzCwf)Ma;)W@zgP(; zVY?DW2I~IPSbWs^$tWJM>Cp6pH%!`5L}XNQQYZVZ;_AM*VuEX%NCQ6RUg+%xoTT|S zFps0aCOkf(&6grPKC(-E_gGkiQ)vXNch90M&+P{*yBIVoHEDc#YbK6EWse}l&#eO9 zJ>|jW-8rI#@+6X=!_TGMItLrhrYYLwXU6dluaMOWvzgI(SSr#%=L<9L1L;tAYF>lX zS6z)!-+lvOCd`T2tX<9)Ai||t!ie84xjXb?=X|!3#j;V!;>P7P?^UPflyj9O!qw3& z!LZdyCm3ns@1J8aG_wi#YRK(iM5cdW`yFCPdmt1#V=`#Me1uLlC-$|2+yT)3&vm(C zvtfm1LxJKuf5h*{vtvxE20Wal$dZqXE^O^CKSTbQ@3hIS$!UvObN3tSa9f<9lqV|b zwDV!75|9<~K=Po=Z2i2j+Xy>|e)HN0<5tr7i*x1Z0Pg>*6a|ATiyxWAJ-&Q#g9Wl1jBYDK%2D9m@16X8U!m)#|GZi=i zIxnZ#!7Wpic-iz`=AyfoE4#41(fh8yp&2876v{`n&y=wgwvM)-!)`9R(WBD zsz+?|=TFSL{+)ph)%#i4{5yR)Ty{$+bVE#^pZ@4_RAiI4&JP+oj2cvd?uRxg?~lBv zW5+UlmwGV0@M9roWu3))|I}|_1(H9N;W+tf^K6&u^5k0NlesXEKtUDAepEmJ;5>fz zt{STlXhGmUUAR(H0N%4>P;>ss{tj0q0>CJc5mk^0{}g;Ceeer<_)(?|o)ke{T%cKg zlN8~ns8GCUI`@s%16|7a9nqy)9@#?iSG7E7cJPHnLnKHCbUj?I4q|O( zbvvHN&wOY~G|*t;GWi!+k$(co+Xve99=c|D?gCS%Wb7{HgUm<5)?iH|PG?E= z!1_a300=@^1iC-xVH;*80JDzd3WiGQk1=Wv%g5zLJxh=kYY%{I5#2lcnyDOXK^#^m4sm!xP97B&8rBNs zShZiZ9(LDsrXXyYcvl5X+2DO%Qv9|JiA&K*3itCc*Q{UiBJ(BQF zuc({hS0)suf>oz31%|?H{Y6~oRi{GK(+4Yx;ZrUfrv*Cu!tOL1nNj;3rgbyglJzJq z2TlFPQSKr-mvXY< zC+}->35Kv4J&qZHrWqfGB5ul@j`%#7)0|*cvB-*aWLpCpw*e*EuQCz zR9t*_6fI{xI_np>zcxmPaf`I&08qt6VrnO~hqi-Wru)-)wR*`yMPb>n0Ygz_wb!$| zIHEq@^{?q)(UU=|txq1euzW7OV2+o}{KQMm2b>tD#c^bJbVL@`*!??Z>5w%}ZiYQh zAvjLa8Ip-vVw^r2&c0a`>iy7<Jn?yvt^Il+*>~#_=a1`x zF+Gr3u4gV+{dWlKF5g`7T|5KUQ8r@i5a3F>R$o!d0Y2+q#qMn14a+@TP<-KO4`!m* zKEJpODCmVa!lj+BN$=cf|Bl;G|IeVM5YWL0Xd~imW$d72Ze!|f1#~cXau;zkG`9P1 zCOt(ROVlru-a?TCs-jk9^&iFa5upVrs9O;V(7PTUN@;H9Y4Z2v>=eB(7oDNp6#aFSR9WAT3W6_H-@88=z;dyDG}=Qg?`Dz zs*$aB*8`^1;@_P}t@>X0CX0#|kIwlE! zD;`vYr2aO(Xpv=&0$q|PD%@*TzOF`)f(^~p39Bfi`ZE50vQTJ3tOiE<^dM-^bp@5u zwSe`>Oe>aR8zAI!{*zZlM7w;4dYQU4gv}?Di98zi+pC-1&z$PKfOD|RPhSuJDJ7Xx z3JJcwZgY5uai^;KhscjBy-}sg=t+aQnX&B{19CeYsb~++%B{7U78mW(hHdj^7Z01R z&5JA84IbWd7B8+?kBb2qZb$2MmhGA-yc!tE!-`hAwd!|`gv?s7DBiya@T_*Vzb^%9zR<59! zEZ48n4LA7zgxB+%Oy}wsZD#&&8)Pc~XW=Dl>m=~Mt)DVLCkJ!4|4(R5*q{m^Rmonc zGr_>XTr0K4Lq#F&8G%QDi9;G9A?Xo|Sj1*-hMTxnt!kjP-b&aB?Day~?eM(73fH)2 zfe;NEx3{aPR3sejr#=&cXb%L_AK5ntI^t(hRH>rizsC=b2RromhW>npnefc7LP<3r z>`r;Qxmh@VZE=aLwOdH0-y{aK0-%{#0LGb-b@`OaKv>yVXOa=s5{W<3*;yQc`l}sk zfTwvLEWBGd_MC}H01jceOxF~0eiJ6SpgMM|Vu&+S%1c!~>aximvZeTD51|&7EBfy3 zHL4K`ti)|`{F(;`GQG@r;piZ|(3&?23db#hL&Vj~Rcs?~zX2Qic@9r_5bmdP+-#16 zG>+{bOdXib()<|JtG1HSVZwQB>p>}X;Z(+t9ub(9&oArUUH5ZB-FCEwj(EBc_YTU@ z11@M#q*;Eoqd*In6Iz#z;5i^awYwfi*VNMU82@A{sYAKJag7()2W|dTjz6d@Uqp9z&2S z7NmIIuSj01x|LLFg?)8s3bII3pn6&DR-tLR-y2Mo*#k0?G$8nbD(*=cZmoIiNd*|UGq*Gfh@+LiA|0US>4t*iS zTs->%Jl9q`G*{RY=f3a`?MBT##azEQICp4<;3ywVVyxQOzo7R6&(yMlT*JltQph6G ze&cEu^i{(@KHD-g=UxMR{-Pf9{gFL8}wG6D^C27SGQHjzF zF>%GX0c^rIi_+1upfyre;E4~u8U4vy#3Y-#W2Yk(=^)eDy)T*{jvbKSpba)6*(xg! z`Sm~sFQU|u+-hLP9k^0aQNM+iyl0=DLNJwOI>xU_65ATmy7DX3Sf>|S=ob}p6#bw; zV1f-Lo}2>7R*3$HK>gKyQ5(}(`5@`fNvn#})y>m8eRVc|aFRe4AZI+ei41q2S%!l0 zi+9uDIJPozg%PO}u>+Y7gQ>qn^IqfRWS;6$oU=*<#F5!oHZ=ZsmR-uM65*nd0+(!BTH61%8qZmoSwi6h$8A5(w91?}zY|uyNVcMH>8f9fE|% z*6{U#AMlDp(RPSenzRn3ctqj9c_dQFLh7Q*jLGCe7kCDUtr0C9X>D6*bH`~v>+L*P z0%w}>6GKQD1VlS8y+R>3qH)!_w zvWg_L`Yw0npChq`(!!u_^87-Dv-$_%ozqj4kYjfm!?+hC-Ox%G3MKM6DucsDZd&~) zgaP3!V8bGS;8GDlU?OpjNMcw67V1q_*zqmcBkCyz8S?Q>LD;>U#NdRR$Y7Ge!nT2p&fd`y)1CPJ%XU@BwGj$Km2bi&3G} zv!jJe%eE~n%gZ`vcM8G>#7`%)2#YTI141(dCkW3#9fU4?YaM}*5?W^<&q84Sb99*1 z;>?p4&1Q~eB;jp|3jUmMCogaieT!$Y4Re!U_YeG(ltFU^#(_hI>o}9dZe_I?tkBZl zWl>I9vbl9pDHk#fHH8sN&7b>U*?LlGwn+5BX3zJj5`R^XpFBNGlq`AVs)Sr+xj!+@-274YYMe69AGUQVvh%-oOZyp#4XDxBFWO`--gWBKle&f)D_YC!g75LlXv0d=l4ZvQ>xX=gOJ+E z-#)AbyD-km!&m=#Z!obVm8aBRZNrq000##F_qWWk5yfNM4sD z%EX0f&Ds-3To+>I=M4+>4i9nRh*rl?8{-Yb@jg!4yagtUd`}wAHCoBHh~z(x<}H^{ z@VHGduVG{<(ZV6pJhT`;2dCz~cg~fgPZfB9BUkI5Q&!BtCX2zjE|>2V@6&08BA8q~${yT*udeh)zamMS*$+#vGdNDA{mfoeFQq=j7`?RgWWaMtWsvsMzDeGQ z1|#AURh`BEJXVcsIVZGmlu7&W%R1x=W*Lc>PbG<;apOf*+sGk1pn5=wL0)GAdu}S% zj_N*mhwJd%LTR)epM6~y{|AKO9eL@3qOmr2Zpudh@g2SEf&;#O+y0B_@F+>d(~=om z^Ao*Ohs)R%Lj`wAq{uM8+BueewZ?m&wRp44y1Q1riw$g_WXJnK9^6U@x(3Wd1$1|B z!V~B%2~^U4Zlxq}kFgUX8brForO2lt0$HLDo!Xk0&_5CW$#T|G=2mK7M6D$Hzsqu3 z|5=v%pOr#VL0e}VBcOx3yo0U9zxsOpuiBwHoD-f3_TQ^3D-&0j1gm+Q(VzLsVB}Pn zDav4*56P@B;0x^a)_EfSV^?ujo0Eg9t0{hf!5buGci2TR%^?u5X7R)naY{&+X68tFHHxk>~H<5rp<4@$Sdas9~fUQhE{uLh7MCM1gj|>X5hrxWq#ymUD)gqhh zwI;SnwZrn6=6AiB$%c^POMA>!iFO=!Kd0~BVIZ~YQ~lePdHzbK<{cYmjUuRR4*iW7 zQp5_gF0k*nA-~zecKu;OUZ;3hL@AvIW#l2BGcjX%MQ#on6h2sGCRxc#Eq=m1P<$ zO|n`RvcX!y^Nae#Pnni3tQ|j0)8HK8XT<2wX4^5sNn(M+Y8 zM6{;%8LDAVPYlxVR+tY}x8{#LPRk1wS)*5LsU;Wc^FRqwT7v{h&sysdWYT;OsSlUE zzQlI^(BL}LPMct7jdq!|tDo zIl=2e8R=DFoPHaVB$9zsubTAz?o9z7ypF+^OsW3<_=Ddy^F!0@TDh_$XZJ#}4kwb1 z#c4!XGrlvMtzW!i-%XOXfg=A*b5pY$UQ6tgE~yu0-~_1dCi!G4&>r=7QAYwXpJ3@c_#7uD1~XLc^h+@hT=H>O;q?IJ1Aj89A% z$(m)aT?9KR6$nP*L*1xenz9P)%#}GTLlI3NJh!3?Y#CWx9*IVK)x)WFSQu)=HS>^L zgBD<$f{hVfD7PCr-Phr7_9Tdj8P`AOcJ9I{K#~qRlTo^~j;44;&ojH=o2wFKQ#|Gx zpz3O@Fj@2Kv=C$FUCXLYe#Dn}H`-X&jMV``AJ?Z^o0AD9#1Moy-aB}wxX%RY)1F)6 zO}Dw|O-~75ABRQkbAS560Joh0%w(X697!L~tqlCjIbf!1oeZuPs_Quvz4PPJHdyc8 z;M$kq4E`7J)fYPvEVs)(^mIxn9EyYD=?c|c)3Gr-TP+uDc=b^b&=X|?NZG!xoc{Uj z9DyPqlEdCuM?bEPbF-OaM606=?W&@_&_R^mK1ZX}>sFKzAP5<|a*lo<7{$mcE20|i zCOm9=OS$>!NCw32889R!NWBHmLAyYXJGz*+`a0k%`BQ(B3+Z1wmB1p2VTlGr z6;Awg^tLPtXK#0&|DhmI>%c5zF9YZ3^SQ!Lf<|YnQOE6|Y2-X$Ze3kTlK$r;eoQM` z$>~qd$dXgRiNuS!yX--@azZmJ_Az4cWSLiw+Gu~{G{&Yvx^~R_Hwr&z{Kg^9+ zk!>*0<(_9f!3y!0M9T|&z#Yqd=rlH)oJ66UBWT0a$^*9xFWo(@gCBRK*c?5 zEfUlAgg690cN@;JO&Z0tDECBn+H+bfx2!v!MUxN9IxfdZj#$=S8)x@W_ruA38LF3) zdpy>PhJ2q0u`0_T8Lib^)U~q%@aw)pD|(3UP+fb%PXDm=_X#sed>&|yN({eJdv?|z zjSl+kOs9nD1lrQbI05Ubli+lq3F-T#wWDCQ1IQMYME8r} zrRv~oExqh9>6XLx%MPS+e$w$twc^fWP;WL5gPlRpM6IUUcHiig2Y27??E z3-N~ys1d)(Mq<9$6x`R3yQ6jhBoejGZx%;J<5E{<@k`&`(~q~~MtEF=3}G~kR=jvQ zkiQ!<^Tt?$x(&9IVEl>7u}`H1(2q=A6D-~jlB9r@!R-fHCZPnsuW^J$+&Be)c)M|8 z(QZH!()q9)-Q_^T)7*Ai^F`K%mv}(gpAM(gw_Jf%42nMsm6E!3DnZIKInDLZ5 zCG9{QWnm%Tz@qTvap+Y`f~DU0)7Otp{}A#IvgqD&_d5>o8TcW!xe++Kp>Ko46qx;h zT|v!{MVSI==?`2-?!`yjaW(jUMI5jy8Sjn=@y_lQoe~2?g0T`q;jtsX8fsw*qAA}9 z18xMon=dmy0>pjSZ=gkQu)1Ph=bm){F|jw`G=quKeM%RMfGM0?TFW7N7v>zpF1H+= z2+Y-Fw{YwJi7LXHxCK2!61VKj{>%&X&LNk5>nE5k`*61zm7vXEiXRgyA-)}GfTN7? zXC22||4JCbJ6c18q!m*`NZJ0eBo&UmI48Ogr8-DUqImR6&R`3l@n59fl7)QrceM3) z%5LU=(mA8uenrWn?K+iFQot8_cZ|Hrl6&$XiBM_Sk(mExjJ{}vH=R9ksy`BRDu5I4 z8Z`M4<4kE3EIs_&yotC(zMew7Ij!@Suf3e%C*LYWc4N{kT-%x`^*+Qhe4za6Nw8il zK?cRHN;B4WUIrnYHnTJi`dA{bQ8)yH`yNQqN!g8k36?QVMKuNOuzX&@4k?0oYrBN;|Q)rIF7=a20Mm>;9DQZvx|+q77grH+A3^ApkYn} z(FzhAGeX6-QtAeV$%T*VVdjW<<#3M5GWax;QZe)UOzb%zPRJLPU_UyoDg# zn6wNfB0{4optT*LsZd5nq_4FY(cJy#!d zI-SLJ`(vg_4YX=xTO}yIQj}yE4NpbkR5eDW5PzRqb$=f=rt)SVb?-cpx`~%ak^&8Y z-75ho-Z4iP@RIB+RiW)O1$&{Dg}8y2jjWlWdg+WXehG+Rc_|2BD2LwFKxccYN6JNa z(^I%nA$rY-@W?{lpLv)4z`bMetJzNqu!WY%LEM4xQW|Qxv4+@IxY2>wHY{_gHy@a1 zkqGp6W_qzUG#eb{WFOeeA$dz97~?YGo;O^R#eIy)6vEyd(^%|a&zLfbDk`Ly7u~=g z%yUkhj3{wlXNM-{f-hVNCMs8tk*sBNv1BvThNzp5Pxq1VE-@{zXY)l`z;@5blSRT) z;9xK=l-Y2V7@Dw{m{87RUvFDti)tChe|v@zsb8ip2QeRJNvNY6I_s;oVsF|nY&qps zB{e}Vso!^T7D{c5{2g)FbkH`@#2{5PG;sSj&JUtHY*{rYOT+$wgDzrH=86WuJw@SX|~l#p8TpQ&tfht zoPUl`FCRC1Jw|noL3X@^yBSl9ETRbpY}OQ3dDz1g6R%7!`VsXE#6dX4QmJ`)_53s$ zR&(+&W%hImlW2}fk@$9CBP1_y1mb2|(4PmT+3-}t^a>mxV@f`7)Q^o3S`7_ll7j>b zC70B=!Tj=ZZk%5%ECSm?W&7aairqzKtk5u(bhA=E59m0EZd0?r{yYbdW1=&|HHVd% zb4s~09?#9y7+v0=Yu==Cz{m^_(@!MUaK;TsQ>eN=LS1K`EgWv( zqA|Z<9Xd3)jS>M+IxXFRe*6?-S!UYckWmOVKHU$XKtLoe*bQyX+ZB6Z8hBDvQbOSG zi^TDXh{SoDt=Tng9i3H)2^8y_Vbkt64v7}QAHmV>XTVyE9Ax=P{WBCY#ic{3)Nr7&%shR@s4+LDrU zFVZtnKc^Q1S>2c0^!X5P9j&GOGI(HWYB11!@+u0htqBc)X=BpWWrtu|t|sN?8HK!w zCgT}J`V}j>cG=`66 z+h#N*R^e(2S=?xulKZ6wyUR|tK)DRuD=ygWRxav`NQ_>n7iVmZV=dJqm4=ffx$;p$ zj~I3=gj;*>5QEf=*`RT^*FGWGymc5MprY#YqzIJ^j`aC<`#lzQw^mV3fuO4q=u?F< ztj5F7M$N{2^^f1`X|mO*7`4W;>9Oh-Lj zG^lSj2zD_7fRIN)W=!hIpG!s>Vqpvi5N<40fd@epZtXyhSn9ASicjlSzyejtE6kz*(-)>&>Y*wr zj4vTT%p}haG1!oYyR0j5JmZ9dOu-geM|sUZ+x?@m3}p={v;dxjd-KdLm&YxtcP2v% z8)>@GJ}v=XR&+?Fxxg)(FprmF}Q-f_60IUIN;tzmosGjJO^CBTMgrLPJhd=sMzP@I;gKbURfDV%IdIY5#_t6V+?G@zv{U6RT!Xa}XXwz3i&Jo0Y9J!rbFQm^s zp@c)0!FeFwkj;gEMB)LNJ@wbb`(|r~+plII_JE(oKi0x?yjSEVe--2Qk#PRhl7aW+ zae{-oE!#-fa;Tv;8e>CM;0}t71HRrM0z@5EfiPRWV)=c{W)rM z2T~b^r}JP)?6*j63T%gsda~LWg!@KdgZ@ORP&{aB?!lwm_j4j2E1wvQiuwACT5Hdf zo__$Burm4KEi?!SB;mgUT>sa0hJOH;^p}%?^q&u92cV6k$=8s9|Dq(P)LxZvpV2=r zh|S|0>GgR`?B^k&Favv$!7>+!hQTbXV$didOMf*aVAM4isi@KzeoZJueCAuAk=blK zjo&KI%pl2^*!Vl2{y~v_8vCc3CA<5133!2{CjL~EG3R;x{`7wJ+_m-otaS|ny<5Y# zxLbgEDb6U)EY4JmRfG+=42*_X`W{FdD8)y+UvIi&tEQ)-2be3;ABr@+sS1#LlMj@m za+?n2b<634qy1}M!dJM{z-RV?7f1uoH)GMg!*#`bQ?t4|fD_w2`oX~TQctMYr-tq| z6-w@v&9!|K|J69{k?yE#bY~sDdw{UJa>o<4n<1Z?o1Z}d$HW4t8-)o@x8o%~3l;)S zL3$Jvw$Ei!B5f)k&|<9qp?OT&+OIkpC(mM25;bPUY_QVcK`QY7u=b8ol6GIVZ>4S9 zwr$&1rL9W4GAoTp+qP|Iq;1=kW>wS zQ(bBDtYz$gf8mHe9S5e<^Qo%3lr<_PJ1GxPtQtz7c$yw9k}EaBz(=^a;O#mFEm>_g zFKZqov!!zmJAy!G&HW@hJ1U80F*&OyV!0Lxp|jVo*Mum26Qd8nwFZ(q!#D_JD^^Ks z+tG;pMN3Kl0jcY81{qaOSccw@?DJK}{Jf?6GubsC z+M*nhV56OgEQF+;ReIXfa?(@Qqk(hHuljIO%dV|qoTr#OW7!^fxXr3|yDKwZldX74 zQ;5H?*}7RHC&5ts*yqkT%PW^wRa9zcgzjVG%wnqix8t%d*_hq5q)cRLkpgBW<$6=# zwEO}i>E!*i%2)QY-L%!RA)Y~_I*;Vag>Prr`aDgZlhn9Qm18Nzeq<^sCvMjR)~5?4 zkyy_f2I!%VL1#V`q}F0xgiofq>b(>c=v?n=(}F$b%ui#Q-m;kOFf*X--~w}de5Wsw zzN+&HyD|KM5OGANu^NWqb0f&O{dw!w{keuvx zSN#x_p`HM%%~P+ct|vJa$YpB&yNt!=4qPHy#4U{7Dp4)*1W0)zSz-xPjE>F9%_hvq!pY9a ziJR?x@Ayk(V?CVRGg0GeY3(nF!2i0_3GjphB3K%d`*3q8^{Yv}=Fo7LS{Uu1|@=vG>btv5beO1PKdBNB{mRc(?Jt8QM;$THVP{kVL5 z%9boFR-3HpJ6`AwDm<36ThICEI=U^q#$>VeCiqkpMW_i{jaGcd?R3}+2;3I`gzbe) zLeUAgk;RI6ZKeYaynM-HV~?FZ2%n)Z^8=XvSZyj*j*De@pimKLhoN&f!Sc*@L{|Jf zHVmQ5qp5U)V!x*42bt=H4SC5hQcK~uhOE%qL%^SZs}6~em4uDiG&w}l4+{W0H@x&d zqjh&Iu-HRb)a;JwaJ%$>jvXij3EHwV^8d!zPH3nz2z3Z~nfz?p`$mj=6gEpA0KIiL zh@FDR!XOk>dPu4LgAEXWDMNk9M>yy#teizAqnuStE8?898MH5dM9!^cDB|4mhE2LI zk-+g#%Ep>X&;`(C38?!G`6S;|YkW-uiuBOVRc{%%pQs1Z#?B?8GzIyDQe%>$SBGv< zUHE}(U4~kJMTwVW+;+tIa_GJ|9wvb=6&&zum>ZHM8s)3K=7u{gHHt?x#Y00{QH%`~ z7caFcp)ELiEsem%(#b|mwJ6f`-C0NQ;5^+c|u@EenQ=zksy5|_VSJd8xL@~ z<)Squ0;(iicEHIOORBLSkv<0fHE{()((&6?u!8fs6>&g#zJnwL*ckqi{#oLs$CO}J z*aQIMQmfC!Q@JWo$L|MurA}_cD?K92O7v+>dXixnS+1$?iyE3nQNF?NsxbMrgk)m=eu!#NbJspJRm^#yhNf&F;L zyndvDvgbRuOr=5~Z}u@1{iXc%w#sAt~@1fmela;4z$7 zR>Y+&rr<(Hud3{~yvhd7pA5L2GJ=8|ENjHD9TEJT1DK}j{NK9HZr<8qUkGn!#)zCO zpeV0D)!8v>QIsKlKl%$OA=ZUhi52^~B~cBEr2S*SznKB8R!fu%zXn5hvHvS&@ZZK6 z|Dz24SNr8(a-ds7M+r^k%Yma;VvY~ujE8|$HKCk>;*_7)hJi}Ph$0c8H0VkXmW{(I zZ;%rc&Z>=f7rz0SU0bbMeCzV5$9_k$5@MnD}Ve z>(m#Z_6?4m=fN0%M<($X?tqr%?_@5|Nh%e1Sv@C?eZ4p+Vi1q@LWVUI{!4@&n2EOR zI^;KE4aUi`ktAM<`H9zQm^~@;;_>0CwyAj)iEVdwLA!5!G#+ymq#^J#1R>_(qR*(R zAvqL9aNTmFzC}VITS=YR5U#ftAXBFnA%w^0Au^8ngs}pvaMTLR7_y1UYO;yV3l9mC zlIEGET}$dO!HZ!_su@2JD;6c+Mai1u-fGdZJ_I~Hw|2p}+Z3ISpLe4!Ac;upXtg&* z0mxw2W=AuRS6=Ehi}uwHw#g_uhhPiC&R^xa`tXuu_fT@qFNMUj5xV1V47Z zwaSbVO#i^r+WU^n=JX1)n-58(#1eL*AJO_CjZP?hvfz#{nWF~vMwnl6Z%8PWe9coX zP~z(tKkRJ5Mb23{af6tm8_LB#COv%t=f-6A?SZ$VK~mF^0s z02@zF0TZH*ZbVr-_G?T&%WHuXy&plJ2AVbsxvd*r7n$`hBMa3Ct;EeS$ zG^g?otb^+j!!b;%4h zz;!_S4kC!rr}EMi_Y&e`lOGjnGurQ9^ z9x&`v83RJLX{i}z`u?7!z2&&-N2UIpQSZM1K+;6QcHU^H)?SQ!(#&Py{yqXlD!Evd zc{cCfn5t~BMhS8KM;qxVZNW}rYS}EH^(z9RgKP+$3pgNYmWa|?lq>4}TaYdvIRjFR z4F{ktP=Zq3(mL#2!I!W#P@qUMn~JG#JW`-Eo1qGv@*hO)s*E3?!O0Lc?lT}T@1sP@Hj5bvN$~jqfRH+p`}Ja69}*r zq^^Gj@0f-D*3L?>tZx!Y`>Rd8|Mc*~j8+tu$D%20y2%uU%|U$7^>`OWRn`@jJq^s6 z&2E)41h$2$uw}{7p#c?Bty&N_W-Zi{h2+dLuzsn`;@hJpk+zthrX{go*xH7pq`ed< z!=5{9r3sBF>}z*P_PNUX{yeMJc9FeAMP_xd{H>nKMzkXbDVtk9TC_s>F!^D93Qdyy z_t_zmUy?^@TqZIE*@|0y(y8h^l!4$eDz4bCXx8t#h`3Y4?el-6?X9OHx5>4j+n2>A zb16i&oDG8FFD_{}*dp2&LtESFD<76n840{cBSXo?2pd_}8(A!P98@xOD9FFrsO}_B zK3CJ>4OP}V#e~)_L^ag5+ng%QmEjl>v7o{vR<4+9YNy7aRk^IiS*m!4CX1kx2SN;*9IL_-QS- z+czRGe3+j0D(;$m4c*-WEs2eDmi%}EF*$7h_({@at6}Q($a`0_vMX)Na>QVj2mnNd zK|NR`jMC%bP}^Wz$JpYp#i@uu6VQ^2*`wP!*-lCwtl-_dXQ@J zv-u?%V06Gk(A)2iSt*ayC3@D%>mRmrQFjAH5HOU>{-y&oy6FP+l9nGh&cAJ$|A~#( zZdb`a$bCr-4WMh9`oSA%_BnS8`ef^=a`IHr#xS`$VDB6S$+C6NAwwHm^CL-1OE9_e zz@+$Wy!Or&L-`e!%2HE?qxhmi7z6f|XCD2`rUscIh1jU_n1+2)(jYD6gUO@o1aX3| zrt{ZIiiJ~@i~;le4>flqR!vJ$ive@$)FRv?9x*%=ABM=Up9cUV7K^6DKx%fg*)ZFR@GMD5QxO9Ry2pt;V_f4 z7D2K(8;4c`?=BMWLd8rarfV$SjkRn71%#OB{t`{B8&>QY^WLWX{;@Frr;QdnnbAT?YEzE} z{_1gy3AHxY5#Y&KYu2SEA4Eh-S?tp|i{oq3P?l~}zw|1@C98nvZx=Z@hB^m}<4k;` zOajNrwPj#~&>Uk7+ol?Rg}TGMq0xzh`xQlXjjOJsyV~Yk$)o1WkCf@G=Ca-Ga51)> zV#>IB)R=d$r#x*^HColTV?yeP(&1B%U-7#e$~&9=^qDKZqu;mC&65lRZa(q<9_X5N zUDfGIe-s(wyzQ;_eGkLgYw4sl#bYCJqE9JA{5e2cHDKevQg;%FD%2gM5NepPrQOHgD@I75nfiY#vbYwBQU$cXXw zggeDB%0;ch4VexdD^&}AaK?x*03c%_kq(h;a z7)%K0o`fW}1Es{)3-MQ(JDP{Vl={2^e^@^R1-%t@e~RP~!COkDz)2tjJfpS_2~M;p zk_CSW;{m~R4?1X28+}~C6tk3BcL_Vi6~g70?l80=M`WP@x8+KdhXz8im^sgH%BzP$ zynAGe%k-vU%=PlrZb7@FM`vU#-tlIaWgYJ6dP_#B6P~9DewOQQyQ$v1X*a$LSZypFgZ{3!)Da5Ph+IkZite7j z*mgyp2R1O+S7e9mrksSuCVAE5j2iIxbA*KSH2ddVihis_|K^tGV>LCb&GZVh zcI!g4BpLBpr3(KRl?!+Vxg+)P}{f`N; zbmRmRbh7CHl51?(&LBfvlQZTNh;9tVzWReuMA+TTyn|yHoQ{E87W^`SWC6OYt_P=M z6JW042f}`VI>Wi~%vdK2{dK~RrhVb)Bi;+gTv9%uoXT#TD!O!PL0^$-)33HD=ZJ|l z7mPcV(NS(L3={?oRLo=zRQPS#W4mgmQ$O%#jbJ(3=8$#Kot6s+@qX;_4)s^)@i1_= z-wKQ+`YwsTXDELqx-IJ%oSo@ z2V~ar!lJB}=(Uf;*w~T^)JDktZ^l*l!!U#;9&^}=m+LW!l1_Jw^zn+!*Wbp|W%3na z&JN&|vb~MJ-wmi`hX5k?Nh&lhg2Nd1LnO(aD8Ivv)SCn~5$UBD_YuH1lc4V^YCdk! z`+6K;!#4t=^KgBXqg1@jncm%zE-v5U&!MoZkXQ)_M;JVl=m-a0JVhA>6BYR{i>^~# zj*6oh6uP(xae_BTZz^Ntn;g75g|o+86VYi@5Ip$~=A$HRV$f0re|RHaf3J++X_OzE zpgu`Hbm!R~#`SBfZc@ zs$goFF*3~_lU=kYd6s+z>y9C~>suQ-<;arHO+&s6p~LjN&oJr(^G|R6Dtc*`AMV>X zH>&?rr~l_@rT=zP!#@@DzXvO^ij&J5dwWSc{)dmDT6IEpQ21+xPRk@(_u_8|tbsa~ z;!<%j^`i#0TRt>n>DjDgLNs}KfzgpE3H1wzf0AdZpfjE&%QMGGjtkTMpQi`V?*tQI zqbB2`hzpPw^hGST->3Wdf9W_9=3cVf`oJ%R!t&|sLzmLE7y24Opgc=#ZXFVo`{IPH z=s)4l*vp~ZyvR1cenE%oJBQ;c+XC^laOR7X)k5VJnkfdQ2NBE~Pg>19Np%U$VG)j? zuhoNV078lBZ5NX8nqr&!M6|UGVvwDL;H*_%q>IE0+V)qi&e&I z^6afD|a*`zhOdP}yYbtV$iGv(y-nTM0 z#_ZKTR4{CtVzVfto%x;oj4G&2r;$H{Yygj7k{>v+~*=*|t~SZhmCMOULT{Uv-W zN}9~#t?#$r2C*UTC}FYxeq{mE2_F+)wkX}<*_ym%mPj}KS)Gy2t(P(*?7R9Pt{4)S z(_)U`Ujy~h8HiC%g@~ESy#D81Ac0Oxj{h2Y%KE=%-~RKv@ZW}k{^xh$KSH)DKv|H3 z={{lrK`!7}HTH|uZMRVR;c!aGY*Ulcl<_j^U0)enH;9kSq(MHNrw*`@e?C60k-nKe zkcy+21bRBoB=5WB>k#W?Co`(1STx`h97(`FXnkdD!6w?Top8p?Vx(=*l6fW2TB^3t zS39fA<|@&c>NV6l4CPYZX=To9-8#{K3)~*TuEEsh1v2ItanH}2HSyu=cm=L8C7B^( zb99vw2Jhlph3*K`Z7QyEn+;7+{HFTnSwW@LICgwld~m;>*Z+5YEAc-u0sV`r$NHa; z*Y;{?TIl``+iO*_{RPz3(nj*2#>1^&9COOqf}c#(Y3rIRW-zvim+p-sX#gVL>V=Qc z57@u?eMyQNj$c<$=MPz#<}eA`;AzI!?aw)X`DX-9wi`18KHh&LeG}7;*t39FW09vz z>t}%2YOCHwyrK;^=8W{=_s!*VQJJI*KL8Q>!GGt4j)Z~VkG1)lP+eQ#IrQ5UB74^B z1;*!OjaJ+kT3m86@(chAjyA>pt0$wKEXm@a7>=iEUrj)^SJHOWUp%2gO5nl6~%YJyf%U;Q&yEvW;i@9fw z0->;|z9{8y>5e)0tU*)evzk)NjYvya6TI^HhCqOvhI80X2(J~d z)HB{x-IjvZWc=mFcAZy};)2Np?>x9!K*fRA#1B}?;w9q!zQL-#H<8A_9yYGABF`X~ z27D{F^C0-%=9(pL1BVyO?cIk6cMjk~tq-4B1zekW!$Faxm>OBatgvdsYQEK^As~Ua zf9dPs^-Xpc9!xgaQX*MtY3cnR`Z2keNt-7hVj@w@)VcEpo$Dz|>%H8Yto>qBUA{y6Vq%B(A5c>hl&5Y<+8Cv!u!O0@#~+ z|6CP_)j^Ouxw_mwt!xM{q}s@(Ad3jb)EaYP@pHGurBv)LUdJ$oI%}@4})fnl+B`WR);Y zJA9F@lhCq?ERh~1{{dZRog)(j0(N;tZJ|F!$w0cqltOfOQ4#l8w<+YReGbsQ%gu`x z2vt+!R<$1E{$%dzlRYVsD{5`63>sG=U8A6q^<0xoqnU(bl>UL5p9;+HoRJ6fe)UKpqt{)%2LulhD!5V<(0C z&5lN~_!o3Fo^F5iBKP9TA`}hwO1bo3&C)J*wj;NOUDfO}A3)-9+N1Pr)twmzEOc|r z^(F>4P49I*Tv60UH3^Cab_d5=Eu{KsTn2!`=^yX|=4C_3y)Gq#03S&t9U zZfE360cTD(g)IS40C&=!(AH0RNBds6aovKS0%CkA&hT_ezfKS=NzUXHP1KLeWB#n1 zeuK1<;2M#(LSC^J6nDv1)gFQCR?st!&QVW$?X;K=Ap2sU6X(c5h0W*ZbKrmF>XP{N zmMVV=XZnk*8~`B+1bP63N>F-OMF4ET{4kDGonQ1S75@{-{4f=@ZtO@U50TxdR}&&* zYQVX~BYksLvUEiN2GFRL_ls~1E7~`)V40TmJLX?`0h(m|+MHj6Yux`Uit0ZfYNG#> zjr#u(IR9!!e(|l<7QR#s-a4dd-1t9yYuzGca)$6o=ID9S<#JZjkZ1djg;1HsY;uX+ zey-2Z-aaT#l@TbT>{}_G?V`Xl^emCT4Vm3v`BGe#j-0*z0iPhmVH5~3X6$AC%s+Jy zkXW#W{=r-GVBFJUs`H!t3vYdFf8{lxRzLc0cxyUqt&oYhhhST0AHB95itK8Wz`$+` z>`^)3efxosk&kpuon=g zVft>yW29}-rjO>&QZ+-qd~$YX2;)XduZ^$=P8ocyX;+z~m&`i%5fyi#8Dj638=GJ&?+aZq+2L7>_1M z@?5%KOVXt2<*32n`kvDwj`H)Ycgdu*#^*UP2;g-Q$aYerGU|j|!r(0ksxC7_1{$C)prq*s^&+ z`2Yz3W1@^4fjVdu8uzqZuu{JP$(Xv_7GQIkY4^Cwz8327g@^;bqpOalF~@VT0J31f zS|VgN=a-W}fJG1skav(4@RO|MgQ0dY3T*UR>dGE3j2?Ic&Kiy7Zz&6h#-_{Va7*aM zbtmC17h@T_J!m~D9Hnzl{FVx@wCX+79BmI#hfXSgSoKY`$6SX^TgH)@$}_%Wmq{D( zTXVIF*Y&sZi$c{HN4+o$yP&PAO2qJCp((IQh{8si>q!}lmf{CJwzg3oOz5%i*SPRmo zo9{fT%l&!eK;cxM>dOk*NNfF`KO-uHNxv!5KVX0kkIq29pA$lXjtvW3w%Eg;R+Dlo zUdNsfpi11kG+r~Kb_&;-q~7o63wg|?CHXO$ScHc(S`s;RdH#F;&<9hbG5M*11QX|&e_)hn1iYa{lFMAy zR{r8LM6@`ooi3Lsp|>+ws#Cfs?g(U%Y4;T&UBnPbFVJ zf(GsyiOL$Zzz@KlMKHiLC>;5S9V22u=^wctlJa5E_O)R2|H}pQKeC|xzZcBE4wGsv z11G$%Fhk9G8+-GEH+D|VEpRaFxX%Jg`>j7=KLZk0%YTF8XHhm4+gjV#(*35b)G*H2)xed7Ck$+N@r{O9@e^@i)))2=M|qbGUL3`VFF2S26=^v>dqC%7>-N;D}6+ZX~f zOAE+BT3r7;Gfj!osH<#flhqn2538BkqZv5fp3SJFGMG}RK6t5=JKQ=u7wS|(j;+EG zt4KCIsI1_4To!$~?WjZ&#{trj4-gs9CLro?EaL)G$^JX5|L(@X)hP;(DtMt4!)vieJL+EjL*EcHkS>?;&tgTPf` zmU7;R;zOir@kx>VN*$W3*qKJ1*JMMYpEv=F!Hn!^>6htQ9=9~wbGlL08H5cj=V+Ax z;ixnsQDye_tk*pF8=$i_6&l30G{|1==C1(nm_`jm^&$H6spTZwFj9riR3aZN?jYbI zeeCKith0oCIy1ElNn0m2GMVP2>1^CXZQ7g_u0gP#9-U*Nkt=GO?KtUhq;_-kqdYhrWvD8Yii5v6Z+ZNwc0OX2el6<3d4aEE zHI#cy5*^3=hr_g4cKou~~4qC8Wo471fKR-?B9#ubhd3af?(f~UoeSyhiKl)7sh zPhH@%lcwR-@=Y|r^41Sw=IjLoaP~E{No}R)QsR0E1R+4$lOPZpl4}@?b?u6F;Wb2g z33Jv5R&v+wekgT^Wr>2mWB`Z`xMnt9w-=#E?)uMB(3?@yG{Mnm06uTA>%Y2vQ90|P@^HHmzx>ypYJ}(C@7;o9xsLPwe!`}I zMfR3?5u!l+&bP86#6#B?RVO#-ms(w|;gnoT;jgf8{Ae!QAuQ;pv>;xq(5y_YFKpM% z1|I*cC3J`mEhIV5)o{dA(Dk(sJUnpbNC&34bFAXlAhx1AZ|?(aY>CY%C{4dI9H)WqMJ?CQ@xAX3>IcFJ26FKW;?*q_m)N z=^zLgOr?f6JK#XAOB_8pT}q`XFT#H_fJ-r;n7B$X_ZVyFG+R@MBFuH{e!JCY_+d%b zy*BiU7qe3LTbbp^v7m-WTebyPBeN#IV{acL_!t)VT*FsAPFLejRDqH8S8e{V)^A=L zKq8&47-24nti7Iu{V-HGY#IgvoP%Bw=e*M`Yem8OKBoz(E$>#xJ*uD)UinfxGRlok zTwJxr)RKn6eHokyCZE~s0A3l5gFjaJ?529&kiNYHMrsSaPDb~djxNL8@UQ`Xu4!71 zrLdtmK`nmg4eE-aae4Q+a;_AS;UJ4Xu@@t2S*kOnR@ozDbIp$@23f~MULoUxfJmbQ z%NGW}zhK+_M7J*Urv|>!M!VOGFHqaS-kVC)`nMff{5-hhA|0#;g= zSd#0X8$m}g(F(yU*IBA{mOmWAGKE@7rg7dF3Dc?s>52wW!N#*Yuv^UHxFmL(=IHMA`g2K}>);c% z`zcgvgDEJ(ZE+R6EYq5?ajddSS8mb_FW!O_av^AWbBcSP)vXG@2e8W)H+j|>q1-_) z|G>xeeFpo*u#Z+z1gpF-|I#O=oADi|F-vK|XUtViq+GS7+sVWuk$diuHt_1t9xK|s z-yEVSupxOnu)wb78q=bOQTVQRfni=%!!&E#wD~(1`{ZrX6d%P5JROLDzlP9oO#55z z`ND1aLA4^m=;mxZ)qeP7fDiv0pirI-A?r!(EKwr&nJ&;=iT6(b@!fU;QKpsGaDeBv zz5GDp;nWkvlD(_;0P~mw-IYGC?0}$)F3zE=15_)AM~C;T5d}JS1bN30!3e8wTlWeP znhPp|g5+7P<36P-h5v5%V%iqC#(j?8UZTZ%ta%m3hNM-+qF5 zO9)js+dust0`}4~n|9gKODM?`bVe)FjHsOjW>urs?PcDc+vt*CU;$M3v^1!16FnT5 zdeOJ2gVsjqc$jrd5dCmxnFj|?Fm+kwkd^P75`eFO&u5;ga+M?iR1piNx;MY-8qkSs zqy*SU5Q5s}zxtRz(e|=5vqWn~=cTGX14s?Ui1Nr`sL?muX*Ws1!kz4t>_`$$y~0z( z-$)94^0IC8ycN)hf2obq-WcM}S3zzYLZl`{8?ky3II3@9+aMNv{ycrh^;Bn=rWW>- z%7>-Cp`2ccmY8Zg>J%FZ=@_viAEAoLb<$v!MtTERm_+0krTdiZk-X@;BDGXp4n$L8)I* zIzfx%C`EerQM^3u+eRjFMV3VFVNDiakYI80ODz3jE4AH|9GSNFE*%ZH3cP55qNtPoj#_;%wAz8#i3u4;Snf{;ssEs zN`@o(Iw_OWamJXpr7v3io-0J=m!ia>--CAZt$jSNn;m&`jU2DPIe~YA*g@7|2*Z#N zC6G`Fknmq|@is6??2|DtRxcO%nkgLR85>ZWX;pB-m>;ZWfUhgACHvu?i zK5ZXj=d5%ylsARk(t25;ZqXMWN3AX}waWz^yt0bn_bjc}hiEz?*)w~%OuK&kX5PZw zbJw}{S0+s=VG!rm+Y}34FzRRTVRHt?!C_Id;0Uz~1}F05i75bc#pb}%#e_$ls&2Rj z=tVI#+h?3p5AcNvVf8KZMp-JBzx$|y#3&`uedqhSJM#O#?%MwU`{zV#?bIFJ zTwK2TFRs$&Za=JDT&+$2S7E8S<%s@;YT4RK&vx$&QKe?}g}yWI+-gv6nn#KXiDa;o zGq$w`2|2r3Rpjebv+%%xrX8Ur{gX#YJA^$5$A9yaMK?13Mm##;r{mq_uLu~GgT$B4 z#tqTmCIxbd+dR*kjVA{l{?C(dH!F{L-&($thEtqY^);?)1fI-Nd_fR9e<{~XG1e1f z7M6l`uU6(Wg%dx?O!=2bOxTwu{W-epY9fl8073YL8ww6;uem_Q zpvp|FRFk?)A z;L@e6^shp5JsX-Qhc{I5G>e4@$g&^tas+SsG$BHOjl2YWd6trI3m z`qOgOSn&o&&ciImthBT<@h&Sydy1d4+q8ImT!pId$-wIPrueD$$(J9uH7S?{+!V43 zo!;D*Yh!*colAN?W#FxD_deCwHFC?%$@?jWc5DhvCxkZc#h`7gvX-8lNd2grA85TD zzq*`Kex7eBhGx06TU^CDnnda2QYcD>S`?_6Jl@<<$M<|SC_TQ)xJ~mh+wQK@@J({l zP~~66xQL-n&|w^1$OBQ_r~@k4pi`fG5y+wO&?Gdel6FhqL+c2cP-cAG+}moLMKS5r zuwjhxGQ_Y$Fb2}}M~uVb5>#;keK}z-4!hA0^K~%~(yrGx*ont!jP6Ge<5dHr$BR|f zbb{lRC$*>?tcLZ<>F z&ow*Jln^#HCt-0kNfcSGDbjKM{-JT9TM~^hX+_-%jmiUVtm%R)dl$c+sALN~VSW`Q z8Zk$`f{=ZpzmQv!+(3Kiy`uY8?9qfX(Y(|}+r}y7<&2=5CW(5H(F0)xC+blvtwf-D zq^!}3u9N~YPf@xHBv2S^JaGjBQ+^Vrg&OVhj}#X{Zw9XyNI2xnuJniy4}2;Ki3zWG z<65{PynPuHlGXVf_57nj&FMAl4KXfU#;*tn^N%XtWC=Np(YXfB{})gt&gNHb_z=C zrofadS&Rh5xb?2GQq$nx8>X{9Xo2T!O-acBotG@#jM7<(BFX2m(eD18$^E+!ukoGf z{J!NOjq4t}`+>q`|Hf%Qk3VTotY2F+caNx0&j`pdbNB{6i_ih{mDAAMGz{6_9|_xo z*aL;y2r&rm^^mbFclP6|T7c`h-LrAC*gDLMF2c`#=Y~K5jT=19`Dx&nr|lr=?QN>I zthi|QnW?O>h&5Gkq`Y)VK@&T_XpZT0&FH2xVx~*Ob(vPSa>}ra!BY#df#1?;D@v-0 z{7p?88SYu!q3LgC60Z4@L{-!xbqs?|ca5THJ`xu4op{7c(E#D6dH~Y>QBE$4CYPe( zdKK|-_<_|xaF`O`j232{^4J1&PG4fQ;aEpT_)j8@ssIFv;fpQZoSb19$xDR9lPJbKQh5g^UL=inRDg1ogXXya zEhj`0Wwm4_2}LKa_qi?mk(I(OoYjZi?BTHyK7-m_%?Q?wd)WtFA}&aVYRx3*A|OOx zDIc`h8JG-glb6Q7V$UJr4@E{Z+1c3?&IYp)i4qj+*lu^t z{!lFV{+9ns@hS2dR?^$qFub6?noYyD>GQPhGA;0&wZn5VzVr4s%IllLi?jr?)SxGH z$GEY$2yZkzJVYU_nVCj(zq&FLH=z85hn^)millTv(s20RNge$=te2LA$_*Fn2Mh!d zBTKoSFp-v&yL=Y{Lj_;srXW%mA0w(4d69sOkA~+#b3--?O?> zDfpQ)OeOE7e*cooRh$Dx%s0nx)_;F8lCT?d*Q9g8qOK!8uPbtvpFBRK#mjFT93;sA zF0NLe%$Dnb2rKFGxWi567VrY8uCW{GhjH=l_Ebx2v?Q17DSM~wP5oqERTk+yrn92} zJf75bz0`a^k&N+Q_7>Bw8x)s->Y?%JKO`_e!m{&YY`v|G0-Sw^oDk2+FtsXtezO~t zE(E?AYA0>6Bp!Qgf0mm{Ovuh(qm4xPkqc0j8+>J+Y@1t^v6*4YZlDqx%r&3q#_vvW z&5hAT<}u}>4!R?zQ?lHs$?>`8Gw-gZo2)1AD#f1QY!iNPwbRsat3$@=GdJ?UXy^=f z*RK**8sXF|D;r!hD6couCv)|wA2{u>Q%378LEg2b9}t*tIdi%+MB`KCj)@R(WC!sn zuOsPsrz57dM~4&D`p@5VnV;4;_l>d+pt_Ho)77!nE@*+GS}y6+xwz z7Iu;=Y2=H(0*vF6eDI}8w+SYk3U07DYI-@;DDR`ze%MH~v~2Z?7)0d`$##~B{u;`= z!X&_DYuA7NM7p#pgD)hE9{q^jHvJQv)8x8d7jTF@XCyYt1$# z{>h>Q%O4)ZWrda9G-nU%TGiQ(`vnBUZP|+s zCNjWUrA|}?(I8kl1F~=2VVM&O;qt*XSewshJ$<`3or-^I1#AnhT^mc~=>zr)3 z*K7*i55G7qXtumIcF|FhX=qO9=x~)vU7JJlx;>}&gO>|uD4)GgkoKyzXOX`UM_R~6 z^zj`sD}Row9^!pfI^FPglmG+7bHe4wr)>mxI?o>eRUKWq*Kuh;WukX$PVSKxdKDt* zne_O{tfS+Zt?_5I{jX1fO_7yu`Y_O`z5sZ`kZePgORSjVWvm`N)hW<^1NM;wI{bKS_n}{R2IRD&bGPGun=_x{q$Yxo!Buf6jNDx<%9H7m zgu*wV{PM3{bo@X5Y&)8CpNN$Q;3kK-HYLv8 zoHs1)Lr3$i-)~F*43U@q3CRjTjNc0#;i)>IF5r!VvZyz9!nNFQrXVR-I)CPx5G|uX zMwsM+dY_UNk3hEbDGUrxuz}(5XULn!LU>dnqg<3cq|rgGz$+xl&sOvRo_t&e=wiD4@nL~nehZ#=;FnnpvY-6g)gV>cx8H>C1s zMCNn+p0vs{1+~l5HN4d-(;cOBD=2vI2g~>64UH&SWoc-fSo!FnZA>gVw}GZWhIo`T zgOG|9)H8=p2^mMkq#Uoi2t9`@P*90;YRO;8Jt^yNJKe&$BeSsV(ESE0c@DYBJ0bap zB;jpqCL>eagToSj!C>R+%Mrc}kK;Lp_L*&3FW`}s7^OXs$8cekhqTl}nM*oXDd4$Q z`~aR19dPdh*w_y|Y{jo-1__9z{`d)XD^)VXF1L|ub;z!^HF`_z!>Q&-X*nC$L)_ z-%s~N$8MO%K-P0P8-Gdk@Ym6QwHJ_@V!HRf`k-ZK|COxxA9-gK&0Sp0&Ey>&o&FcQ zty|0fA3@=-scUQR1+&^;1e%2^8eZpwo|S+M25E}t6ladL_A@ZFrntF_`0KJ0qs1C8 zA*p0aFA-824b)oBXtPAd%Bs(8GtNCjo;TZlJP9e={{r|CHofR~CEH+bqS|Z5o3YjX zoZ~Ys!1M)hJ5~Dh`o#T-;5iff;}rJK`;Bm|FhjyVM_yl9p9;QO+}&VUlQuhsw!b=Q z;V#Q<^ZV$)ttrY6SioPE5D^k{>Haz*IcL!u-)dANAlI8GJ{1Q4p47JvPXQV$C7PF# z+#R+3$7)&r7)PyrK2OQ691PzXjOCn>IBg$8rygSH9gL1{>Q%!8;!=7#GUJK-aC53b zUCAh<)4jH2MLi47tmUjgr~#QR*$aRG{<6z$Qv56j+aQJ zR{AU&YKl0(2H5O0&7!&&9`7by8;&ER=JKP3G5><{E~Pyef2k3W6Rv!Jc}y9p#j0t; zZJmxvm=RJJZNV36s$F7CIq369E|tW>Ei~%c|+;+9cR+ooC5NL z=_X~<(?h&?WeQ?e^ee5ItiR=D*&ZRlG=!ISIMG+wL6mkK0kH z_@OAprX{hRJvn!%F6g@46Q{I1&+YX6bb*3A%hl^1^4{~~&XbCmCk zQ_&rcH6!_0=TyBx`c)lDuXEtTN-L1CY?H}+HwEQao)1I>JFxx=-C%C{H}tg5ZWZQH2igS}RMda%jm zR4SvMt%8_CP<@V^3?yxpj~H!4L*I5UnJbQ(am1$+%f=%{EmfIRr#fS!_9fb~e~PMC zopmW$HAcYDs&OSRF4?6gXEvutmCbf#_St^u!?CU@suhDjs#q@}9R9Szd8`S704Njh_aS8=CYA{odKB$Jl6d9W}&v z7Mt3e)2!m{u=c=>HbnVzPraXY#QeH?b~zm*vU8Dy>^yw?cr?n);_nZA1{_&AUi`f} zYKDY&7AF?xy?+E>UXB&2!VWKYN720lbyK8T?VyA@KPNae;*TlI$jogZRki6LjhL=0z|3;1}?ysN$o6-U;M?aUh7N zm%%n!IM2$tFt2gyJFk8Ot=kn*C!kr3RQ2F!i<8;|NUDH_6S}Fv7bn^i_!!`X`bT%f zC~oqRSSg)F4dmES1=4GTqN@Jz<-6QxaeSCGud9Wfz*&9yF0I}ubX@>cJ+7cz?o^#){EEv0Ul!dS6Wqdv9*84`+Y`HPs5mB0to&(#(6N&t z5bivpFuz(dXPB{j_*p&S^d$Fy^aF!0EVi$IV2|OP>z#pWd@1P0B21``!OcNUZkMX1 zD0Uh5d{pk*$=KVN34>iHMB-K=WMt@!$F0k7JB%5|l-aQ*+$FW^u?4~sS0}OK@CaGd zoG<41v16dFNZ!g@_(@`e;udEFyRG`= zaRP5$;2%y?0bphbgLB3(sc!j#cw2&}8D4*Dod*Rzp;GGXd=U-!(edM+No#``H znlkZ>NG8s^G4;$5yvH@hIroJxU=0-rQ|w#1kaRM+uo(m04GC}wkhpoWhyR}Y!h1!} z1pEVy>He>62;Be4IOYE(7R+cu`zWtq{>uGrmzB`g3ItVw0xFdqKq{aL3YCg3LZwO( zGNk%*VT&b^OeabC9GXqv)^V{68xFVEB+D+~sZu>VLwQ*?`<}IQak_hVk>kzb`g^y% zm7Sd+wHXkzSAXXBdYp6jnSbZnd-u2u4$mVa;-`3AhUB#!YRC^Se}7K`FW+Iw_8s8= zO$aalcbl1q=ZfcK1$xiprGF2$E7~oPiBt#323f&d`Q|3OP>Dk zJu-Wb5dX=6DtnI@zwxCj-tN9D|JeaLR8QqR{f>%M-=W~`Cu{vX?C+O$s9*W~-HysA zzkDG-#gjO@>b*4NcVy;IW@TUdMg0?d=&qA8YR?R_|Jea9-cR9t7u2_Mp+Du5y&%bW zGY8Uw5%iE1Pu&P8DoY5FmaUm_FD&ufRP|jbW zM1>-;`S%myvxOQ^q=ohA&JIqS+G-0l6MYQZA;u_-<)qtLHQLpZwk9$utRg_x?V3@c zFFTn{WL&~?^7<)y3iO3(qp||fj+}0}Lv-Ds$Em9~{Js}FLfs}C_uN&~B_JyyYh)HT zO?MK+%jGQL2Lu&$>_`!0D6~lj5dF6qpX%^HTdp9OsjywRvwg?ipX0G5c@ejV@~N=*&`?z-}c&^ycoE2&EpN3lQ-9995!W> zgtTm}&1S((3|LVl&du$G5g8EEA<=YlijtQql>!4`nFNvLJu8Y zo3L>V?(ivua2^+)fPQrKfO;RnNJIT8&O!$fWLzvd`ci5%-Ed1m+3;0Cu%L&~-+BN} z6~{Y4(8ZLR55=+qSBlGv{^g7IWn*260|tJ34ppQo%wh#6>9En#KL#A#Sj7js1ZlKu z>lkzecote=`tXM(OW{s{#=d7`nkEAO_HZ1`Y2o~0Hs7}Md1zUa_RtUJNV75>4^>CpjJp-1 z%MKdQ?4r(+vi+<~1A88W=h@jsv0e`u*nCg<@Apw!-^>br+axz9O^tMiC0UQW6%=`V z#P!j~f67@;yz=W`NJs*zHecMX)+%f2no<}f>`vwsB_&J25kcSws=8Sjg1Y>S1+J3t ziBLY`3)JE8$8m&NU#%WgzPl9E7`ZC)Yy(xRJ!}$>s?a2-98>idG4Lle=MmRb-SoYb z`stT~3Qoh&hk)4Lvh0eKSYsTRShp z(xb>eO%KPn&d&_V;F~=%W`tQ&xNO>lmbLki=xk3edBeN-&$OK@imte|Tie(a#J3xF zriynO1KKEtC$>i}dGk=O3cakJ<||p|gj;!N_6_;qpIcUit1oQu)I2J}&d`)_e;Xpg zNuheq3V#LIel*F%8=LXhV@AQYB` zuOQc^a}4#Jg}1Yn>>19r86ZZ8A2H{>prE-d+kN4M{Kgf~oaK82VV(1bBy=o#oGwy% zTrh3TM7uIOg%F8(28p3SXmRw`%f9xIfoY!R&CiwKb%pX@=BWm28JT!1nwcgD6mwHQ zn8Qm8ki#>xKxXh=%GngORdPdLM=G9ztlHVou5U$6DHj&7y8_dvq5-e%V2)v`DTWgNZ9+N0#*j zC{KTJ6^)^bb88DDs_;b;|AY@K)8QlG)q!MhM$ztcw0IA7$7yz27vKRF8S^)FFZH4A zXEe@>iS?Dynff!!mLO%xdaB5hCkP!`(9IAJ(;=RU?Za;A&L_<=IN?U3 z$Qv`JZ=x7ox?dGzbK2)z{1czkJ89`H`Jj4T*sbd{cHz{Ad&G$`N6MZnF4~fYW;{xM zCccQ7M6GPD1l-Q#idMlR*=UoU(mtF}VVI9RXQXTNt~dGWd4nn9W&k62%+;W2kEm%A zMN?K9Hf~fI^6za4ZVMf{uyNY}2B0}6N~cRarw2@2zItQ$4PQM|_zfRDbb_~GJSTET z9PxJy_5f}84hv#bCHmN+zlK537C^cZ%I8Fp)na%R)5EG{3lNes=}-nyGlvN%*kXw& z#;%gjIkBoSt$@}ZJ=midqQozXf=Kb&dG}J+>og~F^XgenJ7tjDVUTGP?mx}%(Ejn@{2RQ**e7)74cCU7#_|I zy!S25qW3M0viH;2(^UGPkG1zH*oLv$46m#nV{BQH>`Rd@(IPxz>E=Xyk!nFg_@iq9 zfmUfQazyIX9NvY!cCJjhBnddMfh-SL~MA?~Q1m0rm2Xr3bWef%5 zAZHv@J#lM?vf{xP2gZh$c8AP|ACzX<3a5o-lUt#bIv6seA?x zi&@EDu$IKF1LA#E2m)(a=XF81zqW`X<=n@y?TV1}qve`m+msjjt>*!5&lwH2ykX|s z@=#Jb{rO;1<^WEbS@QCN?fKyKy#X=wL}a>69IHgZHhJnqVNJ}XN<@kWw!b-I_rb>m zvikx#4<~Au*n9E;|GPvDGQ0@5n4$|5I{Cv$yWG;jOMS% zm)59&hf`b6MlAcX5K?NFsVfS=DOx!0K$d+$E{8G*a|(!K8>Wj4_KnDpIC`#z1Rgup z7(%}Vmi+r_I@|I`+LM?w0q@rVgUD`q`}ia+M~j8HqVGm2pjmq%r|bnM%Al@O6;eV+ zdu$o=UIMnmxs}{|wO}o&G&#zCr3b1p29BQivPNe?*j&SMVmC|a>r}AtEsXaSjT>wY zn)$471`mRad1BE@SrlaRB#t>J1k^LZHN&d2=z|s{L(VZz4uEy8y2-H`Gkgaxl4IM_ z$xFOr<_|bmBNf%;l_>5}J#;{>j7gPsDOAME8$6!eO7!>#e?sDhU~pZSMo+Oa?IXpW zmr~G%oiwBI@|0f{JvT+krH=M^zEunx9!mdKG~VB5@X!S>UGU7Z zR)OsWSgT(8je!~eq26wa6>E6#YD*rR6ZnY4rlESy{CBalYYoc?>UI#%uuzAkvel&^ zv0)<}Y7D_CQw48A94|28JBgrQ%(Bx`YQg8M-0!iX`BSrwq-Qbm-UejQ$vz~`1%2T7 z?gA_ZD;Ucq1C)q>7lqdwXW{XLYTJ>F^yXf-c`x?YfMTownI%D*A?5s1L7MUS0y?WP zd~Ko2GN=c4f~6MN9aT4m-Tkqu@IA!gHb>HSh)V`urDpWZ6-!F2cdKtEXPr1dr8D6$ z;^h?0fD$ba;m}SSTOk{^DoM8{EwJj88!bnEaO$DCgSMpd#YD;eq;44ja1W#TGW2kZ zx|oPbQi)sHVAIGkiJ^3jQDlMW1QacseMK4C&;j;Y`hHP@rcR%jG;P|9;!-tV0lImp zq6F4d;7UOx02lU26`e*=oeBEa8(h}`bOWU8ahb>78nw!I}Y9}S>+H%oGk!h1>QOCPZF&qL&$Fm=EMIWGFA zxYa=-&$=;LT^8@cN5Rqnp1U`{N{h<&N2;rD@u1%2gBsP}wAUYhMgqRzJK~O90f)~r zkuCGKq>JQ7X;V%=yv2S$_U2i(SbXW|<2FSv7IDY;DHPG+bzgIkV{)51@fjBA&`iS(tOf*mv;?uIY1wIlNl8!Q=2 z@C~WImp|LDK(OIoQVR#TZ64;XnQ9CBu$ktjt!}*M;9k#BK-DvYuH4gGfzzEalV)yw z*qsxXf_QE>ACh}M|4!SUjm~u7YnT8r#~^-OVNcf*^o2K!K0@fO)%WHf%aCQ z?$dhcA1S(+nK^WQy(k%qngDJeuUSA|D?#fPRCvl)942Q67QP$OWuJ*5ro zrQB*Xt12a(>N221tu)_C$!3n$Tx!;|cMJP6?ILn8ntX-|(`0j=N=tN>CS9wb%59$+cd+O5S8TLyo5Ped&HST|ooK$x1TDIG)~8j+jaT1*i_LXM zhcULw9zB+_>o6Y1jw~XXx)XJa5(Al*Ma*x)e{Hh8U*gl#tQLnfW3nMyM{0jQ)%>&l zG?R1B4cB;@PKM2q;f^8N@Gwh94j!3d(~T%KOgWH5-)h#$XG&W`IQp31KYN4>=}eFzExZKW|Kd>$UJ3BK9-a!OJw7E(N)S@*}hB6*%_aC!n*70*OZ&- zPOT@0)e<~>qx0yDpszZNy+L|J6_zXwB(B#%(Q@3-!5Qv{S9g}AeqfMQ3>0>%0W`^$ zwlM6fePD?)7l|0WE{rMqh-2VV78b7>^$n{kMh%PEuCl$>5Y-(-jGKG)VthkG)J5Gz zOAKh?c??`v81*v_b=$yPqJziLPiR0NpPxOl ze@CM%Sn9@v?hI`fnXoLGm@O%ruz=Cigh9A_!I~C?qzP#XL?3urJYBk7h4#a(L*mcW z%9+P^{4CzY^ckqqw0)OyYIl#(-`D6v4bUZW1{~`>>2@XEM@`i8i7wSngl4lwso7%< zvI5gzW?nE+PD`~fOQjA5`^T9n8?%ONzF9DWdoJHu$>l{)VJCJ=u+|_g&kDE))*6$}e!!;9nY{BY2WZ!C9RCQqC|CUNcmi6#;CZ+4MdJ$B5d7iN z@blY2c!hFoGp8jQMA*cMqLd8yX(8I?%&<%+e6Va@qU@Upl5@$`LPnX@d2eAmIXxIs zY`EjJU>6C`nDe5i2$7<&UaqzTRO^W}vgWezEGsQNcEhVqNbNOwh~<{WjDjhpsC=xp z3n)R-0M>4iC0EXrLvjq_ijdV&6WuiBFA!r8)DG4(wQv_r^~-g-wfTHF_zSCo(k{%2 z7$UDfcy)&2o#OEz1!3t+S_x9}u-r>Mf>c;T6}#21P6-uwwjdI(tsJJtxie2(dJCTw z-)Qwz{=}(^Frd?5qC={QqWlxQEtlSv1uu%Y*X8;s;0$qs(*_XG5l6~YmEKRE2as|{ zl(SKk(~(mgLd`9#~08fkd?=G$~Yw)hL2w0;SjFLcT6Wn1VV^V5{Q?D9O@1k31SPU4j~HkBRT!r zAw?*hp?@Hs4aK&HxKY#x0Tsu(LOR>4vQg*GDHc`UiEDQdo^Xht^csxCE(*J9J4$&b zv)aJoNJ><6t&b6{zr@SX8uPL>REre=a>648hTW?A%ztS|16Ac_IK9rFEb7 z#*axxgWSIUJG0t6bHFG2&lGn5zna2S{}VOy|Lm#y=MA&_SLSMHWMlgOVJ4rb&)6?% zApG|5jFDLiL8qkMFWk`SM?$lP>Kbe*p+QyaRt6QRpdOkfl`m5?5|05+?hONy6s5lO zhaAz! zHE>KEs-q>-l)>aMF%TDY=xIXcphYqJJr?{0GS8{zS?vkJ3h z0RrkpFf*q3v%Si;;_JHekOdo9+nje*rDULATUAuGoPrHu@>9a<-)6;*73D)$n?KgA zu3ML&tqA(b7sD_@USp?JqO$WU6*ZUwI*bbFyXlx~AQmz8{tT{LLXjt*>AzCz99O;C zMBAp=`_el|g!^r?4)QJYCDiPu`VOsweHqGGZ=#NFyJyI)wH!nm?nQvfmeemct0tfX zjbxHa1f6sKPy-saOWvsyKThW6gRa|r&~e{0a#F`mMU@qt{4R9o{H->Z-Pg}DrvNwd z3+|OQ{g;}#CqCwVR)fAS^3*HbP2boxCKQiu%Us9>3bhv}W;7}d64-qgMe7I3`-L-B zHJVAk09~TQ)bjKRjYYX7!K5&|3G|4LQ~H|Z9a%B> z3q9-$Uh^Gc>zMfX*f?gKe4RRl$Yc-1de-1xm5I>rzF#o zTZCnc0NmonfF|M^%=1Aq!G|Vd754ElnE*6{q)RYqhoIg_0A$pGVv|RB*XOj8Q!KUT zADQx0^&Ly{olFG7%G>p_EF5+u5Pl44p)0~7QiJH|LF9>!NDE4m_8XBX7!eU#oUeZq zmG#1^25@lm5s{`BHHI~?m{Ah*PgfFFoFrACap6}c9btHhKWfG(TFKsj#|mbvS+pJh zMG74M*ERniIX3=}HUB>wwizx+50#abvu$=}`?PcfAuux~q9VjF8X!SnOd*nlfB^&` zK$3zqLnad7f8^y%07GX&D^zILN+>0C9i^+V3djfrE!3LYHnm#SEvuc@T50Pm{jIFu zoX=euu%s`15(WP^r#(-1&a>_2z0cE*`g{%mfTPfcq123-8O-gNCSk@nv+<#MjHwj% z)xP)5>d)5)Z8mmu2jcRRiVW*;lxbzgJ-Fa|8Pu^&1FX2_Ap@Lxqd;6HhoC6)4MU2& z8T!y|85PGQT&BixKR%6I=m^_`B2k0BFpxiCd>(bA3SnnOArk#IHyYUvcaZQe1SB|v|Rhekb|gr zN)Dm8r%fy2MpI!}9~a5>kLEEKg63P>J0%Vib3cVzBAiOSf~%jiBRe56fgmR?>#@ z-CTP}H6NKD1=~lNm={=?~ntjL^VVcCyb-K=`2d~6REYPWsj%XP|$7PL8b-;NYFHb z8QN=n#4ds+-}mzP%bR@kELWbKKxl*|3P%<)=ux!Kt!)ZHS5;dG&dsHi(`YJT#4pD_ zvV4ES`ZfI9DN7cfwM(Iez1`~stCPcb8 zFrY@IBGBbGGD4p+@al-6f~kTF1yrS%ngmSvnq{ynU_O0gp?wnx`ml4$G=vi}C^-Gl zs)k}~pIK_j5Qyn)8Xb%Y4x!&6%^S}!8dyIi02&QAP+(T#bJdi2`H>)GR@o7V5e$|5 z6A55=oyu!x9(L+3$Y&3a(B(b9Qd3k0fvO-^!+jdlAQ~Hc`+%?*@Rj;A^CnSyReKw0 z8x4-uFAhetjNROpHZ? zqnV??7q_K@W)TDS(W6xeJIq-_js(dDh7MRHd{wicK#lp(3|S0%M1+4d?pQ<29s7xc zm-XFZJL8t!-u?qt+HCzQZyE2Z$Z!8cE)QClk@9@u43T^qV&>>^e6oNFFM5%~(?l|2 zwfRXW%fG@xI>=k`sLsOArAHb*1K^hYdV&T&sS9@3GA;VP2P~Sk>9HahCDS8Kh-ECq z`##6jGa?ZA5J|*lUdBPBQb`f0j1iZxheUp>aWvVfrHT>pHQ_r4OyWDew2&;-!-#bd zXgH{-^V4v8TI-lkAnd)*Sp0&h0K^$kNI_ApiK<;tUey!g(b~LNL(in3R`PCcW5lS2 z2Y($Vbmlkvc(MrCvo!^P(1=?F=}_hQZWBhOErh8ImK!sGnqcyLgPda!5?lJCGEz}V zI@>G}YOZAk7jn7rR@2GK39p`xrcp=-wTU{C!1b-$L&9rpkdM4PU&h1}s|K#9Oug{O z!?mpM{hc8_2yEiZL1X!Hyz}Kr;ADNnTQpe zZ_+a+Ux=N$QGN!jBS@jH$Vx$~&dN|0&lQM_Sv^1tDPmi;FPtXYqKUnHB;&-DnHM9X z!s%chW1mvo{yY5PMxVu*C1u1sLheK^L#m7?;rq`KsRdgPCjw*k1mqV{E}mDoNIr5$ z+_9!etBwC@F=JgbTu%hddY_j_7{|s4y zqVqHAz=9A@D1N=5g?{W!(rdO*6evdNsf#RyoIX>D;)52FMQo^rVOsj;UG+dRoD}yP zbtw;Y^m4NJLTxJYiZ89l%?D-dr8cU@1yc_d_AkZ`JQYlcIVwX~IkF|s2Mr7pAe;`4 zT}f4KX%~4<*2%0(4;W09#!24Klq3_t(3ZD6coq>_I#tvNu>$xP==o!2ZRD4C6Ef=) zeDoRMXu+`-E*wa*dhBXpS`XPS@(q|d$Okw(&7{V>$nfqG3rB?pRww039(#%OjpkbS;+8LrS4$H1G;!!jJz1xq0U@oYhuQ$62{|P4c2`h zo~0YsUYr8=J}_8ux9}jhU3sYM-VXI{;a<;X?LOQC-}=N5Rxc=>^$T&g{s8!`APoLr zGuQ2)ILmfyyww|q!e5S8SBIs@EtYLzpn;yZkf=`K{m9 z^+(lNzF_eLFt&YzIcah1N>;FXCsq8V(W2`CZw_32gopMJfxdW+JK*ZdgZ_%B^a9DtM?ihq#D`pK-lribwzoG*XN49h<N`Nk zDkH3X!>{S1fAD9)iPOaTLDpA!poaYg)n@%-{|T@Cv4-seu>hK=INdc!r_ZM4zY4UxlB4r8dAn_xPhxfeBV_O(He zve#7k&CwfWw;NE%wWHtlgWzbSRc2{tBj_ty0930q|H(B;=XH-PShPs(zJ9_>mVA0> z4O&o{-1;f{(MU5aX8X=_^^(5E;BBm@7~WJae#mXatB$3%rXFa1-&M=AG%jt_AZf25 z9Zm0HmZG+vd~aH72QNDcHySAgd*-_N-rl@?^nA+ERctK?gQ@6D!YAEetqx}NAF|PRW;>W!eK5oJXeQmg z=GeV9>E7VdYYc%=fEB+CBGf1L$2;sw`2iK)X_rrE=fIe?j9dvnacuV~uwvjNV_1zs zpiS3UF=*+o@B2SVlID(CUUFA;vH6buR>5d_sybTyd+0I%BRPbZ#Z@k9Y(u|*J48QERSZW?Hk(* z{m5+)nW3tb)HyEm_Ua(QysSL$K~pe3z#_s+NRJ)s&Ic@2`0hsWIOt`AWXEyR)pw32p>VdjAkjpEz=7un+#AyW6Lhq1i=khq9z_GJEk=(uX{5s znR;O}eszI3#KJu(bOY&n6Q=llHD-nZG`FNKf6ObvuN!_bu2}LnN8+~#ezDV&BzZNK zDAPq8ela(U=1O9a&8rN{jOfBzT>9xx0#Lo=hq>fRIoWwRnG6Z5AyFkHvLvfaN%`@O z&v#8Wlo=v;U1olY-bsu{^jF2J?{^ z{Kb$9<{!wsH@_d$Hvsb?3UvxZIWVJyN|^UuRK_$?%pe&qYLJNN8Ij5ex(B%?R?LA! zA4~?}gt*dKmroFDpE>{#q;!DYo4Ya;$q~ZPP|-ierI^@+tNb)@xUrMC3nA=kdJzs= zD?!Q1J*~;zcgxOc8H?HEDeovi&SAARv$^{)z=x@wxePJXYgV#w)Ur5a%d()nuli!3 zow1_3*V?Jt+61JlpRwhJ87eVYh8vW~y;UT^#UfbFY~`7gMLf~=Hf#_0yF*sLW6Q5_ zt^mbae(G`^5^2|^OnqOLkh9{w@8YF#7kFTo%^k|%DzJ*jVY*Dq55Nt(&SfByEk?t) zWmedh$G!?#?nPU?jrPYAKE_4cjWp+wXc8tsO<^94ii-djJP>-xfCMh=;VCCVj$)*c z0eXi4o%sL=2M~}4Rc&8lJ;J;n_B;^W5r!wePYVSIlXp2{QHpXHX47 z0GiXjenM=@0@mo5+I=XDBLN|tW6;YBCy#tFRQtaBJwp}$2ILg!d14#4+=R2%VZhY!Gvb6=&DX(9h%E;)VPnNdfv_{Sz2GBK za2u>67jMcYa<5Tr-mED*jeoXil$Ifcbl&GQ+%Kj=T$-)}8v80~ZmTf2cM zaFjex{;MN0O5p@S+NA*W4$H+5Z^C%aWTVV;S>jLms{qNcXYIFA34hCQG_OA+`dA*% znmu)NQhL0Uy#_?EWNK#^)k{f=T(DtENoIcE?ORRg-4YL^wkVWlOG*&W03f{S-N(n_TeU-2~q`l#pH@2BC zX1fvpLsy{zY!Rqk3Z@6L#MrG8;kytP4VlzY>T3}V*{W~Y4s$HKNa5if2anX8MLC{L z$}?Ni@Smi?AM1Or5+w>w5PJlc2sdXo&hxv8LVFTS9%z38a`M+GZWcj%Bv?X1H$5ut z5zBkDjy6adBapAe)htOi?gLw_)`XC@0dA1W#a7OtOP?m;t93hh1MkF!3u=9t8lOb9 z%eY@U%p32Nnh-^`jM9g)>)^x9?HsraAyrv-loJ)0!=RETBGSZFWiJ&LN^z7w`15Lf zB|$P|4hw=0;XI(_h_OkN+rV3fUU7?nXVYX|SzZ`oi^Wd_GFJf?TLi&TZB1|)iOtw% zZv7o56P%S_lbAfLsYvbDUsURp3Q%ybIp1T;QOiWiR*9tP#$$m(*-94fo4IYd4z*jC zE$AM&DZ{wnGOnPw3W_DJebZD@uH55Si*P7#YEVnL7qbK0hI!mGnR@%B2?{9(QnXl? zct!PCL}y(U_NCSp(%PE($B*qgKTuWDI?L7X>L1bVB903dRDBwoit^L_mj`c) z!G9Mx^I-mI`g_$=DS*wq)I)U9Kg;gBH-2jhz5s*pW{3b?8gQ0Hcuk@RP9snp+AKlp zECVu#VV;LZ6{v{!(W(dt)rEpJfvHBcEs?Gcxf<|)B4HcEZ9>RLNF5Y(pu$H??}OTL zb`i4oX&1o!5!L(EjevtRqR|{#t&EuA5Z8>-)`NgvUk6q`DAPYEu+e zH>6Y-1gkXp$Sf#0#~`X=+mv25ftMmB#gpU9s5|F$YsqJvh!7Gn_TH31Ky|?5*OO z@T>5{Id2ZLd>Q_zxtDmRa*|~U3buy*oX*WAzqgQ3lh-4oEvK67fWbl1%LL8UQ%8~u zAotN9+IT}qIc=ZHRje$XTl^7aOnNwk(-1n|Aq!=`0=?OH$j0cr_c3<#UQ_0@J3J)H z<*)jFyV;5vAFrxsBx$}>qIyu7D1Mj2KnK4INYLg@+6}c^S>8F|hDjBl);Mi#3du2} zqM-epNI)&Q+_c>R|Jj78xC%MJRgiyn?JgfUue2PCDwgy`GB>6qeAG%6!ghDi6$mZq z1zsOZ*d8#dAF|wnL$w2U9Ehz4R&(i>ssd~gq>IgsM*7CHs3C`M*MD`WDuZ5s zWO)dyL$W(4_P|z$dbbbuKzEC9ca(c5?4#lnG8Ym50Qx}wCEyd3A3b+({lIRB>W`jz zh)*Q%LpeF3eyH<6>UokRaa{B>yEsN)hzje@X7P0?Eq;aF~j7fTkUK7lS zg2JI5WNFBR$)k;IcO0zi$mifJ}+u zzED9xNndU=A?nkU5fl+LxajxQ&mpGZ!8nKnUW|j4%q<++APEIh$;Ea|4Tu|_Sr7gu zPU)pL27NIBK3kni*|8W^^$3ftm297(ux@>*Fz=HglaYt+ZE6zXLHhy3i#ATWgu%3` z@g9NB3)At{y>8o)9;XX3vVH1ph%tf}qGSU3S`^lyRTYASts{CioR7tB z?z2*2+{GIxi>AesA7ZD%p#ty^Sdc*YNG5!|TNkI^=k|1BjfvnPiCZ{wecw*9{LKVs&SV@8?A0j(dvO$zG z=qhExp_mEOPE87lsv=Y}45}a+E56#mRR~lYiE2GfVW2Gp%8pM8 zl&ftSgiRN8%d5gbK?rmWF%{*quRa{g?xHg2U#0vhLQSfCJ!X%JSt@E}7@UodS(3Fh z1{0bxO&S-*%-pIlO5zOCCa`rh4qdo(Y18aMn>Q_;c;e=+Yk#Q|r2zO83@`oPO!~Tv zI)NmqstP0^Q?$xs9wkZAW9nu}QdI`UOyChIRvNX_K`2wa8YQc7>eHcRDHm!w&2b`buV@9jog8-CjgZ-0WzkfF)COGE~FsEDGl4S;gd3lDV(PW zoI+01=4kRk#_ilA7Nl>8(6E7E7kKJc*iJ{LXwCJU zAYCHv*#CBlGDJriDXa#oZU9(LiaAiFCvwn{E7}C=;PR1fA*abH#e_nf;PTuPrF;OOQ^YnIA9h8-NxjPq9u4PhCJ}0?z zNjhqR>kO_Der?01-v&;#3DV7MgGXCidO*g%d+3qt^rEv-mSi2+7FpBd+V1;Y7_YhD zr;9mysNDj|c3_85z9tOcl3FV6ly1w{Jp;7NuXCLo44cOpIv`4(P;2>eO(%2if*cj( zkld&8u>P5hnE`9#BW!+FQknp3)0-r>Gbk@f9rWfHd;?&LQ=5WU)9|G%qW{%63p@~_)eWd)Uwz1fs389^uj z1Z6PIl#Bu7D=H8qf+W#Ef&y|N09B7nn2974k{MY-z#4tas#aPXaX_uQR)`u+UBJ<{ zwRT-}t4g;ex^1;it5&)?_2;aYot-`z5++Q(?}PDm$9<3Y?Cal%ZO7xO=M#^lh{@1d z5pL(C1g0}P+#APbUQ~_ixM;|QzJB|xh}eZ69{&EmAQ;cd@ZAs(@8E!&$7fA2p6i0~ zBQLo3uE^#Cke+XrTHNy`#CL*v?3Bje^9}|5JHc-_#?MCoGUr9k`T3g1?=vzwucX}L zO5XE@Iqy3syxh|xEZki83HqZnI_g55=WA1N?%}WJ&kHu5-_+2Z#~Uv^{rx==ynloK z6WheEMj`(uy_f6#4e2N2(pEmsQxm~eXVyw=5ZX#OF)m-N`d@c2pC1Q#c@C84XN$(! z_ue>xc5;Mhm^UEbpIZZO0qA$5t-+h#v;cmzxan#=lJUg?RtT)Fs>aH?j=EAaVO?Qc zU142k>QyYO**YnWsW>nq!P+iTgh;TVLRQz6pkXM%%qarqvQQ&hEqDEXvkvd?sHFFL z+>tTAFOQ`F0&h_Ulo(nx6Y9D;I!nMG(}S0Q0>YvBxU>;;RrBA z4|cTL##w`u$TexBMpcDPuLif3r%&J>#{Pjd(vg+ohOp!6gEexCu?mh@G|?=zu)=t7 zTf8|2oR4{gSiS7`8sMxL|8;4S~|mc zxiK%~kb#Sy5mL(Wv~0vFID|TAk-;D;{iee7X#LgJeV&OAMU4-ji)JA4Q3o*>|So72w%H}E#&vDiV^#VN@irF#)af#?> zQ34P9%T=t_;|0ww=F$vaQgG|Nk_Vmn-sFUL!fbNh%{8=W0QO5U`t4eD%UMhz3yYnB z8xD&BQE6z`hCi?+PUpmtSh7fmNH~WY0s`g??W&0m-uT9CE#Zt@#<__CEzH}o9Btu1 zxLPn4%|#KIv`tO*+-TP~Vt!gWI=o!k8$pU2b_Bn*!f=pciG1yp0SxBe3EU9=01)Q+ zGGu{PmN(x#0ETnmn5sEdM-`x{Wkg=892ilOlPWNkcW5Xwu6LBrE$CuMg2Bsj5EYb|KkpD;rtN2^GFvb6fxsm!HBl);I=}NZ?3S+QIPbIj!08zqBDL#GF;`zy<p-0eh@eo9f|AZ55gEmhzHOOl# zxD88ys7{w5&t9M!4JQ0`A6_gxSi!Yj{;LYIDlSOP)!5IPaqsA;yL6$joECeUS5dWm zm@M@oDRpq1NNo-+TMRQvn8V6Rk-vn8n3p>0-1wkFl%H%tscLwqnNhyLG*9?xls5#4 zG1u`HwjJgOx~nxI#Ktq`0hf4>vLkGnm*hR}6i&h?o}|gRYEVN;u3-|`jzk2Ajwmd5xhS z_)>gaw8D~?b-|(~%v>RAlu__k1;b2<*bVxcY#!oW8;(m?l^?}a_t90=d{5R=mnPLb zt&T)0Ki&}-Wmm$pBr|1J9q4c6gaQ}-JQYmo8U_&kh$ZL!Qx?dn=HHvICwQsVbee7! z7$NjgyQ~P4tHOj3hcF(x`k?(#S{DdCEo#F1Yn>X+lNwZOH%RMTz$*ZOj{6!JFzUI) zI~>UTA6m|NTnzdEU%HU?cbbtyxOrWId8nx9Hg%?n0xsn zX|lZ7G0^<8N%wpOXkTR~SGq9|(A0uSws}>h+`j-IMyXt}Qn_NKa>YvJij_+h%a$z5 z2OIAi&J!D8H5~)svEhY9@DdsIGr*{D6b5b`?b1PxSJ*HNLD*>|!)YRi*hxsAl{*A= z{Z#%_jXQT1tqpH0wQ6Q9A1@$s-m*DPDCGdQOdK-<$$gse$-IefeUYnG77LOji@TC> zBAeVvi(siA(5BPKrp#|cDYN?z_vBiK1(EV?hs~M~l}s(v8|S*Hf~Cbct(2WO^M@>VFPZ4J$I3RYr!6rH-F87KMfO{x8nnIk>iX%Nh+& zY}>YN+qP{RC$??d$%$<{Ik9a!FZbT=@9Wp^)vfB@Rr`;cm>9lYhi^N#xSzca>3)emrIj!s-Z| zo(*ZDTgU-EXaY5q1EVDHeSXD7_N6y!?pgzAm`4*)jQ;_WN(CW0PS+W`;f8R@O>pOC ze1b&D5nQtzG|v|{?VAP)pR^QIC6CvDHeRn=_9H~vT_KPO(i1}zpW)9o6QiH=XPkR7 zAjK4?SMZA01cqm76Y##yE8Bp~uY^F>KNHdr*I5mCO;y}$j>P zW@<5wTI__YH}G{FtvQ1;)A7g`@)K9e`n9aoTuh)7q=Y&^MN$UKlxdIDNQ(ExvmkC3lIo}eLh zP!f7@PwM~yN|!)aN;~IQF(}~g(vyq^WOCm18wwSw+3W}0BQ4yefbw#HNUO4jL~TK$ z`yyDfYjV1Cw(T9%^7?4A&5U^W)_*|G1#!2CY}j#e?X#N<06lwZM@_e(M7k;ICS`@? zvEKxpqGaVxmW8k5(7RNJPHZXuLeNQ!n~4(ULdo`;nK|+@A-!rlYV!uxjJOCMH)7?C zhIS0@cLiH7e{PA98?j9-bYW0Cm!#XgT zglm~+twNz~izy9ND^u7i@v^|uOsyQm1Nd{+kvJ1=5*zqtcN_FtGh&))kjf(tm&p7i zz4LVF(xEkSJ{mGu86D%tQ7=nvK*2vNgtYQmw6&(&GJs4noxywF3XYOXR>j9=oGi#Z zcr6tV5H5{!3l3Fp2`MK;jqR5hjVZsG&hx&JhF?%7UE5(?90g{J;M&c_9ZA{2nWpuk zlK?Jqov0Em`V7-V35`2(@4bj9x)A9*F|39eSa(v?0Xp#6hH*MzpgR_x^x}NsC*#I$ z7!dZzVDuhrH!3ml&w%$I7m;?7wb|=g_H!j<*w|7o%az(K0RC1_^mE6rIOwLKg4$fu zIoR=_P2SD*&aLgq4e-1BBzk)X`bfM!bQ3?uwqAxJm=!9`pQA~RsX0Dcm-wC-%l`gn zl$HkbPHFy++OmZF-*tokt7M@6qPQehHF0z{asN*PXBj6f5qKY(>ZX<^g{Vv7mOfda zU&dq8h@tR?6hI?*d3mFNVCg{%nrjKHB$tYnDq(aVa9;o%fUv=d=oR?(MG>(;SKivK zz+|vNIdhtbq8!2n$}C(9O!se(=T}RZk(|5li5rw~9e4YXgx)!QU2eN89NJ`rf0L->qWR-btsMj!= zu#a(4q(QGCS?*T2r9>6Oq)n?a+rqDUC^bO}*$+>Vp5GJq*+FFb%A124LUNz-0aPok+dz)q@sz*4oF5TbUQ5#a)pdfOfX#0p;O zH69znW-l_Z5LVebPFL}rugoqz)?>M9;$w4<$p&FiZb%pzOd&nm1GgA>gL0i6;cmSJp6sM$AK1G_JaLZV*SFu1jwg9zS!hb_L1pn?6gUkB2& zgkL=2rQW6O+Q9jPBjDD5@&@|F-AJOAxpxNQ$W_1Z7;{l+nY*h<-5B6|MKg7UFXoQJ z=DT1yH6vp}Fo=uZiA{Y5>0Y71f;;&)4$JHvT+tBvJH+paC0oI0ayQns<%d!HyaXpR z-l6i_ZfCu~r);)6zt5-M_2ju~D9R>Jt)%DKMrZ%1mt5CLZWBrI-5d|ZCYXi%s7KhG zCTR!jaYrChBzC2z_ApvNIU4TgN%zM7?2X-{%{N7v;g){5)4o6s3G@CAKd`}WjaJtx zL@x~R6%6wo27D_PD*dr_AgvVN;f-9-nMd8oZP{)wxoo>CN&<_2%a-`;EBf*VC}+rB zOs^?Q`Yif76QuM%K6Fpn6>$T3VPc3Bg4c`C;0_q&`v)m?#l^1%|C0pZ3Hk3}i06Mp zO8vvS=07w1vZHk@fdt@#DnHj-A+Heb;*OaK3BbT11NVNDp_^rX8n}{PL`A6G_W`?; zJD}R>v*^eO+%J7PbOELrW#CK1Am)BlNo~X}s1fNg$X?RYu<@)3hK;rjn(> z`|4=by{WY$FV|RPJ#LiA)3(B|h?~<u$w$Hl<^H+(YZml;qsRwqh^dc$4N!Qp-)ixZPiunr&wUt`?}4kDMBa`J(kOTDyWz~MP(AI5wG6HX z=`D57=mY1K8W`k3ouF1#uQH_%;*MkiKF9Em0ptFwe>>Z28nVpIC_fu#Eh>v{A&xUj zpD@Fc#??(XATwjZYN8~Rj~?W*&f!`iHed5AT6Bl)G6V@{v*n!8e3YEK-lX!Zjpg*k z^+89zaU#G?vD5?wV`{j}0|w%Bh501sTngrS3%f}?2Bh#^AQ~Wr4$xlu*pZ0sMyJP? zuPW(TXbk)`LhCuZ3X)}-|s+tV0>=9kI{m%U)>u}vW^PMa`omwe@dbz{#CMi3*Xa;gFe>HYp| zFyI`kNFJzZjew*=yjwBa4XaOdNt7g|!s|p*7gaFFI?}iF+1Razq2CEgi=CvCdREbk zdu6KRd{5KKGY=PB9z)`k(F_Uf=cLhzO4}hLTut{ckMs2VYNI_J>-5$@1tcTtt-jW92yLcY^mS6#I-4D+vmrnbJN*@5 z1UdJagm9iD7VC%2y(ri0pH1v~p3sPHw-;&Ea^-Lj(rx<3WnHQYut6{wEg#*=GewTj z&07fmzM4niid|c|q=MLnb1_Eid5iFC%!2Q@Ot2;kctt03^=pIm7_MW-li5cry|y_7 zJ$N2J>l@xKUC|T3BBLY-nKg1J&1hjOOi(5)Owwdt(BGnla2mF8Pe^~AG5MON^ECb{ zfm69f1U0)uZqCcbPioS|jmOjbDgdxaOwTSr7(%zBi)l*h3u_Ogr41If#$@jOG96?t zvB*Xd+UM~GAdePWOd1w|EOtnPXqb+}1v6O~txQ<1h39i?k*Qahq%>#Joef#0Uti*I znB!PqdL^24aag9~q;qlkLcec{$ev)ni&xAVAugrL?_{z@p%RZ!38qJ=Ju4zvs+ko8 z%cfDv&d?|_iMP7G^9&n{B(QacVECm$yiRjCiI0r;>A#tZ{+2P5;S=zH!6@fg1l7<-O^2QcmLO5YF@7%DZ(6KSJ93%Yr5Gsb7LvMZeqMSTtOkT3F8WmYCPMSbgLLQZKE0~n% zk|UusI-he}URO++JSSRlkp zsa*p*P51z;pK^qb?sIk0hR`jEXg6nUhS3st;_k7Y9YNVti>xhOVIiNIjP&tlalp~v z%pErmn6DS=27s=K>LImGu=H$+BIo%!Nw{Y<_0p0IC1(!(9F4DzfSve(hc13foT6@yeQIzT1rk#s7MPjV(mQM$L`8(TpDe9y@YB_xL z*f#G^*HU30i)1I!`O~j=hJj4060hMB$;i$%5Y6bLI=;2o0Tayu)@l-{j%kL_ux)<+ zThe-=MF_wyJN;w654tiRSGi9r%;?Qn^UhlH$R7qeS6--j$-F@7saC#f7gfc)jkBs3 zXcse^vmbJEm~iOV)$BV1PVUz|Hq?60KR2{=%aPybe<~2uzYTs-{~uPNpR8SDItg26 z6GvAAYbPZWXJRE6!~gSJ;^(@7vz_CAmZeQO?0@9HbaX&h0b8%5NG+kFTsBBykn5?C z)99&OpvDzb%|=YqvQ02|Fr8mO2ja~QrgkreW~4RIVX|0Ady|J3N3$%0DItC%;(bC@ z9ZydK1;UMII45R%O?MsdKXV;#aow-y@_j+)L8Wst8{tP0p+oO8hZK2=N}3%Su}2|9 zQKCZ?qVBWAe)&IFzOJGbJ#tvQRCsrylDY^=)=rFgfR51@pex%GM3JWFVI)G9AWKuZ z{}vc)Z=sP6-Bq4%aLUkKY@86B&t5K7UatxjR+$(E}GcPuD?=B!h z#fdywCT^fQ#N@6zBvPc(8O{Ov6CXY+H@&VQMolHRr04*#NvV006*1v1HAJ|j>Hvg8 zxfNd#!x55VW1grwK1CaQED{j2@?xoqd>CWK-i`BGpy3!PGT}NnudIMb@S8>oh3CX1 z?e!aL9R9D4(wdi7jd@6C1 zE=~UDURfaj_80eQK|UlbSB#CZwpc~_UAg$Vhnn@uVNun@du%l=)Vg>(9$iAc4KWX* zgvjaTMG;j|`qm?~91#F59ezUWd}h`@`sZmNAR&T>%Ge6`r`9c@MyK$6ZIKhE+Fm%9 z{%yz3?H~`x6+ZemV4utb31R?D&{e)E@Hk!BCjTZ3^N0{1#eD#IKhu35`C>Ykd28?% z`~5Hy#HlA-G@HG1X+9qgg%(xPd2f5@Ej!OXcp`f=C+}}yZ`4o^OtKej(N~kK<4AEQ zoNGtG)MI!eujCsf%clIzNP$15=?GRtqJSCi+9gt?xO?CbQQ|nA;i7unNu7@;&x53x z#0PnyUOW!@n}2M`F1l&LLuun^XokkMKfn>Uk`5)CE5XFufPd| z)`Y{f!tMw)-65(sM6mP(!2IAazX5bUgt89t2*&vOn7@%heUnf023UM?R$kF`F*L`O zKN*8=Fqms!A0WbH6WAs4YMHNUan>~xv3~!Mp`X#Sa)s0uJO*~|;K8FHz}t3@rJ}TV znOv57*JLJl)q7wX#8z#Y#u!+vw}U>y$JcvfV2U#1A!N38BG!cBJ9>hXLcCG_enqmoCU)MS5SRnT3)0&|4mUkNb9ONBXWc;9rk@ta@85=<{ZG&D z|3uCou#|JOF!{kxV|lxu#H@b-<)NCC9FhX^m#r2jBQi3IcaMOSfasuG{-HuNF-Q~( zacgGFisO`XNxCdcS@?HvHEk5uAJRQh9|tIx`9LVi%sBJR$t*E_32B7cG+W#^r!KmruNtoYPM$PksL9c`@XeZiN3XEDBRpU=9Aodigf z)Pch8T}UB!;k14U`lP~zlc%1zXEOu!38%_l94`f`vlb$3gY^DM zs};1!4O-0hvHi#PtpksQJs&6Nd04BPE_re7MavRWFOX$v+4j}Z(9 z)M1DN2fq;S9GBraYBDoS?y^#7%}j0jWI~T^)%%_Ipw9wl{PS&LRURO^r=Z&7Tw^f@ zhGdq5@;g%4i_7EuT0O#u9?>q&@Lb4I?1CaW#t*<4Dkm0)~X>!h(l8bnay z)`iEM$Y^loK?CQykxvVpo8_HRbv{`KTBJ45+c11{4NRz99lLz@(-Vx&H9}iV9z_kW zzebMNllEA^3vX@K6e%(L^M|ujo-wVV<0%#no{I8QC9^PJ5=EEIHyqu9K=!|-De zLWDO1mW44y1O*ra8KS7t^wVta&fKjrr+uC%#RWoxof+zRoK`@dpu9= zqWdU2^M7gf9(>_bc z*l#==Z>irbVb0|DxQEyS@u0MG%oD@8pagh~v9}&DJrQbG7*@VntK?R<$5fv+s#vW) zC0r7}QKsuD9>H%We%Aj1_Ys`X3fdNe(5Gz2TF>DTd#7CVK-CgmN7Nvc({oQjPegT_ zO!jVlhoFzk+mQfb79}1jw?}&DN~EncS3P9gDDkPKO zIbpP`54zzlsQq*?iG^1D^eG;v8IEnYZm+BC`}^xuI{-=d0;1qRSQ_==`YHpF(1^g0 z5lmGUbj%1$Nof61Wo)rllT5Fi8}yPVlj`*{90#R~oV2~sKShNG(E_!1jSFb=wved= zKMs_8t~#x_L))sZ=&Mp8^$pJ4xm>>4>pBb{@1L=kdU$`n>5EutM(+Nghd91+{?<&9 z>7!R@#;)JKWDa@{VY9xIRxOrj${Mx6<5KCdiEpT`aMt=oW@2NI*07MTDH{5I=~75y zEcS9$PS9Rr!vg9CeHvC$zrLR0%8D+k)n6O*CT+MmeVB-78fHIo22N%!=-wi!T)ZL> za!92Dkr*!DW6hE6wusXCs_8z@OImO)>^vIVX5dt6g3SyYe2P?%CFLCUIxlLEH!cy6 znUECzuwuNzGUP>G&GPRf}&3( z{+QHbd2Bwb*M1jh+#}5~QZ<{pj$g<(SUjf`{LFB|B>VtNy5TppG(THFekl=6{>%kuY)$@2a+J1C<$Rrw9{<7)8Z((->F`TrgQ`9D>X{l9vF|7azZ zt?aNwka>{!SY5N5SZpNSlTvsuSZ0eK0<=PjWmzdoYH+N{3dG6Rs=&I8ylJfHic~*gy&zeL%F){4?cIL@$+ck_fx3LD`x*bTZ~n`gpK zJRv=|onbnx7^==)JKy2h@`PkkM@jQC)OjtZ;EJjaF4a6^)&8@^YVBoWC)(GHyd@&h z=S86{md;>Tbb}pJWS=xO!JgAk!D_Z@ys9iOV-P*{UIwY{VMzdv?dcq{RIN2%B)bA~ zlv|w~P$9nZ%D}mBPoo88EPG~N(~e7%hm@^TeqyzxSgf#JrHqw1G*0?T)f{c8v2&Iv z_r_-r6>FpJ=G7OhScb%-Q9NPKEX9ba%P)av@@*&4T@mafpAR4!|jHkL(k}Zup?$ z1V^wq+4au;#6@a*MOg3^VIJ}|7aI1NKEch;UCQf!rv$($^#m#j+7Kp4GK(Fv50miD zfjMUm%N_s@yf4y;%-v$iFARdK6dot%RwO4(q?{9Z=qvg$A`tIR@6G`r9Srs64^%7f zXiWZ!CJjqQ7bVV%K+pMC@7@x?&5{_+1pR7FoVHZVQ39H*HhS!E(tkqajILIe5$#IG z3jO}KPudt@ej^bCNoZm;1BA)1pu5k>QzG_W@3d48FZ7kQP%a+)WE=@gOZLB5iAjB5K9 z+>!JaFuWV(=3WB|?u(w}=RDTnsXPOhndUt@w|Xo&PTXxAp8n}o4|s6tI`dO5tAG6J z|1Wm@_j36^<)Z$3x%^Mwzc^Y3vY#G4Sns1!wGX#1*eY~Sb;BGKZLc3`(Ak{If>4Ia zodpfIS123-VS_6+eYbDlC-(Rf7JrzWA08hW9ImAt*$#3FNMW8_r-)jnGbj5%1TqS# zu*oHO%vJlC6^0&JeT|aHBZbmTv4y(YL3x}rS82HApuHW@FLM-A_O#R;6N+EIi6x{m zIc2*3{)8>2i5cTEmQ1y|cMngJ`8Eobci}0}4afQOI`8K_LSz#F;8 zfAId8|CaavU!m;3^t%6fs#wynQr1>O*-FJQ)o0{)PXcJR5NGaU&x$$66%W-l~ z%PCQc{s@ZZ6W@JMB&MC_oeraCFrb$G(5&s5gzGfFqH|C%@^{YyjYmL^@r**$=eL5A z^$RIh_fQBEEvMA6wzBN;U;91@xyECWC)*4dChOM05WB`*3|4K^fkx;ll#y^hgzo{< z84lSG7gyJ%TfT`453;VjxKDj6w^TtGoOtuu%9zTpxT8n0;bFqvG&gA$!OTtp8paZg zIf+`-=h!nq85l1j1Dc)7g%43;&F%TTxax_Oh`G`?WXg?|rG>5atrgDID=Vw#=4V*_ zsTEHzrTMkHG}NV~IbIsf1)|;0%byGuFXVBn5K|!-ET1!T?Frb=qkbzFx$Lg6RHPS! zM59dH}*_QesR8-YDdQPiRg=*ZGF?QvQ4=%)AcqppqM3qyE$Im_jVDmDu0jL#W# zQ{$yz1uJm}P)tye#~pz=shWLZ{uq2dZm1F$R{@;euAXDmQ6rH848)<@a96zUGXGf4 zU%9W&jx_P|l~abc^8 zA%L=}X!Yk=nS-ojt@_l72)SqCFbHZUHAmgE5}XKHQX8|Tw+daV(-ZQDD#L-HPzvZ| zn=q(N&F)o(uo}2el{7_f`kqKPZ!%2kQ7WgzL~qVS-T6~HoHJIuIKBrI%bqAYZX^By zRJ5OF750Cn@OKh;ceegI?aE2sSV9UH`_#;w_6+M3=3i!zwq28iYd>XO+bg-PV7D|xn6)nUUM7(ye7qSVR(hHU6XrBSkF*RN+D<8lAX*fXh#S%-=u?zPt zfIBtu&LZ(juy~2jgq$6soyl64p96zcE}MTQEhLa{ z6B!O#B>vEUxhtH%=0Q~bhouEsGc$$H_M~u&mBq9U$t3z&e)5CO~AaT%E` z$1rXs;`=^MKS_RwY&{RVpu{gfXM>TC7CaCqtciP4yaexi!|pWWW!ui0gVX}%jjZm3 z2L%$2QJK-lgCfTi`LLUZh~re8~XcXtz+dVi&ynYM9u4^J~i_+0)$$L1i3$Qi66{IWrO|Fm`pOskM!yu*8 z&vQ$vgeX9+he}{)v$bz1yH)W)(fApVCd+ix8y!%l1VxZz?DsTG6%?XCY8>4-lf?4v z0xiuG3Ok|h2xJN##FKEt=ZO?Ni6vu&PZ7v5mI7GNN;&I?3ou<|@SlM|6EiOX8<-H2 ze$#DD^tDdG07VJDpTPEMj|{|(`i5JZCA#w&?>0;6CdClIuWZ@{U)I1zt;MZMxlj%|~@vH>Ue*V4cIy_RnXN<@XArP$>k2FH~M2T(!pK>r4R zs>dg<_Q}D{P906)wuF5hptlO6n7JJWJMu7Ijeiu zQKa*Fww3>lz3$cOt8$VHKIKBF(uM;MTiky`{2uBN(>L(DMbNM;j{so< z1v?ssONt${15^f7%m~T+Lmf(c0_z1-37-S_z-+-?C~*rt=NN`&3@ZS-D;{z{I|mI7HA5-j=n?HtAxVMP33E#wCsej?bq}I<2s7tjQp00oPdgP#+})<4uY5iM%K(c zV>{5R8qJVdGk>bgAN*)WXU?8<^T}JRc(=FgJ>3HmZhPf4TbN5Un*3}sA*{_>_y#F# zQ(h#+Av-ll3ObFQL#gA#NW_x5U!0FBRB4h450c}RsPP{%fqtMHZ6C-e8HSK@2@Ad% z7cIsPwVH#~aeKq3b?n(hHwcl*h`5#K!axv&U>D^aM1_OYkUfLbdb`%XHsMK#7S`cW z%RmU#A}=Dl0GT9;l1GC!(8#=`_~8bpy^v0M14>*nB8_V@QodFW^+J{|;MI+o*n&b? zJ#r@;ga_D%Py1A+2Jg>{Vbtc$-_NVBVCv5!O;2*u^*sR2l<(ImPusv}t1#I^xpnt5 zH#d4I57aSI)D8i~?0@N4LKE^oaIn4sMZTN(DN^JkNRqryQQx`Ahwk$_)dX*i`0QXf zl7uOnd+D84d-C`AEI7x6RUD=&DM6hoB%x^{1jq(|9Q>k3e!@q}4kp7#yiB;eW1kV* z*jJJqB@+&lw1uW`7aeUSQyMJ=I3T-ndGQat1=*bwOP?IZTjZ9y`C}5BmbopAlM}^d z-K9yiqoZgNB1yWcL|q9@piHQ=#>%Zry^G@`l5v#tFN(C1O)Jzi4-JqPB;WAexRb_> z{sxs?3}CN`ofHCTa@pOBxC+TqX_w2PtofRew$0C0dE$DGl9BffAH&zxrh)5ULB_fwIIo_goO`Zgx9PU$E4=T|J1hj4`F24wiX~~ACgP0s z0*TP!@7Ig%p6@poxxR}S^Q#aGjeJv0hy|Wt&6D5sK4tP$KFB5Sd+#F!bHa_7CDLgP zQJjcOjkoJ##qUy3W9dUL9}mz(Df)|?Hkc$@OczZlbWWl&9!!OQ+b!rZWinK0OHi68 zIb%&G1p&E?K&Nzj5GNcOdu^)}tNRAY3*}Y+&;yS{7MiY4 zI!Q4x@`Fd8hSY$lvavrvtIo-0ozrD<76Nljip8j-UPJ7T@L?`LezIZsx9$;0?wkZCWf*3l$pl{C zM$S=aebLZkYILZAu`Zv&2=$L5chB&NXHkzsZidr_uDTYL!{9{%+BYR^^b=8}V5Z|F z`I(Mvt1G^^*3c)vjr%gAt9OstQz`gR&<$7dG4vFz767gLbBBR(-?|8$don=yWnTe0 z;~nDVXWg$xZab?e=UT>6ev7R}te#e1>NJ6Kfv$g zJW;$nZ4VShlgBV|v+jrigZ6WbYzM*3&QS&2q6A;B$dP*#%k2?XM&+Iz??eTJT6Jm8 zc!>Ky+V+f6;Y3|Y_E?BAu`1+9JI9F{ZC~|%AI~YI;Q$cL1CA)sA)$lS26ie~z)k2ng)C}V+biaSsr zt|xqp*=~Q0oR3whMU+hvRGd{(y(YKJkGU@!$PeOTy1dJHuMmGnP``kXQ|K;;4TK#e zM>_n2QxebgA4L{zB2mD_&-XHQv^EcIRN~~JP^|#CO9y$Q*d9eLUQwwxLMjR>Ih!_Q z&yXB;xYF^H24~GZIz^$`0O!wkR1g`^~ppB92u`;nb$&!oU=|y zCYJtgMZAZu*o%@&`&_WMBj`F+XUdQyWDX0_M4k|u103}Q3Hk}Y3?1q&;Y+_f*fMK!Zpl}s0PQ*An47W9Ww+aVUEXA zBc?$|@w`p5a#zx!O)#AUQxqHK47Ztf;H{T7yL`o9@kCw+$B6l=&S7S^L(3gbbZyq> z6*w3ej$-G#KITgi=5v!4aFbae5$ptwN~vbuA*yDf3D_Npi2x6|ldlH&rRW#_2@nWQ zNF_iYa3?8!M!rU9GP-ISFuc36*a#YnGl&l7Rz6k@y;HEyqqeV0*$sA=S6JOajp|FL zP_P~0E>(YG%wHS@f-XEjY?w!tHyXyv4onjq6q8E_<6$p3^#-BKN82pFc|>r%;#Z*{ zu1*Ls^IiB|S-AceU5Gsz};LrYz&;undr<+>}*V&9X;qw{&Ubl_x~YsWbJ;2oJv3cHW6_*GO>5I zu(SOaH(afxWrd^w|0SE~EVH`SwB%X&Tu}~3TTEvdfiD4Bd1`w?3V2J9a}hI^GR0v) zC-SNGRsas!{Z=^m*Sx+=L`2VYdh+!s(||UYx91%|AE}vfdZ#MD2_D74iptrlcZePLQfPUIStgX@?JsTmrL2eQ!h_`{R9dbixWR! z$hB;Aj8rJ1!x6pStgYIoBw2d;iOq}wCp5e_qOi;QM5b7-`j}TnX_{JpO;TYa%s2u5 z_tP3Du111@QG+*6y1l@%aLGQ6m9VFv#Yca^WNg2GQA1NfuO&`K=G3EJQ5lpnclHqP zWsnEU6449S`yD@KtKlAH&8?cPX1p@d1kP1rE@rE(Ar6~#TC2rQ3jeWRD%mV|N&>9F zGVMA~vhhNBj1uGq#Sr5+yP(rEoOuItRMp?G{#4|PlQh7M2bPgb*iPNj{VNx(senu9 zj3?WPTk91JcA)2&+%dbdwr8nrFU!g#QDi7|uvgEv84y*gC((B@kWikAPn&t~l{2|D zzL>h4>+`1`>1emY!9N3~y=KNcAm@xf$!Ir`Xy{PXat+6Tg&^n2>$LXY_Ws&)n`=g-*(6qO*VF65wwH0ry2){)cGl4z23O7i9Q8{+4BD;-SHukwl&^K4 z+y(hzz0|D|t?%$A-|-b1^^0823n5z1PKw@|`H9rWo8HIUHfpDJ>D;$b_pVypx5G+p z>&v$G2WIWTp2|l^wqF7P`|r&`zGYdIGz$ zZJvYDl!BVPkxM-LQ16c#7EGddZ;+NYDs;?hr`Qgj_fD6bomF&$#ppJocg%Cqu094k zV&~Rrtj8Ch0bRE|TJ#&(l~byddr?;KRYC#2YT_LO$(SeCv7rMv+=uyj>A716-xhXM zf2J!~5pM)N`W>jK<>tr7r_jzVn6r68Wfb+?a`=FGV;pSU*wbD45JoN3+SZs=E1~xg znW{G4ZS!87@Q|?K=5$JOD_q4sl$e^&E8wek^TFfVbM zm*Gy}?z&j)CKh;b(G6+BDyv-dsO6#KSwb0DmJ3#6Y*X&{-^Y_+7+v1DXb0Veeg&e& zwk`Q(GkhC#NQBzD@Z9~@C{s^>*{wtfSJ zGQq`H@g*}I)AlwTbw`;-ixF*2Ebj8YWjuuh9uOhm*=bhs+OU)4Pu7Ev>{J#-D+;!b zJV`8?LBH4JlTSd1jhNRmoJBkT5;aCF-i#+;r>!%&o#hhZrOStV{$&9gg%H3s{Bm;X>vcb3YUd-nyXM~}J1!HD>z=zQ!^ zkPlx?@MH@yF4?7PmG@bg$=npWXpCt_2?Vu^s1(jF{1lxJ`GU&%NDXo|0kwREM|JhKh zZ!6~}sr2i7fhZI0j}xqS3nB{StWCE(`~0DcQfJ84+yU>5m==h5Xuf`&vpGy`n}t*V z*~eq9bB$kUccTe|(_j?xOyX1wwX(O&aNE6zN0fizO$J z^ABu0bBhR}z9%`aNs$B+rCEdnVArg!jf`@{Yev;g=hI#vEmSuakTG94R5-CY{5RQz< zT1*Ph<%Rq8g({1M;ki6JqN5jKM`z&~?fw}bZcB`Xn-}+%eQQH^w{JkCUnPwd>glk3 z8SivSz~7BjnoOq~9Y$=+uv$Zw+Pw^?mWWLU(&*z939qcNj5iRb+QZaqQ#3Y>l4$Eh z+5XG8Nn#=2+7yWkpFZ=^{mrBOEX}mCQ7QMBKnZVwK8KCU9fCGJc@lBMy6JNgoz?u=NTW^rBb`euUI8PLajN8oLo3 z)VaJJ1a3=&N|d=#9xL~)Jv9uY;;`mPbDS9U!Qu$@SRK^4qA=5X0R$SuLPAyrHdAy9 zCJY_xJ|3WIjofhLjfi#i;%cCwTR9yo@&n#UGJvO|%2sg70vT%+d%TWK2})tE_pQ&5 zH+(dui=+kZcghu0``X@`swn03t7r71wfvpmt*!#RH>jun(^^hM39i}@sjYow)(!V1 z(mb!_e8=+L%umm8EZ{2IBU?q2gg zB&M_ZL;W?G=n0y&uzxjn!b`h*g->@8-J~GwwVKqFT&*$alUh=|EKYoY713aqI{4HP zzE-3lRAFY-V|~QV4nQ5WK}Pp+mq-U==#boGR&x8kv5U(&d4rSVT_>Ro=utQpS(f1j zp=e5%E#z&0(YM^aY=h&~!6gw(^H*KyFz%(>;r2;}(Ux{>ACHA7;kdtO%FdKX!mHNv z;p_?YB_pKf3MoY|;_k*sr&2n!xBlwQPZ*l!$ zT#96qF1f^JEYvr!1Fp)732C@~P1B4J8WmHdyIE=zPJ@HF_DSzfz43!Ju(A{)t05dTZz8YQ5rI6`Vpe^9l48bE5rDnKD+wWbuR-Tbw>qVr^b zA`8IFa(^L^lXNh9`>|i;t4LZQuf>-F)m>llmGire=<~v1~)?8CP5(E_uRhT(C zg`aqJ5TFO+ase4jv?<1V=!V#&%v{Q60BiQNI>e4{#131m4%5sB_5C99;j=SUaE)Nj##vAqp65uUsG=QeyAe9$rQMw6UH>Cak4~C z@n07`h8g#n$4lh5td9^5Oqa$bF7u-{Mtx%@M!)Fu)un~<9fkcRbwdSWN|4fpJ zNY1mI6Y~J*m8|m0VjNSorm_B^X)4?l!dipRZnEtiD0&{b1?Z+_>G_fA1RfqZfR&44 zCVqixy!%HX*Emd~TYLdxC+y?$7iJm6qZ;C=m|&Oix-1&_EE-@IubpEyAYVE(>t7Y3 z>z{fws$^}p?5L})vIkO*5ruTy? zsry1MO(&`|1Vd$OE{u=Z&mmLB_NxX)lIc(83NC^0X7%v+fgw0e=4s~rRkqCtQ1Y*u zU`g#YDzji!OU^8nKmV&sldG-mm~1vOn10P(DK44p9Lf!22NbPBrr>s8P43XJTUi-s z?D)qK_Y9`iXOX<9IbtARj%onc#D zAHjt=Lfa~Jl1SCL-I30U%u8Ad>@}%yuqgMXCv@>-rs}dW@r>@aH7%Q!?59VKM5(Q1 z3;Q??2TT$Z8|Qdbp^U1pQxxmpi7FFU%VOw7X@Ut1E1`53OqxVXV7Pr!F1C1ZqXC*f zg({iW$uJHC#q}J+FImP6ij2=}7-Z8Ivc1NN8>N-bV4xtv6jcS#9tBzb%|Mkyuj+KP zy{Prr>qC&x5y>}^lENY=HAt`<{P3x5_w8TrwvJ)eFmzqA~<%PvbTzaoZ`%!7&;{qyz^+pMra#R4m>FOU4p?-0EY8P7;#dT2FOU{cRqke>)y&YBP>VSJx}7)HpW8HuEWzThu_n(uE7<(oD{JNq5|V#CWmvYFuF%dG>3Cs zs8IQ7^7*Ie*MB4Pcs!<7aENOCPIGQAG05m&rd>f&AEpa2dWg>}y+ud%g&e1*YgJ4| zE@Ebs<@IAp2_qjLBv=d^P^YSqx%n;iI5?L_664-(K06;Q`8e_5hW%`*T)R@niQY{^ zP@3)-#-`SeB zw9tZMQ#9)eUpALW)(x?g&ScU;@h8uhS$0V}Pso=ZIeJ3XV#P)*{@id~Hp?S8w>;j7 z?{y!zDKnEm&pRxPCyT#AlT3vtRM`cQ;;Hd{KCzuzwt_~~@_jvyQ>3U{pr~7-D2GsS zdpvDXB74y{S~;C~=`dp9ERJ~(JA!?1i0NQ+Cc%v_RPoju$TvMkj}@%P8ush|VeOlu zG~KdnBO}AMZQHhO+qP}nwv7x&hHYCJHZrUm=X6zfpYu?os>dDUd-&h?zt&!J&Nb(L zKe^#VxS^Gd{DkcLB;Nfg^h9eK^{Kq+$y=0tOR2WI$y~Z3tesUs(*cP>XpQI)Q%dI+ z?a+Ug)UbtT*_m!fP&I?DWCkUrCZXA>=AhuNVy3mw?IvOHneE}Jf_+!VfTquorpK5T zZ&{b4tTNwTU9(`NJaBlz1wnaLL*ibF+@io!hykI`j6^ssm!X$WkS#uo1&KUaKNDyh z-tM9xP?|?Wx&R5@%wV{Hz6tn!Vd@T2OZ@e7sCDaLc~dUaPdU#Jd7_shEwLJ>uPTJO zth#O`*<(q~n*i9x8c?eqMwJV+h7J5uzk)kJl(|*p0%DLQ5<76pypz*-*uYG(l{b77 zpe*1cKQ9@EKGwV=&m+2JReYdBp=hT7h&Av}g+vcNsArl>o)j@IUKmD1x&f)apJtDRaU)TlL&i)m#< z3%`wnDQkdTI;djIOBtm}e-`}g^C{zKo`29ZeJSMNer&)Kse9Us>Nv{rymZX*oN7Cw z`Fwj_#|03nKM{;khHL`XGu{i_~Uw$&pXHpN>l9-c1(Hs|G9N`!RI z>zX}P#oKLaTXzI(PqOACLeqDWcruh3d<(p*Y&{WSV^>TffYin)JxJ2gBc3`5(sDv$ zY3a5Idgd52^6n9XVuzfJ1g^$xeUfDbW^1Mk3~0WoVU9R@D9TDj4Rm&wY7!!@F0-pLu)31G?$O<7In)JYC;GnuRe!M zTWd7CdOCD|LX?-ljEc7^5Ig<;fo0()%4&RxKVrHE86|W5c4PgfJFX?2HN(WcOSB!X z>lIw)h#xt2j?51qnUpfxc-jzWI&V~F<0-BrPL+9La1X^*krAVV|$9d40C#RkzW_Ssul z<=gxca0o5RSVg@cY>NBuhW_)4_0D#!On$Cl;e_31cr_K(tZ?w=vv47EPP>ta9a^vFnkje zw<&bp-q8iycoYgX$l3NbcO7YjJQ$_nV9V*SiFEIy2Afz0dB=!mt7dS5Pl7*LN zUBnv6;AsP{Hz(Z(p0kgVTj+oPSr7M$X+1af4e%t*(+QS4R4AY?ZupV-;)#?4p!QTO z$bv`!2ApOSiRi603N);LlUce3G3HF3U~qg<6@2h49H&OIsTPnXWtt5iJD*iHoRy7V~}+3{rbsS{`G^N@ZNOCoWDS;1I`&{S$-hO<2h{>C7Ut32$R)~pZc zr_{&~t*uBhx(=ex-4Fzqk*z-mJr$lAU~1d2*mBmB33e#rw7Wl%RUUt!J211_{o)X8 z@AMgpGcT(#N;7Now}O3(fsz#-E|khI#@fvepIN*yWk7t~4C}QB&pabMa5f&%V-4gB zftD4DFVbL)@0pV|owEQRj+a-eP@;h1Jh(4v%w&$>DQS^ez;oL7uN)rx^!VY9UlRoV zy(Ai54XT-_sC}5Cf0y?nsK~;71Cc)#*OjIS5tEF;FJE5f$J6PL514x+Zn+}ftiYwl zGF34h4Dv3~u_%Rs(F83cR-E{DLQ>$&%MH4=Q2O?ZSWvWKqBvIho&{1jceQT}k9sYF z3EOIj^V>|s1&hNzA}?9o1a|-~kD&H^8;pX$jU$QFajC=`K+fv3Po2*&e~4JG>l)Yb zUt&VmzZ4VxJ@by8zJrtbANrKJjVY~yvFX<@5q-li`?C8#wFGxPq($`4u5)@%C{;Em zb|t;uxJ|e|X+VFt0HHpRRW#`OMR5kA!pu!J&T(Rk`jsUE>vH5u?kd!JGh}&I5v1xh zx27K!XY!hw*40aE9nGo2FJ0-ItDA6;9ftM3byt&|KHKl!S6$b?UtzI;i}8Z z>2O#fTL-^m+BnaT;Lv*5XQFNo=&+*fy1-J{fqp)te6}UVZVr0BKDBqa+wy+44M%#~ z<9>>_%ZKv75^Y@Z^WyBB!PsfQLb#1Y2fC^C5aMKo+1@e7Lby!?ink^Qa!vVm_nX6l zx%CB-w<`A};yk&(CV|f1H2Gb5$OUAw?>u(8fownSfx0b49$j;NKIi-4y35C)0(Fke z>L6S*e16n}I$lSBNZI((n*)0{}!YYD!WDZ0FF~WJ|W-W|rRv{#w zG6@>fNIB-mxTR5ZB5d1qO!Gvg2l4IDT*(Pqw;`++DVjz zhCnjPElaD6d(^hu7Gksy!1G;{csB z+TXX=Yb0ypU{!Fm=o2BOl#((XMHN0FgDO_yWbo_~WK}u&V)-$wf&pwU73~*jC`eXL zo=UN$#=(y1E_;Wt>viTk#K0NMUA$Ll*a?vskReirR5TM(Cl{$2;!q%B{;T+t{)F(0 z@6|0ue4&(fn!DoCbOJ?v=aVL4C?j3@z?7cU6}n0d6x_-Klk^hHIWTulJ#V+lrixn!8B{6Ov@3bE)?Zr4gS!3zNH}L8k%qNTYOygK3(M^_QI=55N?CM){CR6iM zS~)xhHb0P08-PJ(^CH^1cEZs2MNt6B*1rk9pbxGiiVt8SYH021;(RFMGV^RGtPP_f zR-Igaj=)xB%n~-YjNi2SURJ3?y+TNhpGeM##tBBUOz-h3b)-_msH)(6mrFA_sIce{ zaXLMrvbEyO9V1p1VM~!)KS+-7QJ;vnCefua0Hr~N7eN$!4|U-^^t%c(8_@Xn6ZwYo zO{WJ}=ndW%;l}h$ctH22ChX_#6~TwUZ^RQSu4nAyN3d3|fAp@=GO3XM~iVxn^?V(FsXrok2wezAVfkP=$xjZLgr_@q0DKJTd z6&mIgokJapI2ubpqidLcGBL6-w@jE75his5y;ar7P(30V1~oqHJxaqIg29sHIEEx& zpssx@hinm{B*|`7!k%`LQ!AwoAzkjsP$M{CCRu~{Igx)hRfFP+QM|OiBDx5yynyiG zk>VXBBwM`nuZ~pp>RW=$sgj6uB^81O^eQEzZzxid<(%`kYEht}BV%G15wWhqEQwj! z$#=Qx8*M22qk%Z~`s%JT5Fd=1Mvg05?RM()XoAheo{C!y4>K+U9eUmQ_Dz^B_{m!u z%4kLT6dy$`WjmbI#`n_N`%)fjq$Q7p2%%s11Wk(QuE z2f%+m4jNBJ(Q=HZVyW-65^PE^(Nt&?_C*E=6g@Br`+n zBTNX}StgMUW9F|@tw)UCmeM_4Oir#QE4}v}?WgM11bOxQ%Gq6yJ3Txmysb{`-cU%g zJmYp|s=W4RB2{NEWAWy{LOc0FY}OXO&L4kRIr*ybx}r8OVdfZk(UA4TG{v)}EB3Gy zU@3A&oz+wuf!H%p&^V7rR|x3f-6S*bTSLa~auub@zlZCtQn=38`=iV(+2;?HI9g%~ zPCA?Bc2pQ!Z?-o>Gv~L{2@ilux+BRUIN$r;1mwHk@iHql!(iXV*!ZNtt#FM6cZwCo zQamF21XEh&@(ON_rEk~Ef4#%eJ`Q>CGyN*Iyxl?TWm{R`mLvo+cAGFxUGefoEW)za zwyLO3pS@HI@OOH`&v<8t-4a-3 z=TL)b5@#p71Yk}qbO9^I2w#aT{c?jWpDVlOVUH0icn(AuS?P3G!p9?NwiYU^?ah*m zwuM-1(lV~QnidAH-Ln%` zFW3yTKcUSMVhBe!DHhcW`hRN$1g#AXyntLWdF&TwJdamlaL`tqIY7@noxTD0 z>Te~`iajYdzf5G)-~N`h(tyjeE{L`r3J&X77M@I#tySFdcsCjXMnf zn-kS$A`mr_4kVHuUXl)ZaX~YJgR1|e3?Gr2^kAs~yAqC{`^W6DOx2JL(+)qwX`;~t zs@WiB(Y34DhxXbh4$&r;ruZ(WJza=(0#Ob_D4;h=Dq&9b2i8C_(U)Fu+_{h=&XRUE@*6oa0f=Ey= z72>=$bIVdM;ECN5zo8+jNrIzEf~84-qsh=}I@3*B;)>c6cU|^orZ$=M*p$X#!xT5z8&bjtY;Y4P0N_NZ~0cieuIEDSV$oV)u(Q3pwesZXZFUQ&26z zcQEm;Z1YL{E|uAoFm6Y~Vg78VlqxfSpS-7#8f5tSeVtJ-q3QRxgG&Eg{(J1B4dr8mB;WaPN~uKR4yFl{tD1Hb#lf zBg$)X;{!~5^sUL*ciIQYks_Pt2teg-w{5jQU^;!Elju;f#<|$9^d<*Ji+?rubg(mT zdNUSSc&IzLD^&NC+e=v)R*~JlAvP=rO3F4XAP~PBt3BP`-_}8}^Db(9z&1}z%_-KL1`ioO{ z&f4uO=A#2Vv2>^F8^ZwNH7=j9B%kU-0TD%QVCJbcZB|hgk5aHlJ#$GQcb zl@B1`*&tolb}X@xGw7A7X|yWluc_~8^Lvg@W!e%rja9JB$qz`Q@h=Gqr|xa2H&b+5 zH>;x@`FOFN8kkdK4Tj~H-qY}((}h5^x1T-Y9vOH7}%BBOakNH~ECEU1O@Dv?d3n(^|n1 zT~ou?E%q!(E*D8`hE$egopvdoEKV0x#0j}LvWve#TzkJnNLjr$8mx!c7Q4A7;M#4? zhq3NpdUz7b%(Fkv^cn*5IjP8N$}+N8$d;ikjd`vGt_L_zLUVrfa&OhNcuhI?&M zyKv~KX~U4{@FC>r@*(EvhES=-186lPXr@mJ0wR1@Ha@zZEzNDx3hTOvJKOd!(4u|~ z=ISAd)yK^l@`!Qc>oV$#vcKoz^Ha_(7Jpb+D7(fUE;i_^LN7n(7GB7(P6r{gOY%0*9mJkgtno<@aU%HFk^jY}uit3)(aw?hb zDAg{g|H2G6DqTWqe8|VoqqWr-a_REWWAl9B4`xD;{c)$mM<36-BD%>*yt!zyKiFARJ&QzFZl0v;%&DoSd z`}H(oyV6a-wpQe%`n^Rv;YF34H~wS|C$ZtCQFPGyrir=&FyeWE6ouMgMo^WX6{rJc z*stUOq7rWUD0yIbk^-qHdU!(vtU@P^_4QIrm5LPkWTDas$Pn zb8u!nFaBj>uiS9(R!N2)>&SiFVeV;Pcx|n9>=3qhrKSgH;MiV8TZ7P5IB^_uMdRot8`MWhPlLE|e+p8;NOVJv9Dz9?Ah4et z3f(x)^^4p3CGyC;5X*qDp(n9}KZ5$e-7_EmKpF&TZ!Y-hk5i3imM8m_D-LBQ+~!~B z0<&AiTmepjtR?`fVusnUa1Vk~Ck*<+{G*&WcR3(p80*L`5<0s;xFN=f!1vD(pckX) z!|AWc1YVGTRYm`vnfEVMB<5~s>|kf5Z}X4v&SHginLa+aY~dn5vYq!AnDBah9`X1c zW}Y}bDp{U1s!0WjHJe6lrnd}OA3t2E1FwBgH_6hatJ%@!E2isN|ks}{aY)Jg)ww=%cffVvmQijNb znD&%~$Vc#&@Gy6=_PDBqTm9UySpe*41;}4?MLNMX;kQIOzjwfI_1k)^g$9oLJVF0K zD;1JBv^H&`LzgHeVc*w6TNfKRL!hm1$c;#L0)BD`fZ@H;3W^0o%}U!tQwusxInge|%8uvJzW$$pMJ(}U zO7|O-pMat?VG@(&dy^~nV3Wl<3py@ao!QS@k6WFOCLd3)tF{0p_S^n}=}6ut*ibtW zf$Un%_LKYw%hnrqdcR6kXjask?8k=?0*fa%}HB6!*`3Di6l#w)ZO7 zQ*FV15-ZguZXfzPB%evDvfOTmfrtz1sQT13@`**(I3e@X$O;8!RM8PZe5B~1QMD;} zZQ3jf$sIDsGL=gBWP2jxw0dkQlQbbheczS{Xrm1X0YjU!REWsixuHY)?Z}N#e$$dS zy4)zLer|5bq{_lN<_`z?dEaf}+^}8kl$5ix&A1Wf zmuF^Vcia+JVMX%YrggWuUts?J2bx+ke&Geu_n*xqf`i7{D4VDACG5-$S!+(136(B< zYOn7(Dxl||>l>fD&JXLYlK>&P1T6k$iyW32V&}u?@9D;^h{!RwLo$ zk8IT5a-L+T729R8xP3VL@r@@ff$e1NCEM8g4Aqk*^kGsMq&NO4mn&*AhQPof`GN|R z-Ll{`^R1DdED=z%fO5NY(3wTFuf&SEfmdcsiL~=-gQ`%KSCz90$=#SH?b-yx>0b+^ zt37bJGtbUlycAB%%t0C|6n2)@!t?WpiJuds8p>x_2Em@z`c?|t8c_n-`osq6D$U#G zsv!h&mI|JRg#&aOlA!{c)edb3Cv?20uVWPtn$pA9bk%zA@4NayFYdzn0OLkZ=yPY3 zF=;gtb1<`2VvT6gGAxgf2CLiyxf#r*$Ck4gJH#O;nJf)~^G|U@j-pJs{4KM0Pib*X zhmIay>P%BdF7Z#;quOe*_B5`~QhTZ^+s3{kRP~{V9byMLQeDMSu1Sir9zaubj&N>Y z97iIhuK|+pF2)0NesN4V4L-GYkFcOQPHr3$<6J4xU^G*Jq!^lcQc;mT{`#Vm*0EmH zJ>8H8nqd&Vj004zF<)=yF-WZdMzoEwqo>|5s7+C0!SH+^5%zaR1r&AxHmH(CV+Xwp zhLXv&QZch1;t-EqQ*nom81d}BU(d>&-7IbzJ)3-6Q`e&_Y$M$~d32-5w<;?W-7QL$1d8nxH zTujAckOc}#D|_D3%SMt7nk<;|*P~od06a;p^*IB9MzoEe6K}lRUS8c@-`RTc23*3l z1)j=sY$pT|&UYtPvci)`AVwJ!l|`1T5NgZ-Nu;bU&i>ldHkL+v3n9vK4g>=W z!dVmb?gM$zvGrIK+*y1mn*H-tJ4P`#tM6Z}*6r(Z{hwC*_XFVh z&ksP!LEpyFhoA*uDI`I(EntgckA+ak0id zop*Jdw{IUf({omkkr5Ip!5{*+BNLtOv=gsKXP5w5eN2Ah0Ht8wCC(}YGmXIvm&FOGO%tTTBL1oQ6%ar z<%2ClBQHLK&F30@2MU5ws$3U57MR}c7Q{w7x0Cy|3lnR><>Kkf8Srb2O94$vhEgLxqKw5mB!6fU$PNwQ7LiEo1@iXb8gn&L7pIc8d#|z|O-wy{ zn@(k=|NQj%{07$#35V=z_DX?gmU=GyWFM+~H zG_KY-V0s-(u2@yE8gnVo9v+=dPq9{I3fE%k=Gg8n#yV5p{Ng*?hz-MguhO7$X**{z zS1+;#-MwmtgWd55noO|26-}738EafBgZ4|rN@hnF-1}GQFfetP#7EV3U5a8?>1HzQ zB~co$Y%nxA46Ww7T@@GDs5z#i@k4PG%xS%n0gbwi0ff-fXfA3?4q_SS$U^QR7BX%2 z(eKZPuGN>MFlTI1VBHpY>qlQGb90(XELEuscb9Xf%3jpfmyPLnYz&s z;s^m!G90T&-CsQDgE^Ckd+$?7h8W>a@o*DdLX7M{M-tLEWp7Ph8oRPS=#(;asE4F_ zTTB*j=^ay-J9uvXpze}u9L0up&1J;r+9mOwm{FuwRE6;i7T6=3WxNa(&7z8cNoWzz z2^Aqmcn6o=N7}mDcc&N91urOOL?h9Bll8?98fS`W79PUq@C8&1BBFEL2bbE0ed>13 z`+D9F@%|Ykqprk0`EYpca46Gp+3b>I6=wtQjO0Ms)MHzYR(O^6X*!vbU~H>zdaL{?hGQ-FGOv%%JBS|oI69I17#=XQbfr5x)rdZQa4`}SuzJTu8)uH4dm?$6 zmAZ^1qg7%3bW_OUiCRgeGgSSjoF#o_e~@F@Y6xNLPRi(HN{Q#aX()^1`49buhJdCi z%@TaB&=D4b`0C4(0|6s&D! zWNxZaDh+0(lFYz2(2^-829cRo>t_q;jiw9h`{`>97$O}eY+7sDrdsEY6k9KK_RG}M zRv1(I%3z_(-1xdKyG{TJi_i_|>D*qgvFR6eA^2*Fy{~4?Fl?WI!BsEkHKq_-`plOO zV{H~0DRlejs!InwZkA?FdBykliY&SxC&LbxuLO7RAGr%WYlF$@Q7vh1_6;Z1$ddBw zTZv&vUDMuGmDS5v4n}A1DXKU;6X7MUF-Gm;RZP*64a@O7XQ7%;z+sdrBsuS!J2Up| zB0%{4gxDKPj$#WqQ7lV`ONN$L7npqc;F~no%4ZjURrRJ-PUuuv2F>`zbhKy~Rdy#D zRt_l|Rv9TO_L~`n40DGV-&NdS#{Dw>Gr3k3dMec8E`Q5QwN`6%ZNTfm`%NlrI^@YJ zEEmr!?}OuFD=+H%pmGBdN4}59xgi<-38(IBg2T5wO7oW_Qxd8%tY@2SaZKDIZnT64 zmdh;uOtd0zMxYCAkAOw)jmM)s+CT27weRs5Ltm9M_m|4~J33ST&nxGzchsM5LPul6 zKUM<%3eqMO{&-$Pgtx;iJ`n0-I<_94JdQ2^E((#3o-CeP6Nacv33*e*fU4S(S@I%A zYd0-Zx7XIc601z2LV^7#Lv=)OA0gFKL;!7KP$SiQ_2lH@`6V;wGUxgA;K~;;ZCDT# z=1}2xx+`52EjHB-C1xZ{LaX_&l<%0^W(N(?$e1nGRSaqs2O)`$P?g5KW{1x(woO9a zyDjV8P^t@ISl!%{GSpE;dn^U(XVnq((rUelK%i{ zMt6opHi@<#dD*&bQ|7KmajMJ-jmcw6x2NajIEmKOUy-3p`8wNcRX_q%Kd+pd*M8?o zo_KNh;?i$K{5ME5AnCVhJ#p?67{C94t`?17`2Gdbv=j388u&$8K!2OV#A22H*eKbr zK!jWJ4a`wNJ@2Q+dAn{uv-TPX2+<{U2{CKtwB?XIPi22kH~lY=CI#-eVs3FT{02Vl znI*+~8e47z8vU{lf3AzRt30Z7D zlJ^>8Z0~wv3Wu0|D|0vrp`KHHYbc+NN5q)ix50S4_S64`-J(sglsH?GN$Svgf)ka3 z1a(86ZNds#DDbGPSjJoo*s>+h#Lde5ZlV#d+~t{~eCZr?BYt5?4B;GdAGWAI|0>hL zfaFgh-i3*298&M2g2Zu(le+$;r_cM_)~w|TJ43+E!(aa7qytC*))cjbzf{C~1S*l&;+|6qrl< zoEe`guqSVc9nclK?Dq(fWMrKp{qTEtd;m5G{|%OnuU~XVL_CSoz%A_xsT~#0 zGbDs-7(hoN9BFH4O$c}cG%e*@eJ{@19#SfiQ_?vFuauMz9TX(X@pEIcy*}IqZ7e)*I3r72U zz5jcT;lHpk;x>-vM#duMHeby3e^_t4|u1j=xGMDa~F3m%dQ++7bRJf%$2_Gqr;*Z zx+y7VHT(3?eiaIpnJVSl9A3O9-VNP^Q>;^J`<%rZ_}UbdPyvO>891dNQI{vxHs<3dHdk~QK;?R%Ul2Byiwi|9&b%ml z!qfJJe3eNd1ju9?L(qj#L0u%hM=Gw!TYOg3|Ni0D#XwNEm|}&LS8R`sJ{^~`<#Pj; zJbZMuJD1|DX+C_G> z$9ja~GHO|Ks;fF<(L!$dLMGt7)Kz`m1w>h5ZLBGSre&gnq`yNGshyg?p54lw0ae#{ z^gO-yO!}qp@42*ra)MCpmR9dP9`fAKpbuLOnv5xkaR{&1mPpL|&H1mWr$FydSkE`e z#hJ(yheGW2i}8WDU&B>ipFdT;w}uI4TN!szs;W-Uh~H|SRz;&Zl)CcyQ_>_zIbhCM zV$0vqV`tx1iJ=~=;3KE;ax3W_1xU}q!KDe@xH1AOPl!B7Qw>QCdfnb+O}u`lCY#A-9M1nwkloF5?gO=w`wJ^j&{EHrp}# zD(l(Aw=vsun2QeGCfMcTU5v^298;p9++4o zaVpUF%D7!7BTAkjI_;)&kBr(|4Z$Kyl}7XQYNtfb=o=?(HR;_I%oAlB&bjy$@=1@E z=CVYVamyHETO)9CQt1;Z#(l(We&vKnC~aWLW;7ZJ#fi4bin{Smi#Sq^CW{TV{U1sX zHI0(h0S%~aOaI`EH)H8qOS~ZDvT>{s1)GFTG1}aZu~fvwT`SfD ztNW54au#05vdVPc^X=WP#HLWM(MD{X>wp)H znJTNOB@E!fmgicSjjW3i=bEDru8PT;!wI}R5%TmVUm?ZFIZfl&5%k|xqD2j4>RqIGfRdf?Epz-ZLYuURzXN0X&c~4y^!! zNXnR)?E6%{+x^{ks{yK4T4R8NRf}G>Xb>T}KiQSB%&8`EvX|LI%ZcuHkLbFLD0rCA z!ft`;h^Q{oI}$eD1@)>=!tTNdiJApw_reUxo9@WLFkW;Q#RO4+6>!%%w!wa+JDz@4 zzi`jI5;!hRe9hS9K!_NF)(~<;nF21j_~dw$RlX&psTh!$75{6{F|5*E`E z|6gpf4WV0mZg@|B;@*8Hf|S0m>AfHHU*X>W!)^XoJ^CLdBj5X{npVtL91!4kbIDI@ z6U7=4BxWEm7bXt=*!*975@a|jtxqy2Z%-_P3?=>PC_tu_iLS}vWM<11ZmlhV9r!R! zlNOsp{$w5lgCY~usbKL86hgdl8vV5jL!wKzCl6#(c$-?7SqRshd4=+jqQ0prmq>O2 zv#b|>RI-W%vGRm%-)lYp?`c-6to`|Bc50v}D2x24<8%dF)UhThj!MU_n9S zS+e+z6LRr8R#uC?yq^aKLbGH-z+^Z-f$lr>OYdNp;u?-01KQNUbHEC4xF_fvno3bm zi^H!~NCuWatcQekrguCjMbVi)V~pumdP$Yh>B#tfvKRs>T7w?JlJi7X0^e=5NH?Cs zd)0r!?9_!xm&yGu>&w@?%=H5N16tt_>TpwiwKti+T#bKkZ~tC++h0blf07ac&gTEK zQs1RIt%#|N_1PI`B(An5K+a5|61M~p+*CkKgaimLu?AXoJcil(16L>k==U| zg({=dxn@bL!=(nBx5qZcrf8aVa~f6nj`)VUaJ5dX35X*#cN6#6ef7Ha>g9X+_vKLL>jN#Nh|OtF9qA?Ju*EE+eIytGD+xHq??f<#I-aGm zy8!L;n?zRvkb(cVUb5p7&<28?W)DZ8uf(E~V@5tTSJTjr^s#&JuA9VSQj_u&g^0*h zO4xk%oTG!eG>cOAmZ`^NfrfEdsZ$|bJf%ZTnUI4=Tb1Ram^w@3ulRt1ROI=U2qmL_ zC28elrE0kJd1`7}OijlWjWJ4*sQeZjpGpNp`fY*-C6Nf}M86&H=8BAQkb0ob{+&i~ z5c+cShY54)b6RK@o5V`64SdZxCdAKXZmJW5H&{tXrCi$d}xSZUTsVY-QqMNu#D z6YfR%!xeN+N)js0s|=MCs&?)2YNKN`3Wu1<2~{_IAnaNSjx&IZ65`C_B*rI3g(Dk= z%Hs6kP1%7QF0@S+uGEGI)an|7<}13)l@ z@mgktWHd_!pIL>K^%b34RL9a~v0-UeG*JVmc4r>RVWY=X7pW9`N{%u`&z)*9a^G!N zUKStfp#=pP)X1glhlONXe zJkjh_rRLZL&7*Nvu_Sw=X`lnWYu(9|vOg9csF~% zjLwHWHRsim5>j5lu&qy>7kTK?#c`p@xe2oe=&Jy3k^*RNrWb1yT%CM* zCzu_mUVwM!tZy0UI{jzYD|YA_?yYgPJI}Xp8b70#&d#q2?J1)0*RE>UG3_2h%x#0r zV5bn7Bj`mFNQKG(Z*m)mQ%vNqaMqSYU3Q9duP~p`UGRmx@wZ{ta0$A9V(y&bZQq2x zaUQ#cIeMX_KFqXrM;gl8j*O!ZyV?biacm5J?L#_!;DsFrz`cRx2A;${l7@xGwQCW9 z-hofS39eBrO#8s`kP@}_h``FI zGtuxB&WOYz#$b#QvE!n?vpPBcCx;mLpt{MZI$m;xutTPwWWU;q696m>BvQ6KUkw-ta4^F%k+k!$&W(bGSN&j{4{N zeb>yn!>T%q^{#6$)WakW?ALnWwjpH>8p>=B9Y>BPCYba<;dn~^+H^_IiDC%iM{{91fGB9(bZNs{DiE`^+OIwI3RoTKyCXcq^ z-Y2algdDJ1FZ}OV9Evf(^Avu;KgRaoE19!v+5MO3+XQ zl?BA#$JO-9NX_GK|g=srk6(Jx8o4ALmFo-DOe2NuFKR2eC>B*;DnYNwRj>dH3Ox(1>e|V;kO5IFq9+!XLA4`6mnFpO| z>NjlLEo+XGAQpchTtzlQlBcRH5Z8(cI-(Pnk7y{h2Uab23DRg4kteaRB{9g1T<5IF z;;G3h89PHNrAyQ;Y{#s})>JA!btt}dHA8Oa!FPOu6?HJh8XZi~pt3`3Dez7SLiWJC zLyOKToK{-E@cA=4wy(UXJmqUPB>w+B8~(Kr{^9510M}DmY(A1QIW#7TCDzC8iC`8O z87rUy2SHc@3*r-?+vy`h@9Qx#$#VY&s7xtuN!hAo3H->cN6)`7fF@jlJk!3g*6#h< zv9jb-{o(Vevi@;9-F7vZ&6>C~JpuGGxZ!%#{W{gXdAC*R>-zu(Ak`0>wbLICk@L$B z@U0z@%B|-64?PyxBjX*StSY^j0L84G9xc)$Lmb%WPWyty2P87J;~;&n=>TCUBMT6j z{uA_>C`PvnFC3a3eG=G4w8L|#tiVC8Br-PE?<70HZ*t`UcUg8UGW*HTFxQ6Zh&a6t zq%=LjUWV|WS`+;UAg2M{%O2*}BuoeI4aq*BHbrF#@4=FI_%GHke( zPY+Nz)w}A{u$Iryk=WM|OE+~fq4y9vdqD~*GsQA#({YEtjH$B5pW~sq9Pg@hdO=93 zdPPhI`WvIUm~QGu`Jvq0S0?&VaJ=5+7#UBG@bmO$z?s{nYDaqDLKx-xS0R2F@nPF2 z+hOXqaO!ja;OOlqfZB!0xlp>sl(GAj>~%$fQ=@X7>19gr*&5QeHrTO__RtKWQ@V2x z;Un3L2?xMmef`Rv56t7rb`DOc)*Lq+NayK}x1h8S(~imF9)STkIr+`EwQRN8IzxV8 zADqdvNzPJ!279hEgLUWeB{O2IveM#s6ah%Ixn=a~%kTws*hkbmQC&_$Zmg!!a|GV@ z4h;l}ir}n&1(U&Xwwb>K603U`1XltDAgbJRwhX4T%l9Y(RyTeB(xpMJKc&uAoI(Q$ z7%kLOccAmLw4u0d3$em}`PGcr(mk*DqS86E^KD(N$s)6pXx=?sBEO2KDtH5W%|aHj z8VjO#|QhO%L6$t!Rv+#DoWP%ExgaO#Q zWD#pixC~wnni`>`pSBmc2Tf}MV^K}OR8`oS>@}k`tj^S2CyIBzb-jm@D+@MR+cr86 z7l8<3IU)f770%vQMdUAsBXc<#raCE^@Kz?r5SZU%(lD06*H(4=_T9e%^#eRp5=b&R zMkO_XdZdRe2YtZKk4hH40jw0Y7;3<1W*w9&g-Fp_cU9>3IT0MRCXf~IPeGK4QWWWx z99ul4#Zy4>G=fcy2EvuFgbjZ~K{AZ%L$E?ssH{w);EmK`>eAVbR|Ci#8_Ltj+ui-M zI!1F1Y;uz|MjJNRY?(Hgj9zt2uB_j`HRNp@h`boiAeEI$IhuxLJGMZUv5|OM!*sO7 zr`iVso2-W0IzK>kB@0OrevC6w?^oN-KAlGv7>Q$e5MjX(DiH2e3J1!pou}T5PFV=;xKS-D{a#o}mAsabzJuhf0(EDzPAVN6|@EM%}Cm zqRi#7&F>dX^*!*%63REJ2ZI|oafIUBXLof5>fblD3lkIO0Rtf@C#|)IO8z zR9wYdN91>}-!s63^jD>ciKK<)E!vv*jOU@xnDP3Q!4+}W-NdpUTDyfcT8nXZLl#EF zRASzp5k=yvG{pFj=^aivvY(%v#+JuMlVbP@gb6#n)(}tAXXoTx>5eU{zxu##w7(o< z-&7EKA}p-H5tFvln~==N41pax2a)$e5_)bvsK6FU?Y4ArN;Cs(ZlQJL@5(msmOktW zl<_@mEhVPGQOS_E##QWnRa1JiRxi5xa#b$ypNpsc7D8<;55r1*7g0%2tcSaEMhKxu z1t)2~hE#^1dMP$iTgF7Pfy?ulHUrv;vX43Sd6>;lY=W}+A*`Na#cY#B=E{_VYQ47U zmFzd{8}PqGtJoUr+iDp;an(&LN;BERT{Dg8aODck>~wm?vtEx>P+^H=ROhv2#iao~ zC8d*h#yo63h^sPJhUywQW)Lj$64H2$(csUfgQFyav#-(nCia8M_M%%e`F3!SYy9FM zsOyw_GnH0CSP6|Do>2hwbtLe~JTVA6fzvHc426QMN2bd~x4Y20uoiY@% zDC2-VaoPNg2n}~}L&*`(a?v)5-1NG%R=yGUihy_df2_S@kZs|zu31=Rt+H*~wr$(C zvC6h>+qR8Wwr#s>pS@4q-Y5Fr=ySRwM#Pvge$ALMGrt^}Z$2;Kq-@jBbn#1AxU69c zB^}Io9K|K`$>@NZ;1pUVsb3a)y5pfTlb|ccrX5;0xM(QgI!@S@gdyX8wR)$GrykxZMFNxSGEuK;r-zkYE@ax@oA|5x$-Tp)ZaAl#}KbX7zgDhj=}mvK#w*?Nv$wi`?5|j~Bsl4L8HvDk$90 zYd}ose|s%pPB1Ke^q?wte%DwD!RW$d^$@_h<=6DA&j}`a7Z#sCMreLGVFmse+TZa? z?kle2>*TV+dO42@A|L$aDQxUKBmfyWKF-YiM%CqYm_8n4Tyd`OsuCh_K?jdBb<4-> zfo>JKtJHleRp+iXvE3!dr9DZ3hlwPuw;$5vWjv)&P8RCBt=)6rkv>4WW$aKC68*M` z)@dgB^|hblNm|woj7D3$3d=$bQ+xE(CFtZOh~%ce*!d3xRc|8egJ~rv*VEh%IZC|| zQ4b}m!JG$dn2%mdnz8_bf*Wo-&=O!U@-~5TR;#GOrzWa8@>yeT%1slTVgQrm=7_#M z(`QzB)(xIb4;?z_5NK0~|B5cmCbf@e2CYsQZz&AJ1aHaJTmgI;LZO;f>=nrB0ZuOf zFQ{zv91uhwH!>1gjC1ll=%HQ5?(dw6DXS5ZruI@Njofm0)Fxfv>!>%R6^$h;^r1K{ z^#0U92Oi_NCJmc;B`F0)SWDDk1?qGVUZ!k01^zfnf=7Ai`ou15pCipB7w+ATrd>en zIOy0X=nIRNs9jIrAoqmWwr|14Hp%mKvcrmCLzZ0v4cNo14p`N7*!V75;W2jDI6fr- zn68b^+5-+6fAR(}A$6}6VgnUyyb5aMIAwF2m8i+uf(b=IqWlwB-ik41krb_rtGf27 zHk}7;=6OAVwUc^>9yC8ov0(vTwQ}v}!GwHXQal3S6+Xc=F~c=s-lnX8CmM~P3&NU@ z8UWZ1f?MR^EAU-ZfYE2nf+Kd}5%A!hqCji~e%8}L|CAln6v{%6=59yfhp`-JOW&nl zh(!NAcRKkmN8~VGqF=3|kX~?JIoW*l5s;b4g#%p)J7+)gwlS9110C`=Z#k~Wgq%ijm{Ax ztmDGCfyl@Jktu0{{$v{d*?Sncab9|B(~i~tS+A`_;+q}MzR2&fdZTn$)sjHXY-z?O z>9~kH{iRVvN_tDHQFLnbDWdT{#@%+{VW`FO#FQT8ylRfploAE>05N|MGq$NyK=#0K z(2GfjxE0uT!$Res6Zf?pkaWYN1&!;6`4x6?Bv_xJ8>{0Zp8QBzU%Aak>h&vR*OlmL z8?iA4Vy)!Yp`*v0?&(zzgt3;u-eX(`4>%lrx3!$0Y)b-h>}b)U7f~g|P-NDU04Fa| z2RGjXM_BO4C`pyj)TL1mn0ORw!aa`+V~3m#l3>W-EIECnICT18t)>AR5&Z@^Jr_Pb z7eAU4CYRI__sNOa8nFYSryq@cUKi! zsUk6YYT6bkGTTYM&|}Yd2;1br3}GEtBG8`?6VE!aZZY#0AvgJdTB7tE?a&vXj+YOe z2S6wt$lE3-OQ@uL8(@d%bpc?hh>jwpkcZL42hrTbk>p_4J_+4c6Ad4=tsRzO+s@H0 z=OH*{EJ?}CP68J(#_Jn+Oh(!er|BX3Xl~ab?kwpAY9%YZuARvPS$|ct!f2gC?{WrJ z!FRLYzDP*FWFq7&?6|5f)Dz8RNT8td>JPtlN7Q~lnh zF>t3^(6Bl@MWZiTn=p zwoMW!L_ydV80WzEX9XS}nAye7Z$%0o=wNCXlMo1*BhfcQ7>0!qBt&b6-YV$0R{WYb zp0yz3w*AmylZ~NQ8j4yreI3D9q?M2y!#s9A?b++f0~}VMW`oF(T8bl08!upb)t7S5 zK}9_B<+uE%f zvesL={!G8Z?@?#8TSlvMVWV%`VM{Ycr7AqlcdOKg^u{pSQBgd>-XeW~O$kYjIoK^5 zuXW?ZO+pctgd6$HP-v4PQpM5@VSWj0=a!#6Mkrc|6GO%_4zRi zC*|P@<{cH&50{A8e_fIGx?l&vUGE`aux1th!GXWhljj0v&kwQp`L&NQsUl{U8~c$dr58ALxWpL$TryxFo*r2-C$2 z$4D2!r!UY*hH#07w3YqGdcZtzI9xy(Hy~!i1-}PT^}%ogEN_2Z46E+KdTEO}l8@;j zOa1xAM_)V9;)eZ_VUz)QFA98~_*JVrx+d^mgVG!exE#u1zJqV)sJS|ACoB%nyx{zsbmX=+bF5%-zNVzYx+XE_^&v7Oqs)Wq z-88oG#asDqu%+7#f_m|;SJpBg?y_+o=;Yfw;v?fBVeyxFn%2na&r{Hydp8mQ&2Vh5 z$quIN!;?P~)NhWMYqH(zJ`SWMh70C~93b?)y7C?`%#nlJ{Zt>=RDCgdu-^bFyQGDM zvb!iBgj|6+eFZP1Y<{}n#MVU3wtwKw@R`}jxDFOpzW|CN@FoYDXm0ahRdQk4Y*Il0 z8x1+azOh>QFZQK2$dgvXU^$@ixHqHGOXJN%`?cAGj2u<)pHZB&Fm~tZp_9;pC7=g{ z8p;&QlXhWK>==o)(st=1zC?D!1k-TmWmJy%H$O$}EQ7UU6Qz!wTH{jGjYa#UWl01`Cp*HW=oRF4)r#{bQ&Kts-r38LP%gv;-U0Bxrz5QP(V9nLfy&WiXYf z))e}_*Sc$bLlm8|iO1B=uU*Uj1P@*k$c9l793A;n_EmG9BMc_x`9x(mWRMk}Ev;GF5InexO0LgEO zxd3J$Zsz9Vcgg^B5o=7hYx^SlcW`(R%-4^1+|3k~P8c`&!T4ya;rR!txyjk%^Zf#$ z2Ny)8uriGo7INff6g^_jCB9ES5Pw%h$-QMrwv>3y;nlmYz1yhVQ`4EZaNPbrZy$69 zbs3Y@9-mFaXoNBU*oyP&pNGU;~FDu)%IlV%5&=t+>KMe6b~!1dA6K;+g~NS0 zn(y$~a~@B>NQ#L_i)3!PrG)YR4zGs!pqyCI)X_MACekReS<6QfD&m-%d&!O!eBvo--Jm zg=d9M8CVtn9LA8~RI|R_caa4(cyWvxx;_L&)D7CXd^!n6Pdx4%YMXNRYzIsmidYL# zmsPG(VZf$hiIbl*wp%)Y9Yg2GUEAt%263ker@@VnwCd8njNrQ%@JjiE?Ey zG*}*_zoE!@PQt@tzdZ;VfUl{erKYD=6DYs13$|emF#@xGNf(;Ml2Vl+qZnw7Um$qw zCpw>?gXYG+;7*ZFl+;E!aAKDfyVTj6a1M>hIF@T-37w|UN{cp3p@WCxyaofW>^?v` z^(t}V&@)UZ8|673`34bu(LlEbFRv&B{p9jHwDjPf4TY&GDO4d3PU@T8J-KhU4*H_iE0M7wn=~=pt)ZjZO}>6D7zT>IYOXC&X`}M`#r32tJiZ zy}=0APZ=!>_b(pc3dV!PEC;0KmH@T8-XdWsh7HWw>S#>#nJf1xzX=&3H(ywcI+~U5 z7WbPU=3vH(5x~GQgd|`6LVKyC*jWY0A{E1iETkyAa$X^O8TI41;}@~3my9GXYc`ZB z?Ac>K`Gq)+x~D#=gYfFY;uUm)yYZ3;?6Fm(fs{BgBAk_%Kf^$qqC$qgm^jYL3z8;D zvo+VCDfC#U-2NZb7BO8I%D3F;u0nYy3Ko~z2{|9`#bns?iR|KY;<}2{ddcM9(5L80 z1}#4-^A<(LQ5bT=#0`WD2=Zm+4J+DEVWJjb5Q{yC0XN<>N$j?v0B_x*F;?L1&PRTzeoD6!i>I5% zUH$N_Fc#(0mR<*TW$_c3G!Y48l=F<<6QB(*@AbY`P%X(yEJD_JWG%zdn|1Px9*Zy z0Tsqjn_;c$yM1{_{>)}CmT-{yDTmGP{xaJroD!#*^Z<}e+CA&Dh(XUloR5UUv^<

ynrU&8RI-4oC9OLA73Y zJrPfNtCjZlfmA@AGPlc>s_fX5f2Y9O>zbK&U???Sv+27O`P_@-RVPXocXUG?sF7^kI zPt4PrlxD+)H4B=+n(7B#n11Ab?zfE02Or+RQ^M#5pVRdR;uKVf4gckbD*xq&4a&OM zbFJpn5s%$~nBtCUTnpP$t2Q4HFQx*bltZsPJbC_K&&Sx9{ZY-`Z`Ho48jx%$Jd3qA zd7kG$p3p!uR|07njoE)Tra)!a@Q!)(gVL;t{34SBmeSCBiy2F{sK6y_8|>kW+01iT zlrpORcUE$4z z)N?^F!xu*d(N3N69!}re2uQ|q23fs{XMWKX?8b{?=DBZLHS@_EuiS@#yks7GDeV*5 z$?sYV+WVq|SvxH!*=w))8=_U?O#EVI`k?qt?$!oC=D9HQk-4Yry-XUcvT+%H_fxnN zy+%h8&b?8D*?DSlxx_%zcG!(ZN#^c0Wp!2gd(1aD_eSOQ%t{Rl8vZ^=bSs?(L*%-#$ zH>V8ys+AjDAYW~aXYRJsrcu}QNAsZ4Y)r-|Y-B3%`=BON(2ZA^M}BCFWA4i{j{WN= zkEsGEUDxOVYVTe^9@R1PG2>ZRQY$F{Nc9Rl(1)h(_N6}177B&<)%fiJ z(~p{_qyBOO@NA7;GjPs!p;?~$hX5JFub`%tjyLQxD8g#uWbO;o+jqRaaq%!j{HBG> zyEIC9UWa}L>wtAPt(?c~{NB9>HUBPzy0U2#^8ybg7W?{+l@fS~CYhtm=<6c2F=`kG}DHLrhStK zWdZR%hMI6bXZzy6;Cq|GndfaOolU$CABtH3lJJv3WNn)lhr7!Gl7inZ_KG&2NXah( zBukQ!Q8+*KKla`-Oo}V|`Ymnm#uo0b!5O^p!G>XQW{_cU9h~67AwdHKhv328rGpa) z5Nz;)QGx|0A?Q7OpUQLJ`@a9@ez>3S7glDay1Kfme!I@8T6K=+-5b%Dxw4~;beg>! z)nHp!arL}%#O}v6UGw9j5vOT;ep_UpV~c;@exxTk*JYnN*tS=PLwhERbM;Ds9CXnt zdSLIX)E1(Zd*#_<`?wd`HY!U~QPr=!|0=($V}sSNXO0v5`Kp;gI?;o7w3|F!?6Irq z3ff0!N+$1$lA^73HK!aU)oQf=n@tOE*Aq_B+Va~=pUBp0*gJ7exmux#bfW5f+p%h` z?}SrJj?8J*|4_vFb#X@FG-)rFiTEk4b7+EK@M>fydAuSX46FRYCE5U2yV=#I$)Y#w z4qp(}=IX#0d;ip!T)o9=pSFk-+rkNa#BHS_ADBzgXnA2q%D>@ZQs zuD(4d_hERc#3vP~}2{NM9$i**pKuWP;^?c?=buA{w&J`+wBdAHfByM1T2OHHW2dn+OqL!<#I1{e*k!NPG_SE>Rm)~v?&bM+% z)nJF3h1dBvi(`6i!W+4NI?mha$eCC4O0Lb4qtON%Bt-^)4i)?G+L9^qyCUBNqmLg|YTDj)P(7G>2bvK1`RF0`)HR-(Idci%Ss$V-N2LrUiLTXQ( zoKdtcuEjN#-xX!KUJgIEP&kQRdv6TLeCf?;+QMh2fsD>-0=RX0U%m*vbw;l#+{1*|+te`k2q?v`-+$@{BT`yyudb2o1bXSiL}BO`a; z&M-Eca3;xtbAus8y}6qW6xa9ba~%As>Myk+<&<2awS0Z)O1VtSiI3*Le=LsI^Kz^uehw4SyD-Tu+qKa0FXcjQ%-V|3x^@7Rv8xT;pSjRV_sYxc)wm+@5ydpZL1s zH_=Xr)8+FWt5Dn2g%tyW?zl9??c-j}Z>$V0D4c9|ORw7gggu1|ycbTPl5#!GLcg8z z=e>NwDIB)nPtUUEe4G-SSF}Ll`pA1bR;yJL3(WpjRLHnt_T7Uv^`iQ=Tq0U%apUC> z?pC7(?X#XdCn`YPOgXPd(5nBoqGP1!X~r#*y+13m=ZHt&tT`{7wf2=LJX5D?XFH0s zC2qSM+V1G%ISE<6+aa!lafjp>cUF}ReY<6L&J@lWSy!#fnYye0ei4-|?uyNz@#W0k z=iy>M$HmKgjKM}1X0+LH$|IadqvWxOuHJi}cNy)mH*)+{s~#HPJW*ft_2T}!4-n4x z0YqiH;hARFjVtR8#SY3ToQ!gaykO{rF;g8|MMb)iw~XAvmIa>XuKAa!BsWUP=S0Cq zGX})1%3Dh~7480ev$9Jj6saRxaX0GxS82Z;Fz(Aq@k?)n_mSHZv8F}zWq(!SM9Q&4 zgALzT%l4@ueOFg`U(0Hn^}yL;uSNUk#sEpBr901H=FxG&8D;lwnqQn!2?@J|Gvzn= zsg6sr?Nn_+%8j{B`KeZuBCi%+TShp`>&Y!_zA~gl|Ni0{cVokN`MX-Ltn6&^Otju_ z?3VXDgB{NIIWcUN=!xG5${_@Ub>h!D^*-WQ+&FLdshcM^oZPd07vaR&t&1wN3x!r} zCaUp`1ld*(wz}Ri$KYqZh4VBhoyf207QI_0+J`s(mcwNPn-7Wa_clS)jhmVru++*t z>!(JQ28um)(=W$#3U-*`&rso1mg8^+Yfp=QeWt3|!kcyFQ-)ysV~IaLzA|1o5whhOjLuna`G;>( zgwsy8ZGuhPdDGvRCfYwYyUXzpt>%^QUOHZo);zGg+~(?O-MtpSFD;zW@(zO)k^Laj zP`~@;)VcQYnm_Y+-&NvR+?;FQrHPKOzj}1WJHlBmM>PqyNj1x#sW(M98{|kVR@I7e zX~*;y=kv|oa(tU$ar0p7Rh`6{a5E?;;<4)XkN&QjC2Ho)bAQ^~Jno^lRXsuX&Fe4Z z?}}KJVXmG#mvA1um20j!%F)?%@r`hvNCtyt-qn2FuMF*zGyJ8d$H z2&cqD`784H=VdKDUF@-273E0I!EchrUM*;fGxJt$IWDLbm1}zDhE>H?@0LCClGV0c zHJ5UJh;Z84?9|%RW8~U6LCUQzYo$~3Le8)6YY0wn#r|lY3FW*i-JisD=hlePa?R26 zizY{`5?7F0le)_-ta;2=|LqIWg1t4{?g6!`?3^`^?qlCt@?R_0boaioOk5dnt&`*Y zTOF1R*C!SfSD9Pe<*>9?RQJr^J$fu^_^m_oX?rm54HOG~FhDq`<>)b1&7Hk6rrFd| zIG5$Pj=}PuibWMVC@R3MyRr7SuP9vNmr3M2w4eD#&dEJ$O_8#~d6i2#)oxGE`M$$S z;e31}o#@g9#>c(C;iz%jan@!h`M{Q#WrF3~>EzQ}D`Ihn7QgNl_4#%VIY4o+<)Jnw zhF2;soWd34(P=dP!mdJV1x>fh+V@G?w%>BDV|XFqRFebDTJ>@_+5LIAsH?Z@|JRnt zo9V-$u=~RK?~Ymf|L&OG?jY|dT8$geM~yU^aC#)k-`=d`h?EEJeZm>EMlO@CLdGcz zHF1XD9wTR}vdU+hm72*bj{EItdE_>iP3>CaV*TyHnQK1-YWL&0m=5EY31|6F@>A)? zy0#peCo0M94RSa&t66-?)i$j<3TL+*EZS-l6_Pv0(Za$xYWGH)7aDQrVoPxyy#1S9 zZ3-pSLA)l;-rLvY&`H5o&(fc6n3=XP{=d5r7cWh$m@3Yw+mD9Z=X}4O$yJ_-7VPae z1>~n%)a`PkyEu89duLfIr zPgUPivb%5^$YK4gh}6TL;-5AMr@5SkAy_}3|IL`z;#l12Fifteb-@x9k*k<+dfGkK z+Na07e~?}DsqYMu#96KT+{u;#WQPo}3A?eIIxp4pr(aW$OTpqX%f8Oh5W{cB^%ZvE1UBY0<*Lw>4l-RMrO zJ2eu{5jmZQ)gs-*oyBWZ6V6%t3X<>i)I6Qq3I^|7kprX$>l~b(-0?g5_Im}S6Y)8- z5|_Q7a3205_k8nV$C~ZQBUrxkN@kyejR&SF8o!9v^HJtof_bO^v1a>NLEK%3eC}yQ zY)AIi;jzL=yGE|L<&@#?R=(OJob0*eGEGLk-*+{?=w;t6DCbiMmb-L)?^rV8V`3Rn|Z_U1e@3*x|$eE8U8U8h$s{zA|>G_NK$~hN3>-9g$alD$2LL z@6oYegfmel%7Vq3y&Uh`E~@d}nXjeO;rY_ezl{hJ&Z4&Vai5p=W900e!dWecYP6!x zMqRA4RkS7UZnZg$I32rW<_u9=?(QEimuWft*Q@moBnaoY9PZKz%^rnGZ^aS3d%?1g z>7;vEN+;7Vy&-4U3N~9X_`u^1qN?9bkOS*k?L!ZS`!|a-^R7K}met{x?4$mfB3f~G z-^r19gAL<$R8EbcWxm>1v<}(RP6|6X-BIJ7$FB43Yo8i($T~1UKY+JVZ zt{GwCSKMo0-*Ij7@u$Wu2Tl`CbNdLk$n-}a=OS@*?zOk`BuxtKN@`kCT&eGMe~#{*S#h3zGyJAbE9g_CWx!Uy|w-Aqg=mn)=@`9d*j|VnaT^681jAXH_9>L9FWH= zSihU6ubGdw@MI?WUG>&Re}3l^N9W!}JKd+uKl;$~P>^!(rW}pmYV~-};0zf>wYirl z$I!Owd;h%g_XqmzPw&g`>X@(gPp>x8p8s3+wyemZ#cof$JJ?YpUa2hiMx*E}dt&0m zc^L1JvkU~A%}iW+XMI=UKn~$HD-15&^6^V?Er@St_Zg#-&P@E>C9Zn$-QV9WYvE%#8mYx+c!uce} z3_(i#h(F|dB1`7KG z`^vu&{rC9Q@+xDseY17e&E2A17r#Y5F9_zW();Ki^yE5zpPe}g``)#@#dTdc$K;5t zR-IvQ+I+DN2?F1VxD0BX6S;1HQYn%5b4>PviU0s}+@t^E`LZl;ZZ_VN1jvDtJ)1=evuh+-w z9quojv~slYV8xz?qD{|t!pSD5nzEV~Uq5=uYtibyU%>9QMUC!TD96zsg;R2pT&BhR zB=69rqLSR_`HrZaIe31vtC>X&zhB!XB`R=m$kz&D&)*M|_oISs7Eb$kt#rI_TFWOs z!Pb*IU+oed6i%lOHt)yIm3%&Vq;Psi$n}KW9yugirOUz@BIn=>b}Tx4c#a8zulr-m z$~8ASyWnJ#v?YWy&8`5||M}rywPNC0d4H}P3O-o>!#MxuYoe`wf2n+e5RB@v!n5>8 z(I>jUE=7J<OU*!GL|nVGTktXta#3g@7GhL?yd{bF%bLEQb5i|suYI^$U8 z_Ts8{|Dw%cWRFpQ_v)2FI5*`CfL7$N?o}g}i^_jLQ4Yp#HGk%C4$x_jJ(bU-tjhYg zmv3YjEu#BxzsPNFP;geAE~ZO3U*w#dR{LJXTl)wx(DfH z8qXCkdx?dbu}Rue)}#Jmq8_ zRJNZ*7XQbeci|^mPaXT2UE?A3w`F#c(?n)dtq!9Wras>_Q#fs8?km{hRHu#q4i@$2 zL5$rV3#ri|eB={RwI1|-AwN|s=dGEu9pc=0Fhq{iZng3E9sQtW1L2Idd;O6=d#v9x zh`sS(nw-xiSX(X$0Bgfmw@*|%!%`!VCTC8vb5RL;C+b$GgB&F&xKgtN}RYgBLl zmBrC({uR!4`+6Gw>S6WW(V~t$`0t5NbAI9@sC;n3zMBy~dqw%eX9a@~F3gj^tM1kT z9f!{+=SEYx=4khmSrztW5>A2~Al+)VYQVVaokic_!DBgbq*b%p!7qhpi;DE%&2Z_I z8@s7)<`UvOeDGP`eX?q9e_VQVDbb=%(B)v-R`Y*XxBjl5sKyB{`P;3|O9xMW^h}VF z;Lj(wu>Y|{@3-ng;iUT@x3I$=<>?>y1-S{C?4Dg%pw9=Tv$%dGWVdsC13lDZGv+UH#IB`r9s>@N?gB`4d@0|VK3a55Wo7|qg z{}@?8T&WZ4%X_(2M2VO$9bOp1X)Fhrwfb!=bhX>36T*qGpRtCnAJKd0Ia;QbeOETN zRhK4PTOATkR0I1AKU}o&q|BoCmk=#SHw}hdyq0@&QE??o=px5g4~BPZ^#0_2`lUTL z%Qe^B(01X1fwbm+a(+fDe2cz1LKD~Sgh6(zsc()4HN)G`r@ob`;9#R+OZVP*F3#|T zQJ3tav#aRm{=?{ajawks({b{X3WE>Ow@+?w|I!6N_9I$S2p_TF+9fWPpyv zEIaq!V_AU=j_*V-AYtBS`72_!?d)*xc^2U;l5@~l9k=zaHK>N@O(ZOrvl0jE4(On4 zo=VHCl6N739oAL3xA%ZJdlS~%&w$#Mcz?Om;EBT7ENATr=Fhb&`NM6||4P^qB7a5q zIcFO^>MmM(3481eaDy(T+84+xuDJ;Z_saEj|2KcVk0r(mCuk?D``n2e)3ArAy$L7n zCnH^_&Dp*AxTpyUXYKn@S=U6at1^=I&jmT1ht+?^wq1Wd6SXDbifnIKk%PDPKkgDe zvVo!X0_9$!dS{<-6$_MXM>{ft@z&d$3=l>=!Z$C&hktQ@?)M zQg=7gZ-1=HWm?RhRxNUx=sP6*C3~a6)@y3j%`}tFme+D-4Xe=ie|C(Jiau;&2Kn?hSZCkRe_xKwA)G97erl^ghI>^j{y}Tb zA=3y}kEs{l*PNAGICW zn7MsZ;ncS8!S=p;;;_Hx0O5qnX}_#)b;k9s?4a*zY`0{3j97Lh!^CsKiLm?KT^;A| z4=N(A1&J+B%DvI~ZQSFHv&A(oG19&>5Lx|c%RyE8%FkhGnZEXMZ})m*t`5(Z2xowtna*mPDR$n9C*mk44z=^x z4O;lt#TK|OoDomtdTK6TJVyCboMVY&<>2sEXEWpX&$x^NBaqH<5OK1w0SD(M&eI4-OXx`y6|GW zxS}O4vCrPt-!vULx#uO}tavDwX;Zpiz8;~1l*BbMhaYVF@9;ZmjujHl201l`)vSD# zEwAS`5zdxF_A>Qir=QzO=g&?#L3yy1ap**z{5OQN*UsRzYm>V6uc6t5bI5-8q-v#~ zi&gyW5zepjC|l(=c256qn5Zp@C++jF|G;Vmj?5QV*u>xDmC@>QboRlkFMbiu1=*Ic z`u{K`U)amZ!nq=Io>rwgO_omlBzoeBH)JwDSajOgKSpH~wI%V6901&kxq0wS-Dfev zc_1g73zpm4+1sk&aN#7|NrPf1BPtFYOh@pMY*AaW18QEb{wz{B&t6HVt66W`HSas& zyplQ3V83o!(|KP+TO#pqIVphE@C4)wS|f;VHt&FDEn% zb~`y=$6mc9pPAVknmuRA_sTot0T_mq&kh|GM)CHxsdaz zxaKC+zbu`aq0cfe8C_R6VfJ&Y-pAheD>+280g@ta*;Fp6|FPt4EUOr^a(ct0}36eEM(Y zujBu8b*s2~CiRiie+QcuZoe(%w%{vifSiTFidubZKn?ATaE2tvPi2a|oqovxI;JD! zjA>Tq?{{WaC{lIF`9qOHcS;vb!ALVI=5uX35FoIhVk ze^%7Yq~-E1L@@vLe_D(zOGkN?{T4~L&J7DrT_$Q>(t0_$NwE3q{7r7pzbKqd_Pw~i z@oC#{$}d_DN!#V@W5MX%W7nPeS=7U%-S(5>eyJ^gKOZM3NIGCw$S#8i*Jw3PRDh%- z@=mGMw?W9sdLQUqJtp7D3U)p`a7gH6(SA-kE$=Z}{kI-%|M|S=-6Wm6Y*(9=jT1NY zr~Pxu?zMIQKGVbc7VV#_a&B%b-(TnM9R5XAfTWvtvZ&6hZ8fjVrek{dC%NVxdG6;s z)AX=#671)v-F6L47ZKM*I4MKy-(K-!sqfkx5zc=Jin^SjxFwvwBBT>rZ14KkPl?J` za?XxmSLoH#pQJtZw|r02>J{-*=r=P1!ucR)dc{q)Qnu{V;l+NrAOrk}1?IU{O9a!xshzg6~C*r6v;qCKCSPo|x% z-f2s$uQXa*bCV0%X}a!@)*kuosW``yi_6LuY`p)6suiDz)>m?=;r2P7l&$BHpT+ew zxtx7RI_683@9zcX3a65sL)Oas$JFKi6tNGJtJ%re`W0?(c`#qllw8X`7QOoZk#ov! zO*r+s%TL9=dxkW>i1RtQq5ZV9)r*wY*T#!Vk{oV7N$Vw^VOLV!kKN~Z}C)o7`8kg9p!lm_Sw?9Sk{fFY71wPOj%gb zVf_oWPD6WjncdE8`6;6C=D5wmSt;jIx9Zj}dgs~VlEPW{Up51IdW2MeDV&YdC4;en z?ez;b7Oj-zt#WqJV5fdB#;v|0TCmBx%G *yOfXc#rLyB)`4I*Z1|Ja~>7Wp&Rm7 z^vL;Ya(r`R--4UcU8Pg6kN8S560>TXXCS|&&k*2tZKoSbw9ps-Db9MZp)(_>^5to+3w?Q z;l$hT$8{diwEWMy~f=i^KZyw;iNvYohsk94^Q`laGu!D8N2i;)o$W# zQCpIq+iwPS>DhF;dYz8)YdHg8uwAyRT|3r!D4c)n`y{>ZtzNY(ZFS*%v=hj6>K%3W zt1?J9U)Re06SKDP@r;?o-bm49(%Wh?dF__ERdxu+Wk2tZY`tm5tgs8h@yVw!Rx|bB z)q2(D2q&$40%f(1_jC*$BC1VFM*F!;^*dvi7pWpzrzu$*%TM(w7WH6_Pt=x_oN@;3 zV2^_{n=M@`uEHsK)fdC*saZ;~D0}}biCR3Yk7%8y zl$39>2RrBauI9A}QTUHszQ#{^MrQo`)sal2{V zt1m1>+Z?e(ek!KiVNXO2agdjz0s5oa=yP{ z#q3?tB$KFqDgWi8O8=LSO6hh+9_5HyJ0nXT5&glG-l{xau|J%x*KCd;Hzn47|Dwgv zXKRL5S}UAE_H`%g51S&-({qQEVREL$V57k5O1G=f5gaLJqYm~y-0bk;yyA+M@?8%3 z?G=7}+dt1)!E(w(Ict~|^JLnC!ExeTO_^$Eq`Rd5@?l^aLpamryX{uPx@kIXsVCaT zDYNYsW7iObx48DVaOT_Buj-i-s@}=6UO0<7$~CvwZZ_ZXqv(mJESqbeQ8+#7&ror_ zNLgvO>*@|c+?c<`bvb3Noe}D{!#b=L{#7^|<(h+SuWTy0aJ#73DO>F{W|eFU9?d=T zS~xrH_v0Ep?pJvHJ~|Kg%83Yr-8bf(F({YdJ>{VNE=*LhW&_Xe7qu=WDECINPt^5k z)qYwnoD+7dGJ3;<$uR*@AydxCcYK1K%B4FKzEJeGQqIfyse^r+mpRbAvuN|DT(VnV zZBkqPIjr^=;asy@GCgXh8Fh3~P&hZgkxu*iyVmh%gKNy6t|mxK<9) zeoh^b-rgI34Rv1pM_eybhsX(ngV7CU%nI%l*TK}`@_9k9^|JmykB=AZq>h%;-3BA) z=D7cM<7MHDv-fJ3*UQo`s3B^2>LmO9rv7be)=hISjc}$dmU}g-Uj^;WT2Z4?XV|}@ zWjEhnEAC_$&Ya`+v8aBt>f=444VgM$&axeh*z&8st^YIOEP5o*=a{m4t$Y3HmoAf& z`UQKNnJ2goioRazD*OIMi~V0C|4yK@cU>;I<`N&Ht4?1adN-*XOG&4BjXpy@_7%O_ z)U7q;es0^xiu}7pOX2L4HQZ|5-D8$dCTFjGm1&T=XG^vaQMFPJ$|O&){MHds$1c*E zkB*Vw-m%QttiJ_ldydPw%Y*$(Uarz6Q##?Cw%_89ns@kclqs&KspsT9hhU5B1@}Jv zP4stCFYc7z)wgfvt~35l63%}KNpM0^)SuM2bBev6yS~iXTGaW}+x9iL>iR6N?miIL zrqp=5SK9-N^M7lJ7Ex-V-6rYubb9@Vx$g=m^_AS7+S}f*2>XrB!^a=&Pkn4NIr9!t z*;1ctHU)Pd|1i6#sQjs~J#w4FQ(hGN^35sX{4HlvwnEbm8>7V1G5sK)aaf%`T`N0! zj=18dezA{5?=3wDC?DMeO^ZnYajG}M#&?Dzf4tA=& zx z@M9I;i0kshT=qyTW$)ely-uv?Up&lbKOHFA@$nyx*Ngr9u#o-kKz`@+%dhEa^21_w zjyliIVCVB|b~r=YIzu8=#a*v$M0CUOmeI9TMQd00e=%ySiiiF?w0W&M^nd^FKg9oW zhJ{BrsTJN*RrGfBDMz(lvAu>^;?E*QTdRsur+?ROs*)zGS8TWNq5V2{8`LtUb6?@4 z59{A0rf=(*LA~g2+cbvs>@`?bDuneP)T30)fS4{lyOrwFzhA%pv4czXiy6|hT&bZ$ zdi5<88Z&rE6Y*zQuOZzA#q_N;Xi&_E!Btho+qZvA*LuSTG>jc0Hq$6lls4#pF~#Qk z?7u<>#dN9l|NN7FCjA)}+axA-h^m<4^Rxn2wJv?^y?a=U`}hAZrK1X!C^d3Qr3RH! zG>S^4lTMNvNm8kCh)~=}<(zXwDk4+{A%sC_J0uD@M8zf{m9kaF+~4PF+P~}f*Z2L; z=kv$+y567b^Xy)0Js)eW*L_cBkKKOLRQq@2Q|5EF*;|K%r}q~8=2#t@-+Ul++>M>5 z4W1_&e4J`*J=M6w;i$vwP6vl?Jmc51@4t9p;CI--&-Zu@n_6379NGBQ_2>4@P2Q&? z8{WOW`ea3X;~Sp;BF+{~)!((Oz;C4I^jH0C{>&Ju8AD%mAZ=%Bkd!wPbllD3|7*8=8 zHbTyIoPk!(-hMNcTwM(INQ&>viI@Aor_0%J7hRSa!2%bbv7u^jvG)p#5KaeG&@eKa)4{RL1A{gW~Gj+z#t~O zU8{1SYr)Rxqh&Wvv&Y|FrMK6>;q}zPqjF{U);riZ3^p2}^I)MtX7)C%0kYwTcRuzS zrP$azeD}^XUMCbA<-;>}e)n42uTu6wUxUdxj|Nn#JQ!kdJ?D{DrNV3>ol4Z}0H(;Z;T-vgKULrcQLSk$Iq0 zx!KEOm&b;sDRJZX)=tlxGSSmU>p`E&NH4QpYt=uFZ&dd>v)dzeX=a@KUfo>toSI>o zeLku+E*kx7dc%|}o?XND%2i(R+C9C&-o+qO{i8vnrAO8n)i){5)K{U= z=A>EWPp`?jqA5Rj#jevC`c~1>v~kqQMi;B8eHsUzJUG4Bq1@rBYSe_vCa+~Xzpu;K z8fW-yQf^81r{Ql^FZOEGKbefb<_hc1(6QMqN=vvbRGUW}M5b8$kW%gN;~p7yFEC#znRX&iiV`}7J2 z)!~0sqpTYzp6s97fdA0qk6x5prHWV3o{){N_qPvtHoB6ReaY~8-;2W=wN7SE7dkY} zSgjfrQ2EuXWY0bOCYRN+QG&`tUcYz0+o0pNTK7w@N?R|5UGI`@Hn!_O3(alyO5O7= z)n<3Q%(JJtN?v8VM>*&@XUHw@9XbA)ORkYu-p&&anND5(zNqIi4w?2{ieJW5mU%Vo zv|DeJ-fr})Gq)n!Z0H}AFT*MuywZ2xSa)?>`^aZnxx(x-Bi5)cw`|ls8SPT*5bW8d z_C>x@loLDbkHVLMmA|}-cS%&1D>N#cESb)8cssRA>5E-ug_ruywd+@JYB%wH&$mdy z7r&eV>}mOZ9RbTv-VsGj87cA8Fm4svWTQ&KRSI+wtfoL4K^Fxa1o8-?bkLPC5ZQ?& zS8;wLhDFJvq)g@hC@>huhZ>qGtBf!mmxa4`|lTFOUzEn~{=^>SV zP^mXcs_W6HMU5kA)?m!?r;;C)EUBc2(rm)zffv%yXqxbvN@`T1pOHX#KHGPDCtnHbliA5vg=8TWNC8sM>}31cw25S({*V$h7^0dMqzdUlvXBO( z0_j2ukT#?aactU{UQjpBbe}2SI>PaYZt4TL5@YLFSEANPreSq#p` z;%r&HGCMtS7DM|8$(|f@*67JW))!-@LRpBNp)$x2%7Y>xQMNf-0hWs^7gr&!LR;%Bd*zMM;&)!%==Hhw^wT zkD-zYmE=)6Po*JLqAd^mptO`qlc>b)i;_Z8NA-`=p^}Te$8KT@hoWR6hmtathEZuW zmE=*{LZtyHHR%qzBk~_0-zwadoYy-QYi_gk5uY|(!kzmG`@{SSDG~* zv+}8Qno3brvO%e6E^t+vpn(a`Y3N0ophqQbD$&p!!tH=Z_re4nn&3pGaVV(};7((# z2~Y+wj52dfcrgSMF0KP$N<&Skq(i0kD8*1|1bVj8)+XvnAV3Dd@{K4xr4nTKQ6>(NxAGjFFugi$Ge>;ZNO)Cws0C(! zt`WDPTM+UFsX62GP`Mn@Th~mCbZ%7%EhtwdMq)v9Qe4A(hq&%uk zqyx!A10gj?e^eW*GUF2?3k`=fAajUnCXg;<3n@T`kTzrmsY6_d1My~jVtYYDp?=U< zND&%6;}cJDPbaH2s*ULj4S{+?10bA*!C4rbg~3@^>|uvMlc4wmkJvttBQz4?j6KLc zgiN4(C>r_-S;JF>+#ypa2GWCqp~(jxF*M5#lEFD-Mzv+(ES?+giw#TXOMK>z$8$f( zrb4{X@oXCMG+aG#^~ALTSLW7yNmgDC!@v2ram#>F0qXgMdEQ=uFz??pkWZ1H>Ij}qAP>n$K22Ic!vE3bwXF4iZNKOe8lHqK5@NjkkQq`MeM z#gE;^R4U34sYvZxsNLii+J${-rZN>zQ!&50sD|R(4b&q`J?=EkoB$XAC4l6*upTvjDKFFo(cg1+x|g7Y2Xho=%aRVH>LeBOHbax&mMdZ^2C6)0u|- zA{mU&?tm3M?o{MbH;P=|%)Y77t)kG(6tdF23a=){UjItYNEQW&H?=D(CPWQ9aSU0XgZw z8*YlyE;ZoO)j`c)2eTIiG-^CeIEcpWV~F=BUYB@1@PEkw`V)VT=2-PTrR{F~A_5WcAxG=}Q(RM((-AJm_vp#Fv0ms9&{ zY9CDm9d{wkwxA>E&=Iy1F_va1f#|PBW-`oSb*L|(&Shlwf%$X*wbOzNwBR)@h@tlB zAciZGsX!*3%7#omG8a<22F<2>kE713WCoKNOAF$OP@n~L2cKy{J7Hafts!hJVPlA( zI~YWF(3kE&p6(!t2m=uJyf7$?9(b!MzKo-%K8T+BHe#KKJx1&}VrPNB)y578Mwoqb^rfT;yD>heL>aIT015y+00aXl0q_ezGXV+! zII;Lx1i&7^Q~;>}(g1J(sNXKf@3^e+xd@OoASFP10Oi#!ka(7si?h}r!f&~(@WBY? zM3`+bMKJj54t0tY(W!(^br=s}1fWZZk^Cf>YF2F=>}O;Fj6%05pf`Zx0W|}v1(b$c z6sco;uULFGg8D<4$Qumd)_GcJHb8S08q?6o!D=4P#Nf~@9h!@&4KTSd`Isu&08lDHez z+z~ZyIMiYFmdXmT?`zv{yNeImUEa)8sRNP+RBi!p!EBVw^?)DL2lc2I%-$3zB3M8Z z%uCT2NPGeD6NtAZUY0Q0_=&J(gsmd%8ew)TH!v+F_+q zI#qngvCcqJezc_@yI>r!B5T5W0~5;=s|0pGv2MhM6MLT6iNsDKRt8w#^&m`cgV;yJ z10uADFeXA3M1dLx&8E64)kjfXh3cxPzo7Q7)c%v&y@;>_@rsVSh>kmfj-X3N2&EYs zAk2r5sSMNUChFzX`H4&wY9C4M%0$qDOSIq(E!ahbCYfqvs>58d4yG-cPsuc-*>vyU z`jSbVC1k#(1>cEKrv-*IgYMuPE%=A9--P`kY!(spz$elj452$vqdQQbJD5sD4hDT1 z3#=^&UzX8RpGZ%A2tDu}#5xljM(jCa<6FkEAMkf)mX(%@J=djnW+|$-@s#vGG2Wig+YiOUq;&j?9xi@6cI^=>zw#iv z9p)jJR;3Tcg7xX0waQ%lo1PH-ehh#bfJ^`-0OA2O*AH53vrJg{d(m6LSD7I7*Q@_} zQF=-L+|QGR_Cd_Wp9c!dVkU=vbqVr(wfgl7^GioA{~ZBz(2{?F;K5!OPWEFM=+;yYzEMVZ2Mc$!j*tjAcC26I2#otqH>a(D~i4 z!)Ct*eu%qLESLB2`pAjF-%ZOKmkI(s(i0voyIP}r8_7r{`NVIp`WUhmJsIeE@d-U< z=*dAcp$D8Jy8R)qL$7u~2S@9k{=I9B=(x%7YJ;5iS z`As^ISx6MH)Rqou0A3A;jJF0q9K0S5*-S_oM%u0i;sV5@9*7PQ9yKPR8i?v+s?tf@ z&=`CZjlWFJOva5j8^Ni-{NK8$Help++DeacqN<%*h(}UdYI;?jM%_n?j%h1VQbNfy z1tlLU`BF(0B}Sc_cZ*qvdR0B@eW|X2dc}tHGqMjBQL2EHRRq>>`(b3us+OfXiFVfx z%d<3*OPwn9A1peCby%z37-Wai`n0M#H!6*%(h!t{>(aiY{V-2FEYDZssNPMQ|E1`Aiv`&jKEnxg4l&Wdn5DXL1d;tv$qNWK{ zqWR5KN zgue{Qu4rj}Gn7v+!4EosF?RUkRms-D>gPD*N!*>iJ4SxNbIA6fU;~0!3h>mkLny%W z$X<&;XI)xHKoy?flM9$*p@$jn>gYE|$&1R{sH}l^g>pEFNhunQsbowgd6e=|@={rg zAEwA4i@ptDHUSd|kVWY$l~&W~H8J!>Du$}oVb4_Td98@jgcOuQsYeMts;OBW0f(qZ zk$}DgP>(6~xKT+NrAyQkL!}^;bd<2?7-hBu(BW6m;q~eb@k16WDWPxGg69ncFfMIj7+{*M-r!n(HDYWw$ECX{lMAS-p5|y#8xHF$2W-DNDye z)~Lmt^{J1L;8&!WQRlU>vM}Oc42EG2BLYT63OZ$B4u?4h<|>$NFqsWm__v|FHc>yB zPfY*bkJx!~2iTE{V_CQUb0z5pH^p4%b)Ee6z1moFn65DWVCKWD9(q$ObcC7O3;#Y; z<`b(8Qx&EzOe=H>oYr;LZh)zU(Yokf0YDFcEr56c%>*O?&<4N(uoi$U00jW*05|}6 zn80YteBy1w8B73;1M~rqVZXT&&tW&kSq^}<1CqxX#sCn&Y=BuY{HB=Q0Ye7HFc>4z z$%Da#!M9)6DcS;46{byZ{JaH#Du6@iE(Rn3R7=oSKhcqEy zC>6~N&cwr+m~A+)9GZ;KWDZk=sacpRngVk(Ol6psFm+)Tqq7+Ri(6(DU`&P~LXm?a z4SDwA4oVDud;Ws0_WMw>(G87lu|jSl6pnc-($nRd!_mI*Wxin3186{smJ|A`PbUC@K$*#FswwMT@?u(ic7Y zB1>O1=!;6^CdSmN5@Xfr3zxod=nGH6{pVfd!>2$0-1zQ#wU}q?xmzp9@0Nz(&83+C z@BiD1&6~ge*1ne4?7f^H_RK!*`^5aH!sTgd=j02G@911O(J%VRlH^%Q9;1<*L6YK7 zV1G#YoP3PY9i3+Zn=BUw8NA5W!%tfkuAIEUN^}te5$aH~iZgNK_ZXl*SJ`L-Y z<~&uK68H^Xn=C&cCdduYGJ^DJ&?i6C6RFNeT?L!t?9ptNi{@mld8$`8p;?=td4PiF z0CFS9g`nerjuW&EKf0BDhF5$w~hP@T`NZ2!BADq-7ngbi%Lf8SY^I==Uo(($_c8I>X7Tp5aR{#yLss5z*dKy3VS$g?^P}Afk_<Y1`LMaL(_x#y_JfW4X0Tg??poLa*u}7IVF$y;eKXk2pqmGq13L}2 zA#5MmxNjD_8FY(a^I;2NTZzB^_SYZS;Q@s}_K-K^0tG^jkRRj@1w&IIAIJ>~f}Ej% zcYpQ1@z(vJIKsyaK%bSy@vS$>|ss=z+)uP{}ceUn~f`#eOj9YNIt1ep|2B?$q$ zr%Wf#3Gmb(P6HKJV@%4&bMo8Ksk5(4#~1m%zmWsapwXwsMnBnmyTHCmxk$cz^dlXM zd=w6&(1wEP=t*4(iUYM4sLq~wz;a<==!-b@F=+>g66Lfp{k|EYB1C09Dyf*A=>pyy9Nszt@zw$B6*_H7;5T?-_+f(F z04*a(pP>8}Jef|SM4+^Z+5jqeIw%#Q`hzl~QFj4drQ@X&w3{GTKyCyLCa8PVN20EQ z3Lt6=QFJO3qUc7?(5UAGT?JH4PzFJCs%V1r2r{<74suK~Nf?Uw(rmzkHy8K@xQ@$QPOk`9t0ie0BKh@YCR@!B2yq20smc z8vHc)Y4APad&2jG?+M=%z9)Q7A32FbAfG>bAfG>bAfZq(i8GbYTX86tUo8dRZ zZ-&o-&wKMQ^q{4Drc@U!4&!Ow!vhtG%4htG%4htG%4htG#! z3%?eAE&N*eweV}<*TS!b&x6l{&x6l{&x6l{&x6l{FM=Ps415MY1D}D}SCYm3i zn(2s*MaHlupzHA&_!Bk5Rc-PBH4s!okTak*W1IKPk3>rONL8>g&K^Bxx#&s8x~rSe zqwR;Dd4PiF0CFS9g`nerjuW&EP`V%8*+=ZTdJSoS7kai(j|+NC=$u;UIdd94&k4E; zsG6V*g4_T_6QoB_{^w2X{jWwy>9%9(232X#F7#OWqh}O)-uj~F5JAfb$^m3b&^|!L z1Wh2wpB`1Q57K`qwMUOFJsCsvd@mRs-4cw$+{izQcN0Jz-vQN5^~SpiphPa9=0ZSg z2ofG`5oJN5qbz=dorN|*C!qt-WoRRm3+;t2K--`K=rD8*+5jDec0=c(EzoHw zLypaJYhhC4*a+7aWw-ySt8^hs!Q}2Ek=d z9lKOXB82CP3%n>?;LXMb-fAU@0G<;r@D|_#&mR|fE0iS7@H}vV7mEwL5M1C%Sjo#{ zY3kEk*lamg-KB*+E61iGJBbUj%W|wIvRqt{U65ldkQLy9?3x_QMRpVyWas5rA+poB zAiFBZ3Xq+^1=%Gzwi($OT#((6V>!rja6xuXj?F@L3KwKo=-V{isV=kvV2^SmB_ISvOHXn70ax>MP7g%9mToKWI3~8-m{)L10SE^J z5=X(RC_pt(GfdSkA6A6VHp`B0@Uy0(bs0fs1Qh~WMUZgba7o@Hn$)Qkrg~!?dbEAf z>SP&z>~37QS)Awhw6@tzszL8%GSKIjpiM9)6#xq%zK z72u7Y)70Y*D4!rzf=&UtNYEuf)dXGLvb`hg{1HlV+a2=gsr5pSE*?Z;7NA#4?ld%HSjOX4mnV>vC zzX*CqkTam)#`5fMBgjOaRTvE+S3s_SJQaB=@>Jxh$eocpBX>sbjJyna8S*mZWylSY z8zMJEZiqY&c^>jSBQ-Y9M2(FY4H-koBak;BZ$RFFyaBm3a&6?=$hDEDBTq-3jyxTC z0P+Cj0muW8S0k@RUX8pOxfOCN~OH z)(qLFceUp&Er+BIq2ZC=^qH2s+1P z6n>$=10kVv3`Zf23LqqO4s#SLP!JJ8=P*G*NChJ39JVMlqrebB=P*PeiwZ>0Ijm5q zMS&%P&cQ`NLu8hd7?8}_DaV7lRndBH~xq%2=G&*sI)&4Xbqm>+zk1y{UY z8t^t1nR$)?SBW$b$fU17rtMn3>gc1Zlf1)&j|_?kK5`O>1&~D8YOvEV4f}6ptm2KF zW!@~5i~c0LcW!xN_JD$e>N7W3w%u|)yTERm(u+r_#Vs1(pzI#U`!;{fq!k|9C#oU#b2a&5_|A3Snpc}u~7YYSF- zD213$63Ph&hj?wM?#ng46`hj4x6ZQkAz@mCohHm3*tIjj-Vr7sta$IBH5~KC7-Du1 z6F^KJF#%vWqrs@}!zgDO6*h8JdCTVA*A{g6x`db~o){qs!AQKpu*UZ@mh9eLFt}{*{PICwyDh`KTwZM3vu}R6wIc!_BiK%jEKlF7yzd)RYEW#IU(?K6WQi|%f(f2dPogNYGgzj-C(0Cb!28)q;Sm+`P`HMI3JPOTIG2mUc@#`gD4+t(SVE`3;B#k?q`*A{cM&!`#bLsNuwD+ju}B{w^;bJp{CB6(AudebNGS4G;Zb z071qC;Y^S630h7NCVjFbXg{E8f@}!FnI3&5Xbm6%O;ROj7a%MDEtYMgT+c0d=WF!h z(IKO|8LO5ZpJgt{(Tx6Nx^G_jwS6-S4i*zMfgpcCZwN{N)SL}SkDxt(;t4V%$PZ8n zLGc99q{#%O1Nudf9YFy`9krei->8E(1@eNXL$jc1kS{a?ngcmNGa*-KHsl2PLmp5F zWDj{mE>Ixk2>C(oP%tzV@`2o-AjlcQejfJouwR7zBJ3AozX=$9b2>V6YFT#Ei_KUDzg#9Ay7h%5$`$gC}Rl_!F~q&8SH1UpTT|x`x)$Ku%E$x2KyQ8XRx2aeg^v) z>}Rl_!F~q&8SH1UpTT|x`x)$Ku%E?#7W-N3XJ=#O$FVKWRQP`W!N-yd82{4$KiT!--7Z3 zz{6&uV1&X6DtM#dkHSP0KA|v+2yYZdqOhL|MEId#iNX##g#(i1NG4#@OJBHdDBQsM zH(38|ba}=(I^q!&exoo1g(W9ZI7p`~qBCRShXT4WcQh8!NHvUmd=jIWqulB}j>&Q-F?R z-L(sq1qaiyuI)V5g?L2bO$6&!^}#wJ&h%*?LFWMl5OkU#oas?ML8=7dOrI_ibO}&3 zL01X#1oV|4SwI4sw4I=HZQi3)^F3^3*2s#BtLXFU1=pYmby@Dn} zSD;l;C)5W@h8&^0&`9Vw6b^law4i;EAM_lugf2qMp`VZ{v>kGX${|yz5Q>4CAU!A( z3WnZ7lcDR-8t4xs3nf8Qp;Bl#bPNiEK0q4K9>@o(g3O^JXc^Q7sX$vHH|QZ`0_8)| z&{s$oIs^qlZy;N!1WJH@LkdtTSAfD66!K9hKw-%ooI-;V6Sz5WPrwaAp&jdA z`tR2Za|RKNBmRTico~4xPeEZS3Xkaq57L>pq9?)+)*>_>4u-#sZp?$AKAt8Y)9+?1I zjb3%`sJsFA3Q(-YWTqeh%8_k`~W-xIzkd{6il@GIa~z^{N`0lxx%1^f#5T=-o0T=-o0 zT=-o0T=-o0Lij@XLij@XLij@XLij@X0{8;>0{8;>0{8;>0{8;>&G4JyH^Xm+-weMQ zelz@L_#F5g_#F5g_#F5g_#F5g_*w9?;Ag?lf}aIH3w{>-Eckr*eE59$eE59$eE59$ zeE7BSYvI?zuZ3R=zZQNi{95=t_&oSL_&k4o{NMrdgM6R>ef;17@`YwX@bN!8zz-fE z_#*fWdREjJb(x}maQd(A5YKCG=^XjFzRm4vX+t^yE&=NS z3;>`7APRsbfM@{K0E7T)X+nPh8UPjmFa;0^b41k9T z49+0w2Ot!{Z~)E#(g1J>zyt!fHO!200;+Q0w4f@5CES5 znt(G%1_FoyU<)7~Kr?_^01PIubOw43VE_yPcml`*z#{+?SULkehiCv+00aPP0f+#w zG=a`Q&mjT;7XTlC2mnI>O`tQ-a}WUF0bl^IIjP(kM^m|SpX*ijG}f#5JT28eK{aP} z{(<%SH^vU1oOtV4Dt8)uV0VDHtnP5g(7&e}r>fi7}x~-~I`%8OE@+kD= zrE=rYGkJAK?=>}Rjh~b?3wy5-%OK#KL|{)r0RjUGP9q4V;0%KP6r4ifO+g`oaTMeu zSV95KQ9_VKb6hB(IYt!FoJb02&R_~?P9Oy|XCehOXB7oBrw;-?&2glF=8U9(=7du~ zbF?U+Ierw-97_sl&TnIl&aroXHf>oHZ2C99aZB znlqIGnlqdNniEC=&C#HM=J-%RbId8AIm;-ZIVuQ5G{=nsnqxu%&55Rf=IByDbAl+K zIkptgoCFGJjsgOP<~UP8a}13u%b3%{)`%l0IDQ_rC@4f=ML|A-cnX9F)Df^J z5qMHifPhN@%@I&Qb2t>x96kj!hetvFuvOv_T8$s>`R1mnoSe?l_T6O{dwxs%5+4)} zxjJ@TKIMnN2|*+U9tavKut&h2nvOrW2(SSrOoDD>q$3))o}SJzL_QDsUC?froQ}z6 z$A_(%GaH@T&=d$@DS(dvOaKG`IFkz?5Wp4yegL8XY|qD<92mhcQee2lm<^*7x`^(t z=&trdcOD=Luff%~43B-g^;Jw){)@R@64- zQIHNa8?u2`L-LRlGzwY(4TSum3D62i4f24@pjb#B3W4mPwU7*C4;etAP=Cl98V4@kO1O9{C)R77@nHJ zu{tq+&73LWU6->Tv@hA?cOvc3(eZ0)e2uHh+zSy{P>_!xjshWqz6kz!qG2##6-;P= zwEYj-nW1rxZ+MqA7}YZm+C2_9XmH?$+NEeXR9u&><5o|?J zM3qAnP$d-z|Wg`MNs_dnJD%%h| zq{?9msImcp2~~DeK$R^B@~M(R0aa2EL{nuy1ytFA;44**P(YRS2}oAXh-1iaZs0D)Ln1&d8mSJ0o{SUWU93c^UFDojx<%2#Ij$oa_m$oa@?k=G)xMP7@Xhn$C;hn$C8 zgj|GNgj|H2LCzp&kTb|xwN$8n2l%-LK2q6I0HfZeP+L?ok*t^#JlE$Oj-FiOFuK zTsi6f`|Qk)p~)Y>VF0TDC{V0Dey&bmx4J6Mp7^n!Ep*^BM7H}Ztf!mAqcc6@J6tY0y+==n8>ssI?r=$9b2>V6YFT#Ei_KUDzg#9Ay7h%5$`$gCchKm?>O>AF}``1Yir`7XS_b9smXaTL8cjKt2E~ z0L=h+02lx)0W`rGfbgEP*z-tk>p}m^ODZq0f4+Qo*%P4d(J7j+_MVpioHgS`RUKoF ztyr6Qi8b^2HeMn9ilk&lc>1c#kABsLN0p4Z8J@$MRlN-FZ?^SMe5<6nYJc5@XP?`d ztm3|TAD!~p-*>dE3oUHiqx1Z%3n$pPN90*r7h2l53-Xp*7h2hr&&^Y{j)Q+^ex>+xp0$C1nxbr-5WYhJ1{JG??SbJ&X4NmU`oe4csyUi?}R zw>wj+42255w&qMz)!^8!tRHipev# z&a|`%{}!i~*XER0kZD#I_w@7LqN+5FTYigIv%X7+8vYlMo zc;)G-*gS3P>lQYa-`bV)s-5yqWWK9wfARU*`6}DP?{qU0ZP(mvJofZdOrEFpnh7?` zzqR+t6FTLc$-GhD{`T{;qAK;nYjrZaR&*s-3653W^k5cuMaSv9Zp?ZbIj{1w#U5LC zIcsn?;>P)n^M)=Hlu* ze+9qmy}}_xWB967DzB9i+_!!EXgc4p-Ev%IdhyxJmTEc4>^mME(Y+bdC_}O3deOil z4N1mL{?<22jC-AMI{>d$s1)~KD=9gxqx(=@jv^jz1x8ntt}I{DnYOH*cy+sx~}=ncble_)L-aYTjOzFcV<54 zPSgC7(2HH6H6G`5XXkV7Hu;v+U+h{^<58qLFF)%}Q(Q^trLM@D$7gk;^0V$X%_ynA z)U~SS@p;{)`TRRgi%LR^yTWT8pVM8P&%fI=r=-5PYkAG%BHa!7wRf5lOF}Pq#nhOc z)!mX`d$-AuK!S_(s~eL)sWDZA_3h{*pFwq>Xmc#x>H7 zzkBX+v$WAi+87~itdKVHrHwaw8l@Y5_uS)lX=9MIF<#o(EN$dT8`n~!4g2TsSa)%C zoa8s%WTW`kR&-W%HV2^dL|d%@o$d{yT6AVSW*F+sWFC?_3CnvXJnsQ! z^#GCoPWTt7?g8fZ0Gt1vu%c(eD*!5ZEf!YaW=!!~oC;Q9FSg*dSYawgDQy3ni!I&2 z;vV3B58xQz1HA14R`vjm|4#T9s0Hw_v!eI4fs*KnY~Tjs8hBez?L@p3T># zn~(N1w@aH3_B221XX?bch}lU+A`TOzuH=}n#B>fveMYZ2A-QFQQTn52DUeR z;MI0koab@6TP4!g_MTQo+R92>JEg4;S!t_8+WJG8$u6njneBD=MkJ$HX-79ul2@{6Md> z0{b7D71%!Av(+Rjv%0&*+Go3mcW~!+x3}sH>(@teq)6@Rh!mps0N?-C7AFc35-ZGQvrCQw~Y@nA)o&9g~|2q$?`&ZQmQTIoq zHR5V~J`)Sm*sku^xs{KPU_V55lCRzW{4QhG(CggQA;jmkPCkeI`QPUMS00!u{d(4| z6RoFT&$42x#dw_s>sWbuomE?EZ_?{5BhjUQep}sSWa)L5?-11Cb*}Bj{)gsXY#&pa zEhABx-Q6wLzR*3qgS)W1y@mgzdwQKHyLm`X)jv**a^COS`u~BilmGnw zXXT%ttt+ox{#Eg(q4moZ_Qr4ac@}#^Bkyp>dIdSohG_(1`G*BgUD9Eec(>tk5?|Fu-0@qULq!W>jnC?85Zf z0ezxg9lbF~*L_z0?scPHwAhW&czM+}C_SfMaB$%^yAD~g_dWBVYq>5}N8iqmc>L40 z_VATNw)Lm(I(eNwe=k0^X=1_tv1x|}z8F(;e(|BX&0C+eIu4qU%szHVK3mgYgR5_H zeRAvZZx3&jz0*&ac=`C=8P~kFIW3*G^2Lrl>rMXI$lH5{>&XiFeNu5D9O7aC`y^e>UezWU<+%83*wQ^DY zx1@YJa(_tR$@4cf(lq#X>NEb_Ej{})_#F3usQ$Z%bc^tk!#F6^3t2-}fRi^YNnNuP>f;S=nCEG|Ja=M#|Z7K6(W|qQ{jL z8>kznmj`}u9#JaVZoX*p!^){IwjZAr#LAssSe= zhscPT;h~G1BEuKWA2B0z^{VNDMf1a#O1}j&X9m0J+G|d>;+Mo0Tb_t2yy$D7zIo%K z4V%=rWZMUYy5wxB`!L^pgvO|n@OYnvj9&~#t`D=0=X!0A{64$ow(91;-W^<4G0}Wk zJhMh6d;9i@nyvTjl}rY{v-vCR`E6U3Xu03H39DB;X&TaBXRW6Cq*gz62kZfM9D-s*n&?A($ANmE~ndD z`R9V7!n=ld)8$VkFYm3`G<&~pbaO^P^nCldnIdncl<4QP8b+rbZmrm-eR$Qi^O~Ag z!ks054^>ESsJyUpWBQ~LMy*b3;JWkMl|w3SMpx-&x2Uu)bNw+SI;?fqi3b-JT(3eJZgKPfQ#^Ym;lw7mwIR6JPwSwZFmOZC;%k=8Sk^R5D^ppSN zOYa^&KQc7dbAh>6^+^w;iTc#|H50=Ymzkc!c0NI2GW6yq0 z2)%QCVP=V5&H#m%?GG#ZzCPSOzkR1c@R&mL(OYi}A0!`;Yj`C7wR`_-@7>dP)@#*{ zn(guT{9pDXU+*`Vy8N#C?18l(|G9K_k?8G-S^kHd-&FYLcqX_C3+Q zs958{nOQsB3r+D>=ls>QJ-G4UyZm3F$I~wlewc9S<@S@NIXlL`QWa^ue1C4+8mBb( zrBSKzSClklZAQ7*+}14p#tfX%w)xeV^aRuBi&ut!`#kMDGchV;#0Jw?pUUA%2ipss z#>aI^=8j3*F;X*C@9dZP)pG(aT(;$0u!*U6bZ!bAeZ-4%s?Gl9ugH!C>GK3lh6!5w z+gmK}?L497Zl5flvh~TXoZp)NhqQNo5_DO%Kxf*vZQHhO+qOAv+qP}nw(V(K(|Wzn zIq${3C*t1y!;ARh`va<0Wv$FyD~nnO0t6eyHSy3~fT|sR>uivPn`PaJsN>I z4%;qN@WIxQdSomrw@CofFp*T^eNg8;c3G7F{v_FJWxT7>^JS#Qv}(Bqdxc7QnuAK2 zQdDO0gx5=`08Ikp@8$Y4RDT2J1Z5unG2CW2n3P)_0jfTs}^DduQmlS!_i&vc^0 zC-b5uiIl_d1J@ODL81(Q78Dwj9b?fXnCwDysf1cbPA?Jd-17c~eyo;Rx`gk*#|HFw z^soKbwX61z=oh#7hPttXqOrZRv5lcIk+_YagR!--jgzedk+i;>psllwldzkiv9Xb{ zk)Xbnm4UvY<$n%_oTLOGKb$x6i21#|q0`>a`q?0seTh*Uxzr#qkWE*PAtM7>*NfA* z%&8#I8##j+fjB-C4Y?fArHY-AlMT*alvt1tKrmngFZE=ri17{Y?_skY+Lk&&^J^Nr zbo*tNoyQ&XbbCZCeuj^Ux){yrv?*uG;8^fDS+s>3yY9_!oF#ZmjvsCG>;_n|(MSb1?>sLvSBv z8PoStUVG>EZH56 z-BWuwEMtBy=3sfWwaikMB?eLyou%fp8wgi@WcfJpbVJ1l~hoFHGGICSI zD8*3p@k^UQT2IgI^Ct+%3pfm`GgpLoPtSkS}f=&-^LIT}p7D!#cSL4z80R;t_wXx-POm zb~rhY`~JAlYEIhuw-&FlxaK$cUS87?GZVLvK0r5}T(|zXDL2CGAMvQPf9Ar3U-9xL z0J3k(<`_p10SHLsT#0fhS3Rb)7a4^Gdwsd=N!$$#?5J?=p}6k&zie$szWND2Or{%Q z!CM9P#D6}=y;C`#hfHPCD@;zKEw}O{>`5Hh@f4YoI8P)xn$B6zWB~i!*lkOQJ_2(y z+X^YZS|#_+Rocv4N1#|UB65q^`wQg7h#o)obA`xJNo6mcNN#csI|_3PDlX-zQF+C~ zXzkj{Ps@@Il`B4&Y0}slKSsLGp-mPMch4UO&zch$A6gCM6RKy0=t6B}ET-m}21^k# zV$PtcXP*nEL0nzYXKj?^8e6AW>9j%BfW*Yd@;l`XJr-7~V8m4RXWL zMDRN6s#cG}`d~T&0O)g2!&id3!#|C|v`y7U2ehys<-9AHG9k`4nyXJ zd*?5~!M6L#e%laUDO8};3)wRm&1o7FkhD50H`H2f5%y!sV=v{wwg=GAw)@b2-4J@I zh(#CVkJZdr&^vva^ZU%ulCAqg&TV(vZFk&$B@}g&N|=rF!l&=)>VDeDEQ8K_Fqsb&%^*=g%DekuHVD?MZp`1#jlHbS-uy;lJmQ})nt}@B_RNX?+!elLg$&!& zQZLazteEN#<>`kj^(~rXcNeX@!%MOV(-JtEqdHpe`gH~}G7M5OGZ=C(vQKybu(8sF z@ID|h(NnoBmyb29eyvz_Iq;%|&)z-dl}O9D3n}s=W>+4JtJp+mx?}vf<0V{ym=jX9 zy$#`r>=07Y2z_6>=#DK1r^yXY_NFWeX;#p45?fJS(DTEw5c3gWC_Lbn%pO?KUvVj4#t@pvnO^I{5=DwhHQiK z>D=c+lxU|uxEjbl!R^m=QQluu#BPMP16v=4SMB3gw8?8Q`{=_65*URJ6dS;26zRS{dDeYJ3o;y@$!aGG2Z*MT*0wNs*Co8!^;{jTH_Yx>t`? zTwdO2Yx~=lT%S2Fx{jJw#aD3JTqSb$MVmBgbv1`6i{2iCsQ3zEeok|}g9^NmzV-Et zt3AdqB^oSAswiqvnm&q4aaPK(-JV`(^odsY&E#EDGi?dzr5n@&ZTpyZY1GX5x9FjuVL`w8qc|I=gYl*zmL^J(-Fcb~7&Tb4ix0GfOj8{vVQYfybwdedC> z4Z?*eWzPPj9?tgb`T3m4U&<#GWHIz|R*29)AN-B|8o4TbRwjNCEeWvPseJWGrYr-W zi>D}kmt#!T4kO1!OvWziDv#&Ra&b%G#Oe89Vzq6|Qzg$W5`MJ_WSEdGV5aofir`2j zK!qqogK^%qk&sLSdtz_)9$C{FmtDRT(f{N1`*+U6@b4?QC{f)OK^|%3t7W!63Tbw^s2Ui#lv;b! zf|5oE5n&xwYKL|JIx?*YMsTCX*g$eW05{i`hW0GtPreWM0s8`c9erIBT<}*W`~6#v z=SqP!z)E7jIcW3aNdEWHdVNeC_1sKefVNr^xN0_OVHD;8l?v^OyiL-2 zeFY*#Mg|COpx5Hz1XzZh^QR;zslcCdfoVq(@8a$&h>Ywt+ zp&jAz{uOy#x>8T7*ntPmCFf^nb$v^PAW|mTpIs*(9R23a$maT*2&uYf%TO)F&0K$6lw9%e(`~Uf@ai^o)s* z|J+9W0*vGRGkDw80YFdz*(xU0XNXlx>4f`MY>rNkD=j?o<^L&^ag(-fqYDx){Twm% z8{h95kcwI_DE7XA_8`3HR(w4-QuiIMZHGwK2mhY*58_`K zU-L?$3Hs*w)&D;W9I|%CHs4%d$@X6*4l#X4GiiOh|F_1L6~%4S&j%N@Lj*?(LS9{_ zAlD#3MjFZ|r$)02knlLlt8uNdO&n6N`vVK2E|dk?mdW;^aPFCAWdXexVF5_oKQZ=d z%YL@rJQB`CnAXK~pwAkE{wUcy%dyAoH3mG#vLfm}s>%Vpi4su?Y{#Y)>ABKUe%(2% zLB|>EEQup{xYXDEp7>|r>9hvA50ocucI=jBqP}L?ehV@-SOw|snyOIGZr%!8sCl4$ zCt;`XS7^pCZhOha2gqMbgsONB+WvjW5&j1YU;nRENaP>GfP%53xre@im9dbm^Y@?M z!9m}hNZ8Fz-^TH;vZSq%@qg&KlC|uD9Fh+Wr4uH0q~9oJkZ%`eH3lEY~Kf4 z+PdM7#b4jMI%*R`Lfy^}2iyNFnO>4SmMI#S^I3|S7Yx~iCZ3a^*-7!2V8<9JJq7cm zv|_gEAyEu<4{ZDh&dX+ee#KwWrb+i;zQLZOI(+lXqUVn2aK7SXs1K+B+paIVrjxpLbg4a=bwW@sA$NoOqePyZ5dD&V5*r< zHiNw;+^jmEKe!Ydx4~IGCqY}Grcb7WtTTX=ZP6O0i5(}PF@W}MHQK6TfYPWY4c!%@ z@im9qi1OZmC=EOMI_a=-CWJEJ94{Dm9lBot<3$5!HM-QE2aNdD$VMQx-+kp%cV+7l6)+OCqzRY363-q{+NK_WS zPq>f~QPLvAB>Rl}jN^9Cm-{C|FH(0XVOSd)K`ZgTOXfZy{5=6r^e&>k8k{|; z{}9`LYJ`FKatFbcusv_Mu{>|oE+cTC=pRGiu_9?}%?Z_}KO&!>>%}_FHI$*qQBmzC ztkhXHlo5@AElm~+Ye}u=+V*~)grORt_K#M%mQ?Z(yjU!TMU)jO8U%TAWUniXdN zy;PP<@h0f?&yn~Y23F*)twtJ{?p1k7lpfty%N8cyl)4KS<4ax(Eak7pQ?+2C?t`|P zeZ6yXF_@rx4%&m{wK6EIlt(36+I9{7G<2b+YBd`uwodgKM(QS`9;e0a;&XQ)MCWU> zm%^tzX-a=uVS*LSOKj!;ByBE-l^v!XLt9Rm@e_YYO-!z>gIkIX3yK2XPfZQ%?rv-Q*++d#c=q~tznXsC$U$l=EP9bv;8O{%H zZlrW5lsVuIeDD<`Kctzea0|1oOtoqiJ?_3?$>@+A zZt)RkHGlO-nm1Y61tSncnR*~A22gCFQ%&R8)EW=+MSK8ZHQ)jlel2-$0g_Xk+>XXN-KSm%sztz;G4DT>kcEq z(9I#*Z2YU>>m(h5nq2tnUan@i*>Kb&;R^lTcW%w;W1r!6W~^_h1hVijS0-OVht-KU z5MAu1X={Dt^rJSgbGmlwxve8w!J7xU7nuiQW}tby)v%9TeE=YPRt{w4Mpn?^sewy3 zX`U!8w=8>*>?+>-mHXubdw~0`It$$?NF}3;d&rNBgyQlGG@oL2ptq3$94dD7xT&E` zE`;{xtqgaMVg$FB3H>+tIw>Q7_Y8vllnzcfK4IYMm-fF!m@HZ17%MpUyJh>N}>&lI>TrXt$X$- zKPlrn!h84vqmE~rN4(Y=|J}x8{KtsH?_lm^W^L?bZuqx?R*|}=o6=F*m-k6#8-v!QF$uX( zAugvqR)N<(IEkHqh%ARa!&an*8*XHmEW15KiTlU`ilN3{!p{EjM&|+4bN9d$8f?$R z1y&PX!TX5f%<2ud&sP{CGTO;w1J}DEY4(ugrssB;<4boyI%?}P;FYx9H5V&t>nlDh zZ9Nw4+701POKltA1K#yEj7AB+!5&*%y!`?GK3UqWRra{6nKYVWV(=CAkp{m|a zJ6&DDMp~xa=PQ)j#OCJYCWz3FhnqJXkI-r}L_3!2>!pwcc!Dv^jrDOeg}~EO_|eNS zAw$8q8$Gh(>rM32sNZvi{L!w$r)$;&6GBDexY6fbdxhJia<$~h(jvhRRdGUrgJz*3 zhGVt%0Uh3|ZnkW6Xwgrg#WQdt!0Oc&;YEcQhe6U#Y!lf}YCXRUO;6SXh+>ZsSDEi_~Q;N@TDOBg7dQ z(KalVz>SYqU^ zff;#{uec_)skG;g!!QEqP@R**hFBPKc0AzEsW-_D7+&c8t_PH(m?t&U6OHaGX#34K z>ZeNN($DW;NS}RpbT&6py>*(8O`skVEU}Q56|>72e%lQ=pd^xU0P^!cRXwtLi4)pk-ji?AI@ll?M<+}2SH~2 zcF?D^aolsUY1Z$6blsIfz1lyfy)B3KJ?hszu+>@(BSF3+{2;yLNxYO}*f~ z%l38Hi|8aBp5i@F#95g#f%ZA?59vIjYX_pJp=gZ1)&@Uk zsBIx>H>`WI>-0_c^_$Tq&V1-jR?B3WopRUK%wTP5blqw$XmS)4R8+KdwNxeLKeB+g zh$l+bVTFbthyi=|90(xqvLtPDJ578uy~;Jjl&Be_zB0>+8r7H%qvTx!%3FmS`k))R z*bdYW>U_*A#xCYjsac;}UGGxQJxm~P3Pcot!U!+e%NF7wl!Ka#k?@SG7#@I+#@%>i z8?kpL6F||Vn{xbfG1*a35!u1`RD>vEW3E~JUf9L9@Q~5M zO>gvZ<)5;WAVxU5QyDZuExq ztork7%_x+R!kptlh+uQ3t+P(wk+FAA2!a_xPd>ZYVnPx36x$dD*)n9vklo!2V-0hXw& zy}D>W{i{=sjg=2itYGN@MawEBC&Vo~LVHu7Dq*`fYPJ^Yy!1rERsaygI15Vv@lp>U zM880rujxc=FU~H27k0dklrCm_y)NOV2k5-nu~uCt*gNB_?Z?QmwFZ9A^nm-EuhV8H zy{Lk^bdv+}rkY?EhI<1pg`y~<2GQG+nk=^hsLDR1S2y`~B0A~#PECk2KF&A^UjQd9k;FTU$F$!X8halquw%RF((*I8WU{CxGf0$%U<@Enb;3_ z0F-H!jUjX}N!>b`TwSd$4ABVsRAmHw3}60g&8a9{gz!$I3o z!{fQlYwpJ&{%iZyaFM$8jD&k6EMa!`l436s){Yssh^y{jo%Yvp7*)T;qLizeJ!SRm zWul*vur!*yp;T<^x2uZG)TdF??uEy4H`2@NjyGZqb2J?_W1@Vl@7gw$$9R^>^L z^|S2q#3x5Q>V9Aj3T#rK?6JfJToS-?24Z#@&=VMd8}tXX-WcTE?CHoyf(GK23_-II z+6*!ppl2fzv(eh*d(MnH6uQrueBA@m@!9`Fh$H6D`q-=T+NbB?}ZTVZZm_kKKs zNw!kH*g_ysKP=zqA`xkT{W+)e!{Nw_v!2OI@lXkunaPh4@Z%;7WNX`I2Do|?>Kiw^ zjqF!o(-EsO%}hM0es+UhjQ_LQ*PjpQTv;)+lwNW}{=yaHy@c{KOYHob3`th{c=HL^ zWSD^KcGvW=fMGpI(67pA-TaB&FsQJ%DwpZx3uB7>rdf8a^4=I;zr1uwyMRz z8HT)sTFF92<}1ebG5pPR$H1|awyM);-kt8>$tCi=E6A|7KCjI@dZ>m8wm17_vR!NJ z`$Q5>BWU)tr-fjf(GS3on=s;Y^enG&8-0_Lj+~)&^sAdN2#Z zqzu@Qu5l#zIQ|sf0?nRi?)&hGp`!2zF>@zF_EyLRt%8|+F>VMS`$#Tf3$40dkg#F4 z2j}}x(Gm2S2s=X)`&8R-JEVm@zhH;ly@+UbeFr06bZ_fx!&Qg8ZVeZPjgb4>q`Vd( zCk9KxwJwrVo8x<+C8VzVTcN(^L0DM~#y-SN0--Zk_|+&_9e80s$Y~i`RUF`mT+Q=a zRG0KBUr&MAvrfYA7sFr1X?25lxJAsq!$1rYBSpB9^LWL|V*^Qhfk1nqz@Zc%`soPevoc{B;=W(wz4Meux4aD6#*0R{8EE(uJLL>NZcNz#vt zxZ+YePt3_}mWGy*i#QpnfNfJWr$Mc$MH4R1t;!jB))Za+t;$V)jMjw09>|I$>=ilI z5$PE=b2pI!Ug(csjWlcgrkqqc@-wpR0v6+lUY|OEAC1Hc)Oxtx{0F=}Cx$(ac)zWabDy1{}GPSa^ zsWQ_$#iWi93eJu8#tmBJ(gPik((mvbl0xEYxcrC43vS4C19aUZ_xoAp^1Kj#9@$qa zkYQ8E8e};jK#!9;1_JOUOtfEClC&`-pTZ>9bI@|0fTDUwu2?@;9{-Ul1Gd@H2uG-WTE z5jrBoE6IP_(gD36{^8)yFRrr#bVu<$i*_pkzQa(v0m))cuNl@D)U&gPrwUMubHP(f z3 z;F*lb=psqHW33l3#1CGhKSe2a;vJqU#8O7|bYx$YuHCqTXVkwVbP%s&CFc$VvR-+QV9|lDn#Ui*@v_;v`A&fG1(x!__EK`mx zZibiTs};Y1UAeSf#rd9m51)TyzL50*gfn3IA`C(yBL3qt6o0xjf4X?A;9zCQsxdzj zLZK8y{xsa7-IK2M^7Nlq{;iKRpCh}wFCR1r&rFwfwIv?k*5Up8otfhn`Q=5WoDG2j z(#W|zc_c>y>e*v5GU^4X@%L(+LWw^*o25AY9L`3;-X#piqoawN9k9;}W(hkS%solWyDN48|UxuNQDV?B<_9`{Cd^zB4(5!X|82b73sx?;*R*ah`t5O5dhb}X=W4{B;+%L$P z1w`FC2ppEYcNgQMF%iS3CLkV#LEXoS?R$~PMf{{#Y8+_QmnTV)3MC$zb7g@|tZlg-J?Kju8#-t9auLIjtyvK* z7J0?ec9NZ)a>9O+{r0#qLi>ZFvN!4DEaA5MhK!V+y0Cip zXTW>olGkLc*A=jfnI}!ax{LP2j*}al+E2lyoA>PL9lQJ9dFh&+=S{xr`eX zoVmKww|DE>J4Vs0`74$UkbwI76(*fV4k$}n(eVVf{b{~gw?bsm2|Qbm8meIO0hg*v z{vONMj?VL0Tw;l?`}Dmq6RbPJYR=8e)2!K+EuAhlgw@Esw9U1HZfZIMytN~5$<@yv zd4HCzS72Dtj%oI0X|Cj*-1HPb%A&U%-Pvx)6AHlv9k!hIcbDa?Ca@n?MDcp~t>&?9 zcQclgsm)|Ro+u(7C`<;Gj+8K(LLkbalD0_9YSL_M5Nn(}hqo@WBhY-+)rAHjY zMk-aXC~QkS&C>Agmp+j*^H?@F%xce5v|oe)9z}w1!X#)VEe?TYe;qc)t^v{auNj(VrATa$#LK^(BVWi! zBpVl=*oZ}*b~{rjPRbPWb_dRorC58QyCe;P5C%YkFrkL0L@uH}EJ0*zDDe=~X^cd_ zHtPE?tU@9Ef)f44YUBTjRsMg(>i;E~{EunjuVA|<2lr`W8>E0L#0PX;-LBV&kUg1C zzou6|Mi7REfIH(dVpGRG^ptqf5XL)78cA|@6~iFYQ4!C~6$)!Qt=02N!not>^$MZ~ z2y3-iYq3`zW!Y*|5QvFlqtR--$CB5K{JWQnFfqgOEl`5VsjtBjW_Hid0(HR`va zL6KF#r1sQ=1Z*ps<-)OkjExDG6^5QcIUsJ~_+aYGUCW-cKk5|6WQ0eHfs9@7qJiAhrN|Q;| zr%hC8C5AsI{3dc#WAFWkXd$CSFYqK`&!(hWY-Q&Q`#5msJ#rCiMUMP;|IG;Cz|gOb zX&lq=a6SJ8EJe6xR2QM}DE|&Z1wvQ*FtZamY;mr)Qmz`MNs&PW+tp&>-wuS;5DA@= z@6Pkw|B#{ow+MyrA5r!92>9K#`*#oeKT!KmDEzh|Z1N#-Cyd!_rlvc8R4R7_39NY2 zA?=id?GsRGZwO5I$26SAPO)T+62ZUA3Xm&7e4AnZ6qLIT8$+H2h>cFBIi6&CUQfP% zxH?1ca&Nbm?ixe0EI-_g_XP(?gM12RGuFZg9!U`u5p5cmUJaRRT_CQVIko(OdeVQ& zGVr05IVy4BiapCfBN}A#P$!G;maEf|73)A7W*>M*g|CoNL0FN7L>C|0bzV>^9}qfh zE2Q@9k`ne~L*A1E(PzOiHOGk*rr!h~Cy?@0Ydb^6B>ZtYWtq}pYa4t~c+GvhV&A%93=Ut&)?l&5SzvImRt_c2TKZ@YD z0^32~>VL5$C~Vj)@WF9sWZ*lPD~@jgYuJcW=;uM){s2%W7Zced04Ng*8XR8Z&|E$@ z>wB7qaT4vOPqV#?$=y|(uHFGGUsYiYGPahZ zU6wvMvWUYHDoIk9526)gZ3z@)mQYEu<;DpGqH_O_4X?+vyeB>jb6keRj4B?%q68@5 z0RvTwTdoMu{?21S;j|+g1OzHlyKvY9WX^cZf}9w4HUyv4L3;aF`j!G|-UfwN z?7XVIv!YBQm9tV&KjgUw9zpNS698@`P$(HkS57dEpL;%1lc2%#G-Wj~LPX46{&&WC zA&U<$cu0nlGm_YwxveQiBuKJGG-I6p7f(DncBnKcSes7vkkY{&U&I+EnTD_7=cB&# ztEhQJ@K~^qv?94xbe>#9eU!kdQtvvq_IC?bjWN+cNWQw)yajA>5<*(mX=D-N*IrCe zQwPLHQ<}p!<)wam1X!7PzVXQ=fgIS$GYJ>u<1dHk zuNH5Zt1J0NaaL7g9%=;V(-5=04&AL8wTfA|KM#Qz92 z|J|eeXRF=+n=aTom>W9&txZ>@=4q$2g#MLvv1L`SE{50f(?y?%z$lV!pyW*#4V*gc@CL-8vIka$&ySl0`(m_oS1?o2aJgx;eJ! zM?qE@qs-;?W>*JzyxMOj#%G_Mk7@Ru*Y2HXHdDu^9oifaJLc`We6)@#vw@Z)%NXR3 zmuN5O(HYPBnlHo$Udktf9Iq|Pqc`eSTGZ!*pOiR*f-0*wwZJiI^1rs)uzZxJ-KC~| zw4%LN{7Eax`kxP1e^P4P76NlpnWbFt-=_@cY(A2gJ-(q}#ka#qGRtbxnGGSc5$K8@ z-7qSwG{j>vltc=uq>srkHY`Zx^cj83>p{ezPb#_=q222Ql>H8zHUh>XH@W(xbrKoe zx;~5SvM_l^@CH!Fh6Zr&cCpngXmOV=u`TP3AEx%R{wd3l7sTCXCQFAN zQN|4}iw7TN#xI*Bv%W}^G@sk9fVWcO{0xLJmP%3kps=js;>1*0?0+FqB`R5oLf0m_ z0!hX^2d8|*YQb&c$WSjH)db2CM4q;W1`X1G4oENUgDF5h zMzoIjECdiXwNe;a7AC@C-pGKl;D76!IM`;7FWg85R~=Tat*s$fPz7MpvZ5)WG>F2Z z!-J6nhf99G*N{XqvgpPzIkw#1ox7ef+nUvzDgLk|lF**jzN}GwtjILhIc&zd6kM>? zZ4{X50_;D(%$JJO?(BHSnBOSD&S%{``Kx*WL)NUWc6ou?Fbxs>!QE590=F+pa!4Yx zZ(lSdvV+?!mtg9dWHEJ6RIi!ISpaW=P{`^ENiYdp2Yt+3h_|(A{bt%O9e=6}DmV&F z(|gW{s&v_MK0qBc_=uux6NHy#^@jSQUY`&ErBiPJmfmV0hR$F>C6JoUWFUggW&r&4 z>?dnQDg)r6QzX~aoRB3`HF2Z01&JL>r_n%+{k*?C=I{+-+v@}XC5?bKVo!yEhJmAy zv{_%I2&R`=3%*|~bV;GNPbYz#JN?t?>s3^XXhD>pS_=n%5pKE? zP5a;>bS4tntRVu-gOjHQi?w_Jc-yWtriXn-?|wuDbQ-V&I{z2?cKx1pW?~L+%O0vj z1SM@=<57D9z)^}u;suXxj}ex&VRsoP8UsR9Q#z`6aD|5eGXr!{V;+CI&LVb z5m8$%B~}u0ZmXrSaaw#4`XQ{h&1@L2)9Os>5nV^woQn~k(`hpV@?sim@} zvZA)9Hm0K0S@EN;Qp2)Ir0C{Gf?S94y7d|g80k_nO*5KnyA0{{Zav6zkqyP$#W;Ao z0(-l{a+CPwIkH_VDXz0DL62NLzv^ODecJjKqP5IX-FN03x6LPItmo~Z5%$)vjw&I+ zDrar$#MvRGypirK?L2jvMSZ^Ry}jN(y`Ef5VcXEl`pHViL9!<8!cM&)5V5JqG`nwM z>nNEZ1!jByr(DGL(v9bZLv!82SYz|g7sMQrUIzn` zT{2+@Jdn+N5i4PgZL_rm2ia{bgnOSl7sPEo&k>5d=zP#oYm%*|1weP0%)HjxDSJf3 z5c~8*-i3FGC6v0%3ci{as9rNnN1|YDd#1#1y85h-0h$taFC=%F5=thJh1#ZZ_1ZHq ziPthKt!lD~DVT_-pUEQ**7k++DnAY&AX8PJb}*_SYU zfV-56Vo>@`0-CiU6+M-6fT3!n4_U-cN53olZ7#*xE#o_gStPw~?z;!f;&sr;1r?cw zbb1PH$TfjeX&Y{|CEBT=QpJK8pqrSo52?5B&4UtZ@c@6HP4RWz&ZB>VdZP4NJ0Z<;-Ksy(+^ zYj?N@lMso07wKiYT5r?*W7kOsk9Yog+q56On&Op=WLt&rj9fjaeuBT%t2YjZJK;i? zhzAGK3H+pyg9LRS5>8GkbnX0|jo=jyXlYv7kK+jRYxvx6FJTSXY>hp;4=gKBufjX} z%ATOo0qxCx&E!r@T3QZ+DR03>4neqYF6`IfRw3X^3d}l##YQidgdfU;9S|Pijt(FX z?mZ6&xmV{jS{mZ6#u|@ACMf+qlGW#dkQvm1Xq@k`x*jQ3iQF#kP$c6B{lY0aZ5P1@ zYa({IU9Q~ZFcv-NP(O1XVGN|A%5xF^7&(%-ip=p}=H!4zHd4BlI@~elbOlD) z*}#_1sc4ro62n#MLR)YZ=2MT2#p%n7dVZw?0`f5obs!UBs$exXTVBKYfou4Nrtv6f zE;NHw+y?tx5ecWk*~msnYqLWfEBuF&5!&r-(Tp@F@~g6WVyI%ciSm;Mqb50nnJc?i z6rPx_C~T^zY`Q@eWs`-S@h7b6n%*8mDOosyJ&{$a@+{r)Cxk7Fi5nDQ21{W9i&UD8 zg6KkJG<%}F=)^+H1x4({hv1E8(tlb!=(!{Th1SF;yT-^_$EY1?oZW+s-H*>i<)SCt z)p(;PL*h)0%dTq62TtReCkn_~){8DUendEft+`BA&{0lM!$3|{7ma3C(xIZJX~RI0 zTEIYdbyw;_Dxse6c)&#%FXN27U#QAou!{3}`3w~zI?g)S9oh%4ORhJumy^xWd|=Wsz`})2EK27CcDWHtB!2|1L3dd6k8zW- zI=R*FKhatdl|h+mcWS^h#bPwTN3i6uiFi@brVqz8!>K(&W}YQA*6{IqepJS{n8Di#FL3 z$hNWrKD;4BO38(E=;jV>vLlL)hnAG0vZfEy;i4fv)nCb+tj@Q50bky z*l`_SfPdv&v?wW~4d1dgRHXka=VJKB4E+C_Kq2h%oqhc~=T3^7kQm@Y3jR7(_H1cV zwnW}~6bV35MTRdIC?v~w;f)gHB$g&hdn(%m3*YSry~!I)Fh>?(^DtdQSGr7*`lE{RG=vr`K3dbwI` zV0uh}{*#?2cg%XSXA#v&TKzCt28Dv^L!kMSI0&g(K@4wf_B{qaINv2tvz?(u;E^}G zYnYYi#=~4V%0C^Bw zWMr*r$|Q&!*zqFsN;gYd-zjrqs!-k(0j}4kpOs5Km`;kIt@5VlT%Drx2nR# zvNI4Ua243G&KIYDVX4`vHmifVeA2^`WcOAyNWlc?O3;{dV?`eiW>I?cC*;f2>+CYH z_=--kfVj;8f8NQ^gUV=#h`7J8`JbqG*X6sIb8g=gpvBenTUHvEc<_QIbI#(njjj4^ z=I|&09vlLx+h!Blj4mV_2|hZ0w}wGhf}dQ9-!{}q0$BQ(NqZ#sNZ~{9A;B0Ip;-GK%w<^7gr4^Dg(x**F zjf`nWqRSfjcmc&$GXW$)Oc65G+b=(3lv4$2OM+H77}y6J8bEAMaD~?S&Nnux2`pLw5#=kDBWJC%SdlGN z^f0_a$&?7-POP^5=O{qGs?4bmE7=0%%~axOUyXhAWbkcD-~K#e0k|Q8||@M z-)_@;7h3!+nhWD3yir`I&ZzJ_;ajWzgd5g?zjq82c85`o9(i)v)bV&%W{PKN~#Phy(N3k(x%lPz# zxQRIR1@eFv*oyrd<%@4cEmNzkuR3^1;-CC%Qk9y@iR&VO`U`%k7Zz1-iskW(bab)|QDl zBH=cVq>Dxl3w2#|#xrSI%7t}f5o-{S0I=l>Sb!eokF>pWbhPvukRlYT>;vI;)~vIp zFxAJz*Q>9TS7x;&)a8pNyQT%srm*cnsQWn)*a7Uuih>wa8hdl`hFB&_bK}PL4%%Pd zd#zOYwqYuITqOy+;VHTk0vHNmkfk3*bLnf8s1Itgm9*2ybbvxVQ4w z^m$;VPQe^ z@khqp6qP+z#Bj;OOQ9}3ly~lxT}fuIvS3>IqGaV;ZYPCeU6MYyGP*_UBCt~6$~NTe z(vl7yFP!dD*<0p09|UO9Jw%Wk%ceynYb7svUT(i!Bq!frH5~!*2isckg=P`+m5pRk zZ&7A);4-3M93(x)LV^-z?c_*u{wVB$iMyX>8T*RsPojVldI(XZb1v|AyX-I8JGthy zJX~RXU%->EGHMx?%WaHR)_$8r8tpQjfHUZFWJvCz1h7KhqC_qx6eRn;xRA8@Niv`T zSK^ZyAn*kK6+t{_NRQ@c_l!3O>ggK;O6`P77bj+u*(C}+e9)d@CQoD@w+sku!A#MH zU^NP!Is-hN(e|BwB{w8lUXZl=KjGgj)S0FVH!= z3_L^EhmWj0hSF>&Om9E{gN`T@WkXYgF6o~ulcJFJ+5I0xz+ty=!i>21`}4QI99K$* zREGl!&)i~_(0TF0`0WR#j4BDTKz)w;zX^=f6>TMch0yD#UsEAs%RWOs(JT40Ze4U? zZzTS?J;mx9?O%a-Ru?+quVF=A;C~Oq|J^R2`^P~1w{`*Jzi+joZ->wKpc?LlWSfra z#(mI6iu}se{Q4mZ+%u$hp%LP9}a$wqmqu^kiJUpRudg$v(G(LaN#^^KF!XQ(A1ObdzhFC-y11x3}WsQES zb@n%ZCQbZlU@A=z_Pb!85!-gd3*W8tBF6_%%HgxDe7rJD*+z?S2bkFvqo=`${bjAI z|4h9SHXt4){y$Xde^0$Q|Hmj5Gjw+Ok4XKGHp>6V7*zhFz4HICS+e%Xj0iq*3)?P^ znrcFSGi)egN*#pMUS>T=um9@TCE34@05ZeYRd4!w9c>{1$J!W4OO-+=s zo?s3Ykf?a*dN#3*k<-%r1B_#68@9Y!LOBh7+Zd5jS+@P|EFKvrc2Kkj!7!=lwvW>m z*NH>R!f{iuZ=6x^jsJ2+mE&q6(t&LYCnkkvjwa<&P|eWLeDJrECn+LFiTkIs_*9cG zi_C7`{_fmOWzMB&q4NBsREIeF1Z*2x71318>&wd4ib<;t+wl)=9u?Hb4L<42NoA^3 z0T>ha}FzBs} zX^3}`_iKqV%`E&IBKbDA)={Yn*Jg^H6&WBKk&e)67HH_Tv+DS+?13(yv`k5kJvF)0 zLz$0%7$V+&!|4Sx&vzU>NsXRW#+tL_tO%y;vw1zyqfH;lNF^V7*6a-5yc zNb6*M!d_AHpmfjY=}V282JE&7(FgB3wi9`Qv!I!Q|2*>~Y>MQ^|HX;qe~FX-jwb&z zZ}oqpiLkwihq|Gq%m0Rw6lLju(zbuM56m)CuD)g!TtyWWN)3RKE=Nd{th4T-tkbKw3`o}7{w<9it*-@(FA8#^GP-4z&1nAQ|~7gsEwNBbU<0PGg}bi;}raHcL12(1!~pD`pHw zr!S18FgTUjvxWK_qC5rN+v&QGG(CI-P`U>}uqSC>n1f5df0CAVVTV3LS)?@=i>g#v zTIY@jKvL_(ICMu;N~5_*R~f)*^evZffj7v8Fbjxc;ZRxks8)ze3(*=FxG*<<)k%S0 zu`fIf&7Tvdf-T(xkg!Y_d!Gm3Jlm{17omo{MURHP6$5Hut3{||VGY(G>iNbLD4j^( z(P$9GEgr1oyWJ?^ESXRxEf9%GEtQC>L>tYOo#Nvu3nVE;qbwrxQdlLG1A&Z7h#p#@ zWGj1Ep*`?Y(5X{T((K4C(F;geEfMF7$>@c230Mhj3Votg0`-H2>2OXr!6{qhrw5Bg8&|r9n@GU5P1Y;7}zM(W@o!*GkG&ORA|S@z)5#6>zR;E6A%A z=%8-YqfY#1_*)~#h-LjdO#iD@+kdBR|L6MD|DkRFY2%##k8?wb(zex-00!@0Z1zs; zjZ*7o{-355ikk2OchVH22yIxq&I2jRCo48gHswT_43cL|Z=^a^1jKXTH-!WChWwWa z{IRKQXENu9oblJ^%~NFn?6$>W(y2dl1IKU$)S)w*8ubkphggHi_D@==ij9+Tyd~s# z{3nV;T@t1l6VUXBrVo8pQW>5B6C+HgB`lsAP`ZN!u_0y_IH54t;)+zxns$sVt1GXV z)dItThGqoL4eF-G1^V}nQd0K$M7cN4w6Ofhoy4l=5?2z!W`5sW-^9KH<7Ii`6;vjC z>!_xMM%b&iTMqSsS#TR?92COb-G#SLc6OR$SWn!wyR}u*$J~gPSUU7*Z{D~jt zlHXhv_K6?8q}v7nLC7cVbAl65LMSjd@~``E5+bC7+x)L4?r-Rz*}WI%k3yHhWhoU_ z*0$dcce68DFv>wcf*3G)JzKu_G%y%!zmwByT&3GhH=%R71$a#rXuIu)|e+P72jSOzFkka|8XZkG>mTV|A&u+{{9Yg@Ed*M%+3 zHAHq6qSQWUo8S#|dsV8PmY-U-*3C82&2+jp*E>BQJ-=JrNrWIGv;+UNmB+umk9mIF zr?I>5ud8C=+&0M4;fdTV@GS7(d%<*xssOaL5p0f8KDIW5!%e;%@md4%2 zwtUymRtj@;N!|8+7Iay!5Z!$n=pCdo&v~I!?j0?o z78Qp#M8|I;ho*%m34;bacCN$l> z^F1`3@Az<(PS+4Febxc0-dvr`ePxtd#OmAes!rDpl6^S4>^)lV*NEu#0qY@DX&Ard zLF<7V-M!a+3+2k=B)-l;+yQRrJ^4-pf7Suf%}*5N&qX1e-pH=bl4Zo_Z5QgV!~FAs zpz_zEsNy|6-Op@9s^6o(n72 zMPwWJxH=>f&$AlT653do(GZz)DA#c;@Xvol4z39iP?EP%pu;>@Lk|>vTd|w_Y3Bh2 z14=czyj(4`DY{6RxN$Boqn_cXZlGc9GMK$A7&f@QP%E47-7Qx8fCN7P&J1eL>ozsm zjg4~%5Qlrk2-ff}L}6*IDDcpW9m?kM*A*x2?KtZi{QlTeM4yLd!wrcQ6Dw`5|8pK> zC!-9#s{{7AAL~=N%_mU*o^de2uETIxWGJ#NH)g!C8EgpH__5P#Xv{IU ztCN`lY;GF58~LGAxPrbG(RMLVt>$OLxQq)0ZT@6uvxT*VpT2>8cAM41y4*yI{QHES z-7ps=zvK^!ZD!NAVhFV-%LD3Ya2_pm(GNcbx`2-nEv`8P^o6r|kZ?V}hH#YUMwRM8 zez8_-E6KaLwlfoNa&8ml`Wglnc5rr9Zdq50m!>l<1EbeukdRmA%b}PP)&1*$!o*0s zrR;aFP~J+pu*=&bdr`s!w!nwMa za{;#z%)du8$ULehepaBIdI2Zub-io-s9$Ci^TOZP^1D&o#vFXEofzfzK+26}37(J| z*d`b_MQ5u2DF=1o1H7$U$Eq92tJIV~kt$9jzDZ%-Bx}ha zdOUM3!-4~dkUcKrx!{ft=={ae!`GrwjHAU?T{>-PXaw`BASPf6>{;u{&JW{N_xt(Qj=_DO9> zrV;ntO1~|xt9F04jyZUubHim-;kPg_?YG+3Fh1tIkPQ;9PVgEX7nSBWHO-A@xsVYv7ZNP4 zT2PY5rY%wpFP%z8x`w5^42z3OtX#EBh6QUDFlvO@lFc1hh?EbV!uROj;ea&fgn8t{URFJ!E9#-Yv$2YbI`?KI>39HU$E;TB4) zD|1pymTu!eA3g;eEyP#^V5LtiHn#dCH8wVa*TxO(&%titocSNSbMkA807lHKTcPgx zZA42*wX~9TFr`XDw$-Pjbh!#>tLWyfWk!_i>n3y6cX?ZD*m(*2Q=l^+scPHvHK^5L zOkMO>sLThw$AGd`I6u!ZqfBPHVar>=3b7GaL1}~^`P|;KZZsp=Q7aQZ#^3JMn1aIt z7Zg6^wbyvt*XimSjyMBcYi z`4@WblE14hW8xbIHV!P`4B#y=fBrbyp_-h&@^w}F>}U`G^E;`}=q%YX(%8;`=M!06 zf*<)^P~I!}nOEDpR(aDz?G2F>rSZ@J*t?m;%hMss`7OKi6B!SGmJY8p-m{d;0}H-t zpJ!7#Yw+El`BJ}efEk=3dblur$GD0tfEoOCrJD{zdVP`L*=V+|v0W`ijpN9<40myk zH5H}E*l!o=?ry++_Spn`HzEEGVO`lm3?RlD@=n{P8pT#)KHzV%VnDgZmmsmcyn+K6 z{Bf{g0J=gt7UK@IVmLLLp&&Y%6CBLT ztjVfIJB|cW@HBgUC@DQ_!duU3PNj1DiQ5xA;Y5Z4_W5OHq%*7@KZugRNsLv63a4zV zi>ut^8GJTALnx+##)Ud6*%=gcCS7Ux6H~{MDr#G*rg5l-M)hJ#s(WEiEmg4FkVFU~ z2YRuFM!hsssz_V2pxT96c7m$)UsXMQ!m8CmWyU#*j1DVBt+u%%g>7e%c^=*pt-G5; zCYMINb)l9ZW(o&8Oq0%fYeI{nuu(3C*_jHNcxSxi#)op+!Z6e3fm-1NOKYR*Q2I+e zcG>#2onuDZLd{b>gBR`MjWhK(&08ij6GY4CNWhCmbwrR`q<}G6v+a~&oOXLU=TJL_ z!GR`uyI*S?$l1{JM1BQKd&>0$Tx+8;C66E=&8Gu(Ckn~V5A*W98$#Ap~!g&}O7y&l-`wO%i?TQB;Qaz2%D4$N>kTqgu&FhQ*D$TTpi3SegX) z%njb}IQ3Bl5<0on1I(~G1Rl-dQImjzI2EY0K6>`n17G6SJ>9xa%(S%jrS&FORvKZe zhrN=uLcrPf_#`Vxsxpo1bw&u;Wo=lU#XH7&AGnkp;o}7sHr9pqW!5Hpb4#`L=90?p zKV$`O_uDP|{ z;oaJ|LltM~%gT+?5!mM}tSsz*&*mj)&6fcd%M4>KdOF`kVLKXCa+*O?MN4zD>v!o# z>4z#qfXG_H;x$D?Kl#nv8LMpzYrE}qWsB@JZ5G>7YYRlC%Lg?;Hg|ne4F@QpW!f%~ zrla!tq?ke;#|BEAOGD{&%dO|a2QfF+Co+De)EBudo_>)G!wy2kC{hP=X553Bo9O!B z+xMY_gLg)w*amdEFH>;Lp>g>;fuRvgbnZ>+B}$pA^k7VY!Y*4y$8~dzEP|o&;|1&W z%FQ5nQ}b#|i@nzN!phpt8ql}KeSed^cdw}ipQ?i5W+rJ%59?~PZKbV6o&9#Q4T8(Q zU*zRDEfd7C&?|CfPelvvikiA#PyW}*hiUV5jP>Q{`D0C$y-tfx3k#ulv%QsNC}cCs z=0tAV+*ZTr>s69=fxos8@QNTAMI%uJzmx#$m6ekclGLQ=l`p)Ff3 zkUXzL@DQO2$_I>;FxyO7mSRT@;FIPDPOjVs&$f~LPKYB{u6arf4s+Hr)pSux%vD)- zhP!7|WMb|LZzjjxjlG#KrzD5G+?u}=v1~px1^(=~OM(dsK@1K{f?Y{>c>v9}*eA)! z-!s<^U=){!`JD0!e@FCf+rc#$3?4ptU6r9P=E+F9_$gHeKQ9->bte^g_oqNNc#m@Z zha4bJsAGwq%AxeVEc3@d3%(uT@+Yp%(={XtTryI73>9&SEl}0K207E!(os|cXpg%o zF|}O)kKuH~SafAB9Y9-k#ggu5K}JT;$a9$jibAh}?Bg5g3PG(QO*cvIaQUjj(s=RP zepV(Q9Ah2wAy;GspDga)U>J5_jk5sjr+g@l;Bqlj7~q<-74h59Ca(dbfCg>&V{icL z==>;+^to6WoN$e674fjZ>#Kc-6bv}PjYR@%4+ZhO65zHbUN(mh|6G-07P>G}R`LBE zQx5cB88`=G7Djxp{VZTwZjD}E$BN4+qH;rH`9Wv+C5)W=6Omj`%IMeEzMk}vvLK_p zAlMktHq&fv)C*(G(U{rFI_6THGH6;%B1- z?xi!O=*b;92~&cnA_Fethg4y7!boa~_BOb|RtF_BwxQt2yqX)B9!W*fmcI42t6tZf zyoUK@EQ<=WNXmZk5O&3`;Ssj+0q=1E-hlVMH3zb(x8s9)fB?@Cj*^QB%*jDHxhW-n zIRd|^0JLkX;QUc}m@(_Q8D!4gOJ9e?5GCblf{(JzV@iHo+D#S=$3sLNhS2);v_X!Y ztd&F*KoF+_AC>z4{P>up=!*6tr%rSmgy%KmwyzKbO<J@}31R<1D5|`XReUzgG@$&vG)~c-0&Hv-V2dLQr^*aAZ%EH8yb7U& zBO+`~EZ!mmUe_@F#mbHrA?sj_bNk5j*ILKHs90#C+Ai{H`eu1!FipiPt=5ER>TX6t z9;eVVSUsJEaetZ+r_e5-8g!#>=NYk8sla=}a8s!8jOR9wJ)ds&TwD$kr!@aYoZy`) z%6vW3cpGKaYokKnk!s)jgJ)Tof>RjNIEWnPX^AkFYcd?+4e4OHXHXz0#ZX_#JW#Z}0oS_|ufMoz8N z8ey=PZrB5s=fSc4&H7C71D{5}sOk*+3FD6IjET}HrYD1iKKH#1g(J=rs3WTn7D-4Euj`S z_=+5-r0aRhA(#wLU3`5^M9Leh;~CQ_a#pG14d*yYTWJlAOjxb}*QxELn`E=hrX|Ys zgE*}aHpy+g}g3YK-3!F+BL7f-#CCS!al_Jsf}TccTst9)j*&IVgOwgQ!C}1k#_`RQ!B|x z>)rJmr<$F4kCD1-gSJ)q4uG~n|3z^fFq3`b^L?`%p(6U*3EUJXKccAAH1HlT$u{a; zN)T;ZDnz`(fY%L9xd0uS_9?xjhxkYu^#Y700c4>14K(V(1$Ct~OJq06)R(LJaCxcxkFwpE`cvH{se*eFN(#*wQc} zx529dC0>|PW**TTDUum-*ix7?VVIdM%9%kv7K%qkbdS-JCd$%4G12KmvR;DpmF9bm ztaUQ>02N{{sX0>!4q*{EB!&2Hir7sF&-!>F2c!sM-+`u{y+mw1RL`gD}DQs&( zC$oI22;kya>W`8&EC}q2JxqC^uMmGTAmgJGCQhz&ZTxgRp{z13M-p%dD(2j1brH)S z-V22sVwV=s!xBY|1%ec?YF|uKs!2#l5M_Gbmd6vH zuD5fIuPeg``~u7}4R3S+7vp>F`Zqe7p3~&0Uk@n%b0h&FLc1na4h!J)BD$yho7=L# z_ji&EoM;$bq=F;>Zp}Nrw0+b#0=>mMnukJSw5cqA5#~B@zd^z6 zENmHW0rY!_Cx@_QUw^fHTHP6`R&!3|zuD<2zW!f3ThX(-Qs(ypxmQi(-0%t=t0LBP zdQ-fd2s>bPGs2Gn0^;ggFn)uBELG&`gV|Hjv$rKO3{GSll?+rl-3_bR{;td;IlR34 zcrbfEJa!=3>o%>P&SFV(-w3>vqXwP&qiit>nNHbE$>Ie=zryVk>;{u@hMPT-$|<7_ zf8^(QjwLIVdqk;I?3J?~a5wV3(>juG=hcoWFO+jj1&=>n+8=;Bq}~a2>%PM6lyVDv zCjPplJs5Y0zeD;czEk2Vmlhrx(};`WI!Md8@dwOGZbB65m(0qN zMNy`(RY96OZ>(%LpA8Vw2kslKnMN_=$d&gSZj@zm!|HmCzMHf0Y2CQ1-4l&-se-b9 zH)2tj$lwc*oF~Dh$ityn<^wmXX@UF@H3Bk#eBCi+&`}kK9$Rzhyk+9wJPzMV3Sm4Q z+aqjB;fEN+I9GDh#?!Pva^5DDU*AP4?YXV z=wzkSl@{Acp_=w%?YoA6+Uq~Z9L4ck!kHcMTNg%|`727X9m(ESxU#C3mK_@cf0vJ4 zVmBoISm+n9En@v)wN;ue66A5KvOY6wjy_N5GJrOl8n;01bn|CJ;2*IX4o}Srbp(s<@`&%lhR=;)LctwMTT1;;YFtJc*+v!d_AjK(+C8}9Hqei`!f zo zhtzUpZkYGz)Jb$c8E>#X|8s*iM5dl|`h`=)Po$w%=$M6P&USy3(v8$>X_<>7M%Ene zROUG&htqQt5t`ZaUJX!yvyeQyUb{%;QP0s&KAbaqb+*>qMw3ypoM4D9SoJu+;ydm(!ibBxlLu*qy_uINoIq$xi}Y`RyFy^Q?=^H#Bd-PfD)Zuh?v*Um5z6-`wr8-vYPA zZ|8@7!9d3Xi>ir5W_tO#5ms(Vrn1%OB};&8d#ttjc#L$JeME)Rq0<@m zfla%k@>y?!+Wkn%oUl>mR-4iXk%}SyLYL{<-nml5%3R6-J#rVcMOr#xQculN5Q{B7 z&g$?IrIaFdevV54h43`EOS8o3%f5&cwyN;>O8|N-n-QCp^0^_Gc5;y#%=1*zgd&k@ z;eZk(D=-DRAZM16>VPiME59l!)Ax?d6-Si_U6;5k{LA$9^w5v#*g{OH-Hy+7@b+r; zw!A7NzRJMpC#|YcWNROH1$gJ>^M^pGK&l?gpT9^PN++no*O8qKi?zvO{45K*xG?qT zSCFY5(p>>~_8F~fm*5#lnrKCkLuPnc<;iCEdvlfiVX z9Pn6Q>J|NZ7I&LULD2dA^wO{|f*|b&)RU;UAO)*%O*wD0_b7Vqf*YOj^6)g#xM6iU*Y);<`_YJo0 z`y~!SF9Wv!iY|?&84;y+=OFS7z|%}YDx2v*o9P3Q^tMH7+~eHM;7~C75KKuX=fcYD zSpkP2%nll6@mAQT^)XCp-j>+MJN|BJ@F*L%w7?nuG~X5%X4Vd6Q(4f)xtp-sV-l9x z@Z5R3u+joIbHJo^4{ERO)?LoskAkIAssFJLqv}5n92^?l7_%;s`t+}K7pBF!K}uD^ zS|1$h`#1M!Z{g^`bHQ$%p6J9d;cEM|WjWT4Y#&x!z_a@E$2X&Qz>@d(th!L$r3ZE< z>fIFAw9#K`A-vQFF|@mD7BHYkFp5B^J4cVmH=G&9^ZH5h!X$eDl0@VRyCIUiLCM~! z(~qhc##apz?fXb}gC&2^$lkfrk8TYU?FUJA10;VS$==n|4|mV#H+DlxzkxkQehC`#lY}zd93qB#3d<&9Ta@#^CFOqqy@ylw)y#Avg?YnlNS{VCA1o88 zVbP9>jUxT`8+&xAQh%pQg$rY+(L#SU72`ID96AI$0)`o`FN?7?h%)1;8?eifZJT5} z0>Byq3Kw8$(6ueQU4W^FhL@~DKYSZ3~NUcjY4M?&?qQ0~r z1De=-&uC)02Tm=JTRQDYGBpEpWF(VOsoyqJgTHG}=19cAKMWs2G@kp{buFp$$xOaF zRdrc;3uAwq`D@4)%ae!Qlo{~~lz383FPSg!_@FIc{I#UKi19RiXk*=!2$rZeR~^731$iXrK?WmIcTSvWDy5jag4z7HEslsXhS>FTL@rxkfDy?uAev2H*v5 za0_y^?e7C=pbxdy3HTYw9J)=Tb#-g&wWs^$wYj($R&lO2!6#L(~yeCaly=v$6z@wQZxK%-(;`0?4xGU5l+YT>qs@7s5yfL|c3$TrS5 zp0Cs|!fqMA(CdkQG3`m1rP?n9Z}ijcd2oEz5xQJaY9n|x-FB5gwqYaneerKFD?{r} zr>Hk`D~csMj(#YSg^C0PnyWe&1GC3F2~y>~qEA2DHx zAQ+@M9_5HjTV&-wRAEqsz(i2wzMG-$BfSv>9nt*KsR#N7CWhx@M7uR6XxGP`7qQRc z6y96vO`4Y`ntkzNb;W7sAhOHG7Fj+ygDeFT5o+e6w?ZngL9O#3>Jy|g_dGi zDOi{+v*`klF*23RjTR*dveq#;|75T%;XT`->QEifl4IV%hjJeMO5(>vK!9BPI%Z?m z+UP3Xk}l&>$PfhQ-gL;@3-85>IyMPJv-#=a6V@G;E_^~P_DYmO^xTxZ$3m&1o5Y^B z{GC`nU5JxLUf-?3r!4MqIyck9mz216U&1D%xN4|GmwYUki@k47%vQ$jxr_0J5? zD(8T4d{q+y<}BIn7E+p#Om5x^W9TnuHCtyi@OXWO=(0itJ^+NBc@?IdD5IXP?DIpH4U zZf4b!J|9)R{My(Ez}~sie#!Z?;ZxW2Gj#!<4KHYM#lc+@7T0nfuE$f3_7k6ii(9u# z)op(n`f(+!RChHZy$m>4i*?pJZ6oCxfX_`1Ms^F0(aJfXU*g*D+3k4tNAjkF%Wjc6 zug}%jXZ|?#Go~GrLs#eh5zh10X4CHc*=*pyWV;Eqy$ze$6-K_NVd{zRqGD$xB0L^H zKpKy?hNP57OWR00S%LS}m`ID5yar(TFs>5%X;8J9imQpPEBjfa!hFIxfXeC+7R#E) z52{XFs%xs?H~s}_LvB}M^Xv0UZ_zaTJva>cY_sIbJP4;A!vc%_Oq31c`)3^0%E{nF zkBU=5$YMWA&GmLDid}6#>WI&yoFG%7lvts8l^K&KWHhT7dk;kN;!MS;SL}a}1RA5S zSaVO6W8Vb`?UBS4y-ViD43RyK>Pn`*W?2_+tv;^5lijvbb={mB)@^|GwV6p2?sSTw zn8`^Qoh>OQcaQi9ZX!3X}%~`Bd(I)6O=}Udt zh0lV#xg;5hlg(WP`4BU$>rNSe~60b=xI@JS35xj9WP2jZ2);gs^$AjnGbQNr#9`=sL+$T-8J9(bgB&=x!4Hk}sD zB|xJ-hqbIP&SdvpzWz zyo2QC4SmA8?^tjkMwSegI9H$kujYAp`T$G6@Du4NK1R_P&=g?Nz|r8z08)U+0LXwz|AxpX1Cjxk0+a&D0cXQ;04uT;0J!#tFo52Z5=zF!mV_a|r&QrKZ?Nm?+fXx3_?z6uR8N)*G6%~Gr1IN^ByC9(^VS!`QSjCz$ zCqyY{K(kd^!Vzv&MIfg%ets5NN|ZBiC&-%8kGLLp-%EhKgR+j*ul0`P-O3zryx-K~ zS~g(4czIc!-IHujzIhn2G^fCf9XBKcT%Cd)GrAEf*5>Y=RpdC$V%eUrn027rbs=o5 z!`FUgQ-^F*z%tv! zyz39N)Lk(rj&x_LjXZkI+C*A~yE7GHL^CATBs7zVL>yB;x+Iu!mg4g{#abkHqRqma z;DZxv9VBrK>laJ3fvgkqJ{&F5CW>7Cn-(X5It7j)E_)f{Ob{L0jAI+}eJw^>Df#&D z?sET4=t0i5JCeJU659<)oiTOm^>&V9X}H~12US9#nKcnDl6*t!%*@-ecW=@!Vd5Rz zO*vTqRJudkz3{Ay2VH(+}P9}~^Q3j;fy-BAFO=u|i zrXw@&#md5<6H}|G;tpfeP@}uJb#R{bPB@5d-If7&#EW_CnPCJ(Wh4DGh+MZi^q3U- z(OMttjV*516RRC`2sa}3>D9pmY(U(|x$z5ru`-7v2_h#;t)w`$Kvu+#42pPPOW=0~ z@tu^+cjwq+g5~|D!%7ziyA!T8uE`BHjC7-PDLf z$i=k|YXgQj=CQi~;|=Pzo}+APnjatG5e#U{n_mH=EcX z?!JZLI)Fp`Q zU&WYE*G}#tZKbcSo~_v4`2G*oW9> z*th5pI0tr?2f*v=3Dr&RcnI02>o1({guwp6Sc0Dh?qJMsfWN0GfS-@<=EZ1FZvbz= zZlLaY1s5%8&^_zlfSuL}pkL!$gE;6Ud zhSpL+jisAtaTyrjP}=3Zo?m-#Ng5$h*-e}s87y;zl@%BF6Jdpt_Z0MSsS%!2+xmNM zcK4V<=@nEaT=zp8JUf&U0Kis1@PwX}`ZnQSZEH!ABI9SK?YIzX;ho)g{oJ*$<@Hxb zx-=eA(4&83L~L;s+>$eX1#)cCpab?_i9k*3vh;7(T*ta1z3+(xBE5B~syBPg>*|CnkWY3kvEZunuHdF6i>t_uaWp&Ui2VJs zlhebmNKd66lImiQcx>3wmpt>yB)4EoPoUGecSl6s$USeaEO!a)lbx9=-})l03-xZ$ z35;LeqhW;wfBT9muTZSj5BdeETj}00 zS!*OrYvh^SO@GYxN}?^)_!vWC7vfo>Gbb3s0~l$Y+8C)U;pw>(&}U?dzB*NKE&d4o zPKnF7X@?0Q3Hgpnil{@GWPKk3O}=00tYm-p3f~B7qF3nsJsq)|`FXUr1e%KJeCK9z zmp8FTUK#xv6)X?-YZt;=^Jf6eN2`oWo!~E#kEGbVX3+U__(uNhG%EYok_;&@d1 zRYTuTztkDAyxE<722{U2O5i{C3Vp!GrMGrv+-l8&suDiok}gxpCtjzjvbeI9Z2Rh+ z$3youaq`{Yd2Ghw1o1ln{X}=gCvGO6UouNsV_Kf{Nwx*#5;gQ0%F~}3Xrd+ZAs8UQqN%A$E*)Sf#w`fx}1Kt}+m>ILu`^!_(7wp^_8Rly)S8 zDcjiOt@EiqGcPMa*D*BlSAwmFK8as={5QAe0l}PVGDtte zOGGjD43-kkZuj(J^A+Rqr3P)=0tweRJeHB|j?WmFU;B4ooq=LQ+&5&;Ot~2aWBH*x zMJ89MRG9MbtQ46(VUp6sRcj)p!kA7~vd7fg26JxjK=ickl>(n1c=Z;AQk&!7g_xiH z6`v-diy4~BpSGTx@6_W8r7xY-2X7tv*`Se2DgRc)Fil4z{1`-D|NBUU+=)g#{yA!czD6J^lt}Tg z3jct8DuLsZdm7X`;clSZ7Of7YkiDvj5^ft(W%R(?l$L;lh9?;W*f zgR05c)$^kQwk*waob4|ge1Eck;`&9QE@D34Z9gr{Lmr<}nPl)Q2=m~N6SQq0k`Y-u z%08rWCG2Zx9=yKCB@fx`uV>Yd&eM6f+%f!+Q!qiZB5&@ZDU$b+qP}nw#{j4x_jET&2M%$ z-iUYi$GcxuMP@~0{W=wqC*x$^*DWHTr%=ezew^I%eUK}&{?%f~GuX3Y89CAq(0ReFYa*+77i?wDxEpEnJ?6lbQ}g zn-0Z=f5!x;;=<5#plI8XHR~!+d0yY7D?IH~_W@ye-VHjNgj~^Qhbp0u2{k{f8WabA|KDOYGoS6!V~-g<2(BEC;^8S27f z6a~-!HhxNVQg_>v@GlCu)PL>E{`#)^en_|d@GQwJIeMDYQil!dQ)hm1sCbmnv#za8 zfto!kJ)CJx{H-$HBkfl>px}MFz0h9eX_=c6{Wts^o!q0B@9wws9jMnqTJk~2(>No| zMASus0@cLvDrujf-wLKZM%(JUqnXy@oH1>H?#Lj%##_U1F5xWggv@0^o=Rfc8mT}P z8Pr8W9Q8!Z)A%ga#P7?5IGTy$by7m5#MveZ{%SI)e_yI6YOInXnbNP^OK4YvJz(Oz z(W4jhs-b#WmZZdv9gM$2^7I^fRF*!@(Rf{yEwyG{G~}t816z9F`3uMl4CB1h61@xf z?h2}{+suot-4t{B%)MUEHR|-D^q%ruT+OjC*Pw$S5UG;dSM*VyX(urMl3uGMGB!x~ zs!Hiw#BG$3)wM}nO>1-FifeQBoR#z~Z7p1@H8D1gZ55dt*v0keOmA7n^~g;34%%(3 zVF)&L{dj?Y4v;J(&eA-WRKEwKF4=$-eky#6ZlvH?tD4x&LJ9gnhnD-_WmUc}6~BMA^# zLRmNi_n^s@6IPfRp;^uJR~ zaIans5XIyrC)nL+NaD|iK#B62-OqJ8;@ReMdd)*(1m*O%LI7jhpS#U(M+~w7@fGQju@d!sLHa`AD^I|timTG6_3l!9-9h?l+7ULIO|f5vr=UU z6MF@2S#;C%AYtIA&AMd5Z3x)WvyCUwdA2Td8okEWd&wUuiYq#;!w-q|9;|K^+PD0Q z)q`%ghsd4H$J9-GXGN&mJVJXCoxjJFt1?^rX}7N5blPFtWChU@WKIdhIg0+H3)H0r zj`z9!O_VrkVhGZ1T6glMHjHP{Iumyl5t%U+%SxP`FqDCBaP8Mo@MI{6dFwvS*)xJ{ z;ZB~wIA5XuZKHWrsHI)*#FM{w+t?)egFBF-NFe_lrooORlUHk8rBMBeyLUQ{D=l!ATz3pI!2-IH(fY+{FhPEm-TY#V4A`V?DP!=;DsD~*>e zsS(q%0y!bJy1OJe-}vmK|AbZj^{6a~fx2%liGc=*fB|=^Fp)lC3-C6jhs$EU0{Dyr zhkd+s;yPmE;uRw73d_U5R!FW#7UPQfKL8FgPae|a#R`rDwymIS`QOV6a40%!?G#hV zy4ds~k;)0uh2f4AA7}W^gcPRzln*5?Z&Cu}=di>t(Llf0_Zx_(T^fRZ4Ng%<6ay2C zZ9~NE!su%tr5R3gMgfC(1(;O67_1ve0lPRq#;?L_=u@}-TzxkRsoPTI`f(l|U}3>O zQ?uqRgcEdAW9!a|3$Z)cU$v13i>nR<^RG^deGn^nm=B#v|>&E zjDxcIhCZpc_M$mcXX8z_1zz5kAHsU>+eSEzfy*!t`|$%^03}3V-cgqn(YLhVLs;Y$ z9rYz9^o}QX7l}7SfH|(uaNizilRraZ$pk}BvF}m3Lyj>*D?9R+F4k@B2frbYLjuAc zip(C%-x$WVxfQ{PHG*@}c2VnivaM&MlvpeiFqez61et?rqQAH&qMU|At^^J^p{>66 zvTG*@tT8TCl%-as;@iU6BeBam7{)GHA@NKE;+qPp&>2Gni8v!C?(kNY-=P07!yp?= zrCj|JyjMW}zh)TT|5fy^05r4vXOp37|6iC#Nh2pqIV0fz;Unb4Fxw3ZB8z<^2cbg2 zJhP!KX=&x_62ZViID%ker6$-mZ?$xv<1vUK_7^B(%$H6QP80fAJ$xO$eS+opvx#Mr zkeYgNJZQ7W00z4+hV5)Q+ubfH97l~4?AC^H zhEor4Zh+AOI?ymcnx6Dv*>FqaJbu8+ItC_)hDq2&g+ z38q1;MW9|-UptnCL(oVV9R-{B@V;EmFg-$>i)j48$QaJm2@_LE5rH}VlW}Gnc~lpU zGIwSa)FKWYevRa>_Oe~nfc0QoZWdZwj$>$1lvetjf#`(U-`%0ng6H+j9O<;HS0h|1 zlU7`OmZmH!p;DE|&KP_Szec77)TJ6pEs|EWT=`{q&!gW{Dn;ON%@zJ4ms-Qs;w2+Kq^kTGlF)qx4 zeFG+9MM-YCC0%1trw2Bg(aH%MZMc-j<)tj9(kJKS_Z4T@SoT9rZrA_9w_DLN0-p}o z6it8K)$Yaz`QGIa-PdLVZZcFrxmB_q=mSZ=rN)30mIe~Xv}d!gUr{?~?F?efg<1J*&S09GJI2zMNmy{|J>*AQfnKYm8uUhVR@l1QdNoB=tWbgvj@lYuh~33c_vsFL%~=6xnpW&?wqN$2jH{lB(Jo zd9J~U0*VuU#r6Kc>8M_IpTkA+*f)CI7_$}Gcg<8PNaPi+l3-i8c^0vOAvrSex3}1_ zSYj9wXbA3?{hGKJ@!@BqL0IqwF@yRTSt$b4PC0G~&S$B+(7(O^Z^?uwcdyPh|-N9KY(>MG_PnrY;_oC+U2t&%1bm`TrgWG=tQLI zWK75bk#a;(3(-ru*ppYe3g1mCq4OevTZ>>3{~o17b5iDwKfqdvdot~8FYj04W-aYpB#19;`dX3uv zoI0bpN!IO{q*Xab#?KyX_(eaf54g|&1YDPK7Tu@+V@8rA{@+5 zAKTjAkxb6WUBuqS&RNXe#LUdp%v8k4#>Uvl#QMLoL5xC|{E#4WHo~Zctbg+B57-5u zaI>l=QAapc{DM6L?bxn2X3i|tw)g^am>ZztM#SG3-0SPN(G zwOy>VvW%pmuJpNm5{hwQ(bpLBu{|}bzzd|?F4dad`hRUS7>2&e$N-%X}<&pxW!~JJH z2cAkwEa(p;1QAN8w;4onBnBD8M?^;lDA)-p3MoYt8h8It7=9NQ8_`h$prhOOp5?Ah z2X@!>e&2u0KGPR;b^hmF*;!d;k^6qW>+>U?R=v_R`leLPU52w7)*kL!vh3FFN0jE7 zo*E}fH|6ss?1x23Q}FZQAW}?nWChXzn0ZFG0L6Q`?n7jT-ix%%Q`p_t_0&c0T;eAI z9DgEQUaqpU*mD8Y;ouR+7jH+KdzbFZ5$9JD9FnbJUyS1}D!Fa#kU+=Hd=ygYUY_oY z;cZnDqck2B=9Zg%U9gu|$KjyY{)+;`M$U|%<8B+kIQE)Px#?Mw9yB4f&m-VdUz8~D zewpE^ONHTsC9$c;b@MDi!fPVrXVf#2oi~A(UnAW2M2J^Z8=sq@ShsGw%l3xFHIi&R zT$zEu`#iRcFX}VnNM+1+3;ewahBrxGtm*EOFAbq4*JO4)$eS|agMriEReTMN#}qgP zA1jQJ9`>fqdUUr+=iVD^IR3PEeN?M9p_f1igUOIKIsX~2;$u02|HZ=UICIg+&`4fM)(p099I>x9XBUdUnZgiNvWB?NjbiZe<+)h zp|q1M-sOCkQLe~Nrot&)xH7(2&e@F;7*sgN-n4+v2*}zXyEi$0&(QNe#B_h33bna@ zH_pwdKaGMN)7l<f78eeo))Of%0Jr1oPut3AwErw^y8NK zAN_$zjspYDD_TKyZ-QIfxf>TH_C4mUMqK_POn<3f5LV=L9u~>(zHZ|*#vT=>nX;~z z>8?2_)vmJUS>6b>ZcyQT%?GG4J_eybQXu*!Li)_V^ttnc7@m7w!|I~E5<|?s8L$yF z#&-Efa;5n09;vJ6)BoqL9YlNztypee^%BP(|7%eg3xbS3hNV&?*yaYv$+kx}K=E z@t(pZ&w*?vW3zHIXZW0DCJ{u)+_v=a#4#Us7V(js4jpd&jb{E0HC1~!XhJcU*4tFx zAai7W_a!+4!uroMBIP}fg{zsV(DcdR?K7rHI@>eM=q|0rFmVw;@+ym_oJ_x5H+jC{HlW~W9 zy-#1UR`yO$Oh>(@LpkS&$(!RLv831MUWQYslb_4kY4F(uV6YtDSJ^bz0zd45*<)Mj zO_WtHp8^TDXBya?p9Yq?o9Qd^zNWHu_mBpLRYp0n`p;@*^Sa+a+ork;|L+ z{}LbL7oTs+^Rqa(kn%`!YxtfSQ-+7h>U2(&{V;lD2 z><2NXtmfm)i5rDY!m~@yc~?W<$`?7Nv$l)l@Fa)$gikL&+QUO$5Gmh|6%(}A;fD;u zPR<4*WC$TWo|Wt%=9bkFS+{o-NcKZkKchk0E~n3KLyI?>Pf9R?cx>0_pYDNPF1^_M zY%q_Op_reS@5^nNt)A`hTIUn*uH<}9f(+wz@9ur)`W&?*6G9?ylzZ)?TU*EF53O|9 zReXSByJekJxT9e`;QUu6gX2JG-l6Ja6YV>&&J3hALLN zP~-GTW2o|+9+Nrrwdq=Z%YM8JClVu`?ikoAxT9{~m{dxIEEU6?dN?-fq7NL!w&i3P+iDRr-WX7${Lf)^i>S2jh zMT6dl@lj1TCw$AD2hGzX?#;kToxAyHHTc2O=M2=*~8o7&q zNn9xmFAX&KzdsBQFJM8nrEG0Ss=t;8-rgcTqtayrYiscds&i}s_w~*0TT=l|fdvaY zOJ}fAt0DdfPSU?D?%_cfRx_4UnqcOX$ic^dfIfY>v^+L7yuBDc;)xQCI2u^>bx!*D zk_Qa$!4yqOizlb1U_9cg>#}!Sf|f#}DF`;BfcX2$5M9Y88;y|G3wk2Gn~g*VqPf(#TmN zFg#8#=8jbwGZ&NldN7Ia1PhX!i~y{eg+f43WD%?KLmS?30|_~K(d6AK%^Y0Vj!g^= zHLli5OSOU2sU~RZUZPNt3>0g*UmtTx$#I-0HzcM4)%p6`%Pt=LZkCw=KT_+im`PZw z%c;#$?0yA+R3bTs9-A$Y9#Q@?!(&K17E82$niVP)T<1)HldeK$8@I-jPNrVs)bad}(>m`->|o<2+}HPHzF`@`db71iI7nHiFAABOQ^>Ey)! zj%QBrB8vN0;Fag8Om|k-Rgbuq+(oW;;!GXiRzvsyg`TOc9^yA|h&4At)a%cOs7_gr z1OnL!z2aMht+k}+ho~(SxrBwe%F1}hz07PONPk%KSw_pi;y6~D%7SiU(rziV-#l! z!u}hhcs%+&!@+NBa|&nlk8hJ-RYN-I@s6jYO3)*^n0a(c@L4BQqKe+%zFK2#>`E== ziS(f9D_-`lrnO8J_L1c2`e{+om|2{miHiOav@-RXS_|9d#*WHbGq`b*YQa@Myu{$o z1D2d)XoqPr4yUf1Q4MmuBIAVn8 zQ;Iz(2D_;SyIBDrVAAcXYCw1Bpp*=k<@>Qh%_gg1eQ0$RE&cCK&)na`#%#)}TCsx^ zMuGG{pX7AXd)*4NGZ>Qc0sfO?Br>0o*p}`KY8>3^QSZVJA#o3mT3+A(_A$9vR z9JiJXU*Sz-74cKys}VyHD*t2Da&!qk8kJ@>G71Ya#Pk|1sAG=UnvsSVkbxpyEjt`LL;6h=dYQ3Y=)i{kriuD<;l$0&YE zi_#Oy$&S~6xEQ?#EUjK<<(y+vtGROz(&*@U)!#2FGt zuy!n~|E}a><@wp_st9_D4X}yE1Fq@pXekvJ_Yhg+lC(isj=WB5P%7<1g!6J0Wg9Ix zlPGET^xk5n0lTV#jr#O$oKSn%;tq_AteX z)*(*Rm=3<$Vz{#De9n_0H!R6omN>BpV-`+r$~0(b%|&%3v_2t{DzT`0Zwj7VQ{OHS z6cfP1za*?`hy2*aum=lkgy&R;aI=G-9eXEs;&z#&%;9Z6xCj%Ei~Z`fgv$t~=&G-hmQqj)kB z0)c~NMrIQ&{j+e+)=;NeJb#Y8q;OFOvj(~z%=N8o3(SL-LWi<6Zs1fzg^CFJ*&vEn zIG=UO9aC#I;E7>lI3Nxm{G+Iz1MZC|)Umg zDKxb)g-p4TY%wKdP)G491{BK+dwUU{#l`&C?^8%UI_MY^$D`z&BjlXTU|_25I#V9W zTNcx$E11y!K!~&TLiFJdF}}BLr4z68gqnWaztC?UHeES>k6o?mR&0=Gjo?YELVSH^ z`~al9C|<4Q-?bVV%R;aw%ZB4KH`9&wpLG&B8g8&*+%JpjGh-|&SqYZ7P@u4aL*nSr z$=425ql~1{oJ)Ww=xkWnK@zJ_d49n04U7%(olZiaAA)6I57AF0>_?5keRtzJ&g$$S5Gk|-BmR#s;-6qK@>ki_%Vg>!_tw@tS)%=j%o zCN6K1WhwPk-)Ho|Eh3oCTM%5Z1JA>XI*($)gU?fIKutqew0*FexVs;kl3Kr?N>ViE zB6ORcUJ-bttHef#q%=TG5fvA zK*gLL8T(C;r{*uq9Tg4YKNByCIX@zJf+DN*g0~n$Z`FzB+?ib)UdlM|P{Mrro2iF| z!iTH0E?mk0W@0K|kTXMHOhe+nZuB8D-M4P&;V1JcE>nyvc%54h_BQh3RZO}#tN(Ew z$3B92_k1)*#;rN4c$WW|&h(2pt6vtjeOa66-#+w39_qsg4k%t`S(~$IDTJvsNW*;|MZn(uRlLcF*O|+yZqqp4jX2Qki(PC^qFXIKS z^j=1aO~B&wSTT>uTR^%qNa??!d!|oA*-qNhER%)TbYCipO|V6zv0^Xdw}fPlIcJGUM3+ruye1!8>{~VBWj-UhUyPrXd$-9sZ4OB(g2c?#a`cDr@bb*|WSSXUD zC#KZJNoL)&jLPBD^Fi57F7@*k4z|>q84&m->5gLK$lGlVAsG=)i3ch7!bddzRCzQ!_G(}ZlL8Qmif?I7FOl? zbvXi_hUXH?##p_X!4Od%X&Lq&TTQ>mULM^Ref}0=*}ho{DjGs9AX=> z1^P9k>TP6LB2F@$IO~ZR>xmTM0B}AKDCLp8)U_T&2#9ePqNH;n;;eo#_WeQI0NFd%G}*TnCS$=*QqV&uic!h6w{dL@U zT;$>;d>5TLLJ<*pI4^{AMZoo}1m|Q&I1JU?z=RtK2nQk2@!#Q1bjIDFSqGinWCM6w z1%(of;JHjGKWyNmV`y*tqTwdSMzcG$!$_5LjBFY~vS2t@Zz>DH_J?4wNga*yKz&b<9QuSS?Mh9>Y zTdRR5e~KSR7+*N*LQ9Dc<0>2PTpfdBWCr*x3@j{LtRS{eT(kKC3buH1c`z!iLy!Ic@#-_nZliOs>-5^lFYVZp$qUV zndXVg>zT5}w&Q4Lq-xFhT7rL*N*;I}v8RduEFzkcUP`tu${#SSXKYB^kCQgTd1Shh zGtPP6(IdngSStJ~@hOkOm~+;aY_c@Sl#8--TaSAx1Vg4N4LUL8PEMTzIAbls4MR}R ztuH}>Mu!W_?5fowkhK#$IoJ{nxmxb63kK-bCs~7`Uxj70v(N1SG=H}QfDuR_3^WJ8 z>4%Z);tmgW&GokgWWkHk_csR!QVh0<6Bfg6vAz+(?T8g2ZCoHOxM>m|uw<{fX%UvI zT$f2`5}J~3$ZebW#9sn&%gA##AhJ&0yW`$>Am2cQ_3zl|$|L{_6L9tMzTt{2i(I8M zMVv^41xk`u08WI;_|CW@?n=LL=_ zU>(gEopW0M+)G6axS>MlAvyDAf~=g0mlnjBkgyv8m-EZbfZBg_bo}-2zjI)nIr^|( z^Y5>cxz44yQv92upbr$vf^CT? zod_w@t|*0V2~3*-lShck3T_GFo|H6MUE}{m0*$%s30bFnrkFix8#33F(+?ny{#WF) z^H3924@QoO{Ni85?-fD(@|zFTl|>y{f$CH$H26xEZ-cX?pj?EpnXslf-NrQW+U}{o zgXrVDs*HJ#5DU;qjzX^e+^f<8`>>|C8v`Q$+mmHFTu{eO*83Q$`SVbf?%_{U!l!SQ*OoGBi?SJ)6e!KHSu-x@GXWLgy@(WQsr@T{jMV1XAB(H*gA5L4W(fh zWCT;tOw`l;3l;oj3?0N#5Vo2-CINX6ms;^dfw6Qax`(0Nl}w>}9_h0~1iTj$LtDIb zI|T?LOVDnH96k+MM&C=*eYQYQ_EjX@DFL^j@0wrQHYu!dO6@5Zp*cjY;T)aC^5EN} zOFUFt*M;tcAUu4q1aHKVk7GcBPwIcF2sr zpDafXy*Ji{b727JnnTGgkKx!B3@48IzK(IUno!heA4#O<%DAkHdp+k}4qP}Sf!v-O zFkmDvCubSs!9&P7aCZ%!7hmf&Ky%~TPxEz7>$|?@b#=bqN6z~l_Ac8RfFxo=PUGlKRJvl;b=BRHrY1ngtr4>$8nvBmdkx zr@H<5TC~7zhgUP36K7kCgwfqtR6j2A1L>i7O&`!YI*HO`W9_iHA7e-tXDz>HD7RozN%t>pi#WTVhl^1+M1)~vHHVBJ?1@YX7%hb& zHijjUG=}qRQFl3q4HymkkdoBt#-&(-Pz}upPfv2x$}Gr=uf<8R`zP29SI=}-FOiy; zPI51isV;L9hEy+6*oNgEawef*C=r4Mm78YbiuFBjke@)vx6;4}py!WsFAp}jAsZD?jdL*(34oQX5aE_W>pDcpI0KCzj|8W5B^KBhK6G z8;r-_a(9l)MTR9ii;%?9-op^j+YZ3+3e7#KTiCDEL|Z@wz@FwJi^#9TFysQHnuN@E zi5|h(N1ax1izr*@u2JW()9N5a3kXyTK=wjB;;E*>RE6pu8?X!a>Zn>6?`Sh5_L`tENirtq&##MbIXk=GmmrwD3+!SP`aVU9xLRDjJvR|+-t0hE-18LCTJ zNHfAn!@V_<7qMvQNdUm~8CI6#8a&bvQhhB_eoMSwJcny(;=Ijpy~7UmK}5kkcy>O( z1E?!QdVhu=yrBr?Y@R90Npx1o8jQ?Mf3oe&^nnNX%%B)Rv!iuF1n`RpX76GE=50Iq z(12(1n;0vXtMPhnkT#t$JS_6Ak=P44yTsfi=3yf39$9y2h(v!hSdW$3^1GKp3wNe4 zfa>5j5p*Ytg?STv40>=yS!@0sh^f||p_!-Hg>aKQKq}?j>Dh25g-Vvnu0h@beB~>z zvtO=i(K?Y8SYv2eNi$T3YDFV!=1T0HSq&}C=``9l0ca{jIr9oOl=Gl*E?_pUXSIs` zmrI*2C#;=0-L$Sxr6xb^(L19ij>yQelKOM{fJAz3SrB$jf+CV|`%A_5)KZ6KzNcz7 zniagJ^_XK>u~@fC(0npIuqx)_H21EH4quLnkH^rR*0QnXV{yBbK>FAtL97^?PkhV4 z=N;sK7z8I+mSBUq)>m|H=sqFA7qB-Nzd_(GqbgU~uCP+*L?P&5A^Kn;EUPHg6iQCL zr1Jo|F>f^rs$tDZXiOnyYg7cVtbFLxnB@XfXF$amvYXC)u*(?3o1!(;ewZDo{4hY> zfd4`M7NIsp;d;xv2XK<4Z2+6V;6X9TGx1Qz;`fcI zUxn}#d;znRei5kUa@msmBXE|D?!>mF@`c9{NmiH*(NBP~IgmY7Zn^3L))DPa+3s|G zikZTyVJ_zw&a^Ee_Bn(-&{_;%!RH1-vfCt5Kxh%qBZ!+i>m0oWth~P#(}t>1RK9?Q z9D6&sr^B*onA%)QSBU(-b?>Y~^~M3C^V(WOO4_<1wLrsy74OtBqA`mtn9-IF4IfhJ z&DJXR;!1dAi4Fv0{c3yUrUL%~>>_AV#V(BIF12HDo=pWXa$`oJ zi|r-KhBe!2Aw<)}TWQS&|8j@w@kNtrnfnBnS{a5?PO5%6cT+s30qw^9$)BV67`J5CfxznlT7gsSAsYT z)F~lUvD(2(hfd`ZN}^~;h`^7X85;xEzi}c|4AC?}9J{v%j}K=KQu?iKmY%|iX_r{v zEi2@?i#!SjkKZ*Cq6*Ljo2__dwqiw9pM$^eJtv_J*4;~R)$gWgMO;9lNDW=UZMbHU z_1bP$E~aK+ckP04<44@vk4&c_c*QRTjb%OsQ8Hy{EsHbY|qBron_Ug^vt_VW|>c|oCpL|KmOV?JkB>TO`pB=wMG7)+`g?&?q^a>Z{NvW3zZDg-eOEengng+>Sn1{r z<0cbh4jm*1K;+-M^$%}No_Ju0M4Mzv{HNaO(g@Oo(dHL+4-D}a+aeD2N{t__^AJLH z4RmP62d;J^-KaB3ZV{?ZGwNThkRx?d3!MZfc&|>JCUl=42;~&DkXpK6mG1PMBe?nh z{8vq*tP7IbK{~@Zgcu#*&?0pTG&c~*_YkSj?Z+-HG3_MW2Aps0%F(X}E>C>ZY59N1 zjP%qCdn4DP5r*&#j~TVSfM1~J1^eu&+*H4?*@?~epYI8A(h&qI3?J{Lzwl-w8w3js zr$rF;3U}{Wlj(Wqyo_*2=DMdpplwrpj<}68-9l5NZ<8jCJUifeCM-n~CUEVI9XQ^q zIL5qSuTlBR+oAW7bq(8(i|kR~1-{UFXnn+VQ+x?+p?s4NhL=sGp~R!25L1#%%S)kf z(N8Q8>$E>9YTb}CUe>R^*^m&akO zPMN{9OQeA1DTWJvFNO<&Dv=uGw`#m;R;B1BkppbS2Mz+L$?#GpLljD2chlK&@{VJ} z=oV19VO=*;yMeGc;81p91gi*s(DJ=nS0RKDm;!5?P}|TB-mIP&{1|($<_|1*0F;-B zD@vdu(1ezO6Eg1JmKssMpVV7NIzKJT$8^ECDGvS)M9IU;^^P25D>o_I-@wDm;ehO8 zm|BvkY{yGJAS^r7Brxn1w*9qtmg9gd6AtOlSH;q;J?%M5`n^A=d)v9yM~vMdI67=c zeph5b#(rSBL3K6w>J2u2T!hU)a#%T|TTlo0FOx@xIW)Jh`W=oOYGS$rk#kVkYecZ# zNx&xsYi0<^Dt$3iW(c4@X8W&Xzb)raPv9Sd7$hE)`d|Th9kl zNG_iOls?uA5hL_96^yk!vVBN``jb@i)piim&4uEqFYZ!1o6eL|!Uq!Mol1XN{1tNy zo?G}Puw9hCx=OS6>oNXf;%QK^N+`KZIJ*iEXDg7G60vwv`p{ZsQt;vuMKbyz6e}+H zB=te8Q^#~NJ&@%EwR%Bqd_M8t0lmUF&p2JeNW?j~+8`%`7TTdC4~aSsN#^imaM(5s zMkwtsAM1u7Z+|jE$6#cp)EZ&6lOT?Ir<^9cO9Cg4aKC z0{ue*FkEZMhAGTdetcGDftHKe4`vt@l+XmPrSAYrwM&cnSbj=c3ni}v(G+lz+6IH4 zQb?w>3i4RdIw!OWAzAS}B-q6u;=`~;U>IdjXwyU=fMF1!zX6X@^YIU0YF^2lLGtE8 z6@-z-(bn&zPJ%Fc<8-ntJ76xS3NX{#B31oZiwl-h)ZJ1aDSnRWVkkrO4eaGRMpCt= z;9JSqMEzVhIz$t2^UaZ4EuGVQh@1j9!O-fR+Np`zq@U_Nw|mqsB4>v*i8xBwALefp z<{C|1T;&l1@x_+PEbmH_N+VC%)GdW_q#y!7w zpkBq~HKCH(d$VpVG$#??U}&~L2S$;$V+9&{zfGI0?@C4%P2j0ia{bV^bhrS|0F1}z z+^+#elD2_ppQU*xcSUj7;T9z4PvjjLSTwuO8`JG}RV`k&=!>H32K0 z*3IJ^^`vMJ_VysQfH`asCg~-eCXs1DogP~_r_X43m<1Ignb~|_PH@CiF3Hr~FuGHS zB_zf|J9ijQnY#WTr!MIp2p1 zC|n8WCUhlW9(v!kZUl8RLXD?6DmW@%iG3w{sYGpraUTd*{ua|s|MDl}goP3I+Q8l0 zMK*;yCO#0hV!hM7`5}wpi0l|2aRZKN50wFnlp(+B+&&8<j3K##bb6pTJukKo1Pl zh2(Jj882BI_)`~wECJWBWDZb()(C+CmxC-#`aIy=i`n`Q5EnH2G$?z=k9LFFyrRmX zaJ62@YK_TFN`LW01#oo0OmblSRvRDUg?pKhDu5GKKauW5?li7I@JuQa=9pScX9@2t zrY=P^ry<=|73ir~3&`^-)1MqZklp-uMLY1aiENjv6Ipn%@YSTDtal(KAOfWV!Zf_C8=@-QVmI* z%AHF3H>uJIGb%Tf90qKm76;pp5Fm$Zs}a;d9Q=9{Q1Y$w32 z#r4Cy9QVno#lfZb3dXy4G_PPh4eIUes_C z1~OqNrEhEoZ4z$02x30w=(Cs(eJP`(Br=HXSiwxN$7~369UK)KS-ukN$eNlhoMmI$ z9$RR@D*CM7;DC9${TO2)j+J%zD_gqRA%ts@zX1Qqgo4R@5JCeKV)*#SKxO?mp_dR* za3s%Rbyfiek|hSCJH1rA-M{4#IRv-1GV%5Ttfw|h{&*q`7@Zc=(gMb)wl^@L1V5PG zx4iKoNL$9QeN`FWi4M#t!3?>&89r1k6{UTK1&v)ZbYMDl7g%Nn&ZZ?ksQ=s2eUt?v zRvTl`B2^5y-WWWdDvn~ICC!^^Mz-t-V`bYBUH9d*V_r2eZMhR4Ro5$?7y_EC2IwAU z8YPpYj8yz*jz(w{HUK!GL&nQ%&?2>Sj!S9{bwp4U0=VN4cVCO($4uNe%+d(+Zd0TKSu^0g^_8?uX zHDPo*Y}&;5@$p(>Tk{X{QG#Oa+}Zt0e>;I}WaT}EfJN34AwPwzay2a&G`Mucz( zVY+T{W+e(qYD7YenB9!LOvd<3Or`f&$O~jAWJ`;6U9ld?qSPoka-38vtgk8MwYq>;v-K^LD(6NxA+vkC{$@kQlCni5gA z%{PHocy?}u=15vkjlMwP*@WU7HFebzlh!mYx}s5}Q~!vS z3SdtH)k*?AUCliD7|VTeS@WY9+cjOn((}@>bX05LDbA*Y9|8ofpI?%KAG!}C#22<9 zIWPI7Zv!Hxg;oj2g;wK&+v7Av>rjE_U-IoGQi z#5yubAKT?cGzsE+Am}6vKo0Xp@RUa{jfSrc)qZUVidFMnlHtP+h}>!-oe4}xL!X+b#DdhWJ{Dn0ZE08sm;_j-u?6iFlRm$D@V8wrMZ##oF*(d#2?J)qt8qtj)Diq-A=f^b0d-a|^HDl9NrZFh z=RrXOY(bAhl``ZJqQ#Uh7^RR0gbA|J{9by%0^G8~-@h=>IVCe94rYZK{rnwz;&St_ zbgiv9%6HbsREU(&JHyqdkd{n%)~?%p6D$y1%-mff5nfYrBW(TIRE3!TE^=^8?9 zcfW)6M4B~ZOmBYIe*R@7R>9!@blE=|yM7__T=K^QZre%zn1?D%;n>9ZYj$Yt4?}~* z6h|5W*(R}>Z~W4@JqmRXcW*VDQ0A=SwzD*y5!0_*8b;6jHndUsOCOdX*)~|%cNpl4 z2-@aPE$ZgWP1v=XMxmJ+`%2))6zGe`*Ky!a_cotPFfdx768^Uhl zCoCpXjuVL7M#^QqgqSO^uXJpY+cE#+m%u&dl<3wv5^*tFTMCf4DkOo>8CZ47_pX{` zei9=H&;&iXe5g=4BM@bB!oRZUK$;2kHZ=?=IEv!iB1S-13Zy-hBSH2m>A=DX<5z8p zpo0nIR|SZH8_95SNe&0f1@RI@Qk~?pBK2~@q!diWnkizZl&J9|NuGAu3>j7`Cx?}s zxXvrV`@i$z+w!T2FUcl{NG2R_k{SX%YP3Xt6lqFnj-bKDHEEUN*ZEV$xqG^4GFr{m-$vHT&JccXj=uF5;uyj3m?g(@8OPgKALMndJ5O2 zVJTpzU=zCU8Ta^Kq8{PjRovA6_hs<4+@wtk&k%1D2Ls|q5(e4#(eSFUkPj(B1CU1? z2F>?@bt)bj=Bm0V&lGl$vy^rawNzmtZYixHamjAMbSW>vdC73XQI5*eioD27$#Fy6 zM@SB3_ZjS(9Hg@HJ&2{`dQnWtc0(K!4h{+T)op?t1iIy)_%%wt$T#x7hyr)v6An;$Jnpiun_Yy+i9oE;t)geRcG zMw>+|AuJk<+b1UomS_B=O$9#!FGiH0My7<9B$KVrqK7GfPNZl-9WZAwNuV{%rpGB* zE>dTwQ6^jrttsvd!4Q|ydS}8RP&Roo2*FmC*;l*`Leo^?>2J;FA5aE9S5%L+R4D)uZ_RVmw5>%(<$x!JIdjj)$ z^K2fP&(}joG3!M0N?Vv4M!2n}7`-V-$%%+9n}-rfM8v+R&-;@(mcJDq7KMn@8%7!iLUP3mMvqY`hgRfO2q)q=#fz z;>YL~=%!ESxqG8{ECKc~+wn);w$p>X3G}gi#%t{ms_!D%`b@UXI2B%S152r6c?I+K z5R7E?U*cq0YqM*)P62Vga`jt7Y}Ao78Ix(OLTbK3K1(!&w+kgwxB1V@n&;V6>7i=% zTDN$o5<}_r@KW<~28ZDNDO%L|ly5Ydp1<|O`pgUZ=`?LDtcc5W52i99o_-BsTCt*> zKu{mu^OWg($_%%10bH#{6Nq$SY-*4Vp|%2F*BWe-T`0(EMtoN{+tpO**SBJcZeH#a zS=KD8TNX%hA)RWN39+hr(9dxJv~H#i%vmO>+vs5S1e${=4ypDBr3Hf119biHlXC{W z-g}r))o06d1M~^EdhL>8zk!*1=_WJMqRswsC)N9rY5S-AL$>Ew#})VEH->cX(7--Y~~O&d0icJkUz-nn+F-^#c!bOc(yf6r^NpBS@i z2t>v_SPBTrgP01>Fb6NcDh1jxuq~;ix$FXF{5#MNxO79VxWG*8v9#5!1TJ{uv{hR< z_^b$&xbVDIW8sf>KyYfd@)x*JJ+^KKI=WL$>|K$Ex#eSD3vzTJ9o^C<4|XcRx)oxx z7GQ4&Il9wL?0wm1xzJrU@Pf-MhwTbn4Bi$!A-Ipfqjy8FX~(SdEhH6F$Q#P=2mPl;(%LEYF#vFfR}2CsJObn3MdqJ4)^b@LvG*3P#5!wP@+5cJee-|E6R zTtN~f!Sx_&a^>{-hUfFFfm{ORUQH~egfHFDNUlS|y|0H7!FA=I&VA+>>rxs}@^ zcc(-K^|KlO>Lz)a6|cF|^pDZgm!vo4q^%;m^^%sI8jj8Bs+Gs-b$?;kqI-5`j*a1q zkb&;pObNuV%^kqwt^2b|(35mf6bxh$y#i?;uAUnBS{;7{lwr$`V;&QqJCdtKOc2}% zZ&+Qdk1(Sg&Ng*{wOM*<0mEKPWA~Im&{iM#L=<0*ci{TXQKZou41K|1Zu14%P`#7S z$pNTSy;Fes1`(>^C;D^;CEfZBDOK&)ceKps5XBB-HOJebL1G_9*~e1>9#@8VsfOY% z+B`5>0U4%()m3R}uk12VYRR1~eDs!eP9Xe*s31dJQGt|}DV(@uJg+K4z+p*wR$h_- z)Qo~rWEziPiHcF%LaMaLN?i3Wp0gf1rS@f9?uolr;fnuKhBH2BiMv+nN+4JEb{MZI ztgHBu;I{aEsN@2`QGlAXvlyVP2&PcV8BAI>Xx_k?-J&A)&)S9gsvx%5XX(y4-jf%n zP&OZFDT295m%nmR!a0>QgSAZQ)R9G8twQNc#ge02pgNzea^W=R+_^)nx&*G0#kqHa zZ&=VXzyC;RczC-hSsxN}3-ojC#Q9&y+b7_Ng#B%&0Pf#?QjTyT+STFOS<*z~whX;; z8A7F9pzlC0NQgo8-wS32oX7ys_oEBNBQk2kD1tMGGwP~awB}rj`6BJHhg!i}XE5Ji zej5}XXKzB!)7RjCV{kZ5|MXeObtFGBl67UhAf-5pSN?GuVE8RIq#lD$z7?isS)|ql z@>#ZrjbN?B?U^{vcPY4}d)sW55r*xm?IE(VuA`+wr8U&g3Dm{MF-F7&WOyf2IHN}I zM{>fTJeeejkqfdZZ{D$I#l3x95VCpDj2!)uj=OCH%a`@j;WxEZoHI$y>a(*G?;%wp zVSB^5U<-&0DKlN`w52XUPa^_1P&XGArsZtD7n=entn)%Dgi*KLk6afY-BmZVuL^%~ zNzzzGh3JatzEB^HaA3ak_3-Sr=uBtX$O*78ILr=-629kR@Ei1gwyXBtIviZ%w+h-h zzRh1V-h|o;+e(CEz?=B0LKd6AqM_h-ht%Msycv4_5;r%nZ1bo~1 z&YrCbhbZBbN?aBu{`Vb-G7n9ns-s>Z%_Ax;TlH_IO!1%R zsRxDwQRFjlt6(a17)C_PHyodg=rH=;!rFKV_(Q>}#BzHAG{YEegY9p(_%Io+@eo31 zlf@d{NFEX8$&6+pWnS*usxh zH@#OdRON3Q^pLQMHwuW*e|@wJ89Q@YZI6=&U(ztE+)OtuMg+ z);W`$wP?@GF9bW*I}(Ak*c6Q~aKDZbYq~53o=GTAkRgM@^))93_v9A9XhZVa?^W}G zcn>DDLO5aU6k7|&D_!XZ2_VdPOO!T`Kw-j!zg#gOklJ=k%0_?T6EF!6|K z5sbC;4J9kYHGK5>{{|2>sQ*h;p>41Yb!k0$=$nX6{Hs zpiuM0JJGBs-2TjwWcA~Zk*#(Rfi%O`yL=#W5ad@4=HcQJtQMkd-Hf8xF!{>AjWLTQ z@_5Q^xQTaYdMmbAG?vZ%R|SR>jh8UWo=NB-+|i{cyB`0JT&sV!hPP5w+j4>3k(I)%)5wICWC58E}zGKMVvi@+`2 zB`L)pWwXVfI1;m-r-+*9=|_YocIWK$PNQ&bATKLW9n3h5ej`==7ZILMLKIH#5wCd_ zb*hBkMQc@tOu@9oH*bnd7+8!xTpOn5cAXG!zpT);LW#A#&uU7j8o5q6ph`&C2P6_EG=r|+#6O!bI*U;w_Ve%o4SQs*0)KxY;K%- zdZA#<4q20KNF1^FB1*^dtllKL!fpGX29`FZ=|~PjST?0=34DUB+A@0Loe^t}Oy3pf zbNL)v`vqQw+hQ}$gz0>6yOXPdz3ok7Y{d#@?`uw)I?-R7q?TBP=tua(Hc>&mm1!>g!PM{ihJQ zEr(fJCMq-)#_!OAXFJ|)KY%V<==v=_{vcY9Dn#V?J8!s^4f*;LZb+b8e;}aUoup4H z6i$yz`vdL$sS$Pt2WN96NrcszauZwU2Yc8`Ahgf0E6@sQp4+<;#CCn$d9fR`iW#)} zc-d<{8nm*BuB=9Aj_n?sr4!kYUSk20l?eoq`Jdtjz9$mP-UI0y4^g_n0Nhr#-(L*nVTb|4y~+4F5^)RIR+)w@+Q7TZn{^6?4={< z0l)kk6@4&UN56FwNT-pT$-%r%NL19kf{u+=!5=kakQ?60HD~J<7wJZa)k~T#jhG!J zQ#Jb)k>1nLDg3L3%m_aTrg7ejC=5;6srKy9>N`5qI=U&b4f>wdf_4e7k|3xjs?L(uOa;my!d!}&0y{NRdLDTYE!PE55=|X0aw(bt_p|@W;dd?nf<-RHYGZnF!qB+x{(XuFb1XZ zZWKiKlDmNb?_;m#tzv1lmEp9;9IBmx+HGew?$kw!H_LNV@`rq_)ZG+r%AKVy$c>3i z?uv^ytpcjf!v=c{FToPe#kB{l&W*0fQ-w)1qtqB4_*O#+c%(#)S*m)jHHCTZ)EN5B zO8py3LazGz&+7@2^Rt}NIK97!%bcYmBJ(XjIpBr$=>%U^L#Ok%T21T1_U35(nXDL& z&5WmiK?_P*QT|vR(JNN^Ggc!`G-JpYtMqGEW1?EQ)CqQ?t6DzUr?7&tS~=~Z+5m2r z(}aRGk<`gq1(!CP+;+79ZU0jpAX}$=RqVv{{kPmlx6X2#=88kG{xnpvCBEO(Osu3O zci$vaRN9gOJ=Y?f7sUfm9Xw60$vOg^uyK4SxJUX8Qi3g;L6@x3?>2xMOq>ptch@}( z6txFzK;>8R`v6qiW4kOS(hXBa4ZEsQ@8uqf8k1H*LrHAvE!dhWWVHiiwSDfxU5w6z zjEDF^biad5lQmmm*va)A#Fv$oF@upbe{1#}h$1LcL^enC*`~k5x0f|lA+kP-NaC#| zpyf3~A`bqaB!--R5KOI#C5Mv~Sp|zkb^&e7anWD2PvTM;C4EC_t%724$^0F3BH9v< zV~r;SPL5^X2&NjW{@xM7^Haa{L#?vAa4ds(u>suS>fIsAhx=kFy>p{UNE?ex?y6?YzDoq=&+VzyDnGcUDZC& zcounmXzQi++8@|G3qAZboTB_6k?c)&;uWreO>;d$vF`*E5}gDP92THI!CHC-TxuN9 z9T7KR0_>65L++H&H~3`rrF3Y6lO-vPaJeF~hHPM|eMs3!t4PaQgkhe-Bg|d{p3Mab z%6y^-dhs|965pgkZ=~sXC4@Zb@QJyhNa^}LU?QFmn?NBv>_FR}p-*jRg9Tji zpj%sm99;RPn#_a>zqonbuHLrYT^?oPDnqp1N_em%+b$#MVPWEFJ~Pm>k~XF|3~uu3 zuD&a(mPU%2m`F(i9=CFuJ8)pNY~7}9jZVaOcUA;rDfh9L?AX$pf?d5e5yky-x%?*; z1u&C}z3X+B&rhr9P2*-Hvc-gxU8RO7LeVqI?~Bc>dq<+90ZV>awNds6f>)#A(II@;;UMU7?>XQi*onCQ zV%@}qSZkf6&@<*=h3^^?$JHR>^YmdtzF)l_De*cNvpKNQWpg5RloD%cG z8GFviU%haUF*_i~v`2o(@Alz!ZlW7Vpbqu-v4|d@-`E^kkgqk(B%Pcg4|$M*+z_R( zCJmDOy7W=?HQ#$sV|mjOzbgoUeWprCRuP|A(r>Npm+1b({d_?%?n~6vP#d!R z48vgD#4=tNgzE!!{!ES`a~u-#-Q|VHg<=p_Zqw#Q_F70r5r!e~xf~JW^MrGzHJDpe z`MH6D%6A{V`-?ov^rW0?}i*!;2aew(TROR>+eiL}y zB2WeiNDD=HD3Fbx?(G*=H%Z)6Y0*%AY1B-B-Is~Vl!#^he2ji@^26-PQm25e_BwsN z{dRJ>*36N&x10@!b=eqWMBWdY2@r`0L?JRN5WvL8Ffzo>ketXbw9Y)-^oB$t6Y>`s z2@3ox!is#DxE=o65Ffo#f-bughshZD z!N0n08EyM^qWmXC-)I(|s`~@kuXs!AmU9%2gwvWde4@Z=k#1HU=jK!)HOYuP><&fA z!e!qA&5eN3eaZNVM8#|hpW-k{Nr%gWs>so^TmLo2=?t%sE@%BkNxYsooN73(^)U2V zULdL$Bk-edgpY5%e`#v@)GxL0lilYXP?d^2k+4=}voMRT=vUC?UdNm{om#m{ZlNkh zQ?{k)I7+oh;T&9EzyTg;Bv}l0V4VRIU%)9JXp}D)lrMP7*G}M0%ArhUyO_!jgT>m- zo-?@1r~3dfN9~k#re|SccV#iW;9lGlPGYyGdwblN!^?!Yarghgae272#iWwOq{8mV zCwOp=hIdaC#tupPJSfz=par|IB`O0Ac@ZYuS%%!FX}lh9?Qv<8aARO@6u6J>$n!!c zWWObZ>|3dL>&;%0uM+a&ILUILR+p5@Lt(8lqL@S5E%)r_qafr7Pm zIXt2_oz>9LYz41RLV$XE2yOSCUNp?TWqU>Of^N{8VfZ>L7eOh7y4@+2gjNB*b0A&=vGMKjWuLr_DJCwigNoURl@=u2UJat$)$y|O7y2}0^=#XL6~1nOypVo*?Ue#L%( z)yz?xgEyz(y`~p>`m4c=VJgqR;)F612|)jfxX6UD<*KYNZawbg)ZHHfEi3nf^JK5hu%Zytar6k8P0vc#82 zh)URVl-%$@demh|S+M%0P-Su^6NlE9F(zd`Ukk5Y{-suw=pgNqK~Q zOQN|YJ!ZnWD~;7OD#6e)_a((>VG)8wNDMHri;%({vvYVxm~=zaw#Nz=Qh!Yrz*l|7 z^AHA`c-^fT?<2wr1^DK$a7(NXEoiA^4S-M%Oll`+JL%fUOznlfP!wf6e4F zacdcg7L+0$m5F#-33!skicX>--^_3nb@>&A!>SuM3iyYBI*&|@!AGOE8sH|ZZGHs; z=wn`_*phj3D!(QQ`6;e+_ z{(^A4xu}fmPeHAw9R#0#jsvd?AXBgT?aggR1R=sVpE`Cpo;WI`u4Xs%!TLtI?s+ zOS(0(gleVnm9~fH(2g#!q?tUlOQc-dGOlfu$=U^iJhF**b(#U|j6Bifl}$16c>|&1 z#5yY_3r>tvli**xhv`1(c)b2|$6_@qMb&!p8R6BfN~HT?K%iN`CEJy%2|Tj0-MKY% zVC4Bz?Z`h<)R<9wO2#W%uparf2I}v~4bvCsyX!uRyDLxiv`mR|2 zyetL@rMeoHpP&)nU4>R{x4zpRQfke*4J>LjnB=bDB0}dcR?jSPtRS%#w@aUfWTw?? zOr@L46N`Hbdn+@~)ZQ<-2hNYxVhkrAynQItQw*tY^+|9x>EKk4FsMOc?st7T)rsKF zAE3nrtRkyNg8oF|1=xBR#+2nHJc%msQC(Pxd}UYh;h(RVbW1FL)brkUaIQ->jQAUb z5X?3Z7@`QIu%MP`AheBAhK8sjt7;zPuTcg}t5R4ujtst3L)5&sC|xY=6b9T?xl7P7 zCY0+*_ma%A%kdyYlLcCfMpj=0T2ozsSjnFE9AHRnNfXE5d(j8{nt}&ag%Hz_-%*VJ zNwgM@@cU=RT0kr$flDxsnruutUP$Z#O``g~(jppJmS7l#9cXX`(>N{JcwOLz|REzyK;9&P zpHzT6DgPgWJ`ObhKS2BoApWM{0Mm2;P0~RB8X)*52>@b{{7n)3Q{@0O;{lrB0nG~$ zb~~`}r2#}h;0gT60h7glp`!WHKtsg*#USbAfVN2hNyL3<@cBCve7JqN#ap;&@XZc@ z3^cU(rbD1ZIKM?ES@^~S5C^qv{Oeexp=@@6sTiaoABVtnJhE_5_1k>Z(E(^n2~ncSgZlp>dMdVXEL^d4AMdL{uSv>Kd{r15yoWrr_a{rdEOV4e~1= z|4Yy{k|r1P8?6lH_$IJ&AM8}#B+VUuZ(C{S`Z{oTYy91QOzm;I(87Nc6T2MG$d_hn zyDB!gkLEc4O2KwBw+EQND5(~ICL?1|szA(scEa<^_2zL4&c?xf)=94n#+F%)+CeAn z^xw!+wd%d0OG{y?dm+|-!2ZLbbwakfLtF&_pd zrFSqQ-BYT}2)6&VUyc$~eG^GvL-kMFC_R8M;$Z7pN%5s zV)>HA`0dbS=5h;2P-S?~MVS-i{^gU!>MS9J)uJSdp5ttEG`euDu9-U|aE2H3BtX+H6EJI7N#+Lr{Na8Aa(z{T#t zbaD4b{((W+pEwuGaE*|ew>mXP3>P6uVlKG*j|dkDMx5jC^H-buM>U zp@$)%W{^EMebkpKx4}4a`{9A5*zTCKtG87!vun4&Sh=lxVXR&HgK^gGa{-*6tC=xU z$NnaJ-5N-PuMlvzrKrf~#Iaw}{j(UzdQR;B&>4IpqZ(dxOLBVluw3e_T-vg_0 z2zvQ0tw;h)pbsz=$9trSGc2Nr-&vw+Xl{^v9WCk#%Xz&SgalA8Z`nf6-}(V?tYJfd zs{>f|MlJQE#w^((LmLjzakl?OlEn1Hk_0T%-v#y*Kb7vL;QGm?Pc+2xrA{``Mw1<6 zh(LSfX0rZiCs-<1sEWBOLcP4vs4UhZvO*GeU@iHZAgo1 zj}=j~U|Cq6iz_K%BS+kL9k~82&8@JJz5MsC$DOj>zhCxqTU^shCc!3d<)XSkyAJT( zh7hl5n>Po0*SMIBv5t^HeEsMv0R#{=Zbz>%v*_zEQ5KrGFyed0oe?z} zEZIFT4r-oY;4(*(5XnOJF^MtEKWkqib__VcIJ8B^urVI41GN@b`E*2egy}-FNthUE zho6AB$(b0VSolzE`MDVJ3!|Dsuz-CbG?;CBskoSh;IEiSCiR)JUxQLQ_@aD-#yfd^ z2R}bNGC_Vqcu_)&M9fwKOv1V_F-GN5?NFYilB*A}LN!~VSu;O&0XDNmh6_bOcHm1C zH3$g)%dnBeKqujxG^I>^)+oiZ!~Sbz(QOga1r^;-4fA*s{BIgb*8YWzm5(Ol;AG!q zlDTnoY_wGILA^U;BK>Jg$ZwvzVXS=xAI{RJ1Fmg=2Fl69tFrbV&BWD#v}*4&rCTTz zy1g_?S~1D~TIEknI;ROL%4PkONZ6jP$QAahvdEoXRN4-Wemj*<*xr-F6&3A3RFt&) zBb85qVOH%yd1}WAt0q?o?qd=;PeKS3yIq;u1B`(^&N*~gKvrr;YrF$8^SJL8I|QilYNB+@WK5BZftSlCUs(k zyx6Cge=r%C$X&Jjc?}&(>CLCP?|xM8 z@IKW<;0aKs!5O4^rsoEBznvxgis%L(gp@)vQ!ob(PJ9@AnK8bFDFv(b7KdM!m8Fb{ zVggC-q6x5fv(lwf-Sg5}vO6;E{@y-#y5F1-uVkI0DcwiQ0)ofHlp9l5&TBPB+f6>o zNMmS`qRbSP$6;s-kDqzxbonpH72S{9Tr4me_#`HKm7QS8sqQ)R>b;11*98Fh z{?+M{iZG5U@nj1bZh~J(O-x?NS{E;5Du*#X?_|V`frBE6h(qA07`AAb;fdKtZpH5* zyqnf6-4;#`g9y;q@-gb$AUOB0s3{y@@l*)!%Je&*oiH;mrjHU$5^gOUZd;i6gX>%t zRWO7!CR0NoFiQLEty|~~Li=iXu$qhLrkGA&)5(%T^T&5bSNiYCi1r;K#X+;IJO-WH z`eZ#e%_Af@5_Lh!Z3}i+_-%^1$v*4A#+f#%o(y{oSHX#*QKu4O4T9KVMV_#p+WL4Ir7Pe01_ZU)K9zVQrAv0^2}hz-lsaR8*uAk*I$ns5-_B zHw!e^_)%Qr`?L-2I2v7hOf=8(k!{1o9;I5^{PWqR$|_0y*hrp{&)_K}9pL4cEZY@Z zAPR%GH>m~Ww&a;QDlQxFmrF~nFoux*LGp(NV;+I|K^tKp^t5*9&q-O`e504v3%_BF zXfb$6$vAmHvw{Lskl#^Z1(G`Mbman4qsv;ytUC1WP*^fXmK1#=iasSs)8UHaghVa>*yUHCF|&5SU+Ukaf`vT=mg%!==Gq1Yq{d$+H6#9H ze%==SB=T$AiRzj-z5E2N^(V%+%_R*FLl;Jl6Gyo!S=h7dyU8u<=Zui-!es|9ccVBJ z4fc{*LDRgDXvNLn`Wo|=jqWtUJNIWrVi2<}v|uD6j`p<(qjzd!QAEbi9m8}RvPN%I z)zipO`t5_*7=7(>?+*%3|D3d>5=bSF5RO>NDM0rSi{oFkW4=$QZRl}c*Q|^w_al}- zKX>H@5>;~vc$OJebIxL0dW~d-80vfZYtpolJXuW5(W$I>4m;<`BU8*%y8s4ALgyBL_aJ1iJ?yBk zTFHoF;r0@A5v{AvF!^x?o8Whi?RqY&jv3x))0tHtGD*o~VDjZ-c1dcm-TC9P#Sd&` zViB?w_Sdt{H}m`?5)#S+5?C6syh+)GfNb)Dvt5J@iBe#xfeA%<4a_6zAgEPRYW=La zz83tk8eyzXNUPPQ@cOG$gB3%p&h2d2g_!Tw!hjBUV4nq?Hg)MR)P2{iP1Z~fPB)ke zXj+mn>C^m-e*y|kAwEXSuz82wS8b;--Y3n-J7&vfHNq6uWzp1J z!H-gq@Pvkq%CgDQCP2CSfL`7W)FqF;9!wB9k~*fkd(q9V&=#y1OZ5L5bZ1`}%JmKB zjvzlnmo%6;@Or^6tUZ|WwabTFiGa!#E3OI*YM^FUr8Pp+aWqLmTV3C{kah7Ql~NCiaoHI;$Wae;*ce^)|c9HzB(B>){vwbPVafKJ?wP3%dpk4UoQuV z1PRzKd6HJGyG3tkgz21>CmVC5ayu3Y0Q zG2kd6T4^j2R-|8TEY^D1=U=psSq{KeEVxPhyHtKS#50e9o~pe{Ce!CzjvZD6$xWiN z4{AZEn>aJ1V1XDbq4Fx9868(t4n5Conlxh>&Y$%^4??Xqlmv*>72-VO_$UHJx_c z_{RcJiM?C<7Gq5!$$_*b{qjnC2+)iD4js8b_1_~Bu5cz>!q z+ySsX`}d(-J?I~BTF!8OhE$0Bgr91of#Zz*VRbnxV3(4(Zz$Sf4dZbky*P|VR+BcF z*VdDt|ByL4l7cAF&;S6I=>MI}`EOO9nTf55vxSipoxGjBi?xCC|EF~nHza`>kh2#y zESuFTzXhQTsd-yo2~{DZAX9ouH|k{8wvxB1kol&;`1;}y<r;ID*dB8!Fe(a~#dUI~P;F|?PY_Iqo)LdK@-0b=>D zE#eyWB5p>D%kltN_2L%U6YpVJ_6-sR!LL>+->zO(h%Y~jCAG|bS{O1)T++CaHpb^A zw;2*3f>EkjzcO`vWO)#Dsk~EtxxXE{;MEo`|kw#|85#tc{>YRXCX&BCnq~s6UYCBA=`4oT0;4$Hnu2yT4yAM zR8S=2*NQhmGAM0RW-Y1tL_k@Ct+%p=c3GYmT~}Ub>9jH`%?su?Tc;Qt1&}FiTKGMZ zF*MglK!5`Ax?eV(W_eEBW_VsUJN-UpvFw0P z``}Q7Z(T56D8>xb1ptT;u!qW`4;ZiGc0oprqp9NWU_w42Kn=L@4+KDA(vuw&1(1~j z-{PagP?!(0AWIx7a4}7PStbI^9nlMdC1v`2l8n$8X2ik|El2FjUAB0w&7+LRTW)iMp>5~2vbciXtDwi|JGMcqPFGF5GKS-4^^m|gypvyGofhjAo0in)Fg zW;0E#jsk(B1$--_NY-T=Zf-r@9Gn&49cIqyF=E~Q_wF%c*wR*XBJ-fe9d~2biDmF+ zt9d~MCV`>Q-10hm`qSO!1264{QmMpqWWm>YB2z;;W+r>?!Pf1@blEkzb~&se zK@XY4cq+5;;XR)~a&8;OL{Q=QJa#O7?K8iMQCW+Z_+aj@lhCcga3BZkqjxtdrcZ2R8vT-*{v10hgtg73*Q4 zo8FyfkAaI+LrEoC2&;!K)$CbesYlZN^^8rTKJ6%?)v7ObXGll&f;G#d?-7DplY=T9 zv?eR4dLgWt80ov?+V@%iWf1V!LVG|$!JW}Uh7p-)nAoUj7+8%~DxVM+!j4-`;Nw~4 za8`kr<-;DDujnh#SoPwYJmE#RJz^eW(sXu`?qYj3%FZ$lF0zdJaUtPc#~bVU=Vc7e zeMFDr+%F+c`7VzP>l%!=7;%LnLQ9vj9EaB6KK&i27IVe#^-g55ZJUA=cP|23Gfk7K z{-{co+~&^Df-%!&Faex|{gA4`J35kwP(m#XZpq8^)<5fKM3E;YS{< z9+a1GpLBp{(-p(gPKs+o@2>?0Oj4k=hTwq;LU5|yUWth?8R+zv`QE6EMaP5+ThYb3 z2$rVk12NiWI_wJho6DulO+?s2LR+@#(0bOS96pdFNId;LyS8yb_4}8vLr>_ zD9y7+fK$)!YQ7n2QN)TyMFj>+rP{=PuGs2Fd*pk(#r>6W|H>ib3K6!-c1(lL4$o+H zh9NzUDJd8KN5Xke?6f~FBY|%Z?o27YZy|l4@w3!BmM?L3un&s-K!kc1h{QKGZ=d87 zx3>?gXs2JKD@^ae=kt%>sNEgG(RWDN9mKc4-vJ6ma9Xiv*SXENNp6l=+jPzlLU9Rn zY@+3%CyL&H&Y=do5OY}gwGpXMshC4h<(c3)thWX+SUGYzfZ#mfrc66N&nt*tK`Q6_ z9m9N);Nvloa}wl2DIB>2nv!|s^R)n-+&1&vj+Ab&ZcjvQqT=a=Np68qS?Q=>Nr})9 zsp38JiFY=}{v*Sd?%<-{;G&!~Z=y7eL`f*Il29T6;*M{LDW4ElGsr*_!M zM&9?@vfj>sCjJ8ASU9hnHK*&hoLaBh?%toTh2MFP15G5oY^A$|2xB1fyK;5}VfZ(> zrUPpvfUasnEMcJ9;jDjTKRGkB2t%}!47xxGMD2bTb_1p8QD!~4CVh>e;4mmCj8BP) z=NDvPeXIp&0U#G0^5t}9D!LZ=ECgBUY|5C$_Wa|?R4z{=>_2B0)ADkXb&YIF)cbgV<3N`eW6g7ApP3EC4 zGev>^*3Jleo)gdCe0Yt8C(9^TtmzIyHEG|BEfqJc&M83&bZyy^x~^*phFX2S z=S*K6Icj%P3IY{H6^}T&ICPQ5`;0D+{~^Y0^d#sa6xZ_RtL0 z6Aym&lY6|h)#mQVVaVAvZ0@OUS}OIvC5VNev&oWw^V8;K4GN}YlzHqaNm--`MsZp> ztj{*BFk^SqLoKwG?M=~I{>Th;7KzHFF&3&f6YtSlr1xJy!ftLTSd7l487nLLY7Apx zZVzcunzCpI)ELSJ1$6xhsDzYV)HL~B$tPiyv$VsZQ5SHVZr&-+eL+;=kiGAq-$8gY z*w_Pd?H$ahKXYbfV&}?kXJ%&4!olQ9!^*%x&%nmR$-~6MS+8H?2Fb~~|Aakx>|ekC zmekqyBt6{1qyVSuT<&(?Xg~@z%7{+BEDin|L!f2Lq80Gi8{uqWZI++X+j+R9&Z~q! zQ|xz@u2m<^Xa1|@(MfF*d%aerW@jCyyZc&+l$Crc`d1VMw1Nb+JNigPQ2%rq%g9Ld z6t|PCSgTR2Ja<;=4482e*l`SzEp%EWp|hOVXECVOb2jb$^td^>s>@dq$y>x(~_x)jKK`##)1MbAju{e zI0E45rKZTPlkh=y5C0@&AX6(msKg$_73CXO(koV&oopvnFYnk2Ct%k zRwGS$>1~r;H_~i8G*1hWVvkoYN=dhbnwV zg7F9AUpER1$nVtS^fSPPe=-kLAQBAB~0W~cltuhuz zun(ZNpf5meYo(0=EOb24tbv4 z4~`iIdSI`3vf43!nb1#G+5BK)YvbKpM+b_hI{tT^%|0>pAv5&>nfaYP9=@dqb3s%H z?l5$v7v9)f1!;AbuS#jZu)Ir^lHQ;*m;*CXUQxf;T`OmT85nzLy?qZwgZEnshka@> zL_8!e*pzSTL_DEFy$%FNN>o@i8t32m08MV=QQ6F;w3S0?4I^*3B(M~1vk~Y`k+`<0WJu%k*s}5Gk+|ka)&dJWkMBc#Se+rTm#SPm9 zet4b>sqD7U;HH1}b^%Q-T1!RT0tkZ2=SmrwXuVU}IXOrM5yh~4EvKS*)&?ev2L_#zs+ z^j9$=sqX{b1lad<$rFW(+S5RW4-?StlF=N}y*`qpi3!mlc8tsqxslHp0!ke)(Pq)N z*PocrUAV-c*L&EHp|5@uwA0MS)6Hsw?vg3D3c!QT6yk^PwNaW45l^5yo3}Zj_oFu{ z_V`0}LQRLFg4SYj*JZb8n!~TuqAXDd=o;8#&{f6HnBDQ*7w}`cG*UWb^s-F|_`;7~ zCx2j@i9Tqw2TDMZq)@4;8PHw%cCJrgg-+tOEAJ@aprBUjEDOR^fLlPpXgSI{A^$9; zX5CE5N$q?I8xNVdTmRe~P22lscZ0^(%kmY<`c(ziFpHE?`6w*+ja`^T+Hl5{3H?8; zeN&XB>$YUF(zb2ewr$(CjY`|LZ96M%RN6Kwo!Pn1xqbWGbGz@@4?V^j>uEi$|Nr8P zh#7Ov;tkhc|8}io`Hf4bGCV2E(jp6FHgem9A{k*YwXz1*!nqGd`2v&#Gm;KTaRO

6c?ib#El^{ZoOfe_7fxH{12pAix9*w}zc60K%^CA& zqUeNOKM^P0>lZ!GZm8}|la=c2zpm=C0nOf{Z*2?q{Wkrd>gvC1TZX^&CMg=&8r#`O znRxtD)fTJ2XlXBD_|i4@+XF)w%cqzZAch98BQj@z$V0=61xN!Fny){Y9+|d5GO;`T z{JCbyg2}Rp)@&KAn7X{yu?QkwG1p?bw5C$MY5gXZTY9v6k~?pw(6b(xRK;BH)q;Mm?4KLKLTdfu=w_;w?1_puEhYvFDjivV9e?F2x2 zW5Ide#HsUL47=Tgqsg!z3>UgrAvQkO^xd_^{Rsw>gFGwkQjZime9l>Y??IE>2gBvw z|6V{+B~6l0f{Qa(n&>GRo0(xjya$;Ar(1eC7syn?fPu}dcw`ESQYcDYlg=ce)6W4q zsydHeL4u|jcP1(C)yzWk;pA;i;3H$pB>Eju?#kPh{1CS@JKMzhP%AbP($`8m zc~DXm^ppsj>nt4AyCK5SXAW`e$(UwZgZee~93{574>1mQh zh)NI7ERfuq+y=5IQIk$`myC&AJ}w8Inz9EG;u@gIr#4nDTNEKK{2iG^@#k*liK2`2 zAyj|NAEM_=^CsEDmdHk-36$h4O$o=eO2w?LLqaS>6d`|Ak~e?K|ID)|HA!ee#-mlN zwu~k}gg3=?!b8bkCT{5Zh?GTc)4Jd)9$3Oyl8%PRJ*2jj7+ZH8K221^lu|SaG`m9* zbtEVyS*r}yU_+WK^f1-%oA;(QfMqIyf&sQL`l# zohm|zWsv=-=3ri~>C3*dJ4HO@b0|AxZT($SuP8}P(C_J1JXwUw0QzJNnMx~6cAT=` ziEWx5!<>;OA^HF)^w31f)i{Gvpqv#8mBysu;*}_2lgnScC+4o2#dq9)PpR7nO6eQL zi*ig@wkLwE$^gvR22Fr+j_|M(9>Fo`RhPF%4oh{Si`V|R9Vxwf zsT9sj%FCy4i>RyWfL&YWj>4yM%k-`-uuh@OfKt2b0=Ff93)NM=N7FUcs*qo<@{V{- z-ga={Ep*FMfP93;g4G7rt9WbmPAV6Sf=THcx$SY|#n40L>@^egr1B1k=YAuG;y1uG zFzctv07|+$ELFD+zmh*D!BZmhht!CPxg_1FzZV=?<#Tg$s(fidw6&LGX{}!nKn^{P`io(c+8To86Op8ND_3o&%v@N0A~n8t5ke1KR>9KZJ^fjk z(DEXsma{+RGTspE(S0&YAL_m}lo5CQ2XAd>bCSqr))TSRu`5KB$_p2ezXMXT^NSF{ z%h2OQzrZet4O*&pjrHr@Wur}N9yvj>{5PHM_(g#S6O*(vP1{a>;O%iJ+94NNYF4Aj z@zGi0p2|CLqCsj#P!bqtUNf(BpvvtCyFk~{g*6{tag`~Lv;RKKe znadWcQCC~6RgQVCu4cbub8~X;)mr_9J(N3Q?2z3jaO;%aH_ga%x}fH=KTw&6?Fs#fz{7)E|9WY0a72xBBvx!yTiw&z8Ds3xX7BY~i) zWimI&wROM4?dzmV^IXbfsVX`;=$Pqe`R4hg!D543t}bw{)-kT|FghHodhN{guGQ&0 zlYofhu2|S1JQr37da}UNO2*$wAGxmE$&>!vhanQkb2YWjIoelBpd7 zW1H)>L`_@f*7CLiRYoxgWLaKRx`lG%F^@$xVXxA?aIAp3%P)a|^&+i_UrH}Ge-^q2SO)tnQ` z?pe%o^wK%RucJS|EG&j`_bf#ko3dxQtiiO=joK2PE75nk+SEjOk9R58#sq8uwP|d~ zs8M&!H<5SE=VI3%vRQq|PP5uZYKUs*f&`CTMRzSAL(!c|sfKz&5FlaK zcL6f?#!)V}76v{jNyCdLhO&qz*+u#@OnHU>e)WurNP!C5Iu`dEXXh#W z=sY4{k>SS{`VKIho!M9>3*v{5sz9@<{VmnY8+xN;Kg`yhKu`1vh4e-py8;^7UvEov zu&93OvDZjj5)Eh~=do1b_h%ItUplWo5(s)LU~L1A!#`_6-ehkrJLm246XI?3M)Y+{ z{kcZicw?o>&M>7xtdelF z-SvVu%{Oj=L#07bC0U1vL|@b;sjW8438J!E(y>(nnK&-UGKTXhFOj-fJ&7ULQl!c9 z053a%s(j9mEN8Wx-Oso2fQUH{vBex2;9_%H)lxwgY5BXb0HD?+t(6`9$ms^p?5xwL z23TeutMJ_WN}2~nWXGI`NRNiRJOXMdBC}s5#(z(ww7{^i0XmgZ1zn-Sp}7H@q4)=r zB#rIiXLf`f<|ShV%K%vaVMClN0}-RiE*7u2v}B{I*f-JNWiMgk(L~su`Pi| z<;;>IRk|B#vinzEIPqP&w?Vu(Ms7t$7Z-sb>c5wV5)zQ!@lbyB&PPF-(4;x> zT1-KFa(=J(Y6z3RmLlX8eXI?GDV{Ae0d};BNL*3GW%}9ncr>u&S!Ub`1>7%G=H5>8jmqraR&D z^=W1lfYyL2l7YH7_ao>eRRA`%ky$ONJ!AOo89xlpfhNqPirh(Ov_kVuJRNI%WAU~= zCLx9;z}n^h{O;BDQMH;B{{)@F!xmnWZ6m(Ah9>WtE8hw%fZuc2A=_R>pImPhK|HyO zrzTbfd!@#8y|bm4#!c%%TDhyk`ciyb;i;Ypg%!t;T9v!kU@WGJ&8G6Id0pDH*<@9_ z0kg#_OqQokQfAxAD`2H1b*$DP?C=;mEe)D!V8q1uC;;28lyJ zrseVr@E$a_{kqM|@(rrDPb~<*#v|KSDm3Pp7A>YqOgcvvaEgPDUZtJvTB;I@lg5gt z$p^!;2l9eg<40n5Y;vEozEtlPwU;mT=jL<{G?+@om;Xi5+)kV%*&WX`%_(cu)TWm! zPZVWhIR}hds7@}!b~onyF@*?Co~G5IIb;nj96VmGM!EWZhwmmWS4G&U?hZ92<&Tov z&;X<~<)fy6R(s7+8ekLeg8h~NmyNmG@&HIyXytked2UDzV7vXSfcrN69q1#F5jd%V zvtC)GfPua+ZwQyEbJ6w3X9Ohl>Dub@d1!v`%G%u+4hOP^#)V|al#{c2H2w(W()xm^eMF>G#%;~(=M;-QJR?yej*X{+h6`!7P$Ip?&FV6 zfgIye{t`7JcN!Oi*%I~|Tj)n?Qu5=vQ4BMp_?A*in!0cGLPqZxI-Q;OHkLRCgd8Rh)JKMu4H| zxZiJoZ|@l-SYi$~v6QTlmUn`DKwt0NlQ&DuYC!tNLxiapanu|TafSrT2Bb=00^K9m ziXBUdQVEdBR4_FtcuQ_ZE}j;1$_huhc`S1(UEKQeNph~NXAq}FAr&zMg1$E0W>yUw zW?5345&9ZWdF0#y6o!d#FR4vRLs#@iTy(yxSKfAieXC+H@JLX9h$vtHfKIS~J?sCj zlK-CHBIDxxkJ7xnowbG0e@NwISpiER0r)D_Ml2avKt2RIjNw8sgrD%?=)ZXAVW%!= znYbFbuqIa=e*t?d*FEX?3BhA!ToqJyoZY;A0P6?7A%7qP3+`o>5h3y7>Is=7Z&@VP zGxop9FOQ$6$s`{p7};7jPgd**;c(B0uFOFM9e3~QOopWH$=-OGQw~;c{CusAGpHfXo97wXUcMxlCE`tpqwN8!R%?zSB0AFc20p=He%bgNz{-e}ekv zZ_K=J+v!MISu##K`NrMN1jnUQm-=>Xv!9B_NApl!iQ}zRf^^r9bgrC(FF|s|7F$LKr%N_T>*YCp zyu@HdtSGy2px^6;zGoFV3%hMhW?ihDH2IN>L>de}L#?F>xb28Wk=*;AbR=fwKifTF zG}s_qeI96T(2un$)1W_K*Ap#O-uHS+-G<}cGaot7MI#@fkN2XWZRc9YV%I!81?3%m zPgYFJ9~2)9E(X6YjaLnh{hTol6M@vi;-dxQ-MbLOM8$VEEZR{BOE);rD~pd#@_&y;q{kv##`2% z{~z|AEv`{2vl7o^I}6-Ay2c+&C_wu)+n;^-cl|M)bn4M2@h=f z1|iJUCJZ8Q^`V3f&JEmq#8XoI$P_lABoQoYDsZXg5h6UyN7)-@l>WS zF(4OKS?T@9Tl%AtES>v1)WP{*%&&jH!v9{dL&?P2#OSZc&A*=O=-B@6;0=7}m&Lhl zH7@rvye9*4EKhiNU|!oSnfPFwj0B@p1J$b~t~UUlP?C1_p$Hp{l^sWpM*`yBlexXh;9~mV|cp*Z!MKCb4)* zU$m=*i26nk`jx0pjf1i~jS!>vF*lOz3Kv!J?{K%HN5jfo7K4|k96iB-F>)1MvC16Q z^-Ui&uhE-UvPbpjEw7d}Ju)tkn2*@q2>vvE=nRCCG!$NP<{p)?jzy%&-hUt>JIOEh z9?MXU|%olK0CEo@BwdAO66WR#Eu;C+MyQ>dYSl|~rKg9tsVzsSb} zL;xnG0aXMlkJ*Ta(l45_C2z{R->TU!bfVE|5+A7iW|4kEp%8bB9hnorrn7NXC<-oQ_^Zvbg6Dxy)9e4$a$KGs4d zu%RFutcKA|qO9>3uoLTmPNXPJWAX?va}7>+xbqlwo#K9SC7sNw3n62wX(xUXah=-( zReP@9A1WA#642Y22@fQ*z!TDAPG39p+MxEBFK~1%QKp7mXHvOhGQ@iNnexjhJS%>D zmVA@>si>0%G~1W@6;FF5OK@y2Le|?paTTS4VesVT&%#xc5~b--f^wkCC+%QaL9M}f zpN}xKbDkK@!jHAN5&HWT-Mv(OQxD0BtB(Dm`;CSQMayukwEn744imhx0XUe+{rCXY zCJS+N^*+ME=a9J=baN%{3H^jNzf*F7r7`V=&NQJrRf@4md6$G6Y_i=%|_b4AH1LI5rVBci<-rE8XfRf$88?Fzi94{bN^=`LmJE+pEaj!^LDa>E&kK-!FDqnap>>S3uy}{=YP-tRjX;aZKz^w-bK-9sb;N8ERedcF?Z9qBucL*wG0uI zU#|Y#xQ)t8=VX^Jxl_lb%Eo}flnGa|EuNiEv7$Teo=sSq(By_kjWz;mgThs>jO`l0 z`T|}RQ)JGN>SLv*lM*||zO=jc>AA<5GW&Yp!~@)jd_vCZPer*HR72hf7&Y-$5m4S} z)Nu#u2=q8WcGl0w`hjY4Ao7$DXq%?veO?tshGH!uz>PedmC&ZXNp7T|?m=Dm%sj?@sslkangGDmP z;FSFA?$76#WUn=$+O9c^vp`8QS#T;I#|(iZHkojWoeUps5!Bcftpyd;%3_cbW!%he zw~FD@)0fi|oV)s`9YCaH&S}S^C2XJv!ioBd!$;h|5y7}$C~8}i73$ONIN2_7OXYlaMQ9g ztBJf^kAcOjVbGM9aaFk!Qj^!YAOt*w)>&1Gy`8mDo9)_xAOINKAKq3F4VjD>Bjqgm zc&{?|AaR?c>|m&uB972%t`r(Y%O1eqSOYUmDiLDVUz&4j77UA8YA(u^T^3YUOohzLaYCBwE;fWhw(#Cgr?RM)|XR5Xbio3BRcI{ zBXW02DSboDjJt~VOu7p8RJ4_EF?Cbx{D`FT_82C|-GzoT-KB=t-NlAGpI<^Biy}Sq z;pds6^vcAE3Jsz6H_)(n0^N_65t&&0QkpGw#s|RJnkn6?RCGk^FQ~negT2gLeNGRS z=pFVP&}gJJS;^q7XQVBU>W9olrAQhfY&0i~6U(JtNt2fu*DivC2idj|zCg7WdosW@ z#~AK@xD|QJ(kVwT7OZA!y1%_LJ+CeLk%v_WML2m82Om~fshyouvGY+;+G6}9YjP&d z%$SVH~;BXT)M8t4D^veYYVY~Dc1%S8j2c&YAuKU;1!seWwFl2Qtxk(o8@}YdT`X#!;*y>M@YRB z_=EWe4_yt8Cro=3xY%L$^DMG|E*Kr=#X*wxLpaa@bw zo^$4e8E}H?N)s{hFY5VhQgESVdbpA241YM_y` z;nk0^;_v4Uuu~U~pfNmU^Nid|%uU)!EPbsvZ2R-(dlqu)kp5lY4GMHuw~XJ&c7u$ zs+o94>z;UeEpI*@p{_}6Z_h)nIQ~SykG@(xmTuSbeFW@YM*K|8|V|nAB5+SJ| zSCH*n^-ClE>(%`4%Kz{2ToqdjQ#(hS|4aBA>8~VPhH<8egj7BMERZjMViUY1LcRr* z%|fjBn!Y9wXp=45y0KLQmK$5K2&kCP%`nC&+O3hjb5=haN-`=}M9=dMUU5#Rh2X+` z#*hP}+jaZ#hF8xu2b7ol7ura;k9-7#9sW_DPxrtfM=VNV#6ud~ zTv!|b9TbpTcP}1(XP8(^`nHW+A1wihcJ~fedVd^Ndzj^qNBSt0^-Pq1w|jEfkWos| zL>#rsai0i#o0p1A^D77YM?8N*2?0;By?I1=2BX5SDaw%~=1dZ4De2T=Yeh!o7F{9E z>L^P`c8rB+XYp|5N_FsYf8>IoUCb)8Pe?6VS zImU1LaqFtJ)&7xvM7Eib)Z|3Y%~ms}+UUhlfw`YI>B%!w@%S0ysz`_4z*x}0INwn( ziftq)jO{)d@+6kINt z>7Xgrs6j$w0v6>=AV#6BDm7%4R%pC^B2uEODhxguHhN#a-VF=MS+#T4?kzLnnKHMFO4dYk~ zTXt~^{p80=mV|4kxGmb8*cPR(!t&T6mZW8{uoP-D?zKE2F9(JkESV`Hu+rfAa*Lk< zY7MxxFx{$5f?iw$D2c3sUGXx`dRqXj#rk5{Xr%EaTUU(AEvP(7X#2UoGa(0jq^PNA zL24KgQ~mDGx$^q-{CZ(;Ze9#LGP0~%x#G&q3E;%z{6Dx_RIkYNmiV-O%;V&p>icSU zp@#D`25}L@tkKFSkpmZGY1Xvf$=R zmQqBjQlNDuyT-GLv!tNU^_k8fs7My0KQicc4;bW@XyYlMB`eQ0pHC=H_Ra+@J^0gb z{h9oF1CrXa@MM76xgm~5RV_N*yd-`GfSnh5gRkByUU2}P5(}ExS?g})3o7kC-RD~E zg&ck0VQ#AJJ1w3QHo~Y0>;IFx^O*z74DX~5r~PnAR$?|6x&N~@Ar^PEWO{F<87Y|G?zxqf_SbxlRpWD28=(CPS$qFxr%smR@ zZU)Vpe7x50E_@8%#T48jhCuA|2Z$P`MHytek8Fp!8ewj6wkx=Kb^JBSQJ;$oyYr%J zG;`e$w~PRr33E^Jq$6Cj?@gqt^;Q{iG(1;~L$&&Daz=v`a+Rf*RFlt`csmdcIoxh< zPR~BJxs^-z0M)SEeYjw>FYdXGKn`eO7Ku*#CF4rh9&Md|e(e$63pl(_J{RW?w+}j@ z*YTx4C}04RFVaV4Eyv&T6GJ>2w(zZF9`g9h9dV2n5$F_zCU<0BH;2I5Lb!szG8hv) z++yAt!Zlt~-GOkA(i?Kse$8yQsQvYQAcp4KC$To_?SVD3k1X;E&N~1F(k_1X#x4_= zX}mpz5$Haz|5Mc<0w{70-5>%nCW+)Bh2&xFW$^h=^2>jG5K1-jCBu--_-N_J6uM{$2|DKciLu+dcjd15{N@?K=hi2`hol2^|usuTWK8 z%_spb6geyzhl$iDPRo+7UzH*oYQ*S5TQyb`$TzH)&&zL-+N$QKocbm$9x#i#Cp2wx zZKpTgBlGEVdm#tF)^8#l7e`Mc(CLq{kz_9wXKLadwazG*mN*wAXS~s0`jIBqfCu#~ zJx~w@xPg*7V^VYzvQrGoOk^N2z$kPbc$)S}C?p~%--TsGi zdy36xlTC+AqQ%C6lm~9f$y|JeXT=q(W-4*+Y6se<#%x(ytQEbaGdX#^p%@PXag#ea zco28{4|=F$>?2vn@`H@jL^=%Lj&U~4j}((Q>`x_%zUb_zyDL|&d8W-(op73j04y9< zG)*@tH%rYCn}oF@|1l}9AKR!H`O@Pit*02?zmZu-We=@2&E@GM7((6AU>P=iXfj%- ztUNl*Xd+jfsScMiSl!-JdnD8qZb-=0g~V#fRq>n#)oxH!Ne++?6yT>(P&Niv5G5hU z)f4UY`Z-yNy$kaK?Jz`R_7d*6ebhk2e(}iP;Pj;4$oG@tQp_r-==&!yzww=AI=Z$f zV|mXsO9u@&A7dL>k|;0!d|}$wbmak(KdVVn43TE&?NI(bxveKvZ4wzW6|Gob*N{G4 zJZ=*DvXVNBF)jkU)Rx=w@B;%=p>ULv0v}PoE@+6JpU`AstHoWQwLEK!lR)hc&q8_p z&KZ{H*OKqg7;)ZTF3SRnleJRD%1wxN@{ia@25mOa?r)o%TpU!@LgN*4AUEf%7Km#> z!caM-Z?umWRj;8A2cYKFLg5#B+@}arK|e&e(Fc_eG*cmiFdFvFaPq~cAW`cvWR z&ZvmcI|(Hl09sA?^%fn_@Uxn#D{r9Vjh@UY~~2fyBVrXb*z>;Fceq-2WEhlA+ezF3A+-D&#?2 z2YaK@*DGme!|#c8&`d@JxZcrO!yvuE%@4kT5)TH!9sUxSp-Xd*kw0_`9`wUkgcyFB z?F1|DitXv$^D89dYYu}7DUCw{J27MTpATxk`JRP__}0dbhY=eU`qRr_AhZ;nv#%JQ zwPb|I3;i?MIvA*zmmjY>(O7L*MS53=7=Do1XT&Tn-|q*?bnwE1pcp}^6ysB-{Yf#7PbbC9{;WOtg7Yq%|}0F6HM2f$sZt<3pQjj z*2D!wG%XkA_r%RlL-aLKN)v?`<0g~FiWI#Mr}Xl8+fXN()hC97p80=LBkMhm;q7k2 zKjj2BNhr~hT1{s)&h&VD`MqTw%=r0z!1O_Q;|%a-9U4^O;2Ct`KuF)vm+xqU3rJI> z*$#SmSMl#Zk`XlR1qK>}ciJ-qV@$T}BOa}K>h=qQ>!=^>GD<0OYa4XRp%j4z7M7TF z7y)g@AGr9)#HMO9;mKu)xDjU{f=jPqP}Ff*XgZcCtH)0l^dyi;sLiuJcuTrT>#BtS zvYDZR%97ZSVXdgS5RvVN>X5IhGU(23Zj8CBYRa0i|5{ z`HL#9Gi3QB!M{MOB{MOmZ}uDmNl0Y@LP-A)N)!^6$jTf{s?%@hCL<>5Rg%%T1yVP8 zJ0mIB`uK>ClVbyk{)UK|oAy9DW$ocqO6MwYXIrQ00e(^a_d|0Qt7xx+oB_=s$~ejz z0x2*9rjd(r7mGGZM|upDxwY;w{Q-vu7uoDqTk`L~r2qRWrK*Ec2(abr?h0QPrM9th zQeDX&RnF!>N5uNY<-^xu@U-J5Lk00sc0tT*4zf8*<#Awi!PJb@iYtYSt}Na3FRgz9j=`DG9Z%|^ zsMUn9Z2ahWVY~t3W~o**mW)Y`$aRqZ@VjxjsW|Y?RAL4VIPB!f4exmYs9z28-91P( zb*GRH9y{EIpF1xd56m3eW8SF92iqXyQKjjIbnC7Q!~s6+*MdPtD7mipsCzu;HK4GS#yd#Ja-Vw@bZ_5qKO+#(_aF;W z8X!3YZ*UXpcOK2b0KEDy2F-=uJenJj{3gD4@JlExdB5JLi`uF8H*km>UV|5ZM)qih zsM)U+1-Ny9VMwGJz#(z1{7r$b{au{eU7S+wv-81(qeqLvtnKRMW30QAQnw2R*Wx#} z+4zTCo>@OMFvHlo&f+K@Uid9WPMVG}3!3S;uOWRY%QrT2sq9IjOoIEB3LydL=e!c?Yq zXosus65#W9n&uSAfTlt>ek8~{Qk0jVc8OwX5Ka#nM@ zld7m>sIv&|YqLGO0udt5+E8>;Ekws475Rbe2_`SLL-!k4aG5+>jxuOwXt+#UZ&8AczOk zs)G~}a&ei6LKt_RZn;Y_I%K(9(u|DkL#8~E;Hm9Qk_^nhXU`iA5t4Va;*MGgu&n?h zU==_pezw)5y77+*M?rWJfoF@J@LX2jERYe{Yktq>ko=fQiMP-wLZiKAvB8H+~&5uuilqm z?a7;Xw9y2;9Qc>_96jl!HA8K>EhyyRrDu#L@)SXdTT?~iz6RNe1b{9L z-im|Ohfu}#r&8miwVCp0b|J~{QkG3}9vDwxU!aL~lY*$3JV|*)EG>{wc-G4FisKP` zBJUQ~KEM^Hr($RK!9s0DrWBbU!ok>bq^gJ$PO&MZYJ1Q|rC@$BRFcJy{;0W>Fr0R}PAty+2SK+CNr%ZTtAA}kB8~@}EMj((AfSzCb z_OQ2964<-IoD)XDMd>by?89lbMUN{5*@P?}l!7&yc5}jN!lv&wg`5T8knV|N#*PWV zXR!%j23g3N@5*`;>14r-*sYRYIY-JS$joJT z^HYatfC}V+Rv z^}WpGOWF3ik5Liab@&GFj%!+rq@0)70Mdr@-s2d_Qkl$v%LIzrvtYyoRr=sXt> zIS(JTKaBy+;OKoIpt`Sg_b)>(+!lDQ*yG-zu$eI^SH>KNEg$q!CHiLuYHv&ZqWv2s zh5rjm{yX#J`dcWeZ0F)=YhYty>-?XwiT^5SWo>~60YZREE)^@6F$YZA)a3(b(F00A z0*Pluo7jmLjO`f{Wl6zb4>W5&;q_kkf;y6rH7s*=K1p42A&3JM#ofh^E*kC3{N5a= zx4%9=$@~>ABH$4$hh3zhp2hp3#3wWmY&TGL1=RaStHXDY0G$Yr>hTLepFo5~n)ZAA zMQD+c=6;eOOoX=@fabOspg{CULaOfrooBiCslkC3fq0Jq{GhNzuRxhgHdLTtbVreD zd_q@G>SwFQ$lw{=fe?OMIYnY%q7*WdW?DQ{^p$E(7*CPq+GJp=J~=NMKP{Ar&0hGm zV?5c^(4Z(k&!Hll`O;;9eAs1pJaSlNS=N$5J1)^^j3KGZauHlnX`#gw4c|`32{Ndf z2Z%*wnqNc}W9bLH7oTNvG*ytUriMI4XlIyj>2J`+5mv<0nyCtvl@}+{i76Kp7Hc8$ zHV+u*6k!PIr53=o%#^(eEkg z!r2L7D(*6+$})^<_yqPriK7L%63Z}fI#czSt-fK+o?k2gErA9ks>?+?ECsT#@D!5blJ!pL7sjV6r+44UXPc znTE*xyEX(~&kmpq(au$h)ueT#)Xu_3R!xa;G}NM|B%I)MlslRm z#Lc(ihwzx?p^{y9X+$W~Jr)Q7ExXRg+`XAlb#>C#rAJm&QwOD-CdQ_2ESb{{(>xz< zY3ZeTmQ|=K%M2hZiJ0vAzd1a7QLy(xoP4NEIm1*jIqd8a!F zv!u#{>S7jS%dhyqCW6j1^K9u1&qhhxLh2*C>6B3oc&z3D#t+A!+I3W-qSBAKrRrq@ zZMp5I4_dG-UXl>AtM?BqEHcotBjPieMar2Lb-2duaD0sxemO5tV0g+M-GY0Dx{@T8 z3y9Gy85`N(c&B8rxrw)jX-`?TRHI&cW)d9>IHo9ciOAu_Wb@XZWF@} zt_x2s^hEX;)?nQ;wJG%npxq?x@_c?bos^&Ti+T1bXPfvfHQ;@KBl`I-v+w;g@W9UvsP>QoyC|R5BLz!p`MDI;vveNQIq9Biu`3 z=uBKe$kmn_nmurIgu&V;?*j19O1p!Fd3J-Hxa@+y{<+N%deL#e=?>$0yUy+R(cVXB z&khd^2CwsH-58`NKp4POI2Yd`m>2IK_|Zf1%Ej$ikdse7k9kAa~6wd)p**j%hvJB7fo}e)UFv zV+xp`G_akCn-XqrCzJl)&5K6WtaIpAES6YEHn&8Ui0k-=X3cEfHyvu-C$(OP{B_*PYawk5%lZM0&l38qq zNn!D9c_RrLWTtrwBBPM`ifn5LlBOura|WtK9waG?%@PBRktEX=C~FEgb|wY;4zJBE z&d{)RuCZb&`(UTC`Re?6W(p?BMI@>+s4SQ&6480)`B0Oh=0A@XY*kVpaTWKDZLy~% zBKmGMbf`Z3Qjr+xZT=ffI18lK+0f<`zk-+Vx|@mDSZsfnU^WtUnAFmpW~$qo17^8; z23ojkXDbR(uq1-R#Ne$MvdTbY=hXQNZPV6qlrmVHm&>m%OE0mmZWOO;YUbJOmswCK zX_6XzH_?+RD^09+hB5~#YazzTtVP~W{q~TfE-&5dlswpQe@wDPD062=S~1EP&a|9U zP&VRA&`onXyR{$`i1Lu(A#Cc~f;m=Ph3_Gmh1y@Ah<8q+_GCA*f>_I|YB4H*k$K=& z;E7kblt|3eTW8;QJoyy6hjF+zAGKe1+;gGD(~P_yU~u{+ep-)VDz%u#Y@}H`o%<){ zuF#4sOdehsiY*!v$Q*vPagGIleq&LY3L7rp_bg0_f+oMDV{*tiqfDEdi#a_0b>Nz=B4dorPR>EDU-y=))=EqjjO-kVQPAeqsjtwZ9L-|f= zQYYk=!H3%|7eucbedHTTSJ)GZw?7<;_J|lHuPI(`p2AMgq*Q)0$PJ?Upw4G1DkZM%FmwdRZ$XA}qSW4@ z6uPMHJCELgsy-7sw>y%qcGqrb)%!Z7FO+a>Mf?G2Qk+>Of{qaBjGIYmpi@)4I8TXH zOe(U3nFW&1NWZXh(idTtjjZ=2gVzNdmwZJ@@=&8}hBPw=q&$T+t>o0}-e`(f8E~=^ z^=eYfUEbrUNWqTTefo7PVPX2s^k;lT0=Xl@xSN9?uOwQx$2876a8_z0AZ0@kT&lk- z9q=V>ht;qx#v>N8r~w2*DV3Ranxzt;mMWmc|GhR`8e{|Mc#Wx+8gw^|Bu z@qH}8S^W6OR?5AqG-Wu?vo5PAybUpjRXqldr{S1q4 z*oMZo@FnOXZ6DXT;RkjSoq0*c)Y4G37vK`N0!vs%3*;5^5!XDBrI>_|k`@VEqVmeo z?jcuf#*Dqx2RAEMSyo3@bwlOSd2LphT;6BG%`*@03zK#FXe;(}{`O_!u|p-WO~m%0 z+R?6Cp30vw-&iKDcM{vqn02~50~pmtww^l=Igb#pJ?_x=91rhINY&(COWemmTTm~J z4xs~`7S%T@?&x|Z?uYD&!60VJr`iZ!9-11!WK_XySV2?C&h*?v+A=NF`ny^yGXZ9=J z+CG7Nfa{WZXd~}(hU);n4#(d@c`{VJ7n=Y_}QMV8P;#qcJ!))k!*L zHP{1q4bOZEM;;(J6T!n_hl}79o{g1+j+BL-O#>Sh0SGz}5!Jlt zBS`4_jYAJ;hkGnkHfH2m7GB;SZc!F)5l(*?CmbnWAVNGxm|%`DW{)ri2M%$~h~{x` z7))FM#=~(+FWPub^ac7CFK`g+;%oX2lTiMD2$RS;8k;zp82>kBAmxmuhVfZLY;|$_ zj8R!Fxe*K`;Hy9E%21uu!QwmQXv{St2m$1!aaXy**F#m zN}V5;IP^R_8sVgF-(l2`yX*`VcDIRPg+1y}H)X)^i6{t4Diub zQUJRxZ!g)e4SaMf0}4es;4V2#z+FukECO1p!n_lO&0V;ofr6Q%R994hF;mVC)r~Om ztNhns-1qoAWcj4%-{JQS6gwV2B@vTJD8DDsDb^8s^yKZ~TZ6^`so{H0R;69l@w3l0 zeOe}Y^rWJR5u~&Ze7yx()3kiE1q&WmR`?afBQokd3=D*QJH`yKdR<55@F>C z4Ck+PQm1!4G8=C)+WeT6$%5l%Cwg7yqz4P0`Jw_CpHC&dLjE-Ii?dd5Hj$)TQGA*< zm(9`EGl;z}q=et{i*nwMq)^d5@?kx~77L~IE2*Av_H3f6!<2%ewFvmtUo7@0!jxiL z4;YxSrYoIeFuB#piH&TY<;-6!dd-u>E*bRIZFyZUf&0*9)FQaLGsQV}_Jsy2ShAtK z0fMOxG-tIH&JvBtHEgW;C8l}=Z_Gp0aqkfe+J=9$(wI^FmhUM3UPqTLW*qTzor z_SR8xH2J?U?(XjH?(XjH?rtGKa2N>g1PcUrcOTq6cyM=jczO0Gdw1`9pR?yoPtVL> z(^b{qs;-Z05ICy35n-X+muyQ=c*iEiQqS1oCXly07Kt!+%PdUP{E7*3Mf>a;D;v z<-o4`9s55)l-pdbx;VpnT6kdS_@YsdTGd|>> zE=Uiu%Iv}cG^(jS>4Lq|k9(DDQgyz@>FU?I!QO=F8W*ayEQ;zB;r4k9Ogl9a4J8OX z&xu3zLAGOVx3@8t_P+Wi0SpjXSCkMwJ%579GxF!oeWi+DK0O<+`6)(Smvh=D)Qq@{ zcK3-3-8$W(hB?g@`-=Z8C=Q7Dpfk1WQv>F-g%KAGLYJH?d`7V$f4Q&gjQ#D&!63Kv z75x}cz)?ijSy!nKXc`_V(%=vo<;$S7lU;x=*}~FOw=+015Z8whj{%)Ei(x%`w*EPK zjyszfkh^ zxcuZ% zkbn-4#E6E)R8~Fe4F)a*J>3OY}kUtesYpXNcg$;un-%25yc=ZhLlP+3L!>ld=!-#stT*BSc<`MBdg zZzKP;&zOlmB-;IH9?0>x=7Iki!u^+O@Dqy>b+C4Jv-PlX{I5;MM(t(azZjQ_8D1F{ zE3C59m+)Qj)l$|6Bb z06>FEIhvNo^0Wu&!dV8<x(qlyf?bO-4&PSsUL$DbUF1fSXM#YPzke9c>@ z&m^h`*peTH@_`VD3&dAkRPYHo9W6OT%PJ5sieT5`s^VN4i~@x|F^~&{vTOyq8M9_| zOc6Aq1Hy*on1F91Vg*e!CQ?B*3Hz#yJY@(8i;iG!TqULpOEjBVzC;N&qpuNK5^8VN zhv+8G^Wi!oD+@KVxQK{!KGgy^6mqKV`)MKH>Z5lWE$2PSgC%5C7E(rr@FmV6?M-DJ3y8fkZDm`Til7#QH^ z(iS)Ys;dSN@F>&I+T=g35kR)Z6Dv~^C@n@=Mp4mE2Wu2wDb*M{w1st58j8+CYl^-i zk!5yb3#+_?3;WYFGjs~~a6k*ynj&j}7xjSBFUSej@KXz>4umvFzNBRO{wN2e^keJ= zIDwY4D+kaws%3c z3=F)(a-y;;5oNxBKK8dPk(`SRlJoXAS5BK+Tv%LVpPrjuWyp29A8!ZLJyUFCG|)J6 zZcU8ECT=Q|XJ$j>=yB<1=H?iJWG}hLHi&n1Qu->M|_IXxCUSkA8t@Kz2-@o$9Od_src-Q)nAR|)B zU~RZ1A~EC(d+y!FsfQ+U@&LcIWGKH z)(LA+0+KlJ(ukD`(oF}}yVO}8Zl3(ICV}{A3RG^v>mrc&G-hzAm&^svc-PglbS_T> zN{A>9J@u@U;uaaLT1LwwJ4TIeXpmePGFU!Ze|mzIls`O|PTLR1_S(N_8O6M)4I&d2 zuG0{jGsCflOD+L0d3wIxr0eYj(MpqNw7j`-Baohp8!CC1NE(nIdlHrF@wxI2II=fgmc$I@b4`*< zki#g3WWv-ZoU_{$zgVf}x3YLe{qY7G0LZtJzixF?QAU;OnIu^nEMZ}Ly{D7CO6!^8 zkU+lIXy;#tA1Ru#Z($dYG89n27;8%=JI zZnnkjy>Zu)-OCgU*SQ6+wyt2m|HG+X4!{8T{W*7LqyOE;^M592{@*9d|5MPM5-Tbv z{+FP+v~fxco5=^JofRX^Fj)-)q7YI!KAe=9@~e7c!y%(U96a)7UVn!qJQLhm56eyO z$JDEExA6wZU`y$AH4DkDVsf&@P{QTc2eKKu&Y2=BO9}|vL^!@hVwcJPqG$ehbW`d-LN{fdyi6TzEz~Ss+$`NcG0uP37D#%VTe|!+lA$nB zQ5pZUAva``D)4~Zd-=s$1akVJVP!dLDHn3K;3>Hih1Ax#j?o=|hEF6*xc$+nDUe=4 z{4vb9M3f7~=Aoye@49xZEsPC~4Zw5;#K5Om@J*S30;Xiv&JAaEQ;PfkP0g^kDJ*R% ztpYaKZ7Wy?eP?81Z%M9HepG(?#}-1WKDj$W}P*>5UD1ANY`)~#UAGAOSszTWxil%z= zp+E9o1`z++gYoWv?DqWZ6-TM@4^A>9A0;Nsg*d)`VNcSZQzDWX1D6KNG4?VK47mX5@jOGrRh* zN!=tu^R6h5M^N589iJWBz7a_GB=Nm1kG~wD{^$zi2VY2y>G|9_JLdXylTUWI)k3mV zCdbwHQo6G?vm?JVddT9!RfI9jIlKLos$WeF9d=%PMWzS*-{D^}9^p=kL*$n9^N_EUt7#^oLlwPl{XhD{N1xcfu$_XJ#iOwug=KS`Z4!|7F-8?lo+W~$fJzls>3Q9emf{K=9#)~OUUDf;m z1nbNUcjwdbog;TtV4#y+&oljg^9u(lH(&!Iel` z!jEi+sLYRb3Xl;^uwNRaWTVr}FmMLt^r0bPIQY$v${g#!!e9WO%**0*n=jko*~D_j zNT-3_V`fM`p%ySDDG+}J*@bbHf&hsao;fwf(6{g*j@Wk=@MVL8=t_ymakJO+6x$OB z*GYytaPKs_-QSMm;AeOAyp+Advg&wE1@oXasaS_HuP}9({_-63vg@6jM%@qq;_9Oz zei2w1ARj8@F*Dj`ZqsyDq>0Ddn7Hgt%#lEIWV;HTtlh@3)|w-3YN6geL=IgfxyH68 z2krZ|EP&_>OZ!~Vf7B;|40FMmabSZf2Bw-=YK%GvIeR)o@Jn}mKa{-Yr!2w_B_5@A zb{?`emTV$g4nEViWlu^+O`4QLHG%_d9b-Jhbk=n*bNh7l^E9$d-@`y%t9fWF3K4X- zXe$$9&=AxnE10(FK})>l;Qw_8MwG zF^P)Wj4>*|ES-{mAXtnfm@a7`CwD6(^E63o@)SbaY`=*O&BQ#(MDkQZnt>L|=qa#05Vhv?_)=_j) zENg}GpOb40Ql{R@XS&o@AHXwpDyGPRe$<96uXdRl_1-(1Z6*1bA8OF9v)^}K$fdj! zRcPPx6emU_+_&}jJSvDa2XgW`E1$8c4Um1=!AwJUrbAf4t7StONe4 z(qHHM$tORXMfPu3CI4B&{r_;T{wEbU`!gTvv*83+2c=eX@BA0xgy!L;P*F<{#Z_q~ zP%$=|U2U}z4P~3Qt&c)rgdRctlX)T~RUzbw>-gFE-S@|LJ36~Nz?OisAlKJ$$*Cf-$IoGkh<~8KdlM|X*I#+V1V8>?4WR_XwHTm^e%(zfCY%+|l1ib|q zGh;eiBpka1B33+lZ3HbtWB71VWjfd2u^D7tyA$zb|Wy$8&HJZI;oTw8&J%&Exr z-^Ei$<_;S<6QnlVB(4cE26N&-rL=HUCllS=CYaW@%|f2Hb~yq%>QlENJ+B686^@kN zX54ndH(c=^WuEes3hc7s&=2kLZ;-HR4s($qp}FX8-F>nmBR-6eM*98Ot(T5UaST9YY(NWk%-A;_|d01NP9oEk%Z{v`h#J>ux7cMkX z*DSPJ?-JD)kYz*4fe9oZW(~v1yRbl5XyNu@ki(iafHx_9(MvE#?q-=}M>x1?3`rQ$ z*^fczirA$nVv*5GsJqrh_WQ@}v!KqPn)x{bvOjen|L?h)`9HdSq-;H$EZyDzYa@&^ z=C3qpjL?IHm6DcA9IqYmj$n%uAbS7hDY7D&;;jplKp+4Ozh4&toS6OQUBDRRUWbk* z3{upveV0-S=%7ywTkhTxr{%#7V_F&DvX}`Voi}w@T8nlJb97;P9G)z=?}_o2&5o(~ zu+KEu>U|7XPBU^Sg9!!G)lhP#aR>TcgDw0cF~m4dcqaVw0)BiR|GdP1uMqzkW9GkP zE&nQ%OVRvqQ43Qx7a=?%Rw+#|oWh}{9CL&sZBbrWf-D##6g=IDhg%kcJ=+{7Z}0D) zK;lcyZ#J|Hkj8JU?-1B86qOu~y}PE9mOneYzir$+bWeRixZrLS$M=_nvm)+%V`0tP za)WbKuuGRC4L`!*7%y;vG%h(=@b`;c_P1ay-qM2uPuCvvlzft7-Q{4g8D_s7{~APn zfV(YKG#)<;!0dGyzXwxwnEx%|5m)^rA-kH__r?|{;JHCbWwB7suCQXdo8gzuuW8C> zT8RbaSwCp$IqD%vQgARo0m-~MW0gnRdJ80x|89S*Kq8Do7;#Xpssn#ws%XK!Udw(P zo^X)p^V76Le_4ofwSYz8%c&K9C|1PJ)B&Gj_*1@{D?Rzi4J%1)Qd`{HikJC99@gcHQ8VP3u+DbvJSPiRn zil~j2tSGXs(%0Xv@Too@dVP+BTyT8fX>42acbHN+D-K%#&NxuW1JcsCl!Omgm9d%v z(^n`PtO_3bgM^W%tQ)Z3rj{*QRzz#`S~Z^@{IOCBS;(N|wreyQ4jfJf^C8RA^^LwI zcQ+c)C2PrrNro>sYae`Us+F$!OCu98R?4xyObew~Rp60@RK=HVOJ*l_;FmNc@EW}J z4GQTA6&$-{%!vkhs6=q<1F|mE(njg-6!dKOMJX#vnqu36yic7GS<3lW;<{53ja16qiFS$c5l&oCID#+rIgdNy@ z^au`HOX@a}#xPsBu@@#Ru`l`N`Z7~gfTZrk9Pha%M(e71*R#rK!m@P6YmJnHi z9uA)DjJZyrKy9)|9tzO zM1z zOzc$ti)UFG{oDK1Gt?#q0M(29l$E0coyxa~$+E>JZb$zFjmb((DMCK8=(mLcroY>y zwuF$LQvN_R-_TBa-dFZCjvKmZ@>BMudmnPsP$LVvoj55>AnjIZCcf@>e%G}Z?O+&a zR6Ww6>3tbB+0huUf15h{?!R}OZGg(f2}|M_JLXC?`EHWc7l|t zyN8Uag{h;do5la#8Jbhh=+YSPgGLuCQKX~;7$I|FW61oV%%mngu%x!p_~H>EI}~9J zi1@zd&JBNJexJnWepfG->r}hzDMXXmlH(PbCr)<%2qW^bUog@yRnt%D(&d*D5tl*Y zzu7#6?b8K+}r2_l5W29q;9)pUJc$}RxeU-5d1BARjE%cR4Yp+Sf6d}o5afON&xrci*q5)y(jBmT1;u#F~!V1}oSJ6ZJu z&CwHkR8r3xL7cvHFwn3}(~iZ#;Q$JJ+_r`5{zs zy z+AIu7OUtM+oi-wlOH$5>(AB2UI9{Zo*&N+U%wYg6vXS{w4k?-Z>2aHTPXUORQBK=p zRgVyA4P*2acPG^VF=V)TvaDJvop#8p6j{IkX z=lPh+T;|PcrzJ1ln5-W0&}n?KXa+|tu^a+Cb-QFk_`|Yw`}btRnYRLe(xaN|oo4#c zVdJc|H@{H6<@21ff2W`8-kX%RCKJkMz8-;lZAN*A3L1MLh2Jn8`;^5(_SOQHp175~i%Af4*HyEx3_pr~KsEHH^+$c#B%4Hxf#JY{HK@DQ7Vj`-=gSpv4oVQsQpm zH~&!eTkTvO%`B=B>8#-2w+d|t1KcC=r)=}jIIG-)Djkz5uXbL9;oId115wL&IA*5a z%T6*3!C1dz!B0u}mPkG7k#6hA53OAb(t}C8qH*|?5V8Z6>IRh1#ET>IC|Etvnup(! z_}gW}lhfD=I+95XN8+y$#1RC~Wqm*XAs7!ue?wLMbfNh2w_NnU6*vBC`Ih?B?$}zo z{a@94Ko8ze-7;19;Lq+KuF$3iZc1BP9h&K)e1(J*Kpl<>*DGy0)G-}cH9iG8tJ0VHOzL(D+{d-#8 zYVci)%)kIv&87e*K7+{sC6>W=B1~rG0V#u`?KlQ+NTy~HJ}%velr&j(_B&Qv)h%)O z=h_qiIF>_SE@X8-<{F}Fv*ADuq?8Htr{qZc${7M zk@)7^Ym)uSBI=`+{M=v~G&;{h*0+r&ZrrRTk1@nm9KVc>ENa$AtFhTjUj!S~NeNIT zhqf;HK;@gx2Y8VvFtAH9!f7%>6zad;r+-oKBp8TCC2nRi%DR*-gH+>hs)PI42da-I zhsdt)AXAA}JB6kt|3P2usQ>aI^mFzFcp#`A?8_*3!7lzV7?p!pe0z?+^)a@Io-x}l z7;t6ntG7tosefbq_FNgTUUFMC^6|I|Vo-PsbtA0YaXYPAxR~^@_x`Y-O4C{OTAdZ( zQzv^=Ir=ercd*ha=dAj!opu)RJS105{!#u+I5d|0Xa2PsYp za;S7*-X~@qXeg_Jn>!4G1YSVZTg!}a83by?-Sc^l2EE5MX$Nh>Gl>BWhPuS*i9bju zonjTwF%K6QLioBJF5oJj(?Y7e7EkRojLy9qiGSUX_%A=_Bufw2YZw4PV6?P(PUFVm zzUHe2V30bCYSUmd*)kNjkL9G=l-pwiWlYGH>0Izq&J6GPT1neCZ+`{PrPN+K!tP1 z1$bqoSlp8#CB;D+EFv|~@HXm*!b4H0=hJ(IIl2ik4RF-TGbQ@|8pu}CqFLOSzb3}X^L!Ac>W(?wy zs*P{_k;SXK)1D??Mhm$;DD1X+Cf6@>{G(!TXwP_8B~gQ)djCK?ueK926MhdI9L%_3 zn_PA{=69OOQ0itm$fd!Z5FR>-@{|}BWuyqr+)cxO@=7;rK*)Pt(;1+2cUgL>f}2^S0y$1F59%nx-Wq|>i$7js+bYHoCwcZ>70eZ4zP zdB5!0Q%mQB^@Ol1)x6s~7m{el@L6NcQLtn&Hcnr$CWLU_T3!#l;HkeF_x1Ccr%{wb zzD8;yTe}gAo0hM&Qsls4G$cT(+NH+4nL2`d>6a`ob$y%O*39{7v3q)Nl3to7U}}fT zd>jsR=XnNbRXk>CWv=S$>6^pI!ygzQ86Ghre(ejIZQG}R>soq}d45nBmN{b-Vuqe# zAD{Vln-y@$@c8FdQX0XDb^n+a&rR(Ywpr=b7pYgFYlb~UKs!A_z9eF=O}yB1v`Y&) z6&O+2-6^Qr!v$$m^G{8GUgjTD>*rNc*wT8Ig~rHrGJ1t-o3=9d>P3%YBONr@*K+cL zuzNRCux?Oef}P1by6*IT!S0opsD2J%-8~;FW=G9K2;|UHu@Zb_TCcE5>Q{R7Mt~E| zHIsoD8%@_F%<7>D81>1L4yvx@n9e=;s6{_B8Q95!n6?Q{%!{`bwK{N}^OA4Y`75_8wK@=;573)+RYe!z zjDgx(kLZ3jVZwa?y7&3-UpBL~6r?o=+AF-d|Kx9b(f^5h(5;0S(!cWe12G*z_UP29 zBh*@pY_E7EId9qyw+z|wG4$sFBFPgUz1ePg59p^*Z=+HQZ=;f21{>XsN#`F zC@2>;6N+E%L~>7d08mm-^|M=$W=NU7#2B-HzP4voS0ozFLkdz>3Nlz#lsG^5B2@?m z^FWnFRp~sU0b&GvdtG(yhf9@mrcR3;zE%5)HF-4e&VH2+3q|sQzPu`@k7lS@TWL*E zgdBr=p1cGg@nS=W94)%B@x@$p!|Yh?upTNOo?q*U+_N%D%af(~tE7gBu?Lp3^d)*D zo8($5uR|gZ>v(mgeuJOsdgAi=o~L^%vz}VBpO&FxXLxBblrx4T&Eo0es$Jw{K02v7cth|TbvH=I_FG@Erz7M&eBRcp3v|59r|~!$7Zc=( z2#F5+VUq9F`R<5OgJE6e5hq)9?yV%U(w5I;{@+tanrYML6nE%8*60AU0S2hJo+{TC zl*fA$7&%kj)97}qo|tR?&ch4mh|@`t6-U~;rztdO#F$NU80@Eb_003ARJM)4IV?JH zuy>t_9y8L>=B|j7FpLbjQF3$%9Ag>U2ZLyO={KJrp1*x3uL40!OZ*j+yRb_kF6)N< zMo_YfYa>rM#K|-Y9^#^i;SR5+0WvJx&PQWUS-I`M$f^vHo;E{C122)%dyy{sE?@&d zK+s-6-FWU$C$~RsCnERE3v3j%N2qxS3l(Q80)oh$X*jevTh97|O+x<1!EQh)* zUt+qxCXR&lJ3_j&bUa@9{X;D68Na@S1}o3~|8X^mXM{8EcUt~YKzV8&3b zR!hq@M^v+#Oc-y;zMPyYM^;o$pK`8#;oe<3+b|QoUhMTiuMV#(QB9umyH8~aq_qY% zyzh<$i>uFj2@ZV=Djkd)sL+DT6r^uLx(0_>gD7yRe%VKe63m|me;(f0U@ho?J?N5@ zfo@9Shqw_aMlapl?DAbjNaam2BA{qFkY=q%hD?Ge)LyknH`2mJ9G&zB#Z~@~cvuF5 zJ_^LIgjaHf+0fZ;Un}Q6)4k|qH8R3v>j{cNCj@#*03x(P2*-~@HgB9__U~7)Jqi8r zgM`7!oztmK?9S&UYP+Kt`rjuy@WWG<)KXKHQ!t$XBO>_f!(PsyJMRnyKOCoE za*JD{CD}()9y$J>`I=MkbIr3c`Uu!C?8PW)s_A4|HKooDg3+?E381W)j6hiEq=%Ft zsJxT{j$U-0bOQ1uzc>>-Qgqp;c$WlRwN{7u^}M3FA5S1|(?3YYiUr}dkn_k{TD}AZ z3^VhSh8)18PC*Vy7dmjPDz= z)Jqh}U$CGm(z2##>Jm`>`i-_+wZte?*Y2QPtN-mB4ILT6rl%hqw7K5f0NDmwo}h@R z=IC9BG-^>S_J!MrR57JYk(E1v8PkWnl#)x*as$cSy1rJ8fgeysB*Dym)@URX?_hk~5C zrQSm+yd&-I?|He#msRE@?qwKqZ}>-;Zl$;sWGMPg3dxHv zc{#JWfW*zcOKF>55{JbH9l>a()PgT5$?v~ak5?7qp0u`okSS{klLx)jUj5UFUUo1r zk<=Sv)wBF#b3WiP5{yM5jq*V*slpP!uweQto9>bmKm-&{UvXNgz~BbAriUrb*WlI9 zgo)3DAUX6A7{p-ovc?Go0(Q=Lg1h*cb1%jdZjZRX3$4Rlg2WDz^FYOI>G%=BUr90m zwU6*G90}rxcOV49EY_O7@RUlO1wRxMgBW?dqp= z<6}yZHqSSR9os#6B>#$KL^?G9c@36D&)jR(iu&!^%^@MPR@12u1YjaZhiS24H;y9e z1*y6eN7PKr>(~8E-`dplv5w(XYVT?v5cIk|Zk{8AS1ho+c~Bnlo9Ob*%GXUvNzh zKu5c~#k#z znF=CN@5aaW*%64+Xfr|M8;Q^;=O`uaq2rOBg%7zXET;_ch z1|nPZjP<}>xk*z_3(}s@ z0+5r$fkZ6>o8rfH@V+wjtXK?y56<Hfkz^Vy~A)?S3np(*HZFZ3SRCruFCa;q6uN8|2I*Kq0fSIt%%U~sL(k=f_B$vGIVSq!Cdgj>bN>jL zD_t0muI%0fcyc!i^RHCoHTfL|t-X2{pt>If6A!|Za0qH6CBW38(a2Vvw+^4fdW0ua zH&#Ekhenn3BS;J5b}YHi;L=v6c-6Vjx+I+sZeTvu)L@u9X8&ySu-u9M6DsSctH4Us zqM}p;)bijK$A@wa50&yDD)1P-_U#S4exSv_vOgNU3o0yv5tHS-ZpG7B)#{o7cx&NP z`NzNR#PuH9m5FI)j&`oc@38DG&+`Gy)T0QC`dEtm^G7vH=JKNX5zIfV9ILvT(y`NS zwt&b$~u+5}Z3IGnLnVRECY#Rnm85=fuFmqFfpS z!c3lx-v%x)Zwo;m*#`12di@l? zNC&-`Shz7jF=d6#^()HWeq|!<2n9RJG1nmPlE;~_nwrTW+7iF9^-B+Scd7Ef+p}_I z7RmVmIoYS;$6Qk6#4@5BoW&|w<+JP2JXFxj(>zqs>)k9pV-mcYZ>Ms8Utq&Bb2gHj zCue7KN@izMlaZl;SfpY;V}i#S!qJkBR}RHqid!Ly$Z3l=o=0UEB408xZ9>E;&XKOH zSOnELZ(&;#kEaOE&B=v`rJ7VJ3eG9csUsI-7&2DsYEu)PL4a75OQjt`WfyKct)Q3# z#W;^Zt;r_E(i$i$l$4+##Y$_!mN9}uW&Q($jn-`2LT%iFAPJ3X=SMQzkDh{PS>7Z# zD)b);W@;n5VpQ0yrDkdq7Hmnh3Po%`QqTR->O9Nsr|C}rP@M`XExpN^KE&7f>NNWn zJ3T}=J)}E5q_nMTpLliaHNWVspPzWN8<($s>vVdEXl=lvJNP0JnVs0zq@7jwlAnSi5?K=4 zT=MvehP<6ZBO=vMbMW+cO>ffPheH9DiScf0q&av-g=R=5jb=!C{bx3*m@jCjAW;ZeKlc2gSlx;6BPU#W-2mZ`%3NIVuWtqg;UP8Sn zglyC-a(G9*74@#}w&p<(VEcU_vnG{XXUAsd1)1$rlDV~Qb`Ky6plNn11x91wh@SbH zJpIF+jQdO?LF1Fp8$|Vq!N`L{V1U5Dz<~Ta2==#x#eZ(#NmzL(eS%@1^i-dJuu}iq zbw^$QuNQ=QOWQJ-IB9- zQESnq#10SGj95Z5E9LU_cuUzZPGVQJpP;J{Jv7}J#%cj&1D(B9$E|Bb_XLY-<$~3s z8JUC9=eV(kX7S4SjaqvJ;sL8?a&NaaBbUeP!2_w2t-P}U1ZTEoNqZUSN#ATzRc?n) z*1EQ~)osHhFN^L+*SNgY(w|rERT*pN<%(0Br~b6Qu{c#$kpp$%AZ8Fs?V;R@?I zc0-~sQyvrKz=7pf!gN0#hINmu8%_Ba$hJE;!IaJSa1dx2>QJL)jI#u3F$md;p!g9V z3B8I#oKtqNMHqjwC@BfIk%vNBp|I7tM>4Q?CkI5eb9k}EcnL8RrY$5{OSEuAhi890 z=n>BkOz0!<-L=Wzn5j(fNlZIco3XzBWZX`!o8x+MC!e3^tj1@GP>l7!ryiyGZ`8+NR za@*#jLX?o-j&+LQw!i{f^$rycD~zE45+ri&Ki;G~=7b3>M&3KZmtxM3;O}5}yws$c zID_|QKOeG^zHB^v6`pK=x~nF(2Z5?N73H67y=;RtfyyE>J-DFUuo@wAq#~G`Sexi5Xd;|G z9R<1H20OgDINME>n8pn`FnQQuAsO?-)bjX>dT`G(wR4q{-J61AE%Gdst1B5+Qh4oa zhtUOfC-nxtmaCz>4Cd(>GF8ywD5TOqm3U5!GOf-ye6=hz(2J?kS=j5fX*5gGN*hf{ zIb54t2(!y;;rrE7FBfv}U1+whvI%FsebuF45Tv##ZZ?`|LWAVyM>DrI9`)w(rP8Ka zn)=u+w5h48f~1b|Y<>B=qvlz%BPKe%R+ma09XFmU!3NSuS9COUdCyX;FQc_)C2XqF zFoybGve&L_8R^%uMP05xtGj8-R!+%i_MTpX_QvH{CB?Z5pZ=!{7QDpf(4pwxZVNHx zczq3nd^z+TZj-E=I|cbpCQckBZBjTkl!A&Z+$T))3a)Y=?WZhKR9OWiCK zDPrR+km;!Wj9}4gkb5d=^&XhiG93Q&nUQUopvPIdkJ%y|S=F3zzpkp=G&;|G8^R0y z8nPdzKoMG@uCvpws_UnB$t1U~yIN+Ewk)!xAeMTui?y8^zKcTBVSPX)J61Nk`)=#* zB#M+eXrPwSxt*w&70Wu@6gWpkB!?~&Z(vqNa^;qx4X?3s5NVwX0|!K! z9fA+>c0jv?(mNZ%n%=550YwT-d&Ht}u9o%);PD!LFL8Uvz@@8-oOn~JKi=man{3t6 z?1~?0am1l51C2pV`6z@jvJZz;t88F~P#|}YdDiJ?4J)>)y1 z)}UKV$u`P9GZwuvC~J_wFm%Y-j}v|g2R|dr6kHu)lg<}ho%vktHna+akxG|@X2iqU z8~IJ0v;*=~9T$A4FKlVoO+zTgZx~83#yB z@j#p8o4G5r(;d0m5;~O$`m-PvMjhS4(q;1{iH#>r%P6Ur_wjb8fnfvonZS%s^d|o3 zefg#-?L>3!_0(HNxEg4516sumM}a7A=2hoexXXIy4dt8$b~l`W!wN5Ye%298!cJ-}Z*VkvZ%Cv9{+bb7-TE-q8`Ki*!W8{TAGoA^9(dPJ9>O!# zClZDi6kf;tk^FZcthrxM+iwl~4WFI1ojNm@Dj!gMZ;i~Vy8tcH$Y>$YM%zZ;em)WE zU5rJNq0Ny&_mOVv{-_xFFS4#e#Q^q~Pry+AUwr=leZBFw(VhRS?SJt-)NP$C|F_2f zFY!iO*F{|u=iSLIDKk`F)WHs1YoO8bJFA0SdDsdEicC^Q0f`1<^O2*Et($t1zRgJ$ z4bx^Y+;Mb!{$vX&-F#(NyTD5>au?rDzVl?sMk}mjnTZWQ@6%MkfPOuR(lO!;T;(0Ao<>_V%tH5u!_}g&qM%3BTR$t{3t#`X0PLCs;)5A6r0^QPC zNH{4m7CAjnpU@$WtMhf$D>=IE0*%Dp8h$`2j26prSdgF)1PfJo2Qp;384Vqdwo7qv zVrZddr-jYanNO($#>BghL~w&9aQpn1ZWG7cO4S~EKg=x?)63o0PzqLZmW}x=44|OADViG zwtK!^!(=ME#&Xv$VJgFH*^no|JGMQ*;5ci8d!Sk55QArVTrO#-L9cHsH<7h{NNILI z>4;JTP1Y!rkre*}Z;@XQDl{Nc3~hrPjUbp*-yo^x`E^g0Ca3RPM(JMhs1)zKGoEi4 zJA)vfsg>i0Bv~ya(72l=3@r|tBZa?T4FBd>IM~>iTPb<)*>g-ahW9r(_+rG$oH<(o%i0sool)h zpKH4k0^x{Mu1JUyYpyCt?$jg1IKM1)e~vh5HKY8SAs2Nfb40^R-p!qD29r3t zfIVdVxO|Gv2FP~Z#7m~8@Nu0@N!7JRU~9Spm?|cDp_R2T`H`)3L6^c|RR;ts)0p-= z&|eiGP%QHDDD>vJ{ebi@t0<>gvs9c1gl1y>iFH^jpFC@=N;HkZ@)#S|!Yr3+t!`0f zrj%xT`3_9b*Y~RBT~wiK5_rjBDZ1PGw55>@qDLPYH!*gTR<>ioB^*DMLGq$TKhg=k z>0S2G8sFK!=HsDxttk1vH{q3u2+T0N53YU1IwAoPqVg!C(a#N z>ozo0{$)E~k?7YGP}QAw(|1wR&ZeIB7r&~=eZ2>^XWn(Rm{BM3+lbMx6}fu|>hy}H zlp8_vn?05V1UCJ9EnsL>yCLI2^g_$x)JRjB^IL+-*f#cHuaHh1-Y{Z!T)JWgeTI9N!3S_# znwy}MMQncr9q6pOdT)d;S`n0=KMq|J#L7R4L3)V`*uLTXO6hCKxLD@et-;FYs%o4+ zJcwP;G0#8G5?>l=^pv0~xogQ`Tbw*YFL5sUB?Q7<2?5r-FSUG;6I8v9e#vv9Rtc&s z!W$$xw9jjW7v+MTy6uGDgN1KlqU0E8$F*b!Zd1$#Q1pyXbUce+QNgd*X)VEOty zrH%W)k6zau*RczPz|)`9XDeRYUpCE@HJK|K)1JABP!Yyw?%JY)_=gRtUHhbMNM0j4 z+_WRj=lfU4hE|atehCXv^j~!0;cx0S{QpRM#~|Cfc1d)XZS1mb+qP}ncI~ol+qP}* zvTfVydcSkx^zGZ--#rm`Ma=nQ{#a|pjAtNoQOI%ljc8N z^wd%4`t^1o2^?znDqd;k3Zey&7RT!svA)TIn3fM{b9{zmhB%JWV?YVl()KZK)_bYi z>M+)w$erY>iY}c*URU@;sdOv2e)^KC)^}@PJjn0y2%qqcK72ywVHar65w6qOi_1sL z(4>2GU7~8osUwV2bDQ?a;o9ZL`uYv9)qi~89pHL{t@tL|8Ip6u<8wHE{UYbEM|f)B zg{K|8@A5H%-ZwxMOe3-~bq~{;mIx;Nke5;Cvdb!>Ar~HcT*ig3EH0bkL{3nMCG^se zg)L+7o}Ic(PuM*mlYC|(@fvs1f+vElSuxa^nq%F3dHWx!Uksf=IO#uqw8H;3y5--> z(f{Wf_+M+ElDpl1X4_^dYRY2#1GrI>Cm_R<2^Mv%p;qb@_K^n7kdcr8A>=UTOY}SX z)4NiQ=}&vgQx}S*F>~Gv(zDggfXd7X8phZikF>h4C$nE)&(Gn05hv!y)*=izcE;8b z?HfZwItUyPs)fci;1RG8ia~x#3|oS}md<*$Y;zg8DLQUskI%F%Eh|seQH|h~qCUT^ zmmfQL+MTr~uYEOG`f@E#B>HGwD`iwsT(WSyH?=IH4m`cPQv}hrvM+!^bGChGffNEA z2TaFSqBrZ{YG`j--&c#1*6X&}kJ}|yWZgpj1GUSjf1tJwJ1?9{`H|Vih21hdJQCJ_ zKy5uaSCk*9tsVS8jU0WCJ^u6t>WpiR&Yj^Y_ye^a`w_~_j)-3EC|WGws>V0lt`XDJ zCeYi{eT=}D%Fun~f03yn-!~NIf+y*pSK~p>ttj05vP7!;6X;Kb2pzTxiYAbLx*}vq zoRVWvJYYaV4(6Kf&(F6SPLyc za!zhuXFymx1HOUx5=Is5Ni@(+D|l4Z(B`tgiW2p0>LVYv*h`$eif+`bbX;xkDobd!3JDxSrGQ1JpYCoTc2L+B7xYCA}@ z9U9V|fPyt^mL*0wsHv)#;@ctlLR9Z0c}~Qr|1Hwy z|L?1B|9AP;|Lg+NwnX|#Q*T%`NpNnm{0yhIuwG8@ZcQX0OA;`{052wIsw4AGw<=yG z?_e}`QS9R-dMWk~74!YWE794Z;{6v4;$pJvxc+&AedGS}J;m`CrdfMyG^R6Kt9r?W z3IHao&2PQgzW9I+==HvxrpW@gm>keGDL|j`0yW?`8O5r4yhHa+^n>7v3$+X;Gu&hE zaIQF8H<~7c+UR!ZCR2HWq{$X^im69IP*2eqkO41QirJiELj7Q`L^ zc_%Or3xe4=5Vf-#s%trZh54GkelCt((@Zp1<-`-I^0DkuLv9zlnZEjvcePu&kaK+$ zzYs7rLp3Um{=f?HmE{0)WYUKJi;K2`R*B4UR9q7 zE8&JzUxC-Re4*amAu526C0=k)B?1g#VKlxmgrQVJ^EB={2e>v-vmiehI>JH1S*mBf zL!u?W*+K3sd4I?mFmM*(cBzFQ0XNV8(mwS6-q8Pd2}HyHD}g8v|AqQ9pP`afnMro3 zf>@}F2hjfzh;o{Ufa3h|!y!ktHu@PqGumlD&-mORMpW_47ukL$2#nc2kZD5NWZJ~@ z)I}yPZ;uz493MV3LIwg?pCZHrVzw|I;eas9Ph>s2BbNbXAlvc`u@zKk6K9f1m4gyz znKCD-Gr&;rnUv9$|j6zjV+0PQx78nfGUWE>0f4Ml=>W3XD&wmIM)%;sD=VM7T!_7dZX z$X$4g49Egw6r;;Da)7#b(IrRwBCYZ7KuH#>By{bg6D(s$VvWg#)@xj}v${&n_6|xs zXP^j=X35nnz7q7nb&qX>tI<4(FKE}m@p5`;p473;77-J7{I`xl(z#~Q=<=>5_FGNg zkOTI}NZ{>SV{~^iKo`_M@p1i7=;l^ZLx=_pd!e&3)2;+~xfspDMkieZ&dY+J}wV~uE5a@r_8FEc8&7W@~LOIo7mSdjM-%xDenH4!)VRBGL{#tJ=Q z2kpoHbmnT+@#!b-h~1Ot<674iFm&IPBb^?(R|X3XFJSjqJ(@X3cas}$aNpwbDwHG*sCEs7<= zzYnq6%~=6}Syh;Ge_aIl&MTzU0H?@1tYD^-hpQ}>uxK5OHOu2mWJ$R9z0Bnui>){| zx_%mHO{PvO7D`z=I!%<#opbAi(Rq^9Vyc6KFFqm{=UIvgq&R_lvNbXXi6ENF**EZN zpRbZAq&-0%2p!!mMS?=!C@lvUsWOIM)3qa_5-%GlB%+ftsgE~%Nf19VAI^G*VUcf= zFX}O-*hK;oPfY1Zq(%<*jJELA(9S$|T8V~VXYOsGtSr!sr0s(4a7eo?+9>`uY+=f( zm{hRvH=d0Tb@Dk~OjEFBkZU;Bb-$$`zR^7%R25dqwd_0QJ@lgASDNRdMEkwp!i1>< zncn6OvI99<@Yw1B9K$^9A%vB{cwx?nd5!eC-f{!cU&Ot1`{C~R_vUeGm{1q|D75dt zesaZAhqf&An~jpPK$VEHnQsKOjL79ghQdwS;3Z>n>h7WkW1zW0j+63e(cI+G9}uUZ zoUGY$5os}B=za2)y7Rf*mG_u|QtVcHW$n|{n`SSJ_9_LL4AX{`1^AcEI}kBl&haK9 zG^skP%6l)`e%uve$DEFgY=hM{Tm0&WCB;nZMdxFR!8{e)gmhU(lv=-|!%eU|PDBK? z=^Trnl#*8Sn@HB&d_HUI_;+@r zQt+QoHZ3`~HJh@^;ty9|ivnOeSd`dJmFE*y9Z^ss{F)Ul^DKzPwY;we^l8O zQA9xJS2yI|4&tO}vL=mXiyZ~a;&!z>Zbs8>$9|s}r>(Td+k6_2P>?Z=H=MOe-wUs7 zt!*d2O~QtAH;eG`e#-@&WY;ZRu3qxwZKZ2^+$XJZ0C2i<>U|EZZuJF5ygWVvCghxg zEUf}=(3D=Vvc7AlbH;2pPz>ck2mv&SmWyV$Yv z^k#M0_baMaFh680)`7W8oc2`|xZ_;2huLcRyY*%2R?Y7T#p!<|Y-@q^n=&F6=yLY_ zriGfoZn3DEB^3w;Ai!$%u*1K&nI@-$@ojLOMpbtl3DUe$%sWU@jR`nnr3$?ft zb&x~DxyN(-`AlwD9-#m1QZ1^5M&Q<^ZOjYd9S2L5T2%)>m#nrdYh}LFfIlAfi9I#= z9)9+beOZXOIgK-Xh+A}iqIbLpAe&UiXNy`B0P3Z!8P21KEzMr`F6PSHGwLPG#n}yL9ran1Xp@@{$9x{M3CMJHvlm`R zQ)qK%iST8Z8TFb#;$S628cmQl`XwJ8vYqw%{4NwoF~OHy?zA%FrPC)Pg06-wxe*O;=@%|GH3IL@ znWpNMi{A@iHmQKl0e8<}qi5RK6NT*)^VT6T^bUi<3%lZ(bLKEDU6gJ;@jFUJm2Sd2 z=+=vhU($dl+O84ut8GA+`cIc5I)15-=>Elkz^ z{{;@DovobAh0K4lS{#22ZuG4LZLRIBjNPR5ogB>F{?kuUMbi<<7|rKtU7A&0K>`W@ zkeZaeP&{1>N*NH@0-)?E7g-}$SbeTYn`G4~9+_V>G0kIFpNkPk#Hg56#}0^50KG5& zcQj*kiw@_$Tb{3gclRc7nF8A1IQ;EX@1EzI&Y5Q$-JCW1l;+sa}^k7_?g=C*?=C{$&KJ+2S8egUUnWPUidTW z^_Y>v4{SnW+$XfvcO6F$PCBF9A+euJnbw(QEC2oLIL>8V>{!g0e8p=&KAzk{S-Psv z>Cz_1Pvp|lnwH&I-A{(S@VFAa$ePBhj{=uY>X6K&I-1_b-(WV;<%>qgts4dsBGU5hDeZcKnaXG>J}9Wp^U<93U^G5q}cJPcupJ>m5$0R_ZE5xkPaBnhR^U|@6V z`6=sBs>nNmsd#1ZnMsir83oOA#;7W+-c*TNJRrmn&gK$dJLK*N?VN*L^0#kkM7>ae ziB0_P^R%bzHZH>hjY@R|YOy%k3gWt>R}1XXBS_dNv)5TGoxV|ThtC-01S)2%b1C<~ zAsU1b%SZ?M=w-mhJU{5mv}ViTn|403XOb}HVvhbt18u- zMNov`q&SR&naonG6nf_EA&uv0ujknRC|z5@8L|iWtA!iuQ}GM+O?wI$Y~o9{$Gg;M z=TmX&?8Y&|F_g4$>2!W|Z|f+X}S z^cVgng60%?ER|#!IVZJ{QelNZze>Ju_Qh`WH&%WZJ~xWyndkBQ&9(%!DN|;}q3*H4 z)B@MeJ>u>{2_zT1^uy{`$UdXoUYI5P*|d=EM2j46UwyJ|?wzkl2BL(LqUL+|%YBR6KJ`9E zWBF2gxXOp5Syc6zRZq>=z498W+So0*2yoty>^4vc4N8dGVn~1r!PyKkqE=+VFu;sY zN+=d}qE20CmP7@QP$gfIDPNaqH&-nPzYa92u_Y&s34e5(;z&gjw<0YkoMz$O)LQL2 zho0Bq4t%GY2$l+|C+fV;Z#FAMYEO#mhVa@vQxtLAut>`6$#G#@Xeac{#zf9hvn@W= znKk7v9`Tna={-l#01npVMt0LN{k^? zD`d?&Wuw%0*b5ZSTdHIHx``>y=@*w9m&m$_NfC;)sNA$9mDoNGR$G2;byvh}_Pabc zc8Vsh1ZLixPTAcX@NrwC)4e!;&VJBZ}@iznaYSYFu z9(wr2a=ylfKY`JF4+xA>cQusH`g)Y6?v8%YFC6~ccuFuW zBH=>Q&bUttUL}wkW1KTWYpe*dv7h&M2bmLoBq6Cr2`J6K&1`=bUY43U^>bOCm< zT=W5JLW?^BV?eiv7=!FoNHwj&DIO`_12A5cnr(ZolFf48m%h>?phYd4=^G3lP0<#@ zC3P!B^pYG~yQufBF-zO}d820X)JUPAChL|9F5LN|7R9r_VT2x*r0B{-0&wDNa%HUH zgax|0q{qa}h>EbUk24*lLlovqUjd=qbDv~`PWDU4v-TG|s#sr_kZ#RxI8ev(d`6YO ziq;I?R&MZgMCCdG1Utp)w)!=uGX~eKh_7>1J0lAAyd%TlW5$%YB3OEJC+GFAulv;br{20-?qF0+fNcl2)F!AHWt`bDZVRhS z_-666WbbrF^9EP~$<7Dd{>%8I_Lt!^+s_il0sZfkB>!DSoF`apZo|0Zv8L}kj2g3FXPVKAlHW^Hiv`S`fQ=0g|)7qSw% z1&<-75_dxkilqA8Mu%E(FnJ$3MTe-xn{*?^r)900(R8MN*;?Eja}Fp0Gjd6O!9D-h zp3k0qxB@g}pyMlft7QTw^P_RH0ICsBPa6h1`q4O{##&)F>$bpZOj+!^lA9MOT6eB0 zf^@oZnl1)0n!rB#{ZU=r=wu$$KF*@So29erVsHErI+_ z6wkU*e1W_rBL<;G=;r$oI_3W(bQ*<>HXDf^L@+o53B3Q8(CNq3STa8~@69mroe8NL z_Y3eJcH#qp@`LUFlb!gtwLpG(rT=)X+U*1_?|5V4$I_w4n8C?oZMn{w5j8~KC!yMM1z~vnR8}!sE|6NI- zlzOo}2UK>gF#~W_u(3CZu$rXS;=xSBdr(wpFT))UL40s`vL)hYKvE~KYgo9Vh7r29 zy$R}wYdcR(wPxL#cOAV&_f~GpwrJAU#w)0+=KLCZ=+*Au65HH=e!CRfM&PMEX7N$I zc7T1&M~fP_b`+P>faM924+Yl>>ON^Uphz=A$yXbbd#@@JGM4aA(PdV0d8tKwNhqm7n-^5*x(jB`ix*9$i{T`&pInI`K`_v*U#ixhEt>8XSyDdi$e zX2G&YD9$rntcUU-vufG}^O#O%n2 z#HBH?p#>g=ae1i(Q`}Qtr+$JlD)Swh;=1U0BkIPvU1%P_#z*>T1##n~Q3=vjYi>j2yFYaj$>!qKh@cN_|Arl#Ncs$|Hy5?#V8n)6-Y|TgsBw79^}KibB^q zn97MzqEwMfG^jG(M^llc(TXxL2n~n&e<== zWFIa~%b)WttqxgQ80;r3ZH&Xmer|7vk1OL$&GMVlX~W4Sb@XR81O{etDx;0Bq>~!APZ;N_X*hb(M(dAx;Rhz}rlBm?yq`ktZ_U z%umiDLqpo2v8pD<=OzO8vBKx>nBCRH)$}*`&NbNcKYsJyKi6?~gX3k-wf8SQpfAKh z)Kq?GLY>HU{aZQ(e^EWgBr?AMB1Nz?SFyfbJb$`0Mh$;Lw($itxS0B0!%5G~GE!tL z!^3@ksy+zR7Y%sJ8)pz%Q2D3?s(Tnzwjs}Lqccs&?7i1hJeB=Ie^dWf^cm1wYp)RH zoc&#QR5$*<2>v;bu)3a!%=yk|?qZ#zU6d{FB=;I}Hl#t1%){MBL@!)ky1IuAPD=sC8u-xk@~T8hRtT`jv9Gh`Q|%VM+#s>~f~?30l8|>N&z2=q#FF~W@VGpy-&Ncuz35Dc zP!QkV>Fkw5*U3=r#d}3Dd|@+DX^r6;BK|uO?(+o!oUkJg2rd=^eHq9J0Gp=J8Vvq;7`f=w(Q&JP^%3fhtyI# z1SG_W?s^tl0~!7Ez;FPa*e4~a(U1cq%|>%K=A|8IjbC~QmaA~b8s&P2l;W!Qw=&b7 z49Kz42lBhpMo<-`Px0Pyr&+%W%5j}+u6{QZ(|R*Yd!2KNGub{S$~xMmf4DB)nv00# z(QZnoS4xQe1^zb`IM+S_3ew45hE(|rqK1-|P)hF-yZnRFoXDK{iawDUElcXOX>f+Z zEee|fVtQ#^!Do7URdwmE0;PTxr{VeMALZaVZdEd-D9O2RlrvK#$lSUcpg<>0~|P~7`F?C1!cD-i>JG>LS>Dvp@L zqPVA=-h|ihGlo4Nam5Bl1F~8ZnW;jCyBC(KIiO3(Tm?77>VJJQ9Z0AW&B2 zJgzABg7uRDT3XFixnrhDEUIx*D-XV<^64b0xg%H&&XACrOGl3v3k_j%KD0*?4{`RK z-ar6Dr3WH1O2p3&>G!Qs6K!J|E$;U&wl+^D7C8Wfra(Ja-zY(=ZJGf-|^>yMpbgAq>Q1Z-yJxSylU>~Iu zL*_IakA(FgS#RQWy76Q@Li)${Q~(k zS^XWP_31lPz8$coZd2<3*#dEZ_jlWhbtS^Pfv_?)Opc4PKOm8nrXMx_sB15_HINyp zbgIxG)+E#cS-#$gFWehX*SP{)xeGA42ysxDD3dp=T|HJsAxnceu3YO>i2fMr`Hsq2BHs7%}r{JCn%GrX1v*wl8WjTYv5LT0TWK^)ZP*^7#v@PrN5eTmNE=2jvkmGp5M}Ot_5Bk`LLe3SqDPt8FxMo7G zL7aAwEW?>^YZGtV8|Ab4hm;u|$`^vt^L2Vr6s?CIF+8E#`133ELF3}aCPRP1{R3|p#)qWAv;+GHu3+s^aBduL39CB(D9n6hig z9ODK11BarP5g^CLbyf*>jr#l8T1kPTMu7m_nsL|DyCPG4m_ zyDYt*KR@UEx)M~a&G+AJhXi3&BC=-`o~1Uop=>SSQJX4z6oREot(gA^{OeS)q#&rp)*m**GfPs^*yGI=ghr}T`y4i}UVv`4A3 zYtN>|sb<`o)im9~Fqlt->EtS)Ps09+W8~tBwjFSOJzlh!e|753?8CZ}Xdsd%20}T7 zW)NfKdYf^~{}zRuqu#ncv*qCIzd^skR=wD!h%pryd`W#A?yYCpxZ>+437M(&KrB@} ziQhS0(dl{MFK~D7)QPjwAY=n$Agpp}_ z?u2_UG@e)U1E5(MgMh$0?E`+c2EZ!2QUXU!5a(Pi*UTMQ05*aT{_xb0-zmBqd|ENH zQ28gZDg|(yxIW$?!i1PZ6N^BF>XJ~0>YC7=FPSi^mt-}iF+jEO@e$eFMIfDc&WZ2m z#*}x;I+PSELP~qQH)I>?n}#e4Jmw)s$EX31YSijM#CFTt>Q3~cQETz~uaX5=8!Zz1 zLE?-*()9m(%hA7;uHrtyKv zo&^fbj*K1&lgQ$}Xsbf?`nGcuAQB{AF;A zU&)|h@+fG01(#&}L~Et2sn&g47Gm?7SF!>MUkKCFC2X>hJmt$YW-}}-#!J8d#CBE( zlUC;Q2t13T4EnfC!#XDZg~U%zkh$rPoanDaDkr zLjF6j<$vcSqGF~b1o@$Z7@IB^-&9r4Fv-Ng>`&_(@m45QHb&^TWYRd}Ce^%He)If+ zBR*Q9Y)6;~v1zd){4?rru9h`*yUEY|Ex^?Jf0O&#h%L&L(>txrVF z`8zenQB4s&rjmMW%JL#c_7qI#b(w>CV!0G+hzh%n-oeq1>XJB@=uH6h&e0YM*T>Z@fc6A~?yrA4hc%GpUr@PArZwxvKaWW^3tb!@Z_Rr5NdL@>4qR?% z4?piS>>t0&|LV2eGqD%@dH7$Sf9M{4M@M5PM_OA4Q(ApHeM2*2T0>iFYg-#fT5EkL zGe+7UqfsMUYg!v)S85AeV`@uhTWS^>dOA8fYi-Fn<~*B>9Az&_GrF0@LWLx8P;}#O zW&Ze6&~I@Y2VGq6_C7St_$lAdQ{S)U?^oW>obO}auZ-`Hi7#BD@8jdoXWn~X^lzfi z)$N*>p1SYj9xX%5mzo~a9bez6Z|hf6rs0~A=NqtX+%?@#$#dG^Z_@XaY2DJ7jIZa6 z-Jd9gjJIdWnNQNsmxQmBCElq=(bKPj&+A7lANlcJ*^3Xof!OV@nXMl3W6?$4f$bOH zX48{Q)%T3^EJ&Tw;GT9L>(3VUUEH39{_Un~bBKa^-kOk}j9vFEN9L=Z@mCLwW#av7 zla~$;8P%crb&s}>LGo{$k+PZL5FX1W$M)~$4PVO-(ND{B%_q%EUT)Py-{o(sPhuR4 zXWhvCJm)Fr{tVR*eTWzi)aZG(+tCNAg!S#WuT!q?MuYz47Q-UPj&Fu-5#b3+amK}g zoalRD>6{^3+-KaiTPbOz>~PZQn~)I&m&@A65NGbWehPKo5=Vn@2Hgi!`>45Rsa4Pt zJ@n8ZVv6OOd&?zRLoiLX{I|^cG3x@_mRcd^m5n#+{QzH7mD1*GT22!P#cYNzhDy1t zV_g{;kG-$DTE5E{JnC5w+yO#wKOMym>M$NXZWnIG-%<;m-(1^@M12$F5|Gf3y+24xIs) z+{fvtasZ&H}JAPUA(<6-Vh+g0wFe2m? zdqw8up|uC@d$+EE$BTQy&f%eT;Qm>ILH&(8xX_NBo66;`;KjLuYhcOX7|aH&hi)&_ zK6*!e7-o8?*EM8O=J39TZ4G5^7Q51zF;ihbOt3jc8mm8#BUqoP2O*hraeYd~r?H;_ z*qD&U_40cAU6s_gDBh_!vUTe+gDhcRbTY{Bqi?nc)pii%`Z#31d3i!L7*8#3JGA1m z;*>M&Smp3aCx&*kQbfxpC+u_A>F^`k7*DMWVcGNGp0vE%%Nw)15YG+QzH7vF&pEhu z%`eoY71h4Y)Z?3{&5`8`$bP`12>rLG56StJ%V+#7ICRKXWCgeBOAutilve}bHrIg1 zG1FF#UhgECp%OGeWnQbmnQptxgc(M(Jk# zw3TWIolccw6ay>D_Cz&5Dal`E1DlrQ$(gj}^J{+9_B9ALXm$!O$*hk&kEpTRl^nK5 zlyQQMvA04Om~z+7$)w%C!??__r_Zr(F!pG9i17Ruk$zZ=)%2I)L#;Czm!D19+hDwA zTLE8F_qDsX%EszO7J-4;mXn?FCDTr&geQimJ)OkSK?l9Foa-|!BkdRXeaw5;3Kbk{ zitSOm5i8Gi5&K|uxRIXdeLG$ydN8kymb!(*xq1wEtliqRK_A!@o35n}(t*X6sYkmk z!4Fq*`(KljX>MkQqU$?wo6WJ~$KWo7VMM#TbW+?qL5Ut{k5d8WXLe!)Y}z<|7y`<$ z9n^cA8qCLGr1Y?nkFv&5CvYXU!SXo+n-dktdgyZeZreBduPosU-Sd%PCL`wJ+quBZ zw*wBf;n~rw2S;jxBqoeix@QKqTUx!MtB#;4n*$%@Be3(hA7$%wR859|n|lUpYvC=`1WnK!f(39^{(2y&@0aFB zkhdtS@swm84enrwm>{wA@wZ5;u>)b<>uPMz`LP);|n>pvDT0*bm9K z$gk{wo)*#G1On<|s*FSMXkbP%(J=g(j~&>S{{V?N7Bacu(={DMa3su;J1 zXPN2BlM0JlTpP2bm8MaIIHKd-o;yr(y4u0}#0={?kjpnr*qkrNf z&26m{%s(IaZ#Zh-as%Djct%AI`zQ#1a3!vAck-Dv!qBuKAAZmWR42jGvXI@Th&&DF z_AmAM)!=(G*zP@Rlp-I^av%Pg{SksMxBw3{WO!iU)ugdS4J{zlF{WJ5fsECa7~<*~Dy7-4QmvK|-%1@(RHR zyaIPmg<|{F7Se2J%%#lg;Y&v~>O1t&Wq)$?NTUNbA=4K0sgoL7}D2ZB!;34QWkXoT(Gl5@5ix?IXr5 zDw*|JI0UJS^gO?9D=Zhy>9A%OVs7K>z3G@NI-TI5u8=&^{5tzr0s)W$Yw4AP+rPFG z?)UxsT6NM}iLmWpHB(eQGjvRu$s82iwCdSTh?#?)WCWFjaupri3d&^=BYBu+<(0^UNBCMB=%GQ>e3gfDoU{8TZ{Mu8w|)T&`Q?&~v{ zIxpY-0j}FKZGCsOIcXEo7$QDAOAT|Abg-hVx%gf;g*{k(p=W8$b~Y?|Aai*Dzf04A z0w5NVpby|E$xpaI;W4PUCtYDs7i2CLGSA4u^YvXNtcQTTw$}q4ILHmVY8Vs->vvAEjWh{G(cCYk!(0-300xIv z|L}?NdSK2%h`WL<1sMQQ@_B@7v&8NlA43SvphY#u67!eRWQjxT_`bG9od5-bgdbg% zgLK;A8~JZCurUP+fC=nu*bgn7h^Zgb{}mcfx54D#_m5gp#)0f&thY%Jq6!J-E6r{r zg*&6jgfnGKT?zXD?av_{h$ zWP@3Meo)kbyelf;#jsP8w$`v7Oyy0khw`crdIqo_u$?94chgKB61NOI>ykw$yb=Aa zcQN&8Gv<2Hsgn}im}~)9I{$t8;N^ONlR87b_d)f{W8RVQYZwwuPoON=KBuNSGRO{C z-|`UsEGuW(z^_tKBnbpM3v z^p;#OB({9uUO(EGeTt4L|5Sj1oja7CkNVcwkuHZ&sFa6)(Dm1{61}%WGdtM3`R`wX zJs>Q)X=uN6R^VVSG6OyveY&a2OzoS6J7q@ZL4{-cJUr}lgi_*R@!3wNy;6JrsjD-M zwN5H_;Aq<3i?B%P>At`>;hsy?;b;6L5t&5*q#M%!1nfU9j}6eCLJX2t4O>FvpIZYv z*cvl=^)J}sepi1m=lX#eF;wx4H8Bg(fNnqmr^HLr0??-z6D45n6zPHHnTZ&a1XMbv zO1X}klYOKIskk}?RnPwprLS3w9uoKm;zm4AtG^C7kVKW_9?~(a(M0a*U%>Lt+gH*D z&$z71k8R5^zIJPE-rWvk?_$ZyQtI!ZzY@nVgWYdTaz#^}V7O+;)j3*vBC3_?1M38a zmUq(3YoK|~VKTTf3=7-i$~`%2+^Y%-*pd#=vtARYp-rNOl){2_Sf2owYsKh62gO>f z-RX+JVv`uPKqN&-$yF2lesFS6YI?^sE7tOd(GIN7Esy|CB{2()z=)~=hH5t=oY$^S zSP5>+|4q^7apq2Eb);fX(TNkSUB2W1F+5+xeaS>Lt^VuAGWt!gc`~oh>#e0^)55(x z)+h}!P{n^TuJ6yAv0Hu=h$3uW%?iN;G#d-r-&Q2qcFn7(aym0I``1H60DMl}l!;z% z=oe3KJM7Sd+7d~+9CuLSXx&>XKs6SMu}%J0H;5z0SO;YUz#@bf`(B;Ma6g%24^3I` zJ9;|`Lo!4Wg4W*ixv+(GHw%t?<@;XWPl9RAkBweRQw*yq{gWmVEjdKB7XhT?#MoaS zI^|X|lcrYm+CX><$ea_%5>@uZk(_N8gVy*H#!Ns2;PgN$gpAKu)O*OJ?rn9PqyJX)0T5t>) zmRcw^%8iJGrFZtStrgfYkA|PNkBUu^LHDUSyE!5H5?t!m+*rtOw)X@hCijm>%fl=D z5U)g4NpC6hs+!hS{4bFfr+#D2`IyB&6&GCRnDFmdy(g%wjlf^=J-xhyj8_jl2ock) z2@`G+dP4;dwvo@Vux?Hhq*?q>@a&RVkA!o%f1N?3+E>3Z9~5D%4Kyh433_+fd*`Y$ zDHW6C@!bTZz!zVg4xUngC^jX2$+{~k)&VMdQ9LS#SxLZ-I(3v%6=NneL50~f^)C0N zvhdAUZJ85>$sD%Qsr(982SxjHx-=cx$JDlxAt;chFycJnY~J zkYKY6p&JBe>fS|loQ;D60T6GqFH!R4=Ff!SBCaC3sRL{0gn5XztURzt?mA$VPN~1# zs>hY`9+w2Mlho^GH(~T;P@Cz#7dvh)RWFUk4k-9*{UI43*5+Oa_QR<}3VIOm0p-tm zYY7nE=KPqn9`GrK8!e(CcrSQduO1N5<~)}V%Ag%m09a!Z*y5Xe_oX%GC!+N{eyn8? zK(8)={$J?LrFmPI)Uo^qsM5xM$I?!N4=lPz zk)f`mK&G*or7#Qvl5CEgnyZ)T?fFL5a?S$H*`xBE^2~fpsnbIP(lr=7i!_or8r9~x z1D4#lK=+I?(|1gakH|})>7CvJxDi+CdF_Sy`4tq4$Lh z75M2&n|7{rZGiE6qP&8$MepW=D0vimL~R&rRzeLB;g{&>j^lP!nQ5^PJV9CKv=0;d z??i%Vc^ueAwBt>15f_j&q^U-!|0x>5w|?%L8U+sK90hXz()m*uqW#`}A+Hy{W!?En6w~9;Na8>W5ik9^G*MIHSq~r?Cxs*Vdzo1eao{@~wcFSCl)unv!||N!cm8;weh*biJc~UQET#AFJzsOg_7v zzja-O=ZtV90+#{txX;mPNL0-e+fR?ffD*g$dS~zDWQu!W{=ktK#qvqx&{VR*xjk65 zBO6Bon$z9rr zM6pp+E*r@6TG8hP+h)3KDzhqeI0JY{!zBrb%nfJL{nZuEDGVlJT~^1)$CrOh{GM5( zs2U%czCL29LZvsGXx`nE8vk3KI9n%ZdqSdV8X_DK|Ml%R^?cepyjc2$e(W#OugQEq zu`Lf=ua7=*v@ik56&$#PD4`DEE6bkRCZCROxNvR0Fs0vm+No(h7wcC>4z6%7jEhF0 zX}`GVaTcdAdt62T@|-QD7PSBXVKs?+!A4mV`j7JwH`*e?XzE_F#vFl$c-rM97)C+Aq#dVF6A!;#jl3ZTU+2`2h-<<5bPqy=@)ZWT%8b{Z&TZYPW_2@-BBptGJDcQPB0-x>!z$ECthf|zC8rQf;PLY*A4$^k<3**@N6YGe6n)Os+%K@2)ckGu)yZ_n zTa)e+gLAw}9X){6njs)!56IY^N7ZLh+u<%!p$tkoOcAG(CUh8|qOZ|4MWYLk1BZ^f zKsxkD(j`GGr}FaEvY7>#c5pT#5gBgb3;zXvjmen1*1z)Wx7|LF9xklXUt4+MDZZ{P zk(3zZd9o%3;{6>^1UtWnA_8m{RojgBa@p?r3JEW9Hjhs|!!_1#uU!)~-$i$&5DBf4 z#b4z3c3|y771k|_UE*Nht}R1xH1TTM#!-;jW6HKIv+C_E7q}qMo6cA1HeMi%_o}=% z(cDcu^{zA++MdU>Na8a|^j;k>(-OTlhowl2lsB}om(a=ajB3^`eOZS@wjR15$AsDb z!5Fa!MFdM0XjpUB5G9<<5a2Aa{=e*|tYGynS=ciA#AQmj0L1nD{8|-4r7CVcmSEGuW9~%h52QwA&{pc^yQmLBK~-u5NNw0J>!8ZF9^UrdF`@%%wc+xkqAjpr9UfIXBaLr4;3 z4Po!wTANJG_K`tNgINeGx*ZV?7^>j#h$v*C9Q;~WZC{CZJ9XY^&Fc0EDnVEME#*dq zR=#;Q>nMBv*ks(U!1Sh#eYG}?;W|nI5{a}cePRM!uJu7nYZ8~Cqg=Trxh#x$rz!%x z;`gU6>>}Rg$lC_a=)KkaaRa0GI zlq0jEUam;$WgQU-6Wb$mJ$QVvlX^$4jwcDNlx~D^sm~c#j5FXMMCC;OE29n4wHqT z`~tA`Uk-pgs`U9$s*+$>q<5SmHIUQMnSpn_m!wKb5^Q&lG8TgU^p=gCQ!e=a#ssB= zj`%jhAGqVu*9~Tvo@dGnA&Nx2bGu+CWg1kbr9{D!cM5{7-Ud>;x&aETJ!mqxIrn6{SW-$54CMt&v&=ZJ>qGTXDJj@ zCJ~bw1dN68yVW2&2VHDOTlGMY5YwnNY|wD|(V#x})SMW(=;+qop)ne$!$3Il0|}FO z`n9_+xS4V=k8(>AamMa+Wfjghmt`42L;svz@FUOH_F2(0N{D|J@V{Gz=4yv_TT#JO zBD7Vc$4~Jks}h5n|AF20qFGmlC+G_>iV9!v?ZsQ+=+J8=X{vs?Qn4V``GD9L0q+F9 zyS=u~>1T0lveZ2H>=rzPLWD_r;k{)Az~bqiLIrnBD5v>szG5h_IL3ZLj zA_+QM%nZY}d^M=R8kv1ZX#v2A@2D_5J>&b2*Q~K)%l`+{2vmmU0j@ zx8#gxp&TfVOfrY-Jlx9?Ev*m{E!6BFlM~NzcOL$TIBMW-TG@nz8K!xC)z4v!luBS- z6R4k>;CQZu;|s#P^s??e-#@yPw?a@KfOHo6{-#DxeTOB{5L?d8D_6cb5b_b`;I6kl zv#5j5vqTTTWEw0aae>DfcEW*x`WZz>*f^5vJjw<#=;9s`#FT9#)>)|0XvxA+ z1S+J03eJcm7I$Wnd=}Qq{X=)BND61rdDS*F3-@8oy$Y-$;BlqiQrCS~2|@t#qe0=| z-TpXes@XHAa+{Y_;vW2S1CyNExhcRd?{qGVoL)IOEFi_}2qrJ!k--i+TFCN%OGD{? z+PJ)UYnR0Z?Zm;E<=@+PTO1j|uzQLjJHsc4vt$&^icGX-&EbNdzdo@xXiDf%fK?hIIKkOF4UFQy(b<>;yP2WR!+Lmhdx&721l&%Z>#2D0qH2^?ewmrMw=GUT%9O> z?3Ptemu2=n--7H+T>CUQH})B9fi7F>FR7m_^2oIcAXge0cqv}gcBk@&1Ub+%zz;%a zS8G}JsPflzr;`&$NnOTR*BQJZVv*p>G7oc}BdMw)!|hWRhX;goYoji?m$~R}$WCi( zPi3o0@UP=VPAsiGj71ao@zFH~9v7Tiu+e=ZBiKcPm=9cSRV@6Y)#7sE0RVnFbE|6} z#{A@s!nzBQvsnm+TS}2CGA8{Ub%25R!t??Nyv00pg(^trjs6w_E$b|_#X66uQ&#dn zSh21+d%VN^9k>>@kBfL6rR#DVr+3Da6v;gF)D_-FN6sf%9I#nj!LMK(v1!6t z=r@U*%&T?eYRr7thuRk0UXVZoSo)O?qa%5nu{1D@A*h$dx4i&eb+OF^&GX8x13>a_ zL`*?gGLklvAlVLyYnOm&XVpPxPomR3c%x?W!aro(S;nhIalRrtN@94+Ym1XDZ-*AK76ZPh6 z%(ACErViBiG*ud=r3280>}cqS#Op1>zTzu$Qq4B`p`zD-^W=$JM6d|%WMdq7_bvyh z_lnCQvbzBC0W3fk_MnoE4Rzt$xK*$G+YqRjlQ{I}z3Myu^cX53d?4=OYPW@5Kx)GZZi$;s_y95+Axtc;hu+2PXgET-yk|EGa8Nwe>4Ui6Yne*8_e6E{y zeMTRS)Y)`GLbKe7`rl@LZgs*wT2*9ckExX7RCu&|M${$E8*|KnZ-QmULb>!f=U0rM zC#XhzvsKQTR&y!N==tQ{#!C$o+$;^zsiYV!n5^sDf88Rs2Kee!TI1i>BpKm*3hbej zlL43vxvPvLd!Op`c0Ulb&sT_({(C$nREyLv@Vg;0G81Z2w?W-kdolAG;ovx(B1MZUj{Qwtln}?^~6)1OQcuuN`OrGr%R&^cJm~D|DRvevVNX zp!}_bM1L4JY$@)43AJYUc4gVDfHU`9S;DelAQjG*2OPgGJqGWo$$=_-yW1nu!44Mh*7M3>>QOKlU^i~la2qkvmB@7VT0=l_cN7nTtopTqojYUu94=X7&U6ZF%VX)pV3MwT-)-q2&K&>AeME<=R#S ze|Z~clm5&}d)0=z(HL4XttP%|IPU9J)l|;a@&;-eA0u&Ri=drL-#5&%I{wZ^RC|4W z5X*8XV4a?(CagV2EmMt% i0NeL3!XY%=*P7F4?Hfnur@Cn}UQa5{}>T!>?h$HF- zV9VJZyx<>~Y5a!F7OQX>kerG05;5SH!LvG3ef%T;M0fy{5h7S^mVjf&kWjtF;Ep+M zRpL3%CrVjDKPK0~Sf1c-a>o0(Moci5K5}4u1+TYH;7r0mHIrifp1iQBUWKml*2biI zqt=fypu*<~^gu5+ABk9b4!AWt28fmrFXu8$jZO;H95a)d7bG8Siro&bVjxwIYTR)a zUz43xTWY7hMd4>SP|K-E$h7lo#ArRR(L?Kj>6`H!Hp-43!fSMAsz_Q;P+1?VABZ

-t(wqkj;9n1%-Mf{Eo)RtnaT@f?2BkOjor4#VAW(bbeSW`9S=J2q^Q zd9`$0d?NIQQ#Tz5mf4#dtgOQouhvr$j=$C1qApDxcR)b0NZT_rOh_3VSRl@g| z+7;WJBZP0Z2{F8FqD`53ASyhEg>P-(Ev|1$apj0@Vq_lGu>b5fhStJM$_AIzs)=G* zc@$nCojv^JAR9u0$ zA^V7bps7%nr<%48G$VHvIOXjXBIxM^Tzj&1(X-t64%p_DW}b>K&E|1xNx&(?JQyJg z5PB3#RiuY^M_lmc#ZGn}yY1%rBjEkDYzG;Nw!pL_u1~)pXa%-7&%}sC&1cCC3SOSQ zbJB*Vh6n<`=UiY&mpU*2y4J}d*k=tpkL0%EA{jHC7KP?5uOm9jKH=J24lUC`;`Ub; zCrYIP+wHctW&Ogdzw+x|cFJd6yvQ@FOhI?vuwqB?ANyf1p=(DL&SE1XY;`HLlH)iqws4fqLpSY(_1dj*{F#aw;ux!PI-4^YcAKb>w zn9?!a4VHC-C7;=f+vvW}E-j2~BsTT|0Oj=wRc{}^g*sx_YzZT&u%1H+qk=*&B`&*! zifPLbxbNAS5lpac%f87KKwDZybx7Mm`^)8pi}x=yQBLEuqmg{~exQ zY^?8ZDfh)K6E)hQ^(L!L^vVjn62p19;s7cuK#inITt(b}T^vYi@fmvgz!W2Y;tIT5g8K2TDwqlVp#P6!N!yuH(Zs zezth?+7lfFH9#VG!5wa=G@0K~pBoNun zi!W!(^@tCt_b&o-E#JZj@!?HBUgWLQ*0L2eeg90?FMENtvx@^$I_TI3$mIp;HP;W& zwoIFC_Y!%Qe>orArspR^ax>Vg0I@CCfe><26Bkb03M#?@166GUI@Ui&D=WssemGl4?MbzR-kgQ( z1&b1XB}&j~uc0F@F%OPj-Qtiy?EMVu(j!!_Owi?8Ke2;t?N_8v0h9lx!09)T4JN9S z;>}5_;8~{rs&q~icU&#WWfg^)1MYZqd0(dxnJdrZBPhrXklTk-K+{{~r+f1LJ(tg9 zzb}39Us}e<2~t{MZ(0TDoUd#pjA>W)?i}60Z)F}jdCW3Mv11$y_KYi$ z)=7Qk2|mZFodV*I(^ZB*l}6W0#5AP+0y2FcL7ub%le;B$V;Tikx_dQUSbZ2~E4|R& zF1uf3GJ)I$-c2wj2R7z_|1Ew%9#UpzpXWnbD5`ysgBV(41cQSdWa}Y}=#cR%Mi9?Z z4>qI-3aDV+VfOLdaHp~t9{9+J?o^}e9H^Ju*aT?4W9d;kWpyM?6ylK%S;UkdC$!!2 zAxItEW5)i#-&v2Qq>nblIyMA)>?5|i#5%X%8Pg%pR#S_tnUhaO!!gS3M{XW--v28@ zX)W91U8AW%=(AnEx`f>Us%NQz{rfxw4RISWd+ymY1_4%J0s-Ym%OGVIRt@V%`sZp2 zbiG`b5)1a>=XaQ~Tn&M{#}Q9FSgeCChtA zw%{S0zG1L?&{tl9xU7Kk0Z5n|%R7E<$J_lmY`ZChHY6bFzY_}SvL^R0t9G7Ur$vx1 z1Upuo(xd*-xidW+RZ4V2v<=Y1x|-a~)=dtw}NPpIMA!Dz#c1$B5Bd$LV4FKsxbbkyZNrf5Efly$+swWUOn z*1D~iVd?}ZJE<;q5IRm>ReTU#e3QTt);|w4(qg+coQ#rw5wCwWqZ+9(B%xvm6yFj1 zY*G!(0tqOQj=JDu&KU4OV@l9M4w_}5X(QxKN8B=-Khp|{TwQ{K8LvuuH{)0(fNv`! zat6b)T4**@(q(&g)-gHZ@BniAgzn0V%Ht1`Ivtt>GcGG1353M>8JFvgo{s29n|6#C z1-{(8M6KDTDOYWld-I<27E%vnRs?yM!3F!SR}UIRiO1F)Ftm*YJ1rD4buh!B7`MJcjoZ#~10xSTVjV*db68PTKa5F&Z3*PwXQ@G8 z#~#XkQ_hN}NMEhv_XJ`S@KP(u_(&~tYN&oyMzJedzdThLO+Oi^6f}3!DfE6m5@AC8 zl3(4maL4&z=G2d#Drp&{tukUI=Wr3-Zae|gGrH=)tR|4LGru+SGFD*@Zn%-6UrS7Z zG_c!xxU$u2IxF%(3nDc3*o(KZ871J1EYSwO2?;zj%C~@KnsOPs(^fZOHZXdBh}Ic0 zc?uzN!2*mWI4@js|xkJP4=LDwQEn|c|m#c+nGboFYhD_mnX4?{f|T>0!s zvCMpWh&+&FYKzzDZcP8$*C_62AB9M<%zk5)9oJsl7MgDRn2qZhXQx4FNH)#fEdww1 zY#ADed-r~HN2jIAFDrR$Sy9jNoM_!2aYoXe5^TJLwO>s~IvR7wb(5r1ga)QoA-m|0m3ftkiG1BMO;(I14qp|oSwH1(og7%QGCC|eza7`wkF z$AZe8E3ok$x=v(--suAzZIFFV5)hW(s$rt^`r0u68>jWo?i3JdDsHf}A5pxB~6&fluLn&!j@f zz$iyzq?wnJs3%vpwLX-TfYL7sXQv*n&B&|^ovb*nHx;5PWGq=~4e8q)?@%Rt`45Ge zFAsM|o>UsWDW=Jo2`tnxfE|@#8OmGn-s^zR$DeVnu${2d!G&~k(my#0@wMnMtCHq>AKOuQfo|EVK1j?hHY?>Wh1PC- zV(|;ettUT}Si4fxF$_xIodgeOyttkcAr&M zk}A7ld?$Q37#>BD@p6sX>9WG|);p^*iiGmYaNM9dZM^tcP4e&>&py1adSxnb1PC<7 z7aB#;VNBePlX$u5%d?trDZ&i#OHKbPa6ocr;b|JgEe1}oQ+!3EjYUqRy~dvvAiv~J z+SAy*1=ANWLZ8UeIg%l=2jqT9W-PO)l-se!O0rIvnrsiUuA%7EwVO#<`G)0ShP6ko zFi9PstU0=#9N#8TGnBs6)|{6QcRTz@UCk<~24>G6ScyeDQo1~;A zTWC;?D=*QA7*3tY%d+7xHyvUIW0^j-b2>;ce-GY8LS$FcnqCM5Gm@nfGX3HhgeElo z*Lgio`RX0!m{dZNE_r=UX=Yv27ZAyg5v$@q?_l!vBxXux@n8wlrOuvp+ z!dc`ZIG!B~br@#6X>*n-U(qR`hQxm?v|}HtlB^U+LQTs`EYtJ>_KzV;n3G8!Vg8w1 zeH6^3e!LW2W_sd#r{i3I1p%}dKqUGxbc@GCD9JxL}#nTLE)c)^pPyATLnl&aWl}h8z$hDxD zG7?_4FdbYw#OmhN-~~r7`3+y6kHb0A@f{#(8r9$UG3zEex5y2rgzKE2p3mj`lB z!$#xzgP4qXFyO0bYFYS*F|4?~GF5t31)8HdN^F#Vsh(>}h2ZNH%_pmLAEEyF>3EuO zi_tKt-$Bk4nmhUxR|D8x>Esbx!D?pyd7-c#Om$)y8^A8f>uYCL#FEPRGEBGOy^S~9 z3C09{idw#I(p!ANlsxG%{j?+Jjl&n0x52$w#iryuq{`tL%#Nl7TnwySKnLUoY(O^7 zErdwZqJbz1U^GD^JPsD}bjo}$zeB4U`<5&}g0q7UWMIBkHNj#m`rrRql)c%@K(!H$ zkp!{d3l_kef}Zv)iqYhBrG>vJXTs>AiQGb8y^ZzF8L=jb)#QyGJ^T8zI@zEIJ5CnC z0Cn1nT{iX@Z^#8u5rVFzFjR;cA?oRRf5COv7|Zc+ZP+=qh;$RKzliX!kPS{b z6XLX+akag!MA-kxU=qH|A?{EiYovcxa9mbF8MxmOWI{3c9&%2+M>H01%%pfX+8o>J zfYh2GXi!X;I7jUJ5|z{P7Em{!dRpvBR5k<|QMyUb7}AaV&6FfdWJuy|j~7ZkrOIsZ z{nZ%&5{m4Ej9Y$rG_oamJ7%Em0VX5dJ8s7>scHZS0*10 z+XS5=Wzk*&8d%cO*+Msg@0|Q7e^dy)#t34a;=x{@nN1aRAF)r+>mQuAsQ#!O7B9a7 zpWXSr?wV1B*n64X;dRnSMk&tCl5qqHPZ|l6SXcL+lG{l!slkh=>U!Fl2hWY_O#;XH z7X<0lMkHWVfXFSB=TY1;h3&op!djuPOUqW&`c%k9j!Ce8c^QmF)$L^h|2cCug_EBC zvc&R!9w`|E1eOESkHxNiy?Obs!A=Hii{jD_A|j3_6~L?VW%;DU|)+O>~Is)1_AyRWm$P#}h93M%hIX994 zdo7U$-C-IEzXAlq)CT9vC|-=~zKqJc_HmBnaJ?89q3vjUUYG7nINLiY6yBCop|Q@D z)IS#6D{C6veC#-!`O`253QMJSmc@o*cT88s_PdJ&0jz`IPFICM3|^hn(eE6Njg4Jx zQ6P(Gp(FtbYcv8`bCV%o2@>SmXW2{P9pVs{9=ZY*XAuLet>U~u*35l<(M5)uQKBj5 zY+{K!Bc*0*S6Re(?0yX+;4nOmB9HwGAg3%vwsVQa@?c&pCo^;$FscO6OtY+!t#H?u z>!4g3azK(guWhhp;uw|(k)1>K2No6e-X{JEtdCoHpdI1}=f^#-J!a9o_AtYW)-z>D zMop4xvB7V4eE*Z*ChBf52aghQd0=c7B2bNkS}`<>TVp)y-DgO?Ko3mOmq+jdE3c3}8d1)h3t04Q3tGWmMSyYW84Y_X} zCYrfOzmTpSNJ)hL{hU;9(WbeDEBC*p*F^$~@L)PhRRws{Vl4BGgzuYW!A@Sz0}?)@ z*dgu0BE$(SANfve6>X;NHK-)t2As#aTr3)v4+8n_P4dtt}S> z0ADWPCxk&vB6;cJH0Hx;w$CgnKh8*^P1e_>FJ_A}^L~LR z!9-l1i$=;AL!k!6uwOl5UNzxjyS+4CDWZ{tye#s{1yuLk2@_wHO1)scP!55KpAMtB z=!f=>4v3E+$2@XfW1=3HXJ+nO=f@-Xs@F)upMMbo97HNWUw&A10C98+~(c3ydgnPGGv% zmjOY}8fLn+xa5In55=$s38XCb4hhKE(37NE6b#5LfQsnSCTzh7(9@J_;|r;mLOhL0 zRtU+D@PN5A<|R-!YvGXuHsu1)dySgq7ZY@rOYbm!kz zpUV)BTfL!6iON&l=stsk&gLpVH9iN2)_RNKr$2fGbeFK^$b$3wg9Q%k(oAlORj|Gj zPJ5&KRN(jrIiDs(HHl5Cj{=ahEYg=46kFye61c5b-cV466x3kert|st`uj@9BAszS zyqZ$`fUZ-wmOJ9!A#g#!b5a08e!o{ErZk&f&j=Gwumk*yx3!mB1Xz;0w#)7Du_7ta zqj+$}8G|43bJv8K4<$|G99Rn+Duc;+y+Jfs1NqDnRrtDd8&f!4kK%>%1`8Rbopc z`sKlPPNYz<0xw?TbTdBUi?e?m>|7G;EkM*7USxzZI&lzSnLW%?I9BXS5edvHyhPjn zY8G`yZxB_A(^u}W8=gepUE@&t;0%u2&2t&EaX43ve*v;%lPTTV%1a_?_sekEBacO6 zk1;jFqh>;SC>3Fd3BV$w&77Zmu{bqPIi!Q4<7*6rCe1AKdKVF4wS*U7qtLjfm5Z+{ zIEPPUh8){jkeB3D8V%+IPb`k`vMZD8m7DA2f_$`k^?RlL1`0x^u`y@o$?P&9`Gs_1 z(|7q$LLV6CW+eR5PK5(&g{_kz_{N z2+M8H-7*_IE1tF*NUS+C-AsDL>XW^SLaQ+96s=BYhM1R5k|4DoFnfHBJ}A5CN6&_y z=6NdB(**jFB^~>no7^s4$m?A${Y9QYki^~INGl*OaYa|`K()zsqIXi zF`=_{d<2L|dRIe+2#{Mca~GG~2J<9KHcdNt8nSjN5vW__B+*hk zpxN_cz^9q#=oRg{n-Yo)zeBOi?}l_$D1aM8EBhg=Vs19R{yx@8pl02Pd&%_?fT zRPF`Wf4|{KS(+Yeg6>3&Bl4thDPuM4`UxWn+>j9dT7lVH4y65=ohs^pLe3 zYIWX@oNS!Bzf#`MQSR^))601Du3bhX^k9k&gxzV0bR06=mjo_IknZ?ZBRZclBi(LX zlBZ8NAOK|^;{%%ig%w~l&WdX+daoP;KW1q)N*W+FbQh1A10GAc;=NGTelOOnsx*`< z%r$CwuMP#GRKwYhk48O@4LF6H9=Bj)IpoJTtHQtOP2)vhYenxHKA^Bm-aq6ZZD)#K~yEv~n zLbf!4L7Cg=`NhWkAY|*eAySlhYb%_nWiT(MU-NpHWS+Bh>?reiHqCez^>NocTZ-yN z$H)iC<1E#7rg%S^7hJK%-i4u4Tbo$D6!>M0>K#c>ooj+Z9C$;y3}!D|ZfUNMwM& znCCI)Ed_g~cUEquqNu2S1Yg=AS~u~sN0!!z2NSs{lA}}X#V_zdqA1y(4PQ@*n91B; z>M#218p69`L-k~NF{9;7%)my;a01wH{y$rK}z83;wGY%292^Vzma%0z`j4$jP-oDI5 zcR;8VajkgyhCjgKZ<@e^=wiu+0&>CqFqS5@QB~9?U!VrOeqhiflI(wWwsnRc-zBo3DJ90VVLc0rfMbe zaM^tdCvJlb;Dep$-{OLWZjIWNVTpsk|A2{>8b@}?EKh?}ZRGTp`F$b`YSOF{L+q3> zBIONcf{v$(Gu+lj_k@s4edUgUttG#DG#MIXi7y)j;nHzAw%3l^@^pp#@M=RiKJsMK zMvef~)3PGMSue}nAtET_d*q=ay%|?GeUn`KT$lSzNMF?QUPiF4h-eZKjMgPbM(`}!hK$Yu?`kr= zr9;MRpF;|GF7PeJ>|0=BZR+=*vq3O$orxqe&v@MV&MK;Y-pajCnzMFH=ltL9&+o~c{a7e+8luxa@6*nE)U)ZxRk=i8v3O%fHY z5fL(IK!T)1`6nu4PX4S=#3Y>}JH?lxPmrId^ZuAtI(3UQO+!D_Zij~5wp%(ZJt{?4 z!TI~yDRM2?ZA{C?0W7R^v;)>Fcip3{Vrmq7PK+==5f(y3r6ps!k3bR@GdKVJ=r9^{Typ@Cb7ugg39V&0YL%eF#flPgAaxMq1 zy)WzJ8^CKCu>FiT|I4d~FDR+Ai@+49sp4ts{}bcA7;QZ7rFUlw(IntsQYB~u-fmwZ z%3&nRWbu4}BaaK$NR=xlEL=*y8?K2>*ot{pU$(f=Z-ewb=1V>P8I$s;{Lrr`z6^aU$C zC9;g=Fe^tJM*ef`Cu|JDdERqS$2gfX*$xi2vYFn_De&hqh8mlK)QjHuS(9Ax?7kP` zbY!M|FY1;sghrh0Hn;zvApFDQo6QTWbXgi^MySwQ8hm#QVT0)I%Z`taC8f z-wHdT(C{=dwt4qL$m`5m;(~x_Vm!C$fPS*^hG=IFYCeT_;k)gsIX<~m`<0V+Dt_=hTWHdc_cRizg!Q7No z2JYvBoB;8LWH}r|tq}L9E#vT36W~>O@G8u35-GJcz(UxxeU$Ro_gNWE$ozj69bj~0 zaG>~l1W`oNitL0pBN6H(Gr>+n(I8A?hBtq5ZFG8ZtpdtDj>=gui@r^F6EA;3T3YHd z5ya#IF3R-$6U^#NLJv^N^O+a&oeaEHH|;=4grSfC)z-0Wz)8mCda>HC z`T8=bT$A=d8OD@ofR&}jZdcM9EC|Yt?bwDb=J|SWHcMmb!YB>dH9u#|67DYBpj=wN zu_slbtEED*HXEZMWCBI)Y5|ia7@h^@#J_?u>?X$d%t5794h|Kz1(OA%qdfgMVlFw%)ST_1^89S#(6rT(QKK8?d2 z1H0>f%<&R5GF~x48LB(%I(bz*7d23W+8Or;m}Nyz!OTBL!4#)Pr6*)X)OSQOkM+eo zmb|389A3GxT*;r3+`0k%N-;4)Ob9QwoAv>6n(+U68#vR5?2n!7&-sf~nt{UyS0EiZ6KYvN+p;<2u=>J5U;5`XR# zr^$m{ofyMkFr*JJX%@Af$_|We4DKjLN=^C*$TuZtwufXdxSK>bB6}w9ByPm&f*aEe zT-_U8+u_XlC_sXV`@?Z+tAXJ_ z+7FCq?9v%4_yn35ElC^(01lcVn*Ci6o%PqtRO9pqK+X1j7gDb?VvmQZagU>yG1ni` z+f&PY*rpKnG9_&U;g_82D`#Om( z;DEQ+GzqG3N?av)sG%k26i~_YK1p#u_~A3bf8=^D67vHMi7=E&P{e($*HQd{|A*~c z#{86)mjeK(xck4beKP+KY@dm{k%_(Yuh12}i?f9_y|kT?fwhIFiLt1i<1g3GNzc@g z&fd|^-o(+_!o+FF=fY`2wc*6=8?`NWJ+dp!mBfoI$(^kgii8jnIWZ4%zQvS%B2Zjh zP!I@*$C$hP^Jb&=0Z4#1adZ7GK0zYygXi7(=iMRG?{0XFYpT-uU@1gxrzE#WZu!>F z!9mAQa(t1SI@3F8Q6s@?=Iiw`1pG%@s&-VVmZD2Xp``0q^Mj~%;K?59s)B!#mpPVyniH57qeJE~~s`Yc@URvnFy z?iajKf~1vNS^s$_@52o5x67eFo%FZ&bZ`4dB3G;`mI|_eY8QN9fkPCoo;PU5R?0I{ zj{&S4C|M#axdKLzGegz1H{v`bwmzUc$9_7hFTOTvd%hpf7Ak{>KPo8fx>XlGJYl4` zVuI3GOua2K>=r5lL*CtzQtH~(^g4~~j^7rfZo=%j&b=sUFm5IO+(=~u!Y~gENwc@rYDO+1$cx|ZEb-}>t*l{{r0%ec z$((PYxLITrMqe&Crm3`*qQck*8Mmy_RZ65*40v>%KYhNvIU-4;Q)9T{#0D-=WWMe# zer!vPXMu^Ve>@$s-?UH|Kt|$P8=imN=*js#eD8g|zqjIhaV$)z;Cxf7gW`t?Fhr^$ z{~Vlm{el1L!$8~h!YBjJ>KRf3Q0ljlz@i`V+e(p8_4)u2|M`1-Nb&{uU8Nu1J4b|5 zYpA|-XYR7s6LuG3X4c1(4i~gUi6oX_miae?D30a8lB(`*sTJ1my{ieJApmetv7X?s^3L2I^%&qk zp;H-Pl?E)o0x(AQs`oI~kTe8ybXMvd7;817=9NmnZ9az{=ZYC(___RsSz7=B0e^6P zAjG1e-5;P1sfK7P6FX%s-gF{ecs!%=q&nKoRKC8F^f& z4>xnvIch4Z(ukfhssF+&pZGbGB^-BQX4*L9BVD`Ko1`5Cp=-j)=lG=-KYHS^^YJEv z?=mvOk(;#h-dn|5XJLO$FUY~=X{;k;c-HAlw37YrIrJOF#1A5nO>YQ#7d_~1z$YC2 z;Rr!?;M^KdhF=WegA&FPDc^q3F_2nWK_%y_Bfw9aH06@j8!%|C_vZ$xp(c+;K-B5g zpY#Y$>;y_GBM?fOx;eUMlndQ6e9pK<8>BL62owkGm4Hi&wsdbFDKv2pv$}y=6^_QW zZinEHNrUKAX}QVcNGrD|f^gYbV`k5VmyK+Y{$8!9ezX4=6x_ksIZdEQAgKD=!CHtP z{Q>N$g~)n`dXVq-WzGD3YgpS~tn1gMg^a(J$B$z#+duA4 z$0buP6{_eN7J%7&rZG;9EhJI@(kcf6?lt1?pSITx*`W^d|KMvxrzQz7j8wx82OzOz zJ*epw`(y9&1Z4vIH+E2+37L{qgp$NI1rF)e2YblqvkJxA;oBtO*KS9v-URItW#UgJ z-f546K{{LIgp&%MTQ$%!z|@1jzL9P0%?EXRI>8HRUpn00xiutdAO}kQDSf%k0Jqow zNiL7jlxd~4o!kA(j|Y3bwn;AIn~g|yS^0M!E80=eHs-6!AfDb+xYK`!^IvZnJwgosqW|R7V#JXzxr_BzJM(N-+cQwvO6t!T?Vu=hvT#fJvpzVHiKkdA$2log){ZFjt670!oK~|<`sywLI$Cfq$bj&Xig}^F{}wGM;n8FXs2nIy9DWl%g35+IZew5CoJQXAZ+P+mXL^Obj}YI7Al*O5RW5BEa<5 z0WOx+@pGk3{y#QWf#PidL&Y8i+(BVSy8b4r7l=}Y#!8<&>fqj*jiitK0T? zLuIOJLFSyeZx0ho9FeAFlgkzna}=|9mKp9@-PJ?DJ#-5FOZ>gd2cuB-)c2WVq6`SL zIMADrkDCIl5#MRBBfHUj*AtLsuFt*4bG`V%Mm%%+S!oZH*?%}(`Hv^>%duY#MJ3l{S}q5ae1BAT}DN3S9G-nP?HhkzN!l*JD=>xgd2&Yp%3Iy#1`R-vKtaCMA3nm{x z0u4xKPhJXP<4c`Xqjjq{YX#wERf9OsWu(e9nqi|fXn%;jZBTcGh}nn*k8CxURQ&-+ zmcGhM1?QyzHC{*Xg^MNC{%{&^l|QGg`S?7iugPGkl174IL!K={x`jHxw<&Hzecv6` z@~(9mAHj`?9m9@FA^lkMx}|6$Kar~(+*eS8$hXx99_rA%xXm%yZd04BsS>E98)}Be zlFZpI>=1NebSw!KzGq`aS!fG!$v?&D6yrLLBqKvCFPBua|O7lMd4Q8~@s zCexp1#SlGV2)KQ1Q>JC=9Q%zC7L&>|QPkX))%v_~;^a*9NmqQ^b++D+hTgBHi&UVS z$CL9?qn(TNVi*zZN2*|z*{4Lx`~`bBt_+DFVvus&!sJ($VY2~}MDv*hdC1T7Zt z$qR)dh;+_1C=c1i=}S?+bVzw7Wjtf`pwsVcj{RgLquR()#9|zY!WWD)-n2wl>u(;| zO;w)LAoY8)kLmZ;?oJgwoy_yhhv_pQ_@Ri ze{3Om@IqS)Q+hlj&D)8LhJT3c)7je0?3?n$_GDTqmS(V*2w1f`rl_zD&f#6QN5Wrn zO$fG}_iOlKmyuQJvF^cvM2q&^-EPFzUeNSoMG_tTyDL3RZ!Ep$7t!~&u0*#0AF*3^ zs}lIK!`1oN6)T+f`A2djAsLBu5Lq3pA5)9=U0w8)7pu7LzKYa^mIX#n&m@=#2`rS} zSIli*R%0fL(BLgPD}v`AG3kir|4f5tP-TXXn20w2O4HNG$2I3ONaa~6;KLS;x5Q6hCrLcFdn^=>f?!GK=$EJCWROgvRC%L4kdFO%rJv)7sC(Ux}R0Hq4$Evg^jBpQlGI;VQNvbrFx0c^N0Auzi&OykFJ$n<*zF?ny*AAs{AEwZ-W1P zyaRQcGj%$x4Q2JJ&cg3t;cjMPwd!YY9=AFail+YsBx-6LFT;4TqcUtut zG(81I^^_XgeR)pZ>;^;C`AAh>JS*z%DuRy_13NdCB3qY-`P7JB-0|rt{@}k^9f|5% zZr4hLtXn+wLX}ASi8oQ^D>4K<#`!o}NVCMuf(oDCjv!Cr5?#1X z;);1Qn?-`g?&F(q*jH(i{`no}oTy7R{Tns-o#49Xrn1h2h9W(f)=YR5>W@R3)^9~p zg^>FKe4yZk7R8zN!jmc0c zLTf&a=9dNHrf^X(1m0CuX_Qa!A;!KVRF)9H*``~uiSW_+3)oEurxG?{vahHA?0q%F zo8&~?`SN%1v3q!jBOec;lTh1yR63Z;7&Yas?q>9`&h*0ZIioZ;WNSHFAZ;5R3__a)-4wvJr42aL$cTCx{n4La7QmI9GY*V(zSFb)FsZQ%w2YCqrCB z!4XAzuitRPk~b51vRu;)Bt1`Lyb|lQlO>a#UJx0BY9v}^VSMc{S8A{=z4hq{vs zxiV!LzmQ^j)xfN3F%=uXVU{67J=wCajgJ_CfQoxcn`EacNbaRloPOy={Ssly&iTbU zzK=n;^CgV5;)bajY%|ydR}En;>2BrkJNA zTR=pyL(sZ%zk*hcB2($g^MH$L^;a#MUa?t3q}q-blWmb%FGkP0DKVVA-p;j9gu6$g zPWo7q13SgxWA^2)G?XGCVz~#j)!Ran@Rx@$#8sTSj9DHZ?iDm@><$i-{klj5}3^ zv=au2YU_6~*ih;@4EYW!j-9F4%zv3Z6G=+dGkWt=-C2ny;AKNF6Lj}g5w8$;zl>^9 zQ(1_=l7UKP*xIhHt2~k+VIN&`_Kp0@ae^?@5=*3&+}5?E00bjE@=K37N^!^40zbSK ziKL?o&zNC{?^V^!$5SnP!wF+bou&AuBg|36%vL;432Ur*=JAW{^a;gMZLnU*quWpN zX~-Y?zht`MuK$+BE@N&YCcCqbNheyoWDX4$w}SW;sXWR6zF!-2p2U1!FrjT$c42H_hrh~V4H z-$@_$5;Es(6cWeF+vZf03Bn7qoZ~jT%~Lu~a`t1tI$|Uixud#*I(4I+T?FM)3c3J_ zyHY+;{yRfo-IW{uyOmBl@3+$81xC-P<3>-gcQ)^?$kbGLl;a{ItW2c!SkCW*o zh8M-8$Pwkx9!D-~H)DMIsw*mYDP7a&c56C?>-dh|e15H&V{m}0jPu;9v|S0tm4HZv zkZ01p!>i;KEnpfJ3<>gwaW8Ikzk=U;M`p1;b~78kkqi-@i3|U&cZs{!z0bqk3CfbT zSlYs(>=F#H{XQ}ld%;;21y0F^vqX29WgnMjS6MPRcDi9YDa~V8se4B6cf7wZzAaVR z_a^CpZB#Tk$&&g&=Z;Q;iF6?+!bytu_HH8Zgz@d7ylKWQQ0#Qy=Rs$Im;(r@L&;ud-PcWMUL+l*=)Za zO?>jDH-@o+Sv@Q`jjVWGZ^*rZm0ovGL@2Qf`aDh0YEW>A(NXPybDlPVVs21Pu-?eO4D#Jx^6 z<%QR8?y$Nt;LJIXurB5gkI}ZzVsCgM>M~G19K#z#5)@KR(!g+4EGFUv9%+T?qFK=< z9@Z7hAue8~>|-UWiPIPV{ACTsvMRY!G)g-}i#gXU581ug%z5<=NL?jxQ~#cdZQ$)% zZslk0gU^c-3yoZbc*S->g0X4p`cmj zHedE&|C*T{GxEkmHM#dy<4yAo$sut)wvQIiI=Y(Yf4q;2@n+HR*~itIUL@6>9Yxeq z5+aXv4!;pZJQpl;m3e(1D!86I;erN^0)A_V?z|K|gXT6o*CSH4g<JPq$@7%|+tnmaV52T5m| zo4_UR1KF|S?J0G{T0z&`PjEo@yYN-zIDv9=4$OydA+sO z=A6X-Wujt681)|o+Ltkym;BdzN|I^^!@1k%Bk>n*T|3*k(JS~iweBJMcAUj%B1@C! zWM2%11;G^6b7U*i7}+dEvA9ZXBiSVfitt!o{@aV86|p+K@Irxu3Z8R}y26&u(QF)@ z#90XxEAQ|1O(kW=jgcNu^-ZFNLL__$tZex?qFG2brRwB&&A{%s_hS za95%!ld?{JPQ2eFRNu1f~tTRFF9Ju&8IqGo(b0r^alQtq*v~jaD~m=F1Pjn>AJ`!ZbF+#X3ixqo*X4az61`wUBS&5GP*aiX94ba7>e0mW~_6 zCz0a2XwR6R@^i;e^oLfs?wU@~G-VNMGLxWCQfz9MxG-Ihl)`fQy zBJ=DNGu6bO@np9d7$LVfjYd8m-H^e~7%E}tB)fj6p44+C$mls~y^-2=-J+&7H&%t& z;Hk=02e;G_em}0uwUKp7(ecJv*-q!toiFsG>vVomDz^_C_T|Ir&TRV>J58^6h0pF> z^YmtVOw^LcL;Bjs2e(z*mByC*{QAkxJZ=4GjQ~Tl?ebXeE$#gkbV`f6K|yOmgNmYTK@)mZH z?)y@@xXl{4RNEe3ve#I26Bkelz3Wr4Eu%gMq68=J$XrVVp?xtUnTN$!mH+VY0Wmf{ zOOkzi^rT+WMLBVrPPWaimzn+Ji{-~k7_=qcTeH@GXadOjx>Td`48{=0B+{<2&lp8(&FtZQ` zj=ONnoPoqkY0vN0qNaY7^?}>#EqMibAE$EvKZ2;CY@DP^x7x5?@YyW!*bINe-|my+aN~}^^)6x|*|5#` zR|0GlF>NWJ%@?+_q9xcnDwt=r-wAUdg<&H(o!1Q^H+Yk^72&ocT-A#&me0rj*=h z5rG~XqZF-wF_wH|SdGoKndib z(tM^Z^@izNH|mzAx9Gnd)@*d|RZAveWwDZsyOL3G$)ixK0SvdA2xH%5!~~M+T8F0? zV-IQ+ocxEX`6Cw}%1gIN1=KX|h{&E{K=jkc##?wipa4u+ZQve7g}cADS%{H# z$y*!yklzpPbt_CY*5=3tBAZviE_2jYh@iblwNbD7wEq%AS^mz3YznyinwY6+ML?8` zlWd`bCCPhz4$m>P=J87jk&HD5h^%#D1f`*7JjvVF2q~?LvOOcmZ$wvYVaGbdD-9M@ zW{{5g%v`B|;-BwTKil%!K5?7Li9?$ceZW`kC5v_xOW!k{Jny*Bk5pq%n(Um@Mx4Mi zpPf4z_h}RQQm)LWguEl*9Um9m%Uh}dcb};U#M-=qlF>LtK@c!uUlATpw*H~GVu%h) zY)2#WwP2xgE%2`D326(LZ91g1+-_&(8+P;Zylb(~7|$o%dsHG}rngqMU87aAmN_jF ziC=vt7EQP}7GG|hGV2;EFV}eN<*dxy?#mAtkiIaglbWUn_(%^lVRK9tAQfl+hsscZ{(r00v!loz>pW3iY)vZaTPDu% z^o0hFA&iZQ+ESs(+wiFL;^`Y#O10pr=ZO!nQ5SnM?{gus7qrlIQ17SQVwDdh=Tg6- zmlp3j*?sX>^7(HPz=)?HP7_cX7d zBY%b|=PGZZ4ApaQtw=W9`&ZuiJ5yC`j?)8#N1Qbj=`0rJcX|CVA`@nQ_ zx&Io^JvM@Lo(puPIaqJSsn$MT9@l=K(9;^^$=w{sAg zy64`82R|I$k@t^Q4}yC%G-|sdqo43W$pQ3eHYoYjzLWKdr7iF zdU-=&>l_8LYYnDK>aD~XjgZR5xIzI^Hq?dObQ5emGPD|yK?|uN9Ij2KL;V=XrPS*! z6sD@n=Wlqr%H#HYF^pyFL9E{M=)j9dB6=N}otfa=E5(2{glKt28YYzgl1_DkN?F4# zQsqX4aYS9+?ZHB}as8b1+Y(Qn2{!cdAax<3>od(IJbgJjUcrq@MzcNf8a0a2;^vqU zGH@JBUA5T_LE1$-suDCV%&L6$=4*70#A#Kf1Twm`4|{`&Stw>Gt=C?p#D~e)SPiMVr~VBGBb_wR+!xVC@Kw)4P6i z3v-<8XByca#s6xqe){yjg3tbj}h?-whn-=o+2V; zx+P=vQGq~vF5iw*p@2ZZx1y!3pud8O0UW226IT^xl#-VKK6>f`wqb^RGWF=cO!50) z20oq2^zGBBOg}!I`se#uPIUiwI*i{w!3v>v0fdBv1WMF`W}WLFsM*P4==kvVqk|_~W%6_QF2F3%Y8W%kpyR_`A~-`7lu16xdO-{a ztBpn#fiJ19yiH`SP4zr$gh8N6k`q=ZrYReDo1GF)K0fyBmmtY;cInG5H-~6ywWRM= zFQ2`!4Kr%>d?atqwiVXns*|u`s#K09GJEBQRvL_29lf-OyiszL$-@YkPoEoMuqfqH z`8h6=8(y=K$o2{3Uwx~(G*dG7a&Dc8{}yYMfT|5 zool_KjTr}$5Fmz0B2S#2iiKxG#lY*NR^&~xI{!|cq&`w3n@ls1M7DAaBq?F^tVED3 zD}d3VK#-f*it=uER--GaAbQ)}UT*GQ=;XqxpH~${5GnH=`JgOP=82`7@AYHUkRXwY2`g`) zR`b*M(-$GJw|0}_nCtf*Sn%_rQoeRs?>uIbX7#uOD&{Nv&<+{9FRNpo!{aci&lvUI z(j}EOzl*D7`LOBY;!^##yBnd0HI0~rKKwmQ^#$KN*~!?C=<-{5VGNcAD7;0{2V-C6 z3HQU{XU;8ReB9?H>x~YdFWw@u=>CXq zbYLNRKh*bA)qAe9AFz$KD6k58LNwlXrq8LhCykRHaI6K`mPQX6PlRXuAAuBY9#j`|`-3}=D&iGEQk5@*K6ct-M) z9D|a+V#=9T@8HIOk5}6-F_DNfOsE!NvNwjU^;|;efg3vDkJMie$xyl}T9=N)~GvHa1Z%j&xDB?@Q_r?#qn> zkqDP{>5U9LZK;~Bv95Uee(nknkR8TDl!;3Ahu>}~Q0BgP$%}t-yMz$l$7PmpAtUM@ zmCVhxYyu6Mfm_Y|PtSC~Vhn}dlDyTpsnn<4SS+0PdY;72SLzKX`JCA0Ppq9u=H7T2 z&o!?V)m+x$C;2qa?a0|cK<0gSur%at9s9GXxj1rINivR5N7(w6S+u&Ve%P**v@<1S z9FeW_w?b24`qiw=0zW;|0vSZhZfd#Hs(D-II`YkNaWPQMS;1tQkfPr)w6}gJ6dnBb zCN`}9%zDp-0A`{0UQ(bbRL5oa(gE^ogzoq>hmFi~8xoGqln?^^pg3NF!+qDI%d z9u#d&HN|7Wdp8?8kUfVj%MW?jT^9>8mjVCy$zq}62*y=e3kNY%KE)J%j4TRkiZj#t z_HcwM`Yiv=M!^)t);Z_xTOoas^~MdL->2eq@?BdOHF!(H-zvKqukL0XGwZ{AC; z9cCpC2M64$S+#Osri;BiA1ho3Q_2dAN-@ZM{rv}OUJ+RwC%T)$RQgMk_BU&)W@eN# z9K^m@pMLMshh_pt3NivunksTB<9mut+e?RT~s8D01AOQ|0(F1>z`+7xM z^aPk2aw9z~?;=c0dloJx-$EOSak^RJs4-m3F8(1sq*GN)^&V<-0PRggM#Ek@)(Fo1 zRWy<5?!19;;r_8ccKk*)ezefnS@tp>k6y-hD$rv0W1_<;=I@**P^L8jTZLcL`A|%R zmXp25B1Zh2Gpvyb|FejtU5r`h!nR)+b;)($vEyrO)`?tgvliBuGzR8ExQC+)_Zv84 zvF{_$G~IUFs26&pGDgg+zaLHznsbd04S!jI)~y_I5SCA@hia)C^*upryYMCbm+zuC zOldMf;vkIX2RTo7SZJ&Ao+L^AB1%~YpJLUOWgOuL+Q>1L+eZGXUWEH z*XJ57^}_dE(ykQs_b~BJO*2PgnI)9mf(dV@47git35YVMa;6GSBOo+!M% zJASDd<_>GEm$w`_Y}>^NLVE`qp_Ce=&%O-4v(tnDM4%b!+ohDDIW zt>}iJyM5Nad%kd=0Dt@=efZ#96vjl{Zu@7NP^`Ci^{9zCyqXZ%YQwVT$#?1M3#vvu z&lmBa2W(t)K|?uj#YCy`_%-U<*(yIfZxK>feQfbJtOaqqCUCjPK7{TUcOSoIK;r7* zGGoso;;VNxzffrBy%8;qe%>=;4n97nqR-SgnM}}TDlQ=hDSTyzJ#C5Ei`RgalC)g5 z?xF3(wzn9(q(OZfBDqnQ5JtW&i61W3S#I1_8bdaH2Uy-OVd0tuFuaI{XZ&k@B^z17 zIX^zP!SjP@D<2=5PlV%KMUZE_<#5ovESoQw&UDx1EbzsvwT;x><|)FQ*f?cB$_*#) z9Xsx*Yv%VRgr}MiR0Uw>@IK)@$GrbkVHyUmXveU-MbeC75ZM_?4Rq9`)0GBGlODW1>v~2>n|D}%dM!Z~1pI!5`{vIX84?uM(r z&z!2P86WupqCnTSa8xYz^9xeX&WSw|0tdw)f1YF55m7N`pztVmYm|W__)LN`Yn=RbOqrF%swb$uQan zlj0N}j8yj+jEAV?)3Icqg4O~I!>qu_SR!(68jNZ8ke>U(d@L(%3%+HzUnRrxr8Td_ zIw3u%#fOIHQC?=u7UudZ6Lwkr5VByngl6*0#F)oZ^<5B9IMGY<*troy?$P*aFUd~GbT?q1<@6F1#w@lJB*Ia zuBTpGzuT67?(rur()m~GBe~j@<|vc-HXmklp4oVe$fc!FX=h%|EADecBWb#nn5`T^ zJk!0|u6&i0D?jS`%_lF0Dt%q~bu2o(MVY{lEMlb|M=*zcgecN%DZL3>-(zOlNP<|+&+>~6%AJMpp6KVIc0B4 zUs;SOPFLE1HAgtfbS3)i;DyIX4@GGQ%V6=O2zGkkf!a4dyr?rabLrSH=jj4NgL7e8f{)bdOaal~0y>DZ)Hk6Hcr|PEJ%`UXu%^CO396t!m&+1XJ&;EamO- zY16!@g4U~+jSVD3kG7GDpJ3FyO^Zl(CYs@mG+9!62H%VH7-QB8$F(OGsrAx3gNX#P zB@%-v0~uYWpv*oTmwt4G?YiLtzVNC0+T{o_;|>9`6t2SkE6d#2g~d^~ZnnLnN$obi zJ{q`ZyZ=J|94xOX zdc7lu(5S?pyd7bP5SFNA$TjKEIs$zNO)o1or^2*M)~18f?YvQc-(5j5KH?kA;O3(qrrna z;O+~=bWbauek#H8dD}*d6@iFJD#P*$>Dgyk&36?R%mN{|jO*{A@_J?7O#s#5!7BpLkrhy3b>|lc3Wngbb zum67Xo6^hRG%PVu2h?g@m>#jZCEC=j>x-A6rMY_JLogx zyOc6zdpT+t%Jf&pRpZ;U3a+9ZU)+Uf_k1>P=NO9UT@g2@xk1b*7JMgo%;Id2bmU}p zJ}XQQ_x0ut9jbM?H#WL4gwJ%nbIZo_{s$ZEz3%02G~ z$|sT!l8-*~y!CFuX!NOZu!=Ufj#Kv&)S%g%2|y)VJoj)!`Hgi$_< zQpV-hUvVs!JyWH|)+71~LFS&+m@;yUW6+)9hXxk8&N$0@g_YtmVRJKr(H{ zZ-vf~Ge~P^xDU_Vj*}oO9K#-yC0Nb>;_2aOTdz5~;M_G=an^RV{Hh3b_%@mCg(94q z^bkec8q^I!!oBm?GRofW(PM9io0N?-+FM64Qb}*;3skz1yqJ|-i+fX{fz@ft{9>2w z0}qPx(|%^0>N3$yPtyah9v(r#ow>@%FR^z&cHG#tNkeB#B0MLE9>_8|f<}T9W~{e) z|Bl88ZzPQ$o%}5e&sz$`37aX`#<_MoF;cC|IMNjzu@1soxXN?GI^aqj6)Pr_xzL7U zGE#U6S)=%`VmX(VehvpV`Rr~RdVxJLHa(dXh)0^vUXs*CJvtx!+IRmpn zps>MPy6EY3re1aG?Dkekbw*NfV^b z%%!G`8Xz;I2;aGb7=#ma?ndT?v;*xO=}*Zj7(gt9&%k&H!Dv5>qJ1iGa zu3)Qen3IHj_Dtk46?>F^Cv!1VfL@h)XooD(O0R&2#{i`8>;rl6I6{Q>?O6M`GC@(Q zT7LHDm$Z`E5?E`Udt2gW{oTmX`X4$!S$&Mz(hw8-tg=X@g*&aRC8iLL>Xx>X%lb-X zpIp8aLP=tDT6qnrQF}a70ON`&L4(gG-|)~pZ5dOWtY`0&;@R7!WEynWY<8E^vHgWy z=S4;f;Lu5PkWxG1qzkwivR@L8~^CRY^Lw*8#H^B9T-YD zLJ#Ba*%&3El+L7tTDfv8=9?iaH)FR77{cbZ$j~h4(Cnhh*ry)&-3XRlr^Ks}NN9oW zwsXZUYak^Q$Wg;EpVeKX6qwZJA4kG9FJ9SUPO|a4%;{_Kek;ktZ~P(^#`Tr^p;<}w z9a)5+qEW5v7w7K?nXbL6SBMFYd59YENFZB9!bm}36<%QJsf){&i)$ri)UIi>Y@J1L za7&uwEBsd}lpn1z%d}!{h92;pQ-SgLz>KezQ9;?PzihsXYmjnl{`36QK6T?Df_0oj zB}PC^O@}4t3e(vak~h!TqH9M7hCK>yMK%fWw?9ai5y)t;8bN25$wY%iuP==+t#b43 zs(B&VRzHz#bRWi%wAol8T3&RyV1(vXO3K;gg~iG|%g)(E%X(g}$Md^=@TQ)oCBBU| z&YSNq7M$g>m6M*8f5O_8*0o0lA}0NEX2qgG-6)BU<{~YFD)JtY$@nEMdk6W8!wdUi z3z+D7I4lMO=ng``a>^*UFP)X@c-*a~u3r$==(S$Z#_eM0?BBR=vIw&t`VD_9I>2Nai*EM{`PD38c@M6Tw3Q#tI|UD18qcN#htn z+M@oq&u-(Ij8@NKQ%5P9gslXBiePvPdiCB_rWnqL;WPP$)m^W^d^J<6xM5X4lWw$S zJf8_!$pNr8F8@1sn_zrU>-x&8jTpm$ckl#W*9dj*<`24DUzQy>P8^&tfOBZkY(8 zFC(ut_G{oF8O@45FJ$&Y6f=X#h6Fcg=DxV03D+k*m!-;9o+|%gsy?QG_=pdvG>Q(q1=x zjgF$mSRj`^a+_B0bM!TsE5j|h<5$hkMPXIbv@Y_azjjbbzqLiTdr?L4jec~7iJn;* zTkOO4%jz^wlqQ!$2{}ZI-w()mzTwhJVwZcE`B;-T=E?aoM9@8x+4YjybWMtqcNsGr z-k9)JhDu<66Pw$*Rn+FAz~k%Mj>U2>bI#Dbe@eHrCV*#H+8y_ePb@Fcg&?kvtKFktmyxm7+gvA0}%W{%EusowLUZ5i7Q zKdG~tX<1Flk%}4I7hc*@`&eJ#WWvt}_RG?AMpsANfVb&`O8o>S6XQio8C|&YuRrvt zrFre9cLB#HP$75Pw&{MEj&X-|>q65gqg`G9nz_F9y#Ws{aAYyU-WP?jQD^<`32^H;qIudn8GrTy)`QiX2>ko z!Hu(fFLvc{vEl<9(JrlxK4W~?SYJ76Y>cKJo9LcKj;O>pbXVcg>vs$9#qTsE(lnG* z4XSY~`*_S!@As#=&=;-+NrhLfRk< zSC})OC5_QD7GN9cflduO^_XK{5GBB_g;Eo~t(mdMKK4C#LD-YHJKd zctPnr?lTv@F!qx^1&GzwxJx)y6(bmKo zN*{*_L+hjQbcFw^kBdK){ng2^fcQR6A4XQrj!s|)a~tT;JIpd06jAk)69u~%SUDSf zeG$lUMx=(KpZOR1#^#Pr1~x|EW3>#Klz+P*Ubk=@Ndp@LD|bh8$7AV1tAG~BrhnAy zPkP4YCMIA9u#J=X-&Mf$gWa!ob3YM%a~mhHsl(rCvqRBtIyG%m182wMwF4c6xIn7@ zyLL>RZH)fv8PICcKM`R&TPt@PTWfOztK*rbgHp?r6VZ0GwQ>PF98VWIz(1XcF2s}$ z0ONl*CJ7YRB522`8VHl)b3Syk@cApPuUrBl4HYRPhw?piaccZ4Q3nGX%fBTcS}36r z(f=m&3G><|D6;Z@C2MZ;HJ<;HdZ7I(@~>2lY#kiHC$Ky;-Lb#YH3mBxIhX^lVRAV> zRWd_qf$Hqvl>1-05aU64!||oV{#3*rovp169Ndqk&kDtS{i*0%+gbz3`B?JMj)w^x z*7{>&`xpeHedsXW2r$$T-0&YAhpxM+z@CZ{=y-2 z;vGIQO%rn`r@uurIh6F&n8zp;Xp8Nvz;00DA8s&-p~x8@N6yyx_)vh>Wb)rg+1T1R zIsruzQ90pNsV=k{vZN78UQ*xY?H%EB>TbS*Z#x& zIGRAr8`~b=<3dx*I*yv1gSj>MczH>oczbsoHCrIv9nTuH@+i(7r@XJkjtIbahZeKY zS;FM+Gy%ssg6v_>VS$o6?=)mxz(!8C$7c;5DC#@^K;6Q?$kx!@;P_MrErc?#82@7i z{bsyhx^V>F8u*vg2Q5U(KTro6Xk+ugl>u%jU2XjXj13Tp4(2XUnc{E^LKk>BV3Xx9 zs&ck5cQJ4PRu{)-HA*P%qmHBd>&1=7l`rVNY2ai8|GIRAE(=81$B2Jal{u_U=nAHD z5^`2x14k!EduIcnhC^BEaAZQ4oUG$$8=Kf2OA30SI&~Z=69WS!?Ia@(9d6*~zl!MQnh$z^`$ja97a9KQ@ z*`X=3;2xvRpW-{(nE{~=J_$0;fQw(EA-L!rsHos#@-yJN@e1rOLp|6{89 zsTZ)bk(IeI_%HS1GL&8nPf6Ly%mMtDjXh}16rC2}Z`+-mQ2fIJd&j5I%vZbq=I_TF zSN)V2zZv&1d1fdP9-WB1odNJJU&yNBa6}y@4qdU=PEQzv2#zts z*S5plU8RCUh*>o|yIt z8y9HSYfenw6l? z6#ZWoAtU6OE4(UluprP9Fzc58$shy)SMsC?@?fANaImD32WGgoHd4lrVUmeC*g+K7 z7c&4xKei6PV?(5SFPSeG1z;8eKLIH03F(t!OMnfWoE^YYHbAxg`uhGqV1>3P3MT*< zgTU|CLK!0Gq|8aN)a;CbRjlyW<<0LBLA0s67DO@y82cO?2zZ+3*H!F4EqhXwZ(5{M z0orqjKwm4qqJyoQ`_Yg}AtXqmfB`=OkP^QT0l~NxP7e9afG5F(7!D>Am7fj3Oaz=p z5DIfe>7;8>0vJd;CF%96%au`uVQ~ryHm07wWz4t+SvlT zcXnpxM&b?*whofOYyi#(KTLAJ7kVJqS`130EH*q;VIFS0q44e$q%^jV8 zrjny^gG|~ZoB=aKrU^hk{CO4oSG%4bSIq{J|Bc1IpMj7w0LD3PM+4KHJI@vc2)h6n zUG66=#NfHUrw4|7!v(UwlQ6ddb~34c{Oi%s$q4?Ml>p=c@Pp2rmHwxP26TM_JqIS! z+%N$`DhJTD7?ik+H%^cFL%wg~9xWv(soBIBaA#v+#tm)RhQQM!s#x3FI++2c1>EW{ zt}OTRdVM~SvjUD|z&%>KwQ3C_TnHf0D?q#aP@tsICk6ew)$zSJ0fAy;dNdRa^IpjZAX4}N_fdp` zs!#l9s1sMfLOl!QRRDbv&@i-i8B$J){(G+`0qhmqI=EA@9WAnvF84)aATb02{tF!~ z_tQ=a`t_)rjI9}K7x`%TiP;7RN?coR@Vfcv)Z^50Ug6+97PJKNR1mgst=%0Qwey zuJTiKNG_JoITiZfg#Qx*<(H7e;{f1V;0NtwGta0-G1m(M9>} zRJh-x>-gmnq>X+SoPQhQ-gkd@?`As%htzho1BmR3`7Ag*hHYy#cbZC9NN{cB?f z6bMIi6?0Q-TXSPEu#tiLk03i**`|Yd_j3W!a{$qy*V$Edrw12zvxDR_$ddO2*t8+f zA`}5^TtIMW?CHi+VIQmZqvbZIxH7{4U{3>bivte+<0|%l+I&*%A3GRSiU#Hm-wLIe zt+SyO_-M$bd!=I#FS`doLT3^Awv$5sxl|pIJ0UB7ffpXe*}w`BnFa*}U5Q`ywJTa1t959P?R0NP9 zzn_Ry;?{Of?%)4a1=wE)4p|?uK?Gq#`?`gDAi#zPz{an+AA}9T^%Jx46Zm(fLNEyW zk)?3~3>F~dB%nm4-8?bIpF}+(;vf$DiGrI>8^GiP92VHB{CO4o7k@r6<{?8;DcSRQwwefMD6c4_b}WbSFmqE|tNNr4NF#y&Gwi4=i6M0S|>v zZbS4ZM*$iO2cWC@j`q7ekT~FNE>(5}T!IFuc~VdY`^b1=Bspg*C-YOO5oX}h0i>0A z1wca&L`K+74126#FVxLkivblbLQ)HqU|}4`Bm8{iNBqYbk{=sjN2@UBfSbDF|- zQV!P%kwneFhVG7LV3*^O^xu1_Rsl#$zae$2Vd;_Q0s_N1=>3()|Q@j_XuQs9JGKLCIt>j+Gdj<(Z6 z0QsyDAk%w5CSYv$^D6fLBzQs`Q3D%8u!Doa54@v+FaQz^B!*w7cObg!mpnbl<)gF*Nqg~= zV~!UA7_;ACyk$-g!+8`8#7K_uWuQ2~IKa9TBm`w7RQZ#@{4&kAz4sp~{9ShtwDEl8 zclQC50^kQ7Naqz!f~E?b8UA*{_jsJdRwdnc0LBBr$Dtb-bj6e4i2Zt05vYK_Wc)KK z#ALS=r;8w?G;yH+g?2wPrIVokp#IJMxPMn61O!F3kdzt#sRDc)y1dJ%o*snt2o#8+ z-c*5n8vzAECKe*V@5fc_KcIdRl&|&nyQ$Q_9=`t}+|g1^*Umf}1w7pu*usaF3R&|c zct5CrPe@!xqjZa5rAq+1WBx5aNb8;+h39CH;B4MiJOIS=Hv?_xogRdh{b-bU7Un?| zAbU>(z6Kphj)wn$!uh9-@jK!^_-jBEjr~?B-hoe#^9Q@Y>J|h`002|J3BzZ0dJtCb zqmmsYcD^KEDRu<*A#o`{AdVj{4g6W`zi4@CoTKgXY7Pnc4iRuzLFe%Lw9fG)5QiU< zRsqhnID)T!e=6g5Oh~Z8Y?ZB50Akz#>~tMUtcJV)g83`oLFe@UWW^&-+CX?Y_(1V& z1PJ71VCi^hE8_mY@B$1R&7HtMkbxEJkAH+bMQ-arb@^zO3=}6e?*blW1ngl!vtb_n z|AUPqb`BugFjtHnSp_Vz3s^=I$};cc|AmcTmidnwfC}{^{r#>Ch}(M)PZlQu83_pp zFX(D$l=v@P{P4!(QPUo_6m z7gRCGV@klJ-vtcpeK{LJPJmHCM$*854>)KFc2F?10Lt6%dWZ1RAN&4b53u?!Pt;>Vx1WCudJPzQ*AE?35 zM{w|#|Am_)obag94}rdM&Y}^b2rK{|Iu;p$!v=rc()_vNHU70C`1-K;FLV6I3_vD6 zi5e*Vb2iA3fK?Fg;Ujm&K&y3nUj9-ekB-ZBG_4yp-MjtCGr>I7*AW3!2S5Sp zP$BAe<|L^9eeI1D@T|huVkHX(o~$r-0AGc?t48Yki*bN<>4-iBk~D9Ayjv3kc;q?E z!$}hkVD0Y)_%9FNUXSyG0ZHK0ts?MHjydEd5X#O#tMct2&e2ZU=d;&T2&|j#0Vg7% z_j)NY|BVk314r<&un_TYeGq1U1sGi(=oV$6Odx~vZ?KYJ2Wy~j{VVb%TZ)EhK;XjP zhCC06{|)(v;*W)fWJFa=lsAygZC+qs9r^^&Ct#-iFE&5qY{yzUI>JbC73k3(0i{40 zO68)o|AwyOZvAby@DLkEd)hv3XQMtKJszNVXiqC<{5Sj)!8RfiNIe8RjTBHiaHjm{ zRqP)M9CJUN(*G9hzY7lW^$#9*n`i-#gS-Pw{3kwS4V=z%S`L(Lt%1#E(_i`JXvpLc zxd(oLu91I(6cjuyq>8z`S2^%_O*m%Ep(xka_&dE6^@b>!m*Z0q^ z>wKPDpZjrJ^`1IYDYD2wW}WzU-KOVI>}HsjC+DSFB@~CM3q`48)y}Ik@#v{uH?Z4F zBYus!v^g|c9wEc0%k}-#Q$!|$$W!+oj2VL610HYi>$K(3 zpadeVNSl!2!mUhbv8D8ta`L4aHagfDpA8>j>lZM)gfkM4)UW_NLog_j+?#Sd0O#pSf%esHiV3}RZGuq%h( zBXl?(jS;$he^Sg)RfM+2m^$&|jOu+qnn;S`;P5Ht?88+t{Ioi~5JC3X*eL$LFGxuc zgCjPLP=|;xN!UWOBc`4gqJ#G$^+F(@w*Zh4VptKAaU2sRoV^4E$MhrC6@W&3PZ6bhHxLI&yT zM8%7@>cPog;g_4F8zze6`*VA42}_KybmZcg5(}FATN{=?j{zPJnHTfbVRVK_al}5q zc3oFNTR*^~eV8|oS*8jBZRyO|fNb0RAjFYzEw6;2pDF4<%> zk4C=Vjf0q*P>A_6cHA0OY!VeW21d#fPc9$dHwZ3L9t!69D0YJ?A{^e3C~+ck&XfMX zi|5sXo76%2OXbzV9gUNyM+kCvzHcpTn_7f8VN-9f zE~F2zMCIb1gV6}@%sf;47irma^0coD@%xn`tHlB7=FeC2{DR?wqA}6haRON3Kt{% zswzaF-Y8XC{upd{Af6NdyQYc(lZzYt+Ofe+f<>cn;SE)UV2#89`4Rd0<`wTb+G2J| zh1ZHc0_j{jeC_aiT z_dpfG2iGl1xa|ERA$7#d;={kIVpwK=;`I`})6{C`b2LO$@Bv5tDyKqipDrq4Al+cCD5UIJV#l|$C3*lt74>%h-53$=Dv@w zhzoTJJ(&ujPz1$Etjg)DG}%Z=MOZDyzfi@X94{V`b62!6ra)(JFp}isue`5SA#A0* zIA;IIjOSNjv_cOX@exDy_o^_qk+-aUo|SJnQe1a_9vRfwhn!AasBY^$?usMsrB{bQ zA`nMx4%lF(;toqvPF>f?OzIHu0Ey|n(8_C$&A=#bD}MPglm=OpFdQeBUDsX_Z7XfL z0cmL6kEfe@S(T7%Ur(JAm5}Fb?HNa=K^C0jcXH_g*f1*}nZEK{%qgqQIp|&EU+TwD z=y72TIh0_Wgb|q^p|iMmns!@H!q7PizRmY!E+v$-bqyO&=xCHb@A*IXxC+K7NW}B! zk=#l+p<0bTP^Z;LDFKrD@)oSNpC)}0;0t{IB2Qi=K=!Il+6y;U*RXCCY@?Ov_A=Z% zR)N?aNPL0#WBW--PR4a=@*d)nEwT%?^(RN>Rmuof{)8aQwXTx0-Ru5)(LWES)^+eWzQf{1UH4mLvwK?&t`;-IXvHm0Rv1}f zUHd7p!c&12^v&Jpr&>W`Nzt&p_V|mCd2CVVI>Y$or!vLuUZhUMV(JE}38dWC>Qjkg z`_w3xbo{Am9zSUIU*t~gs5B$sRJKGSAd+0yFXzV3yvGtHx!K;(Pv+{dRHR^qtJ zNw2<}#7l?n9h5L_!llNrNRlR(&A#f&-+w@z>tImcDJ=?9Lg9NmH$%24<;Ze6c5_ zA14Nv6*hQnqxG}k1G$GSr^md^ow?nkEK z^TJmKsUfx3#^BU-f-4njh79aC1Smaxm2VhpH$)A}S%sd#T63(_g|kIg4fMmJjK?uR zeQid=-<0GQ!#)WrF`;lEIe74QupDi=QLveNyTqADKS)%aS9IMF)fC&m>D6 zrG`Z6OiMaaMDmp_L4)-}A=i)jobLmO8KZ`X!X^<1=(SQTlCI9nkGczxif%gKu^uu- z4J%DD9`#aelC$T$UTg2dXL3STzTt1tR5fhd&bRjV!IKn~ByKpW;;?Oy_6_XGsjt3u zhngn26qRJXV$MGNCSpGmwi@#IFE>jKHB=Xc6z($q{Z}>W^AN)A2Fi~)Y+oEDlka{L zQeQ%~hDIo^;l(ahDcMM)HS~cK#>0*Qg3j^CVl_Y?y&kJ8Q9vb97b)x<3HEJDjVnHo zt~hGrPE5Kz%T&Px+a;Ad?vxi1cTh!n?1hGT8DV3Ko|Gb!o8{R#Uxht^>-)s*DXAz5M4N05b%x+UKE?>l?yLF;*@GZwYATCmOu-x zpam^h3x0a7rUk9^m_|10Toyh z6FqnHZsqq?0_Zu@AD;&t3 z)wdy77iltD9{SYc0U^2(149u<8;CW7B5u+d-Nr#EbHY#)bYabiE2X{}sXp&)2fCd; z^$d!zOdw@s8htzOAdIIg<2YLcYem1R>RVxbxdPC%szIV*Qkh`vU;8R`A>+V7cqT}w zqrN@uv;%M~0uNWoWrF6_R|h~|k8j`;flLj)_0?mM{wx_tTJ_`r+IH>t-v=)frfzu; zeyg#1rb<0$nb&giW>ii&Q8@)MfxW%e!`m9Q*0c7m^KHP4ulME7hU&h6^W;%QDQ5WIOo=iIfpzk0A@&z{g?YQuH#>|IFX+|;dysK+|= zXK6YY%hu%HM_(Pu{|{9C1<>)#z2k>}CbWaOJssK>mS~FBL}~-{+BmFEiT7;_Y7J?U zy)X(5gL9#kZlwCw*^+viRvelpYyhd}*BMK8MIhh&hv_I@?M$4jz5x!>t7t>>3)kLt zgo!o^5`k%%`ZkDWAWw;v>+79M6gdKH2UIzonRocCRF8HLU%b!~x51)ntE*AZPFGLx zDZvSNCPaP!rL)%#sO!9JPM~D>(aV48gw28GPob3IyW}*}ODCfK9=|l4gTWlO z7CM!d-dog@(}-|*2P=5umJ_X+ZiExpe0+xahx4HoG)uwjn_k#=t5$yd-b7_1%2g%i ztX&7QcgN6<&rtlmO+DQ8Kto*o*|R(U_&2?qKQdzlD*JW$lL+SJ| z9Pbc@?@><{4|$PY7S#8Dm1k5z^7(P_c|MKM8gCn@wRxJT-1F-Ci>rL-yy&sn(E*=C zzUA~j2i4Pgtf#d_Ozk9l^*pWn8DQ*%ke|EUA1Bn)(|BBVYt)I$-|$%9q+EqOJO=5V zN48f^sc(Ul{4TpaQpB5VNvoS8-R95feDQ=HFBGYD0$VfE6e4AS|E{*Vcpcmt%Dq5(|~QPS^sLyx0ioK$I}^>2w+z5`sg;=1{F$6$a7O?d(j56Y(Vm< zl&>;mQtfbZhL>``i8Ze-#5*b;o@fcT_lnHwTj6-NAkFq-Y^pRztmyYD7F^+QuS!<+ zY;k)_tZmiq+H5`UlkxZ(DZeqZca9uN&^FVi?oX7U7@D;hgM(QfM`2<<4}L3`8x+w; z0mzl^UFmrV*MoZe0uOG)q^XT5Df!&RrI9F%S7yr`iK}ots5s_FkCF?hhcuCzVO(AN ztno0(0C{|wES(E0!8p30lC_Fv&peiA0E^CJ^Essncok1lceohG?4_eJ8;>M;`C>UH z4o~jk#++!}pMs6w7VpP@5|4fThRc8Byq3pexStObGD9)NP@fo+7Pm3@8L_#+HE!LY zGyP@(2Rk`UBk4*i#4-4!Z9f&FPxS!^E6O4;+Jol zn2SdkT#JYE1^rN8c!gU3`sicuoV+1?nWwUv_E;WajsMxP24 z>W?Iv_h;w&qhPSy&>zqAQC}$Kbku1RTtB7v-}p=q>7|O(a6vv%8{(~$!lm(qGp0U{ zhPN%nWt&*FVw=6G&d9Bm!_Q5sNKZyuEM>kuVK_+Xp+(-q)D2WlYUf&s>)Ldmwgod! z88Q9Em&XgYl7mF1J!I$fa-UFj6vw;E9lgC30<}Tc+?|D0{ZJJwi6_bwKEg;1$vk<> zqBZcELnyj=LWvJo(U7#4#VqfiN<64Xz^8+=v@HV3n+sfZd^Z(9Daj=qC|#YZKlT8% zH5{ll(|3`cDyUAjm4B6S+@ic4)N(=FeErWa5B|c!?ukk`N6i@Lv2Dq97ZhmH_D@9lC329I)KvDHe~;dT1OAL6fhU-v z6XiawGo)@+@WO+4hR(4%vq75_-Vqg;Pz(yQ@a16-a51|Fw$D5Dq!H7VvuuSWail8d zKHn@WGz{*2p}cc${&|LS5)mZo9#Y+-{nLK#4@ikp&aW7+MG@=TDru_gD6TI8yl*+` z$T&=c?Zm_bA6^Vys~iww(00}&`524?MCNzNEKPqs`^^rxfL2f^>Qj_s9L*v$KZ*0~ zr+4$`L7d3^&ib10gK|!gxV}h`s77(s?xM2pi%{W-ZS-N~02GFi#z80zanG7IiV7)l zB8fDj%i@e(5&SQZPI*st4STeex`2-!VYc)1PJz`ySCV%hy@5_Scky+8Fh5M%28<0by}E6I@Ul z`1b6CqT7($Xy%1W7Kc03l&aFf*`;zr@1;3kRe;TCx-HeQANb5Z>=8NP3#Loe#lVPH=V`Fb5FmT z9SN!l+ueANzP5xKvK(jK-y@?+Ax~w7PI*u#R#3x99m~2_DFyZ9gDK~5>!b(0-w?o5 znxUo|U>m%bq0#Fdfnq^GRt%foVurW1rqTk zq66M?ACJ-|M4EK*^d6U&?I2K?O^s;_loa@un?;4>Tfl_EUt;EixOWNo`|P^R2U-35E*O2&C`Q%{?2OuG<}Gpi=UY}{4zvs z2p>RkVE;);HuqM8?ySYTI%aKD0Ot7;ExnMCN3quWL&K$Xkz5>s0Am#YPOqJZu{?laPxh-*IV z-Jb1>p!ut)0(i~+bb@Mnur^BaKKaRy7In!FF$ z^ZD*E(^b5>(ZYV~DlQByi z$g)L+<)4lg`VRF#(^CfjDz4N58&oqTFLZ6Zc58zuD77w@M0mkbaI0#Hlu{*zZRg8; z?Mnki?D=)d3@`9b8;@qCzg!GE{|vxtW~ zf<d-^X4j{yc})^>NYiiL!%%Pz@mnDM67FM zdRY|GRe*HdS@s0G0qYp6Gf74uIg7c=oIbRpCo2TxvxNSkZtxtlny0@GPhv}7*X2{a zda2#;(>c&9&u^x1H_$;^BpNf0V~e{E3HwL0QZH#uZz<9ZzYbt=cQwQ?hbd7vX6_0s zN<23fHV(v`3ZJ=aqH(tw{%K1Ft|ksCQg2VpyYw3JP<_J9f6RL399MRw{s*CA2|BF6=^4$jvQPr09`Df7;f_exV+03i zNZT-V+%|o?yy*i$@koo)X}@hFRdB=OqtKt=oMEEgtWzxX7l&rG907O=;9ThGqg23y zjZs=Xmb4>vxM~cX;_U_SNY$$`Id{qh=^r9?A57@HGeK~lA3Ro~*$6>M=Sq^GAbhaW5 z#g0M6+^pM=sDK8k@nuSep(Fl?%!|V8Cv*wk%&hy5tKg=I7phHwKa2G4M5{UB>(g{w zd<*opyp(8hL5`NT;+(qWnXW3t`Z%By75eBhoWvXpY)*I%#5hI3aNJG32*F2DC&^>6@GTJi?q9kYo3}#bOD{OTV zmx@&Q>&9o7Um*T#!CCkgkFWofC)&b~$kuZ%o)VLMEAK5U1ra=c%H_Nh@#bIh9GqnI z*J)ym294gO4k@#=&@0{(a;*HvfRhEU8we_BmRxUX2m;JUpU@I6Hi+2zi*V-Wb`> z;_%iO7I%w*UvHW4Gdln0Sj^({2Q_CYU?@wslp{=WUF$|rb`o?TJ(tRZL@Xq+Iyd@< zTfHtI1Kz=2W`6jm@(Ov5wLg^ATJ;L6zx@bd3ZtjuX`=T!c}S|0TRU8AHnR>ptQjI; zfaGO6lc#z&H^WT-RdlYIE^Ls8+I&x#o5UUCM#h1Acfix}bcfT*^|piZG(jBu#o|F9 zS5ZvSg;&outp_t7n7kUjeOR8^&S+?F>5Kwic7%OXK7vHW>))Ra3}z*q~V z@hnyPzC1@X(1Ze!s;+!n{(2sGUl*v0AG(?RhdfAF6uR<)1Ku+|PeQ0jbp3UhS+e~t z&vKcgXpAtnc!3=$`0U^Kw#q>mmDGH&B(~*NQN|7+knXu{#+jBROO1B z#y_OiHM&MNV=?FVeY?MvN7#l1uKGgFmYsWVqw)Qag80ZSBvUroGS=F4xGKZQD!0GR z6+R2!zl*5h4)$$kc?MFPbs5(xhKu@vScZ*zo^^py_CjMQE$u%k$uqOcv(h9HyM~ay z-~CGQvx6bWa1>pE_OH`c$l$#4-?xh3ufrN3O~M8165=%G$XFLLk)y?b_4?*)FyA0> zcFX?WUl9DNszFh=E$)MA||fWYR>@Lw-UCY0;cDQ_LnT8&^OF#67)UIeAE0ZlDMH zG$IUAUH2;`t{j19Oaq4(VnH<(Fr3HNLP5v{D=nzibPHVX5B%~Z*T0?uhhgjcr#dwoe&n;6rT9cT8$nDC!`nYHV%7j`d7;8g=wx5*b^O!l1 z^Mthc5z0a4?>X=Btbg&zE3k{V?bG<1l6p zA7r;6<_g_#6kRUoqz=d(bSax0NRzil_tf4-a`+CXnRublXreqc&AVL{3JnwThOUAV zKR~zuCfJaf@(e2JwEAeDsJ?W|g~9><^xX>^uPy4~@c=Q!C#+}8mPZOFL&e>GY@xG1 zlgkfWO+z+aBL{GN@-{w7c z2E6U8Tw6k0P(B#*xElS}o+)?kQAF{+Y{?Juw6qGxp*Ir;MU0A? zHWy;iCL=yySmTU5$hH7&O}{dUsmind*K$L98f5sEER1TOlSd(poL7PsQHy?axav62 z4&j%Nc2h3OQ_~iJr0PUUh0C5E-b^=I=0e)#jHQ?484k6Li#3F8S++kbjhG#Px|h$2 zm%Jj+5Dsr8J7bF8jXlCf)4bjdc!oFr+I~`!SKpS0IXIo{gaoNCU*QQ03qXCeY1Q9` z!rzqS+;`<^4(hAx8E%NfgND&MO@!XM15)Vq6wILqetsoB7W($SJW)Z$ASLdPAGhf$ z#M%dc=P|tIfjmSc1xn3XCiVKVdscwxu4`|mzrX&F2Z`435?fZtS{ZjoKK%`pui+b> zjHda^1?&O6@#y3L;I_GC1U!Af4ixglmB5>!wYZz&ATHo3$?qu`uIE?KuzD&9eRg}U442jq?k7+Hu z)|(cW!Wbmp;j$-gd4g983++4xKh{;svn5`6Um^P)JwNlWk+5HH5Pg`0Gn*?VA_lE* z8@LvbaOH;A3%P?SfC(6nb9WgNpcIG0Uvv&ZnS8;Ak_UW`kz^r6eJdv4)iz3jf_q8j zdpZFj7z$&0Gwl0LO0i*@s3^VGa#1!S1g9^M&V_D6TD?736GLxrjRuX6EpPNx zO7qp4HI8z5`o(GuG4!ut8agT@vdx~*4gdIYXcEG)9?CjCfVmUtE?Qj37AGeU90ehL zv4F-^dbpobQaepQO^hZEJA_?DBFW|RL(rtJKszevn|Ab9O0!*Z?3zY#|FKK8H**n% z%b>*|<}S+yDy7-tKJ|ii*H9AiLxk~%ndpAE!D|8;bkhi>(9~E|#3VrziZ)3f4<-&S zcywdTU89sTyXoSi9i{W6e+bpuAK}KS5DFESZo75N9nX5`9$#TqCyKRW^LVB0h}N0u z%%b(AW@-m*&4Z~uH=>s2O07p$@Z^hbu*9KxvPPpSBX`g&TNHvx&ssEK?*F?*p7fj} z))Rz*M>fmz_ITME)Z=1thlhB-g-ToIY%?K=bg(_^!wJ73=uRNSdEt_7rBYIRO+utx z9YIn(t^a#1TovuH06h_Bg`rARR!8`05+h@i9DPw-uB(?T@1Sb%BsAEB*>=xnrK~{L z7!v9Bt~Y-U$2eqFdgsz;?k=SmMUhOlsyKaMkweHFL73&?6ECB7D}@DVaEGjGxd?UK zqvhjYkuX-Fk*|W$0}NBu@c$r#7ev-Wf^|)+9>lGrCj?}1g^y-^Tk|0 zc)KrZhFS1P?j@5iD#dkljUjD@4M{gB54>bLep}jgNwXEbe^rWc)TXjJtV%E6Ok-g~ zIs(JP?f!M8RHb&?SFdZgn{drBf|~Ej1Es9As$FqJME|^e>N?o(E&3HcSg83_DHexC zQ`gqy4H>-QRTv$({TAhI2WH5Yua)vd#+XXA++bUw7ZjCmVNqT_40xv$j|U8}rO9?% zhrGx?#C$dX5z2>xsLHq(9m$weVbTstjEm69jQuE122cNb3tr9i$PO0o_DW}0%4(|} zAk#fi;J?lEILA>$V?P*^lfKELl%y;Q%S@ZDuLha2!DYCMZqKKbWPc7qW;{zeocGg{ zO2r{nGlWHZ=A!KjE9KehT6H;x^!i*My8;tQ9$yu6_Rv3yDW#|70eKA*GsC!u2%2?X z52<-ngjH0^v`Oqtlv>(ZdU(X?E$H(D&{x%CT3%7v1(Obn>$QWt=<)#kmDr$U>3}OX z8;L^2<3kDOZL2$~DF;aHwA!q^=SGB{PJz9$FUPsvKn&|!7@iHrKMXNYYy;- zhC09_xR$OpQh*3G8qEnI(HQWUB_2n5-s-@xF))37n4Tx6;a?~Kq?*AhLtD+@q?Sf~ zl-RJF^tE+%@3~V^4jHRq;|(*p=}YA-VYN!%Zc+Nmv*U257N}UcqIz{u{%wi*a&o8K z$LF=%4J(wx)}%VD@#8uw0Cd3p?|1=6bT)*h<9l`X{q8R8FkO&Nm-lw@dE5fy6>jKf zFb*_e@>7EYIa-s86+t2`TVLtv1_+Q2H14%eG%_UXJ_U{SE`vyIf|%EmF)rpg(GscI z!&t$25ym4@24P8<31)4)#T1q@#>HhCr5;Ur@(NwUBTPYfGouVP%76?s>#vKB_VS6+ z#3jhm$OW?L9tRFXFk)kqQ%7{utd!OgF9K-dTH+0p2K8M@N4(&6yX&k0D+@|O-tnCr ztdwVwE*Ou+nvDiI-pSA(CQLvH`W7+DyMYIzl=A%PAd?}gy-A1Xa2q$MC&yg**SZ-; z;qzs|)qEfSG^ses>JMxd4SNUt#!up;BNFZak8OQG73dIO(VA81U_^kRT&1R)o$M{nOeSQ92(Qzmvau;{r zOxAU`Qm92%3{j#IblS*%E)PSHoD0HA?$3fjiWlbj0+^iPKPyGrZ5f7KO0i*zH{u~I zsoho!=KRq6M@Sjt>8#o_XOtoxQ;j0kW~-DX`8nh}h@Obcnf|&`s0HMki1V&mlVt}E zE=(SP$GAmi{>gJ^r4-S83rm{3oaYf@ZYV|KL}*NmZ=xRem`29p$rY_hF88cHc&IEr z{jmmvY(D6X|5qv1g?2qHFPcS48dtaG@ll++_Q;R!nCJC8A64Nk%2wu3-^We(r#EV` zkAiuHu~~CT*Tz)O*n8%-iFhZ_q>T4fNXB@)+UGF{{U!IM&UuycSl=bzJy&g3AQv4h zErmSK_k6A>tQ1LMD(5{BU(Xr&C%k7m)^mMWI`Ao`lw(z;qNvO_aOXO@GkrTUPzb}# zEvppgr`O;@NK9#mCK_V2Z4%8`kW-Y0is)*+T?=?gxN9p0A5&2&yko3MtHs`{SbAkr z8TQe{m**mYr8WAt4EtR*rC7%RO*5%nY+iUiw(FOmRz{q(VdQVTl#-qNR+-4pY7{Dk zjTIgzDmrKU=8cqs9lS~z^yIj@xyvF-cc8*-$D}>rs}w5YTe5ylslRBiVqZUoz|V>} zr~aNTm9hgc3l|lICsXZion~p_xRm>d{N|CgZpgK-9y5vQoy-?^&X)V3>#bCOQbkTz*BXu)J=ZXb+zwH+)M7U z5ycFTq}k(@GFhTjq3AakcD?M0VN|}F&O0~SO;^emMv@{`PZ{ykl)o^uFsz)jjVmov zigs4DESU6N{mg@A?~%1Gm3QtT#&1*#c6KghIkT$Yxhjc>YzL(@=6wfT?~GZp#m?pN)1(%XNhpie)Rmb?9- z6v^_0E4@;nlzFv2-9W(Bz+L&e(EW!>f!4ah6^ShPpVyG)tD();Wt~^pk33dNvUIKX zk-0^qvcvP=!q&yn^HE`tl24i6f2Wjd3rJTok~Vif{JLgkcxekv0dg;``kzu(+N_l_ zFV*^0&hrt>ESTx$1;pVDxfKrGZ1Pz&sth~ma#)R#=tW0i2FsgyYSZjWv1tJ*r`WCC zdlVf4AwOWe*pktz7gS1foJ&$BW8VvX1Dc>0$%_(&PXv@Ku9WKBi>OfXYmYkdO(66m zsF|zyVs)i>8nG%9c2j891qKWv14}!X2}9~Ar8%ltg`oeeJU*1}imr(nwAReJQB9Si znVuWex6tLh>S6Ag!7Whj@2l**bUfStQ@F|$ez?l5T6CG}FEBBmClx|5D@;J)B zUq2t|aR#V^SgGdq_JJ^^xU_&(VcmRrH$9+H$!n|{?QHM6b!?Sa$u2CjLm<=?mi(= zYDUK%J_AO5WE0M)u~Zo&Eegd9PrXg0KRR8bSNCF2zVM9IdxZ*y)x*S9HFom;0J?bX zd(5=gW-$`6RvE&_#dB;swhpZJExz6hLh!xaRn{x}x?==-xzM z@7W)QBtgnw1t}+2ic*l>yX%U(#k05b8+3;->tQ^eavttb#&AqIA`sg3^v}n}m5u; zZ2Lkj4(CvgN@VTT+iRCz13`X*op_Eoe@uo11*LsoTvZu!6hBG5^b`<$?dG6k1XoYU zd_AqQRan%LX|jDNTJR${TfyUcYjH}37p&14ET*@)pX-eclXGn@LqW6|dgF`Ht53_2 zES6E~36YEbY1I&%{qP1ZQQxyNoCG?ONoUWjKrD2)Og$Cq>zdU9X&XpB%vRaYt0s|S zNbi6l7eC*v_xfi*)kUWBX1LWCl;UXIY(0rUgDYPo^eB0WQ znrpeJU(dI2bZdGscpj$J0+?J^uP7zihmP_S1B7feF87g&$P|;X`HlPHpLdlaxhjRx zOq{{K_bcp%NOTVopNJjsP$|bBFS{oZEY%mq$|Ew^zWH~So`Fo6Fe%FS*Dd@@Da-En zX+9z@*nx+akA=W9Mxd18L3Z^Yr7&l~gd`H{+0Y5?u0w@kP$BPor@vB4a?qYQq(rU@ zIp|PI1$2Y0moYqY_RyBY4rY` z4m=+w;%)4Jk~|7P+nsn?4Ac$MM!D1|dH#(HnUbafM++^yn(3M@k3yWYgLt~yzE9BA z4etE+9b`L)U+$H?Gbn}1i$|7AI&flRQOr8rDe1iA**~LFlFeb{eT8J}GpX#*WGIwQ zq4s3n{rU4J%q#l~n$Q5vsmq#@rJzhx945l3 zaum8M)g&X122DtSm`Uj9__S?{LNebMElNG@r31-nxf4Yk-0Jq1b)Q10C^#)YDq5|m z4A?Fh?&^uw#U$cLfapmIa-Js7wY#ZiIEliWyJ>Q98BAJ@=Txl<1tO=(x_FQGZ=g&; zUgN{^C8cCYB2FXDm@~Zn%HHS(CSzF6M|uw{$uR6nvsI9iQ={Y-t(UbtI2@VsZ-98= zy`_c>$f7J%-#{|aXw2K!^}%l?y+Jf)7z*X?4^?5^k_h^#*3gW015 zJo;OdIeZXwqOJ_U()={n7DbS`@7Jy!TM6yIj9(r&t(wRnM9iHwAMY@F6<6M&5e-J< zL+#NG^%UQc`A1V3u+8+Ai}dKkj_n^3>`^N-^own~x7lb&`~yNN!frPjG7a#Rf!n2a ziY8BY(<2$WMBBxe%c4Ck(H>s0O!Sv&Pg;1p8YdE@=7QD%V-VT>ia0~^196CbCmhvGAKz$u{e%>^kH`!vE?1o z=*0Z@mSsTQ@Ovp|X?ORKX#(_!dr=aNi3uTz=J-VGp&QF1>*6svI|Cgs8WDt zhlG!^oyC<#l0))Tl?BAb>r8Zl#qoX*skD|c-RiG0!#X_?qr7&0bxIy(wGQ28CDaqS z*M&8IS1t;t#?eZraZ|Um@?ZDWnQ;ilq}9aP?Jth0K6TCRhcNnV^x<5HtG~!&I&1a% z`t|EKX%r#+IvM-Y+}DHXx`(Csx(_pUx$E*@4@)vc#+r-<8Ui>uvpDW@(*+NfLzq?q zVSI1N<4Bk~O`6ne6e<4o^aV6;YT@hjyd=+=e)r_RZWX|?3tj9uCYk)i?AymTLt8K4 zPytL^=YNw2&~*=C@i;oCwW6$-@4GNR87N)g%*qEK6JDcox{mSHpYllYaIyLwdA3Db zsYu;t{$b5cq#T+U;2mk*$MWdb{%sVwM1jHuo>m2c9$Br$bUNUvJcV4ML7loHAxg^g zX#DRtC(y^W@Nyodzxzl2+oH-7_q;s^j!f$Z0eTDSd9SQ_Ws{n%w^5`o--?spn_!g} z@IyXy$dp?i6{JbT2|$fO5vsx6*lkl`niq&CK2v))k37l=k=naSS`_p~R>*>$ zhj-RD3&^vAaZRJvV9<6Ph|4&o{5kYy^xQreJ)XySop)@>#pMyL!hC%EtTG9GfRe-Q zq4yhHLt>Z*1g{9aE69J|<^$x=!tawazcqaEPcHaaH~1KzavEGk{`;5&LdEQ46CsEM ziEBQx$23IZ4*YV^)0*-iD?&E6(cVIj4g2a(g~srHlv6r=SW6ycIbDsj^R})>7D-Ax zA6#`oGF-ZppaXh@TW95}4|@kBl5eQiZP~JsCOu+v0)Dv@pKK)mby?$(09WrmZbO^R z-owjyIbElTJVG?3d0GzW%XSBynq--F8%bw9d@zV5>M~!*lfw;>Mw3aa#$M!$+4G;M zegvYf$NC=MhG_PdhgvmClC{Dbx6s>3q1B@1E^P#bl33^_>^~{V^IORiEFMw2ZhaAl zppW}BEYg-P2Bqs_c(V2imj5`eqrvqsVcPzQTHM+qQz-m1^~9l*W|i?17T z3^>j!Oh?z-S;n}y(mWEYhC&UIGxeJD<4>>2g8>R;x<5Tz7Gk-j-NILZhVb+)_5qtv9s^XIW8 zvJ_kOW}Wtrp>!?jA7rbY8x36pq0G0)aJ;gvuv`{~&01QG$*a9?fYFSnfuU6_x`yHo zEOEh(&g?MNA4ba$hv(|Mv{ET6lsaxu5@L1nLJCO~cl+Gjc~IX=NX2vZ@HI*)?Tmq1 zO@a%K&#;X|UN~aPWS}CQ;mS^P^Wy*$cT+ z(3f+^&u~I1$ErklKb}Is21&T3NRpx`o4ho~&HZrt{pbSySYoVsS{=-q3bE`Jm}rpL zeok7PGq!r^W3b$DxC!rXdtFcpv>D6~9an@VvY$|oBwEzk`-``u+q#F9E>4O?6jt+LO5FUbQWBn!Yp0E|tQ)48O&k|;rAL*MnB?qV+_^Fuc0(yH z)e)s0Jth79*`UX%9gyk{q~iX*`JqybW1bS5X&~*LUJy~MH@x97l7=_a-r2upIkrTv zs9Pc0lnKkKR)xb)hXT7Z+QO%@G+eorn(PNy`cCWf5E#mv%$C)?)Q2LhBj3~}iKQ@7 z?-y|aU$uaH(v9#PSVKZyy4et=c+$hd$@`CWhhC^_N`GnqRcYwhzRR9x(B>{5pLlLW9{fx@e|r% znM-V^9f&ciOat!Z%hUFIgmxstt_^EIBQNz0uq>C`vc7GNP}~>ZU<(t99TE0W3O)kYYTOEWx(iq>VY=lR0TVEUYFyVbdS)CwdiJhvSy5Eq`nyzyj<21 zOShDF3igkxyAdYXhv4Ud|8Fz(P3fq?75@@}-{#l5{mz0!&j7|Sq4Tv+L82#LP+mLg z+~#bwV2_g$sjDW~DrOxpNv-3P_*q6bN-h9P&?7~iS)&GcyV)p#CG62BW&?7EuIazc zHVFC;M2XjzH6pja`bNZ6(9*F>pe{O2o5a*Ly3_x+J)W(i=voGI zk`k*{y)*hDO;VVV0-{(mPj&e}H&f!^+^+b^kLVqxGEf}fBpTISeTxKx9$UZ(twzbG z{)N-mt^yp7Zh-f@eR`^gJ7z?CfD6GCUEiJa3ZnUqHYhj^%nn;Lp9Ypl#choPwWe^| z)M-h{QW=@rcD=?~|2wcqS@?*KwQWY!|D|opnsuxCW6zps(kx8VbYacP8S{CX)n04B zf8W$Y<5&2EcH%!+}ps?dzw$6+uRgUi<s7<{x!;sj#oN^&RU$vn zGx5-AOk6J?>}-R}2i&JSB?NK72l#F|xfh|g2xCS*VNoV~e&y2yspA$~9(1xnpw4X2 zCM4LpPw|%A$~~g`2PA@8hzH&WMd$f!E%7%dVm7)JX2J)Fx8fh4^gGj|6}0V*PnrFh z|FgBCy)hoc5(>^R>|PXa$cQFqyhfvR+9ilfb0PN|Vw*^EnG!DMH0Gweej36OJQxzo zx{nqFLtUZZR0U-A**Nbdw0{LjiRZ+n71Yx$xlnr0Dr^GvhTSIh+Cf)>Szc*o*`Qbz z^-Z8*Y8V#HB4efE|Kot{V}>9IOCbn(sobEt8$5?eLhG8KMevO9TMcOM3I4?)5 z)>aR8tkG?;?lfy*DV1fbnF&mb_5MG$A_qNMSeNfBB>Kl;eb>g(ki?s_+g3=Ru z=JUf{zEDqd6jQ?VB4bpFwM^N{hAf8E^qvk+``@?tf3!nf8*Mghn0y!7m;`O~X1YJ; z_y1@GPLoI<0=#RUn7j{-po68ptTEmJvW>B2_*7@J^fIY?52Vsh%PSQppF!#=hHXK7 z++_@u&?VObL@9g#5&(1`4=qb;6e z|JYpq0a$%7&f}&1o-j46v_1s8=u?HYiz%hlC-+Nb*aE-Khb1pRX2jB+)xbrN;x0U_ zf0ZnK;W2L@G4DitdbkO+Z1|B~<(_h+#N2*JnwZ>o+Gpt5OAR=6YBErV>P)0eCyNd~ z;$43*tXT%5c0O2n8?6TA(xT$(O)Pyq_gQogCxLIv?D@o?25l{a(yVG3pSawwlebr` zwX}$F6^3oe$W0Q|kkgoalb5)>RnHCISseaL7u@jOqrDPksa7GaOT(@Oq>3-5T~J-x z+%gh50jrhvpOoZ#NwO$8S!fg2UzL{?IgHQNh8Fp@yZT?r0<0yJ>upse#m8nnvS9q? zF%`cJ>@raI-4l~ck~;^DmIYVGY)!jG#cfje=&MY0qgziXi|?{)I$Rc!dQv(l5hF3- z=ShOYy5!&-_;ftX?#m>|pDg=%yhWo;ONzL=uoY6XpX8<$>iX9YebW4Ih(m|bYcSrV zk+Qs0f>09r^89v*`3ggl^N@s(U@qV)c^O-{>Op1YB0Yxxd$405d^rY%9Pi^|#>&!3 zkB-%pU8h1xiB)J+gDR82dWjh%e(s7q;K3?4QUd@%|!3l^UE=h|4)edcfGrz|# zKQz!B?{Lbv9+yO-V!oL3=rnTf3j*hEw@{WKUt{x=0tB zQ;D``L9RKALEDPd;LB(OwkV>tOT@EgrdA0ZjYi9!c^Tf8jTuTd2X6*EgIBwwwkhI~ zbglGy>ti3X^Wr-7nvP)Rft*#gB?e79G-v2y^}cCX?7fV(J|G|77^F z5jg3<;gwyp1By9#qyd|jU5P}>JNNINk^cd84OZf%>y1OoPh(URm_#Z(T!=>MG#>Ri zb_G6C1S5K1Cfd2*6tNuoXp~lFxghA?D!ukLWV;C2{28yTM>~Y3^ybs#>e9UdfY6CEj^a-li`Ns`{HsExZ?!X)|e*>xr(p) zCrgg2`!41@Gb%csZUG@lDjxek9?@l*R*1#*TY-19JX{ZZ?r+lgd$_0<~SbV$rr^Yi!F= z;f8^hqcqr^W>4|rP5klEg8*N~lHsjFY~H zlys9m5AQzlYO(ga6FcFJxhM@zVvE~()uQY3>6PExu(OtFctn4-Ofd~xToG+Z)Z+3| z+W{BbdbN0y_G)MN{tfNl5g5I3;^$~mJ#p-Zq_<`7LId=67+-FhKS(WBoxmjv4V!Zi zWG|3;5%oGrEm<_yMBJSG?MD3z>rGJfBDgtUzpOJvE!Q9O1zPJlJ=e*Fz-Pj4&%OYG zPe5QEUnPgB1v@&O%*=X;qxX8e1vWcmMvrFyNlA_#{#me|mIfqBTscrFU5AfvO5?g9 z%%1VZ@mnL*<5e6AB$e;n+NHoS$h`r!=DQBVmwZMzE|s>>iVu=|3aY}vU&E#1-eY(0u(*Gum@DDQr^Wmx#v6O<+S zQI_WmBv`2 zCDZep?P_6SA`3+%>)tLfeRh3Vm(l}24^VBtTB>76*oscMQnN$t0ed2#;#mmEPE6{X z2h{S#q~@ijxDJjkOq{eF^3!eA+`|taQQHPb9Y~(OA>Zn9XHCKx2>vrxzqp5AKdKfg zFSyjRmI0aP znY5MT*)dj&lT=uH)#xo1waj^ju0yi+patLT0wJ5?>T}6?a@$zGrN$IT^VY6}Y}2Ia zjB!9T1A^zOhJPzSs1j0apCc){NZ*b3P9tAehO+r`fZr1ZZLk&TArT35Z+DbsZ-BT- z%YJ`hT_c!tFSe=j0m6`H3P?7EI-1lzF175667wZXjI;}nDGc#)B2M_O!|Lx9fNk#T z3M{5wLf0Ap>n$Jj!S}JZGLX6Po{uWfsUECM+y&*{<~y9~xO^?Cf7XKXjw@u$gT&*6mJ`ZEHtABC5`qPXp3jyUj)`sRP8+}u7FPgqa7tm+k%`hT*z@~q)c#s*#o;EZ zQeMIL+Z**s24kEK8?w?;sgOjOq~)-8Wwt|I{UHtC|1hqK0+L8J6LLtRfN~Sh3_&;t zAg=h)-__L>a2({2?h>Tp*-&s=G@UFe1~#A8S>*M(*g~mEyVJ5xs7Q}tJ%b&&b`RH8 zK(+;dgY-gj*857h*0msSdoimn{Ugw=0GUP6F3Q?T;hEvT|P#vVh z`Dv2|TdlMvmwiKHkF&qkfLd{hx070{1iA+nS8IpHrDk@9<3uAAc`n)0Rskn145jJ` zvR$?**}Z8E^JZ@6eHep66hN%I`y6yAE=owJi?ip!LkxoWiwRdiarnNA_>-8_F8;J= zb{bjr5L8TGbydI?$ua8MKw3Vv{gmM>`tkr&O^sQfzM_YVHbh0od!=pR_m7TuJ#YQ= z`TR#KQ7v68;^9%1QLgorq2Sw?jSx59?WpTTPhlEp6~0-GefDy!{AX!JO!!?&PnY%> z3a>(H>Ri#oqdNQUyJ7O*wQRo>ewef!+Np4-Ua+_xoiP9K+sX1Dh91OH4z+m9l(A#q zN->vz`l9q z7nyI$2_a>jZJVxE?g3;ZbXSETzrQAfgcwp^eY~VomcFPWmlk&3mC);ki?2rG(k06t zUSC~IVCw(2E_Q+JXiJAVQ~l6k zQ*pqHyetou05Q3Stui*OlxRen*R8=AtlfL0NAlzSSjsacBs)Wg8#biO)G^)ELFb^q zVGxOj=FiWSKpf3P9HG+4O2aRf8@C4pEyiYiGWNfhN+?#PIkGIf5ri<(TZhIE^VCF# znFj?9-#k+JKP51`-Xs_#(1A6{7iPgO-O)L7x7(Sykc)wzn0H&uBlmjru`b_ima1cePE0Uq&q`F6Fm-{;SR!!zx1zNZO zB*beYF4iSMXJTZtcRBE`Fk+FH6f3+3&yKs23Y7~li;Mcv725$`v$pm35pP2 z?L3^|4hK?_bmEFUQfuD7OX1n{ZZwDeIz=4}&;1P6yO!+W=yJz*L4(w*a@e1 zQu#1n3|Zm^$oh6atV?UKq>uihnp+jSE&EUn5rm&=8|bAwB!Opx5DOFGUv?^%grn0vYC z?L5gDwbc!vMNslvnjDP5^BJNKXHdbDdF0aY*@*jFMV)uZy*la!*gEhr>$C}e*mRpH zxrV!_`h%9X*Xb%rA@_k#tuvHzqbhyLykD=|V!jpQh~A9fmf7-6^< zR^v;DU;ga|t&5(V&g;@-an{|6|8sBqD(x z^29?jbjZoaT(`Z>^3*qaEOC1d@Xp$L2%P6Arp~$ZTzT$BQ>@NY$6p8|75ks6Jp2O; zdJ%PeJ0|!3mu|ppa)%{G(Eqd^I27BSO$q39i5xF>gDLD&n!Iy^Z4*?iPa#n&UOU}u zCvdr8W^X2H?uQc1X!?XO@KB$hZ$~(Cos=btALO=l-DzCh5oeJ74Cj{Fp^*|bu2*xr)i4^&dffB7^w%qw%59M zt^wS22f7blo<1(_1`*N;B_r!aMTJg%0qY%ubYaX_CX{i5W4B&ABZRb!!DOaTfBiP( z>?9kHX4OF1ujWw zZ6%-9CPv~2ix!Xam}5;^^c?Vy_Iiy$qzos;#bsS*qKBmnP@Xqa+=fQ(;j}U0my8gt z`@%-OPJ=`nwRRebi9rg6iGR`%%|2(&tbTh0ts=>7i_m^REc=JqW@qAXeg|aLF z*klwk$!+>9TXu6M669K_HH4|O^BK380k#BP&)-w7_PXR9@aG@s(vllH*Iv4FZoysj z1hZxpXc~l!7z|zz6Ljw#w^+7R=8zC((bA*f1{es>G%pk1LoDK6U#O5D*3 z#OFv#2u=G>O7gc4-6GoD$1;tKONWdGad3m7CkhrTjuBX*v-5^Oatmy6UYnA|nI|95 z?fNrv0V+JF&2D$I6j4x53yTTLz^-0fr;r&}?B4HtpxDv~8=i&AB7`9mu@5ZHARQYrxni@aSLlH z>}k@=p^Fo@?d!L}d#*ymIwYnpOycV0-9r1}wM2~}0B=1J*8sF#8nkS=q$4~7=M5V6$jp*dD7_apNJNj>mnm| zs?fYkL)0S0kXze8H`n#$`nhw0yVo z9lA{ALwqkZaX- zUc(+U*$tj}P9}A3J$0u=Fs%6$*5rwC)azcamr(AY=9^qeoe1UOHg_h3NY_junGzpfSw!#^H+yc4)g$V_})()W@ZSWB%W(X}@8 z2swWW9+U^O@xag*Ns*H9Acsi3SFK< z{;uYq;UiI5+(TyK={DnUZb0pojMR#6y8Dj?(8Ubvk>dIC^6Nj`;Mr6w3{a{?(>)D& zNs%I~Me99s1Lh!{SiM9x%yjXKj^mLIekt!PUeCvF5Uu$~N|$3!HVdJ`w<@+n@IdMK z#toPPZ>cn~M>blRyaWq&V)@|xe{K*R6{>h`a%+}Kby{N;WMD(*ol53(MO95x34&GV zMP$>eabxEefSPj)#ur}s-2mEb>S}!P?$>Tl#m8^kinxJv)U&Jc8%g_S#(cvswjkkO%k;oDq_)=&*& zI`zaMN?awc#TDohcZbw#IY^%Yf)0X?+p~~OUt2XhRllB{GzMKlEG+DoXl|)7L}3G^jatN?lz#1Eff8Cgd)U1l;Tc=Cof^vL4dY|e`>`Rl1>aV@vQlh_Gc4lQE)3>-*0cCn#l#W^s5Qh zHY^@Zvt;8ta9MzB7aCf31{Lp8fwy&m0hyh||i^6E>~ zK$J*wp?lw4eiq&Ca|i=rJ~3L?S2d68*d9b3jks(`Q zdK5-1S#-`{*YjsYv?igq<3&ZjAoV~x5{%hrmpg$Eu352W7F1jjDh^;iG^VX;qHUJP zs%j}O+Px&}K2?@S7Is&LOD%CndQ|tZFFt-7ZGF2QS^}R2ZmjFc4MgbR0**|Fi$3B-hugCZ~F> zP_g8$2`_V1%7%iwZaL??TWGj?QmVVkES6M^U3??}dMyDi<~8g;Daq5vxy_`Ly^`nHEcN z+GMb0^OIDpz8tmxx4)ocEoA2<#O>*-p#gXZDvB;C5DG{-zJ1%LeSHWw3p(agD~)ET zW?6~`(PIdNdVa2k*B*#e2^|?1>+)>XC|g}7aZ$*)`?2ZoqcC|{+4)e(fAdtcY#CO8 zzbtzZ+?)224@cH(V-FKrCh4|PHJ2{f$G}3H;N{b)EmirRVg0lNg?6N@@XYjG@3x4} zLO93C!R@~L3}CXXIJjuy@);B%bKpcgH5AzT8Nd?rSDEe(&3gd$?TJ+yF0OvtCr~ZJ zCv8;6#CWj{(WK}1<9_Kxj~~}VvB0a|Rr@{xoN8d9iYaiuNk6c`C^%I!*caD5+kaA$ z8y!*2wDxL35D9m-K-aPw2)7lJ4L)`Zd2hv|szHvmtq@0YwY^!P4qX@D6NU_6xR<9? z<7`2iS_Vnvgaw-9hJ;d zB?wt>XHb@i%gC*Hu&t7-^Xw(nQ0Kl%C?_HR`uHjjop^5mIeF<^?1pM2ueU@3pL`}^ z#GSpAZu)@uzt*kk`p;{hBz6-EUp$U z?KPEZDJ`lsD|Jm*sg`Q1l=vxCrL9(R4e=W)+;^RGa&p%BzVGb)rGK6$PlxBpe)pQ! zUVDFQaU#?3d7EZ$1NSEotXSivGa9}8r|kGOH3L?04Cx*JHsPb6bVG6?qfJ>^cra$o zFlq^wXkM_seo+CG_MReezJ5XX2FkTbgTE_=fAUxku;{5Hm#FQcZY-BAQX6yahkrK$ zlIlGVbDV?>gr@}wmwh1GXz;QtkqUJUtft8jn(cCllQmAv?RpQ|GZ5O7$jtxdHCZgj z#|e%OvMC0WUFv-`naZlEL8r)67K5?F7__-m7P?$r@=bIN>DjN|Sz@i2i!K;mu&eIU z6Tf0JDd0mm+sxkoliiGy=Z=$^%0)AAJ1}xjy;SJZB1kukp*(s=7RA|)ROx+a{p9n0 z%W7eL>ITUTbI+f$>pP|CcqgV$rnG_Fb}i1F!3KuGFnKZ%e_wV3ps*Jo8!X-&orLGIR0N9BG{~O;{e%3&7MVm;)cFDhuqM?OTY)llVNr zskQ=TP4&+Y8w1c4sFv`;^{drofz5b0X0W3=@BI1&m0XoxXC%^Jw%=SslSIfv@WOR& zEuCOVwpa{wGSPzpo7wR)Qt(u>e(UzDbAU~6*dm#|Y^|*mo36MGb{~u-RT?$8tP0Ue zSqk@tbL!~C8(}p^1gXU4rkA?3yp31aUD5a?f{}XSF`dv(KU9=PF40h+^b|zt zPaz-PdJ6{g4(dXE8C=g+I^oLgRmfo?vuua?!C~O8L*~wLQ=Zj{>%tpOZ(1?IRJ(g5 z;Rf&f^oQRNXbN$$9>wTg_*|uM;hpmE(%Ymq9-A2aZqFIF+k?n;csbRJ0bc8>6VN43 zXP-l*IElOfW79WxLUF4>ak=))iqwhb=@HcGF+|+XnkUjrK@?5HM|KGo5sq*Wt!~JlTc68a*atefJ}@j$G0eu;AUpBfAD8uu@BsA&dou$vOcelOqTBi*VziFEA#R=fxD| znlTL^Q{a(*9#+~Z{26@yj3=2~@-6!7+(%SmL`Y&SQGb?(M<2O36@0B+d_kO4T1!Iv%MR<(5NiH-dZR`H7Pp{Y7I z##JIX)ilClQ0K2eS1TsS(hG-fE=&;r!ncr=|kM<=3#3(*cIiOVE|*(dIfFK1fQ!1tc!#8^|BybGlFa-j*2!h_54%Get6HcUhuy3tpZT)yh?cNgT&zYjk`!x?z;{pg*)1|MxJKq?%EY+R%F&Kn!*wkm^g zX}}JDAT#aWUxQAu<>I?Is`b$2o;u+_Zalw$d|80PmsNS76J5fWIXt`2sdvA;q9#oY z>xbJD{+V9Be-p_=wJYV)ihY83SFKgh!%JY`{ZYK-20pX4&K;CTUY|Z~M9lJy6CwY5 z(0;CdiyG*}^KvL2sfJPkD0|{zQF- z&fWS4!8-RLRzxK$XbVRYCv`as_e!6L@`fKJt^eP*5bP_hnbPf8#s_dmtr1_j!|&Nv z=S~z3U*#@_i2vK`iI=N@aGIdXv)#e%Wg)dIq5^xn*68Cs2LT+7n9l9(M5ruymTPV| zA9|uL>4AG|R9ON%3;4_N0y^r&D<9^fH4DUHWG~-~dI)&)VdHTufCqKai>EpgN}bH_ z`UIrK!=>y|+?6a2*9*(pDml<)>#XO`_`|3pVAR~AOc8oF;5n)!*_^3!fZW!#A3Z$) zZY~P>F|SUS#^~J%m$)P=-fEEciWw?U0(L|*6*!ozcLQFsP`NxJi~e?A@4Gvo;L9L= zUa4KxUoWBu^VL-?=-}zi)1cin_x?pj-r>Q20W8>;q_uL_&Yd%}SAoq1wY|UIJfHqo z_M%he8s!ez(gG|wqd2GpWa!<7m&CotDQR)y_y-NY+YhCqnPyz+wr1(w0)0H?96sjD z(=E4^1e<_(9Q;Q$+5NM*_^L@3vA4}&PQ#OSbxkw;u%KWd0@X<%@H>GWW?6&+tI2ij z3#Fu`ViJ%bPPGi4@#$W8krWhGd0c+oS{ZCyHs=cnre{2g{PVmDqtZ1+CbJ<7(IEwQ6zWYW1nU|2Mc#o{WxLScwf( zK=bDUO6nmnT&%Wj5T zoacs|@^D@>2y}7A%?9BQ0lo=55En$*5?OdpXwC~C;3SCgPi*`x7ixG2YRJuh@={rF zC#_DV`_?-`+_m88`oZAzC5XN|b9BR3$RdhVj8d~DMPv6-hC*-cA{fqk^ zI;y~6r`F%rLTc}<@)Z=pWxjU(ToF7?T~6;V9lk8}caDrz0rN*{jlheP>0WRc>mc+_k#JLYmK{UK>jqf=X&e*=^p z7zJ;JGJTgUinb4s)+6h{P9H{L8v`KU7$)1(yJffGEn9&D3ft+|ow^)61OD=w)SNxC zklf>W@dIr0$ZNx;BPFmCq)6~PfJ^OEG^ll@; zSZK5k$5&N}20Mk7%nG$o7s8p+KWcpooum%-kxVxq{HYf_1urCQ7~e^^62eLL#{y&L1o@P@L;6cT(epG2NJ?!vt8VEhWCP`wz;g+{V4YA;)r zL{Yen2%L1_A)uW`&4y?EZ#0ud^Nw>WK~^n$A^4|Kzi7N4JRPct_JKjN@Z5!Y#ypjc zsB_``pojl;02#6wrpB|z;Voph;mrLVoYy>Ul6>Q`@1Csm z%+nSwmt1W44%Ewn44rQwxV7vSyoIirxGFhLt@d6i>Hh6XaA6a;fN0|W*<2jeL3Rsi z2E3V8nXo{LWnS{j;83i+4^rjj=(sQ+>(gg%^v9o(c)#p;(%A~2e(9bvZ{#^eR7+?CPlH3#mi`YBeWz}Je?9= z@oQU)$gJJ)17G7T6U9Ilhl@axbB$KCP)M^mUmx@_yhvv zZ=QYALj)L$vncT`%3xOM=0_SH`22Ls9`LInNaAOek|f#HgYi(1$fC!^N+l+y9S;aC zOMrr{gY)Fk`Cf_$g(+ErvB;ER8(}x(W}7l-vKBrT*6dz8WQ27*U0*fCL=fI~=jim6r8<_I^!B+LA)nJExYme-{D}YTk0K~q+QX9s!|>Gx{1Qc1 zla{`60u-eym=<(S2!mMeIGQ9lCS7V(uV$azHl4oAPl4>aFu4ppFM^0RW*IOP-KSva z3^%lH_|2}*`1|cU=kLX>(qBaw<;t4?>qE8Jc>+?GfArZg>2xC)0-$W^{ECjw87pWmK(qpX8sJja%< z6C_&NlOUCIH|@M(>K`?>W7z=kkL$#>7NX_Vqp?N`=AZL$EHx(S3_4;N9f83jAhi^X z4z31A_MfQQx`zVK?1kH#G=mO4hV#)g4D&*W2$Omrs0+JFd`Ry=2>P=py~EkywxU%d zFj6PmVnl;}4Uv;f_U{av)*r0ujjczrZ6E3`0`NR`;e#t0e2P-I(?e*bmX8EZexx_> zs9!d(z5Mfe5uQgPlR{YrPGd^0kshCz*7wB=P_iR%J`s$l9=${$z6@1G-3V^y_2s!s z0Y~?^y%^k_ND-VTP0)h!&rKYWPe~j}Y)8u@W2lL8UxjB~8ZAPLLeh`mAa-{SN7G=z zfsdih4RM&^VWKQn2;{2x+3co_JRj=u(MIgok*70mAu)hey9g1Rb@uiZjkySo0 zhNk}qBC!C2=bD#NMeBPUjnyS_cvzje6hp@&=`10@K7z4W;_m`74p)A-QY}fs1nc4Mx={YFV8o~HxdmRRXwtgKIZq6 zsas1NV0c)WHB1EK8CF!xkEqD0KP&ca@Q5-1uBTfJqUGIGMA-jf2{tJL3x&CBj@tNtS5+3OOtHPW(xE_~)dZh#?b@ z>+^)6-)zy^?#iHYX>t*DhsVvo0+xJ;q?iZV>}8^*8CzJrRy%?a=Bk6s=kElI9)~#i z`<#O-M40X@f>nvsa##||2jTDESP1)WiIXtD^0>NEgybWPC|OBhZ~IRP`w3)?0a<;R z2HadD26Gp5bR?6c8wZotZtsH|tL<<4`8~@}6V{1P%WX$V4~gmPZ?0O_W5rwesi&+!)ZA<~IFP5tM$e=VNJl z7Jy_c598~~KipJj&5BNc4*D7vLt_Yd4m7F0%=$^rJ5jqWFVBW|gX$n(wCT3}EZ)hR|l591KV2D?%_72%i=OL=HapzkvNCqY<+itVi@@y8Pb`m@#?LzD+Bq9e; z7v}L}XbTw(XT>nys8S>(5?-r5xzsz@I_AK#dVu6fSfFNUw+#-w~GvjgPa(%AvX{GM{#qb zPRhLZ-i_=Ep(g}*3+8M$85AlQiEKT6{LMoppyEDa2&ZIRgbW7WzGvYLO_XnA-*Tk= zdWyr#QBvi`{z-2c6t{(x>zX>lI&OPp)D>vhZ5Sgbrgnl1Oe7uw*vE+M<=mM;m$m^V z8Yn#M4(lg_5<`7{X)c{eKBUeIKhGb!7hqfPFpbwFUVcFa4Ab!JRs&t8xD{K;JF?JG zy?6H93}tJhP__+2Wq_i_WSETtHF&%J{)pWOES(ToxO@&|$Y8iS_6kt?PJ4D5wMJcB z-y7xfNEsAzGmuV%c?3>}s8Fc$YhlL5J|*xo^AvujwOt0qO@x-8A?X+GyS=*r0PEpv zc>bD^Cj$~^Ei{--nf;Bqc*PGLaMY0nZIBji7&2-p2>TJg+*T6`WH3|nZH}H(I6*q! zTPpcSq)nN1ygq%qI}e9b{sJqtPzJ{Rsu!jtve+@l_C0+FKkyk*~TlnR*g9j62pj@3xl;R3*VGuP+HBfT}WJxu))L7OPBu!N)!rwPZ z!9{1tC_?(Tzjrv95J$k&WvA$hq+9Lm&4(PQLi17$)9ewiv9j4ovm+{l7o3 zf=a?2;W2mw?Dw5`eHR&M50_Wqd<5i!l$X!exxN;<@c_TvlB<=7q2w^^J&GEYV*MGg zW`6p9{J0pyw>Zvap_tS7UP4N;pWjE8c<`t`jjK&Bz+5K3#<|{+vQ46bRF&QG)pKo@_C*%6rzq1$ q;3n66J$4jWF%G}n3qP7wIS^0TRfo^T%;)N3t8c{>^&eQ#&+os&$J==T literal 0 HcmV?d00001 diff --git a/deps/gral-core-0.11.jar b/deps/gral-core-0.11.jar new file mode 100644 index 0000000000000000000000000000000000000000..108ac12d8755573571d2bad7ee3bb9aee0fc3ef9 GIT binary patch literal 280268 zcmb5VbC6}-v#wjVZQHhO+jgz8ZQJg$ZQHiH%eJe!s`~b~fBWux{yE<{cSX#Ixnjj! z5p#^p98cz(sU!;uh6V%$1qB4iwUq+;Up{Dm@8!kSgz2RfBpBs|6{ID^Rn-{eB_8Ex zrsZVm85ZGX>1pO>=9^WRR#^9r4~{{Alw={HngT#>aQ{Av{r6J(-~Kt<-(Stl8O@!o zO|4watu4%*T^TK%jqMoCj9rZxg-u*sosCUh#r}R#b#QYwH77G>FtsywaY<9tS40&? z<8R(=YN1<5{{SYz5U0{D0f{Cg$5M$wgCWC^-;26-r;E7;H1CT0#~@NX%!E+*k|j@c z3r<2l&$R)Q^xQF7p8Vu>Imw;e{dztfR|HD&tlUcqb^=$0$*1zHGSV4rMk0HHiiGVz zh8UIyZU@^zP_5&H!){~>20kzko*Uk%41_8ov9p7glFTfM(}*>?EwV58rYYOUL;AF@6gOzi$njE!^l&yr;@uEharS{Bo6dzb3w<3pM?mBY=7z}M z0>fTB#}9V=HPBZt$<+4#d!0!J3+#6sFo|!_H->SM_=bP*-Ul;Dxur@rq-_$FbpP_! zSJ)MVm49(9X8gi4Ha?}&nbs4Vc>A(dIWmvPxU)?jh?mRZf+BR5A+jv=co9l6=j6*q zJ8RnT5tb*o^qjI2fwC8Hh%>?R0}0Cmit_`@NhO2clgNiG0ojN3Ldf@MYGTP-7l@}2 zl|S=PngrK@A#-erAmtz6e|&?Y--@UU1PG`N?B9HY<^QK|{Kqp&HMKoa)zQAow-;Px zWOR|J%`ulsP%vIKTF?@$sAaU_I^K}L3S%QqdTNc4 zvJj-*XU1Zh_mCZ$W7ki3s*l;S7-Zas$8wrqr8O#!>9YJxzgM`AX9e9S4A>^56(_Dk zDN#M=O;=Bs;AXb{t$oH%z9d84kNZBqb$`2|zir5axhsl15Tbj10c+P#x6o&>!TF zq}~WJ0Dmn~9rR;D-$~F#<0G0-5GKH^awo0Z)2>mz!vm<^foRZfB&fsu#MD6$O;I|l zhLzU3ss@k$yXj0d0x8pYf-&UE1fL`rs)!wawFs)j| z*4ypVj@jV8;@Dn^Q)r@uZ$xb)fDN~sRlDw(3<>i>#9?)18}If}Q?*a9j{7Eum&L)` zxWw;TY;31i)1C83jO<*2D z7ITYDw0f*V>$7=zjEw&xeMGqiCZFa5**3Y6k=ACA*G?udPjcU4+`z z#rRS(lrPFp7=j)i~V%vqecLv~sPe{Kyr1HjcaoWS*RC zX^8H>&;;3w_=RFKM?co}i0Y^zSI!OyydT8e2D>Pb2+ zo<>sL9L2KQ?@-I-nzX9b(IWHFqj(?`1}WA}{5Gq_R8O~; zC@HKi!4!I|<6&>moa}wBE!z?M-eL#sE7h1aU z@k{pQqW-n8bmW4xJOT|C{%8y5p&B7zGpbya@;xLtsf`)scA%8^{io9!?%&+M@cwuL zcrOJI{P93kePVp({Pi@Q8IHiD^XGO|wy2I?(f$CPyn}w}tq_jG{UNFv2EBVNexXt% ze@aw1$c42#oYQ~CwIMX#-kC+M$MF;m+CWV${F0aV4C*&KT>l8YE&Zi-*TSQ8|$Debk zj)yQTOgPNL7L>A~0tmNhuxBFZi`-e@ZCy9!amPEQ{Uv!AdCRXkG9%D{Cz1r%>m+F< z4drz2$L|B&_ZJUjw>bO#R+9Ta=18c+Lwi6V`|6YpN<&p2s8BMV*eRV_MEhtmL$&@O zRg5D+{Q&~m58^Crl9^PJ%$S6x0s?~~crLyw;lYARvY_&|hYh2*xi?oq>=ZT_+zq5g7rVtiA zN)!uM(=gk?+cSyE&0_Kkn-HBOW!zZIWpYWT6w+^_ULc+GN8r8G*72rPzEIBzS~|U2 zC)D+&7b_239#r2H3W;`-!&B+P4Ye}*n=C(1D7JL+1rp%vCOI?}?Psf%Z1BW?E9rSk z)!1OPs(FKsGruZL4W}u@&OIbtaeLnL@_$Dh>Vt!yDt%LuVTYj{dUL5iWps!eUL%6( z#eRw5acw4K7Y`T8j8bLDD2bDwGu*MQokG~;qE>8b|IFy&3qWk|O2_O-r+o{J*>gG;Zn5O7P$B^dC4|}9gbDdjSP{0SwT#fL zd-ZLd?+x@*d909qgX(3$kJaHFs8d4}n1sJc8KOan-Xm z<>dQaK_l69hBju zeCHW%`V2O_edtZQ9hO{j8vW;j5g~Te*h(=yZa1(;{_Tejm{OyO*H0yck+5qem6KuP z2eI(4r!^DSFDF^5Dp^}T!SE%ro43O9j4;()yG&B_8%-yzOdTi=rf?9whNK^WE>&fQ=Ewj zZ!{PbzDW=AGZMb=n^5aXF^%nGEWWlmVg z-?q~61xBEFDAPToKh6&Do!s~A0>dSVSxH7>b9{x7Dd?1X$zKR<-O0rS%Nm0f=xA$V z<}F#hmUB#sXD!wgF2zFVh97-#YJxM5)N!OIlZlSMqvutf3`l`V?aF@`l8c;I5|*jib;RX|&7U9C?0T4}4i zzR0{ED`)~a^VI8X=c(XpuFt%4`}p86;uWaU937tEen-S%IUb?&XT)JYUIf?o_&xJD zmgQco6NM9ni^U0D6l)l3-5xV|zv`V2c!1JfO|T%%TS~AXt*64EAzDx69zD1Nt*7Lm zAlj$uU^mQ9)w{l6M6^%Y!TywV0njf->+@;olQ=LJs=3@~uwm4h8nEKAEZD=TNu@=~ zNJXT6qCvBx0aIZNl3=^0M7v(1-r!t^!F#Ut;LQ%9#CmAwDDX~4-NXoBVTM*C0){rD zzQFe)Q(z7qr9cAVp5RchO^ZR1j@pSa2;rh&IG85wM0$;x(J&3P13qDfrUThKn5J16 z$PaL6C=?8{YIt6!G$PK8J1Y0hJ1ziC)*Tq2d7r4ycsS*)5x##2(f+Nq!BfVS zkACm5V8Tu#q#`>Saq3@v`zti!koW)Thpm_8PZc zhy-4hQAa%yyg1J<^EhNhsTeR(^)B@Y1x;2n?u)pw=fN|c{s>pIWYzXfWkW^^oii&s zn~VEYFA)O|!;M4zTWIkqZ_(`j8p#+db2s6D7C|A4cgb~ISU?qu3&-49gWLlGvt{wm zbgp<775*d&2d)EXPZ4#I?z83={XwgV>qWQi1Z9s|%Zkz^9)wANoVrRbGym6 z`V~rCTeXCik3VdvT;&*l#iGwHYV9JfSr zVpZ6nnVRvyX`@%uVgRxZ9~nYRY#at~D+|f>F|Y2KN>;!@_aiYPU9G;UjQe_e?aiyJ z7sWgI+DfIi_g%z>6St1wJx$nksWIS1Kb}67IN*WT!$r0*_-(?=vW`{_t!7uxe#-p> zg^TH5(1KHO=_EoA&J~N$a=F${Jw6HF!kF@Q5%nuJlADba!~SB?XsNSusM6ou*jn0E z-j?WfgNI9J-L~D<;NW0)EwBPRmJnifTz?2xr-x^#N}gQ(Dffs(pTLg(7y6{i%evjP zJ^T)v%y-?c%h}hG{Iiv%OxIHAhN)blqHv_LuO40?TBO*-$eTu@duM1b(hj1n0EEXB z27&_ng11&gl$SO+STch1OC`BhXfbQcqU6Ljd}5Uj_+LA&-(6n>aSf~ZCC^9jp&34H zN{E|eG0L_+-h3mv;J;4J5fS2xUx151&SRwNwi}$oR(5^2? ztHVY)U?fNCoa34$AKc5}CmM_-^!++vDYv4a3Dv8$W1dD^EfA#Eoxw#@oshdLg8JkS zB;}GVP1R7>$_x|~ih2*bW&gr|R!wX)zl;;)JM+vt=P=D=cPn1b&-TY$T0j*^ z%9RdpOaUZQxtq$Nj4EJkMX}-m(2hf&;OKWGc^UU7N+8vSlI~@L+b&9)V@+PfMU#v+ zXq$f3+m{s={VE0ryF)R5N&)r0V1Wn*B~foNJAt<$uE#*4U1lSaF~W&VhA5|jAo&O~ zl5RMTfj7F(fZsE_kcPMY0`*TY=HtHN*Hk09dbERCm@94^Ui2qUc*z*gj@A+#&tj>- z^ycU9SNHZ?rVS)m=H7@SL<)f9e|0>EB0m#Y7rU$7(m(og0Lg`lm%5F=Cd0(06hivHo!e>wT&p*j1@3P#Y5I|H6%S$ zX0cOd(Ih{MmeV{@=BaEw)U4$mZS540i&>P&Ue?a~WI92N z>&;K;A$;Ver60Dsan_M+u!CxLMoa5BF6Po5s?s-wbWT;SF<0w)!Q&7R<&__$uH4HiDo2iy zGi0Kzd-dnMs!*<+PpaPqEQ5FwaB#}jPwCW_SA5%9SUN1>Ki)kx)3mSY!6EN}};EU<}HS!0>Pa*G^8B($3n<&!t4X~-*LSd}?~ zDQsxG<8WAxDRV$dl_+1Mu2HJBEmbLUNv*JcwbLP%qw*tQq{ns2jY88wqCYTI9rK^1 zO8%JiS)>(=^nWK7JNDb4xg9Tk0Jh5@9L0Yy#Y!U_SA9VB47)NgZ@#B+80YN)y?s!B z3oHmj^rA$#UwzB0A2j|siY1sc*^_g8@1jNQ(X8@wSmB_zCfY|E^Vfjy&V1ee*Oi9A zfcqU%cTB`4Ki^QeSL*d?$Q9AAnf!g-jpk3i7ZAaO-pP5(+k4oO&QFobWJ9{uhguc> zUlg5hrAs{iSuIJ14EiJWiEWRxrQ7f7OS_*o=feJRPh|ZX-cb%2KTp@Q$ozY$!?xi3 zLn;%0SJN(=dw?RNsIQFKN0ya{)~;ehwDS{ z=YDvm1l^?>E%j0IxP7BHMfO0V4a=e@`T9jr{7qeQOZN2(uh^geoO1#Goy&dXc|EyJ zdk3C8PyTm$rp?LGjTm4u_d%wUD$gtsBI)CSmIdj?t9n zy?d1?5H_@db#nHnIc>Bb_s~Tj<@H+4X)?Yj$JqVz=S~#d;B36Ux3?zX(>vB}^$4en zqK7LVVA;Sx*4&&lxmFaI7s66zOzm>{vn0w~`A0wSh?_?w92UXiEaAK0Ka`He!~-k} z3j{=r`EQi|@2bWBLg`X}Y2D$ko?-tVNKaF{R6rHR;$OzV*s29b>x6=GZfu!wM(%M` zRuN)?Cliv64ajwe)N0x#?^Z1mWM725lV($nmGA=!_`nhfz0WC4FH4HC{$P zr<m8ew%zOf$#k zBal9lO=^Sx(kd*Mr4F4fxQVi=C{td>T_8qBp z0s19aOdk5$A|aV#0&5MLV)X--B%Zp(mYZu=W za;0)TK(lZaauP*)zA&RG7{`1Y<(!o5&vdP^%052)iw>M!lJef9JLmJP!URFOWW!i13OG|goHYK`2Ocy(-3?-%#^0}||8O_AdLGBkT~|I)GBy{X2}$Mz!hcx^534;{ zQAtLG!(`%=6^jqUfwAR=yTg|kmm=YGfrWzEVIW~F=ts(kf!R@yP&OD0Sc192M8ZU3 znv^YAkd&En)*(AK2QtEJlpYfJ%8!eJ^pWo|?^GQ+?NlB@U#;Gk1eTj^1N*9u3-1(} zN|nv;!{AGXzVO{F-P`XJ9#R329J}Lh4_tT*gzDpO4`uKfixkIYS-yztmhMUI*6&&B z*6tD9FFX+oR__G>%lDMV@2qvGj=h07XdAoD89EE)1K0VxSWLYZbVs+*IfV+W>30yO z5*xToDB&K|!m@1Gk2x`Dxh^7WoXxcSyZjO}XHYqA>M@w~Cm0z%)-TNI5-ECQe(BpDB$RAo!;^qUlar`-4axcjy9aaH zdvO$tg;?z^KkmFe*WbP0O!@4tB8;!6kF< z1$x0!SUQTyuV^eHBX#d@qaR{`^>M~_{s>FO(a@I!BipkgBbQALnwF#d6NO7yaaQYt zm?tt+`lw86S6w)U*TyWeR%d?%Z-hBLYc2^g^{`CJqACH%uT+ttx)!F0*ca3S+TqfH z!#Nvdx=|+X+RUSu!0kL!Vn|y0>1tSUk*HA^Jov@H${!WPIL5;Jyi!Bi<$7Asi6iO;yww8`KqF)>do#$Bx}xsNAZY-!3gXS%_? zZ#)^;onsyAnm;8v-)PC`$4hYbtw;U{PFG?wAxmbyx9Ortk2snU?@|BEp{6z!{oXRK z*7buwFxBPtQ`yR|Hq1D&b2aa*O08q}Ou`BRI+WKUL`Yc~tS`u0C*+93a$>-cVXiwT zX5;349C_Bcea*S|Ox3k4a5biVJDPlg0e4Zj;4v6vo=OA!3@vZlx5FrTMXUcj#LlMW zMwf%h%#&cr)w0J4a_x-@s68{6k=7Eb(+rUGO$fkOriI-J5$`&lEmL?ZMBclqAJMEoRu4Z<&we%ox-iMX>Zs zW;zbpWYf~kS1K*=~p(p-ySnMBsPtkt-?UcudDsh77=x;XDlbEQ8sM04RgXI1V z3|m!&xSvZi53HuiA98LVp%eg=uiO%Tb}p7dFp#Uf^1Fj??#^v!`3DL^Fshp`y8giH zs!3l|`VSmT6M>7#R$N0FT6LW_HCmF_FZI=YQLgq2A`Cc_&S0K-)Xd*N(MzG|WF^es z!L@E1r@Z=e(Y;WqyfRk=8IMGBh7~C7rT6f#uw_+)EHf|j8`%0zp! zj@g+Vxhar2SXgF#B@Biv4@+Y;VEL>@y|hG8*PY$)*NWlsLwBvl+3|imVgrch@jG&z zwjv>^&DnFQ0qzwG=;)&`cfiqVXw=lvG69i7zQE@EfyhnNM~Tumm2?*pptH_LS?J3vAI+p>#R`nlCzjfDuDw!k z6?zTp@P)Z8Asfw%ll=NlmTW5Q7}w!?xaQvL1i7j=j@Gz6*-lYJ zKPNBhd}*hV)Cwie5oIbWa4y+^^1<6VcMG0But@<2O`kgBgSCT){e zkW~tbo&w(17d`bumZ95=f!3S+u7to-Tp{Wt=>Y@c8D_EgG>ib#FDYj75L zp^dqVME}$M!!NKovpbF2Jx0z#vueWhgeSB6PYTb3BJ<7r;aa3jljje@ZlTtiv;fn| z2rANSlQ=xfZhJ9G793Tr#BWPf|3LdJk?cX`qyTy8IzEo2s|UIR)zDvqm@G8{6g4Y5 zbdw?$iYc=)-DBsE*;VDNS8;Up&gq!4)m`RlYEiA$P@|slZ^&|^k9yowP#biOt9Yft z88RCYqda9k*gN;9UewEng7cfQXS2DssMJM8Tlv)aH6H`1`yY-C0-5YFmw#&=8Ln zMNPEWEwF6m0wGSC7}TS&wz*-xM~a+dk@vjN$(*Yc2^GK*g`>80=K?X2{;QSJA* z|5%mM!vfCxU%l=9Uxi1Cf3+%62Rk==z<=lOs=EJl9e$UU(%H8MQjuVyqg?`oH5q7@ zWR}pFZKKK1a?Z9F5X@aS$-8yg`+hsfi4ihA4{FBsPa@6R1tEchF#gKr&bZaHn7i%0 z6$FwyY=n><=7(3sDPx}@o6 z*`1L^?Zi4b%!-R-O-#6~79c2l`xgI0AE(VcJjeRFK~ zAkV3xG1ELB=7$D6vPwi~n=a-p_7Yj0_pOYYv7xx7I{+a$S3a%R?WPdKpj){9NiCg7p?$7_9B)}e2BZM`&v+3TdnZR z{tv-NgW+Q7#b(&|djTMQA+Ee6Ykc+Vj_w@Yx*bMSnf__)Teee#3mcvH{lBziUJaTQbNVKQ{0)6vIh7hSuE42E8B>T9( znZ^0&etLRa{|lIJs4ChVotCDG=BBcvKpccsMSo?$QM#%poXiy-#uc9&&5drqE55s< zvN+ZYAHu?oPb`R7yRHSxVmj>w;n#85@NQ7&>Nc{5nrY^5Tms29(>4<1y9rnur_~rO z2iDZ7+LTdwhoi^9S3F^_Rp)L-IpmEsCbSn?WU&*Xz4*;jWX^&_on|`Z@KEaeCAaO? zVu+BXr;p%{n(p+&ur}Teq{W3xR;Fxqht4{vYy?D6WEQ#Ipu4R$T8{DJe5m|MVC=QI zCV>dYFFkL!Vr5$-n>JHKJ%TvUp=F+*Tn!_ty210VB!J$Zd*3D4hh+TW$LA0fHp}D; zwM(jSVk18gygH~~CZ;!1HnE+{saa}15&1oa8*hDt$v$-Z=omT(Mv*9YXTQ z<9td$nIGJvGEuf1z-m>4+v17EIfyY4CdiNG7T0LV$n^@BtB>f%umdgB5DRg}7X+3G zhv}EBn+60PDvSWhe=?iQTa0{#v&HyDUO-i*gdYNnqEOv#og!Ret}va!jElH}v@(Uv z`h?F34u=v{;RR0~JOigwu5{!;GC8~KZ8Wb{e%T)%6E8_lxNaAGqhp#_{Fb6}P*(f7 zIPx2<6N9xZXB>VqnGc$xfBU`%))jP#;XhqGX_TtUJb$fnLkEme_M&jrL32c}Oa(Q?AcF?t4R+c@@2xH`! z(I@CwXz0jUguf7Im{i4wILaaAA>$q5+oss)=^UWZu3bcK%jGuL=ce3(wfG)^=Q1=|Kr?p^KNN%v{r$9p@JS`VE# zNw9@oobwv>CJF}^q$zOq;&D-3>4sg%rpG@8CL+hC*#whB-D58Y_Z zQmh5$P*t9}{m^)0xC>9*FCK=yA7~M-Js|}6n2nm_-5a&TBLeuv8^xrIg7s4S#fpO$ z2o57IG601qch9`^Jj~@@{C8Lwktj0>VUi@gnV1&G+MN!{8s`0v^I%(yWv^wq!q-iLX z`Q|#Kw4||W6j%j5W^d`E&zqxn8b9#*qe1egr{?}}|B~=a9lD+@t-$9WDXh?Ie_q@8 znN@KA9HDrF`=oD>SZkYTW;K2gOt<;2-5T{@X5WtHHFj9)qu<+Z^Ik8FR5)r+0Y}}A zKgQo3v>lF9$_a83^slu}h@g#zHuyQ@fVd4z!h*|##$UgeT_a|VqV%I1fb*Mf55ZsP zc&g#6H$02qN<98Bk2xG{EH_7inPY%xt!d14O=p-ba$^UwHrAioCL(^D-(G0SR0U6} zQE!m%KYBQ`;;tD^k1eLY%;}sSpP7`=bF*xMS)-HAGPt((9g}zHnXwL0 z_mX>~S{2ErQ|C8)3|D8O+Gq((F;PaFG3nQ(n#AE@%R^1+JKliNpz~Imm^EQRr>n0E zwNyL46juOAV=Vi6VivK$7}n}S8bMX4LtnlpRzuXylB;`jv(fV;oT^ZK=w zO81CrdLi*bf$vr!Nh+chA&m!F0L?MXLnj$y$C=wc5kK6RWGi`xbFA!tT_PW8>T)5l zr8>snQeyJD@WHMQqX4nJG9Wj~@Y1tuXXDesf+KbQBd>UfIkzh&oma7a6>`cz#=Qxr ztd>>1EJ97ZO>nMRc(3=k&gPfMZAASi;0b5Y$3vPcQ_MU%baD{H|1qZEBR|WIJ zHepv{%c@|s3e<)MYsmh>RBU@l&_vv-Ox_-L-b8e7PeSVbVUqDe&ao=?)GZhy*E~mX zJa(S-5V?gV{P}9}`f5%$GkNf5PYBhOcs%pzVuVw$4f9yclky0*x6}`ThfrQo9JO!e zNx?#@0OOEwi0`kUG0IQ=Afn+<)kGewu#sZv1MZlPkqd8jEln!^t7quXHNF~qgPpHTgocjoHBu>>J5>AI=z=X zVF(MtK0bSzzJTBpoG?n;-w2p{f^ayzv1)B8H zDBQJ{#5BX^Zq@xRVKFnZ-@sl-Jw@MpKo2O-2-XSAvzjFI*)49|xWZm}1vU(+CV@+&I6 z;P{IlVU;Pu!HW<~5v8ULFcA8xXe69#jh=pzw_onmZh|}5=KS_8uEYAB@HlI6Ic;iTNOI=E9Q zx4~+daJfMjYYITe*d=_|Wr7UtoVT?XyP=s;4BVk*#lV6=YMmCq&K@d2y>%{;W;%O% zIJ|x$N1s9Jcw*s`mNEV9#eZ*O5_C$Fh6IYQ!1#zQ#SDu}z;4uM)TrP-iAk$GAB=xH z8wz_13f7>v@ff2gTsB;Tg$wXkr5Ic|HLS&c_N!3ohRe2QlTlA9B>j=Hz8*@5^v5*9 ze=1$54;ib-+_WYC3CIbNBG1${hFF?+a-|A6KG{6;;K0>p^ZuJr$}d`_DU=7i`dVR$ zWa-5y@P=k^Q}Jx>hUClaoEOE;vM7P!gMh{9N=zM1n9`od$`rMwfqE%X0%3h}3FZaX zI<9D}cw<^Dpg@h|S+7*}d=34JU<*qCPfA82A2O6xIXAkXghs|nleI6;;KZ_phP#_d z;Cp#iw8c1x?g`O(!JqD-MBV!r0guU_Ra#^PF&WD5|C%vlOk$}I`AZy+|2jwWf6+Jm zcmB-W<-bi^L*E5e9m}6Xy4k)9Z42e7+Bcv?S|&9iT4^B}1HPoPtp&a6jAApqbP}+! zixy3|2j{_Kz~=&Q)Z1*w&0%6f9hB8n)~WE z?{e~#@W($3(h;lOOfS_*T0%!cLP8^)qL^qn(Rhk#s)J%U*?8K~EHyhE;!n@(SJccf z1{*Qm4@w}$E>OHMFg)Z1+C6pPaqu1tAyx$NAA6aBDZnlJMzo)iFrL~2v>*tuTwBr4 zkx-G)T!ltZ<=|vsxvET2$l$m8^x(IqLWAadN=)Qb+)uDv#d|OxXlI`KgX*~|O!Q@5 zz^q*LdtHIJAOa#PgX2T@)ISsV;N2+6?BLue>#JC8=<0DgH!4ieC2mSC@jUWU*nfH& zwA%A7i0bXQk`XCT4V-l)EkLzjzGD;|o&@N5wIKO@6f&^;B2gNw## zKD?fX-{hw6#pGzq4|R1|Z^YYh9oqDbcp2SENYL`|)S{HQpdj!WileMix{1oB!C23B z5rGjK51T-cOU{pvbf&cQ&#kNrWs6AC7kkes8swkJMnYtZHr~QJyK9uj?1I=S|OcO8-6J z&tLFOex+Mn|788L)iTv~t!*zuf1HObKg%GKx_ZiHg3Amzkp(9Oq{pI%!#0aIhRKP_ z&^xAS#7oRvqMI}uq=}y{!Arwwf|D3ev);nz70@_ z0)K{t2s@5{AYSOV)0#jWIRAD7x0GCDUVsbB7EvnoL>-*Koz5f!mk5s+6k7}sGhr5y zVJ^zb@7|Am_9dmqw<{9cQx;{|7@(iB4Q_M|oTn@3q_8}wlIk`1%u*|YypWMDg{0NbMUED=|BD_e$UcpWckkG{b&6gPo;pgG2LPkYM(0iCcK==6!L_7xJ zr{~-r`g`LF;;jnUOi=5Mmjx|;&iK-_T|-$MCU3;QWe<+>s035Zun0gHT02$pbcqN4gQ~E0j@tTGM{We$lMq7lFlP`|atC zoXDC(m8~Dm_!L)mKKXf(CnOQ5bGca0BOqKMoO;YcS3P-V4pYiYVeVK zbG*d6hAQCx%Pa~7&LfZ1Mi2I1Wd;I92^nt$?G*i7Ss544ZZUox@_k#G{iXSTxZe#E z{}`KopLlAd#FD+z|0#j7k91PvRGj_XvC9_)oYpgnIUYatM~Ru=5#+I zUVVwi2b2ItLJV-%3EusZ$x+|1kz=dZeP!#+O&poUnlcR>eMr#miDH+c*A#y#@aQq}@*adW_#!{mLhj<9kG=fjjlqTU9)|7dnEcTO!9Qta z2NndU+ZRcK%`C@lK-3=It&d$+g0=P?#uv-~>tnRI@k{r>GY1GKt!%di+u6RJFwzqX z#jKAXE4)tc73DL^oo?qe$HZah_6E8>sL+!QG@5B}AYer$qI&!d3vN9=sa2?>HKoCv z>eH(l&N87(W2XdpS@=_0fwEZqFq7B^NA(;*iP(@huilrW(qHHW-z!w|(hR3l5=;Kb zvHy-KYuag-Hri<^Zfc2`MLoH8HvW-dGu}l>Gp)^0K}# z=i^&8t{2}={Y8~Sy4=gmx^_^>!Bn`muV&z<`uw*_oBXeJ1M2@fYx?h^fhMeD zt~&ZR;N_k&$3CZJw=D;<#9B6G7v5SHx&b~Yv5g}W%qltEzVcY{fpW896TUk~KuD~i zA`%fyj2=p5Aoxccl(ek%pvIIa0SU-K1=lbf)j{kTR|o=1zl%qA4(F=b$xgsL|Lf1k zyvJRaTfgta@dO~Ppmk>_O@eEpa<{ zV+M|{y+I!2IEER~>PUD7x&id}iD3-n0^~+^!pBA8B1S?3J%%DyLh%kUv7E@nNCIR( zz)m!+_!W{!CMtx0vr_9O0e?=gZVaK_q~%?|jVPcQHHrp!qo-jAC=yg!DN41k-S2aW7@LNatbbb{-+r!xWYMbvlP_e2^-dJ0>- zmwMhszdg`mzt8|&57#%!jH)Z_)G}3-H&-kHtkt9zE#+OrCKM>uXeaTD1}lq}ZWNXI z9wPjiaFSKHDH=O+V+Ykwdblk+CF6j6v#E#Zv8ghK>aFMqULRDAj_qj5YM%p(lCEjF z?A1%tZR;cSVr5g)FHnn}t4J;HduG4C17WMClLz^Y_}C8DE6deI(PNdA^m$FqYntQV z=2r#2SE;H?dC+&G3CF04rcb<3tSv}MqnHqmPvMm@_*ZG9;%tHPU}O=GG*3P>n& zy)G$dcgo~B6-`&OvXfS1&XD1=etCyIoNFKvK-ZsY$jJ>+NY9Ct$t|=~9PV2s7+mH` zKjlznnG~fZdaYPkM~aiQz>ODe^|Dgl=Hw&AWg~4m$?uCfuV#9UjZ}7-bP-(+yg1|A z&T`OZuaE{W$G?TPc+yY+exuz|o(U$sikptdnrIbYZBFupGe!?y8Lzw$;i9$}N}g)xb**Px7Q!hHGV%G8GeJ$dk=lIfr0lA31oKve}Hf zb<~6gcPSZbsB+n~!o7HCIrT=N!B7;z#Hy|;;L|yg*0b-RvZsVN&7H{Df3zBBc}v(X zUG)@g;z=>8cQO;iyrjB~k%W9LHXY3Y+Zu0X|H`#)i^EaApu1?o;>lbpH zBane5oinn~A|crCf7rW44Ts%)_`@<5tlj2y72D<0VDOrm z^x-*gB&gbCAz98&bgWzGI0PPcnZStG<7TdI-+RCDvI6ti`Zsh|=hTV~T{W(i4YN>o zmtP(_xmZTqf*-bE{~FJushLfwv=;C=u#ZP3&=txosfa(Uv7*Di`AO|ncYDz^@iA0m z(Ys2x&7rU^Fc2FvhrQlg!&I3-q1s(QBtA0%L7V@B^E$3N>pQe0z`{f?8lFaH#$Ulm zF|>Y3o{oY0Cq?T+5r8hVhenGnX;}AN_Kl;zfAm!jA=>ND=~qtw?LxoDW1M52-t@a4 zF8j3cA*RyVBjO?2FJe!TVXjN&)SGgZecn`7YY@9|(2RTgMsohe^$j0dft>sk-!_xh z0ZZQ4tYIy!8HyD&uD~Djf?$7jOs`zXv;E)Y84l@8{|{;J7^G>ttciAYb=kIU<1O2^ ztIM`++qP}nwrv|-=+ddR*4}3(&WZVEBIf7wJ2UdhymW6}9B3YdKUS`ss`H9cG(6eK zq&3Z-@P=v(MSKZtw2{0Y*VTdH=JXumPfzU?h`RZhg4NUot`rlZ@T)CpJ{| zI(x>f14c3QN-aUPK<|-n2?iW-c1Uz(3)Dwd{Nqm^@OlA)YLB+VUSyiPe;Ye?cIkLb z6b2TtJb8{3zGU59dFToS)$G~O=ly3du}AbKVb_G5ewZ`{Us52w^7y9fRk|`3u}7-s zB@>0jZAdLF_&e_uki&rBh+478U}l!g4i@V$D($NGyWgSFAkOF+ew}>d1^dwaTyJ2o1)z zoJ3!A#~FDdtO<+y64(6=jxzLA9fA?~#}(^_{>RNO_g1mOT%RZ@dO1dG+F>V%vZX5H zZ>Pdj^UY`|v!?9Ob@6F*U=Nn-L0VFCw(DVS%bO8y*U(pQ%;)r%aVIq0RJL-N1d)<;#IR=z1&d18~6qEBxWDt+?aKo4y$l4co5P(8E=vw zfXFarHejc}N2$K2GQrC$J%g@6l)QNu&m2Ix5zMU18rhJsreadBlsKj^i+j7S=(ovv z?~DSRx}lU5y+a6*jblPE3K77r+ETWgC6L1xydnPi^S&tFW*f!xK08d19ZuGCw?YqZ zuVdT$XUoX%%CK{#DghO}lOEs9I8d_{{2{)FH;_xQ0FMx<*4nctKzv`UH|SkJe9_;2L&X>$Os=aH{{hjHLH zKbfsLA$F#l*2UMKpsyF=WM45obWc{WDm8obK6eba{?a&nkS_1Kw4(QnkiG+H-X#y~ z5Urw_Uk*czNB3JJomN9XW+tYIbU**HKbpV$@poY~Wf9^X)1z!;JHzj??uH*`B6dW* z9Zd2AmrU4h03*hC@>RT2)%co{#9-v<#jew1h{2`Rls z_o%jLyMnebI$c9_aWn~-6-k$-((E1-NS3JA5XqzxxhXGf%Zd(5U{Z%X52&P_a>cZz z9mHGOT<*YyRFWszo*T}H{BA=6CYJ_wmEf)0)my6?t-3o9TKf+RCr)#=indw`IQu28 zNreaba@1T2H@9LmgDgt^2Ff8)r*e^Ypy(L+aSa*_%($PXr|x`Fep(+iM{9iT`W=iY z8-R7WN=T<5RN>;#ou6$Yk0sBZ08PM*cG_e#=h>2i4z$jYwAouIEGr#&I>JEpKx7< zf83s>ogDvliT(d9^l}q2-wx|811J>FJz$hbtb_c~{NX_utJU99>AOS%o2{7Zb;;0G zX)<3vZ9^&JSAG-dC@bsQm#A>!x=2QU9}oTFkO6x zNaUI>#kbYztktkLCZ46W?vN~UcWLW*@VJq64hj zXzbys#C5!X74a`t^``On3G|(v^$+H7j(;qofsK`|p1q!0sBqW!VCfBMQah_I(%P0imJipF~^>$kt*kL_iw`Vk=2x&jUJ==Yn(g zXNRrc1l7M>f>w^es-V_bhvzT)Wz&VMofSb7oc-Y2xR}2>C3<5B{#;5Z z-fh*MFc^MzPz)^Yka;nEZDyzP6I)8)kneDoD<4!mP8gu)(aBJS7)`=63JYTL`#&-J zna-HvBOxy+0TA%SIAYKp?%`^$OZ8KW*u}Seoz9zqurdN^^*wVnizms+GCkB<1jkH& zUCT|hjZy|!CN|{!tHQ8W=_u~s6{h{i3jeeH|9`G9zk`91wV|1{$$yIb-^vZF5eD%r z*2LtWc|oWWTg36gL4ySH1nfUSifqNkf)<9={UZ!ipVEH@rY9t&Pv@q&Q$jgi^k-N#(O#@!to#BPd5l#r zH^_)9FIv{Dh1L21W6IVv1J>%z-~Knsx(%hd(DVY>DMy#ElSV~jSQm#!AFceN$dSee znOeXn6Z+YaAmpK+bp4W)*2lj|y>294?T7EKlKw~NW|8rLf8U26TYQlO!4xXDW z+F+lSzzVKtHZj4%^Rvo-i>U25~;hfq^z!`?W8ecMq*oPf-XhRGXyx zhj#$nkK^=G{WvkPC$8yCCMMN%n;x0&AFIQ`!OAdf%#~)XW!-=8-VfhGa^5%~Qy21j zV~xFGg_WSG3(R*hY0+DwA3&GudUF?B+M$QsT`YQQwQg|kT{iFCb~R>#L;A%v>N^1- zIn$k*KCiNUup^>e``?-n<6Z>^pWx!H)iiP`myB!`_cX z`=>;`yb}<8UK}`KNBkz}qwW(>E^(spKi;V#(XN+c0!2BtCs(+<>F}z?)Kj?tH_{C0 z{D9cKZ80^%`%JdFTb&57aESIn@dj$!F*2wfbnZ2zvz7fhhN+aKY9h0xOY7-HJr6 zkQ!s!_8HZ=McKl1$pWuK?Z=>9ba`Mn( zj}nYlHpmmK_yw^ZT={VD=B+zg!$p|~imf;ruaL(5gvoo#O5xkY@N&x^QP<4M+9fZC z#-Lb33E9e-({=l#{>IqRa(ak`an(vRCr4QL{F`1&+%7o(``ukK|JYss8(_}K%F69u zzoY-mDKEuu2c$gwr_7CZv#&6pDbzm5dQd&2@FFX5VU)P^0Zb*sCx;cB)0lJ0rSJk7 zLw5i#bDgQwBakPU?ht!PGb!?U43kNB+N<$5#QXXFaRuf}b171XJ0yavDQ_t%56-*h z^>v|5As+yP-@onCy;NZSvg2nJt>w=l|Q&7n5r^X z+mG8Z13!`D@zb-`T7dd8WB2~uNOS!POCkqrxnmX%7Cbr3o&}mkIv^r>+Ru<)qpgPx zF|x1$%k~HLxwU)8mOF&43(~L0G5F$OfXcgMA*pV0Cr&T@kz%9YAT;hWCPGi4y!p(f zvi?f*Fav*p>Fw%=bkt;up1WhTV8RVXarX^-Csl!#J0jafza7kmyH1rHiHq75;H)su5eUMtIQfZe^Yi%fR(OW3e z`x3FvSq1LFCP%pNgyiJmTjQnP4CgZRbR(%n_=)VononCsS zjF^8D4>fqd{QyBS+hV4+G z^%vyeJ&Hw~fIU(=D$P1yS*)D&geVCg$onp78y`NNt3yBl6UUO>@SKTPY+CfPd<9Nc zABLZP$;)woPt;6wbGF044-xd=jIUQ~4LuG|ncN;O&oLuC*1)Gi8pENHD~3|zsqqXn z2Tm9e810d3^C7@}yf&OZ9h$J5(+sZYov?|!>R`l;^e^Zf=+jKUu!R5jpEx+dSPYN0)G;pH@$@IJ- z1@{)dtP##GAL^nb`$A{8{x|9VHBZ0o(=Z{}KSw-{wW3!=b~z^Wd0>u27&$X%W9nP< zzz)I5ki^W2P=OGj2>`{JQ;`-IfnE<}&h#lPyRCiPGq(^dSf;mShPAlSzBJrQqnU$| zM=q~lG|aNofBcNN4K%!!XSxBR`cUqhm(kd{;q-uAK-pVaf_i4)q~_TdRwP-|Gcl8R zgK978IH{xGxEyN&Q&S`$ujqaeP4BNRnknaYJfso~DbrtD9-M_JhU!p0H)cS}++-(z zeL-(W@}b{&Y1t53NMjLB{+A&IM3nIYV%UdAvhf16pk|m!ib^O#flsF6WgcDJEYeRD z>X`Gh%X@1Z&#+jJ&w-Mgh$AV%hzyUm`4+oNQ?rlg=P8IrT$3yiu8;*##@9w`TMAZ4NUrVp-A>4l6m;$TFUtwKcU@-yzoZeKv-Rx)kwzGhFo{H^{OG~I3@b^}%#4XIZJD}madDxyPEpb%cKQ{Yi zFqyP6`&R9_F!gOttOz&jQk(ZLkUBDga0w=qEy|K zw2n}|yl(pf_J9(=41p&N>o7oLsc8|!EYW+RF?xU1$F_1C>x>c)Od1|bqc*LpR7h88 zE}EVrN-vp8C#~{H>@RB=WHj6DJeywOaXSM_N}f!qx}LirFp@JlPCTEzcRrds-mkN6 za6bOdF8ny&n*q=})N+Es9q#gj@G9O0`sZsg?`>UdK z7VkQN*pRy__Gv#6Cfw^KEo1_ESzY zj#CJuj;b%e!naU9Vg4F-kyeVjn{!OMlFuuW(ccBK*HLISY>E*N7>DT151JjwG-4KS zmu9$UIbBLbRM)}kW;nOARgxh#7LIPkdYcWfF5sJmbuehJqf0x7sOwx>%cQV{6mU=x zZgq!)X0WVRt{L-WG}R(>KW24@nmwZ1T~O|{s#pxzH%CJ=4uf+Fc2Q?Ci=@*3*;bRN zfz5~mD{l89s=gQTFmTsup`qeEGVC&mJ1R+jH2WsB?bA1sgYsFfwy+|7*Rq)n#1kUv zAGbN2y~8-IQo4$xlggZ9Sllb|Fyr%VXYCg<6>Cf?=t8jys}U~g$K<<21}m|g{)EvK z&Ue}!^6Y#8CJ%T3H&G&lhN9${WmsRq<2LQCFg3K!E|ImKUd+}3=22I@b+txr&R*n* zjA(NlHq55rhYP~U&!KG!aAanert6sW`kpodeDLrfdA81y1_3K5g_pJ@`D3oVVy!>j zi4j?}w}Pqk1_j;O9n%oF1aoKc!qKh9wylY_$H?(7qeAB6?O;eUhG$m&qe*=dS{9D% zSmE?!2bw2GGUlVa!@O02v!R7fRNPIDaRBwA_kIJbq=Do z^F?oGg$5^(R!uA$Fc2XUyRkL-@~PlsOWy(!S3qL27<&Hp>Ibi4+BcS#)q-28%`iuG zA)9Q)rEkk$bqAkh|8t-G+r>9!zRk0&j-o7N?5n(P2|N~eB3{H3YpSZ?Z6#=H57p5+B1*0IAh0Xt0@y9eL#2vvqs(TBOd+7XTkITl zTFb99J0WNumnOzqTziz027VoEy{?(f!H&Q}fxBW-&Ql;P_>jXskiVLmLmtlaYTyTP zmZ*xF|4OMZM5~DSdcHB!8Ily|5TKnfhMmmlGLS*|J0GU`b$X7)Y*3uyAgka`rsxS7 zB%JZ$a57ws5F=s^L8O-3c+g3OXDU43jxji&D}Pb3j>n0Gus24!`Vq(A6Ov*kn2a;| zbs-VpR)wQsHOP+g+hkIOKsulwUEM~bZB_h?pEJw(Rn2S=$?+Z%?*rkO1blH|lw2&b z-zpjdXL#9|R^uuW)lGAsV4*g^|Ll=*qBx{Lpr$g$j_%iWzC7r7-W^fsU(6nFY7A~) zYMB|lhy|$8eXuG!*sCHix^6^~=d)7b>8Zu_IQ0bkv#R3^6&klTpHY=-%abKcpsLFtZl z&=cRFV%+P*(YQotx%G^ucmyi);D;Xt=*N4iC60>@n%&DY2wo$VOpFKxd1@(*edtGf z3QVR1>|?(ss*&5E=)6X<+X8z zPwnKw5F|9i+NkW-!lDagqp%_06A|6L(N$rOC^=yrmnJ3a#S*g+ECdptGHmeW2~;6 z!#bCIRCn14{b*KX=5LIeSOhU`;+ITnO6YfbVNO&U&Lcy`AUlaSd@hqI)0iQEk{i>F ze{8^QUI!FW7Z;1w2PtF+K|m79&N_-#C*B=c=!u~^u3D?z9gcI)vPq;nB6tsTnPRga z>j^b8(PAgn9nf;r!A`p~aB}bUF6r%Ca}**FhZiRBT9-;41C{a~X!}-{O2v!x08dth zxG$Be4-}8eb0K&74mYhppJuD^LtITiQ5rOu`VoHDR0tL2ZsyDpHV)!Zb5hP@v^*b4(m2CsivtdyH zY(cB!1bb*hHipw5$4#q0Or?*tm>yN3*B}2T2l$3I=S#mgzd(e4+W!6-hWS?RD>~^r z82y(kI!R?i5lb2SQwC8DT(S+tvTZRL6&ixMX6|)`_8>X#(iS?%C$mi?TiDZ0sX!ana*TEYT1l=E6 zFPI711ViVK-~a{hyK4}^z9p=)-Y>InH?4BCs- zqd96)$4P?X1L@A{1CC&)&L9dLn+J1jG$-o&QNBbyxe>&_j+?yz917@Dv4=%Nwc*g{ z4Cog0>)I8TBBuG|yTtHc zZys+Hh1~ELnBwKN^-+WRDi{yr&izo$Qb7sxaeHM#ea191Dy|1#Ld3Dgs8>0hK@ZbC5SBPk|RmnV`LO^ z9c%p43<`QY^!Deg#^GH2iqyX25C(mTGSkP&tdh`JnGNp!abZ{~Mx?reV(SS~wlj~$ zqlWRA1k_95fFY3YzY>X=)>sxCaY8s(g)3L}{Ib0sYZAes`t$V$Zm0>4CTZsWlX$=z z4{pAr&pIl59o{)e^i5f3m=;$>skyeo)P&YJhALwl1r4F4pDHZ8NR<+;l}J@)+Yo(Q zygYHBJ)<1uzNtg(a|JzQyO}HX<*FJ#|IZMYBu<O3vkV6p}pHKwQ9lp-{DP$kxXhc>U0RZ?kUv9Z2kaZbrHR;Q@a zE`xkFIW4@-ZHJ-VSj_Quz6PU(LFRzUvC2&@%DtQ1^qof+*0AS%z2r;+!7;5Am6t?}SbW zrLE6=LT$2D_0uY|sEJrICnJd3Y8%IFn0zYf{S$zr9r9YduKhF`Q@~~`w3{Jd+1AlN zS(J0C+u;|T^|=CZRy@_xLG#s+U)Uo3<=S2I;0kxMtKTgXORd9Zjq|7PnuQq^f_Jw% z^|9@D9wJ6~#0~EAOKzv_nfL2&$VLs!`y>_t?{7I zA-h>!4a?#6Q)+Jt_GxvUls1LWJda5I!0{DOH*f!1YsHYY`%=bvt_h49s4Xo=mw@@gaJ`3w6i~l^W@(f_2 zSpGhhW&cr{%=C|^va#8B2GKW*DrjTv{O$gCG_(0H|9{mtK!~M`{H0xQ_)sU53xf!6 zX;ncGSlpbB>Yo(Phn4P|3%;h%NJ0!(;kXC7Lb`#@_9Wge;yFE{d~XORrB3dhNuw_l?W9Nl|+xV)#|@MlmX4% zHT|LUC@Ch!j^G=v2=sC*@&o7*BzI351|xIn7M7H`GomqAlD$9=lL!;_=sY~|Id1+I zC?2y~Uu}RTbGf&uojA|8g&Fxs;kBb_QTgx*(PQ&d-+1thWe?gFFLm@->=2tOP&oi z&uC5epi?A+i~dGMMjM+&BV{_W;^gWG|16f3@~1{Ci0*TCMKPj+=GO zV%K_j{$NG0m-uZyrv@`-(O(R%iSPW&erEYv^Wq8R1?P@rsg`&G3)G?E#3H&2(vs!( z#y^Eq_*D;{19zns?Q6MLBH~vHuf+-38iZ3A{S;IOtRwLARA$!5<)B$JSy5y+g3jh9 zau|ePFUj=S=B+7*__E1Yc9d$C;5J_Fo1gVZ({xjnOTEe#LF~uF*xYy$3>ihLGTJWb zbbIt$UyxqR>9aw~hJEzcrUZ=>9@)!~Joy%1R`ro_$;4f0h8~sQeCg(ZWZjEP;o_`a zh%*MQL`DLG_)heKX&*+TUM%$^LFvgU!I&89NVo7C8>gO*i9?|O8Rvd`eGY{<)s?kk zP(b#cHR4u_UCLktT;374iO2p%%bi(eN$_+b;!Rjk(sd!*8W(TjB77R2f)AgI5CmID z7mMQ*+-r~M1b^f9NFI$AEX-dba~L`@FTEVCM{mEmTDHrMWM~coelp@#Bzq%zN4yZ5 zz7>ph0aY@P5HFTT$6#yZ@044f=07j|C0{(zQa0|URU`W>*sF$(lUsJ=NhZ_;0_-9t z*ks`|1;A*tl8tyo<+9{NVw5Mb3L*@}g$z}ZdNLRz_4c^M_CQz?s2StGcvNWjkw{`@ z#-558gKEg1EXEzs0GkD!a17#Ky(YI`pmc9IR+Q)-kpwSFuBl3e#JBllEUyTz>w{df zktOi!1K^kJ*qc$#-oBUUr;u9=uEg%%L0-*84C|9)1O);Kv09>)R8OHl5eQ}lW_}o^P)2Wk5ZhRKa)2=|sg_(%TtKED z_)wZ_5C*BDb%@^DsNCZ^&*IH`w)tYiBOj%TVX$h_BDgcjO>+yO8N6$`Bl^}^7=7(( z_Rkd#oBfscOpMTK9a~an1{L7FX~t8k_KnvfiM9&)0!-44cPX#L)Cg(Ml9yH zK@fS$dNdu=SDjtq3uukJnp=e;d3R+RR&+#?dlPypetZGtrc?S=;1gNZF22swYnuq$ ziLECJ!@C?6DBxkOl2VPTdDBIsG!|v!e4Pr*Ip>1+dM#p-BiF0msCI%ZjA?#0O9)5; zn4Lr{r{JSLULpsKc$zQ#T=L~F4kl{Y#1Os1o0NfEymoKZMVB(pA}3aR=3R<*iuK__ zY-3-;YPyuaj2kHr3ehrS6l5{KUb*|A(XSCRNGMX~1pgw5$mV+C568yUEvfrms@lD^ zcu8Gh8hGw8(dPK(w8V^Uh>%~Iz?Xo{qSY^qpuf3JuaZXYkv2Jm+%k`OP%2bEsoox| zad}5diqfNqlOkit6UQkTs>P)ikH!*8sSfV$gbsPoXBp>*Ae5wC>aCiYb3+59yF?xA z0v~hoi%Y40;|#3ge_&ki0X|S!O z|1UVc|Nf8vr*HqOWz{T{lvYqaVI54a*|qrkM<^c;Tb|sbJ=slJMmnse&G)G zn2CuJg-B!b^yfKYA}`vNp3L^@0f)eK;1?`|kS%wF-tfSFn`YS?9ag9Hz(T-7WY8Gl zoe7|xJ7S|sp#U$jP)u`2{#eqqll{Q7lYJ^^_ILcSK(JVVMq4@U)QBnUX4~0?JprZ= zR#<*m0$3dEW{MZ=cEIJ{EqI8mgR55GiJefND!XUY00Zm?cDLUEq)eV_AJj{tzs)p|ugxQD1%f?ESR9 zbEDOYe=teQ*t?}(>IF=sK}DFea~Z?ZX8vw)L{c}UhRdvb@1ra}{oJtO+~4bIRy~!v zXVmOUm=PFhG9BxqV@*3vZ@d<-c?{AL`zg)h(pT1iHOkBlF5#o9mfsa?BFPpO9?VwdF)EwleMWtCB@wO2@0#8@5>K?!IeomE@V(%c%Y zZ53Hc!OU(oc6DDAYdMCv$hO{ktVg~7RS+UG|7y5yA3krk0lY zI}%R)CJKVuzlq|oR;<-Dr31{Q_h7YI+6~?xi(d`Vq#4tpSy~HZuIek}nk%g=e~TTs zC2*^+Or{O`BcH2D>QgrTZlalHK+YdPB6T6$H!b+l805s#+##-L&}StCslW(E#7y)S zFju_=b0tK4X0}Za@KWqn1b!X65EV9 zxB+Br)*Z$t3pJ(!XPtw}9gyIdB##0?iL;0c;Sy{{5%Jfo)$2K3=x$0(Zdigoj8!GH zT1`PkI!2LiagR-{eGT3L)YQ#4ZP=Y{%?c+2gYC77A?$~{sBj)PxdNLpx@esvZUu! zJR2lZc!4V}2yHY&Cw0+tL9Ryt>RXhY0Z-jA0QF;1GA!I)w!`g#C z`s9bF$sj`vqIDk8&*wRZV{dmeE?+lS_=wzmWPWN<&T9cM6@4sLLMf_^xiE0&`IZ#Z zx7nbWxl4Ne$MV&%li$0UE4!=<@iCWQMG0qsZ7>O}hhkff2!o#Ie3F3Vb z3U_k(ll1DM(2TfxHs@MNaRG_{)&etaJ}mSfwpAJ(|*duh+M%yjkA){!m)C_ozmE zex?r2B_TTr{7B6e`sxZTdCNY2s~+Buq$VAPo=c{Mlr2P+RSy$FPAbbkvT*n{aOg*r zSSl)hkCBgyv_0eh&|}+hmIerlR{zSApnved14L{)BO;)EhDS&u!{ypLluu%;UsT4r^~VE*m~=Rkh6Yk%wM{B0t;?jV{r&Y@ zx;%pl3UgEzCJ3STA3^K1aY6xwtV19SrG z;KpiYqNXNX6(YMBQ=A?2f0w>r{(`K%(<=ON43k?}bWUC$Pc$?&ipRG!QHz#Hwx3L6 zs6(b$J-b(UFI3& zwb|J?CW_O)rr#m9J25fSlmeSyYWBmZ?P-A`+C72QEuz^ygYg1~y4dB}-rad+zTyqg z;P09oEB{C+v z5#aeOtLFzpoiVu6I`?!zYW+pG{<&^-8zV=?8^ROO6B)T@Ox~Tm4ut$h-jz&ZuNIhC zL^Q>N23w4uWfc3kJ5@NLP;`QCrGY7a691?bkK3Bo$gAwmFrU~H|A-i`BaygLmX$tF zRk@y_2UyQ0!_I7>9vY}blxc>fZFXNApq+nMPtBH)l$8n3Ca9EILdKWA5LdLSFUH#^ zkWAQ_FAT-z`Ptz(o-9YuIg=h#igUSRD~|Z(5XXLt@^>h8brY?a*=1S86(9&Zr@R{wFt&*^+A#30KPca@PKd2Rzja-1F*c|(|zcdxE6rmX)-yl&t@;{;K|12W= z?*&uR$llt>@;?h^m9nN~f)Tp+CvM)`3e2+os)o$|a#Mf?EO4L|Hfgox_YTM zmkM`?%@wW~8%m9PASiZ&O4xh>;m&@regmQ9r$eMDUZ!%t;g&{Fm;=u_JS{G3;vMrX$fc%5BdVWkwdnKN_7F=ao-m)%P zv9#1Ez4|^B%wVb|T}QGBxeljW)0Tq-lH^R` zq>1qD7H_FaGf!?i^RApLJn>V(TcTM{3i? zQ?9y0C9zN4+*e{WLT-2|@dWM%M>!EU%+_yP1gV;DF#v417P-|MbxNb3O}!$|-0}D` znYa@NSR=+oeO+r8*uiR!2uGFc_X~%@Wg{}Ri*LE=YF-?Z{w$JAn@H?}?*V`|Cx0ka-AN(Uc@mI3oTc+1{f$SrHu^D^!^K!{|<E>%+~N+j{F z4bPVlSf!!qxlH-k4XOI5*L(x}Hew!Khu;CV1f|4gPnD(|zJne%9j>`&+PrRdyx$*I zeq0ZVqX?rIp&(JhmZd7$sSPop_$Yio4RS!KqkNYhzM|ZT@JajmINMT#%?)oB@)g1L z+(lQ(hwcKki6so5QIL3z*ed$FqL7G?e|Bd0Z%D#LXa>@6CO zs_jZ1I56bFeVhj}7vzb7Wc~~}E}Cis%jA2SfyX-9Y#sV+%IK(z=<5zw;_W21_+W!$ z5y@b6dTchp{;3LMO^17ZKrBsiR_0u~%$L7*Ut{a7f_=-%_NMkER#kw`rJqszm-e(r z%9-b_>ZC$}R79Ocf9;maorl-vOtO0AA){4H%2wqC`rlL&_=p)vlVUDbOZF-r*$6ZE zkMtL==#ELmCLDo}q;<#jgNJ4+ux2{ao~nI)+q>9G`ueR#>6R##Sp9C~#lmpsu_db( z*_QE3Q5WgsNV}Cn6~F#ejrC?2GNZGic!F{n5ULKTja!!%+47+2c5V}@`s2{54kJujMjja98UHC^jiHhhB$A!ks2?Y!l_zAV33$hXvPS=4@0Fm^Bu@t{&TT?;q z5nIw)y_O4>n_>%!rPlmnL9M2Xs0RgoO~r! zmYv3jAwhMAa0@xnKMKRCiMPfSMVf8(Lo^{9C(^o3Mt#(BuS>3g#*|H*=mNZC!TjCyAv}fa-+S`<2pikeDgX{PuHld4 zhT!ip=5$<#Xct+x9~ej%r?PcUw5FwJlRjcCe0I{goQQf%t8}l(PT=^2Y)eGff?qR^ zzr3fND)+k64;k55>pq z==Nbj5RZ^dVfJ=~H)-Px2xu)Ni4h_~b70&U(C_stl2(;r_WqW)t&jGK>jq z^?ydBSunjtWpbOA>>$1ow#4V@edHQ-5lNqkz*0=(NA+3_ zA$Zh}{6MsVJ@|nK`oSIzl-Y~V(?`S}A<7Ui(w0T=j>6Gx^yUJ6uv7TVIe&+@{)qTL!9vM=BxMnjbNsvEhV7WgnQ|Hhr7pLd7^0WbwCS$Pe zzT{wcDyJuctXt*_?vtuif+OPZ4o17I%vGUVs$a!+TQg+M%Mtgm7#=D25azmSj51qE zb}|UE)Ho&A<#s#3m zqTXhIggk&_0t_uL$^La?u;Po3rF_3@t_%Hte`6>ZIheWsH}9fqA*Zy0^M&(d=aK>y zKK(P|w>G%N0x`G4hjME1Lw)R?upN5jKhrg>(0(LP%RR# z{B64b3Q8mud&Mp%Bq?&H;_WwNi_%%M8~^=ivzE$jo_`GTJ6|6Ph$;@-Mm5?sk9W}^ z3>xO9twBs6DjcM3FEH3S3A1FV7&~F!0x(%Smt3u8KR*Nl#9{j!d7gOx0ip&;qqwVt zfKWdH1P)@Ue5e;L@J3 zZkzzz+W;KHN`{1yXhPEZynUx(pAVD#v))V~yM^fCA7>P<|<6{>PCTj`-01FweZ( z6J+!gHQ^G+VA;vr@O{xN*#&4ygXcn2_MZWd9+VX~iiKHUg;>np1GA+QhPieY15Bvb zW8p1CbLj0*BaOS)x1(e7d}D@^_=w1c;hkmXXcDh8$1R!SC36Eg(^2-f#GURT{yur|Ny?wZu1 zGBh}!wt+QUDhz%bomx zQ<7=v5W;olsew@bhWr)#E4ddX{c?fv=9pXqaUQJEs{dr6DNWgx0mG#FNODpJ#blg4 z&UKhRPHe1q4b*wOJ^aZ*fs4~t+Sr&2O8i7@1Z-biT4QIN%RQfY463?od2Kgl)!^u& z%V?m13(c7p$^_w1ZhS@dtj--&mDWc1l~XjrYP+;R{pA60!} zV>>Yit$Pt;SVt1uFs;qeRn3QnkwGOQo&kjoE3xhZy;p<>7P;HXs;qZpln;MM8DQyF zxR;je*z!O%yD+j7;T|bbi@R^xKig2a_K2jjdE4D)H(&42lnh42JEUF@_LJNJq<&DL z+t_c@%YWf+X!Zv!=B^-8+xyY+1+yJ8wq!sL{~wgrfR@^u_AFi2&3KcDKSZ^um(6^_ zlrot%P{|%wo69ok#-@plip?uiij7Dm*@1T#*USPx%}vvY$d`z`TO*nrcFF^C4O8{< zSR@ir+a?KkNyc(^+Q+diZ0uTtVOULCv=rhb05sLhk*3oFwhQ2O zMVI&?KY#n7F$SQS`9y9MWXowLZkGi`@=0%DyeUZ=#k>e+wV=1;KVoYraz%@F`xTn5 zQ$KrPo-5d3E~cCWX-OBI;xr#oNSY#oSyu3j6oQz^Svk}El9Z4#2wi5DzeKNja?^e^ z{hfZ=pz5y8Q@o*ABV%~S)O;-G?6pB$^ZWhV|YS1SDXIR&y8XndO@c1=T;u~~DzCKju0fJB+7`;k)j0JV-WbrG+4I{5IAzEl_z8>xYtAoRX;e4o2LDB7U<+;qd75kPlv!7sV$ zUY>yx2MRk!$o$^EwJ*3%$e`9pZAL03(VVeneb#9@Se8fwMAPfma+wt8dDOuT|hlXroM84xIeV zj@wTQZ?wo2p?fRvfdadu2zmipX%;c^#;im5h3#!JX8P_3Rg(5yG(g4K-OJf(fPWc?~?aw|*LpR2yBk`{^Y zyI%6U2vS3pu6cQcB4tVT;~$yD0ZBE^46ttr8r;Q`o&H`35rMtqL_?=Kml3OS*hI4VZ*vT`3&Fp-j$z1 z9vJXpGFD)c103+e|9toNj&^0$3#A%Rj7(WImrUEWSR z|5ld&JMcIOMXPl|LiKNbnp_bsC6tXTj0&w>P4r$$49DmNOb!6Z&%?_ z&p%^+qTaUfaVvMeB^JN)T7)BnRiOoG#R*r_I3);kdk_`Ww%1oLT-WMHMjAd~j_40Q z^pF!IK6;QaBz$H2^Rhko$Fl`rgVND#dGo0!=4B|>CmdRS)H9o-Q8)~o2n!=PZvYSA zL|7Od(htw@7PtW%atlLK1_hs2OL#%G_}n?JR?DkkEs`X?D{FWMS1qlS z4IG^u^bMVa9Q0lP zn(y<^1a-8c_FpDO+=AvU)WIp^tO0pmjl$#vcm!m+FaUx{VF6s|+G_}?6E&-w5!ZXN zh)BUg1-!kiU!l`HnA292X(0u0j+fb-#~Yrwl-Qz04p7Vo^b=A=i)_DNp2PFhuy|1I!}w;8Y34_C5ZI`2oI?^>M1BNm4TETL9D_;q?KluRDh9}_Sor(0v;AnE)F4*Yz{kk8EZyW<$|uehv7gtdgrEM+=J znOWVW;iYCu_`)6oNek#)>HW_JIT-kU zWt@_MV&L$*igQm+DmUIF*cq}vATW!zGTEt>;2E15hTT{~JTyqW(o`rv=*gpc`c^=? z-C*nq5xaP^d&aZrgyT?~{(={!tUDWDJsUK?Pgz0ADs6W)wD8k*Tyzv}JB@*7$I{Lc z1j=zdpp}zd|FJ1KuPBjdkP(L&PqCJ3b<<)d8kYNKKqp?cOgJZ=o<)7>9Ks9R^Fm*} z0oERMS>haF>3Y5yxiV>3zWtc}VXFY+?OtIErXp=VmdNq>gp%`wyR2{fud~v>1mQdW ztrJT7TPvi0YdZ6vXXXDsBf)VUG6Q_@!dE0RS!`VW4S|TOixG`~dIgZp&H&z0> z;tdNQLhyN_1K@TF;SEO+VFIX+Ha64SI5VbyJ;D7T#O^?EWrH_+<0rG*14|6{kXNX# zmMT*lm!l=8b&ikizp;JMjHnt%6lyEzfbJL_ASJGuWeOl2$nOIx_qq)kpMBa}`yx^e=l zf!{r7^^*!{Z_>zLI&nx=yDchVF1<$ZLzM%O9up?_Lw?wivq15A&nEFWYyNHHILlGj z=Pz+#FXoccWVu-7DA_1^>#rSuKt@=MWndy;Ei}4v{(hL~P6!wYyb`C4p{N-4$ulvi zQE)W@nGpt?Q#Jks{kc(#exnD=qoTpeRQcVY=Ozv3Tn<_RA0rHK9Qd)>u3|Mboa`zcHo>PWu#Yv<9{hv>bM z_+Y~{Dp#<3GB!+9lHEaxN$oxwn@ zDEkzxf$y&0#P=V7tQ6wKC;yHD!GEh3WdC=n|9=NaC4C3e|7e-YR=oO4>&k7by>Ie-TJh< z;knIu_5Brl#mnOhWQSMD0m%`8nZlgJl*C+RlyC5@ZVj3MMLvMJbpT}$Y&F;eHIYW9 zvn?RorAd)iOJkAmV-7K|T;Mtw*?4rHY0}IV+#Oa19iq6P=mOSWUK@& z?BY{iG{}1EM*R7OS9*C^VGIAFYTp?M_eoHJIZKDvX^2s_WE5Kb;M{6)y;>C-Zlp_e z7(;3K3WP}W1rH+Rfu4ck;FAXj^djxedv>kV29b76tB^D&pEuuXYCIGsj#`3~nKYNR zx+s2#d(v;0L>S8GkPdXzC&(W3FH+V5!8n#7{SI04byS+5PWUT@SAP%s)ZItolTu(T zx74>ZZgHG4STPN6Djp47u@w@>F=&8jU8xAWQaA7NDBU4Kl5{2kKUoG)`$Hn0!SCq2 z1Z*Z7$>_`MI3dY0t(T*G4S6$xc)mhnT+)eXpvtv2ZDr^mv)r7>M2^6|(I)=4Xk+;Q zh_?R-d+UGsm2xLCvA9TS3eZB#IG6*Bh}S9AAfgmVgH((LOD>2OMR!PRgMh8V2AleT zQxr&WT?2R_8!QzGQ|#vZT&JgJJGz(-XXN&DfBmS1R1K{ztQwfLANirL(FXzo0)!!j zF={Y(aNQXWp@u4vrYP5F2N8){W7yX(t<_*B>E2Q&=4O<7#yOXqe{~@|x1Fqi?jks= zc1gK?r#)>>B^V z>Z&yBTxk=|$nm;{aG?3*zO`WWOG?ACS%-D$4A}dgqR(p{FDS?Bh%)=}SOyT{ljGez z=v2LeU_)}Ad)Fpn3&MSPAGQrGMuvuojjcqQbpIqg@2r{QZ7$NC`uXW5#8_T#y-$aq zTFk&*bmb^bzMpH~IL6Av^joNL2!9N#kKOk^PQOc0n0~+#CrT}kB3i-Bqxx%-O>~qq z`KN=7Gx%?H41ur8oc$I*w8^RgKA=RiJpzraYCRXHc|c7CW%lj3HwS{ngaPYe3dzr6 zi_&si3{^VDkc!-rONSfP1b-tpsi4DB;zw}S6`C7&P|2QugfQw}2Jye9;Fta_sHp!( zQ2lk8>YLjbJNy$*$=^;*>vYK6AvMKO0Q;7PSo@ZIP;fbJ)R}{!B+3;`jo;ugQBaH$ z2(SVJ=Cy`<19&HEv?N7d60>}b!`9t)oa&mAzP)~agY(l~piryQD-KW&nbqhTtJSV- z;Yg6I4uB$D{B9q0Z35rCcohH%VI?H2Ugfr+yY@ej+ZYNzq=qX}BN!@fMbO$nR327+ zPlc`uYtO%rVU&FttcYt#vM=b`INI{77uDE^Xpm#+W_|CI$r6{BR-r1Yd7f^NJdKrd ziI|WLG00``qMV#^RVmZ3HH!IghJV{mXBY2UVr|@46JB~b3|*ud$FT^>ebd(MW~mw4 ze=l^en{QO${FQH^vR;7&k!dzYw-tkgGm1x1q^IP>0d2^St)5RXQ2XG!Jdi}j?Cw&` z9hO)oSRt;VIIbowE{TQIc(cHtauxi>f>K&2wfraOq;L!`Nx%Keoi1rWN^a?vqWh=9 zB3H})61VH!xemjrP721!hEw#6uVIA{P#>kA9grd}Z{FSwlnFOY;kiA`J}xW$#SIP# zL)QH>t}PeME_K^<;v2XL*=JClj#lwAp^oR4N6EIp*s;PeHYyj*JIG&Tt5^Jusrwrk zYkv!jf7`+FpLd(M&3F5+BZCl;kgfCoc?>FRe~-LE_mRP8CknZhCQlZiOgboHMy2v8 zNag zb{d0LtSg%?G){CXib4P=1I|XiW6o=l2eQNe%TE#TyWt*{4n9v(j8CnX9N+^`1}d&$ z8bmJI6zH0OV&~|K#2f ze$B2FykkIDcpv@|h^HizQBBcuTLW0fH_++&ff(_vI2q4=Bwwx#%7K>8TuepWz* zoSV{KT0n^$TX)&7li94CX(3UEcIy#jrmH%Vtbp|CL8H;efYTYX=YjxKmyRrvY6Aw- zL5cZ$1;N612vmq6w5T$9Iz{z$x_Obla1%%mnO=t_snyxKPHQ%oZ8IsimLL~uj(9C5 z1sN(Yn@6*lhBx3V)$psRbk^*KNtZzlI^=~IHTU(|yQ#(;N{1>r zeBE*)kiI&vEiy4{=uAhdZW^1T=$k!-IWno!x$>LYdt_ilmAW_vnza5xmfe%`v(yJ; z)_%t19Rm){1nQyYyq)KL@#39>eRh}B$THnHqqzvpm&w{cweYz&F7ne53C)m_?S;L$ z^jZ4urpOC%6B+I)MfO|eh*-<1QFHew_NC}D9Ol&XDT^0Y;xp|Ll0(20SL3*fe`+7o zBtn&0E)Y{lGKJf78U%gv5<)eiNXg|SbBFhyS&xV>(58VLj0kURV1 z!F*V{`NoiJc>g>q*2B%EUZp%Uh>o7E_hLdmLxbWTtI24gT0WYVsxo$gc$u5r z*(P5g>K0$&($OYg;!=rC-b;Q)HM}p_He%0yd{sWKtC{9;RXD$Eox4xB@TcH*VX=I9 z8`QQ`a&vf&G`8fV5>$E1Y<60_gv1e&fOrWc4)FT$4JV3dYu`juFuErQBf2xIXRI)! zdI%xs^+rI81+xQO4%^ciBBHkol>RND0L3lrE$mMWcOduDxR?#iE{&#FzHUOQAJ5@# zsTJ@2A6L6{E;Et3v$5MnK|F5nUj}~aCzIt#k`XHL=2GX~(WN!nNScXE`w)t$g|O@u z&Z5~4N~9vJ9A_O{T{pWH!E?UX{a@lfc$?3WzB|5*Lz1`bWVg{eMgd3+H{t*6#T~&} zdsqLCT8H1s(0~6-{GZ?E{}H+Vd80+kOWPvRBV*4?H;bc*<$Iw?2#~E4G%DDF5Bdx7 z$q5l_IJh?3>{(c=uNoAR#0GtJ;zGVWuE8ayxNt4Al1uw9mq^ zA%@NK@J{2F3~(oxD;z79-gi?}S}Bb856mhZ(_o>OQnW1k?kzr)uAQ8w^DQ)ZM&NoZ zwMt}I5Jh4vKXhkDLnRpLMNxPLJISyE++@&%u9dMi4AfD$8pAWYo>xsSLS3MpnKt~q zKC$Y*#G{N3ugF=is1LoD{2Wht{jMjXzQbw3E&34Gian~xmJ~V9X?qgY3NaXfWqV$X z`+LzcS~uXhqz3ck@D`vnLz$DTK0fmucIF)h1Qg3?-r4ZY!(?P|My_G2465mE3<8Dp zGEco?TbRW;`VCfY+(`6kt-l8pBO&^04w4k>=?5_(`ZWJ=d}I2ReH1fY)jGk|Q-ict z?{mk988!4izs-5Jdq74wHHDj@&{Q>jWU8Vtj zLeu(J;^3P-|9eFI+hOJZd6!w~yW2WD(MtW}=U+r8Zd&3yWi#AUO|SVSdh-(z8P(%r zR*n`R*l%T@1!tam-D#}7_9tENe`Z(xd*@%$-MzncXw_XlWe0$T!GA{!c; zSc4Y6#ND~LUJ|OJ!htli&w!JO{fGP;sz?}2b z32koxjC*8yPT*H;&lBH&%m6MmRH=LTriI~un~eFN-@gA^)Bi{s|JSvRmXo9fl1JxO z#Vb_SxMHP_REdW`WFbI+`6;kBTieOlWnnZqI;mt}c%{0s9u_1<_5OobA`3%_02Oun zCFieMaJE;pzkVFa&(M|Wiw&3=TpfB$^mMgJ^5f$OXkyYAF^uMO2l_af()ro=tC?3I z>MP^xR0Pq;R|xU6S+T3s_P=ImDgs_u*6f4LK~&7y(4i4UQ2U=ZAC_egx8-*NnXjA| zJ#B`VRyb2i1r=ccLNOOpPBX}Q8)uWz&Ya~m3bwK}N$Iv6Ca;6vD-XbNnS-v&Q_y|T zEsP=_)vRR0X0Jbr@le3>JJZSGrrDIRLBqg~hyLTUQgl4{n9kHh8&f0hORt}j_ z5B`kG54A_T+6Z8aCXL$jA0=Ix_$hgA)XXOmz@zCSV%hc_WaNGdu?8dw*fmHa@x$E! zfLtmMDDfPc@Q#>HLLXr~1uwqSb}m7_P7Is$(9tQN!$6;Q?XH198bUARD$UsVK-T=C z85^fiUpOs{sf6t&J#j>LZ`6l*={#kag@|!uhj)jTcC>(qFSI2^vMv)%2%wI7uFqo z=jy<*b4P(59@I<~ClT}^aR>#04)s080(%lK=}hFWFoLJ(vBU5vE)!SedM)@;bxd&x z(fV-1h4@3uZ#(1kM?S5v_^`0}&#@^Ml#%6uv%EjQXZ3~6DQ#IJ=kyGoc-}99GdZ?e z7$lg0jG`KSp9mY2a{fuA`%v3KvO%2sv)Yn;>57^|SH?fp0vB>{9YqU&s`5V}{@SK0 z#?wc(?`I!-ZH7s|~S;x03OQwfO7`;fGK6=KSn&eOG= z1-qAzN9DIJKyL*az&O&eJ%;iF5rM@9^9G~QKYHPx3}}j&i&)HQLI_WB_k=Bvpg^z~ z3XT^^9*UrQ`t1Fn?%PaiigBxUAd%{Eb#$k&Bn${eNa3BG=8w^>w(mc>faoVm6kVMW zCg|55mY-0SRK%r-P!KL^dXN{QwCntG)d89bvt-EmtFd=G?nW9zc8rZ?Uz0&*^tn0e zYLtz1zcUJofo9xIc$ipp-&QhaA#3YC1qwuMWTt;+d}g>dM;}O#QxI%Gg!NqQECdOT z!Ak$c)GbY)bbxdtu5K6xZK7?yHvH${%-Hv&q=}hhk)JG#W;SFSitr{Y!`JWwE})p% z!ThXTYKq_xc%~=cPA_?A{r))6@dC*Detl#?Xq(U-$X=NCA+i+D(6E$jgV(|#wDj2e z&kO_dA;0Lnl6S?^px@AWigzrbWes}*t_;Nb#Lwlgp&u#SQpS$aW$3d^o^cBxbB?#3 zFsA4_d#`~)(CRe%;M!bMc159iP23Mq^#Rpx;;Wr8j1EwP@}QNN;o@uZfjuFVO=c62!d6TPf5_-mNU zFBU-!MCK_RN-t?P^0}>Y#JNnp){vkNs&lv-$4|>$N|?RBm;&4@mXvvuo+`-dvwqLI zEocd6r!?1eH{$|$N*c_-rwMx|7tpb^nAOP_WLJmFD-_%`H+6XfN{D7X))AK!D~L$& zSs|yH^E#MP$RQUfo?znO(j|Cj7%$B(Zq6^$>@=@s{}E>xTw)=??%K?xhN%24Q54=7 zRLP1NZh2%jx8px(rog%+y82wDqd5O0w_;4vPScaj-8OM;AVG}}?a7#&B-P{)z zzgQ~_Er7P$9%N1u((p0+j2~PU`l=#F`o~YoV03ULFZ%x2W4BSD10fnZK3{!9mZ%Wy zS<3KF-91SWv%oM7$M$Y8D0_!K-7=DQFM#Bv6N$*g*Nut*1Pa8?tUnG@>OY7b+T_HIP<1 zcBEhyC?Q-+cjcNX@+b|D-Ke?Tg*JI7soPHouY)&ql5_A@ji8l#Q!gNzEHO>k83Enp-=oSm4G+{<)m3H;DL$r37KPX(f~G1Zo%c==cqakT zCwJpAY&}*9Hc@c%V>5Iks@D6JcdSS#{b6=ttQ5jIZFtG1BHk(^Tz<(VQ9mfbDL=$M z&aY%1@FL1+cD9LyWwK62Ev2!91u0NVUL+Vx56zZH>mUyru8FrhZm@WRISRRgh5j2 z+mAydvb>_Ze6oJc-YY5xA$Vbn79Mt!Z&!JAm!1kD8C9oW)RI;|znfdFhN4}g3Ji^& zk#ABMVG#*}#-u)e6f!}*!oyj4F)(>jOJouRVG#{Nr844lHqd9W^7URXTcaxFqz_bC zd4izNxY(viOIreQYoe?|6|G!S{Y6KCCbsM|Yz@9nMB?Jq0P(H}0t_L!B9s_Q%)wr$ zIDfwenK43-)P6IgF_rDmTyEy9Q(wl1IsEbm!;Kv|UYwbL$ zQ-;|oA=tFOBJg)TB936L^Kl|){6VdXeryS$3-EH(L21*?O4HurX7SNZ<-^$;Fm4U0 zyhDBTN7t%_SsSo7N1B|&Q@g2I^~%gf1JuE^qYvhZ^}&PHNn-O0VT&qd4cgprJ%%-e zg+ql!o{5EHp`-K^K0d9`euf0@<+2fx*vTc>sZsRHo8!iaD=)m>1T_N6id)(XoR&0$ z$x7;HCAsWijP*7sU{8ySXC=VyG&+S1!_Fgp*=rn%w~}1*bTVvwH|xf%fAop)_F}I0 z(2t}HK}_avb0IUfBc;U}B)D$z>x39gl*{G2A(T6{#Z4&yw1ujneN9h*Cq)Qiqrpiojl2ljpBJ7Yz=cL z1vn<}ppkRYE;{!Ju0KOGUPd=wMj5ZEBzmE+*}>fEvrN+FMQFHgSBuJxKzU9F-#r!> zfT0g!6^8DCC-D)+c(A--+d?e8#<~IAY9`>8iI*Y&Ga<}T&zpGTZfP}rxH3!~(56Ns z0x@#Sw9j%jS17w%^qX}*u~z-ANhdhe<*qx<7n|RIs@4>2I_HgR!ImJxCx6EsPZ#)>AWSy8CqpK;{o3F=M1~-s z?X3K#$=>BrO~=3n9z3%@fkyx`6xMHUf6U#^%?&TEHwMRFB~S1@VP2nDwYi1IF{g5e z_DpSb?&Qy-ykQ0_Lt1QuT$893#%rK`B)qoaVk%r-F;T1Le(NJtK(QZaf6+q_ZOhRL z@E<=e5&w=1{m&Kjf3bL3=kI}K|D6$Kt6JJ&eKVpO9ZE^8RryUP2VF62??Vyu`?p+pT+P3mXM9W85sipx8NWW`#*)*b60* zp*w^eLw6+9$SZKw5qjImEq+&1Z2Xx;aa;d;I%NkmEn}9b#4xrZ8hZE0wRZ>}U#dNV zImWNOvM9V=AO@X*P~&&>5s=BPqddRqb!^P}cMT5Q>`}8Dd+O>pLv!XnI%b4ellQK% zs1nn)KpeoPA}=-Wiq}QMqT*tbkG|)kl*vKGF|0{A3wdqnVZ;o2UF|g4xJh0*k2DkU z&Jz5brF{tBUp2+b+{u@83LB<7J^+!dqfv`k&<AZpyZr46;@Z)qO->`f za}DOHIT>y*6-!5-$G+BE9YF@3$l&RqDc2&O$gfC-$L8L%+H*Qhnf798&xpY ze!ucC(@S?!r)7{3W?XHd;v&X*CN{=sLog@KG5{K+_DY<|SC#V_hgHn*am5KK1N5LHi9Hj5sm{jfhcZGz|qcS;2$rKV`#}X@hb5!35S#aPix(u$qRMggp z#LhHNfHfT4XHMu)cvab$X3d88`T10P1Iwil^`{GQk9@gPSQu$2H1H@EGs60cyO?b zye$Yf)-}v45oZGEkM*LCY@Cks*9Q}Q$LSTw8H~fITSc;2B zt`N_KA{&EDo}i5Iz^73-B5rB8`wXEW%oz^qSZ5^!TU-L1C3IdW8Y9Y1WC=Yoau0FK zlyCCdv|nTyd)$K!n1hvbwLGc)5M0nihJ)u#;i;?5QQ)~S3EV{scxly0lYZ?PH6MpMoBXdYGo-LDgVa<>+cyCAkBly=7!p zcIz5}Dt}h#D0^5(SMS5Bjz6=(BU?X0WGMl5oyYku$TOgWj*Wg>@*#`hWxGUA^bjgy z3vk7)0cWKo$U};srhVHK4_xRKfyQ*-9;6cGtwSGXaRt5^BXGo?4o#W)*q%>22b=i@ z5j=#p{~bfoDAy&Vdlp(<{vpAVXfiXsa16*&GLb(=$rW)sPl=K!(8Ht+(c@HE!C+E_ zT3$X81QWxi%zcNUgf!F616z`_L?8jBGL)H(;wiG=3wMzm8lw?zq=GDD4Ynb1iM)N? z6nD`)ykUNHkj|VPBVjz;l`;=>es+Kxd03wk{CwHygjXYlbElGgar`o&M*Xj0Yc6{t z6@}^WwV2w?th!(BP~H5$!Dpm3?Z7rx!a44DZ0_emHiW-i41s?}6~b}6-k?9~p$0nb z!|bD>_Y*wsT0=u2i40nYg@IzjSG&ns_43=}!G=@I4dF&b1cpTb4-bl)8G!B^pdtm( ztnU#Q4RS@N#v!Pl7`#(*5%@^%U)d?VW0VfAvr&Hv?{lWnv)?5Bamk`zoKp)mm4acj zY)6~U2uNeTAoc;C-fg%i68&~e>M4*25DX9xco6y0FTtx_e79A~NZm(VDp<4A>j(#e zsAvCT)H%6xWBY3F5d-^?O9%$_%l40V`xJ@w?|>REttPX4i&?+qqU?~ypBiLZO!(R% z#06?7=D255Xp(BOBS>YjbqZMfB|EsM8W!c|ZIK+wuog;>a(!;*8}O1uOlY~2Z2o1O z1iV>~^G*_VRBjkF3F7K10=dfvCff5ij5Xqm!3{3Iy zkt95Zt?s~#8|{axtm4&FrK@|VHy13nHBDW958Z1npa?c#SFDIVfrhje!I46L# z zm=(|9(AZ3rSo02X=s1B25$TW{b};VX!b8Y?&~hxV($`BO;gXX$ahZxnn0g4(|CFP+ zv2xl%dJTJWfUIhyMJ_cVL!(`oC&8=n5D5`y4GuW`&tN9JT&4~ ztNV>xb-u%~26XIhD}A)AuH+`7W<~_{^cjB$wYm`c)uNxWHG0BHH(xkKuCHJnW)p4G zqjU3q=}&5yys-fsd9#EI@n?X?1}0%xA-&1o!!3G~?0qj8eXRt9|955wj(KAQ8&~cb zx9htzSGEGCKFW&tGiqmmsPQzLd>3X?wx~GV>1aRco_zO_x46mNJQa6&Y$=?5m4bQs z_O8X}AKH^alKjWP@3h?f-zF>B{(qt7pGYZIwU*OT#qfdcnAoHxBaWjnH=W2{p{qqlu_Pm%hT20#QIzG&2`LuY)^ zoSoVL0t}pmo7jLn%m@=#)h+~#tc9Dz04o#M#mhck%vD*rTSJA@gs%SAi(Et*UnHE4 z)%`#)jE`HbuwEvgRNguq4BpfHV2FypC-52w2MEuf(gs;@E5sG5+5tFT4q%UW@G#`w zF2Hq=GN=OCJl-F{9UyDK&5-BNz0oxO+5ky~s(Scg^j;!*O86LqY$O3`-`3~|{$K%a zz=8Z;Dm#vVBlO6F5JUmbolZUY*TVjyb(~=%LazzEsUY0}-27QWT6}POl?87Zy~`lD zBi{U3h-}faVD_kV_v;uA?I-t6@^nHqTJso;=pPrirO=z2NFJx^(U$$8UHh zwtkA1x1ICTozdDzb34;*9}(MrGa4%0)#xGc)o$GEqvwsg>*SB*%9f{Q$^AgOcxBu6 z9MW5KeA;H^;eA$eF%YGwiYv{ag%8ar`9@O`gv>WP4883aVYJrBMA^7VM-a@PJSr%y z=I3S}^U=d))o?W;amR-Iyy)`I7VP2%vZfE#GtJPnmHpF}#ZS0c46m-hvHkH0caee~ z+hgkBwK58O0z33MX~d#$#aOIpGJUZ`dK#4e^B~_$*}Qk zb5pRRc1x?5)=cenGnJT|4nDF58cImBKKoP9p%nF?p#H~PU|H?U$G4PS8dF7cT&l!9 zZ7C=7)gA=z?a7FWl2Ip)be=FvRptdJhKb^Gk@Rs=;$>_dhLPQbz231ZMtBmv3A=n< z>MA{XFXqfO%Mt{IvmW#*m09HVH(`RG(gS;pBsr`R3HGLq;~-{X13mY$A@-hG@8pA~ zIwAdVVo7+qZxV{d)&mYTX6Dm#;^v0nO7(;W3TsakWb#lC;6eKM$Ru+O9wJj4v+J6P zdb}b0!$Mv>3Stn+ zqC*N>uaAs){0v)@Dcw1n!-diB`mB&`%P=W@XV(MBOQjQi$5esH4s*y|%qL`l@Ul>c zz)?y>`Dlm1B~lQ}1bIB>hsUz&Hfju*R+d(*lIuQ6H5XjkAR~_=dr0T8+X*u(H;6?= zwT@hywuMlXcC24Jh5cvX!Lj68p&g}b-u=~6KhbYzron>xP^w5P>qAOLnN)@~$4jsC z8Oh*43X*?PYd8Z`T8x*}(jd1+k;n%F=8qe}R9m#kDJza5RUiho%N?S44Ti>zT+ZGE zr|+ZT)F>a{c!@Qu%GR76*`uJX5wu#|H%Q2wXt%zKO)^e2(HuCodI)rLEjPg~Q_THp zY}vP4v`UW&uFRG~Ty-oXlwm-D&4UJ$j~=%-UIpzw3r?% zIr3%n3!^H#bZLhM`W>v28RO>nj?0FIRUd!(fp&9jGQrg71v$EdiC@U0*+ABs4qH#v z6G>^a2XnxXMQ9i_nxcJ(Z9#ve^IUgzr_L#;AX47t_EdC)>)n(SeUpk1cMZ(i`3E{h ztVi}igz)WH6S;y|4XSUGi@<){>%gP%NyQE4*dg5VGqHb1+8FW@y?Wsm6ytKbw9c3X zkx3$lPA8w{4d9fr;j4#9D!BUvv(@s8@j29;MVh5ka9c8_dhUhwf^IM+F06Y=9oN?0 zN1s)Oi9OiO8&_52`+eJ>>UF5pVrnfUtszWFEyVmv#6%c9hU+fH0=>yg?hEL4)9-7p;?jH3!rf;9^wX4Nv`1WeKEA$pdQ2wgE z;UpJLYCTXBX!i>TM4{$=<-uyRvy9IzV;#K1hz;mO#KtBcb*bd*WbQi)cgiTK#^=!1 z?;NfHN-X!w-^5`fTYkK^m|mtY=Xc@Z!Zib|u13iM;I_BFKaoU(&mK0c0PZ>n_2 zSx@?s?1|kni>D2~RenZ~f;KHtwn--BouPRL7dXn;sUfXWN^874+%N=EfN&baLTNv; zgodN;Xu6!gIpw90343aaZ2PnhdfJWO$BL=hd&>dADaJz%f>p?#$HA=8PpUbp>Zi`b z&ny?=?8~f@J4-U*Wsm_HVe<31mQd?kjK?~ZJN|xA2s~1+1iDC`@G5@!Y$Xi)x@Ljq z$C$|h$Tdn9oxN1y`gQwlfR9Ufkf<_K|GhFE;j+942QKj!tiOnQPk76y);Hz)`L~qo z-#Rz{_iE^W*};DjuJ7cZlhWdMIkfYV%LbP#AUz0JXpjp$UtV4yf{y?bGk_QYTxJaqXx)SZq6E1_F+&4?*&VX>c@{boE$nRp&H%nde2&S*nHe111jO+<2un&#vGQN^ zImlPWKN96ZeW3@P0N(S78fpO{0AQ<=*unLe@vr&8RSR4IaA08mV_%3KSKpr*069-u zubQtV9B+~QN!3Xv> z>kU-A54qhB*)%q?HP%_fy*RN@kQng$pXLR+MF2%ooy2qU{w*L|2yUu7+*V9CmR5B3 zh;SLt+)L@tKt6hVvTiGbBVuXKz;NJP27A+Lzjml7ZD&@>BE$&5Oj*GbE@oX(x6Av0pomjn` zG_rlYCnrB=uwe3Pz(=hCpgkSQKmVFHmZU%k4{lPWJkzkW6#a;6Us_^!Jf5UB?E7-~ zLz8H0GSrHDElZYK6AvyJUg4m` z{F8=#_Q#?HDRIA&G<0t^r$)^I^a73ifY}}(vq^zAhR)Q$r*84L__GGVZd&rGxZIg- z_!E)9V}DrMQDafnj0UE0#?~|Q0H6AM(;eDgXvn!(l3_@r?)ehiAK2hC8b)N4aatR8 z0%Bwno#u;$s>D+50`YzgTkRNq7gNQucCLY43@u-Eo}BF*DdH+Qii;yjpVJr0LOI97 z$a46Tnfb|KQeWJ+Zd}T7J*CPQD93&1_47?pEqK}DJ#F@urCd;beI(C-avaEYMyKRgbHI6aIxTuhdB3YnZA^j>&J_H-z z&0sAy;H#Ss6y#CtSEF*H+ym6j2adzBE(PRK++R$Fh`Gs^PO?l5?^86EK-!4&F?KFc z$+<>cYO}^J0^RRZB0f2^?k0b<#4jujv#CB2YnnwR#kFACYyn`AcVkx|gYo{X0qZ2X zh38wv?W2S~Gg(f!x!%=M)sRs-J?LxP*c@OB`>d-ihGK13lJP|K2et>Ig&~gQYy7Ad~XEHz5 zs&|HLs>!qb0fp?M7b*4-(LyF$-4Vo%EglQgAIKj;Qc+nS*jbRm*<$#GK~J!j?U7ilzUDwRZ}SeC^hLJGSkP zZM$RJwr$(CZQHhO+nsdmbdsGp=lia2Vb8g)eeLg{4(gyzs-F7&#~9B&?)&)B;88De zRu(R6kFvpY)(M!=DI!cyD=|=raf2}2d@B%g1tZACHIRFh_P%gv``NqI9dMo*TZF4>#UxwQ-Rm}b_jS!p z$tpxvGj+s?~I#wc7q2ft^z<;WvM|_C!lNvDOYV~gNphae@KH2ckqoR=?mHS)gsV3jjTc3 z2YPM!lI!|cNDmzC3x~)d%4mz5@&f2LoFvyNdZZf8pS2TpzO)cxRo;i0!T|sw40Ino zt2}{W*K{+fM6e(B(15|IJUpi2ADOv!x}o!GL<@|&*!=WDQ^rvYOOflk{S;fG1MtOT z)q18*?dWj7;qJP9Jwj#b9U`~ZwuvTuL_W_loi_*5G=Fc$NgaL(&;@8=0?e_=R+!vTll+0=Z zDk3bA2>=uuhcD^DbF-wEwog$qXb8FCIG?ocNC$xALF7jKCYgNWi4FR~lG(4K$Gj83 zoO!I-86(67iiJm4%6pjXk!c0?g8m+gO8N}X6*lv%`Wr1LEaxui8HGoVM7oUMvpoDJ zjbcd0F|-SO#!PZff^v^35aXJ@zjby1+r{w6aU9TQsCCZCePP+J_*b$11<32DYM9(E z0Z?00nk90Kaddpq_0Qh)qJYvfvQ4X`dX6DX3I6s}^m0eD>7?WPY1E$shd?LTTs|c> zpM1wEo5=I;DYc0Q6VxVSSOdqnQXe5x&UPlYrVCB+v{Vw5uIfs#1hVwtE=PXhKq$}y zZm<`Iq+k>?7d%DrMVqvplh{Z)1ZX93HP5!Pu#$>2UC=6hM@I5q3ls%cK<*90SF`*~($uY69oqynE}wb-sKlmH-rq^SJSk!S@hbLzufzn+tcjDz7~}#eJ~*yl}y?@UU2Sg`L+J*Rt2Cb-w5^0qU1Yc9UtBX_w>43*JwjPn=$^ z=3sc%>oPw|&}HaDm`%D`Yu$lflf9l#w$H>J9|Jz_`pFQnS|BN&*-k&oqp3H6_%_{gOzGk z+>OxEnvMFrr1AxGaT(pxVy+$uKfUsm_cbW=#T6q3C!p?GmjH9E_J_;0tb42!xKRQ2 zsQ^V0P#TCd=;;sN3eEdVPTEw2-alnH~_sC@G?cMWz_rmr;aN*gA%nY9qirw2vW za<&mtUpym{o; z5Jr(_Kd1wtk*J@0+jw-JiET;j!09A*l>k*vk18$zW@5vt(WO7a<3?!l5q8?d(>R%! zSkT+~+!|t}Yeh_s$@Rwu6(XVM*9?16&ydfkb(_I74_1UqB;Nh!=n-CEhMnow`pRIX zk(&kDuW_YOo4uOVHwMmfzz}!*!*C{TQ7&GxwD)UPyRt;9)O|KLp8UHb>-f zus`<@VyXh@eUjhx#+9oS0$6YM7OV$`O zlr>!KJ!BDQrH`{op1)-kg(MUx?C|`ycJY1I(hdfVU{-r1T$j82X>pGqLGx^g`tfIP z%x(2DVfp2pa{Z5v5dXXV&VTwp|J71O$pm!0cd9ZP<0!D?4p*V>#pPxtmVKxFNS!Nf>&Om$4w z>%-kHqb2S=;9~7Mzi;smEA(Q(D1#y;Z-U(+V`;$ix;dH@4jCh5Ivb+mRAXp$gQ~IN zG{@*nUp6Gu97-v)A$##hdF6aveMrs%1*LdfX#_Q94K{gJ!@JYv@k+}lC}sz_{N%zc z2KPj8>~{^$XKvF^X`WG0p8Dj;+ZwHwR|S&v+Oo;Tg&DVu>U{Dwc~@rXP98RJnwW|Z zt;QECJ73CDMnog|%@x=A8a7#8&!EqK-(Rg@R3O2Y@C@svB>o7bV-;EB<#&HBcVP0; zCu4uLw8{TJ1-}2b;`ncytWByGs@O{y-X>`1t2p0dV-ZCO@Pny3VwEhbP!I)r6%qOK z$;j)>gSQ|g>nG#W);7znehFzbp?OHup?SzHs56V9fa^1-kks9{y*B)c+0Onrjrncy zspwUH&)v|_aZw*vi4 zkey)1KRjb7Ii4DCCp_F3sbVxa>MAu{W7tV^0E1y-lu6lr_A_Vw!|t|RK3LyVGgh0= z8N7Z146YfxUISh!79S6-9b}DS6vuy)c+~g12XNa87zP5Kcu+N-7Y|wMR*3!mo2(xV z9>oy9QoQ9;9;n9e>wR3l$7i`fPLRDu=p6XN1aGRo-0x2>a#2>^R6|?-o3x`q-c$lH z-#J0n2uHQ~@*%qeTfY~7hl98c^|vDeeo6N)v6YOaC40ujRl4@_)b4}3b^_rYY(eIV znt|+J!rQ}w^p2Jxch!#70pEst&h$si``VZaM(K=1;G+Vm(Ut52h9zU8W#NU>=mWV> zxwi0>>l4azmP2oi4Djcw+?C=g-GyX=*#6-V6R4Zp##$c4tPm5an%*tL`0Kj1Y#0~= zYmQL4b)=SQ!~EPj1zua0tr$0o^uo60E_ay1{6Yn;Oz(kCsOj0XRReDcS|SE3dg$fc z#SB4%IoKe*p_{4+myov8!IW2JOgmej)RG(ZvW{7y>3{@{dfN_HteKJ`HeZQM9 zDB{GjgR&ZnrDf88kS$jTr}4J;Y5mirLTGT;2U2H*|FWd$&e)>V_Q6j`j4^`+m5O_Z zv2G(O==6NJ7ChE@kY;kgaRPpxm5L~9i!o5#VHZ;^mbB>=DoIOm@VweADYa%=D|4eE z@Kef#p z9-V0pMS)tPfk)sH9X+a> z0`tgv76f%(+)DO@h9XJw!}&n4IjN-k)p-o*WN5Pznh5z-%hD)7`vtC){7bN&U?_{3 z2^C3RVn9{9*_tNKzD^(&Yc!x|xb?HH3`Ypnh9aT!I3dJ2)WyMMT0iVqO?W@>NvgG) zVc|Esm4yXq74|b@`^;G-DCu2=|AP>3f1^9 zE^*44`+pykuKkwb@WwoTBlu3Vrj_Fque4(cz`itUvkM)vgdhe_IDlGq0h@5FwHL2S zkr@n>?II~DE@{Q&9XcUFMG}aKH7j|e<}3quL*BpufO6pISt;omPBjc{;hJ;f%kok= zKUinMK!= z_F%L&F~kfu9k9w-RN4Kvct*R9F?Gfn@hA~3|r%KH$-dz{%Hp;#U?rVHC=MYSF+D3v19tB zjmXtwVV@APGME@aEM1F7#2qA~AW2q92+yC#g`UobLfEngy_`8N=e9bPGh^$FSWx|w z1TB1tu@oKoO{zelA6XsLBcUPYhAS_!3KA@2#C6X*GnZ#?ohcOiYM^?mg^ZA(0Awc5 zG&7Ak>Ps?7I>!a;BN4loDVRFR(w!e*U1|ek%*nKj)Ixho=F4fBv3r`V%cfa^mda_#rGCB`2u?y(V%jD=_m5H1-NvRA^6 z4I^V{c^mYkI)&_J?|{Eu85Y8 zW@RG0KDE7C@bh1(DTadS!9*3DHgam`Wc5#^b@sX`FN5@Z#9eFi1JQ8GD)-*OCVve= zDU!vAZgQYqDwI4SnZnJSg=hqOh~K5!sX?@AJf%m*go)hJcjm%&7>9knKY6ylTRA_J zm)gJUUJ*a@OBQ8tkN!gPDSp){{ZIkCWgWTG7rnA42=i%ZE!#NdxR4C*VS@%$r-)Pr$Q?kJ$gI7`+B^-ukHp} zaYx=W;_jJqpk}XQ%qv0R(w0FZ!*_%x>lHXQq0(2bu;wb}sURjqmJlvSJXR*GBotS} z78SpP3jK(5f81K&`uoqu&nrbiRO(BEEB=oOFy#NM>OoRZ|KH&+Nh%PYibEKmGW8iL zmfHN_pe&jG*b~;@ebMl>W8qPd1Q7uNs=6(;<3(6H>|B8Oxz%IB)lts<`hczqicqT5 zew;4>sh2<2maH!;Zn`@9Kee^uBWE>h5^^o+u&rGu3ZS72EuwRcU%mAw9cD}Sq z4>(|EuUz{F+n7Hm2lJY_stkBwZm(RM!1&BvtHAgyT)V*Fxpv)cuPVPzM~2)lFbmX|a6#U021@fX04?}O44hl*WQb=bscm=6r6!SW zQ*RRwvVPW&elQ%J>pbvtkal4GKR+caLaz)}iLy#y8wFP&Xc`8TLm3G73owfVcc=;w z?&mXu^Vw8LzjR`UjvjM>ZtISEKei(#`)=?u1#A~rUvO4pEC^TQrh zJ2NauqErG0}=EL&=!+ zq8Q+_fYyV$#jdWJ-KQ>Hy5iwu5;#frPJLfA187-Yv+lnZQXBXlKMp9+@8x{%US5;z zii?Dv795wPlx&4kgqss|sb5_&rGJ~+yH2GDSB9MK5|7dpUqZJc@e^$&Q^;Maa!Qd* z-y9KIy?!n9-o8>5+dQqm)ZM+Kv!!Dxk`<#0VLB0dygE!s|HfSH@T*2Sj3&b{Q!s0$ zcwioOKhSHKMl=$N5+mGP(!DQCq7+ubpwcg3?$f69(Tnb%r3de24I@4LZ5-YYeo!g=j7nQbbCEK( z8_+ao`ZQft^mO4sMjS=B@}Sf(fwW5H6j2n3nGw}kW{%m4^{Qjx8dG*sbTSDiFY%f7 z@C2Xyaii>P5R)u#bXP@Hvmq(aW}e)Y6H4XlxbiOW2K3}w)* z%zJfYDwcgXELpuv`66Dy3C~S%T;`VKO1r3ZZETci0|uH<#dKj~eqhDdRR2|?^(QU8 zs?SSUAAz`GI2k?FFKl*Vf-Xk@B4K3TZ1m(`@~|R@B&>RJx_k`H^QH~0im(0sL>Z~$ zSX!{O`5eOsgq~4PAz9c*x=cQuN^4%*WfzZUjuUT*TbB|sZYlK}Kxgzz8!Ust7NEtn9gK|iY*~vz z1>VV^aD(XI(a)I<{LSH{e}?d?ZpPg1BC)mO9b}b3^lf@eVlToM!tP>&>JryfNOkI0 z_p>n>Kq?z>EPoF~rRr7B40SquhP||>l2y5`))1dg@h7L^VrTo37D)_vyW-ZYMkGN_ zh*fj7jCX)7d4a!n4Q;&IM(%Xj!C@X3%1-RebF0qRk1E9V?=x6WncIu z3vGL$D_!dOIJc$XD%H7QtIeF2-qv|=b(lCSo?T2=QjkoSQ{24$p65(fC~#9m=29gJ?bSt`=#-!vo7pqAJ=Bcfh{lUK7itZc4l};Epp74>+=m{ zx5{#DPqc_sf_ovnB?}C?!a`{b>j@^`p$?YsR+R^{^XY4nJPz5UliBgAFK^7 zsk2;DL@ZAWz{4)Ozk1SmrlCZe@Rl#xI5t7FRQo551FcuWv)J(>gnYB>v4eCbvNSrE zNcb7^HBG<^uEd>}@L|>D4eI!6;h;r7GV1}D;qTb8&(KKE>mm%55)|=k)aJ~^5dE-u z9#?Ko2N&_m`7Oyo@iAB)=&r{0Zy|Px^3H{&hu_8F_~=cf2cP{VDZ^}y;#A2|6qUXg zDJY?5GH+ZxSaclC-lADePBXj2=_dGKpNAIc7UF6^Iaf3D_NB2qgmn)I`t&dzvT-cqy^lIPoFcBKU zune}a{5JS{Ye|7wmLEo;9QO)o{bldu+Jbh12zLvQ1s;1Kl((GUYyNG=lgZg#hra) zB>!WYn=_tuoDG)T!I)NP&1a!{rd z{#kKt=L}EDNdsrjImKbFp3fe4=ht!HuLZ_V_I0#M-V2F-$B}d4Q*dDnf67(eiimB8 zBQ1ZEE5Pl2`N`*47Gm4vj?P*kV%y@r$b&UJpkkXUq8xqfDIv>LP}*twIzkpd`m}NT z_6haJWrt=-AAZ(X>Y*vhKk38&cS{~g8-xFBOs=?LKQD`{MV?Z~1X#41QRQNhOR-HG zq)jI4(U%YNla7atJSr6y1{RpNPv)9c(Y&glV8NuPSEOgq?kYji;+McwY}535N`uUF z_EbwwPB&m{c*q}C&=jK-sY3h%vYQYZB z2GA!MOu@hc@p_qi{NVVS&~rZx!6~HaH0ABUSTU^2QhO7_#e%5@s05<%XJmC#4ODei z`Gtkz_Ha>^s1E8OaaM?*8wIubH6@T&qEdv*tyh~A&78I>In4GviS#rjxX7#1$Q#U* za#|$M)7Bj2n~LR3TyHkZo8^aumuxG8rPu+eb51I;*0XUOoC=o2ujo&u7wRp}x|E=t zJpyhS*ZK59Xm)&lyaMK!Tz?PoP$X8U(r7-C6azPQMr-T0Z>uHf`|94(5Q*A}eef$% zh)qLyr3y{gj_o}RmMoK_mN5SntF! z8EnRR_r~Nz{QF5rELI2ep;^sccnYCnc@iZZHfdNg3uE8zTWACBj62tvUEe|HhyyOI zYo>v4B&m>X96QJ49Y2R?foAbdN-T*}dTNd=*Z`ibC0JfdA(3Q+=wp;@XEavNK}R4n z^0}Dz;0@0GZ>*gm1*y>+*1dqq64B@wO9Q5~)qY)jy4s*Tm!3QQYb0q|?{sVY0PWZL z4#Ts4X7wGB@e1yrORz*c2G>*F^=^<}wz{XYAG5?{tx=TLrO2d1Gfy+8WrIXI*dnJb zQE^g&fnz76IHkC)sYZuD3KQ=fVu3~%z>(S|bGSv(#nAt(4radPX!TWT4P40&u?91yqjmlGbJqdh0D+=iEoiG0OM#9X7_TQ#FVlu*Ce(pB*|MEzVQaRI5T*3Itm}jSR5E2v;Wy+^d zWG)m-7bF@kf}hi?g*A^YoHA&7d(xAPO{P-6;0R z;gQKHd6}Pihq}$9e(!PtP1PF)z3D#5bm6>mKhA9Vd>hvIW<8=Kaq}YIS!m0*=N5#9 zOheI`e_h^h0a-(-DW9sGD%V;`S8*NOpV|K<#e=jV*OY55zh(@|q5RFimjc-%-&%Za z5ww$-haM6D+{FhxizW!s4vY=SpT`+0?@1> zyekTy#IWHD2Udp=z-QS%_r2VfF4SCaI~|l8FcO~SfDfP!-uyb&*AL$M2U{Q(0s=hB zb*(QxzyQ8w9|XWV{$^kdIQrZTa{QNd;B%qxh?6J8%-J&oiKC}bsZP?`%I?qS_Q`HP zF`S)20}ky$H5}SKIh>vT)My*R>H|*nl^ZQj^^qst^VI$kr{A)+v;zw_gaEw5gdEkDZx_@Fne+bjdSMgRa(vj zM?%~yOv5e~tF>R->5sPOeywqmh#CnoFr34=XYtMSA#* z8Xa5<%v>UiipTK%%JPYgC-@r!0mc<)>UD92W-w{hD;yV?b~`cIK*Ig#wfo5?X=7U+ zWZgU>T;}28pu4SbGUls_JF_~Yqd&Y-=#*B_pyOkI{=D;|K@XM+LT`KE2Dz?KY^(4! z{iHD3IKO+hQneCg-jtW+>d{VD9$494+&C{OyX0<7sr=+Me}{HiEwdvho2YYm^>dWTa!cS38t^F(tew`D5ObZ(iRRLHM3BusxC z69Z%Z`Pju=m$l}zSA2#xO|)i9#&}FTx-D%x0lEo{3l_x1jpPWk8MtvLbFs*E`#~o} zCXamQ(eR9>=7S|zc5;u}s>iqu66QpqD!q+sc^Vg3;jBa~Mowya1FJJvX69!p{J^i4X>H#K8pP5w)GG^j&uBp^- zcZ%bo3eqs_)`RFJam1NXScNEXP$L}uo7CbUg!But-E2~L$H*l8F4d6-;86DdKE3XRt5sTcnHA0=XMvEZsIkONiD8g}+p!Q_-#L(!7I? z`UJ;nH^cQZoCb#KHebfX$xI3%NiS8q*%Br8GxB*x1}QVF z5-r@2f(OI31p-V=Kk%1^YDa!6G_2UBl~Xk>t#Hn#8sr#eXrI>==w&y5%o`Al z#Ytig7@HKsvr@6%@vJbD9GZC2!%)Up9eZQ=%!)?W;<>So_R!b5I?#ez?q&)Qn&?!! z7*7{RO{`Ax?YRgg+qO3hPdY|`>{r6UHtXc$V=y#L+y&e|$`=u%JJ0Y6y03jeJJFxV z#*3X}qm4UwUIA^m?NNitpm-*WuXdYp4vU8jH)rvh?;4tK_@Ln)y_~y z_X?`c{s9fq{z74VL*hTkHL*liv)8KyJ-XGoado`afx~G>>#Rrncyk5+Sbzpbw&fQx zD~1C`?@wdS5xRg)IyY4-=<0WwcU-XO6}euJTC&J2{tg4Tdv!X%Ym2CJD4hUKBkNYD z?~bekthy_E@wt<(wlki2le3>wT?8o@dU!`6-;nKLvP61e8|R0ZlC77>_KD zvP0>LhH^E3WHO4D8;$7g2@Nj};y8!Cwx2mzZHD@ULf=`mHI*bZbVrso{Ps#Pm6;@S z@UCK)fDClExRp7!uzW0;4d@kTW@$p8L8~h@F;o`hBVFeh+VLf^V_=c0Yh`0$cwu0X z%u^iRXpFdT!`1_}&f;tUM~YgSx4Je%6yJ#DbzV>~}YXRq{eySG!oD3*a0$8`6ep zi`%S29}5>H>5J9J5>d4-|6yxKKDarM6zTOLwq4dA@&U#Q$PQ7xOP z=g7H}+KJr%%vH_{cfQihwMED(CBXMW&CKuH5uwlmYn>@s=pr^ak*l+$qAW-VepWW^ zMmf5N_jIj3>TsaMnY~8xq$s#Jj;xn0E`3D45o#kNdjRVe1bPNI$bwbT63*o+fuyaD zbz?Vp5ovRedl8%1?oAp+HKTl?HG1adQ{bIYi(RF*yep9yXGkQq+s2#uEAw1)L;9TR zYvLXCkK3W7e>d^|Dn$N!0TMIyWx9wQG;>eeto#P$Fh-dhB-1rC5eD^x$f#DsG| zO%IU}wp-D53iK?y&*Voz;@^26GivwauO4Qff+)}VHa7nyGaQF5K){eZ6 z`f9n)^6wDtr(pL5`E3Ls&2ZeC4#vmXoQ#|eIXYK(-<)f4hvm^N5anM2Wx#Dp(7ycA?;I5MA5>NJU)7-U|Tkfw;YPLc=W+h!&RWu_-}@1oZ0w-1spL}kKx1UjiZ8$@JQz0Ot-MMh~kty4UhRO@Mt zRG6~e71<=UlU&BqU#xPCw<3x|oYsH%vJ~PM1Nx4K)bP`C}JwIF6DBK!Z7^9ezsEuSC3N-5Zr@&}{BLC$N2gc=p z{DuG4ko$l9!U|sny`IUx(wU0nrDQgKz_#?sP216t7J;(1%&iNGaaIy2iMYoEZw7pq%#e~|5Wjui# zul!I^^{`yeg!2f4w3~pc{HzPJ-7#9A2UN+k?;3 z#>EuvUM1|g31QyI0zX$$B&=aG=uM}w*!>-j;FSoBdnI%`TJkldpL5ML2ot4DB)zXngg#9n)69GRB`qsT8+}YuK^NA}@>Gfx zznLty*clu*kW#sz!4V@T_)uM|9-eSY+E~Mw*j+$3)%r_*Q}UhVFCW&$%y#kSuVW$p zkEvaM>u>mVEDZG=_5P#P6a0E3Z=`4VZzKOGg3zv3A=RTMn^`5RB-%|-of+xNALi^n zKiZFOt?nAC4J9*clFON(wT7q@sD)s?HfKHq(6pcIcyIaGIq^eA zakt$s4g3=YU&b!P={@I7=X(TR*tLi)qrGSK_3z(fp2*gDKZe67M;JFrP16*r=kGw% zQOk+P&ei3rJ-1eA#B08Xqqw){)8KoZTAC`=sR%`7pDkp!RXDQEbP8%GY2{(zmc_rA z4>%mg-?}NdQD@EsLY~tB?-1yW{K!ynYLc~nPukpz6`xPewr4q)w-S}vFp^QURBF`RHtMQozAVyK-fW~- za@-R8lOqsUFZe*1i~FFTg~RhtSUgW530QIr!rE z;vwXfs)0EGwBE+Z(h}v)=mpd&#V%@*mPYRlX8$I7?4AE|z_b3Si(66EHpflWO+Vbr zJ$^3uZFnvaqEN3Oreh;UEL-~a0{%f-7NyO8CvKHn+zR3=lUSiuNS)U)NT=~Hn|J^^g3WLg^Z-B}V15-~ z{ovVlQ-&ee2MEe$;NJW3k%^(}A^+Z~*oQ;>BnQcq@UKVOoam>e%NOjJ|4~u-x6u^; zKH2}{M9WFZ^#4H43=#*Cllutp6=uCLg+Sv)M2aVAzS%c3%Wu+*=C;W~8cZcV^G$ZLWqG}z zc1bx|=QbUQn6L;f$e9U)GKp{zgR=4%*0#T=F~KdccFV;ouZGd>m?8$Vc$p8!HRwi3 zmZM6$ZQ?W{%ctCjsbrjyo=JeM)`|x*+f|6lIcb0tpWbK|ZS!)2C&Fy2SA?m#Q#K0V z!w=H5dPV`yTF>PyX$(geY2Olc*gZc*$zUspHQ&l3a6e~u&z?wxuif_?-+>*(hBmS( zW&l45)QX>-2jH+2rgZkHHM%hskj~hCK#Qqr`&z>zwi22rp#*3b*?ckw8uI{qD{4V>Tx+x<%XOt4xZ@-z?1A?&FIL1 zuYPSUt&Q51*dY4N=4{4EHDu!dqRZi*bP@cbOG9?s z`JZ&*`xjk;{!JH<|DX%v|Dj9N=20w5AvO1rNfJ zn&T3Z5y4u@kPSHXg-TKTV_*TAS*4q}#1~zRhR^;*mwabKyOuAyRDA!7E;(OxN%(^< zs9$t3`A>9F_CzSPDvTL|TZeQYP;69MpSc;=q@M#h)|B6_}Y0zgD zSkG^GL94O|N=#t(w$8>TE*CGq-9NwCh6BNE;5u_(kZVdCJIo(i{#K0jA{ybaBUy47 z5Y`z(I4+79%b}i(m}6Pt8=Ht1a5l_-Kg;T$GhC98N;ciIN`78orf^l2o$T&!G0Dh^ASob=pCbKSj_71S*X$W;G|Vsw;^%D?Gj4Sxidu58v82%5OpP>@4RN@l zN=T>+WFs=JlV$rI^^>L43R&3aid11}UGb@DeMv#qwBU6eC&j}9X7gX_5hX1REG2mF z6iYU}4o@cHRDIry5UcNnltOjrm>~1Ymh+1JB7{~CvD^?)Vk}!*jZ08D?ngpC{yZ@c z;TjJFM|I)aZ#hiUVy04N;k^U4k6G+jlWA!V$2C6QTL88Q+FyqV6;Kso*ZQ0DHyVLt zy|_J8f#^NPV5Q&M^}5RM$YRZrQHV9jQH5F>lo0d6gyah7{dKqJ)wPiQH<9@R62V4T zcWLa}M;6Lsw^Vz>#1luN5d!9vOX(>O*nJZ>Uj3%53bALMK26m1ZHO*oYA2@^KBqj3UjfHfz4S2V!Z^0e0l@eeA z>fD+Co;I3XKns4F;cev=9cM=_Pt zLAcc_RQI%}@|u<@=9DBT+`sOPY>M5SR%Tlm1m>KorYXR?G1<@B%;JIKf5FJWwqEE4 z^yhap`-EJ$bGX!Y6!yAi=_S}1Pd#8~KM~#e?-tu43qJ1P6M9*@w-=aAHHZtVx6;s# zgTtmxk?N+Um?OKo_-(E=K8eb?deG7s`Ohu~d>$GQo zkGPRWl|X4xu3C>KolI6SUu|x5+z9fgB!f)ql$9~Rk3$C0rbHONoKQD{T&!J;XA@#P zg+Gje3&*A>s##D0q-a0=yf(cjkB$Oe`moBZJ~%X;-C0q8msAH~6$KqbZ3X5no{fRC zMYi)4ASC6>94xYRT<`?)j7UsGdZ1z;vOpF&CVk&`H1$*q(z_P8Jc5qD?b>_ zVUr(8BjId#|x8%%nWhb`=}`LPD~%8vP2~h41wJ+E#vxpRM`8 z$6r^JJ92o1-pPMgB*AXMde<+$pwUeR;e()9Y`@ppFfo0f<>zyG{tOQLu`iuy{MA^zIs`+Ly+)8OS#&@KQpIC)u~8ACD{VJz_oCX%~Y&MlJLFNy3seba{Z zAqU<9Jb8EFRfvdGChZB2=;p^v_LIr9xt-6C8#G^wXQcrr7)s3UrP|`XZqVW{ql~&> zZWvzkXR(19idzav6c7~6q2lm(NRgn5{L1~f@Nh^O5l&$z$M1OsNGimhBzqD#S9=aP zTj+7uVS(fj3mp2Q;;FNCusPzXmO@z7V(1n^wB50E*1K3#qN?$+^w&U_=&rt4pt$%+BiJY+z_eS96P1 zPgTPw9no^wh*wyz_fO-LsMK^pP)*u%uI1k|bRi2(UCe$c6)67YE-#@+*?LbyE#C2J z?N$2SEqT_3J>e;ki)8+xD_m&gh`Rb6L-8~CnqMK$M>wVRq%L2RcM?x2O-k4!E+WxF zMM8SKio+jLL@*hO&#B0N6s%_$a*_I&`i?u^RQbJ<^3)u=$nkiodM;@0!k7HiMwqq# z(%fE*i3_K}x=gaO$1kfy!*_jusv?wQ{st)8Ra5$beCt3z+NQo-iWboSh#Zfvys&4+ zt6S{C)C-a}@^U=*x=@t@kl$U=i=jcx>sFP-_s+4(Wp*V%Qx}IFQ{}7-gaXiTfm^MQiyeFA} z@w1;W^rvLZm@gf3N1yNbV(m3gjsbl!%;H^pH0*0)QY|o-!(2nDcj|tPy1?D*o zva1N{Hv`>Q>?dB^ZyhI{?{81M0Fk?9=uZQ#x%$FGmEr6t5fsUag-V8sR28m;`*q0dTik>)q?3=Ujy(X9{D@0)u@w2)4G6Lv8m;~~eagaZV#$m1Y*2ucl2#Oak7t%hzFfw}a9*xv4^Cw* z$|XPlISgmkWe#bld59hrckS{N{ObUt_`MQEDkG z6Xbf=<${FyOX&#JxyL}!cW2LdiWDI+S{bb1Qe`i36&e0ac`FIkYPiFegQ3Ip_QdD! zD$)2DoEnTQ3;kP-5j=wDZ-f)pxOi2Irj8QN*IV5^66nk$jx91R&evDur!PA?Vtk)s zZsYFOSlSfqTY6DmurzL_DxHoAX33JYVJ`#I%m?J?dZjb?*VoQK95=+}U zvmc;ZZ)_<$14BA<+9C`4Jn6S#+?w7(d(kE9;m-4*Gp=YVx=i?zx4(Ia6sk5caP7)**DEfwfAlbh@&D5A##MC^9Q#AQuFAuDnG-c znKDOkE_RJP5G|`FkyeWOE#G-Uti1e2DSd%q?kN)X8@&phzd;tt23OQ`f4~wr#EAk^ ztwXIb_1wxpQ)If0xL$Y;ddY(87AVPtgIjz})!XK{xHJN#BK=Neu~p~5goa;p0x?c9 zhK2q!airwqPxsGnQ-dEw|92?#SLO8IC}j0TA>=vyEo3pms)#|e)d;XeVgX`!Sda|)vA{R$VJ;@PlVaG|ryaRe+ zC(kf^oEbY65!e98V1up*kU02iBWuOLCK^pzImamZetSfa0Y*edq8ZHzq{~b__vjAp z;_vY1T1s>X8lGmI42Z-7G$ah!7HdOwe?SQ94+u%6M2ZKsW_&^DNC$F(@Ou6a2wf%K zH6?($%X~p-@!XhI(_~^aCD6v1sM(od-5sl1m3Gcrf4z<}TO(A;1--hgS)#2cXxN!!kysm?k>UIy>NGT zC%6-W4Ci!zGu;>G^vwF|s@AHzcfIvIf7yHga3F1cpH9izoEMB!9=djwzVY!(rbrc7 zB$dc0t5Ca0Ez1dQ7`Z5~=;4=b#SkW%1C*4Y+dL5@dD6?<;!(Fkl*@!0I|b^`k8Wli zlf^hh@w+Q7uTagBO*i;A*ZO)&^ZxqzkwN-U97_I8Hh%eKf|$xy?c}g3?zPvHDp6-5 zrZ|D`T0M)YJzQl;Ki_d2Ynft9>X6Cd_;Z<;LQ}6y2Xgkiz1AE=b z5rcWUt>D)raJ~1lb^K?882j!*lVtXY3G#4bB>;#x&r3nX-gxd$gwM*|hrqc0@`Q+| zi#I~fSJgz+9_q42Za0>Q zbP0Y+!Wy?Z?=2@Q;-t&vuhu76I_tv6neX^RIAU3&xley6x0y#NG*Cy)^Z)RQQvZPy z78qF+!#d@4i>1>186(<=wj9n1^w9F|x1+rynwqzQa{J|#dj?xsPd%*}&s%l;j9Pv3 zXI%M?#>!VVnm2y?o9PZD94|^)@9h~!#0U=#a;?#%@9cAXZm#<52t&X8KGu;N(K8ah zBfq!8xN?Zc-`Wm!?AolKag{EAr)G76UUP=2GQZm!lqK@#zC!f-{ zM1k;0vmSB?-gOFL!0t{_NK#0+E(j_Q(u8$FJtE6WxsC~PBkQEtEeLud^Zve@5QI$T zO=`?TaJ&Z#;F)1Cra&592?psP0D&q)5ZEboxG3~cZJflQP-Es-m~nR)2%d>or>+`r;oA;z+Rq&r9jVB30YNVlETzU zgXYS^05K-)XhaJ#I?Dru`579b%ln_puA{R;zpREP>#GliAAYQ50a$Of)R03e0FK3_ zh2CO<#*@pk?4+D=^VH}?9_*Hr3jrvoH%3iadj#fcr*#Z7WmHGfTAC!pFRyR;?~CGR zx9slu3SvaKRwf)NSxd@C)CgzP-F&hL;k(e8Cs#-VbmD5wouy{=9tJHfqjqt=>i*>A%$<`iQKVIY0mLA|u9!T? zvo2*%q!N3Qsj|~{f{oy$oAw@Q_c}{Xv+FBSn`APicd$sU&(`(r?#vS9Nc{~{oQYMx zlkDlV0Fl(Bisr_p@vU9!G`m5MXtVwB8C#yEXc9$XBlVcH_U54FD z7hj88c2<(TJF2ME1oB*~&F?I~L+vR99%gHN=GL84lWAOQ>>x+}L`#c78KSba-{>*r zbgHC8b$$d={6Q+1){764xFOj2DNC(> zP2|V1ls@m;L~*RL&95rlrWOIs#x}S6fG^A0(X}$BZoABjRYtbSgQvTWnmn@I8#-+E z=A$I*lX509<_HBzCL!`RntRb!EI-f^ri{pyXTvQ*MS~>($~+IyTm&&b+(ih6P9IY&$|`e}d>-B68G13q!;y@SrhT z<~$JflePNo?u*hQ%ayNqUa?6?UD>Cefj1$KlI|QQ|f7YovxW(J66KkywiatDB;8 z&Z=a=t>)O|8Y!4XL-S=R?n=A@3&k%Vg9cg;1F#*btw_cXqr-sp-1s4I)4w7Qy?ZAQ|ql2t|beVHI`ym|lNO6QYpF zb48|ZeEj1~52`dvaQ|Eydw)7k{&j!*e|M(;x1pTcnH%mP#)mDbhj@jHO-h)Er4HU* zm{B4n7!P#Z%YDs4iZ=AQsFk^RNUfjW|wc9JZ_i9uKXWIn@?amG1J&~=Beq zW`Ikx*3ezOkiP%|1NXFDrVxD=UeL982o|=U$tMK}8#Io95ds$?E6iUEohV7jR0EMXTnwEEZ44V!oXmKYnQ(1% zXTzF+sxX>of@&<2T%posNJ&Tsq9MpO!8nmGC>xb~?C4*)NJr#Vcq0fa-0{dTe^7=a-2)h~gYqDc_3nkfcbcZbm3FZU)y-WgT#b}Y z&xIs{S1d{&UdG1%yLk5y%swsS1DZFn@_MYd-u8f)sr<_(dsVUAV&1_*3DoP*C2}rq z8?kx)%@7~rglskX6WOuZx-wUx!3s~=NV7Uc&U-wcN-Km}hO`0{awSFA{x-d*5@2=j$45azdA(CBJFl_wZ+m(Q|~3wI>&5- z{%paOd$81cf&q(PX!aL@jlN}##jGuk+^Q*dKn!aA0wlWSYqD;ueTwHL<~BRK5rWMe zr02A;qzo-~Z?qWW)*s$qKI*$BDqngwo{JEtd|({$d*NuDTD^a8y9DhQZ;x(=WLV`_ zXBoZ3B7!;PW=6ixy1^s!(QU7QL0lf@S z#%(`DE437sxM?#9>#e!)%1b1)eIFz(1jg~$_74{p3}TKw`l@+E9d0)DY>mcjA$+Ue zdFKIvI58Gtv^vyt=Pq}G@CDsj@f;&8_Wm2iM$9bf36vzUi4?hH8QEIN?gfbDIf|0h z0U#DnE^z|^x{YV4IOK>Iyu!^+J1w87E!X?VUq0qdJUntruumw9Fz_2Ngs2vMvM`1Tq`3tWm?J6o0Fx~7un%XtpL)+1W1NuyWbTHdCRGmKMn<)SLE10%R0uz*mSuu^>5mU6K5amw;#@ky8e_m&85M(Itx%{+X-m@v?Ut zNO9qUeBp}K-Anr(+;L-%Ls)=sY{4B(K*`K)qC-hSD@hO=btQ#*&GtH{9`=saJ)a~1 z<`3}=L-5-UYa1CXd%SHUfO7Tz4>U;Luys(#phsD#Ci{n%P$H{5T~PexLvGz!TboQbaNU) zN#Ft^MA37BZ`{1WD0qc8sygy11f;kX*E=7d7bY~!n*~Jb;iqft72*Ha1^T(u`j3|A zf2X@E+se-?p!;6xtyMe!45LI7MJa};>!h)xryZA(fC9PvL}V&jr*9~7mTb8Zezf1Kqd@Av-l0?`Z33`andrgW{+R~f(sxMR*4cPApj z2n^5$7yG(_$w>X3Xr~$u)=lL$M0H@wPzFRw&YB==rGZ{cY5;g*t%R{x?UkOeme>aa z)#lLRtqnKtuIX)3sv&taB^$wI0SgP#nm>o-rg8Hx=p0X*&i~^|MGIJxKM^$v}t^!_PYr4 zj(2>wO*cH!f*!H)q`p_7GG4TGCmpatkgqQ3%hP8AoWfl|guMGb1q<>wZ?ZGYQBYlH zSUa)qF}>Xd|u zTPq*mn}v!$I@E7ZxKGHbvcnx+5Sr7}+} z%ygo69`T^+2h<=AT(CTF|EtxHg7}~JkfeBsVVH4Y=yC2p((vMZ4|(bwLXUbQoM+6n zW|3Iu6S%`NQ#J&9JOccCM9Io%4RC?y3HF9?UX7Voam7NQ8PRR@Uq6QWwFHf#0Q5xba`WF}&m@jr&))Jr6lmGqsA8Wz?^C}ztXV86;_2;XM zJ^T@>yO!(-j5z7s{jn0FAR>x#u!jyt@tuS;=y}hEZ$ijcd>NJX1$f`(1twNV*c-bO z%EVt9XW_sQB0YUI>hw2veT}fE+Z&oOq98&LgF_YJ7q%Kue=sTn3oeH`O}#eHK(UVn zavFn{Ebd3FNR3GD0Ajc=B2Kk*5g8OIGmaKeG%%(Db(yu1s5Bp66MvtP^ipDDkttFV zKbEnagyBY`U7qxa6b^M9JF&IY7_!Bs(kO_iy34vS)V~-|(52cUMV>g7fHi8e3}|Qm zV`G?k1q2<*4N|`39IB9;D85s^sXMkc(v7_bMLn6n+gg>e%;eS99k?qeBbF3z{ekMr zg#1*QG>p|)^{=7k*sJi`;riRJs`UHRVXRnR#yC{A^q*-X+Mq~9o4z;1BhCZmwPFtC zXKxO5l^IXqV@NtXC#~5OjYrtjnsq=2{2aG~52}5#sE5vu_>ki$(tT$M*GulB$ls)}xq3EGxJCI~8_2NMYqPJYt1It@R3i+EAgwpF#UH$Ed^qOxcgO z(OF}Rpyl&i3Pu@GS9`aB@?^0`A&h%U+@muQI6?vvsf!!JbuuKO(++(yMV9SX_K6bS!yfYqb{>;4at!8%Dc zV+PT8P>!k4cZno_B_r?zoX>#Hld!688G_M7&AkcSuT;&{5ldQC&P*%qd1-6qtu8`Q zP`|aRR4W##?ObX;f6-db$hkACmp5ATJ^XvS?KREywBa=UczHd8<>m}Qi6w2?IPR`9 zl*pWua6@|^;NfXsh5|2C_L>A8g8%tUuQSbv*nT$ymRb0ZT zowPF{jVL@lA&o42H6e{8yp1a@!WLoMlrwdgm*TcA*{}nRzy@dpC+Al1#hfu~^jbJ1 zmxl=v3PeB=(@Rg$DZ#8W@(`}Y56gyh@~52o!5%LmT{(3`ii zV;w#-fi89M!tGhICLO?paX}bu8d3NN+s4o70RlT>A=&^Xgueja@oSzCag5Gj9zc%j zwK|@OyGY;qiNZCradpm=Tm}OV7A*0|XJizJd^&2z7Qn@@!PJbgrF8d#HaF1E zNmWC(`0w$SfulfMl1rfKu2D?$!{=7Am)Pe|N)#^b9 zG|P*fAgHPZV8UXBmZ)nv761KwNdO zHdNbO>HcT#&{&}Avx#>HU$c~?lj4o>v@}fdibA~{)jW`#3@|ilc2tpdf)5R4w&rea zfSpShH_wk%JWQa~=7<7beedu>yX-+Zmp+?gf+a{?0LhwdP7r8r(Ozru^&L9Pt3Ols7=C8Mqn>Sj>L=?A;4hzQnf zAc&+tj5(*DFoH>^Wq=QUD6^x*a`-H=DpkSuR?3ZJGkROgHCPSH6pgcSMc#W-pGRJv}Qh*!sb7(@VDIW~(h*_-3z%G7fZj3KGSu=HPA%=DD&# zAJ6tlyIcW@LV``a^`f_FoXrhGtKY|=sF@W_B9zrF^@J~{L*Lq+4pZXHrqIBp5KFU9 ziK0^mNggd5QsXO@tf2o_#N8GP>P(!Zj|gD9Q6U3r zIPQgf?ODQ+d&;KQ(@5F0wWubv65X^tFy*6=D|x#eZB2#W))Fh!)T=Q@U{59$7bS*9 z+0ENwYvxvGfMCLiwpxYFW(Y0p4yY@*lmrJvRYaI~Vhblr9}QiTh}fww##H?(QW$u^{vXkH#Mn7 zqDr$SlnUQ7jiX2Np)W0Ps%leWvZ-Xx)3&&IW;G|XDwWT%uW?)7Uzw3}I}Ja&f1|`@ z^P<5;gX#&@aN>>@SLEZ|hJ+i|!ZyYtYnhy&wrXxsB2d5lR{gX=Vbjqp1r7 zBI-U9N=#3Yc7CVeIUy?u;i_H;rzE11nZ(IYjB78*7q#5Y8c_ zA>$wJS->2>Ggor2fe|YzAthfK)rga%Q=j9Z1TXX3YjyGIq0@ii{Yj6(<+>rg-dAFA zCX;5JMxmEyM^-ksz>H1D(w6}$i^r)|qLT|i)PwYG4EK>8D{V`@A`&toKc%q&`aFa4 zK9P#CIJc1;~D_UeW3SO~w=gX{599B$1G`cWDAw9 zRtH1@i}qgWRlc6~Mptj3YXuawx242L=HGrdTXZqhs$~t{=T^X|Bnd1JY$D4Jn|;gV zMycER-r3iVZe=%^&~@!P8&RZwN2sV%08#N_dq@iJA4Pl-Z{ZUr$`d@Z&H>h1OoTV5r0BfJ&k%#BmTYnnuN1o?%#cESFv zpIE8vk7ja{kRxo5OtWG}LwNg-%vOK$Qn+~uzZlEISuduo#2f+_{1UhPBo&+M5i0M* z(c!tY{+3rqFL^hyiR~WaQ5T~w?OPZ9Xh_{OEayYcOCjLQZ`YO2VNjEQ-Xxu=nX5iW z>|d1My|B>UcE2{RXdgIvfH)nM6Q7A65fthx6K~!x;r{3gfoc2dYe0gwa?+FfRats_ zx%{n#t`WBGGu8GYv7c2L|_)CRm2ik23a& zCghLX9P$zz-8l}Q57UBZ7!lPAVAS&wmcJcq;e~do2wzzAAzBQ|sv!QYg>NZ9Y>B_W zXw9+sOZmYAguWERx&&pbc)9HwI`6yS_5MZAm*C2OHc4 zI|Hx=|GJMd6EJ9PxGyr}*JzsUAxcwiHPZHJr{HwjS{5k|ccjc;=M45jr`SHvIFj?% zXGP1?9`CU3Wi>KP5RI5h%n z(`flalRx>(d2Pw@3jDh)_rv&(Q13R6?L0dNAKgWO2L?q%=uxoLNUhWw&fxuZg`L~B z4He~vKs9wHjD?IfR~!B9n5uzl`07(VyQWGYb>5aF*uJrEw{H2e zR|azuSL*tJtVP z#4jp|%*E9O514jUJ|_f4r(exrN@2aXw8Q7*jqlZ84NIvLxZn`}QO!qnlSOjgq4`_a zj~=Isgz3OF2cD>5K)mRiyFh0qcJmO+NYWf2#}jfyLs>tZU~Q!!yI)sEB8`ON2e)aA z<5RPhzp8?>t;H0aV8N|N)}hCI;dA;=;|4O{9r``|moFgff7dWGezwjgrVOTzmc|xN zrj}-=j?N69a5x)=PjR4wjlHuIgOH`Ot)atzU7r-I!@A*qb`(P?yoEO_K=L27s1(6M z)Y5VyN>bYEuo{t*qzU+>tG^`r@THAC@HCZJ3s>wwbCB(dlrxwJ&R}ao(rc)RD{49^ z;F~Aisnz%T_xJa#UG`$P)W@x*+~V6_PAzWR9Z%hd(H}bQu)Scf!o5D=1mCXneujSK zrTrw`@-yt9fXTzTtMvlF;KB7Uulc}g;M`?<&%nDGc3QxFDR!Q~-@os~f^VT;n}his z15<`+W3k+`_JKLWc(EP?0y{Ut1Oj_E#sv1)&#e!llrTaJlRIG`X`nU$&-~gKg$D&|HY6xaw^fvMa~%-HL>bl!*B(|8k5vcF z1Vuu;b_0f@XF>c({3%p5B6LKMV>g1HLl6U)0AyGTAodaDSo@Jx`%8fleb9i7!JR}@ zg27bM2}bv*zI}x52nOkAoWL3u_mDo0YYf=!fo#+qkU5z*yfSL{by9$lS#HDSpjC6h z2|&E;wH8X-nH&g0vqA>$@DaT*IR=U=qA$UE5?fBzU_30O<)0R6#f#CGYeJitS$xP>{#zTRV%KK_CrXr3~AHpYe}nv&fd5uGuUH46zIxG zJk>Z{CTokd`Pi^>>yRo91{-y>jNv^Ra#*6RV=U%%&r)-!E^c**O=Nb;F~DDfGG?ip zn;QGOY18fG5%)1I$CmQju$QF%&=sp%5AWV;{T9ZZp~8K1UpkhaM8CD6)nI<8)Msic zusVvg_9=@qN zUz`e2>d@M+#bIi&Jt9I>1o%~8H(F_6azCpYb)h=sE;zoRMs>j4q)NUVLrm3{rG{Xp z3Yr;VSl%t%<^R~#JJKDGcW`Vi70ACANy=%R+ZMMTmFTL=F%SZrT!o8(!qZTroL0t8 zr2L5Sc(}iv8ptF4+m@z?mp9a7 z>VX69-6}GcUEC~N=p2g+;bmH72;|5QB2b|51{|{-JxjFZ$#J90+Vl!?4m^c`!244C zsiU=dyl&IDDDnjKTVu5Yu4MAcl6e~I>@t!A>OubjrHq`z9U0R*D6ZwKf_kPVs~hDN zoBsB(0-@E7lA-*4zttx8`VKqLUagx`0I*!pF(=TCr-PlnY{<|xLQex*z04ge zev&PRtPtX|sQ{uY@Y^U*B^9TZ5oN4~K!b&5TTlJ`Vd?CAicrRFH0WaaQP5c9qNW7S zfMu$}Hf#Z}sa>oZh)KnyHlaSJqSxaxZ`bgW_3PX)`Lr@$-N|tJXo@^y{kcr;&kxQq zejAfMmldJ{WFhe>IIAuUs?@qH+Dd!eB26W~#rnh?e6eFvr^xE0j??ndUE8w2iAyKv z_>@)K7%d7sXZ+W%KmlQW`-GstwIDZwO}%Xo9SZx0Ng{8B6wNzq_hA-?1wyU2)lK$5 zTORYBTkdJ&56zmu-55aF7UnE*qeLZ9hs!gu;TO6f3X39Ioe@Ey97;$VkmPNnM2mi) zT{Btxd2T;qng~aU;E`;SHlv%;yTY2|Gv7)8ER0koH6LHxxpApz~QpZ7Wt&szC69h zmwd@%eq;BW-pG88ZnCgJ`F3h|2K*% zK%CQ={jUX7m3Ku&R2V#ei^|Y0cWdUxLC~HPM=DB{usFb(IO{_Ht?TKqfweC520f*a z1&(7k(c-%mP1PN}Cr0CZ;f|*#+J=OD04PZ?kTa0T6K+F{!5@L|D}pCB1C%?}3aM1)x_QGxKH#?bQe$%llo)_phEx{Z#I z72tyMky72wisN;(CBZ$He~Mw)H3pW6c9fHZQYcY$Qu0|MEu_b?bb5Yf9+(|RUX!04 z4!O?}N#A%l)9vJuDNyjF^U5&xnb5UF*oE8A^i+(yQNL z_->SR2)iME0U@!6f;Zf-z#nP|cZF4Xe&m42Cz9*XO36xlBLDVJzf%RkL#F?e0j%?H z8Nkf{V}0=d;dcI8g%H;#2hQ{@)x!UO;$zi$c4Ox?m_Ip zk-?WpYJXo&d?&;|vO%+s-oo6T@JpSisWAy}z9dN#Uk5+!hgD+HsXGzlACAKjuG~&5 z$G#-d!B`JXFIi<{$(>2Yh?#Lov&d9jWhtI_-s{-fWF0LIJ=-8sA#j}2MqT#QTK01@cHH>W`=GJYx-PFQd}Le@8+9H&dZWB#YkO+LT(hjIHacKaUK$e=V;reY(l&ozYy z2K=W2nwh$uI;TuSrLKs$l(@!7b1)*J6eSCUhzRCg@G0Jt)JgC~q<&!yVk#pdZbG55 zOkkCo3p&HeC|-yFLp&~C2+3630M(MVko{qekc<*#3guDc6(WvcV8j_TjuN>+a4V!V z(CF)O-xg9N4Kl{TRW+=JAC^tR>&jxh5Gl6lSR9Bdv_G{ry;)$=-JLiMvF2Gfh6BIp z#(-453C4Pn=2Kj%QX)R)E>Xqd!6nYG&V_UAWYb-$P+i+}kJWX(2xip5(c_(r+u9N^ z^?M-wu`Njhnf>1I2XXk(=-S|FKwaMbY}jGIGrcw3a=pA=PSz~$C&&I(+Y4pZOsi$O zosyu#8a*83+BuD|icX@#rw*EJJ<+-|`a#MRxq{udxu4YI;RM=Md_2H1T*lT(meb>x z`nS<^GHEyK7=-WU%Xq>Q=}NOnPA>cFje1Ja`(RQ?V&8HdT{_W}~ z213rDkJ>FnLGkb)=#9?4hg;{sg+xJg5Mik>%J4r;hufmLkXoU49 zb6OCkx<|+bTVjA~4b6!-wU>$)`Je0(f$jkLv-&o8@t!XCKhg%l%n%8`^~p6yj=Rrm{QkE3-LQ8 zA^AT344@-qEtFQKHtz-}EaM-oxb=}uuVK_|h-6UBOMliCj?pPA-1M^2!7Uwn^GB<; z;4RP7NDkj>YYrJwmA)a~>dU+U)R#vv9GiOnX~(#h8J1+D{@DRD``qmobinzw@Rv*X7hIr9T$t%P?%RlTG4?9Rch=sX* z9A4f@^K!SaB_g+)|6#|FSw=Scv}3%aRd`r2hY?32@fspwT2h3i8MCEul|w43r`?*n z|L_P9W(-#~6aDrkJvCMnM(hq+7MZOR@kkfd5JZ_)EO3QTP3n4$CcaJC0W+%{l*S45 zyCcDfekFco^)>W84z!=8`U_&Q(lu$e$5(q|#!tcjme6*&!u2~cPW_JPH~9$eiPhZx z=zlCqR~|0YsXv#bj{nva_CNQ1YNr24iv4e=y1Iuu`XS&$mOazn)vZ;HDV#M!ELfJ^ z1OuHh9A(6xit8t0(YnUk=p`v&rJ|z&R-CUc^syUxeNBz7xgg;Smq<`f#G~D>t}6MD z%k2w7A1l9Y8C3Ssel&+%^R27(r`PVM3=jRk+mQ?q8liq=&#e)|D&9ha6sq2ugUc$s z`Fm6t@)ho4gHNijKL)8V_NmELI*ax~so#tCYN+4IukroOA!A^9DXu$v;lYO?#UO{i z%E7#9>`;IUU_7Vy(ty{%WnsC??zs5p!oLdbq=NULJ~#E+fAyug=JDT#*ZKAw*o#Y$ zWEcy5=w1Vj5hgK1(bq+=5unE)RW}}aHoHGaeSV*C%@6zN1%xot>%;{zl-H^U_`(+G zMO@q&A@=KitzD1gMsNqxATZd0pgZpe|eVz#^JE zh=9i3e}K5WH9)Zr5+K5xun>X$ypWz9Vbmy#XP!BnEfKYVPz;r?uTSR?1e_5CRH%^k!x=$2bf1JkQvGWd9UzD{1OwLJkQGf6RAMai=^I zv!JLb0R9-x(a-q&_$Y$Z?|dd=4f!ci`~}if;<4#)F2|M5Qw3zg@~oU%THAG);?uT~ zvmki((u5RXuT>m#pY+I#n3r2a&eGq>&vR95>4+b-^<>g^Uh8z2hS}?GDoZXIx<;W~ zd>R2~D%~DNhrA@g(B(UW&F0%*3A-}AFs0gGU-pSbuV}xowMeXLgTp7%=hksmn>Qfd zT`K;xXV+K9G%6zDhTFjkJf*3$a{_bmfuG9u>;DXhJvw^CA=iA9EG&&1w%WX;#l7T3F7X)RP`4Un{V8ma$X#escTGEYRp`;! z)?_>y$PA@pFH7rAGclh;TpO8pVpz~St=*V2rAw6o<6){u3Pq0JlO<2od=7WDuSm9Y zmX2~Rb>SjjnyD3>x1?eRZ@qpE6wL!!%Exy?(!NH$;>l23bM=)5`0^`4x-b>e3plud zLS(knN2($hnZOuc+?l|gXOdxO?EipQU_GrVDR_}dmhL=ONZMh3s1`jI)7S01l^R^^ zVS}6j*3U|*a_4J;l9L8E=VuF*0t4}L+X@=F*Bj@Ph@so4>$U1n1ux30R$RFR3 zI3q{342E1!VRPySMs@2~x30h0$sQ&!MU*-E%_NkkIA$)h;PaRMqPZUJN@w&$DnSh0 zQz54rO}d~RFvH}H3!6_%$CJCDm}i4*??+gAJh8z&_c=6gH{Jx=^rPR%$P;H7MV@Z?79`!!spf@l|t&8eEwk|Dw zC^B8!%&SePR^i0LcN9{1hMJO=?kn$%u@rHd$O{aHG%HX8u0E0V0I=rPKj8^(T&Bt9 zdFM*{5O7kq36(?XmA093Ll{_@?|h!FVO?pXtjD6gjnX(IF@*)U57usqSZG01X8%m$mMs0B}%CtD<<7jXR|ex*8VyoW$y~8pVvUU ziQHp>5!30rCS9YL@pMgEgE5a-=$0cs-^gRl_7j$t1sbbfYuaDIqg^hUQ4N~)+_wB$W&mz$zCB7n z)_JS!j??tWJ@!2EfIwl|mLuNOrPpiazmGC{K zW^g<@CwvimdOh}POBZgEnoTS5566;ae^A#dMZ$YDq$(YFP?sgFmyg1$(lBu^@J&5D z>oBUE{cvfc9Qb;_)ZMfttOah30vRa{7#jrBobNt{QJmp z$)2iv@B!Gd$oua1kA|s2`s`fjvo`tpZ+Y1q|EghfakjK!Pnu{t(f9{UK7A2o{ywigQEqj3KH(5fFcCD3QT=X%dhK zt9lj~+kGN`(^sW6Gq?5z_D(rI4^coqt3-ITvCda|)#c;)G8Gzo^$zWT*C45ZQ*G5+ zVkic(MRa5RBucpz!gpXGP_L94NKoJ@I4JZHL58{v#4VwSi;07Gpd*~k)ar{XAttUA z8q|Q#_vVh^v<5Xm-EtNiZ1fi4=nVz=({S4FaLeIR8Z7i8;xRd(kwBFsxk-D>W3woz zfV?=V858U#ID{x*DCUx9iB8ptao@X0DdwVQ^Bp&liwWfrN^wERknIyPf(DuC>7M7b zJet!t6|0idmaLB8Z`%`7w7e;YwYFmuxPt@j&Qgp9W4Lu<{G`c7S%@kk|k2Kl|T3x>D-lmi~k9A7)enf3rNQaV_rlN$E5lb*3Ar--hVy|u12dFyKp;F~zw zeP(C+*bsH9uS`$Kqu|G3f#-S#ZsCTQd}+c0m&QNApl`mAAB~RfA9!Xc)0(4QxMElY zO;fv0X*xTbJ)=6(RDg{!Dj0H(YChIKeDkt|w9O)F*SDpW6iH;;n~YKEN^X}iaXSC8 z`Pv@*5;d~bE{CsGN?uj=?yvUfWCRT4lh#~3cb6jl5H46Stt#-t@NuOQt2w4qa;1{9 zw>}^{c~~QhHj8}2T-R@rxD6P7Oz6qS>XIb53eTnDm;X(g`Wi&)ks}+Uc3c+uE^5~C z%|{4}|DRGzCgWT?zRwg=u+Qnxzm{75OQQY1_=hUF*!*WkZL*4_GMXUzdj_ctGlKTY zS1?gUa#*JCb|d6sDHa-}Ntj#Y`LGZm1Ud4Q!|m&#z6va?N>qi)PZ;uVc_n>hFu?+{ zuD&S#i4{ zO+Yax*-qn6b};j=jqscddBPz#Ua55#l7Te#+z6_E z%{q8a16!4n+3@DCY`o2Ie79CxLpixM2uJ5er-x*@vVGchm@ zaS2wb>Dzo_xIVJqJ6c-Y&eWC+IYN5jTrb27Ee7r6fJkb1!j_w~VGhe%E~&}ub6W)< zfzG@u{s3fh-d1(VBAcmisAvRH$mC+8xeMaa3<=n1hz~q&h}ta$l}x8^*>`UrQ*J%; zSH8fj`OGgbK*fQ1;*hUdn0c_ABnE0f^m@6#Ai+ezLVhOvyaU&B>krXG^5Q&ChJhkm zK{>b%`U)+C=jsF_{cQ$hnEMq7$Vu8c;0+J72E356-s!Rs<2^dLM+h%K0%D!89r9s) z@Lo(i!yuT^5uC7h;H$jB}izUQK|z79)ix)?Ogw<^xuBXC9A zOvJb0?nn|?jnr$>2AVoc}Aci?lYt4s3- ztr`M8kvpkVJvw&jodx>Lvz6E!( zK%@T*f){%RC1?xriH)o>hlWaXY$`($Q7W~T8l`b>WVMrNc&7dlf1x&o=V!jl;b1iN zAb|RvTQ4irLffb5L6dEgfm5}KIXw$bxhq3}U9kzelq9w)BNcYtG6-TjuEu_M$nB&T z|9s#{q?AeP0YA?jQ|oYt!XXs%CJi!?hJaN05pD85ca&Onx%?1JttW1=rd4GB$zpL# z{`gZOa$=az%xg{OTl#yGjc%v{lh4GkxG8+EF~k$AZoHj;M*p7gh6A|O2QQMCZWxI_o=u68YPqSN_Qmb+d4zQLK@|jakFShH zTHRuz)b226c)RARi2db#)#*u0wHNh;RH~WQ8!AlXr?NV>V;8p}h@5WwDQoJi6B4O( zo|9D*l~K8FaaA$)Iyl5f0w+|(|-B3a?YgJ4gNrthEI$((=TFUhRU4=uPY-) zXe|`PW*pQ8OlUI5XfjIixFN6}{%ga+Z@}+8!0iz2V&w0#%hHUP+kpQZ;j)i(w=dp| z))RlByA&v(5jRRZz+SiM9=-Se`*lx zs@y!xL$?=nAKF}2Ho5;u&|;9KrzH85+gE)GW&U-k^Dl`O|15PB{ugQA6r9=CwcANL zwr$&H$F^pxH+SH4o&8S~Xs^JUir^~I6 z!yNo$pvGN502V_pqr%aU1UsL-QKVRU$kaY?OpJ$j-#$@{6c63qbK)>c3^h;nZOhO; zR}6M_mJht|)pPa3I8@8*5#em_01%n(Q%?Xc9>mJ&57IUs^-<3X`;`Eyj-wx}g3=de z`3YeGcAc>SaxvBFJBz(iEh&Th#UJy*Nq=k(Zn~W#HiyOM216Il(QtvORsZvE*ZUk^i_FDaQcktypVr#yb@@Dkcb zMpaOZ!oNsvV$;8CprfReZ%K>RRH!a&(HOyttP!pv8+z>a9UARNk^FD;0cMy&L=>fT z%Ixh{=X3$5;nS#DDNuDKqAZlBP?g6_VMNK*%1SbbmcsKnW9@O-_;^+j3AhX-$58X= z7|iDfswnVr?X;K{y{14}YpgV0f8wTal9o*%f6Ge&~c4~T7|Y0?-mYg-D^(ClEcJAzQPhml*m?njfZ+Ww2<;5 z3yngm1+Ea*8jg>M$geaUN;6%IjN3rWvjkWn$x$)uDd-{9wMqm?_auWj29op0MojD^%}{m(VKUBUDgiXReO%tb91q)OYQ$&q@Sutg((FJ(=#k^* z-j=;9Kh)54L|Kxn9D?ckq@2ZI75?y^Kf1`nU$af?J2??B@JA$*@A&nsiCyrC{yLC6 zx7`9IcSSDe1(aY+&iRPMzpM(-irIMFJ*ji^>u77)T5wCu(VAVg&h|lGPXO|M?;`Ev zc?IxcZ4UhGG^h60XV_TE*S{y_i8-vq=UGKl#VbOvLlv5sgK0Q1pEA$OvFRa+%5vqrAKJ(D8V_%hj&*;{lheY$c3& zW;iC~OE7<$?`%pCg)#zG*uu<{W27}M)4bST>O4`KX(*9_+Hqj}7wAipz*2O04jyE^YTa#norE=UkTIM29pyl`3KTHYQ`*RN`* z+FX>E8{KeibsCd!|6`u28{b@G?i^z8D--eomwp`;Q~+i&eF~oRxYz3>e8$Y=pua%n z^s24&6Ms&Nq82&PeTnQ3=wHphe>Uq+vaiNp@?Vdh|0-zw`{)rjuy(eyRWfmKF|jrJ zXS%jgoR(VjuIYs)f=C$}Gp4hT zbXKBWa=<*SXW%N(mRQ6}o#!y+_$*kPb-cwy43Cs7D^^XAY<1LP#<=cDn2Lz?oNQz2 zbIG{M1DU-IT!@+z=eFp2H5*Job7P(W=}W*AE%4`^CL#1_Q{Yi z2pjQj;&ixw6UoZF??dWA#yP~ZBq3gL=RvNiMGfc3m((o^EwC22UeQ`ceb0gwB*zv# z6y-9n*;HUnSn-PKjg;5>y&*HsYd3eMYM?xIe~qx7EnVT)ia*9bcZ<$)5%L>>5+*PD z0EU$^LUlqR?{1+I^h7(6dQ?`OFj zxc=^j2^`k?%WfQoI4lapcVHfjz3JYnSpm@%uoIM00|uZ1&!=k08q+QrVDNUal2~gi zGwIY!8_+d-rJVy^NNS7QI*=hka~e#V>bRxVoXff};0*0bXipkn2=jU)F_^ zG3alWQ3E4K$VGhg1#L6VMxoQwez6WX4^@5y)q zdVG0ben%&AesM7kh2tr@vO;vAQOJTJtCfCbF02)l1mk>_lV5@WzTrPnKrlU)KP70S zmVPD9am^8rp)A?lM50XmX?_bX*f2a=6N>kTe(gA9skGI_viPK5NWXj3;QQm;!r%8B z8_Y>*@n1kE|5u>@S3=m|bzRKF&c?*q(c^EhlgJx5n=6@^*_hZm|1)GLegXe$fm*!j zdRi|a1r4DhEV5D^8+C#^l%YC_r6^7%1EV(YN+SelFm^33qbH~_GAv*m0>1|J#@=5Y z#EvARn=l`Ms9paZVTMoVn;a{|86*i6L8*+Z zp6Vvw^D6>%L3?AcKEkVI-w^to4zI8_fHk;d`Gkq*u`hu6Ga39n3o@7p4^*s9*|es~ zPv*5SDfwmV@G7*zzjlNh!5U=O*h&|^%Wb>Ck<)oO@}Q9F$;W(cJrwih-D zsSWdn1QD`Gmx%^PoOEqpLGDDY10B)f5K9K8L2M(_b-kvv>@~eC2plmmpc=%4nfBN&jqF+@u`q3Pn-TMk14J$kqPrP0zJ+Af#1<9Mw)C@CP+LscYcQQl1IdW9*h40)W; zHM(n^#GW{zPAn@Iq$`itDH1uGt;Ser>QjV zw=*&NOi=kERW8*@Am@&XeO}zFbMZ5%HpRBvGt2bq;&aR3YSS~z3dw(^-pK^+yYlt0hKIUT;26Fc&UjSY`x z_}+Jy>`xt6+BfvIpPAIZk?1%aQhJU-yQr>R*jcUD%@ptmj&Q;74>_0t^p{Dexm@fzr}x5v(84%&UW=g&?%7$3^B-g|?8%r&il3QUqeI!sbnGwk6G zjb#5_u;X4v@EmA;;VF{+{#)?akRBElctG&jpi}S|aw1SRj&G7X2r>2#hNt@aL%>a##a+MLN0C^-8J0++u&z<&8O{Z{E zd88~N(C9{=qla9I-bbaSc8t65!Gn`x{Q>CGzFS@uLt(OE}@94Z?xiVC)0 ziCl64HDY8gjwSbNv$i;)u%1#GM6tWppW0FPSy8n7esTgp}^Yb;;NAOQDy?(-bP&aoZi{l zOIM8_DH;I2PQ(kYVRs%rAk7$K+$cgc>pG=8GxRMyqw2=IaNfE(`e#ZSEl%{~ZuACV z%RCVqdn-q_m(R&5@N4{b{uVU;=bKvIyq>o*^Mj&O`?`?hrH$#iZoP5vX#6}1)d33k zgnO1vw~IDOY&;>bMibAw3mxMcLTfF-l0x?k z-dzAyJ7#SLPz7exMG27CuR655pP2+!8Tm(D@`Wk$*o_O3Lnp_1;;HSBgJ;ABH+%Bd zGH!C2$LXk8fJ*xnCslBxJhnGw59

NH0lfMJi@~w#|9Dp%R@SkAfhp*556da6#On zcPbol{C85uL^mCI6tp-wA>!Mrmj#jTrxO|*>6E}cL;-$ac83litWt7DVOdhW%W zcYxfEPpNgsPWxgaw!5Gf7r4u~16ECj#@ryN1L?AYYrkIP zg=+%~I3sWF!|s}?o+&?_9SySeEhyIXk|~{oI}US9!PK#XvWk_7zvb~NspnBVja;%A zfAn~VtemP!(|Co4&POSfa=UJ@!ler=f%NU=gkspixf@rg+1NY}T`o5W_%2a_M++jJ zH&{^%X2pmqh%ISAvjO$`viw$Xdu1oPkd$HZ#iqfBoEpqel8`o0ap!}2Dqg1qn5w$5 z^vOPF*{5ieiEVZ3_nBz;2b|W_38sEAcw>8a;L1vh5_p%|`uL5 zy*3SvQ#luQi5T%JeciA^8phc`xe_}t{F4p{g+=n%wyM7$k^4S%uH8;a~9 zqY1?rqi=EyS2)Ai?(rMh`fOg|V%MA8h+~?DFgM7OogYcfWv%As~ZF!3T_YVC7m@-ZzGF7H6=elC9`PQ;rk#M;^?ZD z!kwTQyYVApe!c{=n1F^uE3B=?^bpz{DU0DJH-^^dU=pYH`q0_XOpz7^s}XxFLbg;& zPL5knx_(a z#l^UBz*pU~UG&J9dR9?Tm4f37!>KzwK5}bWBXE~>&qV@?1bEyZvmBlvp23CWV6y6j z8!c5snQlzAyqztx^fnT@rzMNli+yur06k87-`bVAr*O z9U>y5E0&hkHI@-v9qiQ+&BBh|B2mgYqL|XB|7%L^jzMN}Slb12Oc^q{RIyTtkEMc1 zd;DOt`aQHfs6|9&&(?+WQX#@#oObAgM|jtUIa8w8)R8%D%JzfVXBug!I09Q5AS7U{ zij~1af}>jGK6XHIG=ofop2nKFt4rDswmELv0?PSL^{tET10ws86^@9XAn~?nHsqmR z!*_|Ley9B$;?l54t6JYI_r)WzDUm-0RE)7~;^-MA9ck2wi1^9Ez=-H29%A%8F>!|M z4@x@nXrOc42WCOrg%L*(Y}kQLeoqZ>*5yj9_$58}>A9Fl`m3A-k$gqk{`t;AbzmOt zp_wo%RU;P7TymbMR`i1=Et>_keG~wx7yt#{$hA?vxE~6DlQTbe5M2LBZxQ95?!;5D zq%KyAp&>DWKxcL~0&cg*q@zAXk?9KLL`T3a0dgQX+02_E%j=c8?`LTLCmg+X(&1+g zxFgIqrtpvS&E&d^Y>dgv)%hv3^YVurUbvX;eF8)iJh8*Pipur7-z+cCAJIW2*JZ-> ze&1gJ*X6>uqlgC)Gc~mL+^dV};#<7G-knqQ^iHPp`-+9@jlRENBahmc7*zu;!j?c0 z%ZbRBd&-wR=8KA)o_U>~IasT9LX`Ww`>w|LoPD!Z1$U@vLlj$(ahKivg}zY5QDHmW zyoif-480qlsP8lt`YJBzm|aGfYksS~2OWI+$*AK=*_F}OC|9ig%7bfSV02VJ%eQ&a zPyuo>TH6u>^+aFymEdYu*PMB%o-E!q>Q(!R>OS@{EmSSmzTydG^}#kTGPmFC^{zUd z{-reOo_yvxr76%t#!WIpT_%lpd$svQ*9=cDI;nhb`QZ|FAlmJ6%?YE99;J~b!EGh# zEx9?B8}iCy_dqY87V`Y!Mqga|mKt#>*6R7Q_2kDwc}S`ye1R-)Bwmk7J2v zX6q>i`~~Ek0}S}0!$xuTfX~@?JOdAH-obAYJE#vZUDLOjuS{F=dcAUs4bQEwR9lLA z!}Li$B`K2MCPj*)Imf;v)r=V>8Y~6Iv!K%PLXCW#x3vA+M6Z=vQvLKV3!`R|UJ2-e zK;tO3=dKzJ0^T`Tv-49S!WinDb8mu^_C{fc92C zO!|{EG11AKAcfQyXe{_kK!BXtAEPHRaQHifzq$Lx&z)~n3C8g-n5KIZf!F0b$f#A- zIwJDs6-_Ia9+nXLy=&Di;X3ElF(O)$ZWT+eT5Vb`E{pe>US_vMz;AEAcQUUs?|lB; zWnFn6XST9;-7e1Ve@Yx z)l`b2Xwf8DMHQr?S)eFfR4QphwOObrUDP58c?b%AALF>!pm(+Y(Cg)=BKy9Y!fUv` zmP188#iEkEabP-`v3!PqIA8_ce5{!=tytV?u-5z*P}GlVcQTqY*o@~&wWSr2+~M%2 zxEbZD(=8jb&PuO(?_;a9A*YM?_m9E1kK-+`(en}2j_DRY-n-v>*>qOO!% z0af=)(d-)Y57mB)C)8K+9rSc-dJbp$&3n8}2FGRG(Jv@=mTp(va?v$YEA_%RUyjAz z*{U5^zUp^Ctcv;|xAzUG;GAM>Z%F8mJ0 zHG8~nu9v#Q!42V02~lRgpB7V^gKvvU%|5N>6HG;8EE0bxRF(>RskB^YTQ>3is+CQO zSjs|Gq9hrO6s2$0A5U%MI;xagmC_+8kH%1#y`xr$o(1~;@k`p?&MIyb=A@agrWXA^_rpj)UGeqVqUt5BLM$Wk=pzjraM3-bF_I))}Q?IIi~7R+l30xDW;UG!~o zS!UuWbWk8fkdz?%U#ZZ^4QH1Kti+xc*}w~|B+b}ZgNS-b>jX%)P@<}KS%Z$NZa}e- z{KcI(IO@`mam!v9&Lz>8YK}Bi(MuM>cG`qbCxnU6%I)O7W1BU9H}nq{W>6j979hgf zZ|YaFT1U>ax5$Cyn^DZ7BTv;?98^Q5sXnv(Vm(HpyXfjolA++ar1qX1S(2!usmVkI zUNWi4{J!OTOwW%KK1Fivq^spy%bt;0T!IojjN@eE8d_}kb!C~rLx)!m%>i*~3aCtX z-YWNZd>|+t^pSTm@&_c#3uRsvPKz{uU;Cv5ZrTr8trWfZ{Kxj8Vqyu0O*r33z`0POwjYCpIuiMd= zU^ZSmsTT;c3U(?yC|&E>aMe#p0XMWMJk=s}Trey-Z5M#XXR2yMGn0pIQ)6^%vv+O@ z74(v*!E~=@UI$?;F);Zh%~U%C}o`O3o(1-GP=Gq&;-5#&6J%8;y7KRJ-AjE;>9z) zpH`cy_9dONv5jThKu_io7X8E5^Te9Fd0VqCa<T;&tZs9{%)zf5J$n0c-?TW7fy@y#OuU>=#^WRS4| zzWpcD1-6%s7;#8P@s2q06Th97(2qfQtoPzB$N%}JTx~R^4>z9<<*N0*P!k2pEzuM* zm=s47IX)A*xh4z4s#?zRe93O-v5~AcdY(C7ua$T1INsU7KuL*bRx*IWZ$m($3k@~nz zb{!|15;>)%n0#%jlIifR?Yp#4te;|77ZcU?$ zp;`4>5WcL!lXK3f%IdcC;~{qv6(dPl6Q_;DMN}W=ilo<#dP&x<%u|!9F~?#DOdMWk z4RQ>=Q1Z5gTY1)s4~Crfeq(mvq>jZVNXGow@LLznW$a=MHuTGvJ!;lwSl({~e)*&di~yDA$|F}1KcJ6gtlAc;}nl<3>Vf;?Z> zO+U7KWXlJPNa!C!;yyu{%CJf0l{u8nEyxsKs!;Um_;E6qIH-iR%R(5P|0?2q!bE7@wZEF~Vcg+%H$W7tSic3dj+n=CZ(hO85Lmrw3- zwofd7JQ+liFI%7@18xxRNT8+Al3_Ni zvbXXxMohpmO`3hj5xsI6PC>dt;a?EChuz5LaLyg9!uQd!5@Kms^*@~DWiVUdk|!{w zn&6d>fWtjTlol4#@|-=#{M}Q2qza@)ftN7uUkBIHW`8UTGpTetF_~|%6!pe~7E?B{ zm~Li!4GTj-`F__&DeekW;2cQ?i`@FXWL93dg@oIjBRkK#Lz4I!4fPDDO0aFxWW1wt z?4C4}Oo?4=g@%yT!A7l)qh2hL!fF0TOdkmp@|CNZT=7SE!K8roSy;1$r@z*8(yxFO z^`2Hk91Zm;)aE#9B8TdhC~b)ZZG+5%6=OM|;ZfSrQ_7tQV+C7sweLB6YLgzTV-{=H z-{c;`M!y$2Nt4-2ORkPfU`Qq~CJm=;7+G0Rq0O^Y=3|Q2cKAap?J@pBmS!r;V5WrS z4O3ybaFS)qct52|)2w(dodc0Ox2V_Tha~^$8=TbSc%CdR8;E_-QEeWy>MyF%U)i_+ z!#Q<4A5~SirxGt7ZZn!MPs>o&T7>!nhIIj5z3@SpCnhS{{uehd*_3r$c_czm2B%~C zFiE*EwHXgNK?#zXVs>YmiIk-3ElZpi2&a_a)()6t#EXO}B$PR2b*@RK_BdmfYHqfw zA@ydc4Nekx%ZaNz$fE*+&O&5L8R*rFC2tEUgP%X}RC&u587F}3#a{3H$b3zSYJYsT ztChU&K!Q@nPcffvFeb|-W;TW3ruXYyxZmTm5ui+32z8tEt<&lJ8C0HggJToiGr&;89y%uT#Q-BVJfGg zWCu#lKmg*0G}UdT1i!vHD*Jbkvm?u7@)_%=AJ&fgy69{XF*++u2+cVTTR$AOI|wc* z@bf4h2Bbh4KFLQ~jl`c4R=qLcar-n6Jr<`&+eVJr&0gO#L!iAwW*i`!93al=@;KlO ze3BqJoFD2FUEsWe2b#-%l3y) zo)x%!%c8sIdgK_dQ?Q>&Be&gi$*Epm?`D!PenFuaa9Or~Eqy}p1&^GXS|7ef3qy{m z{m_&%R`pl*zvk_zJOCc*m+wz4_P@>B6#q)bkuh;{`pU}thl>-Xs3Z49N#LEY-h@Y| zK>dyw1lntZsybU5HUJ(v1WpykiiKa&zR%TSo$+jS< zIkBnQs|1-~(=A!E)Rp$RU^mwq@3U2}wuFF!9WhL_Om>2N#(5#e2-PHzGQr_9D{mfI z1&g>nUHq1%D-a<0uIVpcm@yU zpU(A-vVxNK@u58+XFMdmVl5IXuotbmxta4G>7d9A*hzM&uTV}bN|be)5Lk($1IlW( zpMR$;9@FYs?thUHetxNz{yQ1rznY8uO-4}qGMhB8w(vACv^M$SXkzd`e1xRGIV~8x z^W8;Od52;MC@2amwgK1=ih_a+WT~R`Z8 z%&-_=;k*$aM;UjMoOeFl$IChR{6IVbSNfy9#NaWwG~DW=f3{w|>pv)6BM?ekV36sU zDApM+iOd>!h9px58)2DAc?P^8RixJ#2Jdv6d*(9hf_m=%=!*@8^ad-$ z2bDz#QWVHu16*>~Aa^U(Y@nn)`z6t`ZmQ$!lls!5o$Kjh*CXAMdQMDn9*{6eWiX33 zB9?(G9&}JC3fA9vi=Gnmg5wNg$+%#!224u%$5cz{xagN%3bzVFXic^>w0HUsgKG-X zPB_-s>ep3Ff0qL-d1%z-amPt3_FHX;W~Ku?i+*PbLOm~AZG=NE*fJFLBxF2Hi*@mQ z`_1&O2k`)QU;Je@v2E9RKwLD-Xi_U~clcs*TFL3&GW<@*oAv_;c}aPqVZhWO#38!9 zq){*Uyk&d1)Gv5KwhI1%2dFQ@h8q`9rQoIe^r=K@{!u{FQ91rD^UJx zH2MDx6lV)NTeYwCp1q0V|A56tt{n>a2TbO3%N-<|Zy+0;dbzqLB$}Ikr`wQ|No#_O zT(4ZiHOM;!qd8%zNa_Sh8p+e}1DJlKZK!FeYA9PCKL*{?7dvUuqgZt`TZx}^0lc3B zEpvKr)XwLVx)W8YG&E~=N!!^_113Fg)bY2}aGRkF|v^C(OV=NO; zem~?((?NOLG#>)O-Fm+bCV2IRA}D`kmIeh8SS~EmRg9GvkX|dV4(bx-hL(HNH-!Ax z*TD@-r0e*qt^{9S=)eC){}18cfBZ&D<_7lv(0{X(wEil@pT)E^iJ+DWt>P-VlJsMa zH^B% zY9iBao8J$JA*>y22u2-j2v!=S#bBq{Ukl8(xg+i5l*`?dVKbT{-v1;_XvdmhYS1D( zrU2GVx^TvB534%0CAwoY5rnLm!Q2q56L?e_P)n*ODRpUH(L!lu87$%ZE83ZQsbDUd z%BpWx+EqrMWB$wKrrK(~4hn$Z@`&SRcp_fB>huwKR@DHoI_LCX@pch{be>Yv(UVfE zktmUEH<>Myq}8Wuuf9FPJ$)NPM|c8lg9cRKEj3GxX~mI-Oi>SGQ(99cK$S<9pu}bAAYd}Tmtez_&%TpD zyb#8)9=;sZwN0Q@xwwURGYn{0?#mCBg4=`lYwPVlQvldLf=EUm_#5zVmTC&BTrS1>K;DUf>$e@}}bVp%5oZBm)mok|Ru<6AZJ86{5!p z-8&G%2*V?KBUZcb_ENB07NrTxXSC`ptpv5kR6qTYPHkh|$dK4D64oOo0!7THZH+mx zb;UKM79uPWPjyH6U}$kmo5W|$5@lOh{hQdEIY%I3^TkbT_*cH;|HIGWKd>xl;ACN> zc7=#MGvf^Qg>X=k@v9;&N)gVZ|;lsmML*n?$(eIZC7e_m*&wB94pcO7h93i{EnO z#j!lFK(R#pPyJ>{r~N`9q(5@hkoKajAu&h~i;A>#U2$Gs-JV-$bjBc*S}f6(9My6I zjy3>IU69|DVt$W>x)9Fzc1*ObUEMB+EeBT`WHNsBrdM%t zkux7Qd58iKA1!h<0zHMx2m;ie&+&5|Ay;M7&@!?t%cp&>9S6fd*0{qU`zXU%79kL( zhu|I9_Y9#%vtwamoEx%?=-j9tiltx$wW@ocUjS=KpMc{+10g{UaMp zQv9E)9qihETCW`lr3gip56~Ki(#;bvER|t!4^wG;WuZ0F(RLlxCAryj)BQkCg^&sS zt7tQ2r=j7aAo*|{XD~Y*W!g=7^ZWXKfa$|YaoL`+f;VWuzwA!U4jxFxVZm+C&a8 zkX{6X3~2P!*AK2*C*6qJN#AMT!miwBwTmWVIr*Ggm+SG_*+iJBDk9EdG`kc}^_!>| zGx&?5d8BE%vXN<-Nz~q9duN*WybK09&9mAW2P0DpseCu=DQC*7r-{Lw7Vm^>_ihJ}3Y5Apxc=$>8 zySJCt_lS~f-QtpBE7|dV1sr+uf}`OdO3JvafEu)$qxKN*cBz0)qJ3l7dNQF?e2$qx zTl(O%Kl{=F)?p_m;Ae$#$T>Z++zx)P?sNO(_-@Di&&S3V)XK(7A_z!n#}&8hhIS$1 zyF?buB1=N~6Zw(ARV5NTyfcg>MdIg#WuieO;(gx_rOPr>DB9#4;CBNThcGMLe|Gs4 zl0IJb*M@J$ZHQf&N$S^*#Kd0vV_KRCS@H@EIw_}0c(_UNsU-gV^#IzL!{8lioRw_B zR1oFgDP&Hym4w}H19M3^RPW7S2ZR>tgIS=SFB*Pzvcp@>KU+nwu(VtWlIqo6=8`U} z=&ReQIz{47EslKny&6eZ$tRqGlIG*@PHe&V>{aaxx3K?;+yCnG`oBA||F~d{QW;hK zYBoAWfRmiLq#^fyVu7JAR%3`B` zMs)AosE}I%-((u!l%H*>)#z?|e%$Ua4^MxaG9V13#woyI=dg8*bcl44w%<5v>1P~t zNHIz`3N}hMiZ;sL#~b#E2FKF0R~GsP3Ht+QekPn4i_2b7h& z{!+v|o8ek9`xru|y(&o+c@|UFkUbf#v{W?-54i%uIn#}_x=EV7D)QENzVv+xQc?N= z7^dcYGBFRB&lsTSygQMG(Rm^jkV%c6T=XXY?B5ir*==0E1W<#i*1I{^O6w)_)Foqn!kyDGZ-yxdogey#>4RD#= z{W&{|Z@5Gt1H^van6u!OSOf#BR`cniR))kMV4viYc(}fTz%g25W%x0ll1=`kIlceR zg?8#^I2wcXEh285b-O626ru=2G;yecCHfgi)EDHhlgF#Oi_h?DjvDz_n-HphKY8pN zolT6TEu8+5khpw#3S+CF_}YeQh@(NElroA33BvA@D%wPJG_in21=n(~-B-)#5$cv{E*X1j+C zn`8AX*iQ`W0SgMNXSp&bzi^!tYy-=!gWygtZ69S2Y4FQ{DiT4oZ$^DK=mvs|ag+i1 z2gVgM32~@?;x1P|Z1DGfmj1|SuT-O!s(qzG7i0SngKUEz!)EGBaf2Z+_@^s9GPoHq z@HhU^HF0xw<7+xgd_$E2Vunn_46&&be2m#xW$6YgN*P7u^%rzdFj*1U)f!SJ+7{Th zo4U%Cv_ag!b;89-nbr6>SOA4`iF#~r6}Mdu;afp}wjXQO4!INOrj?bI9y@BxL zcVI75Mf57tZMqe4eU(~NQ>=cQb0{XQ`7~sjwDraNbgyFYq@jJg$th6K&|RzalqJ-( zpQ=*PR@f#fA8btr=A(_$Zb6=j)oO(Tc1w-M)eiFUuKt}6!t2cWYwNOYnn9}@DXiByY$d_pqd^{)QT4 zBDn?$Hg{6lk#n{tDbdRJUj;u!-DEaC+|7^ z@a~1Cbc65EZ$3G#qsnMCYOH6Q*kJCUwx1gsN0>W29poy0v=2DScyzFpNPJpIR{u7* z6XyAhss>2$6F#oRuB2%&PQABtBXD<|EoW?-_s4m@?UZ!0gNYGOF0q74?L%X&EnO=n zM0i8@IR??ob9UWUf33AUZKo|dHpiNr>wakYpfbu=m?Izj_9u}?uncr@t%8RBSc^;s zbThVawSZY!B}~+#iz{Rap+n9>Ozj1GPXzlWKPdhNJrrQZ@dKdYx30^t^&0B|D9E-^ zi@}7RAe9Tj&NzJ{`0pzIq?pS^1)Z_DEU_}uYZ?a%6#e1{`1gRJGV<%#{7f( z=JUZ7?LZgRJHSZXgJh(?Ti-SbiY|!+ky0BcfUZwtcY$uSw^By0?Rm`B=2J@LLj9E* zLI^Nd6jdjmWguy@P~um9Td|n`{3Vl7?6VRAX>sR!{2aBfU5>hYoOzdd{GNTx(|mW- z@aOXk^5^dsQ~d>jv7T`-N3dHkD6nv_Da%dz30NGpqe4h= z#t|gkJTtW_@n)o9p1DR1Bzg(P86?vZbCeP(B)oVn2aq7xy!KLilnKXHyTW3$P1Y#~ z=kd-`_45&k7q@)_?4+EhgBZH^ME(Z!@s6%wA)Oo%sp$KTX+ysBWHaX?VC|hFW2=QE zH6xqL3_F9^CwF^DkM0hb;GHc*?A3dqKxXbnHTfXncuMyzKhZ9eupL+Q@J1H;JHyZS z)LA*{$Uin7I~CO4sjSuV_%~o+LYhfJo-@^3*!}trCCQqq@~{ zFq$5=6^(t2Uw6Zp?JF)3kvc8SOps;h(GXGg`*%TXzbG}ib$&i?*{D9T<13-x`FEG@Tr zl@z+eZ}eCAl{T4)t~X@9aq%|yy;B7u#gN%0Ecd+2Q6dW8HviHHMI}ZGC`6MAKsG%i zxK%K+N>njIdZXNwd>>;H^@+jCuY?3GS_PW@{oo1F_lEu7n0OLIg{(=)C5-d%s~)-6 zhk2<;H&KOjMpt_=hDUqGzt75(-763X(aKamPc4{)#rMt1iK;qGp^Sl-h%5e*Cx>N^ zs+Z0yRn5dsq@LD|22b>*=4Xf;f*}^^8?}jyKg=7l7|)S`zR10D8nJ0fqzBgR3XyFy z)2g(BO%K$8p&>ImW=YP~_N)eS|qW(M?qo)m9 zC^;l8Xsp{syXXg;tb?{&68P(m&pO-+ZcoVKhL5d(sox^ZC3H?K_Vv5eVwnfM-GM#b z48#3Wo_)mDw!#{M*ccYngqb^_N|L?!5I;w%4dLvsN3cTh3$w@XmH;mFob+F4!$URK zLzE|7sZBOcNV(U+!^UJVTu)9q#JPGFZ|w*P@O_dwx8O3#PzyD`N?b{&0QN8lrgRvk z?!I>_w8H55GWG{pRU`YI2Zvlu+>4e`!#QT*WGNjct2OD6s)6P9xa)@BGkI8 zB8Q4#WFpeJ{gNTUrF##Ti}}4SwNB}!$ja~|e!m#8#^jwbe0Y>E-ISW`i!b&DpSd2K z%mF&(mrSgIUvk?($nt@<0qi2sVGuHqtjlPzTu|aJuzR-I1uhz-D@gm7S41yPJ%zu?Rx~aIzf@&XjTk4Hte{MpH&<%)oFS-|O zyk>;7`<4{iD$^nSk7Exqvgyu7I$ z@W%T1?MvcaaOjP9mwha|Xmlj%Xh-v;_w?vgFvT19lYIIs66=-S z_M0}^l%uc1+9V&k z){DWcVyT6}Xm%v@%2~7)cB~a^xBM^L*s5U(o9+8!2^H{_UVK8vx|StJAIKm2+^aHm z8-KfjwzBZjxnsN1$Tv-ckx>x^2sujy=+{T~3bsha;%z}qf|KQjfvGGY`9e=vDPi>y z=>dfO)-diNm>ta3;Xt59KK{;`SrW+Ks zz|oyTs{_j?;O!BsnZ^~hrWW%jn7mNd6=#i=b<7I{Uu|jT;K0gO@f+B0-wr_p18p)4Xh9EJC4R@uCXt(tLgwK*Ue+vys8*N z!4_x2uJOMZ16IvEqBq}45EKw1-EE(OwHUTr*HBwnQ>X~~t)2K8F5;a+w44v^@87q5yCgbw2bH*B(%yoA3=(3%Cez|o;gD99iU{vg#I_jL7~o_| zp>`@V0oh0Ju(`vxg(uorR^-hlnZLS1!yzP`P^d1%Unk^^0>Lv8@ zW1}scIpD>X|5i_&PIv?dFY$zg=9XRhgoC<2Rry*nA>=I7k^cPWQG?UDqXpqd*tg|} z$o=n&8viyCY^CdDYOMQ@QV%t+p1p&euD*lRzdo}5uc}X`vboJaeCMhtOf60I_0^p~ zb;Ra;4iTf$V*W@*!0!v|)f^%O$E5JJB`rS@J%JY_>SJhG@?-O0H$1?SH1P0?6$4E| zGQqPMz5sEvJs7{&XMUM}H_?C2F2{HoH;U9zz_Vw~I$yK8UpY^49&bEuZhL-Qx&Lz7 zNk+q3yh#ZfX5`4-6@{8MfAI~%HhYN;!VZ4U)_fW7W!5+Dd;bQzruNuz(UtoXxc=J- z;sW-iqle3v%9kB4Kof8ikQ2}u`~mC%0up?K(5AU3hDS_?!0*=+1V#u>L?^7t3M?Sr6nopV+!}Vv9{6D3f6ds30C(p zhs%g~3B+PgrzNp*gKWOzHD#l^hHh8J_YU)E0%&84Vadl?DxvoHqm0xH+RV~}krz?7 zg0@HaMq{oMHP!6ocb2o=6h4|QVm|i{YpAM$I&;b-&Cog@xz|-&^7iU=buagivN&RK z=PF~+k*U_CejbCvCdTRs1f-3+ zF+W788f&Pa^5t&At~x~sPZpx+e$6KR_RR!$dibQipsgRmqvSBB+0+3kIabe6*OzaW zdvH_+3OXt(7wycvyTJigpm~yMuzOUc3{=sJUi(=7I*kFlk}kfm#F8*WVLhYSsO!0Q zm14LM2Da|Wu`5LRg5&LWw%@n=RPa5dC{icG6})*>Jd2mQZ`&*6eDw8 z-w}Bekv*I4ahQ9wl*{pD{8QX^0pC7>`F1;pHdG$^xPehP8sngzq^eb~4DWHr3PYf9 z;N2|LaaMGKV_Io3fdoYuH@c1y;a3PXbo#xapCpsz+C*W6YY;}QeX!&(>BBEzT2j!) zrtdi8YvnH4q*Cxd(eD(F7r6AylU0f)YOmb>wm-};Ea_ng!i+{Edi#T}CYn;Et~L$T zAiHroghG|Iuq1LLLgm;*4Ob;QL)FkXK40999@A(A$J`F7EVr1Y#=uY&6FSUMd!^%P zw~Za6EnS8$zm7l)zev-mVi$989iYRXYxdq{l3Tn8Cxl;}QY19~^_<*hS}wm?2?e~=)9Z3tCfDt|woo{$YJ zC153TtAK7&OJFnA4ofSt>LXfylFyY0tQW{2Aht)F(`jF|(qTCmk44`%v1~SV~XtsZsv&ATWie|%)8>lP9 zxEz7zH;mav8PeM?3TYCIX~m{5kfvFb`L0!FpX%i2-yFAxXOGsE71QDl_jHUMcF3hb zf@ej|WF^|fUy#FL3yfM7y7`%!TB4ssrQ3N&?24u7x!lN zi3`{;+NDyMg1-pbB zeam8m*66O*0_AO`1M6q^TqBtriU*A>Vs(3R`{FMdeK(cKGo>$?ZL#r|;Me&_E@6w; zpgVns-AYCTQA~@zm18{ZVlGo@uq_kdOE;ECGb(@|5X=b82nXzjpH-1%Ro40EnGT)d zRnFR@kNy)!{aY8i-~UYSwWa_(%>ShJ7GeI=zDfP>(tH1xee-|cFJ=E(IPK&YPxito z$tigO22__-DhC^agWn4pC_suM;(D-b!(75$SFNXCNAXUB{`%#ea65HjpbjC4G+%I> zF~#|u<^KLYJ+1v~#;^JBhNDiuFC`#h^C>)wLwY9ey-J^db=<9e5(%}0$pIMK5w0Q! zk`{9@m$XWbXnM~ShjE$9LFS-FNmaDtb@&42r8Ct@iW@9q?y{sXP*MYTgX9SHQM+`` z#hcnitCw$U+g*vs;bMH_XXd+h^6XOoxeB`m8Iete6BdHgP^zwT)b1SP8Zh`VcK*c^ z=Dn^EYJN843@`3Hk%NY$d4Fw~>H3 zNwkss??3pt7sIz9J#~h}3?pnRpQ&Eia2TA7RMRCe4mr+(x!82IY^*D%JAD&Wp7|!L zA}b_V_2o@!5-A331sMSvyjS)1X+mYiC4Ey+uhJK6W1=9!N8%%?ga;3Bc4nb%h^oP3 z&;`R|andhc39z5(`KP93^lDBOWWSMee*fnFm2Lc@~aurif?ttz68|+SR6zh ziL)gCnW+sq$M=n~;^>X&jG6u|^m4o5^O~Q~+gav%YQcK?gp=KQc#l8bdi%)T;!(UD zTlKT=%&|rHCUx*njmb=)p}(`v;0|Xbi|eF>);q*MQpdJeeum#aBonJ2jnjXBCS&=Z zW9#R5_Kzg8q1As=aWW%or2u&m1h4rGfEjM-X^`S!*g>I8D45E@LO(C=G_X*O;&hE5 zxF`FdZ}KDRgF*s<-?Z$dZLeLwT|9wkhFpWZf&g}n5~@{dlg&EyU5&66E*oW)nB~rK zrpor%x0o#Y56(h$zBSUnv_g0z+#K}yYg2w?IX6uV8!8oHn+e}XDLlzLzJqUQnrvzr zI#N+sI_#Se5Q%}8>5^cIsEYLmYI{>K2W>(A7#{|ryde`MLwlr;wC;gJh@rs3F}E1Q3rGkU`E6!#22PTC&ZVZrN;n&T2bg| z=xAtpe&GYr#~A48fc&7~4``OICxz9|LwWqX{yi!f|9_!E(CPn_r%L?cg6{DkaPq6G z)Og|6oxOc3gjvArd&u;K&l3BOig{q`ROp+Dn(2Ng5yeS*-28dTk0=(20E8BwYkl5G zx1Y+Cx;kIKhw$;dFsg~|l|lmKj*F4xqY6f#W4cSJuMP5x)FxR|5thx_OPE?8laIC9 z+#vU?%v-s~M|H`)Fx4JvgLiv`UI~o?20z#y%X$DrecKYeS8CL2qAXr8p+T2A72AoX z4?J$!bRnkYOc_c@-c26KFxxlTs9`!Ko>Rm;Ya!Cfa#$0~;aD7>$Uc`@Y$Gd6Ik2jcA7jYaN$jHY=sitcmOe0w0|}Fa>k@X3e^3DDF!+>I&oL05%G#HkeU# ze0&ynglzyu5~2>myb=u~H?R?J!4r5j5MTKe&FCXLf3$8C%^2pmg=1GVif`Td;$NeD z)@^b3OtC72K9BYEH5|gD7@|vcAIbA${U};PccY4F3`HFpu=Q7^QNMzZ2$l|i$Z;KM zfpTa0AYa5NTnf6XuV^9?tB@UCEhb2R{|Q`B`tFgm*dG&=?gkRpMM`?}>VmP}EcMvl``LK}Y+ z)ZcY*<8Y7maQAbMpYe5a@!~5es3@o@C_Fx~fw8`kzNiCwIskDJkQDy}wrV9UD7%DIIU0e5hw; z&%ZjeaaWTkS3znTo{-5atG1yPlv`*Xo|x5C**PW_m*cjfm6hwZjV&+QXhzN~ifAI9 zoDpbdR+RH;M$RpoXhzO1s%S=vcRJoS#yfARx)$jJsD2m9GjS3goH~r<8wY;yj+FCl zA>4Jvbc4Nu1~}rL^3?@E!o}emgv5B@;s-<^*u}-f2TF(($Db@qi5(;0#%Cso2J^bq z#Mhm4OQ8u!`_wFpvd)ba@=H;?M#OA`x=M{)2XIgyJo9P6-POe?2Xs&!{4}N^-8tj_ zkg0=Xyun|SW2OT>)JMDnJg5#*VyFWjd}zRQasT3?@_|5%BE}ILG{n^Mg=H`(2tXM& z#|PEQj}QhmMnnIWC$&0F|B(s3yU#*2ng4B$cw?}i}JIn4Tp5Y3K#~z z1toQq1?fD_>;17Q&kMg(Z8c%xBtBrobz#pC21CUkxXhEAa+p<+f~VUMES|9r?7;c? z(i-#?B>)OHm2U_l^&;=Ik1q3z>;N8S3P}#fAS33KDvej$$EGaYC~PK`PQM5=lQhrh z&c&a4R}Gguzyi*$t2g-$3PgKooBjov?+PiY{WTb5yWf$I36zz8WI12~V%6%V)1$4| zJ>ZoqwoX~i{Z+~TS=1c+dt^t-)bTczk0xJz2y3Sv%FDM~_a^-A>1WV?_zB$;^^jjc z%qSmaG0Ux^JIn?{=^FYs>T^FK8RLtzM{cjR_%o&!bwU4*vukMY^{tfuci*@1%{$-M z5F&^-&H;ZF!wbHa!Od{T(2lfARIm4OA;`D?IMf$0HPeeW$M(*2%fycNy@r4EO(}@? z6a?fKwKdZVM3&_ZE!Xl677cly#^4MOsg@B*WHr4)Sc9BvVJ^npTwuYyX^`FBGZbT1 zw|NQPN^aPz8^5H_>=@+${=hghT3LWHs##u)T-T^fyg}~hogVl#-GaiFZi%T!aIRD@ zR_W=TQ_w^vsR2^cAA|guzqspAjOah&OghmE8eMZTh8=@4h#O`lVy2XQpe2KRNjQHO z=>DRa0e|Ev-8DlthOI+2rX@qD8kaEMRH=>Q@>lL#N~qlifX7qOnIgs)yYM;scQ0&X zm26`?{9$@s=P!)B>>|RoOb2@Gox58~ilLs_v(D~USfF-pw9fAa%eeYtRX_L4wgGD8EG#C{2rrqp@{3( zWghUF#|D$&XiN+_C3!UrqCKLl22fYlnBTc&O_jK5en-{~D$r5McnVU~u@|PIPp-z! z#1tAWN7J?B=0o1tlE=5lSnMLZmlZ)?b*8T`8MqS}Wn?=Suzx>DLWNZprdVD^7*GNO zefa1FyNV%gyVzr34O5T9B^%OlgYb+mxN)6~PqG33w%@eOfveTxKE>lIEgeD4dPBSu z$_Qk@)rsA7H#yU*-8#9g$7*-wb4a9O)8QG?BO};u-7d|i*m4Y&!v0z%jWyy?LiFom z+xA05R6ubzYXRHYS|yQm&{HC`Ur|@nOG9bBPu<4KG> z#ve$!mNFJnwPBq*Bkgo=DGnR#KbeAN{ofj9d~q>`AjrewF|!+c1rx-G&-o51xHD$L zT8iT8!k};;T}JV{2QEQ|n7LaRS0uw^7ZKH@Hd&6p;{fzzZ6{1Dh3|!Ql=eg_RKG~;cB(k4YhH1SwAW@s1j&ieboEl^a~!%ay+%D+s-WF8FB zkkDosc|E3akQxyY3npoThvaP|oN}Ye^`2^?=mBmzhkuTKu z$Hks^5X(v8Cql#2$dL{3^&I~Kx~OP!Q_}OQ|~fWoE#cV6AzrLN=Yo~S99Y0B#Aw$9dt55Y^pYvBffT7Em2MmnIRWM?Zzy4rfW=Uo@edy5qv+8Hu%W?2rL`LgQx>5z0 zKvb)-y-C%q$r)E5CL)1!0cfXBOM=B^;5Gy#MXn)5T- zn4n--V)Id8v~HF-C_D)&MR!Ii;c+cXznT8(oCEgO*;v6r>sNb7K4MDhFwZJN|0Yjg z=eyxk!ZBIZ5f9+=)hWnCs_C{4T%nAaZx;*b>ogNMSRmMD)QN1tqn!vww_mIi0hmhI zJ}$%_t-F5b(n!AmjFLc^yf%{6UJnc5ff=M=CFwfpg(5vFUm(&6uP&|Vtj$MFN2I4_ z-+f=Iah{;%jn?Yx7xt9#7=?WbWNmP>cQ4QU4ob_9D-$#S=*_8yz0tv(*)Y(~+V4xV zU_n`0z|h`bVC-VkU?R3wE zG+Lnp_yFwApFMu@$MR$vatKJ51_0Dw7AGOFB6Lpe!dxBObWt?})&)Xnmy$i@_o!c} z2onh%5-*T34bp~R?M_nAmKdoNWz|SR0!|K8ADdd5IyzuFAl!!12n(B9Q?q!*$ReoZTY-Mk<4_}K8lk+9ES6y$9x+s|23pn8t#imLI9|kL9>yyW-CKL%G;@A;vUTKx zchncxmu$he{6o9`TXW90ki<9fNjKvBH|?AC@PoGy>)r8+mS<#jeACA(;xxu9M8zug z(fMR?vh~0{->ZK4YPQ8w;z#46htxj%#4+gy=RIq3^?*H>W>50XpvtKoURRid*x*U` zCbW#yrq^0c_EHWj@Fcdw93TU6zN;s3qF_2i{^XrWJ>FVH1QT*DE7T-9n`u{Z)myIX zS}8ETb*_eVZ^A0+)kgvq+c{pO^Rvgnk(3%)!I~#_sl&>=sA3Fjb$n90y{Qy& zrHy%J!^EZ_`*TXy7r+S;+Fv)=))P2^enW;ZDq?C)UiuR?kO!+g%?JLrR4<99B5N!&oJif*-H<0 zr7^-qe?fVNv3XHrA~ru0gV$T1MtT+M#f?9LjcKV zm0kV@&#pVi!bd;#C)5dNsaQ1Uortj(l~MPcA>%#}juj_QD%w0m%N^0;*+bWb95O>S zeT@F58KMW8ZARjo9z5oN9i_$72J+0DJArC>mK2NC=3kk=50vMcCH-r^qgmsMXQ3Au zWDHQ?ymI!Zyl`IdTY29X-W$Vw#0C`i4gKNsSGkt}>I1Fb5j>ixH#5{+$UM#~=a%U> zwzWGc{JH{2vje%sXpQ^60~_GD^r7{dJsFOW1KJs<#3`Kc_KN;g5FNBh1JzU|#d=}wqB5tTTx~?3D4FCKc!`H&N z&JV?u)F|Ur3;CQX5MrpgZrA)1pV&%Ghe^}9Uwm5h3@6QYqhK z+R|_?5dFT%*xiESutfK-fbLWCHia2wjvC=J<58h8n=CkU_53ppO-t%?lFeiVf22h% zB^|+xTwp}DZXzh^mG!1i@-S^pM#^W^f!LSjsH%(ks`76;e2MN*87LhwCnYqc!{wM~ z#JJ*@?o^8=t;9wzc}-MOE(1?d1vnWNuxdVHaF0g=NnYu*lLt@_b&U-M*!AJvvis+k zG631Tj$Vn- z>+tRjKc2iHz)tbT_#$Z%s0(8~P$PTA;AK%K_sS)dSwx^X!xnl!2>l3T4+n3_wEskZ zpwlLfs3A_f{roEK2AryNxbY_{hU_3f`lBMdj}z!QE*gGc;i@FJoB^X(uaSTI>0iiR z+G5oXIa!hVCAV3@T(ne5Sm%18Ps_~)YNBo^sAFd3%0IME_M?{GQEj$u0RZ1{RvqxO zj>w2Nn+gNZamX%oiP!z4YvPF=(MkCmrbAePF5H&FuO`P`c~}D_1l_wvckF;Z(y`d1 zt4>yaiGFPG^oG>R7&+lisl$eWnlPH3j-d$Lf+SvLlH_ft#9*cY*h1GhJjbwTQ_=eV z**&jZ2G&&Gy!`op8s=vjTNT0N6Y=O*kMn0woWvcDY1NWPQgURfhNMiNB@ zl!wE;VDrXX2~$tbTxP3z9?DT(aY~mMZ}YYTP69_8t3r`K{|a=6$4UeEhUS^?3wA@# zCUy)OIj-kr;;m5_=kL)Q62Ibye5cI4!e5MT#(H)waIJ*X_a#~Zh@D>e62$X(Jm^P(}m~~Z! zYfs)>UAIaETr%Sk?hqHw*@&_)6)RQ{nZB*KTFJ2NUaYU;Q zxoA*iXWbP15xJ*Ep=GZW(p{WQs2b9Fz&b!P-$Gf(*u3lwJTbqmvWw?;odDCWCw8#} zMLB39i>4x)9-(5R_c~%2lPgZ4Kfg#-Ucq4%CK5~aY8C=+pV(3L+2S=c63E`^AX{ zM;J3n$TNJ`eii~zp<^4W#Z&QPotDIIir;q1HCk5nQp1Y*PETGZQqO6e z_Gjs11~Lv<<=l4sq^1|8b<=~`&4Db9TqwGQUhh$KCOaY9p%E37)wN&$<8}`(a8S$w2h_&rhNU&c1Uj9i|(5p;y z*QK{*tYe*fuai0NSYXvH5IwyOcB(y8h)vC;BR_E?%86|dwm?ic1WDfmY-_nJUD8vw z4;!DqnBl6|bYW6%oKUlTu%N;j|59wigE*E5V+$+5k0_9gCz?uz@uEJ`6F}cC_bkQ_ z?#O_HXV8(=j9c@)<{5V!pjob#wWN?sB#Uhlje}=fRWW(bQzYxpiF=(O--5&Nc&D=!Q;zS#WkS)FkFX3yNjre>^Be{Ta@qR{LnCt5ig39C zab~W}q<)2@qrAwb^|g_i)G2a}=?3hDR@g^Bz0Kp)&U8n>Df8mGp`>H|Mbm@pBa>Ea>&sN}-`YD%`DQl{c zi?)pPDyp9`XY1VmUSx?=Sz;ZU-J7N~`3RXA&a&YmPq^cQaxX?T^x9RmnRbIMhEE7- zAm&gOIaq=nnkd55P*eC&3ygrha9vlGdnwrDr~e&6Hjf?@*vzt7m@MH}e2!_D^JUR& za8sU659tV=v_>VsBNy-cGyXeQaJCAc`w^z_kp1tx=qo9!k6q46GjON9+(nZd=nvDLq>ieWYz?NhNzy0MGk8N{B=Dim9tCvuS;IGmdCiY^LaW`Ui>%_oOWP?4)dD zJUbC}5N_(?+cogCg35x_H8i!7%6!B%H#YV1e9ASDwW3TZWOL&=s!NJCarX49We*3H zbrEUP$0IKaykS~2i@fgz{f4EEuwv|Z2nE=$YXGW~UGX=C^D8X_zd!;gRx?)_!D2W$ zGq&bc9Gg~8vm;zi4P4f}F@J`uUz#2?g{jJ3X__CUTY?{&xxToD${Fthc`TjrH)K^oe}@R3V^ z97K^dJ^RK~Z@p*}+7s#;$VbXGMdcgIP1>9s6-qz$Nd}kGf}>4AB#+H8PCe2|-SW|(waV@7{R!ejxWb^j z6#xv6B4Ed!WMEiaE9u zgU_yNNS=Fh;j!bo5vs4nvQL6ui*>JgDg0t(RQM$)M-5&`ttl0=dbFCTGI9Y(wazQZ zmcgMX>}0aZh+~M@5Yx0YO(LBS1awsS_@v;BKYdB6ErJX*-BA9{sj9?jfGmQ$USt=a z-thW?dNk^~w3e^bzhY`PVV1!@8KoZDJO5C(ND!q|KP}Z-XJ5>xtE)t9`GNS2PSq+v z3_qE1Au|o<;qGgC{$W^Y9&1WX8t%4MPpOd|h&T#$68Y9l#DT!3Qfkoit31HhE@ik8 z2#5_cn%AFetbxX5Q$xJG27ZH>VVxYl^fcvVZ|lH z%N5P`?xTidN^Ql6WsM!`y8#b2_~J6kc*q{*5*4?7trKk)` zIY6wrq9W3ZNOJ>}B87T`QuGVv-X_}y@d|d0#z$?w#1R-own^^`Y=e-Z2dEFy0p2J# z{D$xWW~y%yrFxi!m*vkgD0VN4E>+Sz4POgnd5pZ5X!2#911RuYd!L)gaciAFzAz!9t z3FyE7S%iEU7)E*gX}C@N;llp=>iWNJ*ZbEz(sePkr{;Ar{V#c?M5Xl~TUnHEODhOn z-(P%!WshOBy+V~uiZBg1h~hnHy?#wkF%&gubt#)TjmVYMTus)P*>0&#T`ck`VPfq2 z4n_1&Pb=OznNQg!*k<0w&S1DhsF|W&_EXMX*Uy^MtncUE+naxC{wynW6z*k&H7iP# zkCf6VPL#Bi;8pj@>6Vj}q(EUwYeFwPHa;ov^D4xp5ZH>c^%1NSt`d$~i9U(caYJ%H z1;GwX(UjTXM3`}43!z-b5%iVtx=p_W5;b}$lN?KbVO8Zm8Bvwfv^=5OG_s11r@q7HVL(+my#mq-p0E#o_9r6a zYA+j(BG7M03}7)?fvIrZ?78B|fm5@sJya%>j>x``>Yz}Yv_3}qTo~$<*K!Q$6hf4C z-?e~-OR&aYfQVmNM7*|zdCEJ@`^w4_j@d;ldq^Evoh*#KmN<};aRQ7No$f7w#NaZ% zZKS18Rwmw-ZA08!q+10>j)9?cU6l4%G6Dmbl~q?Qs3OvjtV*g5a6z^>fU#s6R-C?~ zA9%fC4zHYkfvx`xan%8r+=5xUOm{Y_x00-%-4i@5NxjXxM8zGrGTPDs>-w-0fuCs0 z5ZQBIO#Q(q&=4x^Nwz*_JRwJD4El*IX zo<2Ug^(-?kVK?}m5E1n7(bQgvsfk@xb2a4fH*4N8Wf0BAw0iZ@+~picaK)jTs#axL zMdI1S*w|l59r$V&*U4a)-s*mLls%47<-uS!jre88<>Cy-FmJ83sgDZgyR##d-H2v( z!apr*)6adwwX9Ca=la|EMh{e3>H-8yO(8|VRwOLEYazc(iA|BuY+=l2CNaAZuqKTB zNHF+odo(LlXCc^kJRP1x@VzJEx5c}(+2HTxxsbF4_$%~bBM*_{7cdCMU@EhArcm5C z14v*AnvmKfMLfXNJyOe>E`@*(8Pb-PHg>{60N zs&`6=*RBrfF~Wzha$f%~CG~6X#(N}YNC>_R*}a?>U@Q0#yNP!Ieh3GAr(kpq45k46 zl^bw8Q7s+Sy-TMP&yLZeR5}qh3p8LVcmcAwyRdBWMGC$D^=Nlu!{Qs52tKrj=|4IP zP~;4zj)(!;0FqQA+6&b%x@rW>-NWpLgL1vn8W0Jv;qh|pH=j8di{k%_iyxkASjofJ z@+GdLI;LlN1sP??M(6i2VDamzEj)h0#;@E5b#G|PdqHJ2Q1A(PLtodIB&y9JH3~MPPZ@(TNQ^R>-Xe8F z*G}m-uTfun_8O_MCeN_4JyHA1CD!9TW3P_SzUkU+40m3VZ=2j5zFECuW7|rLQFoKh zUbh+YC)f%{-=2ARQg{{3lXXWW|dst~-)dQJ}n`rv1NeJ`3jY;%kH_nmNmp`|q z))-!0HZn9VR*&d@p=s(iiM5=1SWhi}9~$*wYHHWtHM1Uutsvg-A^+fkBm~gBVBqLu%bH1!+)*}iytf}kc9B?vM19qT!8KbV( z$CoLe0XjdszO)=RCcxVR~&n4FWR z_ou4(77Ec@CS=>U+-TGJCapJGXKE+<-bR@xnL!7}cWx2#wA9n@GiG(8Bk&ghQ2Lbvdvv*@w zO3v6C5bIkEIwI~k^(&T?=a}w?Me6el9|9kU9f&?;um_MJ6-DKr$K8$yBBa!xpm5_q za_;`EF4F&HnzLk$wFpW$ebwivJf>{>j-v?DH~5i!~&Q5FkQ*>G>ihu z7P<1wrRrK}9a8L3PtJSxs=*2M;7uo+9tCRqnAgJyi%vzpe41G^`x+|RjpJm6Gg@xx ztJTDDEMq-^u~prD$&JcFUwTDh{qo(30g|M93kwn`nA2+Y?Jz$BD@NCvgkUl4nMKCDzQLjDu57;|RK6peeB!i9+4#Yt^{Tx~w7_GrA2!fq8u z-kMW9zR9Kh#7C_7FzJ0tU?^l~Kbxp{3$+y=B(NyLN#RiND6Fu`J@G##9e{V83i?l| zCHEh-js7R0)<0nPUt~`OaqFMF#aGjh`8H#NscWimuB4A%iPBzQu415qJV{xZSX7I3 z9HFX>rFm!3O+AZ>2nLJILGcYfOns4H2;YKG;$iCQBS%+iY_~P{PuO^aQciW%qT*CL z*MneGc~jA%Gbl)Yl%`|irZV6c%v9xavQre?-g2~yW#!TmT@IPy*BS1H~#$Fi8>hm-YmMk7HIdHmoQOe<^ia`0 zkWoa_I|F&d`f7%8XF$9`@#|YAg+Us%5*a-q>=+Ff)zV7iaR8f}c<$g_nW02w?t8&v z@cJ=E4-|S?9#pfWeGD3Nmp+_t0YW!50}?e#c~~!vaE(3AVlBSf)Vm%Pe%0|BWqf=K zw~+NKMF!KQ3lL)6{)inMelvN`bgD_MMWbDx3&kSuhNu4oP={htC_@fAy^XBWC~a;~$*>0qws)m8lBhf}!mAH7&BXiW#Yuq?8tGIp~C;oo@G62zlEUsM)^?dbq%FOjl;PdFfS7?_=rl6K1 zS16|V<26*KR4PQsPbgogmWWi=AX3;#_E^#&UHD0cDRY`5Mw|Gz)Ip_?U7=0Buw8*I zZ*G%Jl?+pnRI7oj<-W_9%dM8`CQy0j3z(_%1U@~MSZd=M4!6XmxyPMPf}8M$(6<}* zB^idHLvsfc@OpvAB|HdlqdFJHJ0};^8vX^-mmB`2pa&n&oBYNZ5c&5PFaNJ=xR;n7 zY_JIM45Sx*UvAi!ke*>+F5H`#o@|JZz@FmYUvfLuzqu%HP<@4gvEW}adR%>{AwC*= z;?b~gnt`)mModBX0DS*2axGn(kqo7PU|uiF_;D}FgatDu?Dhj1|K=jUc?Oh*_{i^3 zW>DDc1jL?~38Xd$4Y%!cDGxGJEm1=%>%E5XklBF-##+`12??z>D;ebe;iNp9ssz{r zerrU4d*q;m|1{Z#50>;_gJrd)q#Gt}{luOCx zS`9(4ZQ_M*li8sQ8o+l|%^RIs!LE?akj)U$H|-L$Sq|5;UBYZh`8xS(x`-C9-`Hoe z1)L$Az?~qiP};QjV0DzpQx@Z-1k#JzNWDurJ~whmcMM(L?8O%qfh*HA<@*ztxpIX z^aswixV4|njM$n;q2_@0JYdlxbAriQy0~tlJauAycUon82p@td`l1Q0>ILCw3&4EE z$mkHkh$$Wm;c9Ml!;77Bp`);xI=0T8PHF5^+&DFe{g3_7%N2w5 z0A@O?b2R3(TIpB8Wt8&aaQy$l**gW<5^deOg;lF;+qP}nwr#ss*|u%lwr$&5WuDrK zdrsW=_dRhVG9pL5&4-bF%-*xL_Dxz|W1w?bn3~jf#NZr=Gp>4t3YF)qExA95vBX)~ z%&enRW}q-zy?@f+5FjnLgmLz7O3lwDs_}EUUk-nl;U7EiuJ(=hI6G9awK&=EiVU>o3E}8GB89dR3N~WiG7|ZOHj+eW=c< z37t=kzDJILNmss>6dqTLX4Wz0BFgdv*}^z}RLAW}?K%#1QpGreqvi5^o6y=brEz`x zL5#%4R(3QpzDu2wXVo0~9mD_iN18(Qg>^)MJ+rFv6#ssy!-@xHNt09OK5)dCQhN?T z?sMisP?^wX;F zg`GL&!s0l?bIq2L@-THONz-M(g&6Ls&HHAqwK{Q4kSKYuTpv~oxjG_BC9g4S+khE? z-cl^8&=swweV|h@HJ=ucz)3Gl(?cl`>dAQ}^bKGM#&G4?!6n;FTv$A4%x>bWQQ}1q zw~ufHe-^oFCCM9=Cc}9JmJ+o2md*QjUHMK-J zL4SQ^={jt(V7v+w=BX}@+;FeIkdA{PQ$oU0N1AmMXf1mbBbRy7)@~%clSu47zhiCQ z&FfxLpLsc2$@zi@6JkcayfZJGJV+-D>$#p+R67=V_dLb{q* zUer5YsyoYKm3pX{{K~vLa3-coAD{}1X@k##Ndkz`8ine0+5!QeqFWLWe=>e<%Wvg@ z12eRNVMwyaGE&)sTlqXrOvhII6?0lNiNO7gO?V_z$*$K#Msy*a$=cZ z8z@3H3hk|g2eN!*_-9&a(IOUf5n-wS%_g#%?DQ_bI2A0&Io zY_=Oy2u;PWz zCphMSnae-tVBrO1_?DxaoR@hYy3^lYtB?Rf!H-e1h@#knTxdmszKSGk*>PKUh7hwf zl4TxfT_kBySie04$^$X&fhQTKD99-oWzIA$rGVp&V8$o9x*)|2q)USGY(=RCNj@N7 zu|Pq*BFVT>q^!hQf^e&}vIwOp$wq<0ETBGwU|c_(0%a>7t3Wd;p;5dohJ_Nhka|2| zvD_g<5+d&po>-*diPDjnf@^6EMVT+ z{2=JxC(BhLxe%0D^PnPivtXH61EEIh8hUO};MLv0+S1p7YKiV6#=9@Mdc#3|ZiQ@G zOyP3K$=Uq+Y4TiXT zznAJ{$cq^2cDjTWt~=eLv%8<4)W#$h#)exaKOBi6sj*{Q| ziwXy6JyBQ;?m*9yig0CzU_oU-4%43xtAmJ#{mn)wd8v{cx6V*nR}1mAY&n7S(l0=I z@#~ugxBCO@&@uovOsLV7=uGnPmn;;$JuheIF(=KoVT|J)H>?hftqzR_JUPinCk?_F8TEzMxffdABgnJs`GjX?C z;J)~K?g-hmdmsor)O)tXULyUb#9lJ}C&V9Ffjud=AmF-*x5VJzczd|SUh4g-L|)4M zD?}d&fi;pZ!GX3CFUf(nk}syn#)8@5rURPa_0L2|G)a zCl_KAV69n0*iX)YWenS~l+a~s*Lm^Z=CU@u& zJ@qgCLn%~W!}~W>-THU3DBlKm+!459c=d2pRAqR5+GVjYt{edR6#>CqllcilJSeiY zY@_?;C^Pjh*b%5|oum82D871kqA0WtZYe{aRA2r3qM&Me8Nijdm?*M!ZqY-3skUAH zu$wvYK)&|yI<5@vOi^-bUlsvjTBiWbZ?PkEKu0Uf5Zl#1wgJ;_HBn}2-I9hZsdP;5 zf`RLIRX~jf2&r`R??^!pd#PbgLAj~AU3%$jLw?OOeC}bRe7o@RTsrpx=$PSQx%AfE zrUFL?kYdw;bvyU!U8D6Ipjk-=v2#DL{MBs_N zLz*;>n=!zPz^CG(G8tD3YhqB@OJkVsFJhQJKE|p{sY8)XvB#lFse?hCX!YX+a!Zc< z@nA((tr8f*nU1ao`=HMpGYf3y?JA)Uun7;lT(`oJj=8}<>rCz=aPbdI&QTl~w@M99 z*e6D+?xHj3gdrMrLSz_!5N8t|ETs}3FsI@lJf_kdaGHA1r~3`dbow1y3t*w_r) zGi*OWAy9*Wpj2X4Oi~6TgoHR@dXwS$WmO$HDZ)6iIHmoG4D^p0jYi&(YX0F?|i7Mf5nUZs42{tmIzhj|7+c-aA_x($a zFwEsC!l^mr^G|$vE$tyRsNkKZGG}?0bzqj!AjwFXJiL`I&aHH~pjpJ%aRn}Mf=~sWNl}vF>v3>wpGFW?IQKf_n?!aG7kPS+G!Og&z$%2O0gU(1{!Eh@sQxmHgF#b{xhDfDeE z-SSvxWvmN@^jDbjhN0d%nGKx-YN#(u^ncB2rt*9OcwYmyl{YP+Qoy<)4~=Lyzy;&( z{cSz$nS2JLnf6-8L3LB!VlW`B;6jtj$*(RPKw%}j-;WL;xVe%_SaC^K&mU*-Wa)_K z^4*u`@lm|^kgnRc^9*f1DTQnf!SG`I>|A+huWiW-Dt+iG5uy?_DH$Y8j$epA`&(^? z>1mLIIV%ZkX=_Nhl$?N_{I1!R$L!2wTbk!?f`HjAm+MG^5pE41O_vT?ovzvNZ>9GDuNCdkWv#& zf6><&;IzPWXC_T?w5Z$8Y^rQg?v0@pCt}aUdvQ0%8|Sgfk(>40mG%TAYkvFGQch9A zq`)?)g&QvW<}ZuI3Skx&wkFbjh&Mc4(cDZ~$)Dpw=5kQN_&~N}?}}1>{Gx1yewA4S z%0)rZD3b6E65ORsq9(TmVEQP(@@23ZN$a^1SanF zjGPK(fBfSdoLt2A`4tIB)8PY)-}&0ZhK^oU(t9SrrAMg1rHP;$X$(od7~A+~CIxSs za~|v>8_S!y`!UuAJjSpF<9p>eK1Y2?)_p3<+&FofG~5bHO->@~@X!T(LYyjv(>=>0 zq*D3qC=KWy)YD+~FlUqI9tjOK#c39yLWr<*0cWYdfv@zp80N0i+ItX7k3k1?rl8K? z)po>e1UQG+bVrmUFgde4Otmvw{xH}_G8;r8bxHRb7o8hSkw-Y6P~jBxJ!&-Qgj|4& zD2Q7;Q7}8{%1y{xz9u=?=H_wlLR+SBZPX0*>*eX*Rg_NEEV@~emAoS_(IS7vqI5fB zZ#T2x7A^I8#GueL;q$f$GE2DQt5F3)p%N?U)G_7&0;|rETND z)Em3WmqZJLiu(k~ROYlRe7xxfn&p_r_2i? z);4VmTc6&f%<0DeR`lxPF!TTrHPCRDf@B}KZ$nmSZA?~fh%)co_pE^|9I8maNlQa~ zCL(XZ8XoUda7f|3i5oulnU}hS8@~2)+r(uD*Lz5;_lc|E6YqrBjB{}aMn^b%8$&8U zvw>0l6#VZm#EfF|JqO8XkmYKL5;gAv*E)MskgSZEybS*xD&SFx$30?S-{1C=z3k+(-BglEH`l2huaeU=(3Gmq8Vy7F~Hm&Oimwzfa^utHy!H=@L zVwG>4+B3K8_(`Q6-Ee}-v};!luL2X?dzmosR$K)|NfX_10ztCqvfe42;?cQGibs~f zO9p?dcsT67$dume!B$=es;_shaoI+ffL31wT4c))@KuehfjgRC>!o{olSZ1_;Y7S* zOr)aSs6nHb++~Sji(!|z^ovWe>a$wI*@I(3|Bl-PP+0|IunLxHO^c;QB5CO*YegRJ zWl06v$OEzop=bp@?#rr$bLmxRg;eR?sztc|F->NxjgVg znN1LJ?em_MuEJS`_1qH)XuUdHs%s1V{fpd#kT>9Kn$t=AGQ z8zwa&edZrD)Un8Bur!Vr(5MAU?nc;pOENkL9UFqF4`vfgunBZocS!e*=!eoV&=>xkr_8EMpEfRF z{F~g{1hulQIG$ocwE0qs3DrfALO2Ea=KCy7GTsy?H!Wsivct#Yxc)G0W_HrFO67}& z)8oDvUJbSbx{## z9{v`%b`Kw-5LO?_=a=D~A=$u8?r+`@;TI65{ghcD_XO^JAbYe;1gI+znY>)v6QlKM zYqe6$V@xr?Fv3|yEwKp=Ds8)UAe+34CIB;=8$_gclD2ybiJi1|S{LVsvmyu}|HA zq82d1q*?q505+pdHi3o_W3q2+miY{Dh0tugqTsAy%t9% z$wQ)-S8rno(x}AQfLVeIHOwj9lZ5u^AqwJ2LIv>~upxy5p;1EUr{D6Wp@B5z|2hsw z)cb=5twWE3L=QuQOxpiw;BV2er}vHX`!RmtDn32tMW}Y@^aPZzpRQ&yUlja^@hb;{ zTf)MeOqXWlei>E(1NEI;mfh7s+FBh`^d_?W!pMRiTFZdLDBQvMl?iSq;G(u2Zq6o} zjjwf-yzLOI+479vuI!1Z1DSVpoqmKdBS?3lW@pg)IpNl z?nos2JlUbQ!3VLB!#yw}gH&$eI-j5AB$ztZAWcgDqPcC^_IF8pWm8c2 ze{XOu8PUSYFM$hvjio-vQ>F4h7&JhmIL}kddIM$~UraO#CNpx&gI{&ThO)vBol&@mKLE2{NNHauca*&f`BfJXV# z39#^4fCW^T_En2hUj_U=4rrI|p};XE?{{pp1%F~cs8j^GMG42kyvLb@%p5)Uyn-@- zp&ynyF<^{{9?W-2>{sWW@60}zGo^c{eRzo(AM7vAyv2gIWBD>f5_9DX1{LvHdN>x>$YrFJRD>WyVOUG6kb{1TpH z5ly=DBNz*(0b=JAyzA2~6v-9FF#x>kJVH-uwjt-l_399K1MEn6)_x&-L@5N!QD02* zt}UrEYe*_o&9hOP5Z%y?QQa0roh^WtQ0#J9qgpT6gwxAi*InW-TKh&HY-&QthA2|G z`u0V^{d(Zt>pxGxv3)b_z;folhKF^OGTHgLeyPlf-z^Kby9|iugPthnWG#;t2vP{) zM9-;K&#B_@C#ImrMU8vtDWhujEsd)=SE?{q|0Szx$hjXdoYlqh+uOHy#vW(wg^bFDZRw&Mt+;&ZjhbMw(k-ZO-**h%g<4pMkGW5+G0WD35ys zvA~WN!bLh;G?(H|ifUyWt|9J73HwI23snX8hI&t{w7>TbX5I!UBvlZOe|vqPV=e!N znd^}p^-(-G7deM5U9yzno)Y^6m-m$zrB1aF;NCJzqb+>|M#(_;ZjXDj%>N3GwN5n= z&^9UjN`?YbGZ6X5>QAXJkx@<=|2XvTy4$3`1#Lg8#Rt1ubp9mYQU%Kap&VOU7il8rdqUj)v7QC6 z{(rneE*48JndCe}*Z;W7TSUA)G<%B7i;59CgUjdejmj*5l`&x$VaZP%!z-8<(h#4A z1#a4uJ15CodfYVA5e_j>1X=D*gFA`u?vfOg~8{M#Qn}5+2{@!u{i(whf>skJS^Y70}tSh4wm+0`f zV$}$G({=tb?^F|xY2miyVhn;q!5KgATJRbAqvHB#6NeW$UmrH`D!~dgi`M0`7McWQh8R?6~HzSAG#R6Ef5Uf#P9>rf6$XwFg`o;VV zHeR8SpjNv1j76W-hDA<9bWxs@BH#cxU>V-jOMe(O(4OL@w*a>D<+7lL=cW9B?6E^! zb0S7TYQb@a{kh}W=Q*>1-Sc_-*%hF%FPWa?02!UssFUKLFjA4hfq}#rjiLAl-QA;O zbtfyW%XV`i@_2CZL`A_IF&->jR960Lm!AQERwK|1T0p=Nj;0a3ju4Dh2hN}b4jkVF zWKU2lbc=t~47NYUn*aK*7Z|@4G`{$wnzvN zv?o#|WE_8qf936&72pbh}QRTfGKj|o@wDK`$0kArE^@fN^eIX`d`_-Uhvq~r`WU^wo<$?$K zHluYShk{`Ymu1let_~-OjPKvO3DHQYZt>8#zrtOHK}Lp@>&=3JrsxfOcjVj$PJ_cl zSQ@t}*adL7bQ04NvNF_~Da+V832mwFb}iFMcNcFtB`!RfchwY#x+VG;GN=;;E92(~ zDvuf_V{=lbN|cG_l-|W<8(kn(O7oHkg+AbSq*8H#!=g2%wVYPy#f*sr=VgEcixoq3 z`Edl64z(q|FQI7f!GmaGnCyy<<18os<`q_^51+vR)e@Wo!u%>sGYgD!= zb5TH_=o3y%1BcQA=$b27+5qOnIGD?K@rIV@qJht$HYU!REgNdJ(v)K%fmbmBVI7uF zh*wmllB;h*V|p}S+{gjxjP8lyp)$=1#E`iH`$9?`p$G9na4!Fe{C=sbeBf)7sHPh+@rj1yT z?NkZC}z6|rBz>Xpi$c=2}Eg1^%flvQFG~mgpotmgIcM=Gt!mT&%#{L>UGZcC|?<+w$IEf?;1;^SS(n!&)$%apo=Yw z?>2@JkR!>{$Fh>KL%a^BV*bhsIsA%qp`V(v4az>se`^1?f)jWma;X~cQAJ{`ypxk zzskAlmg5g+i1)kyoDa!*mlktcU20^d^w&E=F9XGR_chH9_*iNV4IC{S)+dAU0rO+r( z_ck48xKFOxdmN{)=X$z7H+TWC`YGYLsPl>Z!%|V?QRoQ;Q1?RZgcpS-!&-?9c${2L z*RGF%bG~`GR-tcDg~2}M1M5-}yb&~F_lRim{X*E>)db+)+1V$>qZ4u*9fbTtsYtyM z2+(3r>v6ylVC?57#%PHKZ}p%UUZ=F@>DmXe5a+Y(_Xxs0Rra#%5vs9x}dILX%N;Smf z`n_i?VrO>}T1=&X&$`4PxVc+8;wZC{9?+_&>n2Q_qytBgzOl^6$Y>i0x6m@SiR;)| zZ&7*Lai?u(&XI6qbWc_HYC+`KbhN)V7bkoyWUqe@q~qLjgFjysU&Da8`C}FrSEj2w zC^RsSNK4l#t(l}xTqbfBq>)d^)S+6W$2n9jN=`N_ED+IG)|*^hPgd$k-JRg(s$kSh zNbz078go>ev?Hd=7j$tMq)*~7FpcO(1MIc>U26Y$owi(?Z}+{%=cS(q>CA^jofBS< zSgPe~7kdmvV{*8LR^kx7qEH^{%i5STrVIU*8zL_4vnZQUw5rt57s{On#18fj>qKZF ztCaG=BBWSPE6viXi!+dOC+(m~fQHwt3z?W*I zoEn7aEkuHwa1wEI3y>q6uu3ARpT~0 zfSf^iCqTo_4yD|1OXA*>Yqg_F`-U#S$XP=nX|)6kO+h$qO8JfVve zFD3iCiLz6c!0O7Cj(;O7lT5eoz4|O;ni%D?^BB$6+Wp#y9qBq1hVT|E$l1ik%Mv|( zkdM>@o6$p?i5JH0w{#*4Hv<0!1jwgTAV<*c7va~}i?NQ!ECh`|^o7|zDY{FUZmePM zY$J-d$j2x3D`hrGh3ugeLqqtyfC)BWKc<{uryQSmQw|s){vDwXkgpQh+MKyqWCGd7 zvTSajqP^{o1A=`fNb%70PpiGa9+Qinf4%!}PcsV+F+s)XeV*WxP*0pl5z+va=t21C zL7YJML_k`BAYlAAPd)4qGeLzEcmO8xI8dx$P_rXq0(&%%r|tgc7#3t$!VB~MocE7k zcfy&s)|%V-1QKx$q6GIW`FCDU=nTRhxS(_rlTVIqqaAXKW&{YGc1s!}Vo}FOk@dBK zavyAY3F<@BodQrH_NLv`1@R8X$l9+iG>KKpo8Klh<;|w!P6VnST}Y!tO2j*5F6GvV zIl>x85%4*-IvL$<*#{G=;){iVof3-mQ80_KgIG@sNbhjabs=SBpry<)d&uSf zI|?o}v%Bw}^Il0--+nuL%$;GZwPFw4AMiH^)SH7jwf?*Zj8wZjZkXTrGhY#wFIYFb zl3J)5x503I75&^V5vr8mf|r(q-FfjP;itFh!huxxU+{Aja_U&nUV@I?SupvA3*?_b zt7N&%9*EW*0pYW9;BFG`rLGDH@Y`~KksPNsQP$Tf#|%F?xWzf&O5|-Hft0CzS+B3} zHnj2-LZ4r;KzIqN3@D zB#g$5$bybWf`1qs7}!y}_6tSs?k63OgF z(ePMEc4B;5BjS-~sc>}Qf+I-7&T3-ksVKJ5bS@y7Be~I#Yy}6_SWEWs^w=rCIwN$j zZ}MbE-q~^wINqGSf&!y!=qnFMWXM7TIe#mdEIL&lCR%DB79R+cVh^CiX4S{rFlD<) z&ulGhROvBCl|=m&SxkM*|4eHXwUH)vt)&y!U{#97Vx%(PRud=TB6XZ5+Rz!3Nl!~V zwP!p-KNH_bRFEFB&(Lx*^GYu$ObOx?LHY^Ud@a^x>KKSwldUnF)HoYMOR?3tZ6C^< z9+@H^;!|S{^yY^%BEUim3h$CZS8v$BjTODrC@ubST>|x|-DC>>gz&e90L7@GomDBe zgS&HLIhpHaGAZo)-P0#Gt!V*Iu1SREJkU&oalmpE0MllsHRkebMs*g;NGgW;y|VG> zN>$EVFPGFMa1CLiPzt0;3OJ?jP6Uc`#7EkeM3fjrV<)IE?U4$Ga`xb?@odm)z**WQ zX#gUd%@C;)<0p+x&&FiaDHxhuM;FG5%FqCkgzN46mmw>*V=UiG(vB1AK{x*gJ`8^b`= zkl`AFSxysUHYT^orG7N|DvnvwU#bozVbWE5+-6#H^>M1WUm$;%$Q}Df*S75!#Eu#w zasq%{=j*r{#FmTD;()m##7Pq*8TZqP7-Yts+#2%ewmTycZ9RRz42-2T&mllJ*pO*^6zB+|y$TQpV}L0q!cZYxn4=2v_7W3 zXyodksO*>6m$sp;X{pF11*-32yoXFjsWZmW@0mxY&_24fluShG49FJ1T3-uCtSS~8 zsG5Jk5Z}i03I5}McI>~9E=CI5eJPP}*|PcVYUG9r6>IY#=_}j$ClBvTq~`%P@hc9B zHU)5A+UG1MRCiY`)+s^PBYPgwhz6v(eT~*TN_=8|WWKKt}U&g@5!#;ZXmrc>j-Ni+>ewD`V3i z-@YTQ)Iab4D&a|S+O`XHNWr=>)##X8qMAIvt-P$P$ZOF(HYnAYY)GKX5HL2|!ct5m z55}ii`eYCMf2{igSe*J4>Scq%ABUYDF`qc^Cp9;`08Vp{x4i@HAt5+Abes2_fCJe( z?BPTy9N-}$Bqa(bT+0Ma6K<)2!MGPfCT*jLNsnmDqrN0GAgHSByh`da8jcF@WC*0q zBtt&cOKn8Xh6+(d70D3tM{K6=7uk7#JC zeaBZsHM$PhT2U4emcc5OlO2pV$!#J9h)U>JFYJKQ)3lRp7qAt6J2T0d^S+93S6mw? z#tnVA*^vlZJT-DH%|n@EQj4C)Ye6f9*-*?$6Su!owwH;pvgT)8oF2u1yH32}BxAWs*z`Mk1u2g}Q?YdqrXMJ7x@-zA+^L`K(01hpSvRYYqg6%6xfA`zA!ZjHn|wYV<8(rN5rCs7KJ(peG_#h9@88*u56CEzbO@LU{j zK(o_QQRH@_HoUPT4<@|AJ&a%?^d&ps1Pl}SghOp;M>oj<>CT!x!_ET!5oPEIv_-tz z;9z1XGqH)SdM3SHY3Q8MENW;r1W!~|BtCxSQcD4T$x_Ph{F4VW5!Qt{^c9xL2R--= zGRs$91;kuSgNW0IElG=C+0J1>YnmYD4aQVL)jNW-+;IrKpfUv z*jUA%)e={KDfS?oyNsq(O1&=FE$WPQ#3PRa&ph}aaE(>B%dK>sg2P*XN~FOYb&Xqo z=Kcp@Piu`48?#`rdFy~xbZQa;1cpKKS!?^*^jR9!41}k0Tk)>iCY^Bioz3VvnHkMW zsWYR<`r=llbPykp;6d=BO{)Fl(2}@!m!FCgOLexy9D}+2ihOb*ep*bNl7w7=&UML9 zdeR2(RCU6*qN#CJWo|*d1qB$6Iu;1(#P|wh@`Vs10rg}eBDOe3bro&9{Y_e2T0I8MPR2p&my$bPC;k2iq|J;`wWi!SR+ooQhIrq{d|5o+m70Z9+ujn5yu^ zO7sF+6UktU2x3jP38|Q?M<7kQ9(Ju$k`UBcM#p{^sEN!hv?A&fCT1CN3kz*Z+>URm z6Jh2YbKDRCPAw^W+>^okyg1wt|CSTH-E#TiKm2bvvikS0{e*Da!(nzyhD_Z4Ubi&~ zEb|z%GxpBl&aIQoVesdYn6JNh*Q^;;=K7Zvpy9Z%GOIteIe6IyOEy z*+h48RLL0elBGFs>@mc*)p!T5*A?$Y|^e5#I0&P(pRLV;g^5{pkGZWzN z`0hZn^IFJd^*im-Ko3WAg9kL-?ko-;P;|tkxP_$~>cwR=4SK(kq~o{lku7|OC4s+K zzHesNKe#o)Z1|2GIN*7~>JnCd8#JWQ#fqsBc5&?aH#waA#MhhV{lMEc=aKJ-D+;)3ZTmf zxkLAN=ic;;Q{rVqad_!&3PBaKkX?%FfZ`r)p$B`occV+TF+@*h2N}~TfD!N-6*joMjG*;ZO`SIp+Z?G|oXFc>+Q5VXQ zO+^h8@%{OYU#=z}kq&R%^aKH48fail&Pb8foCc6w$0UIz*uD<(i+qOXiCpACD2 zOok#=o{sZ3G%1o4W~-m$@B2}-R{z951k-4Xdegninap<5br%#akSFK_X_d$ZN%{;4 zRoq7#n}?i#)E_r2Vtv8wiIHAUVCWv0!5a%-<(lh$A6grx8L=@SSz}LT_ zuOGxQFRCd&!Uu|w;{R+Jj^gH#4!BLZ42krtAbkOEJCz!BUO#>&m#$0D$&|d9a{E_R zZ^a+~QJgs89Do=SL}MGp!1zIq9cBjg@X9~Uo|w#X63F!=;)_^GuV&HQf$u+i^N)3# ztz2o-Z>m%Z8OF(RS+Q(#ioC^b!L&C%j^xr!ez=O2Mi8ZJnuF;I<5Vk(r3}!lb4{@n zVAA=kZwjTq6v>^XDllR>h!Aqiw(?PkdIT=JU2}84x`uY)3-9>Ti8uNA+3@4iTPY?E zf0^Qxgv)D0w6%nK_x>6H7_Ml_OE+50^)QT4Z7c$eKa=hk@^JLKL%({gxp!0oS}kIk zp^xG&tc?-w#LIXm+a+GpP#QkH0=tVy=Qm0E-25k>I-PrDqAbuW%w#emC7QD+~T0rMqQ=4 z%hWaA+{+z3eIl!C_PfV`Z8pra_u$=yKw&f0+B$G}C$dweT6TzFXL%;Q zfS~3IAfZzalEAh?eEQzM7V(cCe6So>krZ1tgcXU7;54sTn`NgNsFo;+61gbK>X&U< zPZ6hPD@}OPi+0n#wa-LW?4qo(e{2P0;D@?`Z(j-y?YM+_2BSjciq*x8pk>62;@SPn z4z&CXVF>j|yy%#CF=)sYg+^$@Iu)U3)BOVmv~>!6r^}!Z~z3z6pz-ja~B5~6fkrCkXn>D6HMbEaUZ_WOG{Zm-w(iy0l` z2W*o8kDn48m=~7W>8$xsSndNS==d^1#W?7-p0GjK|F=wh06m}eUEpa$WepuQx|7Y6 zdpvip9bxmZB1*Ytmj9Whpo2G%xz&&79(JMp&o+qlc`-?k^wz?kqKb5@RJN{F!PML( z%l0egdc$F;b(N6fx?>&N)tAWG)AHMR^vcX(ivmvw>fxvB7_|*Q@60(}g{>bBbxGCfvP!T0{TEdOpf{enQMO|nLeHGHAowDP&vCpv&yaJp! z1HFis1B&w>kx0CvFtm0cwDQB0;gg1*%C8>v<@a>Nw(fr^t&6a2!5vrGVVj(3oWt$V zIFIv&j}>@_G0Mu`FUCAlrgy>AAJ3!YW@6^U3Ih_v{}rpbZ3t_o{PXH=fd01@?|;P0 z|DP@1|M~jx0bg#0~`f0&5$Ckidv$nSRaBCk|GJz2~sn zqHsr9r!DW4d~bVhxBd9UuGffozqePif79vmSdK0QPcj;H<3mEJn~f3(qF~k!#uf!r zF&eeuBL`Q~9byRnd|nxkT?($GH>$!<3RXg&Hy0a>EydRk?wpBD#kUtk2zJ7(pNahp z#-cmS#b?F5_Yt(AKLif;qWg||E3xc(I6T&bQ0W4C*X^??Bq1IX#}Bvj#Sh-Y50WM4 zs=O`jM@9Nl*s~Af2}*z{LCThQQ`y6XpohU#bn69$jeg%9(&jj59*PB(F`I*&Q^Hg4631c zAoJ4RGY_&Q_tM;R4?;!iuDKNq!hNL!dM4vK9We9K*{ktF3-DEW34=AXZ-G6yGY`_i zCD~8y2M_YS*Jt1NAAkebi6i_Tsqys~L$JiDoi#U6JbZ(Egx8c zByr0ebP`U7=v#9u9kc+kBma^@FxgLvj3fUN-0vz)K8y)rOYtGIM;-L7!X^o~kf_fv zmzc(|ov6-{5#{)+Z5)aBEB98^A1PgdL^V}`rl@#QKF=`;C04w+GJ!yGnbJByfO(t# zNFzuZf|<=$qDqRTNTxWo9{nb*Ubsa&Bt^PR)vUKhYOQ!SR8@K{S~sH}_*-8BQHS1` zREP1%<6}M%GtnJ&o8?I4qd#%$rH!2RYz6OYDbeI(GEv32?xB(UrHb6zqsnE8qHv-M z0^4mXu{M(FNF`|F_NI7~Mp2r*@D~4LI1x5tCXv(WNq);y4ch)67Zk|$htJ1$BIqrt zB94-q7+0~E*3}1iknFy;B2Uma{gHkq{ZZ)pm;4y((ZUO>A`c-*F&By8FZZH`3M(yI zGV1?D+dBtW)^**Z9d$ak)v;~cwrx8(ad&Lnwr$%^I<{@+=6Rp@tNZ&^eJ|=(-BbJ2 z-hZC6=UQ`(HRf1jW@yh@fR(Ei7jWAIJgC(OWmBUqZtr8 zH3Vtw{GON#FZ8!AeVi{`<4I1>36!!_O1 zt8gHVCtzbV zcAgyHN)3A6ANt51+k5P8^Cd!?V4-jPPsG+F%-YEw*Cg#t!K-bWUmRG7*6(69U%)$T z{&@YSe$UdEcH}~UY9xxCk{2jCD{ofvErDRs)aO**17rlwriTzydewusl|#Blwut4* zl~jCQDuC}Xa+@fXX!Ixv zFc=yjSC|AV^$o;w$$xfj zpFe>@4I$JYkrM2yZk91lC-rV=xu|4g&|4MWsNric=#f4dZ3Z3K)`Gft;ah6P8bNqf z!8vW?v#j=CgZtF|MLV~5m)9fm%immn#X)dEgG!9>NLqeU& zNBxzh@Aw7b)dLjn+#!gr0cr|ObUYGXx~VZv?q4m@e_5e=oC z4@;wFrm9Q=Nn7lF33`VXWeYZv$@+JuaJ=Ub0ezLS)>0|{8wrj*+PC(9NaB?^l zp`2foNyJa*yjC@njk75~e1vM=Cb9}q_l!la!f5>?&u5y7aMlthdv78RE_QQ_uqs#) z;({5-E8;4TuyQn zUGP;^n_{NwVAi|xW;AivcOZe=u(YRiBi#l|fz!d++cyNw=0!oG?S;7~A!YEZ0o+Nh zCo7NHVhkbphfNCNp+y2ZFviWGUVDcM-iEMYj?Bo}<7%UxR^V`EAO!V<&RSK;QBz}= zBsfk*A4js*bd*2qgUA`$FKi(&EA3HWs4wK#R#Cr1nmMdHq7N^3bc~B6JO~y#q!7 z$|hHmxMpTmAJj`Rx}w&%Y>~UljZ6!fgLaVRJGnXOBvy`+-XPCU)R5OCo=-SlN7CT~ znvHv&!x%K}FQf*d53q>x8WeB5Xom*g9)$2v&qb4%8EO?@BPG)~_f-Q_Fb{-NzER)Bbd4&5Pa#ifp(~a{%0LGM+ zJZL_~1WGeaEZbDOJUd8~avIWVRlNb7`?Qj%izLt!Wmo zR|x#pEspnmZYL+w&K+vn4^Pia2^p?jd-%*C>pSLuycP9`stC$XecU0fML?Qw+71Ds*JR1J&H7H#aOx27(& z@)JrRN#5MOGv{k-y2!(@D1dY|fkQD^jOS1JPTCHWK*wl=Cvt=*O(fH5Rtr`3Ig|`h zn2V_!4zq_B=$Mu)nZ0lR5UujhTOv4_E)G32D=nB3d9nKmx1a9(u>I3?D*Ne&NMe?N zeVhaH{k91l!>E)YcyrphS>fa1_#|kypnm~K{2I$&z_aJGlr?DI}9Zm!LsKcSQW^JKo zZILTrss(-z)!9Q`A6ww&z#wyv(YzB6{oo*v05As~4cN?t>+po{A$BZNzp#h$NJ}Wn z_)*!1d1sb^&wVGCG`(av=YK+FZNb|T9{uDoyd_p>+OHp1c*IyiU;EN~Nv@xK#_#Bo z7_+|q`kkB9BK+xF7Nl+xSMDuZFDp!Yy17f#;1jXq6Cv;nQ?j(Ze}|BHhcK4qgp+ga zj`kW5|1iR(x|KDcGG6hniCnec!Bcbu*>u#@(#qNN*8?N6S7LkyfI3KDr5WZHR~0T~ zNZ;Dzr{%?uVto~|PxJ9OG8MO*=*#QgyFJ73qHm7e zf(#WCTAA~)iVc=prEXG{xZ-7tQ#h6O>nn`Dq_z8cin-}J4<&ue>Bt6bLpeHeb@*0V zkPT?_@)A}Nl7G7k1NI;&l3~An>m&Ggn_uq#j%fXxv-+D?{U7b;-&gpFux-V#~6RsG90YrCJ%sq2t#fYHr}39x?|ATob|`oVDMtV1E_o zu6h-LbHD!T*4Ou6D|MLvyO*K(rIIyv{QH&s{SpfPNit)R+Mg6ki_@-Qn)MY-f{pJ( z5SQ{%iP>`$<;;=)COQn+z#(*A)Kns zZ5tpg*|h{?s)RO2D1TqAY{|3}q5}VN+1w0OWA`2h8QKlyY(s9Hp~DSE?SpK~M}2R3r2jpqxAh9p0NRJyttv4G1pm_C#AW4#_zflV!s2-U+`c=!WQ5 zQocu*=}TE!T3v+9V|{<*3LI7PgLa)-`$QL_um|1_o0d!$eHR+=%wDTEu`}6nD&Z&c z!APW?-<2~D&fyCfdnNdJTaWEgSi<#A#w140q{Lu%v~d}5IO@MOAg%@?36U}Aml=$N z5m3d^<`f({2$#9;&mRYi`7GHSP!?Y$m+)JhZSGd4MnEipAuqiwitdw`*h+4^NH5`I z1a%Tgx``)$G`ro~ckSZ`l&oy`1J>XVN1M89lrW5T8{BtAGDTLsJie}yaE?D_dW;Qr zzg?_KhrY9rS>^={(w7?|N6EM~3)ZCGl=}Qb6lV9@k@w?^Gd}&dobi7!7#7lZ(wDO} zw{iL>&!oUD3(ODi1wv{EaR2GuAOf}5Cs|+pYg(-QN2=Z#n%WfcAvOEMn=Wd9e=puv z6vJdD3Cmz{O^TZv=j(=)iH=TICJ?q^Q*Z@Aqc(gfOZ@0?&Q_1#sXo#vuFDqE&3&I` zZ!u5uC?AQ1LtFHT2nop#Bm}Tqu{2@2C5i(lb46YBndeqEW(s#&%m+>t<~Q4g3q6tx zVfYX>=obzg(b~DObVzL!$~i(dQ+Eo8b6pIi2Om0w?Yk%(#JAs}`*a;xV|x;G;&!4G z;Q``EgZnWuaUoo)4?QUklKy_S->aofz5Pdv)&~G2q*4h7?m6MJ^bde@cAh}&QkUKE zQkUa#8zZX#glqogF*U;jf5*(aO+ddyUW-uYj7G1UUg#6$Q(9lmNDUa8bt2bGw8nm@ zMxez%%JQz12ve+IWqIGPko@bJPyg>{zTID;aHRc5ME(lRKWDvywj>rmGIv~ghPd_xFm+!)vEnV}S%eHIHhdBHFkFSBBXP+YkkQpy1o8~Sz@ zD@o8+Svhy#V)Sz>1)izdt;HRQG=Q#2L?4@8_khqFKV03QTMAG731pz1lWb4=>-SZS zHJ#5m9U_~FMcCFCfdrp3UraRu;$f{<@{FhF{VsqJT%Pz(g&GY5ce(;CIer|;98V{* zwo3XFaV>OmsJK|V{49_5Q8cm#2Rqde2=iA^`>E9$a0n3>ajaFHSt!LDHqIlw8R~x$ zKSW0B(M5leKpTD9cg^zMZTxjwbdi$7%g7rhxr%I(P|!Xup0{Vfw6sCkeKr4OU&Jw0 zhXzJQ(g*0T#bA({vAF(gNQC^`8TuamMF%O|M;VZ};!u z-{$ojz8yksanNa1FxzXp>UC zL;~j|oQCj;?RPc+rgDQN;~1?SV3$=7Y6;IPL*%e3(ia;a)%zpVj*%LWb;~*8ic@{+ zo@>Xfz~{7H;Em)LUcrGdLI;<6{L3?gXImKZ4H1usO*Ii{Qtm{P)%C3=-BiC^AO zlDL5=%BRi|r+9`8vU(o1)qIWkCFRT_8`**Hv$lhKuDr*=>k1rOk<$zAX}h`_o&fDc!KQr ztV4C>Jfn74kyXjP#jkNrEJI#2ayu>L_&R+VZg}pW<6qjPym)eXXyvtvo(LAS^IOA| z9wDD^l091>i(+K;P~C6}qnGqB-R5T5I87JvlV4%}8qgM?>KHa(`K{wii~O&19N&MH z0vEd|;ZVP%F{?Hv9vr^wYJ?La>uQPOf%19=1%a zr*wV1@5+A5yJEYrUpoYJU&9PFVZ*U^?mlG-+QqX|V6%u4GF_c6UxI8$CS|bs@e@~) zAzTWP^2qH75(maV5djCz`~U{<`oe|_b;ro> z?Zqt0_16aqkDIG0M zI}+~yf%O`6P?mmQPzv};@go(jtn`JL%3K_ zCR>hmf#Cg6p%Ja3%;En#^sR`H!1fQ5RUbh@(pav!yJKmSp)_As_bltk96Kzwy0s4H z$iYxE8_-d%m4t)^y*HUM?B2GrkIZ!C7iVU^bPs0m!+s#%sB{M}{E}c=s!m5G`{J<& zzEfWv$cE#pOC-WoN zzWvW_2*H=TKSt;_lvv1*@%kf+HE1Z4&@=D9Ix#KW150EvDtieP>eFO|HyGl@U1yLI zM3v@OX_9}YBdeNAoEen)W=nlSqOf?uqSN4nf%Pryj?l}yaEmInF`pF2ovcF>sXK?pR$QqrH6ZGK^fRfTQ1Qmtei&il#m-Yr>s zkhygo+dEccAo$@AK!-(S??OmYf)09ka(?p)}aVE0FK~@;wkoVA5st zS>UCiZGR>L0$H=B+4`VI=*)kHp_ig>Hojq<7z4e<0zz-+h;n7GMeLw1!LERNQWp89 zCi%#4tRn6T1S>=?)zs8&b}Br~H}F>a0}h+(1DZg@ZudxD%o!G^{y1t$S#N6xZo(H0 zazY!X-x&v{jdC5+Lfr>?JP&MtY>|A=d@@y%kJ`l^S^bgoi>H?)vJD*{dX_1TSSmER zXlM)=Hx_kXqd+xW(Cl4I>^&Tu38dEeQ?AHwjVzj-hrslgJ7-B>*=Bp!_S-*tWZ{!A z^ih4Oeaa#Jf6Gh^e}l0MrBj)|L==Iji;2|8!oot=zK|W&3btau`|DHZkq!9LhP#ek z%tVvcOA&qV_cLO>^g)R|({Hky9;Dw+c&4Poab7k8?a|rl zjq*))GlML_tkK!kz3z@a>^@fUT%+f*m2M{o_Mo@gQ@{rPW+PzR2*XXEr!(5&l1WSM z_lJNoM^dG?F~BsHUK?abVnk<&8431jaF$Y(fIXs=MK;u#kIi#qfbPHnMCw;?cdTOmr#A+wM`K+w8AE+R<<<|YOk$>1S z&0r+w41kNW6R4kQ*fcsq4SZTE)1@zTKN!_{#X%FHoU zX;qkD6oS%`rXv!oDc(>9E#mz`(MC;w|VU1$u-R#UPm0gL)J7F`q}4iqeKxduw9dbI@Gb{10^8 ztEF2JCRx^MX$84pVO-Y;otK)i*g{`oKVGQ_obk~d$(xk14hn2v zOsknsWoM)2Rr+G8Bo@Pu-B4(wV&neDVo`>l78gqXcw$ptN))s4A+vPA+jIwZDQ{uO z&OKr-$LgTb1@_1qsbbq0W=atX2Vgf0$f6^#g|nJR(#DPOlEzK&vK{;eeh(N5{@nOO zrqElclV>U`Oc2h-Bn=@OV7|*F;{)TGL>M{-!Rg+C>|V(v!KR`*dA5XmOE^I#q*np% zp2EPJ_Q1Twx3aCru(eLJFb@&FKL&e;gvquM-P~_16#P|}CK$T@u?HNRJvIvYT9607 z^yUA0LH-XtLjH*`|Mvy???K<7`jft2mYzGGFFQ02izF&IC`aE6fe47i12MFy1A$kyd6V=G>$cMZmMu~IL zT>JL}h4>-LN^lWh*Y`6b`b0nF^=A=%P+g;ibV-0% zxOUZ98&7RCZLAmaWvA#<_n8DzqU`B`^-%)*0zJk7j!84{umkf<62;S!&2m`6)slg8&rI!)694)5Ae~1Aj|^hd}E&t?UWc z#Ne5t58fveXiL8~QLQP=YNL8h)mgj)e<63xb)kH1c&2cTw^YnvIxZ7n>{JJa_h?d&h@>brPZS4(6Q`#PM zQ3lvy^(}!qfW)0zrJEXdbjNq^1qS2JN0PvS#~0ZqgW~9vFC-k(n;?nFN1~G)qL)N?(>!oU(NK$XY6{;#H}z z#Bye2^DvypHpui=3A+afv64}@-!euv-6l7Z&*+0;oejFQnEglsO2d!?r&NKqH{mQd zqiQBYh|q+3CbQx>fIPPn#b3~@k4!f9D8LJWou%WlPU3*P_{DX#JApa5zz z()UXm`Z1hN_C#- zeO(F~nksYTJ;|^Uqd(m2V7~k39X)!BiF9=A%}b_Z?sc&XbPuz6(4qtN zBEMmjU?H%D7gr@#1N{V(vmzfAJo*gZ)Txz8i3t|DBqEN8S{B+qe-EN0R8<}&dBOMs z0YWQwr1&@Bp6vwCTc`mMR!|BV|7cJW?8BXf)O&O=7r;_oces9xgkn$umLp+BYadPg z<2L-5+!PDw1cXxNw1;oE`VenNU7GaRbnl-tLc0gi0_xuJhv&15g0M2OtR?QdR%bn8@#}jxdD!<1^5y#lb@l>Pv(yrVz-r z!w(Y5`9%ZX$2pGkrAY1&heRAZ2yuoQe1sl6oE;ducUB#SX^Ys8cZ^VbGsT$%4Kwod ztH|(+I05fulkqOB%mquhY4V5Y)%p@KQ|m`28IJ`DT}cQyWlBUMg>7|)GmC&U+$I`q zDRc+a#()x2N{Oh`++*ufa|B(O$+^NnnPGSBmr3g?Gy7hN5Xi4zjtb@49~^Eqh{^9O zRGvpILp0=8=sK@sl9`t>W5hUQVG5~`gXJ-fMeOLNIrTP%6oo6r zML)4t;McLD@a?6GZcerD7uq@%W6(*R&}2d!u>(y~J=v~yrcNQaPZX(UTyNPx;%T6G zikiw4iuH+#iMdfk3B}EX)4QU&Jg+i#Y^w}x`~2xxg@p-9?pQuBu_$HChE3;yh6H!W zzB^5LA!>M$tr1xE)Sbf{R>u6tFA;X4N4YE>6NoO^*qZs-!=G!49M{+Dje=-7L#UHP zo?x3YDKdd+JQu%xZHjZq6)8EcL*)7@buxL4b=gzP_?D!ghISj6XAFnM9jh8xELpf$@g3a=~M_qMGsw zjOy^^iI8ydin2ZWiQ*gMTeHwKDFwN!Qu7JH5jK)|>lBY7ia zP5?^$Qk+0eJ*Gc?v_xEL!+I!*uqHDXvRoK_!>oKvID{GiD2{pa!PKJ z3$+=*YKHj|O_pt4xuJb&~C_S;s7j1+4=@^l@K?KlM*et`~1h4&aC>X=8FO3-ZpYprEwZbrUtAgGeEk0 z>>46L-pmP-P_e-X5cTpQ=tqS&tCC=iQ4%NeRz(jkXG7Y6aIObKINTwAuHU2(QSi6} ziU7DNNLE+~uqg=MOtjrA-yd7T@*#Z&-y?%>uVRy{}Gt}U)0OrI4?of5`e9Y;aw!{l6tYlSMm1>h#`qk^rF@Y~NF+V?FN3WJsx^Vq0pRq1~2do_J${Wl!I~SNjS;9CD z6FGOM04!8Yxg8mSc0b7HE{G@U<>@K&&!35lKjI}Lldlu)w;7LGotK;*4|hJMxM0(P zNlKnN1KJc9D%W5rx=PoXV@EhfSp?e)FFcQx}$fo6_v9QVJ@es$XSbT7=oM-MBzYkm&GqWO`M< zPC=m|mPxnVf%2DZgW3X2g>duVeS|!^xCB#EC)`&g}ZUT*ep0{75{}e5@8izf=#K9EpbK z93KBGgr0JH@ay31wz`XZn(xFdyKKJIR0Qc+{CV@WjJ^v75>jCw%e|H3bn{3sR-8`z zkc`J3W@t+fy3H-BH`!ifk{rZx{2*`6ezSDaL?17>I2_K-Q-~xN^3VxWF?oo23H-y+`2X&+sAJ>UlRF}?AAG%w#=A^ zz;LC&DM%#lSz}W+7O1i5}LgW}2DiAU1<>SW)m5Og4P#KBH! zY&sz|biEt>pe;u4NOSd0!QM!%NIJ1>@$9*W!~h=syT4LoQX@wauaj)a8aKuv~c(qUB4uA;ba${r0_bHO-w;tFNO%KF{%Qt{@@*q(oQg!HtEH+#? zBhNvnq=lzauAPF;-5%K5$O|4+Z(I6KCtwNC*hbIjjB%aC|4m(iu z4v0Thf(ft>2TNRXF9Aahihmf8$SdT=MMGH}%+*B@shYS19h2CE zr5g+s)1JARb=yQqWj%Q8+*l8wCZ@$~B&Ss4`SecD@~uxe0N=Sx`aoT<_270P$)Gx^ zmD#XpX$=At0OZvW>}%ZUH{<)-n{(xh$d*pEx`y!Q?1i209A3iKTFzVw&RqKHR$)eL zR7bzAixn<;F{l}Pp3U`YPg=qt$M^WXHp;^`&CE+1^UgMh&bIyMi^P2o>r4u%pRwYy z4y${v@{?4V>8tz{D%VzjhIdWCPRx^b51-)SnlE?xU4c>o*Pch4x4}o6nTTFvez~@8 zYuGfj%WGhol8^kl&}xaeOVLijF6_%2JjGa=qGA6|JWCZp>)h6Zn`t~-7y zjO0}I8c+zP`8>VRPUEeXSp_~2fqqUC26lU!Cb9d zmZD%Nm)^ahTEX4nL-CAXo(lMGvlY7;j6ydZ4$49hLQQAS4x5dW*9>X63L4+pV@ z8o90g#%zy_d5-u&1?YMz5e)b~4?neQ{rjSjuPHK?Q}Zrp#s#q|OW-x#00s%7y-ZKf z5~JRL7;K0Qj@Jx;Qt?BBSXc#zmMQ9KFQb2ROKhu^c&=+9c$ z-oY0)KFNOrI{-3h(0Q2fMi%Uii2AY}_`Y zuMhEAOtb|*NTiwERkD8`<_Y`~+cfpIJ;W<9cJ!5hpa}Ntw7)1blVOv8y~u?hBCMs^ zfDR0YyGD*dR%Fq2e&nH@&d@DDWXL%DxY@TH7Ua+gnZ7uWXj2OMs5x|wgTziMh&U%a zj>8IjX?x2*64Kqd{U^AVkrM!YR(^mSXDR<&S!?T(oxxk^vjQ}vi~2Sc3Q3s)N`FXoZe(#MkS-9&L@Q|i->x<(d=QQ!lpGI;~5vbXSB<~pE_GbiQkFB zlu2moLy%E@+Yk4hn2{f6G%3+HjV&u5W?*+D=O$JBNxh9!FN_kvvZJ(~e#BTHYt_%{ zfCM5^FqnhxIrzMXTt3p$dxZwcx95lCKsOcYx%GjJ{dP$)9PBIK@Rp4p7?6QhY1f9~ z=k$~+j*&@az_<1?S(TRHqkd9z-jNGnf)!EwWl0(UMEt>vdKWLBX7yofiqFn>6L zteVLT4b*BE`s@&Ly#nvC(s?^6+@e6mQcbC`=I>G0lmd23-3aB*EL4-4y{YF1aIo0j zUd)D^Qd|0C$1zaT65{*}_h^!^XN@cK!e`%4ULBJLy#^n@0U;acf03e zO8%ZvyX%_#TwB7xxdh?5SwjhEOQq(_d{jzFl zX32x4{ZuY8dDJ=M24hSrq$@QBnCFhUyP`76b}`K%(%;#JKNk8f9Dh*8h>*e>GDhl= zMmnIbidx4+#5=?c_G_27GRn>%qwmYu{gVYFYB9!EupNh?wC|unow-|gwO4i z@x<}EoxguenAesPOnxCLv7IpxR&ez%u|={KQT)1Z;@`K`Kd~vMeUhrH$R)hl&_ewCI0_i!$~}xWryz;#+2GPTS?&n|J1(7~!tSn5eUY_`M>bwTUG8 z5l#aJl2H-YW_mR&WEyVp+E3LO0W6-wR>Gt?Ot$%*F6roOP}(9||8Xs0Ph;nkT||3zG}PJ$0) zpHtSS_ySleYX6=>b%5mGhM6v1sqUv=H7l@xdqVxc+tVqUyBq5pSQ-CsSyf5f5lI={ z8&`2rpy>ldcnGVi zqnJ?+od&(?o%-WjRr%B(lV1!O3?z(~Ze5#)?U$L4RX%v!-|51zzSCenO?UhL76y_0 zPJ_{Gu!RKDaFrsco%hSsVWkfw;Gu`Hp zfq?!KP};5ECig1fO^oA4>Vlb8TXcY=sQA-Z6*3DkQoDp}w=T!G(y?UD-m3vsg7*Ye zKM7y-{G@v%?jukUwv`)WbTv~ZDYv40S1c+kNc4>0#|+v=4bxjfa~vU0hhvh7(QhcK+=K*>LkFsIpGJcv4r$u> ztp=M}Sa&g2Lc!9B2WT8Lk*IKN2IGA6QSBq+jvDOSMaa&xZTPexcU4U=M!}Mj{@(YG z35vt$h|CQVl$s#6$t15}$zQZMs@FVO?`@PA&&bZ6d--+oq4Q9gCf7hZG=-Oh zkKn|U;ZE^kpnx<4*rZW)i#8vu& zF7cIY39Yl6^$CuGSq4%ez@Mx*7z-jqaECUhU7a*0t#1G^@h#2Gc4NHV@j?6bu#WPZ z`_*rMN5lgnbi@PVWJD?m3XwijD_GI0JUy; zATI`se)%s)ANepdVxl!o2(U*=wlIC5BIJBJ5pWFz_#Js?wLDuO~i z2vQU-KYXw$1GyeYwwx_DY{e_!NJ;<#66EAA0vIjC#u%^;!d2<7CA!=#ZLWeXuW*L= zAk947LG;$X3PFfU2hFG=oJ!J`^HOq6#`$plmPpJd=rNahAbM!a6zC=ojEC7w#}(f~ zi?B)#Gs~2ETvzwpdI!nv(c;218hXEgar>pl12+3dGzZ1CRMpp5@%25VMiUP4u}spG zL23p=t_us3(X9<p%cLP4X$9+ASUI6#rLMUFXBy%LSTg|sGb9J4w5lgse)#$lH1HFd$Rkb z;#NTd57^f9^++*N8(p1!dvhbz!<;-+OaAmtt1H}z&*4)HwZ9{!7I~bTs4@=ksw_s{ z?zXB`VY)UvVRs-|-bm$rQoZjgjR{j5u&HsiyqMrDE$&>n$I?5+D~v&d+gwy-#4pd3 zAP3H}Fu5wCOSs!$tVjl93XV0-s;jcHNSMU_7-iJ;t-mD!#mKBtUff4ESE=K2)S(K79W;i3TkXE89x9pbVpNFU{nzhj(6ZuddmE|@p zrZ8*0rp}(%AcdLOpK}{wbnlgp!)M}7!!yg#aOGNfh4#aiRRwEuV-!0Zbf+;YPgzsD zJMD*GxmMR-Zratjec_aA+J_R>X%r@&=RoG0NZx78(>yQ=pNvE8r*xnQp|MaIExy0b z0lM54w@||+E`@e(FwPD6W|q&>i&c_vwa6DS$R<8HUG8Uw7tyx5k|e*mSQDrG|@u5A97_UOEN@Vo}dy!w#5gdw`aC!582FBva|ymml7JA!Wk zvRAAXK+5c@YFSwW}NXI+?vpeTe1 zZsq5$zqoCM0;iy@FB~-eZ*kE7haCD(#ZHCN-?k^P*6LHu*s1n)3{MSAbl_EO_?!rVdO=Q799;@=e$V@PCxS4T zg3bg@##UvBEXYwvm;1B85ECP#kJQ=d%iV{H<|w(ZI?_!FUSJpL`CAxJCy`VXZ9)OQ z_E@?5tUI;#W^r?FVYW_#)RdatK%%j#L*)6GtG9}qx7m(j6?>;C7wQEhr6HASfp%i0 zQ(eWrnmZv&0DhyVVFkrWZHTM-Q?HtHW38LA;ydp`y-(ML8cP@oF)G^>FL6nHf}vt2 z_6~A>u!6J+#Cct!_4BR&a?JN1+v$pl{%p4g&%F;}xrUUBHzw~$^wo9~2_3mAJ@=&;SQc8VBs|vIxsEVU=r$m_uGZ9Ca+f3+N1x8!^Hukk2 zT@~F>PT?eVQrg>&JK<1rl&PrEzx}-r_L{q|4wQtyq@UzJlp<6?rak3whV~4GD}jKk zxmCg(432L4PI0+19b={l0;M;?NEyx52#f_N*4{}oEH7}wGx?JwbuJ)V=!zh1;({RQ zEwaRtb*pP+rOJLp?rw*N2FE2mS#f^!5Gcm%sMc3gFY@7e#25~4Sqp%C35C5QHC z1NNpY*bf^?iO)X~p$O$}&JlW!LZKek?|f~6mWJ2glHXB3z0Y~k-OoX=8JM~0v1{b# z(cV9ro{WzTf<}JHc3%H2YWNQpe*X(<_c>;cuPi8lN;fU&n?iRLC>QBhgSAYw zE3BcnMpKte=L*k-mJ_#RADVH2ASf3nhvngI5;P$v`{i!^=>UQHFg*YixU@e^lO3Q; zY*dqNZ8Rs!kEZuG3xW(RO?{}HA)mj01p!xcgrI;B#3dO&YYDw`D=Jsh_UGM{tak5DX>X7yh0wVv$`#EYRmMA%&< zMBF}7Voy}tq_66ZNbe!LCs0=6m9VEoFTxt>HZ-0~VjnvZu_xGN?3MD_fgNj*2a#ul zYx)okgzjO3?Y1>y=3YY)n`c_z(v+erS z?7wMP0F_|P&L>v%_p$%GS5cMP$|UL|Gi$W7cZPrP@}#}Jqq)rdM2K;tIh~tY z6T567eR^_m4}DR7M5JN9*hk?P6idKQW$r{7L)0*U6)0#CehBd8w+Ing05}SX6De8L zvd&4+#!x}e9l!^!9AERxm!T@p0ky@@rse?7l2h-4Cy(m@JNxpnhl$nm<5xBdh*}df z8#4{|IMiN#nc+e64VaHxfAq+5&aEZJZ-$XuDdKfjz&NK!739eB7*+WUJ@=l6^Y49T z8KuneHePxkqxITq`>NE#_cNF+!O%8k6s)oPQRdfK!VV;CF#G3HYf<{^QejFu?T-X7 zPX>zn6~2i{`7A8YhsnlCIcvp4gh66-slG6diSNd|;sEA&2cvX-z=j}7+Gn2x!cXC<4JiGL^aFV5h=67K|gTvCTR$)m4K%!22R4!DBl!bUMFHjT| z1+SN0d;^bQiPRsVTL%Cy zj`knTs>2BYElxz{P>m_pbGn>CQsbOz&YtZkS;%#yrKTmBDih=y21pM}&J!S>#2)A- zocP($mPVL_S^65akp&ZzDGhszR9&4D0%J~^zICKO{EoNI21qqKM#!5P3wFKx>unvV zfNzSvs%Ga>obSiYJG5I@9KL5C*0DYRW~p~n80dG(kWSNK;S$~QA&;1B>8?5y@C za=eB7nFoHJQC%>==bF)cII5r5IE8Z!!F9mPU!v;p)z)~R$a}N?LS!&{K+l^K;CR2~ z?(<(T$A6`wpzI`_-FeLH;lHL=EZljnLn2{LRNNztl|k~Cu}*w4ja8l>12Os0CA4%+%$Z(c2~S2@p#?= zisKmV(@a3r?%^K4Vi>okPu0A<#}#>msFKo~Oc~^N9|V4m9qfEC-C&(U>}RF7r0$3l z7cTV2VrSskFoS|a>VV;w-YTm*NqA5%DC;K26h{ zA0BzwCwhhDHa%UA38VLwz(Cf8h5e{x@mvmb@!PR7*>>kdiNZbv-lnOSby?K z*>Ic0HE&+LbeP)ZC;Z!HO(Y%GTzhujTq5`D#|HQBMDSf*5l^Dh-@$I=70?ix8D=e} ztI!HJRxmBlA~h^KG|jY0psQS1_s!4Izf4J0s2d`XtGL101CM-2B?uE#@=G>q1)U?E zR)^cfOUmhNWJ)y&lB0H{eCxiEdAe1aL>{KFtRQ2Dt@f#E<#d_HkLqILh3|0uHF!ar zOZ9s{0{Z%G$4~@(%N__iHGU%ds^IWeYHGFo#aA3dv48x8%ceG?MsfpQuTrQczP+{1}p&5Im7`gQ%Ue;+4v9dVRBtXF9-B3-wnR{L3Hf7RtJ} zd?jj`Y*~94Ct_Ed1==GO29Du3t`RJ@iFAe$DBHBAYus3Isb^BCYgFqka3ZbTD=o<` z^O2sk@<7<>HmC9!YRzgzk~nSRa!qSR>S#s0J4-!OQN4JQ?)_?JMcAc2vn5+qJa?z7=MJa(oB|k6j_wbfJr3J!2HY5@(~Ly~T&%Xwz-PSdRv6!?LW)B*7A!WHZdr zOALc}Y%jm{?cjjVHm!M9dDYfurQggdx1R!!zW*uqKWOgkDzZM3Z&%ISKQ^`4{<*33 z|Et6PrQ-Y-b@9LSn@kloSB*u4FOl`y>gr5*OT@sW7+t?TP-1Dc7&AlzQ1ctay&csV z;N`nUPk*Y`XKhkvg(mo?M&exfr8*Gt<%Uqheg4y=xrS=56AhlOYOiYvyf;}62V(Zy zBGtuyZYc%1%7-2yO=@bY2=6)gnMCXcxnltv@w~6Sj^bf2dQu5>7iJoyc7j3 zq9dZC)G$@_TEiq0kkeJ<;x~e!`lz0KAxQcAGGr8I}AwJOy^HFe?VN zffR=KYd~S4Bq29wZ*qF%d__QT7jL~HAU#EP+BvlQ3^=rho*h5ngPlBm1UUW#csPBa zZ_nK#<^Bnah|0#V+&}KiLVOAAp#_!R$Hy_Dt0D{*!*S!xF;HJh>1}rM45^4xn|)90 z5wUg57=-5F9z?+L?(656(&Hb_-bMU~rM81>hlm|Xy3%7bUsJYUpsz%jcg`nY7ZnMH zSq>S(c&kTpp0gyaFk1XM#7Ah3ZJ*D&KJ-$O=(x7WS$EqPn~;hV?i>-Jis6uLWtb6L z!8OFOE5zYZr#$p{(cNNdS)J+_DM?}FzJGD%6YK(yNpPEIpN5imdoduZ-T^JVXE!VV zK`jdtTLsPh9t3++P~oO!X!M%~Q>I0kW6g?Pf31Oko<^;^JmYTbBKOINAe$nH1+zI) zKv>UZJt@^9t13~<$(XT<{j_QP&3}9)qPV^asdKjGnQm6~!#SOtk+CB~;$Ctk6Z|W> zbX=`~3x!l&`O$O3)nPg5QMcDqzox#Tx8)#DK~#)=_z4=Z&U*npnen9BGN>@I)ABCC zeLqX56v{+vM;Vme(abQGzPg*-K6VbJ(1HLBS^j!pCC2RgbsJ)AVyL%BwKtAerNWUc zbfxM3R(=eFEa4u?53{LjMCAgWTV*g}XGM7WBohf^G#{|$rX~jAXdEns>Tt-mVZQ-H z$kppvGNTGn?raiwTG8LQXwa6g)-==3fH8k1i4|qQ0n!#&vrCXp(4eGE7f`MoBXFU| znyrE_{0^8lshkP2t_vu=bcsCZdUL>fgD+;rF`t1yyCk*?93v5yPs`>ttguQf=ue~@rFvFr8IU^Luz zKR2N`cFUh71J{@9rw;`#&TH~j69}r5cyS|Q(Wc#K*7j$Jdg6$tdj4XL@JxBH)N@IY zrPg%zW9<{_aV#EfHHJf75LZFvM{&^VI3UtNOSzyY0Y5GgjICqvcTmjJm7f5r6dYsM zl-C#c*g3V3V5lBP?VwOJjHLlnFmbP%zUxZCq4FGn9AD*PxstZq*4~>FD#_k%Bo+|# ze3joDl4rC~y#pIct~avL30Q=t)gX>_p}=XflDy42KWf&6U14LDS{^f2-P|Q)p8JW7 zePnaJCsvMKkBqaKiWX?Da?-GS7sEj|*Y+r(L<=s}~RUi4<6GktedcHYW`fA3-rRXEA%Yu@e~@m320*|448ezyV2GQ#Q!skLC3O z;#B+VF~HxXmIm80lP?&q7G7a@2H^bK8!H#Oq*f6Jisky}X}|oUwt|2LGF5~rx=6L; zkgAFGcxD9)HghPE-7*qX-C+fFe^m8x99U;m&qLxK;QTU!341i-Joa0Ty%=d_g47;e z$q{d9{<9?xR}dP9505M2(-GNap0MUb?#~wXATn1_@u?klKIshwS7`hLvNU~WzR3+a zS9tfV!%KvA56=num(cJno_j3+1ESLGxS|B9DRn1*`iaw;w9O2xd%XJzbz9_C5s-WE zRj!L!fOMS1^{k$IHf|o=P2RKpleaX!H0hvNnQXai^~-6iK-j#|kMWr&b-@-y<& zzS_`_Xe`&LQYl=Vp7<@o)*Frf)K|bg$MFFY5YBLC2=?E9>lS_!U6y0tv%fWP|6~IB zpDT6$-}mxA%0=dXDRo87R^z~l;RI;k>O{K|s_gzx!F(%Gb4=#E$c_}r_1ucpE0%T* zh@pY({c=~aNTROu^uIlSciL|!nzVal!{Z+^*iF6-rt^$kpC6z7B0nfwigx1s#-UJA z(4mr$D+F!4Jiad8#$|N$S-S~TAp_`1CS4H$gkpkpX@bbbaUr`6VQP}1jO3FMP&oG# z_NuaWC?*(8)EZ@w0xiZ)>qtjQwqE&H_TwdX*;t?qSkmK_VM;+YNz{xH7J-(hyQRZ6j5I_VWRAE zCtMH3T!>brGw5b;qXaodmsJWI$Rru3yt{}66~=dA_m7E@ry2zfa&P@Uxu2#8ZM$K8 z!bBO?7sbiM7I!Ncs;sl+ny)tt)RVVIl+w^jam2CO`ivA+ z9j~FgKZc_d!ZpQ*#ebyI=&2u>3TYeckll&-WLy!Lj7V52dP6_blI^iYhte>KsI>~i z^|0i}(i3eFE)MNr0WR?Hl~3AIb71h_)bY(#{l5NkP+~Puy#KpfH^d`+t@*9HN&lnn zM)p6d_x|7hoS7}M5b~GyQ;H!Ydq@BXJVJyaBP3NG0lw=12%Y#3e_>!($+~{yK4X@P z34K|)+rFRISl384Qi*CIQ0j$&Ng|1^if$I)ImG23ySKyn1JBMZ;OX!JC>o7AF5PaQ zZ;#75(;Y5!dG3zdK00lY&3BTa4B7G!83L2sGuyNa}u<_Ya{rZ)v9%2gX0d@*&{@}3mTIoURkg^t~9cMRN z@THO#Bx;JQK5-P6eNL2Thz&|xJmqp%kT%}(FpT&=-*Iz`T(5`zw^ z<$G=^6xuznATl+1+<`Cwce;adH3$rQ#v1KbDHf3}NMQqyrX`e^4i_`_Lu)O$%kV?> zCc#~Na6(R$i0VsgdJXKBSu-}$Y{pCrJLq*`u4>GFh#I z4d11LP+0baJB%Os-tfv4^NNgCB=d|Ss1p%Bh!ZP=en1wPFU}!K9PQ^Hm!No-V zzEtF*xs!04!dzrD7i6QlW?g*x&VO5)6EvZuW#1sk8tmPzLv@?NGuPQ2kfM}lJky$O zPrX~So;QY>Mz_0z(5J;6tyQDp6CYB)`7vRfmBRLpmXdUuAvhwTaD2x%a%jhMi`_

r|o%%L7N=mId@vl`tU9Dv*-RIvy zft1g`(nc7LlbGuXe8R<%484a24>?sbt6vL~oF%N2zM|tXM<;s0-OLcV{v9h7O}642 zW@@jIkC0qr(3A-Mb_x&$9+B?PF}`NCE3Q2gS;i@`&ZI`8PSnRKdc~WO_)xZ&pO&rp zMJs_$wE=^Ql$ULt3nxce=4*|gi2MFZk{)^{$@Q@@Hf!TfQ*A7mhbI{dO{rh@2vCgG z#g=RHtO=~VSoDz=fAVILc!{KQZ%irFh|y9Pf*V5e1bB`y%Z~Sm4rj*I^y7*A%8LI zNDufDasG8M8@Os0!SOk6Y#B`_HxEvSPR4h-O;$E>%gIm8f3X# zDf~8sqSrZoTm4k-c%(DnDI$1zK~H&s-24ID!r)$h=w4woZ-8$;SW8$}59%9Y^UQKf zd{=M&19evJ^$n+2wDucN`-#X!VYV$owMuYC9FN=!ttzxOC@2*0-(NbtEnb@Z@8Fid z0?Q3Q0x`P0RDT_l2)lCP-o(Z%jF^2hkknjTVa(#oi!OLy%WuX{@j3;|%N{QL(gx(z zQS4}0Lr<+~Nka+2mFPodFdi6@-vX6xDJl0@6K1bF-g#F1CC(rC6;kN;mWn$gAZcMG zpTlFnj5ng7=c?vgm!3x$D>Dk&TNHUgG7f!d$H$Y_g#lV|2pkedp7sYb#HqRA><=JK zmi=x&bIpD^o;qOU7Bg@|Tl{iVKJ$BR9QBN35Kyr-jr72hPq@WRd3^K~`rH_5ojgKn zOIeR3H?#VH`&auEu`~3_`@1L``^Rv||Hek9s`hUOimKZ8(1@9do}-zKwV;{3k-@)i z{_~|P{8w!z2mb}zc`;WdJ0{dxN@h;GGp1!KBo1UHuQAUOFgD*rnUTs)dVjyXjQ4}&R#Z@Spe4i%K@NeEKv}2) zG6e-55gzr1w?_a-;?g!hI~<4xtQCDve+3jlMaxjjj<3&%rb-NAhXu`r2n1gO{a8OO z{5>U}E?Nx|x`hVcPc8^Io2M&Z5m`+o!Y^auvc!#YK==N28KaN;ud$~@qLRWm4{hmM zlexNmucG5?pmu}!o$wR+>1?DWf2k?x;9S^Hn6W$v1DPnT3lC&gljJ1X%vZ$qg0-TG zc;SrO+G&Gwf`*DZ5?W0sCiyeqwSb2r9J0rJ%4{pU~kem5;fCX3i!3~Thu*ads4 z_^^UHz>}$+gpnSw$gLHQ_m@`7{*(jpi1%DTPO% za57ELcIQ5uLsg_+5~g?1ZAL%Qn8Lvo>Sr!gW=@`aaYs6P`;5cjI<++TOA)!Vf~5I$ zcahrOKq;u{j0nTS@Is14YGxsZmlb$eo+lgO$LVPhtUU~EHoA|A4;+m8?~u+2tOI6Y z%Bt7nvfg)$&0zTL`LJDFF%uldP`utsgFhNx%ZEdV#_wQq1}x9SZUsLVP}p?pL;IJ=4wtVKWUbgHyF{W}$1yto7HO2$EvqX2^Y4m~ zITlfO?z3$E&Ylq+}2mgW+ksM4%o3+HSaD(9Dl4rx!(b(gz6&i7ji38;qjKtJ*7sEpLlq z1r;=ttBZ~Rs*=m_vS`~^FBTMU?y4JSvBARNf^EHV)KqR{wYfm$H8pZp67Xl~Jbs#*`j8c)E=^FY(yk%*gNN_H_j{Qw|7SJ$#>a~9Q) z6O`2m?Y8sgdWdR{PDiD!$XKS346m~`qTZI?Y(`z|;P$(p7JV;=`|>RHl+UZlk=}7K zt;zm=scTf{HEJebk%%BGFKSM0%J^iBcbvY&!chZ*Z#+#Y_i0o25S?QQsg*|PFtcBl z_4HGH*pX3&xoX$tzD>;LV%k2gJSLLXmb7p>BzRkLJ%GNSI+!St;B1_}7+s#^_sg-W zuIVQXu~fW?6Qi}seL^o+cg$|R_aI8U5sKo42G}V18KJrfN+lEN0?ekd?lZdQGsi5y ze!25_PbO9wWQX4|L|a< zX?!=UZ{Tkkg?0~w*EXO{>NtS8`TXSrON7Yxmwt2WF@GR=pmz?I#<>j{xu21=B#bI*j`?OYZRa!adTzjX_zoTx{RwO0<8BRrzmh693!gD`pPJ4wg8a0XSJ+$4W{qKi~5>9D-p`;TYb_0`n( zZz4T)Q;E&~VwUuWE@l_iq=wrAirLm|e)Y-?F&1vDU1Ee1LsgPpWJK{;i}H{;hJ~Rf z>ApLLOnj}faB~Ef;Rf0MDZ`iOkQ9S;((N#VyJ3gIP`hD=#*i|`b?mJ+#&!Jd9}K*h zTRseL;(Y-I+?ZQE47jnEkcePIPAY@+h|46E3JVt$ORw4?SSZe(n?Rho9qS+uj4Okd z?A*xQ%-nuhwTWcV?KOO?E5jBEAj*x2nNlAZZN(l~5p-?i7wZ0N6h!ZEVAz#vA1F9_ z&b}MA{&;{4eMjF7X1@jikG$a!C@2^MmI2$?HEkCo==hs$yI|m}y!X{L@4PqrF$5vdHN9HihzAV6he5VT8!`WvEfP}35rWU zJ<4-Wx6;NqW=3evp4!Im^j%WGaZQJV+LjyDHSmPeEq_)^h#p>E7}`EM3N4@5phW65 z19suwA)EYQcHIG`Yd+;JI7)TjzG6pO@+V-DLc4#w>TuV|RN?k`;~ljB5x|<0rw<*a zV#iZPu@yq7*b!>hZP=2!iyEYXVQtWoxeJ@1bn$&O&s442%V&$y^9$2bE!*4w$j$2K zN69u>Y@?SNM0>&N41oo4m>m%Jl>ng;AfriZsoT;xf_Xh_3heBv+>$M*z(2TUWU{(n z3>;4a?b{M{RX1YiN2RxUzIaG*a~2v)0{MxMcSt;!gc%Ov;=DJ387))uOrUIY&*T>B z%1=<+i)Bfr(c)B2yHg422E1F@D@%B5>gBowB37_s=9t~uxYZUyIDw9l5#jxDkGZ7%ln{OyA zsf$ZBGB@ZXe!zQf$TJF+p!AEB%8C)uxw_y|S=?wD#5$9R#`=Ze)wwlORUa$O zjP#~9e*h=kXViGbyZ|-yrJ2L%?(ETT1nu(PSE^a#79#QfCmROqO$;AjThI(eWOwxE z)y#mWUS_73au$J1Sum*{gnI2fW)L~ESY_`SxVH>pmqVC4stU+wf<=e7m)sa|T!)N3 zHO8-fq$FYfUYu`U;NDTtkznP8fD~-xf!$#cvd$5ye`xCOnCR8&zTU(8_bQ3F-#m@L z`(a?EIhK~%c;EC#LgO-pDMjm(;)AD1U*z&u>&HrU%~DMvuW?Zxy@ZTE5aD0@gBG2> z?lz)|ij`!&)5u|eNo9({T?=)N?5vUCA=k+Li&A{Dobmt=+|tAyNr1$rn|e;!54<}oPA?Hu72T?52Y zy{_q#l%SKVwZ|{(D6B6RyMla3=dcN!g?O%$URVIK@!ZJ*uS+`0y$MS`dKm`?H;c*2a`x3W(Vaq zN$i)8e>glHW$`C^FdJ?)vkd-8ZrGb^Q zTNAjzg@Ro&(J)k+tSnm77+Oi>^TrT?PR=p`)@%ev{y>|htFmQGj(~cEG1)Hseob^W z>|4lL*)C*~MNRGFVppd&>bT)lPt8?%nr^(c`bS<-J-XZw!LkD9+u4f3#pPpHO>~~D z4E+)3qzc}u@U7^kdMCcXp;eY`V#%O$RE2B`tdsgRw2JG8)8rp@sxx;mgn{M!`KbPE z)VIEHtaJhoQF5IW?gMpL5Svc)p-ruIkCUZf`tGGC+_pg3x?q9rBSzfS0?F&-AMDM` zw9tIo5Do|XhYTYgouY4pL`S%Cd8k4BSzK>M_>7^LQD&)*voOOSGv~$8DR>bcI=aEl+Gy!p z?;N6bsPMB!7GWaYg{ADWBEDq79lzOkM3dF%^JlF znrlhOz5a6>HDO!55%)c@kbr_fB8O{B939dxyERJQoECm*{nidH?ZagI!v`j+f7llF z*Hlg{B#8ja-$|pw>1%rHdTgaDp6JF56JgUiDXE`yV!Rm=Y(N(QHvS;jve#Uq z!O!^M+&;iBILN)hbdZ1G?so|Hs`@0hq@AlR{c+00!`6GG zyjdIgd`fELb~A)z){0scjYO z9s3F)tdln&muKeXm#ESjk!Tow$LB!zH_|r1Cfm_nt{C3ru>?VKb8)70Q!{OURyNok zs|TR240fKwXZcaZc|d4_=YCk{t_~%g*f3`@JX;GapCA-XnE8V>k1yePMJ#ZQ8eQ+! zAuXHHc!U~T_`?gNTrO3l;ne;-6DMipGq89d*yGS*^;UpZ51d3?w+wYkK0opTBY z8}L_@^b4#5`SU$J4s%~D8>YyvDkl)>K3j%AsA_0n3-0hfNd_WKV`<`X3?*Wj>Y7FMjC3we1)WVhoad-Yc_| ze*4T6QkXu6`f>=$jlIq^KhD|2e~EUUvD|3U2j{tPqCv8PkMwztM{!i4bE+Bw%-w2y zz+jkEr~RRD8~Ux2IZLsI9D7xt3!EY3mF-pHOSi$K(k6+M?LXehyPR973LzIoWd*Mq z`4Y2G>qySc@H+>%Vo^~MS0RrP>ECMA=G&V^w&yL6q}jFw7gP$_9@QpEFcx4@CqQ)z z$7$M}@0q4-h44i6cV>{KuTKus1RBsDY-wCdxiZGJo@mINn)}(SnC>SWO*pPyaW5fe zX=>V-(-}K)j#{-a6xoh>KuOye8Udpx#%AWM2c~63rm2Xho}r-XdWvYK*5mthy;joK zKAnr!VoaAiPDU2aN6i+n)D~nP?CQ>}M$Xc#Oiy%XntjdOphzJKp)_3yiq?(3#YiUxbh36g8lV&$8 z4l*|!YQ+Ss_07K;`co^Crn0IJu`UKTkS?HbU|Z8Z;U!N4%1fmw)w7CDSQ>nV$w-D`y@%-Az+b5j%SlN|d%NlYV^Nz|M9Rg*`TjLs+wYvKFb zs00GB>q3<}{3^%s^8x4fjTkaTVjyY9`AUcIV$$0GHi4wtCmmN$r#v>Vd^- zrec_HI;GQjh9yqv0QV=kMlx12%@_0UUH5=bS9{B6-2SQvtfCmbU|k9fBM=R&i`4yy zV65mn@%zkIw}cBwKMyQMM(c=qsU<_wmAvScoN`qO;vyp#@@25aZT45 z;gZJP(=NHayJ?KolvaO>TaR?jEHm^zp>X@>p3}3Z109bk+Yc^v)3v7q5|1T25Pb4G zN$TFnb;Oevm&HXt{Z-47^)KY_iEM-7R|!u=`C5swp5cPnmlj1I8BwGgF*8(d>dJnT zg2f`; zwC5%R=5`HLA1k%R4fVLO=lYz_wQAFTdlHG~G~y5()$dz@akZD&L(UI>BRscYYXtcp zL&AF1b{y*i7@WdK%Rr61tfb@g=y<>DCGu?142kT9NR7Jq496y7@Hq+{AMn1Twp7Jd zLK_)O<=R3H0R~*Og^i9tGb*fb4$ov-Kjy(z`DP{eB-AD`7`QwGLWyI3zaaW+6rG1s zWw8-c8P)-$(-8EFc)z@fg2W15MA7Ll4tu_EMg$;zn z;ga@#dj6y>`le&uOP0^86I>xS_b(ulcItTRAwGk(y5`OI*$kCF7*j>cM4b9iQ_?i( zTRe!~`o37yq)-n`?#+>Z3qbsn1_2bLBAzVm}Z?Ipx#8RLZRr$uB6QMm}!9DzbE4Ac_wkDUs4xK3F_05OYT6CSz?us6NaPx8%gpH z6^66SOztd=Cu*a4tg$DPf~(1M`1SEPbG-S*3cn4V>rNO&9YgXAi*^#omJ}-r1YEE) zd`RVf<3b6g!>Fm&^7aQ36rq0o8xF^~5(Yhl_~QpT)j!#C82;JT@V|7j|J}e^sA}Q( zFY@oy=tRcBQ5*>K*p581pR_h?E}Y>Wr7^s}SP#g2M8lbseLO(gc&?Q-rlBd3+q6;U zEvHNNR?MQZuuqa7B(aGsXDMs}JZur~vbw5j5$|&`aPxgil0l3_pf0WPZqw`O^@;oa zqJFydd7_pP92Q75R0cUqc_sgbGEj$-GyeuF&;;dA`AtUOHS!b1hxT_yuNTxi3L=zP zpj==xiZsQC(k@P*3(A&)tIlqMhu0p`W43`ej~WPTmu3Ke1LH;>-yTWOI>yz)PM;N~ zoH~;$ygnUzA11Q3vFZGXWjq*6C8i^j85v)F5JSbXEi4P&g9RJfPXMZaWiIwPQ${qI zfMh@D3qgM}dK-p2x@3?xOgLRZZ+PS&8LtR^*vzP{1$`I-tuXnO?g_;Z{{y`x&5*vQ zub%8M?G1B~6=2)AC3yE8z+?PE-aqZg>8lrX&2TYyOZ2B||2yK?0I=?a-NWh>VGtaJ zc0-K=ev5CaGj3Q6S$XShguHkF)^ETe*9-)1t?RXSfb*it!Z%%vdTTK#==?XqBGCq7E-YMo@W;xr5<{5q-` zEK+h{vf8^%zl&Yh*ElyB_0-{L{L_|{rblg@)N9Wg?sh{>?-iYB z`pC?Md8jx6FsFMNH<&c(eh&)|k92q*?F(av9ZpMRN}^02hjkdp+z*2-A2FjJ+||n~ zjYz0uEBRl34*e?b^!kHqAD;;IwQ7zAI1Um3R}HB~lh^n(m!wV`Bdf9mzZI;cm7>b8u9&jTnwKhE2GOyiHmnOj zXHpO8w$;-y{s6U_L52yh7l@?s4Qs_ta{M^XEbcLKpahH!drpn4_DL8;?>pG@+cejc zq-p~kbV649Cd8^rkV+;6SoezbUa=t7L#&1-UBApQ`blPk`<1`QNKE6kRWc%{j0^@C z!6;9m^Q~cros5qS?Hx8dtSE|Xx;$UQWMfKYNllcwqWe{QctoBG{%$_xd4v+@HEE{u5A&L$Nq zBe7#k!wjy9!X#!UKgd>y!wqhr8nig@LlqXvqqsRL3857m)fiJvfNJEVt|*=z z^&8w#ggrL!9y%v9Ikn*L520ZJ26l5Yhj{SG)Q+fbB&Jv-Y_Og{c)H}5NNYh4}g58WczBXz3D z5H^+uk`xSV4q%1i^kJx`K<`%heQRW9( zC@3Bm<=P$1yj2uW3gaSwLMD>2M(q@|GL)%`D6UAMA$<%WRT-M^Q=HeRaYQfbmfAq*f?LHRM|DFAh08a zI`mSdx*jIJ<69UFu2H|r3+0JOKOj8$ zhl3qAvE}Cu_Z~a86~00VKe*46ze0;-AZHo?!e~kp*vZuwEydm2h~6)2iA< znLP4rSm>$qc1Z5l_`zG1h&RUKrXF-4a_9U?kDJe~e&b2e#7B-y(SjVnpW3G%NC3)u zL!LBw;y-_{L#0BNISW^CnH0~fUL&oir@jut20rvNU<0k!pNQJY5Dpjo?@0U`<*-{z z_8PIOPbLjcd#2IqC(pl{YD5v?^ON5VHM{SE;r|SBqx-)q7XH&vOH}yJoV~Hfs`DnW zz8sK^=74iJ&CVfc9-Nh=Ii`)S0ABH>?2@I+=oRXP|E-+Y!{!UtfCOFKNPBmm4nfu` zDlxiwrr}g7<9+7+Bs=Nx`*ij852_vIgTb$_uCQ{7s!}?oiP97mJFcc?)@Fv$?XK|c zS6^FVguxKxVrDY7Lj0hHAhsap61IE;;C%TA2|GR!SVj(GJE38z2zomF%4XPMbXANyBDh5G@Rfc}iq8Mtf!}N`Y)_FQ;>vHq)Ccv) z;9lhVPaS#>y-WDLbgo?QxuUg+hh7|DBnjqq`-&YF0nbv8kfY5uUC~3WVYn8ggw{<0 z4O)(&_guU*C(55akx?Bchw72Q$$fluXniVl=jbg)XK-74b90lwOhjQJ}04cw1P z<9ceIUbA^fhx`+0nJ^DeCi??Dr$GwbHTlrDBhppfrms%EdRETV6Aq zan`7>yqIo;2=5;LYxt~d^1uRR*eFe`Bo68Y!1drz&63sRsg0p8(rkWELSf*MKCay%KFzBIZ zmrjvXt{+IDT&AB$VXh=s9JW}dnjhw_v{4n-SY|3a$f3kkmM4aCu2jp1f~7QD5r(RC zp&}Gb;jV-rI|!tNttcdm;#CGwN>CB@M`@!nEQBJjETmMQ7bW=OF?f-5TeD*^z25ow z=T5iS$Z#-*ry*k4Ej?KG^bV1~4C4zS>D^7UwB(=xfO~2O4nxyE55oJ3C@z}eg$qoE z&NZ%=94uS^rWn9Iyu;+rV{oGa$kL-5*dg%mHon33mjHD2?UVz$hIVYwJu`caz*I8G zdh?|vO=QP(NpOvC#K4X-$d1iG{aal#dhveK!+H1agiBNPK$4=~IpSv--++EkmWNKW z?e^i(y?~Q$yu={kavlnz)R*-UO1s{wfq7pKAacfqkFt&LjJJ{v+_#eT>oB}<`ZEH) zqIy~Fw?^ z(^W;fMw=P%w~T|MyA^mzB#GK51%w>lBoc0!UPnG*Bi^htCRG7$bSxm$NgHP&Y#9o3CrHBkr7S zdrY~qBACI&4ROS9YEN}HGIAa;OMu%rSXx}ZFO~j^a9=IA5-wQ}nHfE^NvzQQWhiTl zh)sOHQyH^}2OGd<_)0Inwr5!wTQ6-W_M7kLb?UFr_Cj&YcO8{PriY5LD;K`RhAX|J z=uL{FWiB&eCuO7ZsT9k@PH=1M>w)=4Wk`wiYAPyM=l~;8Rn%q<2|Ew@GDi<8M2N?f z^aR&thOP97E6u`WRZ5Re&mfVwchsPXuS~3xm6Fa-m!0n2 zO77$PE4*x5U=0Cp;Q9wj0@o5LUYf-*O>Sh;A}#A3p~JiNhOKQ3QUyi`hHZ;_3&!1E z6||sBn-52^6_^I`35sgzVBY=?R-qsfvJ)4?Qm9U9_2?cfTbr)+?IKE-t%>_*w=d4( zrA$~1D&N6f_*w$8@~xy^G)EP%0l>BHKsEwG=Digwcu|TcC}J!qTJB`XQA&=OD7n76 zHR`%z0)r)a$%9E5K~YIhoj3~x>i%gUW7)i~7AbZm1dl}{ezkMxS1ceT3gi*;&A98O z;NYfN2F%02Q;#BT5r3YX5=bUB*3_MC%r>`n@>MdD;FWxaa&RLt8%S8>3^;v95LBJ_ zDLA&>3%Y6#YHO)^ESIHFpohWX9M$i{@1aTGz@2Z0jpMdM<8ZFBS>Ku)(K|f3(NF($nFoz zQN9LyyM$~HV{DS7t~RQU>rA`W5-2IsWecsaq)~kVbH3HA)5qEjMx@X~6*{P z9q7?U4b>b@lGLf>!EBgi$h@(-QxghDY`6re<{W4lNrG1@u!E#a4EYuVQ=M8IX`-q< zp}n*>SKLZZQ|lJ{a5BJL#YU5MZ}oQ>poZ)kL_(@4N5boO4#S*Ps0HJLbvYyI$R!I_ zpzC^$qXMeJYtAlFel?GC!llG!fZekXE>ZRfu7A-hh=P_lG-m#YWu-eF8tGz29oqeV z{*bMXH=E$7WFcLYI0a8A-Fe^7hcvy&^hjPAn~b`^Gclqx2vcyqy+VKXVoXjNXNO-4 z^bB_zX@wvbG*a=U>OJ*}0>b;qyQV#eBl1nc00y&x6KgnZMk*X<&^Cikq9T>(rnEz8 z7{SpXpfP2UUtftuykh6>h9bS!=7^km@zvnvR zAr*<T#u?i zrOG83Cj5mO$=Av3=8gbYC|mv^Voj72NKopk?3k;uD@N+LsMW&1H_ zPQ-nav#UgyCIhA$sSbJ4Xb7lJYeG%API+=g3Wr;?UEyZuqMFIIAo^`*z1??zl9l?* zCQl~^tJNFJ$D85+!w%l70|5__Ba*<6a025B@c{8OP;XU+x5HFp!mk=b4BS9`Cq*1J zvt|DMAPYm;Kp4ohI}CG&j}cW!1_<&IF9A9vg^fwwoR8APrm&gWBvbfyEulGF=tD95 zpw^Afbf%5VgfH-5Bf*^#Z%;4R{EgrfSaj0DjsJ5)6eS)=Q2=WR%5#MDPas=ReZ?=0 z9alZ9o^8h>+23>da%!{2Et{-Ct>D$^1Ef41jtJcAKAZWhH62z9$`lUC^K(=cN+t-{ zcyT*-SCcw{=Gl{CFIG8|p7dKlK!09=ErQ}H^1B0pCwps`_c4Q_Deh)_`T2}8bAz_H z_GYil?3Q%JtIyF>EImPVSG9_2-;uDbJHdD{lGij8YIqY9%Xal@IdlfK(t!K4L=0sFN0D!O3`f)Bnf5fSaa(dw^-2ya24P zE+$2ev_Q1)?h0~Nxi3yGz}mQ>Ts5zK~VoFBz?PCAgIijLW|J zH_Ciah&8?iM+Dh&I<6bjaAc3V7pcTih4nI@Vh5lEjr#BqlvkW^dP9HTk%SV#J6TL2 z{acGMeOL%}dP4XV5Xb)WX1`Y}i4q+cDcobCMBbrzRf;6tnhm6}q)`RRinYTwyl-N^LVd1Js043jBiD-!qjmq8;JER7VWG2`6N5WTtpVQb$8%^T5jf zCw<-h)F~p%ux+MzP4ir~syj^!l)r;H>qjh#f~9!uz3N?Vmo-ZhR_KX4=lDV=;_VWs z+QN_y@T9VoG##bgfi7!%FIxj@ex;l?@AIRq``!K9hv;Z}u;dM!~>a(&?t_fV%%etiG9pc*pQa=`BU7CyJIa=JHqKB^2Y1N znkkJK&bk76Y5q~J&TvjtQj{m6HIC}=072@as%Yxf1<;Y49NP*_fR7(TCb>l%IS{W_ z-~;@8ZlY}cW{3gv0}#$h^>ggD-ByI}k9+~I9-Y~?aIW!>!&j1Fj{sv{$r?Gb3D-mv z#J5hE9TzPe`j~jx4m{~sV@{_U#eFl%q|EU2eKV)Pj4n(2`VP@J6_1MtZU5PQw7{la z*wx&VxEfnXM*ew}Q3TbG@#K?z2hZyEGfJ8plvT^OdQNqQXQH(ap;d&752k#zDACuL z-!@g3O=~z?t|aoRAdybbJSfjB88sT>8#mUlE4Gh_d~(b?AC`Bh3X_vF!n3ss&jYVcDZnW{@2g4vvd9 zkpfbq3f3q@=@!3b%Lnx_(e!|jk#g>esDsPmWAy3KSQ9AaNv^J&l1sMOL#gY*!OIAm z6<+UsXCpaqcUtp227?`iux}kb#}qQU`L=IGWkQClk0zDClt5Wqtxzlw$rPRN2j4Z3 zW|)#_nXV0Eaf@PJj;`ZWhnd$z*xb(jXypFMBwGmG#z5|s;BDl0MD-}vIEIMUOugeafi+b&mCcw!iDCr}skKcnk_jiPF!fYk8OaFuwUBls zxKhAt$1w_}Wd%WW+O?9+z++}FmKbTT9W=H~^KXvIeiaj)9Nt}5WPIJ|T1#9gt4D+d z#K0G2iY!N~W@u>KLUndM|y8@kiME7Oce9Hj(WQ*xix z0npl-z_ZTyr;R|pK}Q0VPMwnBknD6fovON1k`C|#idV^JJQd3J0+-;d#{kNzRG^&ACXVznU(f%x|NUE>$XAq=?-4-w9V`VThBdf@y$2E-bIi^fX5u(`?lb+ed5f=tD_yH z3pJy)>aYjVzwNLQYL2&)IlGc2OBvURGTQl)NoHpfFv<6YinGVJqiyT zIn5kKxlhhKPYV|{T0`8691Q|N49IN)F7T^@SjR6K2-H2L&!GyY~va9?;kFe2p3Wdo}bw4A1?&e*Yb- z^}nywXoP0rwmx5N;l;a zh5SGr)ljiVS63<1*X=L4^CTGO(p9bwlSK7wD(UHKrJ~U`f+UTrg$)cdb_wzAnf2O~ zrFUF+D#QS!b+=h+wFXSNeP?ZIPMkn>5mDqqo-8r@n#~LQ@r)!lHf%zHn3r_qhMcx} zV8WOP3w%>y1{`BH`BY`|{5YAuA1)0SaOnUgQg9J>6`OkIWa@tvp^5~{i#h6~ZPQY^Ry4((TheFaqlsdo zUZ@Az)H{_tFI%m$Obz*(*%p=ENvJTuMB`ZkR-)>VC5vn1UTTQmpFwBgaYILcL3dLl zKUx$XF{_+aDDkdHvahYkt9>&f%%6Zkmn@QYLvO<^w29J?zERU0ONX6wn)e-gK~f$a zXYoK(9ne8E7FQL_D>4jzQOOU)j_$UF4T=!beE5C?IKd6TV#msavAvUvpIr z(QpxtwbV?iEzec*-P-n=Nf_O_q?xIxMR+M(HCupU+f8Q}^WvyKP2JWKGYv?uyh8x$ zC|dC}>sh;f3YPrO>I!V`vGn{ti%JAny=?zlW4>!si_;~0I3k~XZB=q6f(lk(?otm9 z1`~@5_f!b|Ue@gc%V}HU!0*PHs$5l4y|f5pvm;vZ*@S7XY~F6nb9j*j@MYu-o<6?? z&rm^Hr%=LkGgy4059DUXH6m^)JnU>5KN?&ek{z7LYZKUMuL&e9;9qg8WE+IkoR!lngz))M z3?;Fc+<+GpdYs(&0GmDyQg4YoY>^Sl^Y5^^e(6C{19(Hxzk(_MJgWX_{6it1U#G`- zg+d->*V4Uox^IYNlxqCZ6dX1zAM)qkLNh-PQPM$yAMd^kdReFKyfx}IS*%_~`ic?W zTZGa}YzS+{`6P<#ek&U2WODe#tyT{AW+(C|dQp_%34PcLwa~^Owsj8P3!%V!${8Fg z55_%)vv|ylWzGj6=22qCtaw*Yu!FQUa`YTD45GM`_~a7m$Cakp_P;tc!E;sIj9M=8FY7C5I6k(L% z`iuan%fj_+T;?%0X60)GFDPWe-C%azlqVuS|Hgq@>hIvw6zOMUUvcK#{F`H`^k4Id zpjDx(m?+FCqge@poPi@T9}n&y&gZ9vI7%3iA&l^_g*>oZbs>U#ys!pqgJ3c*P5u`6 zwM_>`c*=ahC|+wlLD66tW+^li^SW2bJX@`F8mw)rv9zsCHGMIk&ik0jE3x)f9EI(g5Yl>rl%)gS{hxVO z(74dVu=x%tqV2t{MAvHccD|LbE`xvP;8>3_Umc^S=Ed8AeFr2stWN7?|85H z(1)_5p(S^`#rayM5~{fh3=s&}Nj=Tr>bx`J_$Nu>G}Cp2+T_rfZ>;6P#Z)%sRj^jS zw=X0mi9f6NEo=)Z$8I@D0oA$l3~u*DW|}*(5sR3GUpeKUk68FD<;-pSFZE0+ABSuV zYn(r1`v!*nW?^7!2ZiDTFE;mSXC-8zU$RSOxQM8B)1fE|Kr3Nfj!Ujv_V`g>H{8e z$P#cnd>2)XTLjKROrbmQX;8b&!_pw8HX)^tn$pwrI0@y%+rLiKq}H)-QeQ2aq%Y+D zd(`s$PZ-hv6Se#l|Doh^n>~Tn*02vvaWTyQ; z0se5ZzcIe{<6Qli{Hi!i7ArK3MOMaYM!YjH44&`RSZY!`$=pC0d+qG~H>cSIr{hFw zDzoqV`=0AJWR1P1vDke(&W`=29{b-$NxR^KvQdU7sGjj&A20j#<@y|^*-#<0Bry#! zeTQgDPcuTy9SjWmThuT(e}0&EBZ7Ean~Qe(ce815{M>~V`yPSKVX(^$yPCpg_g$Fn z2HcdvG}jLi+tJQy3|phi9(!{)AQFiT1L>GBd0XFu!dHC_J<2WXw<=}@XKgn65fpo` zoxbM;dUuJV_i+V{CDNnKFUytN-x*0#M+zo}(J+j3OnEaEmQ5;L$;@|}T%9zy#cd9x zaU0<(b!kW)%J;&!oE_*xL-zaOMbBLFW3reu(xj;U*K}=$qADf>Zm05>aTh3U%Hh3Z zp0PH0EbY=3jfVh#WEE=N)Eu=Pe~lY#uJpIcJe_P&?XxkJ+@ZP5-`*nN@_#E6YCiR)a_u%rk8SiNt$Rl;Kc+S!NvTHW?gW9L;W=5^qyanEHCs z;scShlKP`^aG^z%$Z|ssWfS*)X5@2G+L1?7k@^abE8iP4j@#})7YoW6sRY*y7Qn10 zcMh!CqbY}7K=x&zXl`1$)bDaiQV^ZV*!aGuoXDc+o$>-;B(2Wwy0E^r6(Z7_;?N=j zU!qgAN*{~ksLQ4|A@zv;ZLuBy^YKfIB}R-Emqsu^lncrTaVJ zgkai}|#=te%haOlVrA%1m*2T)2Rax+fED{U8IA1IWt4Mz&Yrxm$DRzn9cpOfG#Y zHkVl%R(yF3DKwM%tC0ST=^~gl;LIqMTsQSTvd1_YVv@Jq(^M4h(t;9ZLZvMyr6y1V z!^=ozg+tIBPX>gZo=it?3cnHg_!^+PAfJK}?0 z{Hdlm*o_zpbN4?+t{(p3S~0~&J?2%?4aKa(Ep@uLqd>eZO)yKM9_C~W3a)Xs1v*pK zPl##489K+xq$axkFv8TR75<96mb$w(!TzITKokBY#B=8X)a?LH)@rMwy^p)1hGpD? zeo{Dp8N^t6AH-M+KgM&A%zu^Vf!u}~qZ?P72bk8r3PXjWUHk!IW95txTw@}kUmOl9L3SJwJU=b??E(Wav%5S$5r0AU4PnNnL7I))%!2=G_QT2iQA53+7T zxX6Fp5SU+p;C?ya*ezmyhu9mps0XWOK1pYe+KsT~dvWDZg1nTl>o4iIFT*X1>pmTtXVhI`Fwi~n8KCt8Df#bK^0r^ixRnsL$Y{FL7QlWD2!oAEN$F!mMrtRc+b)8V?yl2JQH<%8 zM6Ts9Ac}4Za|eUru-Sp0NNWmLm(>>L7dFY`ov0$8$xKOLJl0I5l-EqoI~}a47@|x` zuVK=qIo6zc2)5;XKm;%h%l~pmM1~=u_`SS@Iau@lZm(&nsWS@2jg37qS&*;QBUeyp zGC=NfOT~Su)x6|Kud~f9mC43dVIM$<5>}}i#r^Cg7bio26ir>+9y_?yt|ajm(xW|b z-L5fFlaKyOOLri#LuSfKWF>wkk&g4J>vEcsk-WZHCl={K4B(K%LSvce{0%ATFj*Oo z29fH0FeHTFA{>&ac++Hr2U71Mo0X~sFXV`vOEtT~4b`7Zx>VfjuCbA>G) z1RxyE1Lkcp=_)#)=L^l2`{Uz{!HGZHbd?YAJ34}2_&jgIyBZ0rX6Evi$+*9!R+hq~3g+m2Ho`ji{Tkj3Dg}PRM zYeYrIclG?M!i0kdhqH$Hk?)D^dYC8d8-b@9!6!uM(w8a#+EaKcTx8Ts#*ok-X1d6# zE(W)bQD&$+N|%aVqBhzsc;l0BQ)pOiOpNy=A;eV zxDhj2X?Z`u8m7cA(+iHna${$)c>RKUSxyPRiy1jOrFK+KyFtiKlg;`5(s4y-5v7LR z4T?0z=a6s<&7A9n%uZLU!60cJk;{AfJkSAEnw~JRk|wp;SY(rcJ}R^aJ-pNXn&A)j z4`6GRnrxPQIxkh2NaxE0u^)-V?xtQeZo=0~&7%rGp$1 z#v(8N#K@i4L+@CDP?GcvHVA0+iAu>ru6)ewp3+nTU#gde@6q(|0+g# zg<;UlYq>Upu;{JQ@-IQi{oQ@jA7zaelw=m?a`fTgW2z1PdjxHMtZvE5K! zw;fp|V}>j-zzSPt$liK~+2W@@mf|BrOXgC)xDbbw?5dS$7 z8n(EO(u)3wf#bA;-bu&aD9At`8}?CbE+Pt^SSzr-VQNxX3^p~spCK>3TflRt8uqIg zZ5*$9dql#oi=1Dp?N!30`gBCcxQJ3gvS38AsUC^pN5%Bs-`-y)3}K0O4W*H+r%nv7 zh&U3_WF%?rSpY#b2S_r7Z~#Ev4WxuHrFvAQ&51#L&AcO5Xym-1PKMln?phkt$FKv! z#x$0azKzeND#Ff{qni(!)ZFY1nrG4_!pBgl!o|?Ei@(qYW7te_AmY9vFgFF?if5@x zp#?bPyGr2pEYsi{#+?}ldw0z-vWb6!XZe$`#rB}puuSey8dNIq@a*DL#G!sD?L0lx zh@vF>{HqvM>7x$*s~C;@M;^faKVh%`FVOzY0{YcYzXCQ2dXynx?j%#06G{(WTI~0MB!_TpM z1R;jo`3(Ow>~XOU3K^eQZ%JHimWg@r{wR!qB)1YM#=2}E2<7*d)g z$Uc+g7wL}zL5W?+nK*5VVbQpix>?2`YNsWQaw7~&r#;eT|9Y;0yb6M04koT}jY6ZsyBe6}qov4F=QW~! zt?ArdHti7x;%bUseG)ViSB-eJm6hW{aVs+(@BDcB7ilJH3{5I;uu_h=3+hPt6`M$p z-7Pro!}yl^9J=Rcp_ai$ol)03-gfiSoK*}{awc;436A{k09m$d5i;WPoVk(cJx}Ci zLT>BU=d~iU!w~CaV5f2+kDRS1-If^o72Ou!HT$<|n(OqlotX0#I#C}(q4(T{pmrfH zt(cEAcf`O1Kv)&Z|$sN^+ogJ zP_bcOlB2Ylwq+seUfsa*Nau*zzzr>HG-~Oo=)s4j*{1>ccH*<)hTeEr>ux_m=DswOWAGm`0E+F_5ln9XT+d4*vdFQn_ z@;na{xt-%%FYq~xeHy9Nlw$C)nKOcbIWkJK4;j4_Gorw$H%{EJspFv2dX!v9Cqb+y zL`maVA^~ZFG&<Kt>1|DwO-?5LXG626V&t)BP*G{RV9~*_C&N|<2YiUfGeU3_1K}1EPKAl-u`93En4$n1UWxHQr3OOqI@m4O@%LBAcb?Ij- z-msPjMOBJ;7AGe)gZW*F0krZohY?C-O2U&Z&VUye2lkP%wE(uwfEt(HYvP;;Jg!4u zh@`kU!L%%ib1ZLe1EV_z?eIZ#)s=9DPbdoPB7${}&6XioXz~nHOGF*<5wW_1c|cu_ zIzKR9%o$I_lfXm!E-@?W0N2mT9yZjT#5v~h@7?Auc)w@3j^W7)r?`S^J);C*aR#*G znVI{>7?{DBiNz5}_ko!;4eI6wB^Zp0IYYK7%ZLuN0h3+eV@t`iomkcI43^LUOvWZe zrXBzTk=Wc6623tLBAYOPp;xRArBdEk%`%4N31z}fUX=Q<3Ts@Xae92mBLjfVh`wqM zN0Y}Ginj+DW>ABj|Jn`L0w2-+^(N7QcZshZQWFeXk(EJ98m66>Bg;+bhtnPe&B)$CnX zPEl#Jruc;o9Vh0F^o1$j&|TfSUA~e@2s^?~{Lv>6hG)LA?bqpX{DJ+qZw*(07zfe% z5&YrnZ(qZ%(YxP#f$6Wvulanj@NdnoIDOIdt`DzheenjLemw>;fwxbXDqo8EA?g}Mil&ZlbTl&Bv|6mCE=d<+YrsQ1}L9tpJAbOg+Y z-^nv%RL{-2EADs+A3^N3LTz&&uWmLGp`p_)>P3(HYueSaea`>ox9-4V?x*%8yd1;+ zla~4)y2}P%o@b8qe>tE1|GLXD<8nO$D8Z8g`F?(oA2vGmFw9|Ekzujsh7u$(P5SH! z)vy*Trd)}xj@uwl3InUvv7liv=Y|u!jfbtx%$N9;w%_RNP7Eje35DlxAz*nY@#*@1 zZ5f(8Nfa$zM#*x0D_g;3>QaIyUeRhh{M!OtF#;LnhztA|EQ zRhd-6#`}qgD&C?XH~^tp)Vu&EncAG7Q?t z;LF}9EuLi2zfBo2^;S;}K{GsJbBZ(RTKi`)=9)rUPVW>Ibt{ta?=x#8(u86~cY3Ap zq6nvqJ&{SwmItiZP~i^_t&uK-#PZ^@ycIpsuz3s&DvFMl-l}M>XSQbOw7phyuUDNL zZxx^!qq#CX{lOC`O*K!uGQ4h5K(^8F1o>Z_Sjdo-n*XbNT>3>Z{=L@yALzw@t&gFj zlY@bg)Bn9r!Ad%|NMDS&m%T~f`c&O=en;HEQU|OQK1EEZzM5@eDygsIJHrm!sZDLG z`A%;12O4sDY|7IX{MGWGZCi#+9STqu#`tE}i)Pm^ahsdp$M+R3E64#!S`sC$DYj1v ziGBBSRDCH*`zVCRNFuC^AfvM z-Z=q3Gj{R7K^PC(yg*#fwT0#<%-#S!F#|Smfzg?Qq~^hDce(IVoXg;n4PH@_{16N^ z*2ulg;D+Z|h_pMgpe;elIX!rIwI~~J6r^~B5ga%jQtIKKFoN#ki4aRR{<|}N?>N>s z+&agIg(ox6cg%Nc7T!f+spyB81^!(T_*7z3P&zPoDj<`SH9@S>p=~<3UA$VZ0tjuG zImo7+7xX+nxJELeDk0BwmiHMRlUzYLy_`J>GGXW~p#Bn(BuaZ3TEN^fJn|g8g)|3y zUQ`eXly@e2YTgFPJu;E#*jpgitwn%G`UBd;hiE&`1BdsCj?yLKa7gs;&wrVkZh45H z(|tj*^B*rY{D;Qj-?03z7R>*SN+yy2)i|`2|GQT6u2K*H>TeA29?^^l0yR?7V*KhG zLT?tHTXUN(k=80-+onQd@jWf4Jh8uF{#~d2)imT~cD&dea*d`EW_lQK9UMg$fB{0Uemd=;>!MY>F9RAj8$}FAHohWM4@xU~}= z_?lv`Fi_WJMW^RWyD6c5q4k&=>&ZJ0o%FL5Sh@3}En%d#4P$iQ6?CN8BVC)RWFAJs zc}SztG7l~!^l~9$Ok3T zb4@qa4W@*W$*2$`SigEL5VfRQLyy}m=-Sz|EMoz&G#-WfiAwQ4X^o)4rzcxB@Em$; z;(wMpcO(pdG06s!#Jh3e^rI|lhO32jE@}=*!in;RCdRn*#BvidqK5OTtIRJ@qFtCw zp`)=~cUSF~qisN|LzLDt+Ug?acLQTX3M*MZvx^Dy?`ze`&wZ>7H4#QUX3+g0dC>VF zBry0fK7-Q0u5LJCYZdxPk9Nl?bz|K^Gcwz}N+EV^zd|rfxPKtwGrIKPM$4(j^dZaS z4jh5+#&8FxTLpKHEM8jFXpPUKNVr0fuRiaTfNG+lD zQSo2~1!y4noW&u)=YaDH&KZUTtqX!q({5WpO-dhqCn9OISR&p|B{-?l>G>e&S;7|e#cv?5u9R}7vFwKG!}=V8_#G1wxgm3cOXv?0 zo4b)CaS}VtVwk;_9eEOpa+`h=uLvv@GqIIH{2$jf{E3@32?^$?O0Sg+J40T_mUxYy z+fQz5GOEyt!sAWFu_Q>b+00tZlqPo7N{Y1pQT8}jChG$A$=fEowFN^wy42%drh{6||3u{VzW2DEVXf2bm{;lL*E+xYJoOR~R;0h>-Gt-)OJS zlv?a(H+RE8ne>;c#s-M#$`-272}dh+2An$xuC*j_gtr(g7vxK@+!yYo9%Q(SU+({| z0S1SGI-~#{_=alh)e*Y&4m;TCSH#v`$wS{EF4Ff+M?QgVej#M0?EB2bZiErHd<{C8 z&AKeBqM#YulF6H~Rv;Bokq0y@trQzhd!QZItL7UK_F_A8r4OdrW4!I73Y+OTp}FZ9 z1~JW=HOVl}VtLnx{hJF509N}OYeBT@{9xu<9J!4~)Vf-;yzFQPg38&v-i>J4OuN2D z`<<#jBz*_j9WaK6Tyh1rQ$Cy)%kYod4G~6O*Pl0yyf$_eA8Q!dr-FB}d`zOh6SMI$ zgs8pl5(0G}@1KAxr#J-XsCY!Y$n>;(?02m4VyBNTIij66J->S6T}EP1Fc{g^N>0r6 zV0>7C$ypK3B9po99a28%GnsL@BI7#}7Wl7$YU;?JVuzw4m>q&Tg_lHJ>f2avRvkQ@ zz%Fo+hf{e8lAi+eBP%0P1gNxz-iY#jsA+XWk_2mIED&`1!fk+awU&yUYU&kjN1$kG zC$YZh^%2sbfeE8qfnP$Jxwo|8N`1ZR3hI4E_Ov+g@zy%9?<{r9UXh@(Tq$$BNn9bU zqElZTH`ChQIaQ*(4h+G))D8YppJy5zWv6P$MBt z6$!!ona|nvY@OP(zb+eLdcos&iA+89LR@7>xT>e6g^RTgPpok>A8t5KPORH*c6xzT z0h~d=Ktw@EK}2t0E$88Aola#KFWQZhNQB!n_>@d^a}#^YrW&jYdbZ&e^bX>@ zm_8$k?B#u4#NeN36Zt$IP6_W*m!VrjE9eaeK7+`h-*YcAM9(c3iOHlsGhgvb4y@&4 z8ww!!)-b0hDnuG; zadwrYc@7|-`mJ*3iCI3N&O1c)m$WsN@#w-#=rF5@S*cu1njp@{CS3NBWjxRJX|?$` zP&4@>P)hmoLta^=08*@Y#Uo=5S!*Z%iW-{NaXQzvK z^R93l-6S`@-w2=4*nEk)LP$@~Wg>HGe~Y@U#!WtdafX0@R|*+CUVxpci# z#Xr?#1v6-Nvpb&I*X(#Y!oL>0=8msRAV~^$y8i9`z-ji!`&rKP^XAcY6J#lrUR9=q zqry zO)yeT3W*9Y;ie#r$@X*3+5F0&7Mve1sY*u}3~wGmq%}yK#e6AGa1akl2TSNi1Jy<9 zXig!r9La-)rguRKv?>=V(X9xHHB|DbLWH(Ka*5QSF$(mB6erG3V~|3@SH+E}B z5*IUtODlb#@sdZ!?BxckL6P7E=$yr8?HCk#E`ccX`4R?*My`S@~g8~5V@0A z1Q6~Yi6@lk(I|Vlz^{CradDi(M}Wgv8(lI%5;VPywG`(fvm{G57Uu# zjNKJ$M@z|AtjIePG5~C=M7yi`nnaUIWs0(yHZ$h2!*{Kwq_xRY2p$|21@tId9-LYx zVaa0vKhCdV9iS-2<8t~ot%=hf9a3+KsY&i?@-=2F5!h9k2u=W};S%f!+OPzdMYEj9 z62Oj#*L374t8P=`J9dKs^8#2HCbC7Yj;^{yo#~exv+> zt4`C=hEVXBi{gBqtD_ljJa55n64$CuUGY;-Tolrbk!ep@pOwA#o|KBQ)vDoh7?iqO zY=bTReyaEAz=t@fzqRRzQ)9gL?}e&tf;o$P9QC|4px7}xyrF4D|BXZ`OcygHj;L)4 zg%;F0+5)f&X$~(A|#0%@aUh*hpZ3 zrV8OrI^fje`&k7?r8ppaa**%E36k*;UfiZ%FoXvE{KswOhAiqh4J|n!V}D5iPk}E1 zd#8?{EQ8NTYQvbTm2Bn$3JlfsgFLfS@it?f5{H@5EVspP1cv>9k2ONOrMe)Y#r}eI zA@Pmx`Ui@SxQ)WTF6s~6H(4bG=iR`aM{*0f6dVvqrXxR5gPycIP`!~~twg+k3QXXn zN#a1fL^ANta;OClJr3q1f26h(Ym6r4MwH89s_i;PR5LTSEjxUeQ41`~<9dSbFqmO4 z{ieXNOf#!)d1k6>;``;iX}Hg>Ld79gmLo|p5~;NuRHyuklv%*(?uA?LpxO$n*VgQe z)+j&u2gVKHO1RI-(6>Cwk;Yx9z4i0^y>Fd%&pY%gKtcMMRAl4|`EA5Ww*%S)+?l!P zali0mBOp=Lk=nmwf#zZ;hw~(NiXd1(wY`$h4$)PNx+F()HQLlnmdx?rD2; zr=qlIf(R%7G5d+;;v%2jtA!V51%-_zopP;kXm!V%StGW8#Z3?GQAF7K#~OCIO*#Dh ztyeBiJD^#(lrE|Q)kVe*GO*PL6R?r!Z%;TXFUa#gwmpR zF%uIxkq`V+r^x;>3riK3G?+WZVj6L|^wJdl{w1J;u$eB!h1pG>z{FrtKGC)=hD099 z5gs`3G%Xu~xC4vH7=JU$NTrJXqtRAG!%yy>q@^3W#t)#sv^47ajV{|S_K^$oPg>f4 z=r8{t0W2i{E6YgI#?4P|SREjK!Chc2cjX97Tc1PIG?l+2yVJc3 z0E9aoT~?H@ch7dI{o`6K<4$$O=+v3!JaUA8^X)IVuqXfrh;w)v6z#YW#EX1o@Ok5w zTxSw5!$7i{IV)TaIr1hHNAoy4f>_rFmsd$mQ*k5D2)LXeE$B{`7m9qzMPZd#7(ny%f0GI#I~CMlA@JyN!2dUl7I}@w2Xd(AM39=E^{` zLemwWF78^pTUp--J1MM_FL-ca0>AcSrgeBQVHxLW{+SkLnksBUm(pzNPCSYVDd+3& z5%{TV=bGw1{_0=S$SX9wikW>@FIL5K$z6tMRmmu{k4@;WHK)2X2Pbuu6Am(G@s%%B z9VCqB9OQ1rIPgF{)>9{5I)aYAk zG3_VVUm&w;(zty25^OjAQ5mEAXX@~Ofb4Hn{r&;vg))!%*?Gn|Z0vx5w5E!HAe1C4 z1d2LN<^V3i040GS!*LcP6X!o}v$PJH*8nDZUBpgxT~;pCPNm`))`(WFX$en@SFTxJ zAEFsuLQ(VHk!nyYorJXYIO@Ccdf;ul@%S0_xN+0tFOCPnAetxTCe{Okq?>RR7qlti z_M^v^w2f%n70HKw8yV^|_Nq8&lEjN{8wTn#@hU&4lEmvg;{z_jcLMVO*}^W%-vF#v z3X@WUrWfF7d_reXWTw$SH8eF=mDW9ppbyC`g29Esg*jo?ZG42_p-qM>uIy33opl8yhx9&{)OBj=SvX z+jE_n8<@+AQ?W5<57@bL0Ss_^qh}a#MlmLgo`8BukB9bc=vV-e&>nUmz1Fae%vNS! z36`~QJ3sEIpHT5ssvzL0-Qc1r-SApb-_kZefYd3Thx4HkpZrlA0tx zPYCQ(PY^9AZ}D26hEMFh;;{I;Twt$uwE?zY!J6+);@v=JN(lXIqJ9fBpciT)(5}{Z z_6CD;q8xVdL>W!Wh)6zE`nNJ=3{_J48D@sg@oG82cLNJm1?-mD5|Yvq_sMmyfw6YO zLOo3WZ@rNxp+_Ha!GgR9#pPM{9oZ4o^kur`E+wQstW!!#tJ4iqFp09n``Su)cRLE# z0jj0-V!AV-frdsWC820a#DaK#;;(Wv;ct(i0)zJL;}=AQJhJ*VK&xx|y1@N;@R9CDAx8yHBhpOWR$> z5tqy>&b#Y8OnPitu=7uwkTI4n?=UmPB82+Hb|6H5@Nw*|caYhSo2PMkw^$6JYZ!?P zf(ks2(R)9y*D?1l{4tpXsJ!`OS|HXLL?Z6J7Jcy|#q`ozMNDVJdi(FR-AoQ{ zJh|1@vPFHxD|0Nfmxp30)}+T&FP12FEHA9ABn;0I=`&-h+Y%DiI2x@2!-^Naz`4-^ zu!)`7O5$1*j5RV9_)-=K6kKW0LS_}c^4>*TXWv$ih znv*J1-n?-#B1&A%;XzI0VDeF{fbNErzJ(mbXr%42`wRxtU+2R$njq40#9^F-<9L?z zkjJzh0{7`P(CxA?L1EmMoS4^4mOk-nj{N=E%d9;zwX7h) zn&+7g!ksmAeyaA?uXtenE)Fp({TP7j#9|E8Tj+(E7w9^}DGWK)oOdY?7-EDrTIZ^7 z|GgZ0$FQ8ujtR|ESsYWMMJ`K)8gifzFjPhbMZ|mz9}X)&0UJDb8ZM zTb|J4)P?JHmapvK6$xE7oi=thE<>ZUmk<;uVsXB>>J+yM0*O`Gg2=XkVISkwJI9IKCg~-Vs!;dK$ z#kFF~Q#6QVaABVuZf{(Ebcp1bDZZqNEJ~;K`su`&i=T5N+tOH|nRzbIc!hlHi-zyw z$GQ|x1>)zraT&5{Y#s-mo{TfC*qrz6DYKEtMX9pm;Wjvzv}b@-t+~J)9TtTx#Gc(_ zF&J&}#>vxTwU)#ec0-m11D=*L_;r8TyVO5ZZXaWyr_42tRYmZ%9`-w3+BF7UlSgP? z==Dbn7AK+c$4u$MwjS-g9L4xBpd~P`_DNatR)u1$=?RLxFr$@~>&WkZ09lHY!8Vk+ z*E7$Y${+8|ltuQdzrsBk`ZuDVT@tv)FN|wj+gRrJttb;E9i)nP;&h~{SY~k)XF@QO z$wnOA|=SaI^vQ+s?$B4Vpi*55o^uAMc$;oun zWklJG5&ap@SG+xTXL~-zxl!Qdog~I*i}&~831-L~=ywAgc_-EV=@s6a#%uB8m#r-z zHsLph>V25rbLn8ziipl3*Kymv;)8vhz*v?Oeu5@kFD=h@jVEe#6g17Z){LKv~QZegy`L&KbN!>$OzoFXQWSmuUjbJ z?(fwWM${HO>~v3G`04|u^LRMDayXl_RHU7UBajqHx7(X@Wq)*)^Oa>)PU8{g z!z!aT3!?Bm^kV(HR=X=vKkztzE_yBv+H9@2>WHuVLH zlvoFGBMqGW&U9BnnmP;Nx0wv{q;e^I1-*oZhM^8H$WUQ|VA6=G>;i^*Z6ib6vHs8c z>}G;hMt&FHG#gAqao8xtjmCx!YltR+ZCM)g6CR2v@aMicnTAN-s8?aB=qRlCGqqC> zFRm4>g~PU+h10Ybp^$}3?4usW>dkvdH~YVH)PomWHN^wyu(GHriSd`*D7uG<-E4T1 zu^Eu!Fai}BurT#uZU2v+MD$kC6fch$2s>5UA6uHS99a1~DS`Xd)74 zHwvJd&(iWMuJ)}^a?X-0?cmkoZSH#9hr$NYk@}sk+vKlU3#Rc^jIyDB2M%n-HF+ze zE78R>v_oSMtFFl$_arfqq)|AjM^AU%vtKFVbUhN^m?#>yG>%I)*py7K-QaFjbmF?r zpiKq&GI22svu#cgdhIbL6M8hj*~FPW;B80z-LP)&l71J#AlM;hsD>R#@zXHhvuiBuzU?-4=8TRb`jk7M0l+HZj?}R#-Dwx)v2Z z6x%j+C8%5o-3pOyPuiC160I52!A&oG4s9IKjER4iytl^zPBxgNQM@+O+ao%2Rz4zL zm6R*vhm9PR?LPPZF~L(!O|rD7@hYA{CZoLAQ2_4*ufsivGMoiTC5Xd5L*rCK*S>M3 z7bD6>j?7YlF2!?=%eGC5Kp4U%iUH3EYNsOhO9h2@=p?gIbK{eT`53b`VJ02&RN2t8 zJU1W7p;&w7=dkZY)1CLv0l2~LoNitNVy&8x0y6rzD6O}{($Bw1@@ODPk>S^4plqyv zBFXIk%wG(wEv)VA=>-1zNa@+w7}*g^SsNPti^(Wh%FN56cwH_vYEjTh3-URH^|TS9 zp@rf%AtV_MkYF=mr%`*I4jCmSI03l4lA{D8g!@gr6K*!5j#0X5*7rG%?s*?Mjy96B zySqNV#fWGNsSmb=eI4WVlLDnfNf8@qAtE5zuJUn(MY;rhiC|=fYjXA&k{k z?~$$vl2C6DD4}YV4pteoJGG1xpjYEGYFZ|3Es0Bkl}esr-j|(y)s{?f7&HZbZBa*YLx+_p7`M&SBlLGyU<~9YNle?32B(a-ew~(WCr~_y0Bbo-OCO8F zv7*3C4J33e`j`P$wBGB0Jk&aUQvpfOATP)hA|aS*hyzor$R`b#r(pc>4>JmmN6`A@ znCd%&-Bd&lkO!r)H|*5_iTS~4;CEi(;Ht=kldQ+t`~5V&G<7i_svGZ6%Yfz2Bf^7WNN zi7X!2{vy&@A}e7;Uo&{;f1JVpo0n<-dm#Q-3?@qVnti=Y%P5|eQqXYwb4iFd<_AvK ziUJ(yr`}7ay2m8EWU-=k(fwxz{yM(^o5$s$H(f8twSz;)>+_rBHRUyN3`7S)(TPiw z-e?o0Q&c&P2AxECgGIxQG@3B>nc?p_O%~Yo*$oSJqKLUw?aYLQGTMV(7uEX7AvTG3 zmsUlk3jvF3rLU7vl^F&iA#3LRb&Mh!*CvJjF5bsK^=@5s_?r!75P+;-F0?<~JCFJv zAqfMWI1zU+c?hn*eK|1T(?fq4nWtCHqT zuG&e?UR9uBhN%;DRpf>eA~_~jT71$X!%G-8oHib+t^?wFp=tK*bCIlbT#jM;*=My8 zf@|lrshDtiaiAJELY;;DbN5?#g1DySRxs^{0arK48_=%I*LX#*p1D|`{w=|TL4e^$ z?7_1+{S}?ZD?B(0JRiJ2kAgAGL-9Z7hzzPFi1EgjJMfJ+ODe`iNu|K@h0qIRPM;g)6d@txXIMugI))M$W6VLZasAO32t*xG5lvUt0vLF>rXPIYy6GV^(bQO=Z^RW|| zFaOL{_Xa;BBHfCc4uO}PS2SV(Q>G7051>U>rau}rp0IldA>De*Q?#>*B!@E=$(3j& z=PcLxr14}Cxr#k5(%VLgLgvjL=i&RBTOu+C?PquEU}t6w@LQpK0sj?WUn*{;$FJDJ z{Ks_sH^bBanT}Qt04qmpNBjRh!v4Ae&xi5>wnnR!^g1XnRH1kg*k)HO8?(j_j7GA7 z6iFwcHg;Mk@!)rpESlF9_oVFkYuBIQW>QCQ_Y+~-qI~D!8!^|>gok_Amr{2$Bip;n z3xwXM!iNy3A6WQ%1QZ5x3?ltWwiRr%_gm~ct{@F(%Lz*F3~gVq`G$inGTP3tBO*{h zODiG&FVQ~Sd(oC~UPwkZ{}vj;NGr&_77{&RHWEofN%N!=WPH3GFc9+Jpd+9v3&C5#WyBX~h*~m_a#9nCn5QfYG_C*+{ zcJ>mji~LTZy~+6j^vwH`{Z1(TY6=d?OLG}|CCbt&78;G1E8P8i&|gatE3PDYhbSX% zd*yeOO`~HoM{`QkAa%rsycum`-Ckq_)ikw?(JK1y$&GQj>{UWJEf#Ica+!-Ry8U(e zC_1xFO8POZOIwO7{VH)oF>MJDLB8YR#u%Ltqc+U_ELyJvww*_eS|alYpo6RGg^;Mt zUj0-Ojkk>?i+Ttn%F@=nT3yJpg(xsyTI)+8%NFylVO>S)O~zQ|_V>bpT3t8uQaS-y zy!nT{2txwIBg3Xj{+y>^5#3&Oj}RxM(|d2BbTPcH0Vu0J;KCjek09{4BG!pWxzY*( zyeXo1ITzm|4-^{sIMcDjS>Dhq{q`kLHs?h4F1Q-5UBiZcgFnR|3;?BNMZWUpd*Q>5 zb}bO5brZ>6{t(;<&L~5Y0Q@`(e0vCQm}z;$(-(z!4hIktUvCWxG$g65#;4xC6bU-P z5Sm%&nE`l4W&%lPWin}`#6}hDsR+W2xcltYOH)YTN(f*2M2-stAtByg&3uW(^>Eom z`A~oD*B^41Mk+53iB(2>Nc<2(dND09#mU)mh;u>P+jkv5eD3(U83_J+Gu}bq^7ZrY z49k|vK!5ydc;Eg}2hZ>yAuka-Jy&}JJ&S)qu0%yOc@#bb&p~QfDJFvOx{$HFdPo|g zaCV>L27_M{IY534w|Xc7AT&~Jv(RA8*XsfpPapwUI6crVKr-7vGZk5gY%m2xoaLuN zU1P~=iGNO>-VuFZZjpqEBg8S{ZAAK70@{&^h&RGL5~I_*afEn9iX|X;F$oPiTtcEP2+H>|S5dV@C-{LMtK<+? zZ4~m=zRCE7rVnIU|>~wt~id)QHfvuLj0Cj4*=;5(buI-Hyk~Rbt~FP&uKRbh$5i z+157RV~mLf9aN~|gpkqFv)zTyX^J%R=qa(IIxC(71)eD#;sF!y9yq6dK?lE!}|?&Qia;}0r-83kJ_ zv46Tm+a6X^BfCH|pPgg1JP$xb(5oW|@3ftsg;0RZP8NWZqXc^jVUjmF@|(CIU0B$F z*wJUm8E6M>)%4p#Oy)10#XmHH)4+7{H=YAfr4Hu^=-4M)A_Ap0A%|=sHJ!=}#gDU1 z9C%S)3F5gA*B%r&>2yN+cV9n)!Y4?a%gx2OQP(c+|4ABqy8o@x-B+6MhY%27Zhk>0 zs{e5wcN;?hd#3<$i`4ti2#$ztOkn^hvyUfHFqWI5nZM+5Vu{%mNrUiyqBwreiAk27 zkMvAAvsiuaH$7$pjI_%fdVcXkuD|gPITY>mSGK(WV?Pr3kFrJKuS_u%u>QYxr9?$3 z8DzOH$>`6aBwuBepRxm2Ub>ZeK4H3zsJ$o*eu9zd09P8KJ(wv;wG!K0>`&j&pFOCd zX%JZG!h3xKItAE!uJfV#`EuzKuFjY3U++1Ox|XN6es_I!CP-8P${?i-SzCD_zQI+9 zwC*m^r(O}0`}yQpjJ_38J$D>Ji_rNsO1A21fu(LkDfCh*V+d%R@$*|a6JmgJ;MJSTNk97%1K9Z5Ll>yHt%PL_za z?N@J}IP%RWYUG_p8d{NuWU*5BV;gwHj-ooCSdRa37*C&{1lvMQDwk4EvI#4?Z0jow zFAJ^H3zdjmN8On?MIrvWdNOQs9;AS}7j*A9;o{~PI|$AYHdUNQ@Tg-+h4J(`U7-7< zBbsEQ3fsQ(@q_Kf`A|}cZSW2MY1GvlqTXq>>GTLDdW)L!lG!0XNF80fz6+!BM12x9 z%MZ5UJ%JhB!8w;B-0)1*+mKg%@DH?56& zm|F|_Y6l4Z#w=jQ|HrMYO^CH+$juJq;{~60q zT)$B!-Wk9qOumWcVG*6Xe|k27N1(c*Q3k5B_v`pbDZc@e;@<3J-(J`LrF%4fRRgmZ zI<`%;{v(AuJG+4$iU{=jvkYxG<`djsc?s%(*iQDf`&{{2wEy3E2;F~_m!d{`4qxMg ze^EBYaXV}w6rRfA2yQH~B$9q&TY^y7S%3Ngc1YyaT4YEPy8`Y4Rf6^OQ07{2DPh`4 zauh06*+f(&3%$`GQ0%*q3*b0--Tp8VQ2ZYFns4^*#MC4Olm+DuFTdwEovWrUx_-XD zzY~3{SB2mI`CYJsCXZNOZ9oap2oV*L>c?p>II{Qq%jOFid_bYCi-4;92McGn`w)g- zN-Tu-j*YmV&mN9;GPy-kzc~^=d#_$vzZe_^8~_e8l)qz)FOeZy4bFrkBiKr1Vcy9eCLX+^a2?w$cfQ>ca{#)OKetB!qEx?jWIBA~y28HHZd^99YIVZ_<}Pa1 zaWS&Ws#HUH*m1#l_|yTHWx6=5tI^28gfcTJc8@Gs;q!gzQ!guRci*(eytBPI(u%fo z3?a>0y~wf+o&5RP7jZ-Z3MSTL*hzEK>8x#$NQZW{X?9YhZ4UzuM8h~FQEL5Iq`h!H z_}F5Qi)xXx(`uePEhBtEvvakmn{8!JgQ#@ZT)?xlTSkmAQ!hfXhWA*6Un!S37ePFBljvmDeC5?CZT@?NoX5nA3Pzn?kNraMe<3c1ML@yhO_qAwFP(G~G!Nn@>pm z$J#?uKyTcF4iakUgc(PfP@Xz<*`K+uHT z)Ih>hOzN(rrWi~rQHGeuxq;55^{0=lK&W6m#+Lu>$@luil@erpMsEXwF-VnrO6L!xs#=plmRm(z&tY<2yy6(<=YE>>PGp?ITGi zbUK(bT2~8y+F8m!4;#HKv!i?YC~l&h&#kIEHZJJFW|6(^Xg6ZMT<0Z!`$P3)3phcz&8m9#{#(7_D_QWRaQyb|;vYdV=YLdA#HnZ_@*b&YFzWdN2J*YyM=O_G!IyC zd}GiND8GeN7e?iKM83)|U?3ocYbJKTT;_fo`UHxRyb7vkSOMiFqfM0Xwt_IDMnf$9 zu7V^70ZBDls>Ja+ypbfR+ZI?IV^jDdfz;x;Bx3PtDO+uM=J?-^ID$%IRAGS0gz!3P zxA>D} zNwxB2Ek*1<%`eg;m3r&y1qfpJZ>xw^{C|1EaDCqq;;B`Be z+`!N;{?SWs<2L7@_z7Ov==a7?`&O@_BcM8{sK`K-iY>vMTkeQr6z@yc-mO+|ca7M9 z+s*;DHG37-TS}P@wRnx$kX}GL-j#BCQyq#UgNGV-wVoAdHoSaj1oD-2O2zh{wkDo0R5vc(sE@jYj zVwO4>lY2;@&u1a#Y=bBv9%b&&k?lA4fdL?4iEXltF2F8Yi9Ix;LX?LFJ3oyGV8C=? zo5zjVixTmNHARCzRwvJ5AeYlP;{AHp=il?y%4;FE+b;lp^^c93<^OeN+5dOD)=-$2 zMfi}`zzT^?_XF0>QIrbD0_{LUB+pw!ll?AqzcYhpMqeZu=jMKg{#4}+Y?2T@#oooS z2Y+4tRCFmuC0d%#?a=;u;W=&G{qb}S`HK#ZT$G}vYCFiU!7sv31F8sRLz%u(SGYGb zO=Zj9I&Z5Br$PV%T*uQ(#g&`e4*1f|>@4J0k0%7vv|iNG*}_8RD5Vh(CC!MJ>^ zslApUIT*7RKQCAV_WT`6Hx|u)4%j_}dD^34fc{mDrI$df2` zKM0{iP7?%O*yXg@lL2g(QE5Tir)FYUE#*#k zShJf)N^IRXMn0*9$oGya(i!hqAH(2oP8D;H4F^*w_Aaw-T^eWX*?^_W!TTz-&_GLk*MTGW~EK# zmsix-T)(<#S^6q5cUlY?GO>(gHFpxhu5U3W*bYK14D^At9Dw{C zgg{J(wP1X9^5_7jNsp2HdOBT_PIM>dnWX!`glwY{FN3?~rXk*f7w44fzw>!N;QsKO zt>E|Ij^gPEoN=y+x=9SdB!@K3b%ILE^~{^*+-*kj9v_okuuCWOuNxxgd@|icv7E!s z$p~wRfU_hL0YIhdPgt0{g<&-w?5lLAIoCj*BChLnY9$vX#eQjmJ0j)c_aj4Te92?AudX=$k6n@VKg!*|1PXd~UjrjUfRUBM zzmiu;%pO?;_m*}dcAa|-|6VQ%+~9!Nsp@r4l&8rx@(1B32q&xP3p{B}TsqFFTi z073OwR(owhkTB*g{^3}>gP^e4dV&Iwn6O}WSVgndxf8mK6O0=I+WyfMK~PhsEzyLq zI@=jR!Q8J9ps+gnqI|!uro<+wR`Q+EjR!qr%bto7DO0kt zq}{MyEBg7%&4}VBl#>bW`d#2fG-Nry0gd%~PA;p}pKJXc|HfEASG(q%eK8mMvdScoowN=DeDct)_3 zCY?R^kGE9p1;R+DM8n0!?=T6lYpq!}Gilkm-^&(o;}j52#Xhwcw>!SDeqn6eGK{#L z|A|qcQiWKU_SncYA^W?uiH-_UON|*$b0U_9d?I|95oPs zrN=QH+1hM%8e2n1_b+bK4+Y0O=M6cz7l=BLMOZ*hntUzIIr3VuOOM;UfDhk9w_$Fo zquSfW1!&w^H!(dt>7i^py~bV`Y+3878EUfD-#eWTwBzh!b~H!c;pgt-DxB791l0WfDu68f4>JfHOp+SwMD&gfn)w zOuTM@^b9%rjAHNt?`HE^`1tU1V-Q-Bk`E#c)D@w|MhE^I{^U`K%eDv<6qgwt^%YMM$ZH#zAmu zWEb#rAQwac$01>j}5 zAM~?ak5Zj~KW3UZZEbygoN)M1m6-2seOrr6_wnTbxdTIkNr0ioY_ZNU+xGP}0)Zz= ze*MIG+I#KJau(=!g+wRTOt2B_<09?DU>+4u4cX2JaF#k2O-FHC5oALml{AzTWWWdv zB!m=$Os4S&phB`kGrq13%%~kRseVHT8C=ER&1FsVrlP>p=1^mesc0`BsoXj0Z%QO z&XnY;$(&$z2A-w~AGX|CDzxbYT}QRQ_>*>hWjiO&NZD;icME&l>K22^#b3~m6+K^j zS-0unI`cqLqV}-nrL}LFnp=!>{c?m-8qYwCA8Culg5?-wx@iyMmbg^$6qf>)XtSTl zibH2=bjoNDE)EDO&da@3IEUR~ig^31l}~RzZ{M(VIXg8CC%kEUVbFZCUj6~Ej6Ry< zBS~4a>*8^h+9!obKLDXL1@&lIwJQ{wMk_;}v=ixHc1gA%B0&iE2@T^}-7$r?+{$O3 zxSy-SeqC}O%JI-9MaZJUT}aU}n{=b$z;&q@uvN$7Y-=no7hKMoHDW$ly^X^XPTxp~ zTYQaa<+lS?$$!kJ=>$}_SBF^Q+Qg(lM$oM>W*r8`0$RtiTjGxpHGisM#uIV)T8fJ! z@g5Zs? zas274&m@VERk#GEng0ek5YvZQFxnP{xL+fP%3!9n%&GJ)tt4dn@p4ZqjV}N52k#pU z2%(3_vkvuC&^1*XtHL_FHce1HfJOqlbDh04Qo+2@gELO*EH3Oqj)TV1a9%6!Y<)*v)Bp%CT>N5*dfZz$~V9(fP=Zl zhb5s#`oX}gOJ_FFYQ9vv#{2l!h>x+XLb99e&&v%5ALCN*0HjCjE))rseF6Tc+Nd+v zG7{oP`F`*K7F4Q|CRF{~vctFTzlNH}fN7MaFTB+04sfK=l`{EBr2@S zBl98f2#6{tOZ@^$Bp*|<15(}vWj2!|O+=!U8~;^yZHWY?is`JtRWHl?g8hR01e^fx z<%3`NU?tltK?uLjV_(!hotkw)r}NVjO!n7oPlGQeNIjSZNHfd^iw#}Zt)89Xy55!K zzzlxcIBAh`~S~&K%koR0`z6XrzzUgMPH_?*oBh z8em)%H^hc{Pqk}$NxQO1zcPCTb=K4}#CQu8zqDF2qB9jo+({HaQ1uv%&ysoaC~Bj% z*x{4Y+monE^$4}!?>k0`PhHP-^ag=%ANLOliESA zuf{-v$6cO{#%z-q7>}WLt(x0dgrx;p(~zj5dW+i^haBul!gMQ-qT(b`W>+fSP){&l z>g=%&4MWx+Z9A;AY@3&xaBa)iHJg>*sde=IB>ZeD0Sk{+RV73R(2^7+Fcp7J9-qzADMRFey8Gp{u~cKWdBVOC-CKq0tgMq-P1 zqVbgQ%W22N{n_)rGLhyCq0=4FK$TVsly5$@hZ&4s;Jki-TZ9v8WL6C692-cBc}%## z_wY}MW5i6AtQ@Vk&putCalll35vaP9FhoA8fUzyaY6#~m?q6X{n<`9d_(l0m{&8o< z{2$SV|3mvzvi!@W(#xuD)sk&pUR(kjajYF64oLv)2_BY9Q7FqF4)k@mX5C@kfz5)| zlTSzyg5Xr}DToU;1~{0aI68OONC-dbUe-?$;3*L})EIxCU6_*Jp_A2 zKCmaJEB=BW#NMfpi$c#0y#o#`Q3MfiRG?g-6A&&i5^x+C?QVjvZ3>u00jy*XBYkLv zFV1hqm|+eO6`MYvU_ua3!e>!Tawq^+G3L#uLUnnALWNZ#o9UHD(a3 zM^rpaucoiGd(lytkBlfp!=p~l*_uKDd4@Vuwa^J z-nkPF(?)RD6^vxf!`H54R`3U5+@gfu>~zMBkl;x@ZJK6p*4JJynIev=T%414+D@-Z z@Kq=(b2izWwmtI2E=W69`B;rxFT6pCVyl6a!lN|8hh5A#F8IXtFyr9xNEE-&JDkv>HA-e! znY}l3GkeGOa&^hYcimv)ZclA`V(^Y*nQnkaPTKc$;#w^$c2F*g`w_$Gvw2;Ab*{Xp zrm{kyl;-1!9?}qX!Y-SSh?}xqQy?yaUf-?hL{(4;!Es}6BR4Z;nVzr`2%6Q%9gET z%siI1cZe-g8Y;&evImHCgP-}F?+`TbHKBt311lgF5sM|=B`3Nrvng5T%H!^hr#Zk70Le7@{pxINUJ-RSTEE^vc%ul(>5(G5%Q}o zc|D_2`e{ANx)Kds@My`JdQ$yGwT@Pyb`J|3imH0cN+>xE5SQNxbYvm&=EwFZ>f zVP=Mf&X18Zh6O?f?u9XeW$$Cwr54(@i~Bo;51qqBZaRM%yWU&}%l8-z4sVGg$|L}m z3MOiBw=K|zR;&zHwN=jvNL9g$R%}}^^3NH_r^#)9`RC1w;7uR9SI|;QBFm=){eisv zAR12Mohl4n6O~~YB3#p$e?N*Z5Wj`)ld;V;T$8KFl=p8>|I1 zvZi9>KyfMhrijTuP$&@lVs24KfZSF|C3f}C^|^coU=>TfeLucQbNGDc;|K0dM1BML z05YKssWn$Zh{*}g{4+7t;dF$hx?f$yeosw_jKCuNkra$pb$-UNm!wq#&I8u zhL%i$vY@V`ZjtZ)gIy67$&J-?*|3R}6Cwn2z~@ojG#fDnzn) zpzSR2Rng#cV?^Ft7E!89I3J|)g+a9g`~)1Xb{(_~R-zR~{C9MZNdU7K`B%h)MJEY* zK^=^P1`S{So(&DlqMgLih;Z~+KTsiS1DK5%afTHY*#z8WlgZ(0&IX;tzQIw)6hePU zP(mx{5VB;ni8^_uPg)F+atsJU<}100v4qWlgxy+;Jf}S%&XFSBbUgsc^OzRQV(IQ< zG7iWtn(~P7pANs~;sBW@fq~He3gX+-%CkLVM?wlO>?RVSIR*$vQpQ$1>uvxEFDFw0 zoqs!#tZM&oXswGK-^aJ+K7kK)j*O{}M}j>~g$9Q-G+@_EtD2OeTlFQ)76V*3xM%cwuKU6@oD9Ygh$Du zbv6?)C2@K1-Rnd1mAm(=$5x_u*Be+5SV!S*NLW5)9p#YX3Z)&Tw){<9m=)QSuP&KGa6z`nyBvl9V2 zqIhwwAv!`gp@3(T3j9PH3b`yvC5Oc$52efp95w`p80tcAET$&OUP5rA01Z^C^)bf1 zjdh`28Ak1$VyBi`5x<*U9uW=tL=9oN;*V(}VAG{vov`SNYsu)NX2&KXpTV%d4td~R z+lcacGOscY3oxo+Or; zY5lrus|wM7{eg019j?kIgnk?jft?3_L`T#xSx4i{g*}%lkq(9Oz<*U|Ie#*N_1uxF zQsc%DNU7RbQor@~DbrQ7UMJ<b5(C9U*G9&XCW2!wWHVxb2pb|S@cds&0c}sJ+ zOz6!H8sIv4&ag4-N$lb?*=*73SJv?84}-A^oQ^z_GSLyY0$8g$dAgULAB%|75prV% zmvZ_jc{X#8Xi(B!ftq`*Y~UK(`Qh551BP0n8D!VWu%%prxA&A0X+#B~@hnZ0PH70c z{F82S>=CnxryfztTjA%`ian>*+iSJKvwuMjw|S%*H6^_jy+y0RVd1?`aN_eS*g}kS z8j&#JnO&Ub{MXz_X;OzuEHeh}5|58*3oOuD0YT!xj7*8NnahSU1%1T)~`@d3aa3kXJ;0@H1g|rv1Sy zA<;9T(R%XrSia>Yuh<@xAilyyL(S1u#J$9>a|tDaRJY~A> z#h!(=FeR@cS-@%|2k!P_&O(LpSNaYSgwyCdn%6MwE7UIiNHY!|xcY2{dB$~r<(dBk zl6wpJ(=w6u8G!dT@!fj|MmshBlH&Hg)Raofj(y0Z{FqZ&VF0)Oqdx(pd+yWv{*$ZK z#Mpu@(c(;Beh;Ng-)mB$C}-<<2j1-odHfokiTxZmb@v^lALpVWS>;9Nud>SU2#j+5 zRZ_425iI&1DsrADuiTF|>NniKt`Ky*-cFo+xlhzUcq={m_2~tIqjr_p2<{LDR`6%{ z^+UZwMU!(^U;FjZp?Vcw=k-;iN>jcG?=(YoD?D}f;fJw(_1AHUY8QH3)f?`PZUSJ_ zCD_=Yy5dnrKNKLY9EFgs*v=xeNvvUI48l`P@-!o8csu{u=k{PNR4c%z4 zz;fnH-++pxR_M@ja8k)^oB^tiIUHiXr|`w)BuRSft@cqr0t0l~_gF zX$TOR!0q4VfnWKr^}>512?J^b2q4``#7sWogBDIeSBFwRnTtp)jmsn;uoYbHN$4gN7@!Q^}b% zwC>=6YrS+6(PQgty$!3B{&K{^SXSJ30hQ)^9k&jsg4i1W!46K~NT$?B5MH6m`Y4OuUK z>hkf98GJfKW320Brt-qr3hriv}|* z`^NF9!`MOXX|93!t#H;uL2lfVRsHa8ubKcjva*|sgON&dX5AX2@z{yDiBoM91HXy= znsjT{JSLGLjdHMg5t7(=yb9XB7+$#5T98aPuDiP%z4gz&EFLF>MwqAHaTqz}GM$U&11ry91jD0KPx8EHp#TSVZ7?V!K zjNy`DXcXi^goKTaHYn*I)ukN{wAXh?s$a4rgBN533|$VQw}-25Nmqx3Vl9c_H^@yW zYc`};FAqEzvF0+-2qyv$Yy>x)m{!L3*XKN%P zo=zRrNF6uN#J5V4MZxIp42atY3z<#1kh*r(<}p|753RjnB#NbY<%|kg)pC4Ww=syt9=y>1}z8tHyxs+bC$r@cS+W~0f z#?E!B*i?i;v4RTQO$DDxjd-F$iR2~+RXv}|alwgt%3!kFU^Wu3WPkQGMVABqbxWy- z)KNLpycb?Oyff49X-%4OkGBQ0*P0fm4}lb~6plU<3<)*#^TH6ia=xzeIL+2OCzbt+ zqNS;6{j6V=J#TA7DO1y{{@P_v{okLk_qLv)_wdR4e?EtOGP--_ZBKpzPb&?LN7S4| zJOxo}ch<6os|*$w9-#gqZpGiK^o`v zO&}G)!!k5(V;JKJxq9&7Ck-2r@MDFYP}4Gr>z7T*s!{KS(ng{#j}q^4g}ZrChkzPt zsA-}^mlo5XkdqElF+_TMw*0VmZABc>Uz8?PfoQcWUU5^7^|CmG77CS{i;fI3SUsPNHzN7b5~^*?!77=2+??^<;_ZB3l z=fF6{(vMNTP8iH6b$x4m5(jiv$E|rRE?lPbX?WBF%BzE_29I2lafX1-1w#3M^;RP& zlPh^dJ@q8}$td3dsFleTQYvH_e6YR;0}cZ!v_WCESuyd1s(Nh8gUYujmXx zXaBk`ZH)L&YuA5ghxISYr(gjv_?Mz7FlJJ`|8JAEVg?3Qsdudwq+aIq9IHX8aDost z%1g4*MrkoJqqrAs+OX}uFL&1gY}+gSDGsJP+h8W0E&S}S!xH;?%l%owAoyraoHrmV z*Zctx{O9@jy9k~@T$ntNEu)5Wu2-0majiq|mBfI@)n6sqN=72#!=ZCHEK`G%i_b^Yb_WgJB^kNDQC#5AkT z{4ChiIvu+%Zr@Hz01>l?+#PSlp0=j{%1wx4WpbZtJ<77b zd~RbqDsRu$0QQA0C34>hz{*_j37FtmV0jxTHqUe3X&rbQ-=ytfc-R=*N)=&V;mWXF9u{5r#_*0{SrGn(P{ucl5~j2R4;J>*aSgSK}J z&MfS^d^@(y?%1}SJGO1xcJA1=ZQJVDHakhjNe3NG9!$-gntGpiPMtcR_WrzU?`vQG zb*;62Te7JGl?$JbOJH_GTqhg*9YAML_0CqF0ZA$KDD$q^lE=q7rd|eT(*lhh~%q z9U%0OJ2f7sRkqZliPq-sD#b1?t1oQwhNa;V7}=niqJU?FXMyyMImRBKQI+kS*uva- zEp$eu+;09a+8)l+Ns=y-jUD?bQ`SLLJ(yzyZ~viY|a@E zKS82zn!`0ktx6mm7bRV$uF!BMryr>`1gpAMNRF!)(&}BSq#TKoBX6M1pv)PsmJkeEuKbqhhEdCeM z@h>9X1E1Cz`Nk>K<6m+m7r1Q~ysT4zO<7)jmftAKUkI=Vn!5+QnT2c0`R|+n|G~08 zhro|fvA&(z25nA+)Vv{~=6w9Yp8N+=sWY0m6EOfod}_`=+*nW38C!phEoq&Ec#iUdaHXpG z%XafexMIUQu{{5?pWH#^Ab9m_lK%VurJwx2TtAurEm5jz+kXX_KFo}~(ag~j*+D2s z(KiGMC}vuzAW)w$FH$?#3WjSon+0(;mA$j3Yg@h|EZ_XV?YnQWh}lYS0*290<-@VS z!?T8E1D+vD9L#c*%F)NhrCxI~oKLpQ-5wXazWae2V5S1e5Fik~xH?M;OAeAlrU;X` zwHED_1(=VQv%Q|zIdRwGas_`LeguKRlB4ski$t$eVjsYk7VUWuMHJ?-SW;s zX6ivKabW%)>sF%-6aJQ!<+hX0ET???o>T&?3>H}TAablZ^Mo$ZPDY-MH$|z6A31C) z&ajIITow4AOwGsWXqpw7u1q%@{hbG8>RJx>@bNi<`K&h=WVQdv7mzw3Nh(I zBlhle0&WL|tYYzZjEJtnkQEb4cw1fwhLz`YLg~atz%n z@(Py@D`NzY>Z~F8e@^(_T-3+pLL(rm&EWbPpqHjReB;pULCtbm_2{@B{ zxLfcVo&0&$X%W#dRAs!ir1YJBLE?_Uf#FvVkDOc2xlW^jY$`6vK-)b6l>=z+&M!M~)T z<4S{crH2_S=i^%(OLr7D!Xp#Dx^$_yaD#kvtVI$1KY8cmQAhJ*qYz1 zZrW}0Q0rW~6n&S&LIS`2ulee{uR6XWPRFY|-utWpxRV2Ll}gC&cs+-D~eJ0?osC&h9q`m51S_b5Po=qPO6@ z5Y7#NdxCzefa6B&RG?Id9)sX#xG9DsYo8DGd~Sxjcl;R&>!b1Ga1eA}_eZB4d}lrK zY*#(>cQg;-y^wxqP!W3C(Y*G0@F9AYeMBt!!FLGCeq9L4AzN<0SbMm)j{YZbJ*;P% zz&@;J072hq-|uIJz|Rr?(`SLVrdW3fzbO6FXM*0M!>4B+0)GQsj01?A$QzLyDHBel z&wOR79pvW>InzNptn|3LGZms9i04!};KP=OVwo6c(V`I!{Xn>!^etFU<&A3&J*pO4 zZ=G_?Ln_?T0a=ck#B6YyYvmA!>)k=K+#lh4nCf9`Q2XC5OnUQ{XuVa+S^Z{i*>BGr zIUBc?a_Z1F`+^Ekexx^T+_oe7r!FOe6n=$^awr{AK;6PkI=HRSyz^#lp!W?zPVHzG zcv#tty_}irXEw4gFkJ89NUG-Rx&(P;(#b^f()BYs+o3vpFpxnj%T&A z@18+E5o5ZYh5YcMj5coqCL-Bi+_!{Y1>TVl)|U)@{)sqOAQR0hEZSTGmEIx|sF0gb z&Ggn$uIvn(m1M8dWC%^cb?}23K~m|ON0~hH%wML9p&G7%=28U>)EN#|yl74<^tfo# z8%<~@v!tV@MQ+5tW4*sc23#hi#jFzpX;n|$?ZSsi&L-QXY~&t*(4pB96)rz=chJHS zZqnOvIo~5dVlk20-+mL^dQf(7VM>$;Q<2+}(elZY-{vqqS?8PCRVZ)aM1)-kUchS1 z9NX>Aw^+j!m{|2PR(X%v86Io7(AT)VSjC0w8M<>LN8jB}ZxnpVbRHSERr%{1HpX8Sg-+((2M0EWHZvpHDT!VazGaO~!#(h{){a@c?qQQ-) z0@cN5{y&+|=+iB&vzWu<3^0QeaFw>d5S7(FDgya z4-Pqm&yRbE<>$rE=Fk;LJby#GZ{Hn2{BA^}mR2RAp3lMj!&wuYilUKXaEB>AcZzTq zp2?&JsO;37HQk7cLm|>#PHL`qZ;oE!;;h&^rbeb$r9C88 zUqv&eu_8@HL0F3mti|j>iZaKq?v}-MMV(DQG|4k<%qZa_xy4o5Y(IKhm49(EE$?xW zu%{@h#lq>4Yf!mvR+9AfBwMuc`lsSTNEv@$v$@}ibLImCB8<3+^r3L{ZNo#@;CTF2 zN^G$X6d9G=f}o8&B^A;7_5cloOy~ld{7x~`_f8+eHZsVA9vjlQ*Yzg#neEA>anZyv zFyGr&QSO{QXFhvoPxT-cHRDWQ`0NTBRIHLxlPYBLUleGgNX7L4dH$^9<6@JX4l16S zJ0-B!YTVJQQZyrCWGwf^h0V~(kcdn1j+dPltfMBkEt7~Nb(;9(LRXqUYs)sXk`$ksQ0O2+CLoU&qB4k(3 zNZH&e9d{^s;PPxeuFyx+VQ5sBJ8{^RF#mQiaVM6k%XfIMZ6zotBkn zNwl55W{a}QvVHxf0F7Q7@x`jL%n$M?yR7wx^NLb^^F{l5A2Pq}6#daxsyhghIj`_`uPkE;-s3Ax%F#~=)CYQN9)S&=(u7eMo@_=>PJ@!{Qif-SRxep%;)RMkE@e~5 z=tEB9*sNQpVi0hdWlW>KSewo5EWSi4tY@@{YYtZL&ETG4w;t0>NewYl4<6r$O^dPD z98#X($Y5%%={SLk@m9tw&gmGbAd)ytL!Ufh-$T|2xUpuAkc}2@5k0uY<`SI9RqoVNur+8Uvg3)lVVgr zJ;baUdu#>LJt0_B8B&2+s7W_SZr4^ha;hfnP@@%zR6!lG%v`L3fLL|hE?LuGGZDPm z(WAY*?{_>BJP{VQEajuewnw!bZrFlrzJ%Ldv9dpA#phR=2~(MJr;3MBG0m#~QX$@= z+|wDfQc1T|SX->NEXlLPzERYw+;?7xr^>Ni{kZ4vfgn$GtxM~TRD4^oC}`dQMYhi0 zM6mK{LhuGMW7Ipc5Fck*E!`m4OwM%CJMBKehvr}Hj=5T}mfHqu{5@-toSL04Eb=zZ zO_-Cwra6gY57Pb0hk`=5DXFcks!Y=xg3RvMq=pZ==a2-OwcX_=rHi#4rc|zAZZn6* zAdkk{bjmFL=$~1Vnz?FC&&6zWve+XLcW3@X_NEZWF3pMdNm}!*uLq4i>IzV_P{9sW zY&rnX7BdS?5dz|~G&RmJJ}<4}q$u*QVVI@xd}`{vfz!}3R|c8=fw4i68bZrPl8&x) zm}fK+wl(@ltk)!w92l!V`8h;M38>N3GEs{#n4>%{(k7c?{3X*;oI*P&w}dOXlx^;l zn7{_pv_gS1P7tR^hkJY@F3Zq$A)C%WWV{5NjzY*|n;$7cOF?IFIZP{3ZXts;?FvEywGPa}{xJhbPCSe&h^ z*|6TLDAvNa?8DRFS2(o#@ zjXp`i!4KCGt65&_53c94n3O`ttqGp8#ADrTmtY0NtmJ<+Ag?{JSc)uJpee19x4^A# z5raEd&EDW$j$#^HL)IvPvh%WNfs|tsY#|WqUjh8Sh);Ak=VJRRxM$HxNG)G6~MCS zFRg9`KY(Z1c&Uc4tlldK^;{BHMZb9HT-qh;FY|UmZlUox%|p6ZX0FQYLeqJbi#Q*^ zzEb%ibz)9_3Av|6FW-F$`d!I4#;>NgRw74D>|Crxp{F>tA}s}wqe!z%Q>p3;aII2T zjq{S#E$gi+Jom2D@1ai-zZ9O=R1s>T4nH71m@7V4v630K56uYPl9VxI;ES?LmYdhC zgt5#W#XZD0dQymO(ufE(9#mpAOLdF3oEC_ZN=VO&)J>=^Q~_4rTdf}$kH{=dIL?E! zW$TYGY(Ur5glf75NV0H^rmPyVnW+*m{A_}^!3(|!I%c)+2VE<5Vw@afg7cixdS|t6 z@|!V^(wCSV%~f$-r%>I8zPq4UZsE&0jHCWdR@xf}`ll+9*N>}@?eS+(17N4J!oEJZ z`k{{3>YyR%@{__|TWZp`ToE^dpl`jI1^`!?(IpJ}u+(VYDzgm2$m z3I5Zu$bZwa`@acI|8T^~n3|i~nfx!6-c}hMfb0k4($Gl7fQlAf09im(K~zFiBV?tq7(XAsY+&h8X(&C^3e5Ry&S7p; zrvK^N3xjZ~T&xc@#72M*#x2}lSwz^wO_$E?BI?3g1OUMCtD0yeq{phkQ{QC}bD(!r z6n$yp%_JMq+&Y%PKq9cF_M)H3#CdogA(CRL2tJ`WVEV=*{oGf$9zmOsHqkh1{ox=` zi;y}p*lWY(f!D|!d;6&%`ZbV|N9ZpgPY7?}j*x_B5iFv_d@PohQnON~zLqtT42&$f z_0!GJAvhF`rzhRX(M;LI%dWR7=|(h+*Pcc!)+KKRoHaTg-ee@(2+lsX(@sZ;6!`wr zf7m5{UGQ+jF=Iee7*7Vp{gvSTa#-Y}Fi1uGyp30dHdu56+ud@Z3tQ_pf?JT3miKyS zIkW1;+NzO~V=1YhZl`D!T~PDHsowh?PaXxb@PZ>X&ZOBI&Y+AqedI>bg8O- z6fUglKrSWK(cd_YGl^t$9bH9XsO8y#?Ww}rRPl2fYTT9jNn_Sf9v*=t)fmDUzUEL; z;6{{MV{2WalU>AOP*xg93xXwmh%*k-kCAu~m2MV1A7F_xqU zM*F$<0cXt@cn>fz#jfnpJKbbSZtd6-SMriB3@AMgfDP8;%}r7>bYw!VplC8`DxLx# zA@WH9#U(xSDvwOuU$|{eC(@eKEDqx2b^``#p@~Y?EEjvn7j#7?tflsH_1eCq2=f-J z^Do8V=fl8r~4m1M9O2Wm;^9!NrO{+M` zEMLT(ZBeI;03n#Y5iy8gzTOVNMUse|;}q@gX}ji&rZS7B(^N_ncL@`uwY8~RH zU%-X(7fdUtX$0$(yrF@VTHOcfJHjep=+FL~w9Y~L<>cYeumfdWT$p97j&6P%O`P+5 zZ(6%Xm;Q754Ee<4B!x#%{kc zKm53H{R_0)Go|0Y@pH=VVA@d?#svZ-8#b;Mo7FBSrUkp``>rc(;*x5-h=!Ol5#G5a zNfm=d^&$@zb3Ek_={LB4`g`-E7ahLj^MwB>pZ~uzqWx=C`uU8 zc{4750J!nsOzE@I&BX))S1U^)sG&0m^FTh2A*?)@2Kn+#Gm$qY9lSgv=3N5nq?0P}Fm%zNHd(^W@K9}`A zM2hD9`zRVaZPVjE4|I}j+r-izoomJ+9iAX%w7{HemU$>P6`kJoZg6)Gx4PM1ps}lgcO#ih; zkO8-LDi`gwVyj)%Qj6XBE+AfZRAGT8+g3cpryee4wy{$XG|bgdg`Vbm)oy_@b2d?! zLQdWpJiz_j5@XK4y9@^DUh5~!Q{A+r9Mg;)VF}@#4H#t0PCP1Uc3~dcN{zVl_i}rh zhG~hUOMM!ePPUM)n$K)6Tp17Ae(NnfG>B|u(PMMwt{l)Jk1q@!;A)`I)P?L9IaEV{T(jDz3d@{zo%k|17CX>}F>@7a@VXn}h4Md#2>-ox`PXONq6z1dwCeh)@1N&ld)8zEk3B^LiAO7qNKQ`L zPyjv#No<4{gdij+%s-iDOV)UFngo9|&#v258dq)I#!e=?TC)9RN5$0WA9Yn;C?>OA zTy5mPx9TiD>%5q^-CnV=?RKu^mlR(cK6=7i`+Vj8wdFj^7f17wW$$-8`7KkdQN^N! zn0~~E3R9v%A(EO3Q?fxL(uyioqCq9nREajtC=@+SLXl)dib_pVk!FNVsablSXhe;w zRkA@h(z*m%x(7jm77$9bmZ@nH9E04^d6-PN7ohp#^V`vImGtaH`w#M z*YmWTnN*u7=HvrApf@&u|34sM!#6O%*9nDKfk(liA$T-GiSDfZC+wZs8x*AZp0xcZ z9RA@OL!f|3d)~e>e4d#{{C*RBp7FCZu+PXN`Kt{D1~`T-$DDl^pLzYzKeT7ch&|yL z2F1TMbMp({m{8@W9@YPHz~?O#3eJIHD9=M7l!s3vr0>>%sflg?z^4%_iKMotOQ;j{ z#OO00jO#NMobucb)zUs0%)NCL3Wvn#GYTj0k!+Z~-;7mtYYw0HWQ4FYb|VQ4!zMIK zzbPdAZo)Zw0|5lUcgNN-`y}n-0IwO}()Zbb{;VNzeM}*E<_JW$x zIgj+=D1E%ay-+8;8>Z*mZX)U%ePDXncih6nf>e7HJ-BbA?BIJwUx^6#5uBKomK;99^K!WWYR`#{QP7n$xkmq^Rgm891!To(Si zUmn4c?WuL|8h#!~fzW`Z&oqqSF@lVO*_Vgp9FWqD(#JR~`wS(L?lFVx>oJe4`1TX| z{W*e&_N^Z|*kc`8#A5)N>1_eItr2p_CJnroJ|6;?8yyHikHG5ks4c5TjY-g0vlfsd z#eq;d<)J)?AA^v2rolYFlygb0j0Zs-@qy{QWW$V9mgNPULWv@;Dw9Xl8s9I~9oHb< z-V(BgbFy}1VOnc$y2hl*EIq5-av>*(;s{+-tMmYCnZs$y$aLARa_9>nJT>_9^(Sh! z-0T;mHT+XL6~Y%UgMhX>$eXayLy~b8)ig*O4BiP!P?@r1=3NE0uX!Z^4dc z-oAvE{XP3nJ9f_5sMm=EPu5wJ)ODn0SGn>kTAbJm;?u0+xfothT$_39AW}Dk<|}eX zSc~hDRB_6dtaGZiLv5}Lbt<;X#h<47JYym;oOVVsL+uG>jI#~6#L*fd=IHIE3aycP zYK3f2v!5{cvlPTDWPzHf5Dc{rn8uP6`GXM&GMTaV8AFi zfr+HmFxlT*SRn5PGoUT2s?5^!ihi#2!>4%>EoK2|yDBavrpQmMci8Wnzv*)(AvaEZ zWwm~lVmr6>>0UV#%OREPV8eH-O2|qJU&%Iz()MWf?|v1kIG4B8c)zY(?Ko&tL|Dr| zYJ(nMj)&y1qn-7b@roD=Q7z@rfq~}M018*2(>S&Jp(#++D*5a-TE#>fL=1*>77`Za z>JmQWs6{l(ezPshMVZmXrTp5Ag+Qk^NaGS_5&1P^^VeU>H_MXd_0rbWZaO#Ax>TlD z^HS?d#!1cUiZZ&%5|CfGHnUDeMqJh_s3~v5XjsZZ)z~3jGf!vEwuN~ZMR_fmHLrc9 zF*CyYggA16t5!ws>oQy^NqzvZzL@$c!JN`+J%yV^|K%UQv9z`!GpBojJO(jb@E*Qs z!g-bKb7D!7+fZb&YauZF%;1l05co51uhNevOTJ)6Yp8EdfRT<>a#&h}Xx%?Gyr?-t zCgvQsT>fgQjln^omxKL}g~ za%ufF{>be6+>8mPddVz$X0YiKNa_ZgvM-deGT>=0pt&w5r*TpSiA&}FZ&P6NCi81k zNxF!LYJiSxzP{{s>1HRLF>?}j{;p6aVRN_+su{wGyVoK!;&ijJ#L=r9BNGw;6a({I zc22HID_nP(!4g(m<{fDdXK9I zsVqzttr-uh}KM#@V|OU06SOc5vmbZk6UqsBUpKg}%!$)cu> zm6J1XdsqvNuVEICC3(IpK6;{Ql)wJY{`pHS5xt^60-r413jqHR+k@t zL1gPfw<|4|O{89OCmheZ!tL1o0+VSoZo79}oJy5gT$eE69!Hh+lbTSJqve6BM=go} z0apMoJuLJF_2&~p5C*h-RA9gF{t#8=u1%daSLu-BhVY}3THxb5uJ^6=x%yq23h&si zWJT+MWw3CW8_{idtU1hQhB#WYKTOMz(4}Mh=sa%r@WD?|)`eM4JO0o=LZ4JRgbz7` zz!(^+~0Etw>?b(1jZy!!5yc zFOyuquz%-Q7^}z(0;n%9;nh;-R#q|G?oc53Ml8zspIa!w{kMNPd?Iq|f*4Sj4!kO2 z!p9gd!YKXSkXQvjoro0@m@k+8p&CT7cQCFEaaA^MaERUd-DckRsRHG;4ZuA+D3XKc zL4L#&(>uaFfc==G;68G0GsLT8j%>Pt?4uQ}5@{UB9(}A86zzbA+l-#cmKDtyiFwJ` zY5|xl-449m$XTn|4kf(QZP)Z}+Y_+|ZhmS%ldi}Zg0Oz|dZnP!$J-|lr4R(q3WUOb zxMk{&ieX(VCz(j-@5FNq6rE&JC<+0iUE~TQw}{I9R{rsv&tci*4BEko8Ucmin#%5& zGCd(N6+Lk>?|!t4R|RnIKY}*G95dV)GIS5RX7nrzjpMc?+;+GF;k7$_P-%!$jPU1K z21;Tk#~K__A-$FD&Fd3d*D-9CzK>0Wt7$H<0I!0C)aN|&ebIrBOe&V&DMb9f$U(1j z<-Vvj8%(B@2!)ZX7Nfh|xYddYVlybb5v~O=_$Qk=?!5k}94&K%q=aw+4j#A?@Y>}% zxAA1L7VQNN9!PLYy@Fo6!ZvC9lZe`Q1SuhgObu)T2m)deX|v1Du+zM*y#9&RW&Ds8 zIm14-v}G?oonuu#?h(q*8IruEuF+QUM<$} z`^N2U8)B=j(lA=vN#!vrU1M|1u?1?HHE7B$Ra$292iCVY8>++Q@;}Di8?(HV_w)K2 zC8~bIEH!uf(0y2~TH0yBlgl5?-T;{qEKKe*PZg6VlnxUD!T+NZ-hf7i*4oG zv808(&}uJi+av2lOPz7VBZ3Zbo>=f3(aPla0@)Ajt|RBugjo_Q{r++v6u_}`yY>hA z(@*sqlox7#693q+V{1-&|G=?k^BasyZ4dERcE3Vjs9Eb>5ghCve)|((;PG%j2YkW zWEA-leVvpPNn+hzRBv85JCpuej_r6kj4VM!)S}mW!<|LxP55@(fGt02yVo1k%h7Ci zu57wtBe^<7>PZF9D|oJ0T>_`Kjb#iQ7pp}PvVC5xT0*zfZ2mU@5?i< z&sKDbFjDA_dPe6t|CE@Ptmuu9bY<{@SI!+>5PUbPS$(V`C|@8^^-8P8zJ!zubgdW5 z9gRtlo8f}e-cAnNs%%BSGN9{jp5<4v7U2CWG_`0in&OA1b{eKowHuvpXOy!8a7Pu( z;?KVdeY-=LXcx8_T{UC;#E3)BAr>m;I7~x4`*Ar12@9Tf7fj*(EwY-dp!%<_`My1G z%zFp7#+)mLsp)B$vg0iJ5 zLGoz6M)_Dz@eyN}vpLJk_)LHK_4)b2cAtfWNC;UE3gEihUmIvhGR7LSi}mK}9lxcE zedX+(z9oo#H4NBC@c<=X^L*t0}rFi?9(pVPY#lYTCWL=Zed1m z9;X}_GfjqzacYJQhnq8*8chLZhd#x;k;K6WhdE7Aj3|!gYL^jD$yeR4{1$l|@eOAS zM-XQP0$DUHXtq#);Ma{RM4NF}Kodx(|WA+6{tE-JbWU^3Ate z<$9>nZ_)uIKj`*YVEqEVKrjtr10rjcdtt(d08l^LJwqR@0r@XzcAl_$z4{y>N>3il z8ij#CD-~xD9>yEKI?Z!v{=3pc?r^}jtOCYv+H)hgp}U*Ll@QE%TD~1~Yp*&pu7u)} zQerTw#Rd{b7E>*^Vog>iR|CN&T%1Y?^QcbQnDSt`BW7uW)5XKbNJ__(xL>4fO#%xA zBLvG5rL1Z4*0tvGgNlazHddp>o2uIm62(r*nZ!L3OEOQztc9jdpjfHoow$`BU?nv_&vlA?BFHnSJGsbS@|94a15*;R;N8um<9MECxw z_=e0T8mqP3k6@gc^v=X%YDp{vi=ili#uFxR)GG#^M@DHFSgvEQx?HJ_Py^N{*d$yr zcER=y89W$jHF!VV4!j0FIXlld=Z;c}SBWrXfl@p?aqn&TktJu@8}!WzKh93exrD+5 zYq;sGD-Paqnm-|nfU>AgJSP{XQ$mb|v55pbZx!wXqifdV;YC@2H&5zo4<`4+Lzs?3 zj)rIUKaWaeID928Z0U`hNdO9cD(s2aE~=vy7fUA9iw+m3ikb1~6(ZOeGQ_^w*eW}= zCd*ALE4~!;I}3FmDP)}!SjvxbbZ~n?{Jk!d(l0j=FhN( zC@uL_MmW83Lh?;FRjhw?Q&uj0LFt-y2@Tpfp&1q|{+cfV%m*2-8;~K0x)i1@5 zyJ?kSZap<~IVKZPR7~qD`S&c3fn>GW*dxNdod)@!W#nOVKN9A#UKG*?G)c;T=J)op zj>Y~mwy$JBN=-a~Xgc_VQBW9zll{dc=Vcov% zBjm^A&M?n~ZTI9((WAcyQro=UWB(`rh4DefxZ<$l&;7%_tFpCsMsAETM*VK_&~)CC zbQ%u#MEpsL5zHhcE;C0J$7Dw@)LcK+jr1WXH_Y z)U?atpRp;R&hhQs<8nVV%oWKLDP_v@+UwrEveO zb~5AMcHIa;DcW?j%^pEIQpWQvWXiB4t|Ve0=V33YW%fqTc$xH)J3^#hv6IDL4wInG z0aD(2ecQXA_9i3^i|BExjNUKH zLkWsKEBcj$FvM0S-@Jn0;XD?dE~x5NO>;b$?dkV*WuRwY^dx=~$6<629|%}@q6Ta~ z8HyESL(ilSvQ#&=O!T8q;{K8}_L4&LI%D|93qZQ%#hvz*SA_dIQ~0leLH`ZmnVJlij4QieR@xf?HJek01?j+4Hvz(!V$u5lmplPRuUE}mTzzxS69w0?BEzmDs1k^-e~?FVDcZPu?( zWgOZszl7T7NcKVk^gt-cf|OCWPE+@U(!d$Ghp>hF0)#-!hp+*p(bCum#=-%_2AIC^ zR}!q_a|98kxs_R!g?3+X%TBEWM{nzx0W?Y2d(OlO$51>ix9y`1G&>Ec9R)b43Wa7F zQ!zF=JK9B`Vs71iuUNdTa6p!Hk&|b)6EWJr#5wu2ptg zXm!5!nUt6lc-%RxT!hOE3*J$3NnT2D)?17%g&#jUMAu7MHmhgZpPC#4bIBQcEc70X z35^Y~3sT_tU81nYa~F$DHX|}sZSV@$zNmfprOUQ=T|XbkyH4YcF~CjSA%xbI14+GU zpnXeafs}><31G9QWVAoR5t>B+NRgZ|sA4)4+9mj;lcLsl>fi!bWv@2B;07V!mxRNt zmVNKOVenCst?#5gxYzwevzMUbs?bNHXD?07UfL9WPvvz+s1T7mcMsvfRSwHux{mk@ z=2@F4zWi)>*FG}-8Nfp~HtIg#dPsQ_>Hzucx0mC3kB`V2%7jkH>SM=Pc*p3aWD@Z5 zY-wg6sDT$$-NqugdLR?*kHD$zDItkv+p&$@ViF>GcmAt(J>56Y=wHF=jeW$DfAH_r z{^Kzm&HwGR^Y8CO14ct-72~6>soT&a00%-ykirfgj2kirlZgqM9$Sz^oPcf8_yh#$ zJIi4=2c%6_F?)<|vusjx47=nadyTG4l`Xzewe}*p?MCTq@3r^hyL4Y&4d1UGoYZl_ zdY_v|1#-h9vLPy$bTScGre!Tu81sW-_XEU3Au4r+sC zq}fRhdV>%!SY$ehHNvo(n?0OFlP*`2!{)S@++{Ctf8Vt^X_wH^+zb!=G>~5~l+Q$S^22acl%}wSr zJ+Pd@lMm%%iM6js8C@8xjW|?ck*&=-gkdcv7+~KGhS4*a88L`N?+0L&NO&ra!eJ<2 z>m82R*gSn5SVdYcpVEhf@B=}BzM<`~;zTDuX5wjwb-J}ijX8&J%z&@hJJUDNLq*JT z2PDjL`*iRC>>ZLrG}>Fq6K~Y-sgAf~raq8$DYu&4%A-vlY0;BfCs}5ZuR~x#jx;IVPUThuUr+ar%b&nEj%lOy3aglWx6v ze;gutXpDZx(Hqt_eZ#qqzs1^OIIOGwu=hv`AW_(~GR*346twkLL8y?VTQD!zipyjb z>5&ve62nl2!6`Me0#=AcE3E#km&`XKt_UIIh?&D2JSnb3{>7H$EPmj{YZ;>TJYPVH zYL#eGDOsw&UKf(g6RsJ96r$Av!e(Z1t06*Dquy=fE3Ffiv9d9Bky$(JC6d+kx*RTf z)JV%^YUNcvt&$XpW3Jun2zS{$L{7uHNw-C&fNMce)xef}zM^{I2%)8&QAIz;F8NIx zrt_e}MAUX;WGg4If=NC#naKvUMOjs16iGh8y)lH0a{)+jQ)5M2Nls8IyuLt9er&7>zgQ8cCNG{Vlfh%Op~LX}c7yx)4*s%l9$(_`4PS2Sv9KZ_eSejSe% zNL_Fh$hyT#jUYQxk>;(0MQ<54UP3TFaTAlD-?F_H7qp8SSt>TwU;`f}51hkr?@n~1 zE8Q61E!D81p|}iaBERq-al15MB;IQYZqYNY5nCD|@gBDsl^Sa0pT21__H(8z_FvS&5l5tn$7@av}Rkb$%SY#EE!SRx~oFgVjhu!zEbH z$N0)urARqFZZFlyKv4_t%jszDogIb&9vw%4p8yqi-UXiFw-{N+8Chlb+)C9I7F7MdW zc+cjkF*si+*)`&Fh7((4P*u+}k`%4PMd`C(YJIE{mh8<{h?AJa4Hw-@)rS)k`$!+= zRRr;+5XszmYuAfOxmCJXD<}A&hpo1K&cyfD{Mptt|0zYcQGZH>4JgjOSP;2t7BeyD zP9cbr)6Hd4!1)O~tYjcl=AN*z4W_ik%IF8q!(&Si3GCCkji-s|#v#gx8D*hn*ur;t zI|-}#9IpF%TUu>+b(GjDeR_~W+mf6_*9f5Q1_&+}!f&F>UyVCkBD%?~WIzWt-Q>tK z%#-4->AD*s={#U9I5YXV8gpDesGwNqc;GxX zZ&c$A<4VpbF)k)hS_-J>kITk-i}DU!ga%)1e_E+v6Qc zwqDTKJw2LNBJ8kL1t>POZ%Nvvb^Tt{z$;M1wT?A5ToJ^fTaNRA|X(XQ3 z)|OUR4u^amW}ZT&QJ_*YD$o$yv@X1?8I@`Pwt9fsp--=ouN3Mx_aoP|t5=T^HGqVP z;h92dK*e3}-bkjupqA>Ns7S|?sh|lNp{1SOU5`Q!>>DVN?M{7ytyO;(-cbtThOs0l zO9qhM%FMwknyyg*=iT;cc@3YqreJw|Fmw$mf};$uTP_D!PLZMApR+BOY%8A>2Y)}Z zc3OGkk&U@FuSx3X)xxgg*r0I2<^VWgbVOgM-7)Ce;7HZbRWcqG^!IZjAYw)^uB6Mk zBNt$w#8g7n6Ib@YvAM>5JrrktVZl;F}x{f+V;F0X|zUcH5lvwDwN?7cJL9M=K3_B#g!CKWHNd2MoI-XO5y-)nYN1Z6@$V zK^xb?m=lCsu!nuDz$QmPCJmuPaWvmx_3|3DW#!$bF?>*?M*92nysGj%SJP(L7_e$DHNY-l^R2*_-FCz`;z>Ezu2 z>)7~C@y523YnYQZe}%ZB7(Ais3rc?r9>Z_o$gLz{`@Cg&{b8_?)O(YjSkv>8a@6SroFJe$3NxbudBL+rL(oE)BhnEYry!RA7gy_ z@7lOEW)XoW_R|vsqU(azA;=Z-r@_g?38kM4)eKcDhxe)F3%BK`<^ z6`t~KU#e`StB!CC<&KhVQZ)MV$L?@7<&LuLlJLdreeIS)*XOP?!3$16-}}u1Cn}#? zZP*qV5YC&T=Lud5v+7c~NB_|5v4G&)!BcL|R18l)7M-aC!z}{|mJCoAD2+)2L={fo zQUt~@X-{4<^1mKl3JcH2z#QJ@Bb~t$7`8-ysF_yZK9oR!K2dlzCa;wk!-gk?fJ%69 zcmm_4!Al1q;89_eOeu%iYcQs?Wi;j!+Y54#uAi4zfnVLUiXV{^hCa3-c2^)hlXkTM z|M|TAC%svFBrF7e!xlJCmbEBumbE}Ti$}Doh0E_|%t-~~q&6IO zb^;qk^r@b-E9`!OJbbx2)@D81w`b<_#Aapit2D}o5-h%+R_o3*v?@uaCh5>P47vxggM6?ZzJ>J zEHasP;n70GxN90{SlFf&0^+KKDd}ON+;P>l@v$>@a78b8nX@B{r;5yMtU2Wo*i!L; zJzuD*P|t`u1p&7+OD8-yU?>^!GeK#2*H(!j^9JiU+GWgT zPiAb7^_D4viqAY+`bGqbv0d|bX&UC(r8)^Mu{>7P?T$v2i!JUj@$Td2I|nCX zdtR?1n!0$Cnr_WkXm$O|P>!&aeJ(P6{Rb|NVh^1*67-&g%C=nRq@$ac6-mI0`k>7-pY$BUMTeGapgU6mAXMR2$6_8?& zaZowa1soWTx9&7+R%9V@Sa<6@-RJGkK0pe$Fyz^j5s8W%^ZO0YsjCbYOx*rv@4xCQ z)>VGY&0Wg-wTaxLIdcBT&2AWAl$6d@54Lxw>l1`2o*Mh1F3U4HCaK%_1*I!}Q-$aO zE?Sh&dMjI?cV_tdwrzS!`0>3I{+p?(2 zSBc7_ey}z;$u>OqL%vHg9|_l=7c&yu1wk5`ra4y+6BELjqD^k4UaA%?wz*D=QLU&IC2vFZe=ei|J^YiIOiA5D5& zqHut=lvdqzfGEf7Ev*vu=}$;67AykEMETaOe z2b;6-Jh3d#j8gkGi74|EGnD{N**QhO2&+;DDV5b4w_L{wsnEv%$RDd#fPx`pS7g*Z zyi6Q+Ut@SmprE*%gh(TVk1!GK&yUtNdb$^%$9~~0iUd9?-eb=#K97i!3fl3GPOZD0o zmJ%(9X1sbl$1y1(_Q?i$qw`WPW<+p<@DV&1izdv?PVoET#CK&SjN7DzGZ57MjyB8z z*6?@S(jTc1aULP1Q8dn}5(T{maxpAiGO`7wbySCyb#qOKX0s~?BFV@LqRDEIDW>vz zSk}Y(7Nms-r=vMTgIrqLQ`=Npv1a*}M){T2h9(Rf$u!MRCL|js?B6UAw!e}<{{)d- z@r?Gvap-h}nrxF+AXn>mx}jwZC^SSYB4JeLt9AJMT#?bC4B4aI<>D!Bno>GsDA#Ct z*bD4$<%|y*9D$5xV~FcMRZGaa?R`<8is*;`@P{@IQ>T#@&B`Q7-&L-SKh(_2FcIiC zmREO7Z&8-RSlu1jmdaB@>6Dv9VjoE}B%jd=`%P&U=Iz+j5^?A)LXc>(ZQvg6mUxIF z@-umFTf@D~E$&dkz3g_FvrZnktIP?QOhUVc=hUl;hchnMrf41(osBJ)l+LE3Pl(t< z6KNj9cE{5=OKfB!o{C2t_HY+rqjay+NF!UMVBXU-snRYEGAUOiUZge~Ly$^XD`^;I z+w*FbWZX3+rJPcG-b3GWboZ~*(Jjy>cHYy><2F`qRdAu;HYs*2kECoKquZ0iQoA3s z-NR3lKTqKuHAqv&k1x6oJypR^NudBpN^=s;jn>xz+$C)buRq0K;tu#5^~=g{spOW( zp8>kwkS7W3Wo!dCnkbYN3i6iTpi{2mkfk=qOju?N%+Vm4SF1~TyfFE{SB>xUwoJSa zW#6bt&3XMC97wgE>vTyv^TzoLu$J%hQXl(pbg@DG|7U9a-;_nKoRT0audo(=qEIdo zG&EcvnD(V#P^!Ek5iMD&RH(V6cB;%q`#l1WX?hyvEu41iH9*}$`|-0Em~S7@O)n`* zj77%rV2zve1Gb*%?0CAz>w!cElYw$W)hFw*-g?__uU;gm_7H`JPhtQX!o)CA#cJtV zz*f++8^Vs1Q8*Ov#oigLjFRruZJ>IR@hBe_S!ni^XEC@$vV^#1w;i@Rw-eKo>ib`!ZQxiy0E1;e{n_%{^uRS!A( zguyO`bCK_7W}jkjv9D-V*O4H%9*y8I&S<7Z_g8Ht@2B~H`TGRIp+f!qpe_*qk-Fgi zXAJf~?+<@tvT8O?sK2m$OmAvyG@$jt2$8@(6E5dy<)K^AB$5y)(Or_ zb@Qt~zP~q^E9@;@;ZpGz+lZQF(i;8%rqjqA+@Fy-V9jFkVHrfwJAMLsU!?8pduWkG zYPB}2pp&v=kmO+wfh*vmJi?yGY`63Tf+522ka-hexCx~L zV7*XOQ8)SoQ0@AnwpUXlw`pZWubS4flG~Z%9aYmWByM!P=)$qQIKzJ$v4m4&Mr>m+ zuqLuLJGn3A8;Jjqz6eETw`OMC$J{pnx$NXOeaw~#$tV3NsZNFZ^c5 zu2j@6Ei5X2kv+++aR~<(Y_ehzg^8W)tVucaOX=J%d%UL7p;Po;jx@5t>KX=yuG1Vq zWwMkdx$Xd;dv6iyd)lbJZdDZdmKJ6J;-j$3F%UJF?3};%rA@Hk6sl=U<-qQisnz?quxMwpK9NR}i;<$YoGr(>UY zve9V49xKVZFHM(unfWL8LwZT~L$!~sQ`CPXrgElpP*3Izn!WxBVlJ24l;~$&hf|}1 zx`z51?v0l0l>Za20B8kq9h`OE_whc3J?~T-n+?5*)()_2*Sdb~908mkbSHIJ5KU+r z5VgZdT7(_?2&uOgKduQ`RZUV-l$VniZu#hNHkzg|5xn#V6?8$1_n;)Z$4DRGxhFfUGE~7KVvBTG|ECoxj zwI6Z2KV5y-Vi2FN2>JQ8hRENB=YC?i-`^0$_(sNz!c1FrpEUzs&X|4PHGcXI?Nk>- zWlM*lSikw7vkV&5a`qdVXw3JI)|W)77}s*CrVXU4b40W)#nUVdTGmiSJTI9j!%ygs z;cC{YV`TL1(<~%tGofaI5HwhJOAthrjjB!t*AirZCzzO+{Agi}D7wMb5e6JV(rc4r*zcA;%!|IY5lj=iR{)8LALstKqMg~fR80l1G-#&Tbz7RzP{kmw<$Kc0VbZuv)e@F+Split~{ylQSORi611-|5p1 zzzY{CW;Hpl6l-p=MK!geVJp+e;rwTv%bf5SacFdkrPvibn9~-)3P1jZaT^f$*OOi0 z*_4TXJKOzey2I&>Q?xCMBVuYwI_0Wc!fppWN6J;PEn=LR19Q`3y@6<5diQ4moOZJ# zzd|9Rf=AC7;PHu8`*VEv_-d$TE5d|f`O2BDNaM>ePlWL2=!Np=!O)9|82N4UPAZ$Z zxYL~}0|tRM!6ZJpj-E5hzkc~d&c-CT6Hnhksyu6KPX*}M$rl0?pH-NO!F1TmX6=wS z5M94=UX9{Tzg zT}cF9Aun%T&kX*+c{+maYPTEt3#ZcD={a?5u3qj88Qz4w6Otzst?0FGCVu>2T#V>< zg1;uda{|OR-w&QO^B-}-|HiH1|G4M>uWk)VN>f%Sf*+os^&>?iY&JGKF$I;H`DCRv ztoTZ0Yzmb3v;oXB9OKiR_x&Ix{iu$xc+;6uaz=l)ds^w_n86%4QR3#J%K zsNuK>wi4Ooc4Qb4879$_P!wTSHM%PPHJ&Y}wo66Xsufq>cw#< zTn;fSp*rr&lUzgkN22mI%`&$Xwbc9SwY0iw*n=_D@nX1DGoaSme&2$}GzU;o2JXWD z5T9+I&$UC)GEskIr*u8kk@|xZ-!4PYM10splI6NSgw{+hiNn7}p5`?=o&~)0T1|Se zQh_ug_j+iQrI|iuNGC+VLX9PTDws9oK$k-rLFPe#3g;o0&?1fzb1UTdgFIsBMKE(W zjJo|(e_`=1G2rl%p%E-R1VOBuxB>i}6ImbXij_zsduoqpBw~UYv47Z3XvzE(YKPHuV3pMc(<=MC&W@twl-#H>e|i=>c$WfKB@M&J## z#1v{Km$Seev_MF4PzIsl&f235v5?q{fH;J(i|kVganI#UgXnOHvwj3SsBtJxajnfW zYdiAF87|OqSTOcai&Z^5f>&j%jUFqNdJ@r&tm(306c`-CP~y_rgy_x(w_h-1!r0Ni zUkJtnPekRE11FcHg)`*IYg3tLtMFYPzX8(lpWbB+RUWZbUFMq#)RTqRf511h_0ps_ zIo%<9x~G%n&ZeSj7?`l-D}N^Big_n?Vhz%8a=0t2>b@4sIH?@f7v@2f=eJe|@=Vpd zDUK$61&l3+JSEyNv8Y@co0EF;nYF<6r4a_&2Z1(m8kqyUD0{1RlQVZr{coRJbaGG( z&GGAJi_T_|WuVjQDI=3>XtpBL*PMgLdIquD-fJ0w>SykSjR`SG_vp^EhpnV%so5nqI4{I_r&hL`0%NC=! zm=0jP))n7_*&CQ4o|<_Dqm{%Ctgaz`2CHmNC|??gjjS>x2N|)<6l58^AFV8!4eWL1 zoQYtJLOmwMm@DxSmU)R)UqhJjQpqn&OGZ=aNIgcYuFS*Ky&QHEkXxV=HpEnPUfMR^ z>G2+M9ewsNynTf6St~ZEY1!Wd{B;-$ha9}gKMo@IKdN&68wZU4+neI=Wl(9t_9MFS zec{RBeI+6tm#qG};E1$hTqQO5Wg+fHxi zgO@1|)B@5>x$i+rFhRMbNWIFi^{Ia;bDmJE^!b8GX&8bWpCE-<)lQ&=TTDGcDElZ| z&ti*v$unDg?C0F8cBNnbPQah z^Y~GP=IH?fyi|R#+B`-DCxQqi@?$&3NN%Q%F;;*lW?S{Ob8M3cPhI_(%0}7`J7ygC znZ{nzZTV67t-3j6V><4pgCDDQ_T}OpWtOXb2qi&7J+{m=QNyi5@~$4XS}vsAy1~Vk zMYQMlY+8NZ-(N;zmx|Td3;Q^{X@S9i5*RCRo7Lb8cYwy#KS@gZ<#BhKp-11z8{O0% z?=UiGhw`WpSd#_0Ym_r}^YBYO!qD+GzIfJk;Ti}5a1(cz2aww87 z4Y*SA23#2foPC_LPS*+&WVd`|cYWd{t`bJ-B$*^^6ne<2U4&Jqad%Wqfi0qKvV)|q z$hOBGxiMj`zTo*Jxv$fPPIqa7J-Cu}M0vgfj!SpWu?M$3&RG?XXs*bXmNQeKY{C|e zzu~1rB|@d-N&BInB|60o%|dSw_FTgnusni=lHo$bJOXVLS?c3;@%!bx{lfO*Xrlar{{hTz?=b@>rk(M05XZLTXs~+CZ8b`- z{VE&B7wsxC)Gq9?Db!3f^V=03@&?)!FY*RP96BS>_7IUS+7${iKiU;DGC#&udZ=FL zV`1oGmK`PihWGgrKYiOEUGy?P1`~g896?8zG@Y(3vi( zA$tg-!_t`GevbX&7Se&fgMIHN*HBe#)Zrnca|O>XMKOzjwbn{+&e zSfk&<{VK^36GGB4Y(l?v^UbHHG{r%r50O)Q^Aa|MV2cmNZZrSe@7+uEuhMQ%Ka(!C zyu|u0E-7KUhw{I@_iV*H76iFoal-g+Q~B*LPo49I52>QlE+Y z9MX-C*XSu7f<5K&EYl3VQ3OM>nG8qUbk<7mr*9LBuPFhtJ?R!W9YnG!b2?H!1X)Gr z$|iEhWrO7tA!p$Wm6(Y=>x-QM?Mm!Au4G>(7U^0?SH_bOoRVkp7^ZHnTX_^|Dx{UH@vcEy-!>@}%T6wES<%~QqLo` zfTFWS#qa`!3)Nw-{HnMnQ|FN|)GNh^B1+&{fgvms8{B1cS$ce_Dft7yj~!)QmdXs4 zn}%~?k&L`PVT^mE{X4*B8e4`+P)8abazdG@6ek&r1d$>I#w37!cGCR3OIr@1XV(_C zQC?1?4J!df>g|&&*-tf20%B+B+@Q-yIB4CIL6jPEE)|p-d&@@a0=O#g?GlznRZW)M ze(K`p-Eg{8{(&|bpQBqnC9|2m!c-n36uD@>^b<~fFrr0w{#k$dbD0sC70F0yRa1a( za$5oFcga9o4G-Ty>s`xpLW5{J>|&g|L{pOrleQsoWjg!Mq?uz6J>w%XzZ9Km&1zze z@pg)7ca(~=$5(YvlO|laQs;NeG=84wQ`MKGPrON5#quc2a_R99fUQ~H;|Vm8tzqBB zrk-{o$@5%M3UsDDRA=W%>&VUHIIIZQr$ZS^#fJ!d*11{)V6~B0B~eh*#ycuuBv3$7Y7|A_a=0%(y>ynetjOj&)W(xq944m2S*Pbxx*MawHx_ zM;YC5s|o#Bsk>C22O3o1i?K?NDCsC(mOAGYwWm@aD`Io)v)-~S-|nht%UNyNHd8wI zJWlsZ`Aj4^RgEnm!+4caH=T|sp8il`l#$yhq!gc|)y;3CSj+Pewh%K|aJ-n^ozeGk zPV1T7Eq<^XNzKpQ9?2U_9Hv_)o;;L3r%>8VV^@Iv6J!0-X zd(<}!Rw9zEjnJ50$@{R{1Ze_}<=L`CitI8RiW_RN8Olw@?7D079Q`j72YvNc`;q!e zEn*Tz&Mo`!uQSL}e>4({YWL?`rs^rS^fL%+X(^1(QbA1ygzae5OD?Mzkhzg;1$HIl zO%Mv20#(pxpV^bVZyXZ8@L=`fRpIwWbzt#f+O&VNlf_0D+Ts{^i)e~5Z1*EHWIkC) z$t#=G2oH8PJfq+`OxiEKj5NeqCkh80(}_*`sVID4qM z5pjtqSaz8e((R2|wN>kCNgtV&&Ko3PgMFgLX?=?T0`zlbtk;aHomX5=+Aq<@)4tO> zPddg0bwx5Lon@T#Z!rd2yGzv?V=7Xjr$p>cy6I&V7p-ZWhbali_Mqf5Mh!~0dLzM6 z`0E&(L7CQ3?73hFS+kcd;W=U6>$9##u+ji!Wdu=91mPlxCp~hR&=70i+*0ohLP_ld zEar(NkK<5*%b$5b=R)ZS+wLw%^tGOs*zFkAbB}D?K@Up?uUUh>H81vY>+~E;;6j|- zhKupfM*H3JuY4sLu%gQ0(63OUMElVSW37^8u|YhhMBYwD@DZCMuvsLv14Q1%Mpu{+ zsTtq4h6+pT7=`R66Js-wT3WGJ*qXr)c>9eqyMyCq$WNnf#b>@vv_ks6R*TF-#?>kx#1-`lZOzfh)IEWp4fz_+L zcUpd0-Wm~OoZ$U6{|BQVTc(;l;U@%P*x!hKAwLAK`IM2=V&&~Aq50{cX8dQqgSi0& zWqLycV$evq2`~Kv3?K+7TS|xn%VGKE;sz?B=^2ZSV3@g*YfE;hWe(K`(C}QZ!U6!! zYagbadejtKz-Xo_YD}fe)_@Eyw%7%OZ8*FP37CE(P;0!*Xq(1bO`*HqLY8r>tupGz zurJD;R*Dl7DI^*VcdOt&_c$qm9g}H1SRpmWW`zzBXa_r5r)nc9&Yajh0KB2Af-$d! z_YGe#)Oeq#L*};qCiODw&>&l$S)~!}b=t!AR;wDIl#Q>Xl-DIJQnk5@6CkSL1Ydq? z!q5gVOiGPV>9Wy`_Vy9u!?J^=o(D`~uvr{oXGP&DNx%>F%lXJ z&RJ62S;MkUs3@xrcdjHANGlEYd2TYJX_@D)H%2PwrKb?}kaPFzP4>Gu#uv!w!x)Tv zhgsEN2{}(Fcss0liN!K4R%y)&nf{_Ig^{tgQ7h6hKLahU7ewK~2~7~y^2FO~@|FC$ z$O_jB(M>+Nw91zQ4jgdYRvQk4uvJ|5W{D>x5oK9U*D1jvRsjvjoqkD0l--w>?9hu% zW1cH)j}DuR#6PS;^dlI<$S>1!9iuazQTL0;gP0!L1h{G0#e!7j6u#O)kAAn6B+ z(Ho5}ludd1I;jPsTSqwG7(h+NnoTzvMXHH+OK1l}M};FQPPl#2tKeb1DR z<{F5yi%N)>#nZ>Dsv$=9P>uEQ_drgMwV^RiXP7E&eg%#`gQR^oaN`Y zj&-nvVT`j_+hE;}!sl4GpS)IOU)@=cLlIBgQ3X?8f|hyqY)AK?J3v)3FW{&C$8)dU ze?bDZm2T4*AEubFA3f(kuUt(3i6s6%`i+{S#fLY6n1%Jn_rKdtl(NoWQBu4p)t&bq zS=9@)g^aP&=tEzZfTxI&WeFHFp+>WI21*nRI z@~S0Xk>5W7lB7J$7LjG!5oe^#&c{0+)_z=^Pj38qyMph5Ur2cT9#+n^@1(uxAUq_C z*X*q9Tyd;EryxxjT@T69k-w<}ae*bFzvfp(gNFjC_|Yf20)D_wQn%>$2uuoK+hwGR z&h+!}u{ppolc75-_cQUa)CL5E0Z_fdrOEg}iDBHSY*(DuWL7= z8ta?r42Oa~O)`(CT2lK7%n0u{ zp`n)o|wC?xU4xroLJR_@<|sE#pIdcffTtKr38k#;1^=BB9gN?&gx^ zG)9+mIX5{Up&+=MgvUdp>H+V=1+=)2;q@7Z*U?GBn~Njf3xLn&Kw%=}eoy0@vRxsY zXKmA3HPz|&Zck=0bZ=5v-}_*hF<%ejwrLgJezTpsP?L~uK0c>9;v3>vhqEZ@c2s^_ zFt#wB+9ujUTR~$GK-5R|8A=nnVo&XcoLPj1LMF~Ef{&j+4q4xqbQheFuehx!>PLZ!3(xB9^>`82?!N{)LV(O@eP|8DrY1VCi!lV-`>}ma7L^ z!}u_iv2C^vszH>J+f<8G5PR^ST3 zsfk6EdOEjfuHxj7^yDi=#Gy@013^sD`Q@)uY$|juYx)7~p+f%CDgLLaLDbFO&e2KO z+|KUD|31D-T7bV;pCX+$`Q-9OqD=@i^_9MDS~4LCiMWD-9`Jy;<|7x1z!O_$?xgpx zzi($Svc3KN!e-R|1oMM1PL`801X1w!$6Y5gpC;Lv&AR?@y@PEcXQ!qz#4*RQGn(`< zGOjl@o88_u5co^cGT?7vdGrd@2u3`r3WQ)j3uzZD#Oi?^cRmnPlW5`Z^8hLXT!p) zCZc(1-7AWfS~4rXMFdffPIQ(;9LeaWYK!wOjs3fXewu34h?!oZhgV~GBQ>QF`A0KD zVJ^7v3$cpoM3OeB-q~eZt!X@&M?;aNZ1`Mbkznw*OraXT?iB^Q zqy}L&p4#*gqdrNjXBN1Vxk6L3-+nHtMI?6jo9sjOz#M%dc4F)pV(_;GR_l+oPDymo z;pXjpI(l1(0We;H*9AI^Nake<5#a7JMw#7WWG4hUXu8AZ2h)+rQd!I*8h+74<%c7I zu0iKA)c=O)6F)lB(t|h4i=JQmFD3~6gQ}MP0QY+TkqKh`hnwc#H7a6ZU~OkcqViFv zf<{gjcDDb8J?s2ct-Nz*F3l&3HAJvYdGZcgu?Ql5*>4Ji+*-scZZ+ee)`!VV&WFkIECT*+FQ}Sm6*LGmQ3z?+QCKS2f|6q}66PME0+wE^7lb7HN|##!n`R_@;QbKKi5 z$|kXq*Z3f%{MRDq9$9>j`_)+P5T4L+AN^L-)6|KFi`VZSTk2IC^k+bxlGV5!&xWTo zMxtf=N`{JP8K?Z7tLI-c4YKrnMc%SIR4b29W>wS6=m!c`O($-04I{CoZ!U??lau9> zx(P+tcP{zMh7#TisTG2zRR}L{y)s@-Oc~QR6IyhR+2~PDo z#TOb1xUqQ)cRM}%^mv5TI!IUx)i-YAhOst_4-%EP{Hs{wjP(q=?_FO!f>Fkz+z(=P z39tGpS&w(%S-ToosoOBVYoWSW%H1+l7Q_vpjQefziNYBVOhXR)1h{-X0vClxgkc_8 zfxJ?)e?a6<8n<+By~aX0h^4<#+P*=8edqC}3#(Anpvx5e;}+H-k=kcdl1hwAW}y^k zSm6`g@zZP;%QjO;GC-LNM)?UxboP^!D?hK_3a{wB5O+#}S2T>Wq;p`Ny8=_?Xu)e} zm2s-`=feJEpMOEgkv>ela39r1_c7c2=edUFe_Cyfe@`?@tA7z3yf{KxEk&{|$y(B@ z@|ma%v}&c$B#xA#TSN+X-bVBzkV81jCuCme-@f#NZ>Plwjgz6NP$OwrM4OqKO^u&M z`@TPas2$1hHCs%!nt~DFGSJU8TT;X!&8!(R+3XiS$nXOM?S{Ak2pn>S8pc2fDC!o& z&GbMfbc71d5=@)*9$9dFI?k5Bv9I`>R3MmUZDPabwbN_w^I#rJ&uT55t&_^Def+?^ z1#>K$Asfg(l-gVFu-FTcicXhtVfrLp?PCKdn%%Gc;J-h=;OF=K zY@UOz&)T#8>DMQ#&*v!$J=R#FA87;(I}_TW7TS?De&OtDMB1PU=#Pkv3@zmI+&=k= z$_s{y#TDL>LY1o?$wqRU(HB(`uL`#lb7SkaQW3-F7+zO)a(0aJ=Sj(SDrgo0umYmw z%sj1%2N-^_@QyI7&N>)o&VJ};@KW)GZxyX9GQ#ZTxPamZw&4b}8!Z%`S{6?pJf~7G z3(X*;E=D7qF$^m3;xc#{Bt7FC;rH^zD4j;u5Kn+K=KVk=6v#<)qIFF*Bi zE48UC@*1+2UqlZ1HjdB7I0l4Qwk$N)C~H~+^b}TZ!PenYi|0;uE5F^78@%A=e79AORby&1_7!K%uFs$UfNhiEKYrqaWwatnf{N9a#-GCa$;n)g z|L67Y4a$$U0jvU29c~)F26@vI4{dxwVW1TWp85B9aO&VPG@QBH55hiD?Wmf7o8Q_I zHPMj5jg3$72K7m|Bq^$e;N-vj8#pht;;w49vlfYsZtzH%=DH7BtEC*JYt!j78&)l< zBI)`Gn&O2WNLn~1-K~Md`Gu2zh(%3V4(bx>0wLO>X$F@h&hTSG)^V z-u*J&JlW4l;FW5RB!SD(a?Cr4=ln@eJ-3*7gOKy2AIb&-1$MP zd7X=Z^i;y>_%-_#XO?H}{%Rtpm+=w99~Bbyj}=1oKfJ;I9+K2vv~WMv+JL$-ngsuz zbhy+{wcnO>zFXxqu`OZt0fW9sU_%=-%Hp~}rM9%!Pfj{2WSHC7`1my6Fdp>z>hU4wVEwt> zjKKFA2^`{itb@|K+APQCIq&^}?=|sZ?>{V&n#@4Fl^K*mIxh8C6tqaH9eYU(!=HSK z0>htl$qd7vatQ}xC-GPq#7_Du)mKgWI{0?+E-q#Hn~qcYL(yc4X&A~Ng2e*dGECeO zOY;c96vKiCYGDpyk{KuF=!sE+q=1fVG@uAREVWGr5HeP|TMIUnaYe5J5K}mluved{ zz_`Lh7s574VWd+ka;)W>0Wib30^}EYhiNR2MFW(?Qjsa$Hb9$YD$5-!=@kTmKKwD_ znbdmumQ36J>7*KNT(!*9dFY4iI4)9$$47XiL&Oj9ChgK#lBe6UceS}J`vglGl=QY?S92n_eDCv?YDy=BQ z>BxxZi$uxkm|+$ZxeKScZ(!x#gdynprTW7XhyyI?NnV7{2Eeh!k*M910)lhr=i~y@ z^3Dqp2G**%$#!md<|@r(^s_m#imy5mqDPp26d&?_K&1?OFUsvsfOl!r4%0AeedI@>36)CR)BR&&Zr*J zj=mhH+Ayqy(&(TQUn`WuwkX$H~yQ*EMC z`)!q$$XodyAsWG!N<0g>h!(pVPbe!}5b*NhRy~OFcdU+MBi0O=Ty3-H>5JEuj#^u*B+J^_g>W8*O_Hj{j*7Q}zPX4J zARU1v|6GZi*A4wPv(i?G2J634_;{lDLhEv}U-&H}Mami(x@#;{@rkmdZ`P>SmNqGm zX<%7sFv7rp8+l^Iwg5#TK1uOsHIYh%w`BnI9tkv7oKq&rj{+5vF;yYhS1+B$hvhvI z)`v50x!xk5Do1>5#HFW`ymP^J7$u9eDbAPK6_X^zKigD-DHgdDLy=dU#{o{orQ!z# zNhva>{s<|VhQ+j6f-z}{HTIj2p^jTx2>0{c&L$~f? zDO?2unV^GUm#EtOB!C&#OgWtL0NzyrtA%IU+RuV92~)*LiCUitnHeAy*9hkTr5r+r zO1fqyc4>qXD8W%NkgvU@eT?Bwi_^5WDU~li)a=F>Le`j;Fp%<)hlz*^r&cdQfxGAq z3k;3qqR0aeFk}I;J`TD?UU&TJAVuYxm3M|;uSL0fjyI@sJJ1!ai}}r4{?Au{(B=(` zrkEqW@1E()t%7uAO1D-0S>jyRcEdq^rHmE9Aa792Y@VE({Fl%Ke;}4qdr>X%rVd|V zGJJr)Mg;<32S}-n#}QGEGnK3MJ+RV0W%B~Ym0dR11)X(E!!7LYw?(WqI!>QS-5Yn* z8CE-nkH2JC-cz* z=e-&}hM_uIby2d;pNSV1*4OA}HFoG~z|OHy{wSAw5lXFE&OmvTR{aYB7fl+O>fNLL zCksabqa4COSu+X|FaQc)3}l}!YJN<>B7nZ&^A~%h#TMOxMobZC_V`_-H+(Tv@f_g+ zM))m~C^bU?sskJBjkFVugsgiCE)`b& zR{PP{=vM4yPWv5ZgfEf>*Jy3~U>GA4h@w6FNzO5buKZfyiu+-BB*H}P=(sEGQOCCS zp{{7k`Vi)p@Xq6zmgXeTb-9tuM{}43c62^hYafm3n;H4-Aq45b-7m)N_3Q)zrit$) zJ;M1!FGh=x;vV5Acq7DkLMAw5PcLHE?^`FF5Rx70xLa|~>x`Nkw+5cPr6t*?nWu#@ ziX!PEB6u8&>wSQ7J4y)TBgX_DiFJK)r2Kc~SwW@tb2)1x5wKy9Rm?nP4{9yc!*z&` zT?c76y}o}I3UEu}UF zR^bFzVG6xq0V7Wit>76}L9b{1E9>SLwXZBr!4E9*ZyFNl+$9tC?s7_>I1#dktLziV z(RjKmzfl|fN#wE#o2weY_VQoIoE+S|{kK7df6?bysSn;@^dGrOhJTn)ByB&)0)r0} z$K~I2C5ge`bFA{J9I7A^FRwNvP(%N-f`9_uv2Krod`AUi97FqF6>o z1H;+=#4rmKGucdLMx$-7u?$aov#yR&Z@Z7|Aau-U8kXEeA?D{s4)a_SE!?_k;AfnC z4r}5l16sKij$lEYuR!a}g%vDZBXcQ|AMm_k#_xR9KSJy%%z9I@M@6bgfg>VaG`Psa zvz8RQ;n0anFfAwZ1qnBa&~B0=ZR(rZ_RQG)e+VA4GSRlwno$4~CXVT59JM=W&Rdkl zn~Oq>)xXBOKYy6nxj?OHp!KciT6EIzmR2#an7!5MhnjfPE3YX@uT{p`9Pj|XXrzSX zLSrpC1LxnVjSokq0c#~HDWdin^zHrTXm6VG-xdql3`GZ|tsuI7+cQnZF46PynsiS) zY)7dCjkeV_B;Q$O8=4byA9D(`mns<9K7~^sdBQtj?GJ>9d$4IKNo^pUElii2bjgii zLf&UW$(~%~>timX#HQqa%a)tQFetb{Ej2wKg<9psnP1G1Ya#3mSDJTJkW`~8g)&uR zRZwoCnByqxc8BxP*>DO$UXF(rD)VGy7hg4)HpDUymUKi)u@7jn$y}Hd;P$v>iu*0% zn$IER7+Hb(1kY7DPu{P1gm~yCjy@4@Om5)MRe1) zeX($8gm?i2gfuM2P`nutwfN;D1Z2!8`ET8#d*~YZ<#B8MCXzE#)4eIoz|j`#{{^7w zL3tMB5yi;PMVu-P#Zdk<4DyLJ*lei^`i6O1SPDKu!SnR5T`jpH!#Mn7oiF@HEb0GI zo&Sv|B`NCIeft0{!BKI3CvXo|5;hi1 zQJ|{w(*#ZW%sbdmxzH&t6Nwg+zMy(0_O$9w?ow};A9Gs7nE^(jJKrD2tabZ2rtSGF zGAWs*d*t`MN;pq`fyo_?ryzUdi;kC|(7kr{xX&|27GbpftzWOn3^(^z9oc47{B~WiBOgMdh0iPaJenO(ohN?3 zTTzP30ON+oKwzO=)cwrsd$`Qxv7C2!+>4zjlQMMSRo6jVo)% zeS2qquc;-3d+^h_=N3x-2j{yQRtwlk*F{!l2vQmwlEjV# zdBF)|rDrid-tErLKAb+`Tc+NE{zd}_9QtX8^Np^tO%U`5*A~OUx|pl#Y*WDIQcso5 z3#A_Q2=mZ*NcFxCQG4dU_!84V>$Q1?HieoqGlDsJ#y4#;VhMFb@WQDV=)OG(@1lt4 zUif7{%b<%}>r66pw} zS2T?8nx~8;UN0jkl6q=u>dhJ$ca5Sico6=pp)9pswFi#cuo77 z?RKGS?na}5_NaTr9NTqmXiw7P;%W?P1AM-;OLsOmaU6uXO*IF66fil(|6iDM{=L|u zz6efT;q6~RASjk`)zl`->G9^IDje$6ws?j`!UY>#O>F{heaZWl%75Q`XfU7awUD!$nr)VkJj(@s7W>Khd==MlX*7*ksFeX<_Y z-^U1zsLZiUr>8B6>G8^Mx)e*`U}c>qDVX=-X3rCNvqGo{ZD;h20@uWi(iR&1N>AI- z2pJsj@7e?Bui>h7s6y(WkMpZVnQ)Z74+>9suZw%pM|wcy(c&EqWFB?Jgqu)*i!(V>XpTzO4xO>VXa$&Hn*`( zUJu0GDzXYQuhEN%^m%5^6=is(|4AUD9)A6uD}_=Wn~g6KJadLS`Mb}35@MXtgyuD4 zTxlYaP(Z~Y8pwHK?LumU3|`H{<~%Gt&F)C_Qk#!Ms?0-Vi>2-g=U|zbOfOw~UTINw ze=TPqTbZ?9G*gaCL5GX~)9LccZF!;?m(fyQ!JbgMgn&=Z12n~VN<-d~YOpFLKFu0z zm2vLI>~icKa;hgwka-MsVop;gnQe3MclUiQV3u`0zXfV-(zIB4>!X2NViX?ljokYL zZrYMoPLuobZcZC=6zHfN-HR!9f<@op-;|qTp^wyka5~cf|6bhO3#%i95SyM)a_(dJ zhwFn|@Z`xJX9bh#C;Lrb2oAdwSACIF!474SzbiMTj~zNHo}}n3NzB`+B$0ggtOp@a zCFZx$F-OK^9yjvfhsg@>Ni?6V(~CCOB|fKtF9f^-h#?v5@Amh zh(F%kV!*$V{nUS&)UA2=t?+Ql2P8K;^0V6)&fM|7bS>S#kB~Q%#SZ%xBxnb6=f2d{ zn$Oz=1>2Z1+lh%hLLD-*64?{96@E!;{CD3FZ{yoc@KlI?D&Ho3$f-hm$MflyLSd64 z^7mT1i(lB;v=rW4&n=|cP?3Ckztci|o_0w_qs*>OX6N0HgQZgTND6_VfW*r$n+8a?-LJL!11C=?!`X&Q`AY zC-qbU;ObcR+GL zC!TU_@g-KnH#JXurCQAG-ir_sS}{%K6YvoeYZlm@eaKzRYBR-6U^)DzqDHK0l_{JB zLHetC1c`FuP)MV|Wqg4v)E-y(t=fa1=uv;mpHR_ixO&lR*{$v7`G`l>OJ6c*&aOB6 zF31c-ge*14OSlRzbr({7;k1lIB-=yox){!KKUyU;?s-&qe)N9KJ-2$)Vm=yl25p7& zXkR~5c41Z2JS0DNK>!kgkjCh>=#O2#MQ`mdcgCFsMe@@&dmtSSUC1rQ0=3F}m}LzZ z%Kl|`@alp~3^8QxgN?n0^Hqc3{z?@|%y6k0E@g>l{4~thOW?oSMc8{yiSVqTO^d${ zE_eH$swS_yU>aM~*=RwkoW!e?W(Z}K>>C;SeMZ9K6@K}=w={&M& zV9z9R?26q4UR+=7Hw(@Cb3H1u7#9-WUQTDbkW*?eb@7(V7URmkeml?XZV3Kvz0;;q z_)hENCxbo^TRFyTV$@a!i=E(w!W|t2`B&eO4`x^2ZR9%_KbT&gmP2fT%)0VAeu>6;A+ zDM@?>#z>q2ic!mD6UBVLH#xFe1yKYWP$Cv8+ltfeavU|DkB*H- z&lhxm^0R3>Ux|NlaPb|r3`-QaZL(-gK$fs5ld?h(xeBMX?t89`ni>M5jh!2#^u@Jq zfr=I`1+0FHS^l=JZ6wo=TImY1R8qp*^^u+TLc_Qv<3n%r#qA)_m-;sP>8p^KW?l>+ zNN&9Jg-|F`)=GF_rm40`7eOm{yFhL|>HI#u7*t@_Sv4nV^Zm4h&ZOHsn4D0mu1ZoDVh=~-`#u~Qz<6o?t5mFsBQ^^ zre9}A2%&6z-|HjGb?;jutF)JKL=v7ptZ$@-_H74AgWS(3Q@AcVnRu5GcJ|FNjc34ndiG^g!k^ zQ#m$)8odH-d4q9(i*;)o^WAezU%UtdBdNS6LAg_n>|rcMr`%iTm~?H=DJl2clTUlQ zUq&S0JW7%$p8G*CD2c!`>piyWb$l2XF|;rY*~Idc0$Qal10aaE86XQNhWBwsq%Hff z-@1_!_0F5ta+9(xbv!dvA@Rwv^XV|u7jld0H_=Cl#_`7>sbfCdVAoiKihhAN*vE@Q zl1P#gIu5@{RFY9^-)}XJvxA{4E<|BQ!;WYs)z_w=mg*r_mZ;`z4L|+K<^+=b=_j2Ux>K%xe)&^DgSex>-#s=JRLyTeGS;^|QGJ-+y6j2oxTARY_spV_SL&wf+-( zX9(rU#G?##XjIrvE>T2qjHGF6e+YWNuJW2su~4pZdz6Ls&5*&Su_vF!zKg4?-W``( z)q5zFCKa(egBsvB0N#MRR#!LDJ7}76x4sINEn@ z$RK-TiEjhEGgz@i`tn2lI=(loK-ns*WAI1uIO5c?Te3AHeQ!7nNA247qigtxcIawh zU%QyYEY0QmooKA<%6Dr+EG+uqIqeIi<`t_9&;1_ex>jwIO=1`N&zvcKR6%Z#Lp!Fg z#?IxxjjrQE$)s}ut?WL^$c>=oXQWeCS?-rmY`!RQdf}SgMio);pgl#f=w3131qOxB z%88h>2yPGP1Zx@Gf|%WEOWXEazW6qnMLPKwTu3?}hiad{Mqq(D(9NXXZ*Hu1!61c; zRU2&&d;fVbnx+H!S`T(FR>wE84*?&M>uGA2KDNk-MW%3UAu)1PzIgrd9EJW6+m!Rn zgMAi#*1GhLj~C-V^2N_1_IAi@bTDpwK*#K~2TjX$?ez!v&?_6bp2O2=4hko>dZOq zlS{>9HE?~`BrqI!+tY!}wppzVg#JgKR`Ep-_VxT=e{9aKY2%RR2~ zgsvW3*SC)Cg$7?uvC8H(M!0S0C4{}L;w6L&ZdOY|yQ4LpC2v`8C=XT?P$JJ+;?ULQ z@+&bbdTj~3x_HahfRP#Pj?_4#yy`>*yaGx+qA}u2UZvnIzE@|H@V7<1+EK60i(!11 z9A`;boy^27+UD{ab4->`@011e^wei&ym3CSYMkvdwDPsc8V+X8aZz}M@;qb~Q=>X(gzq=UzrnMh?LMrj zKDVnlE&<6N(unu8Y)7r%FPZ^p&3-VDUC?hJgPt_+N^jtsr= zj2bpCOs^>yr4;!)GAY)(!Qz6N9T|iyX5F;II*8V|AJgvyBdzKM%PV?`-(PoBuJNz# zqVulqp`-DC^3EyPSS-aM`Gf0+kJgZ3N?Vqy^bZ~`aw*O@oNk0#oMpGh1zq$~kXKcL z$s*_7*Uko$J;KMD5-zZ7=Bx;iET1`}kk>iX}7K3Vl}_UhWDVF=rJ09#>N$M1bPI;EoeIfzoVa z_?6@PMbFB8610Vh_dAs73dkZm*Xzjx6EP)dw9*WGTda0WTgZv97BF(=cV9?e!pmC0 z?WSy~qikW3UB6$ER^>d6o@>1Rj>?sv0HxPCuf#RY8yfWTy6W?R!23v;xOmPMSuLt$ zxC-3P{^&Qiw5^yr-*CyKzZfGl{-pV(D4yT$g_TxS$V!!^y8}{Is1ly9^w>+p+@PM*vHVd z0DhEj$^`Qq{4$RI=_ziHucm!7zvW`?mZ^g!M;ymJ#V=*!_P|36vyh`e)>-q>d-nIF zan$}aj)En!d7XQn)6UqLQiRfUNi&bLFQq2%zO`B$zS#bHxVpZm z#8x`IxYQr2^~{}jugT|$1MB&7^_Z_TWn5%wv!^D{&pZsk*ty?zwcQLu;qw}5Tk+?V zoyZEtCP8_L2O}BOA4A2R5~I^4hMD(vRe5n1W2etUkgKuXFP)G0#Pc$Y?a94Lb41Ey zi7);7*M%hLZoa9YB}rUDv9mRqwjH4AuoL+dA0ZJ{&Bka)Z?IU-8|IcqE3wgdZ!GWT zTBcdilHW`oZ=Ig=w{)sOYt>z8^>*&I@2ieRs)VjppT5U>ZZO%Hl11=dZfxI+@a(QI z%ks1g3Tr4~qF?i+mTGo5|IO;rE2f#ecGk*UN$bR|B-O?~LMg-f!AM^_5WdklQ-8l# z5wRUCV57^XgHxNo5>nKoUR7@ypVCvWfofTsc+16sTKulOvHBvxKCV_&1k!3tLg;=f}}Z{R=QoHCr8-z zTFe59WVAT!o{GJZeZXAI`2^}>o>=oPlot1Fb!cp|{C0|<_>#&!TJf@%=5>u2A27-}+6pc*N-reNdk{btGb=KU z5?JI|Bp&K9$3*q;bJj+;s9C-;Ys|B23O0L@qo?fTFo+vc^w1*BQteTb!k!whnTfH} zMjBJ2%*yje-biNpmvOig-0PGdI#S`Rja`{}XyZBa8k+>Uxtw0b-1P-Fxb$$3Tdh&G zvNYfL<;YSdMI9f00f)9tkT{~r>oC?=@=~4!6v+yHCL4urdhsH1ECbZ^6@{5O;w47J zxhg?b4^tRZ_mz`V?y~8SkzXCh!dwWav$>OeU#}HgPny1TcerVHwPfHEUtHb=appv( z8-sqP(v~burb-<3xFYOwsE7j)dYmW+Wy4Y@xlQlPfgK2OVBVQw-5OuH4a}yqN|jPt91Mpy&<*Tl})EtM*^#HaAjK96!&v}C{) zp5@ym7)K0sCLm2@M9~vZnM2zRpuB_FFv&YO6DRSk{oU?V%!ihWS@>rB3a*gPE&Yp+ z-)=xjjMm@4&t2u-xr%ts!NiU|!~v;?E7Txu_JZoIM+>nMs47-SPP|fTb4pFB>>00V zUu?Qs8f5l79i>nmf|AU>*4VzFWIz zgRoN2$-RgP^9adBaj%8oZgaLxa+HuK87@1oY3&MJ3)NUdzx#k?Qo@C7AC=f?q5<_W z1!fkcfR6m-ybNz0@<6+B$v5_RpGT}WNI2|7S&@ zsTFb_W6PaqCH#Dj5%k6giNZx4kM|Yw&+?n;Rof!zh~FEOsPYl(^j79h;woAyxa1mS z1&8X_4DzZ5x$K6+!?IaRi@-DPp|LeaH1<`@uoj)$`xckU<7xqF=9+rTgRnAMn) zYq#M++OvV-^6|0hQ$o9YRldeq48|7glhO z6%QZhB}3+Qh6TbrOzuRh83pR<&bF(>73W8m^oA>-;W-7yH&?A4GfL z6wBDNyk5Lz!RP|NF%otqOqRZ1;%s=y)RLbhcqW>?|H_Q5 zX7Q!ITC*|bfOE~aRdq7^nFRWoxGV{<9=~li9`G%Q-r;nxY|_U}-`#8KUNe)IS0__& zP4vBe=4)bBM}A(yN;cLmi<$>ODAH0+6W^ zjnakup-R7s#bos}0)ihb8mp1Ap7jeEuMSWuFmGuU5+~=zC!gW?=5}@TIbw0D_ET2K znOl7%qjH)rwWyc;jJZ>Zm{XB_1Cgnlm@SnSv~-a3ZXu@t0o2>iHkot5d*#=8J!!Tb;)Qld zMrYtnb{eUbSmJ9UUDL1L^3mfCbW4Qv+1V~LdlLrhR$`@u=%t58WsB0feK2W5#&|0b zY=`oC3a<-SJPtDAGp87@__Q!tlCMQ$6#VPWo{BL9?)P{>B3jw$wYNK*v5_n_-vCL) zl87AYNJD?B#}|?!O~@bD*IaRJcBH8Sw}n{MjkSJbDDH0Hyfd4J>O2p+2jLQ$xYIbw zCUag-zgh2#{?ugk1w?;QHE%6i*(}v?ZHI-%#_{!JqLeoUYn7@KN$k21!!*X>HV=6b z$A<$SGRRg|XL_!($3eJRHqTDpXEYjU!Az;)=e59JlbNoj#9J$68g{{7yY@JUghnWJ zR?{Hl?QF>hk}RdS=6o65s~C4AG(L`|2vO*jo_E3ls)ZT&F z*51YzYVT+Ub%;`KwjN?VUopo>&`5p8l3wnEXcy-_^ZtNyeQZXhUP>EzI2t%;@pzKb znfp~Tj5oq$h;MCZE~A^=-rQXxSuQYg#Z9!Lbi$C)(kw*I2=dMCpSp3|^>&*TVS!9+ z+@?Ns#HFOFY=^h9%5Ce+ta>ztrKGx%;PANx&!_uR&lcVpP<^znMIS5id4AJvs~v-~ zhDe~On`lwb$kM~Pg3IRleQ5^xyRRGRR7mk98m3n9Lieh=@HHrv#yNEs{maLM~4W8=ju!utMnoz~Qdl$zTLJ)?EIC-}YtJOWd z{OPlF8!U}|?{4j)hV4l9$40ku%GPfpy}-jmNJz<4p+H>rP3QD<8J-QxzP%c0q?O;~ zoK(`st^9)%D@A4aPO#Nwa(mlht*TGw#;X*6-7>CGc?yE6FHYe~F54%9K&`ioLb@gghP zi&T>W&Az-3yZO+xhMNey(mf%JhHO5rYD0hyETFrATHL7+sHJHV13AiG!yN45of>fc~YI_<%rgu~$ z2FKaR!5WR;SC6MR7vkSp&%S2uYtgidg?8K>Y4M~At>%ztcsO387?hFBp@H`ehdjT^ zo1K5N(D|ih{49EzuQxqwqpy?rbPgpvvg}%zB`GK2%ynCaqQI0h8kD@8$cyuP?OkqY zjD^u|3K<=&sE@g0lAnH~SJXlfcf0epw~=DYlI-<{NT&uxUbk5LlMZuux(u7AqK5P2 zqx*vMQ8w^{+d9T=Sv*gPvC666pOu`IZ*-WV^(67($LTGj;NZdzue>RV$|qv+$}&~K z%NRmv(#|r3p8SREw$dZ9Ma%sFW4)Xg4@pC0Cp#pC>!;tc&LBNnGSsE|Y$76dYf|mW zCn+ALDa%Sp70oKD^KWRR^IfX+ZlGEgzn`VnL%9CTUFl=${+4;Op}3>|{NU=|6UPBIA!@y)y{SmO%{ z9tqDj$I^(2Nn(D6sw@Sq5Pi6? zXJ{f8jpdDsPUS*eS*iDx84&L3yrENB#+UeZd;46%qw{a#I=8%6iEgL)>Y83+dj6T} zb&d%mFei!@sZUKeYvpR^N9?E5*M$A2x5=;V^3B)qz>7{q`(iDi24UnmL|2@p z-bGt4S|jvCl&qx94u*1Y;l8T8$$+Ti(+e5M41;g4{mkU?ZL=6>j78Py*Aqa*k@fV3Q+~^qUF&1~rhp(^Rts5rZ zA@1f~v47M{UdJlwtoLPEBP9gxJJP|t%-vE?E)KjA?%2H@a5p!c71Y52Vgmg&69%iv zISg^1uUynv3SwCc66KrUP~>rx2&aw8g(aBH9(S(&~vGw=ogWc5;V~Atdi;UgSN;_A*xR%uJ43uB$&zhh{S1andqoV2J z?y=Xk_`1*Lu21-^*%_H>K6A7ccFVgan+lHQ#;-3LxwzjTyPJB&Z}P#Ft$U=xjC@)4qJyu9#Abr~OdbgAkIb>9PhRcoEJHKgK9zeuT$SUW?mTYb?a zn)>XEDw?THE>+b0Rz2*Z7{%A~GGwNP%ikJp!l`ijS>i@!#NE45NpLlF_cmKyce z-)vk$x*NoDmbtP{L=8_?IE1bu8tsgQ&!GNIG!4YsS_bK5@L&|Wu|ghE{hEIC)je5F z9lCsj`vM9T*$A`^cn^&`t)=oAr|8H=aSd0m#f!hko%gegY!Pp!4w_>_*JpbWVYXymoLQZOmqfyT5Ue%kb7xNt)+k{l;=E^utwCEeC&^ zo?$}9pp>=P^{>4A{VH9ru++5J`Mq~yOTD>dyG=3mhY)EkJuri%i-l`nHZS0nPqM4z zcx??wXS<18x!etmHx<{o%5`39fwt_S{gk$9Ov^Qu@0qp^O<(ga$muUFk2y<5E!h${ z`VPd?aTMlsCXL&!ay%34%2iTq)mKz%Nd5kHA2vG=gh#Xwaq3 z$03vXyEp8d8FFMIH;43PyHJhe*eBLPW3?BW4VgY)+G7Y~=ie z-wHR6%fnxkMg>n#Cex_R>0+DE?X3?iv!gGhO7Jf%FMTW3FI$BlQN&!?%d)_U9kP`U zT`pEri_OR^A6Rc8P(^p!yi=-WKJRxWR_s*_=Z@^zhV0nrja(GmG8;dJn6lw-^sPSP z(N<>!nYTq>?)o~N)ml~HgvX;JGRm2~dwGA|W^UV@#9-DM8{v)fn*=7;cYGC{x`Vb8 zi7aJZrXAPpE$jL{ghi9)GH#RaT|=9@R~^MbdGWhA3sDox&|J~T8Pmzl?>}x3sGi=7 zi2++g{>NUHd{E^4jO$xQ&|m89V6`FZA@TDbTN>!&F&FaaX>X7(_%WM4d=!`Q==ytt zpkgc;dr9lcVd~p42Gf_4)Hfp5(c)5#77b{xj6dXcXq$*ji0fJVz=l4h?>O=qN2LNxw~IFuAJwkl8PFB?o1fLhE$lQQvPjKYi)3alf88cyeQ6Hf>w902Cc_Ge zyWXIOeVi_(w^FH9+&eVQ7f8x9!iMjHd#;)>p&kUdl2#N5@XP$ZL~+lMbS`UlN7=0} zLwKuvv57=WDWtn)YYL?h6z1ef&lrM-;B>QldoP>y%4=^Hx_AT12oi=G*Z27x!HYUHd5ctI@Aa z)n?07rKb_G)3MVH;JhfMU#A{04C~bWzS0(shZ{&U(o>#DeUA?L#S%TZ(5b4hxa#AV z!QwCH21+1H0bG3>%n5NR*9w^8U9RYCes~`5+`2wx%KG$k1zOVji-BfORkgQm=L(5Z zp9ko6EKT9|E*s7}k*No-5CIW?VS_!s`J7msK*; z@V$k=0h6XNE`stWSY5U#XJ2~=UFxw9l0()N2jLl1cebr+^*?RUedIP<8R_KXffd`98ga>Fb4 zSjRHsww&vp2|{S4oCLn68TiNs)Me!Z)n9j3gbK~v>Agz7Na$XR-78Tm5|YC7)lMAf ztnPF)`Osb3ThQJ4QZ7#H)f&Ow$zvC9(I1NAjj!Nc5ZZ&dchUbyRt~* zu^o~jet$E>a1pt)V=LCTK|JE?hSy|hu37Qp2s>J_N;gy&)y%->p8jRF(i``8@JW#$ zbM{V%B9o*&i z&&L%=^(PE}ZFB#Qzp+)*|k{AWbbz_D*aIJkp5hyM9kVH}6-;0SR9z-ERHEGqx| z_3*(*N$m7h0JFA%!VuQ1xWHGAR?06Fl7Pwv7~JY`hA&<04>rNO{&4Z(;0|u>|L4O- z@}~@JVuy1mu6Gc91?v9_Ov~~Q0r>49&2bzDrWG}XSerm^+=f~^9u6*`j6pQ~*?`!#-RSEaB|A_ra(?gB(El&yc}ypE!;~Rrk9UXo<*+dr?+j2b8w~7QspDYfoE#5E zds2qNw2H@f1MtiMo*xE2Q06#zLmMkwh&{y7#@>PDN2vVo?}v*~g)5}@8SuyfwZrBs zOS#kX2s;=;t&PmAO%A7s98Fo+0Tl9p0ydk}Dx8)=40=2VwWS}SFi;g5aC2BAUs67f zL(Iv_%Jo1`hYvmPeLqqZfJ_I;5H{vZRF8wbVeMoE9zb@48Xb*&{q1mP2Eg?JPdS66 z^vmak)^XUf5% zUq0QY$H5x^xVF`SMbyUnHps32T&wqc_$$91;nM&HtNbz%*ffPzC+Ggzri`}Z2| z;U;~5-|7o782$(Fg`JV>BTr)Zc~kn~$XQ}Sm*~OReSxRLW_G^l(;$O93!=#p>f%VH z5c`Kbst|jVqcX#l8g{9Jc{?4@z_tLqkN=G3 za4~A6zHwFo{6T(9o*FdurnY8U~^7d(n-)#)*x3pu!~WN z**Jme{P3}Bqkm*BIdCFi23RN3e|}nm!;#Ys)n9!9+6VyXu+@is+DXWk5LX)~M;6&1 zKMsf2yyWun0f6=e1BdmUcj>2u{~2b-(PVQhZ1Mt{G(aN^W80z^e@OFJ%77XjM@J&{ z3?mEBhyY4hsdT}AKD2cGUrPF0X{Vt<)U#;J1lN}=;r-KY!Xq5yKivXnKPlI2Iw@t2K`>O5Lw z_V#E%Nq`9)0k-hH^Zw6S4wppG>T9zlm||DKObE+?)O8Yvn3)yS+5t?mC!{eVA+~4| zpsj-&3}C17-rhgpI9vda7!^r55G~T6E`x1A6#7pD|9c8QAG95QCp@JNdl`xz%%7jToq&2UKUU+5Pk4iLf??$CNj^L-LDEKqtW9YgZhg9)P-fWqoR?dx%% zq7Yk%ff*=bj$9Y$eo`h~43MRPreP;(o^Pi`Rsq@o8>ELj;0MWlOJ^`_E)YSm4k*8O zG=UN58ULs8gLX{$$HAz>DXi|PHqiqa>;MgH4MPWa=J1IJ*z*U)Nzgh4Q2*P9jz0U$ z3D7@h=mUzsUb1oc=(!4rI}pL>m%tZx^u7ouP@DuE#jrOM3@R|{e>F}sfbq~7`KMxp zos7(Ej#K(tJX-QWb*Bgd3Dzas&YgfQs-k|JLf~5Kzf=8<4BLHpfxtR;)c=_C*ceqE z#{T>H+21D% zEWyus8)$HFbr*j3Mn%TcVjmu!Sr=VpYeB`NivR7SDf-4qH0scU+4MLe*bI}b1;PAu2AF{d#su8*N1%hHFv}l1Jy2sOOH~^Ss5Mwg zv8Vd++u?R@)SN3p1SA3=vS2H{ex*MnQFc12VP%nHrlSPjp94GQJP4?101fN(1SZG9N3+jWcVQAu+5Gg|$@HlY}Rhs|I}VW))`fjF2MsyNz%WOld= z-FFvu4%YZF010d zIt}pCL7r!TaZS^>WAVW&u)q=s*mOT!F@nw&C3s+VDgnU?n`WLT9EU3hGQcszEsZ_1 z(FIh|1KLPfqhh5U0c#DpZD#VLGyPw4BmdWbvN^&r?Uucv`@rq3!L$L}t4idYOmYJF zkYUHGA)x4kMO4^znv~pAg9Do$e`X^Q;=yDMSnhx?Y&xFK`x6#1GkZ`f0J_7ioZad~ z2HX(N9C#3HqgnduPiT%g_W*gYbJGV%Q3}4W#&}h5T8blAv+s-Gx=(`gl~myOod2ls z2=KqE%%6>>BB(hJSIu^P!-X#(Gem(Ppax_A=hNPLEcDTkd}BM7dcY^gK!XDttAt=r z=g?g6*JvRwPzM%a7qcVg?j-MN`Uzmceo(`}=9re=)8Q(E&2p&yQHj1Hh=w2z$Uh9e zu=p55r^7$q+0S_9YZ3!hEB`AABMqO7uWDv!L3Qwls_RixNrhT)GP;b{qLJV*m9#k{n;KnbXy77~7fBN8oVSgF`EPEbt9*6Q`rs`L)AgK)|^Q*rw z!NG|y|5vWVrHUVmZ!`vOss-E>wyJ+|7XCyxl?9ty5c_}RIh>==qm*SG%mXih_CW0Z z@^L^t1&56Z1UzYFYGr145)p@4rt*O>fuQk+oyXeFA4_x)#z$9IqO>=s56-B#1CN5u zY7YsHg|&p5fLL>2k^S-WaOFUHXCAx-z}JBRU`w|laKYR$dEzIyI>gcmdK^P!joKz3 zh`1S$HN<~WJ{%l8*{K+Q`tDyOR6qZ!;%a4J^Y@#$e_w7GHN-Mi1AIfEQh{~g+)Mw3 zQ_2x~#92X?X;g+-P`A`w{=LYsruq*|hZ||NRs}v8sBRp51z}WZ!Eq{*zf|{^#(sM7 z;Z(NYDpOE^wHE(1OS^EMit4XJZpS%!~idn~T)L4WPQ@&o#S<8XL$1g(qKV91pqmB7|7zTjNsF_H2s{PD`C zpkc3L0>PLK)`PFZ*jZihG!$Y`V~CTb;}1c8G98`en>*)?0)Rm8K+1w;TLovyP8R40 zw!d#<|2-s&quGQ!fLwK87YcU%niKo)Y=@i5$LGF30jQ-0z#Ik}FCFry;rf|kU=(>c z)$Qtdw?$yGgR@nzThU6O*E?B>KQ`D-!BfSYUwzQLF9T!2iu7FfG(0L`eeIx$KLwR? zs-yon5UJx|bF!)au~Z@u`-7Q`3jF-(eMeOoEzR!`LV)jm1LDBW``OSx<~YLRl3vo) z9_&AN0xy7_+7eCwl;d#Yd$&|sHi2}I2bO|h`!gE*(=r@r?C+WFh-&PekoXF)F`WFr zbfxb4=PZXyf>Rl=>xUz0 zYW>|HgQoI??ov6CMUWT72O*g8VViwAztd42FrLtlbMyzIy#q_=^k72`)}!8nM0y%| z4oD6vy`z?JsDd7LwE_|B01IsU^XbXy7>@U)*6WcsZUKvM0$+k%2P8`U6a2&N&58Fa z<|?BxUbqcD#XIxmOqf+dp z5000hKxeBU_+V>bw>STl>u?2DPpy?n0jc7FR6;OjmwI~|CNl>^d#EGybYc-ugbRHH zL{Gr%1Z%DRhW|`?i_PFpxOg6 z!M6QM2&bWvu!p!h7($LZ6M*Q5T}}&}w;#lcD9q&MiF_J(l>=y_gCm-!l*dcJxE(O-^T@J+gpF1DUBTp{- z@t|F82139tmek<l+mm-w!*<}y43ku7_)f*4Vrh2Np&eV*$@_gkO*^1gfvq4S`A>xn)bs=XXPtLcgFzcU zhCd5}g9z9ImZ)3kzY!g=kTWlqFi`*&CY(rrH$0`-eaqoj3kQmWo#O?S zPfK&)XUBKov>(a9+i>CFlt7mco3?N@{+#7-N$6>cFh#+p1P=M{t2x`+r{OppHH5b0 zlPnl@99ZpwErP?%jzv|5fGZ>ZS{nT8*ONSpYS@iG280Hf?|x&Fu=|fpN4VDD1ZL_% z@t_Xmf}IZ~9sV2B;kt8D)3RO!Nktd;_s9D^Z=aIqaA3vSJDSZP0Ik3xCv1IP=Xor! zh>gpSqzHa$n3_3QKu=t=y^n^6oCK@_3WeXOzJe{6Vkl6|!ENdW8KCkvfCF~m z%Q;8m-*B-7C*nj+ZEPHlItCMTm;DVI0A>bSfvpH1<(&j922O0+m{6$!aN%RlV-@q+ ztsbTl)v0?FOP2|aYkSId_h3rvuO5`J4d};O3!$yD{{4eCEuTP20 zakwSD($0iQ1NUnJj?M6^F5qfQPltRs?yoO7hh1O&Uv_1 ze|`TVEIM|_AE5vJrqAEE%71;W9W1(k=O3W|{YJ;%(SLnM7c6>6&mW*4@u1JI*QvvH zHsk}RM?YNazuu2c028B~a{wEh+yE`tZ`ZT`F8!~U9K&MhE&PSy{I7epf5-UsYFeIZ{s#c|{!B#~L@*hG SXWGF(rV3zJc?;xHxc>w4y=$8Q literal 0 HcmV?d00001 diff --git a/deps/json-20190722.jar b/deps/json-20190722.jar new file mode 100644 index 0000000000000000000000000000000000000000..6db21f623413dc643a66ffd6f9eb511a21baef31 GIT binary patch literal 65003 zcmb5U1CS@tvf$meZQHi({ncQ?M>?^T>aL{(Vbe%1p1c)4G0WKUR+g}URptdQC?U1LgZ*cxYK>7z}AA|58-8ss@UOZM|6om2kMm#G)0{q|fgR%+ern+~ax2 zBky)f1gk}yFwx+=yU`rPH@8*iS*<=4ibfVgT^%P0Q)wTpdh1@pLB8vcp(zWd06^0Y zU8WLuC+2PF-jIvH7aJf_(ky5G5KBU>_p0Iq1?0c$; zZB5a%@{9=}0JChF5_Rr>xeUTE*NDUqVnLBD4lhul4gy-S4}?B%%yvdOBaeXi9Xwl(rQxo{_r- zck@IbYHo8)ypTcBCEAxuHb&*PLXShDGhMx20ADxcBFcnN$Aa#|d}Q#^sY{DFp(1g| zEM4uTE{;!U^38UUkP=JhTCL>TE+kcWnN<-x;hF~^C@w-vilkSr=Yw|H@uUX*yrkwg zIm0%LWWX$ebbw7h)Ko+w9qy!}L6zj9su_SJAVe~gDN{yBvg&Dd zvZxrpMU(6%kN;Um;gM6Ns8QC`#Wi+$@pc)rcE-837ShzJo-}cR$$Z@My!1td|M%kP zxMcqc36O<^;%|{mtONl9asdMZ0{m}#$M~=I4*l2m|I^+<|9%Jw^^e`~SMHz3|Fa-aJ%gZ&P-sGQE?7LnA!aH$2B_CCk8o+u_01PwU?Ss||WM&)Pc#L#&`Ss3EzcFe$PUhX_ zp~BAST=nPoQq4`Om_<^RH!}89Iz`6U*2QM}Ov!E8hp;KZ-kl{qUrOD_#LMdU1n=Xl zLeA+)QEJPRd)J>fRp=Yb-8EHzj1}T9EUC=(8GM=x%YxrdK4jK-lZSbESb!w~kw9ph@_Q#2m5C-O+}yh*=;fo6?Duw6Dzt@_;PpxrEy^4JsIw4TW$% z2j*RLh36p1Fl7^hm4Zv;DdPw7bd!~ixVOinT#21aQ)i7Yav*d^^5n&OPjP3OWyGgF zQu$^ATrx4Rx$9G;2dQFBa>pJBgDT+sL&k1cNKpffXxipyo*Kd*T`os69*0Ief ziY$m&*aoc7UsCaHF%Ju=P&2@#VQbSB74BS1EvakjDVFQngxb`QOax9Cqocc>QDyBT zs=k*sIj>yAuL9^i4>yYpSCZ)&)Y8r2+a@0%5N)cIrA=vMX~B$&@}aR>b{c(j;2@KA z7rzHP+o&-jmu;H=&=ewBqiojH`z}bT%#%o0)92?K@bo>?>3xTkz=N+PA2hbM*`yHs z2yvv3<_p#`S{sHrXj1=m0)$eoV6C4q&;5lSea3IB*&vK7`5|oZvmZQR&@lAs zG4xQYu^{0hMwF+k3O%9#QimJ!f!rmcbNE0`(tuO)TDDBB6wx%1SQ@ovRRHi6L zMD!0*V6K!!(I-0}ou3-n!F!7hkY=Du+?O};N@gV(*V&XS$i9ke`N62~cd6HBOA zPM=90evZ-t1ui&poe(ogar8K8$X1*FsR$q!JC8f5x7R1WLo;u<$N3BHG;_$^ce58M zca$u}TMALWX%hT%)vA_~G?;TqywAH{g5QwGIC+h7wpmyVIf)>OD8J^n!|@4!0D442*7imfQ^uI+~u(=yOfa!oTuO3E(f|aek~FgBLC!alzxU%XZK>>l-i- z6}Oq`uP?PN2QzsV4;An`ac;@@DD(fJVgGK|Kbw4I-YS6&ZDlHK{F)N1+T85=Qy1qi z*J66=FF&IXo%a%uxefU}66@%&?|iGjjifpO(U$pfLf>(>`vX(4?bxzkPeoYaD`?o| z$a!>rWV$`W`9rVUy;}e1@pVlgS`rz3#&%Qo^5dsd8ZM}L2{j52&0*xqGb+)cp)2_T zj8Qb#eJjt9At9q<`pz=kM)B0Qqa7i^z7{<(1LPTl?l%9$*J5!5yyqf`I9RDq zy;+?gkJvq${I!=9uy}`UTG||Ec*dB_C^19PAF`wmeueeyvSOLa@8`!JR>RAGa^asA zEbsZWr^0j0)B?&{57FG*wt&%>3(8NymO~Q zgPU-(2wrBQXW;}alnqiAIG%)`DaC2$E*0&IR%ijEf4U*;olXW7%8`C`FBa zB4Lct@WCYB%3+l7KH|Um$(0qS?qcBPqRut+&imJno#evmrj9s=BUB)AS?{`oOkDVo z=h$d9gK?j!*R>OUnL`twJV{o$or@_`H*tSqA4awDZ{Xr@V#<%4aJN}b;l-7qt2a}s ze8PiXm=+e4wDd?1Y!FUeM5ygF?Q97n2%+pAg)|!d)P`++&_b z!&vW4N$mE)wR2?%_Og4s?&Bwb~PaiVa!4~a9${wXY+cx zEQnUKl-4om$b2Lr%+xHQiX@F)Z**Wr-U6z*VFrRGVZ(&s@2pMi;YLtCGlsH@U1abk zvMXTmXY*g(Fre?kf~?sLNXzC+@DyO92nrHbL{utzK?jy23dZp-q8nluqH`* zVawj4d1+`klda%xVW*k8HKt#RkBfocFyGsCkGnGJ!cpiC^24A{1t@Ou9$v6vg7k<^ zxY9Ygl4V4KTg!LHXqdhr=vCKnIw9?`-_!I`+SF0^4?o}Y4Ec6}QsCTUqsH$yN3wbb zzjpI)VxIHk$%}ilHmK&OCM)AYMHM!w_9jf~%v&Eqa#C;fO$EQe|JS-fgA9AKkX$dfWHEaFwJFqLsx z{jLn@&fC6b^f8T7#y{NAmwpm4mfv(x4tDb-Ybp+LIjNTeRs-J>m{4MEihv%P`l)vC z)bYsTTKFpUrmyBmhJ zD(lI<6PjvBfq)v;sxoU3H5QxZSKHi7r{ovgv-%X;Cu!ST z8}{y5D>OCvp%eO3Q=C(_ZNa)nMHBJo8xOD1NaFj>ItrK4FQAqe&tSg+kc6BUsZi`@|Vw-N7PH%=jaI zA0-nHLiQU;YJq5ZF=JYU1K?S@WiKRoz7d-9`)TvoJH>mVy+-i+iXf>yu_Wa-Krx)A zjZ9_snvsiP7KEA+Z&V1WOF?-7P2i7fn(mOIW`0+2GyEW97gGrI1FM(We%Z3Ax%~D` zRP1m)`OsJ0g_$yFE{X;98KA-n?S3~6@9iU|%DH}m+)2^ysBv}J;gpRD>pFh|8{gIA z>-VIlvWI$(qL3q_yDbcRkkb()eBMD*DW;d9WNG9~wgRjIgRy$ZG3ayXue{+VPZ?3H zLIZo#`e37afT(gXS%2(FfQ#}Qu}CJkJ$jV=pjE#&tPOlKwVB7;^4k>?2JzU_PjQ6L z?&#LVJ9Jeyr0PQ`y^7or`I)ouXc0rjmLqXHRiduYjJx{T8)Z8f!SZ^MEaQdJ^!n{# znasu&!(KYR++S2W0hboZZVxkZ2*>VM7}9=w;JURukQ$mOD=YZM=6fqzoWW@s6E+0( zYMWRSE?inxNzZ{zP%fv7O)c3Sf2s=?%~z7pe>ASDum-l)mr0;mgU7nt6b+r-Z7}Ay zE}psoN*C_1bNjujk7G;DVBX=730=x3Hulb*6r8o5Fx}#{+PBeDlk|3`nOz7Pg5lU4 zGkckD$H7jxqOG%scv>H|<$lJ^vidR_5@!7n+%*;H9wBRwC}WO1yW`Lw;=TUDe0`Fv zuJm~QX5KBUMZ8D-NKA3AtJS77^W`Ciiy?`bV-3Yyb`jkBWyE&r7zN#u)Lu74yFMk; z!jh`O=N2D#9ut>ZJkL&H*WedP;%1?{0@(%7aoin<|HU9 zkR=|gO2=lUFFph8e9=kU?rja7qpu@WR>}bzooM{6%dRq8SQ4cn9UtWj^(U9rYUM&+QwOs~gn)bZs|a0ik>*awfO0o<(ugOh!Wl^)LL*U= zUyoR9VH5FiW`!N%oFOPHFV!?4r)psw-PZI?5-S6c3RH&SIAR?H<1_7q!BD7E_~KMf zSFZBJ=aIb6VAm+#wr`8TQ?JCEJR?kL>A0i3yN_u*JH2=M!{G|$#f|h=J%>g(dt^0i zQkhLClX*RhvQ?3(rVil+K~tmWH&ViEdYdokTmX%D15L0_%1{|iy+q9*gj!_1cC5UQ zA3*KQdkcakZ{60U1=39o+O_7@vH3J&Lz1y%&umBu#Jk})dn~nPCQpZVf*~2kO`?(*aC1!r>K%;LLMS#_HAPYH*PoC_~)nF2=cQKZ9zFh0FQ& zV(>83xPp#gYETbd^~ZIQbQHyf#g&j`X&5R!RYnq{{yxBN>d@3i6ltLAs@&N?7wB&_ zM1P`y;D^si{e;}nk`<91b+2AnJd8Ps&0^(N9>nIfIh{?#MR7ONb*Qx| z*yqs;uJzt+U0k+7Z#2(kQS>myn2t8rm~}nv9F5BTHC=+}Kq>vR@dM&@<0Gu1VBckU zCAQehfy#p0WyA|wJ`@|;Zfh7q#@&APf$DQub74A{komFq0A@EeA9E+kq)b9_hE8*% zFk}dRrutP4v!r!joK>Td16SQ-GOj~Pe<_HT_yG%iF)?IyrrYVc`{bq7T2xkx)}UFh zEPo##+Ij)MibR+cm)aJpOxu}5glOjBs5-WToY5wyUi{i!Rm4pUZ^a2rkEixX5C5~B z*yz?IA1&zi;sxHX>d4n8e_s@z^FAR?shifw1N4aO+UmFr@Vg;S@vb6n@8Fro{s7VV zr6^ADU@oMNk-mM0N1;gPI4FhQD>ZKJt|Q0{-+#ak`X0FpkneOa>KlI8iaPg3F!ESB zhJ;3c8xhBNR}#l7GN(9vC!h``o(DFfJ-L;uHs27{g_60n!mm}J<+0F=Pm*3+EtT|G zI^G1(p7!Ori4>LjF;rQ1$8KXTi!8;|S~^CtC;`ynJWzq{EoYe1C-cLHKbrbsmN1S# zRA?)@;kCr8UVW`4O3a$qh8O1RKeqq0^rv%O&jMaKID_2U^&|TVzwONS64o8=9fmY^ zQdIX^Q+C8D;WCy1#r#xOHOb!5$NQeIcGuJ?^3D#BE;7bF8C`4fn$=Xep-Yv~F^Iv+ z*{p1+k;Aj!$vuU37uUzaEC$80<=O2ld61~WmKMf0M^04ny@O}%baZgaUDb}fGy7fj zxk8GP&e`_X;1uO&Y2T~qlJB*e*_JAHOuG(u1Y{7X5Yb0OrnH0??@Vbf4M2S+{!EFc z_((SyrzF^?g%E)51vag*sx?2&9F@>nnW);*`y!x1Zt7l zXf_CzNYvbclCin+*gR&*>?=VB-g~gHWNe3VE?GF`Z|0H6LR`EA{y?L==QG&J8xY6A zoah>CrRcscqlCPtAty}6BfXq33p3dWQV=E zcNe_CeqDwnyz^aGi2)O@-dvoRBXY9&wx{Bj3~A_y7aRp0;soI&R~UTmW)ek}T|!uQ zfaa7tc$GeYThAN|JC5>8>(C2<(5N@;jr$UB5IU|b;ue;VQE9e(F+v#KKP7%D8jC{2 z=t1$YgyxbFcG;VAe);7B*bl)!E_x42d%&-}*@ma1#`IZtJbE^W zl2&mdvu2rC=ji$38`u&cpAF~yrl`#Bq4wM)xD#rY65TrbL(Dgu8Vjhf3M$7NVsg2q z^Pps1!O)A9R{%0k+?s@WyXz=0coPAX%-$9HJt(#klEytukV3{{4&lXkjJ*^hfiVRp zf{&bf!nS)fe@L=B^5`#wB=^wOIu_sC#*bTO@jjz0O$lfl0X)XVtRq_##`o9*wxC~wdX3F6sjaD&R;7om&|z;EfdF}d0Hg7}p*!3`56h&tuOrS)=05QF?|(+Z zLU6qEF^IpB5bj?i;lI~xvH#CVC}-v3`ah$gnw|!#2HFm%919a%C{ZD`c8#4C3dntM zC3p}<6gpfaM?$h6qEU$Spqv~9nm^1ZXs=s~Z-jPdr_WP|f2p4AuU=6i_?W60?T)kQ zjx&>6m$@9T`^z>#Al*??c#8yO<|<;M6L@$S`^gj3j=zP}u`*?yp9pQmPZ?2LIIhLT zW(}CK?MuiM)d zI>><295TVsYddHkv7JBC5iK^k;0=;*Y81#7}KHyu?MW z-N7y(ls^5?aIg2N$OacLID6+W7<&~j`r(1>_~O-9O!q?8raqVO`L4Eu%1Vn$65?a2 z(<&kKOpa_q;lY)0;pxjtqI%)cVR3d^QzMABLNa6I*B`jPS$dMapdv%~Aqa}mHBUac zwQAA~o#r!+IXD)B4vWXG4&3ZZxNh#8rdho9`U(Ko-DkG<_<$o#HrpnBwn|k=-|!8} zXp$*F{Wzbj2Ch%~6SRN;i$f=F$ebK;oXV_eqhqt$nhl7&b1yF(m_7cJdHc|3zD0}@ zXY7yBAs)2YSA=>Mx9=>^cNmMCvZY}w0b8t;w**n{e5$#Da&>ucz5SRyZaiJ6jPjMY z`|p)EcSFh?b)el5>|VH&I#`ii^4hc43gwD?ILJN5eKBYV`{~Y@SGLWrcUa80mwcPR7H`& z`bv}benf{@q&G}WWK0U(s02y`jn4)o-as z^4)*nK0z|>EwGT*#ZzT8_qid;l0C(&4u@6mG~mR8_i|J9X9sj340mlM&_P|-m9LV(6* z#HtP22au|TghaSm(rfFKAj~sKfuN1)@5_J?Ve#0J%JQ|j64gy@ z*%a`2JyrP@_7CoC-s=dQH`J_Re7|m*YkS@};`Zl%|K$Oc#r#Vc$xfmBNH|h=h+utz zK{^~a=lsDCAE9%eek}r43Hr*ZU@cSt`iDlMA0|SFqh_Nd8TaKdGa}6b#lRT3m!dtp zG(FHilv8$$3X}m;S)(%JLWqx$wWCSG&Mm|8^z8s+=cmKsFT%EF)B5%x2%U} zUH}fk0!4FaNGhIvRCu9F@MNx5(^$(WJ=!!3&rKp-*wJO=n^N$cvBj~bOM#Zn(QQ0xMn@t|h07A|qxsZS4UHZ)n23o!=YRwdskfl^2?YyJLT6T_&Yt|QR; z$B|eW%lW;G40?{TikvdtK@_$qn%c+afo3BlNjRlJa1_~GC59*}FuP-r)7fCuFGyut zKoj9V{-|ae(Y!zr!g^*vvL+#%$mp)t*fir^MwK)-*Y3m3(!7A3rN6oF#9)i6p06sJ z|8B;6aX(cabc`47-IVTu{aJl_Fo2!v=|<{HKMwk+cdFzFzn1f&I{?3}dM7^H!3gdHo1=1<;(Bhg zt$YXHTjJhiFkml-W_YGtt6dm_t;p80NIt{H1xOirOItcrxJ)u|CmEQ&|f;oCR|gYuZ|Sb`;1O6Z1dz=q-Nd00K`Gt2vlb*0x17Fvs63n6_cf{5n?&e~Da~ai(Aa2XcR!T83 z3irtv+i{PosW!dwY62O~Rk(B&)q$f8T_z=v4h|xKb?>92ir#;=8OozDx^8q*P*3|{ z<%)asdWVn4LZ6@yXzSn^A9nj4G88)ZdQH80NZ$JeWI)J9GVDg`L9Pjk>(xtFTnAVj zR&%6>-wuCS39_Yd(;U>cC026=vK`^5weOBvizsYdABwL^Zq#9=y68jH@q~Et!=bTr zm>yg}?u4|!U|7iswZI9?zl1j{_zk|o;+1VOg=?opm%wM%+uNmyt4eEbbjdf(JLas% z6Wb|az`Bz8YqhhQQPaf0@a%POz~DS%CaM&k<^s5VJ_;s8Db&4sOt`cJcMEx7D?<54 z#BZj!BPfad12PDvP~l!b(RLVoPN$%`k@}Q`nwTFjE6ecApfQAXNua+BBw5{=4A9#H zay)~*DhosP_*xF+Nqp-0Mb{%yD6bW&b#?;Us9ID^$XUB^y`3}YsVQ?a(6=lA6VvLU zpw?O#Q)Lab`Kdb7t%gE>%$0J)&_wWO!!lhe%K zt<2I?z6NKLIV@zgX>tUod|p<*Yko=s^hnJD={^wa)$@Dqfvv$ynI%rm0tFjtN&7o% z9a?ql03Nt{)>?5Jb*X3Rdg>Pwwkj)lOP+|h*4J9gd*&t~bRNqPHVrW+V5>78d3)(6 zL0Vv^HiCgG#TJ@bO_~GohWxWmM6*rdjP(qdTFRTJ z1-v4PuGu!AtE*Nhudy1Sy&K~Hr0podkEv|nrzkqkf1(LcJ_!cir}H!Kkq7zGl{Nn{ z_(wiP`6n_&CpZvLJj}nk{(sM>;QYJmS9P#4vo~}8j|kwVBCm+5gvMV7m*Z|(;-fh% zOs`fzpZpdGL!Dm$oTAFs8kE`YDM!f!Fu$BOyer$6I1H=Cx92B zlHbkQb(!tTW9>ue{RDD^O~T<}DkrHR4yeLm(_M1J7bS*+r6k{PX2M1%rIEl6Qc1OY zWraIa8FBlHJFDE*pGomqYt(qWAcrW~SCtE!Ei}uD*2$tR)j6eA6X}eO8>o`qZVA}~ zL-(I~z&aEk)0?UBj?3{@We}w0#Vxh#^pZK77(aZfu!S?)+I}iYFW^kECpU7qKs(2R z19k{4_)fNVpQ=@8y!W}w^1*fvBNc=X~Wx6Ng(e#w(SVxc7SGauU=$EW(|TW zg!8o+#{8`b#=Q-2Vig(clNax+_g&g)w!O(p88)gb#vaRox*;JL;FtSZx#Ac%1Y1%T zE$R3H=Cceesv~nFIW5P-mXiD3g0b2@1#ci0p}G5zd6K0ci)$=dA@as98veZd^!k*2 z#Z!!J*Yah2wam8h^ENp%3+_RCrkNHF6zzH1%n<2t2dxh%J)LgD<#^^NVZH?uYa`;5 z_(P5Ym@uhd0cf$#pG{a;9Nk}@%WyYxi=OLyPD+w?!W?EbTqDx;#PAnfdH}JUL57srKZ%_PugO3R3<*UJ`M_Ow!lufznFsTxpU7a<^P)t3bn!Ga80+Cs+xE=&$`kF>W9`bb7LvCcFi?-C zJCl^dBhk%-r}$`?e5>cfJr}&=6MrA)iGZ^{^po?veIYoj8>xSWuVWx*R=qX z;%M#FIUx@7@e~X7H#|P${XQr5iTbX41tg=%1H;*fgV!BQuffGY71q`Y!3T$+fB1lp z#@Mab-8+x|(E#DyFe3j8Da5@A;#WvT{Nt+4EC0Z>jQ-YW+Akjcv)*%9B!509egpgY zdx<}VlG7RZJ{uEhS?QU2JiFJSYVA5>IPUeK%+Ss;r9!%Wq{Q_}jQ`r^ z>+0fd@8HIZCPm|{L$rsAyNwLz9o1QKgW`@J{FPwXUB(;2v}!fy>e5JxWkuNMIP(Uu z>9(inIm;!83prv%)=e>)69HTm*?|@0bK^m`{C2H{c4I`Sy~xKlaA{^=cT%tCot|@6 zj;(_oLxSLt?AjWuix($7I%CvcCjp?GFHSDMjx4x{CICF}j|SwS$Y-aZa-}R)y8ZO( zvz}H+kLjZzb>{Stt`jwT9ywaVIu8#lLmV+RHea;SZV@Cm!9hIeHkWp2pyo6&i^;`R z34fgvIU(^SHCtZFDr<(ct!$1D^MWAhZh*IR&=OZGk8zf2%v3MkYvKC`18(Hd9gGH* zHB(ffgNAxLgVO%VF60b1Cb~1=nS89NY{eNx!L4|#&dp%TjG^HjAz$BU zRh{J1>{v`M_QOqb1P(f;buLnZS40>kUB-c)l((d#V}W4F$I_Z1L0SbKf5C7&+lq-Z zV>K;sCY!<*t1(-cPE$hIhNnl6ad9bM ze9FXSQf9_eU4Lp>yd%c4*9^3z!%ElhZ0y0cy0|2aqP!+KWNK8DBNDh2&D{Xd0PuuG zXF~`_)->QPw|Xcjwin4mMHG@Y+(fxIXf3U<*wi#yVQ;l8U})oBUqs}gU!N0CiE+4X zrZKr~a-`YepOr#jPG!4n4J*8MhU=#=2s?1pD-wNruRUaMAC>ZpFgA-)Nt8h^T~cyu z`gVTucm`IvJn}hXZ;7Ce#ofp3$!Pjq>PWJhX=o^B`#Nf25H54nH=MtChX}Q1pM9LZ6p@jhaYCrg&U7yR zbTjiyO;K|HNd9OtqLaAVdn&(9Sx3SpN-;lDfWax1#;jl7J1AnTaQKEGB|0 zk7Bir^XnQ;SuvRo&B|tJ5bZNP%grZu^uBz<_*GfPc*EeLAP!I#P~{PBoP2JAk@I9n zx>Sk>YlZ(kE|DEaF1t_@Zt}>}b(kfNEE1-i)iIOX&=FK7LITTlOR|8$9@0TI(ROW) z=fJW5?g$^M7=F4C;4tI?=L7sLMmPJUbNhOA)y zlmJiMnBlpcN7wn0LYGO3rZXDHiUybmpm|20kHfi}>T?_>w#rp=4Rf*tH1C}9897nY ztRT}KCstS;Iujm&i!PwG0pIp_LHr*2q<&zn@&?@vM}%9Rmj@(97y5DTlfIMz=M7rW z)%#;d)q0NKE7KZ_PAGMwk;UtIkizl*Sh33wVgPmfUB7f~Jl^5M>`ESg``W48|16@d z4uKVg_|)kA0$(D9oqiLH(jG{;FC|KC&WIaJicAxi`2<&O3QI5*=S%ZS^#QI=fhPmK z!PzaxmAx2R0H+Lr%LQ+7cj6{WtriA|<7FLeh@lrdhS1q(=4Zotjus8q{*Hv0RiC7q zApE9hB8P^A)8`JGcwW?<`Um%7N&U=(m1cpO z7*1+dGpBsUAG7W%&YrDeQgJ3B5}NiRBD;fH-(fHxPDRm7#ny$4V4JP3E6WO=OI>Gn zAekkmlVbe`!;bc>tvyA+Kr2V2NNY_+N~oH5dBYus7nv)@Nw?d8CTx!=D)M7%1Mhl@ z`m5GRAt;xCN@638jBq;FN{@6F8j`FfmC%FuPWg+ zOlugobiC90xsU!Sg1cKNiQP68o?=@XUksH850W&44SZ7;=1kKYQCAAn>bw_!vcP!l zjIfF~+2rpr5iJCjiems~p3~o@#&;QM34GxgIzF^4T;f+(vS;s9L%_|#x7EnDd%#{S zbhOZrEDwdzTmTX4$bZbRh>0$8f6h1|di!oXsN)U`EScI=2tTPCD?Lh=#3YESSTu6x zDNJzZrr4OHEJ&{jQmZDMqOE@D`57aCafAp?wik9|N!eu*=2AcE)&!~*&BX08w17^J zm=yKOM#QhS$~*}1-aVe^MvXj^Xd+#iLs?=nm3MkCi%dvbtkCGp5{EQ<$U%c0HXYFewqcCRa$olcM)bm)g9PN zzwuw7CKCiyGSlp!iq4){Ct_T97D{v7AI(MZNy{%j^mD&(T zg&3!cN1X+(DZTb=CLBuljoN;iMvMEyPQ0lXdc~Vn@wwo}Y8D0$xP@q8p!DRB^GJpB zA`Aj9NIhWepJnX*#p^S+epoF8zZu?flvmt@FJe!NcoD)m%~VtEfs?DPpnn1=G-(VP zS3%lbk{JV7S+rHwzSu@s*t?%?FemtFQb zgH~uZwS+_V#3c?3cZQ_NJYY*!bmZ2OBHU#$WQG2+QF+iv)z7~LI5=fzWi%PRPE#ik z{)V4?(~5*I-t?kQ(XV@3*}J6o8HI1uGfJX#2e#zv)e%B!T7=p4M0aE{hNpxf2d4O> zKBVu4X!J2pu?50}s*O@0J*jd&BGYxqvun~k4oGwUEgjPRhpa%p!@O!TOqp=DZLX+@ z07f10>C!tX{DR_N+|oL@OC0XPhJvbpg#WlxLG!@`+A$H`L4o_@g4aD zLCDqf52|}UKm^IQv-!MP;s{OL1&9=5!y4yF=bu7&&|1m{3p7k8|LAPG6= z|As;6-@w@7rLv)XFiCBJ;m3R(ob!+>ZwJM@7?RwItS7oIK-So)xDfqF&KQIv^1WF> zgd&dtMFa9X_5^X@gz7^`a6;Itnh0tVUJuBgsu6yj;(uIaf2-IQatd*S37~vZ^BmN> z{DyTlN!vdsjxMr>fpMc}R~!s+MVQP8zF^CjVksgtUmW*vUUannQA4E(g5$&l>zWPU z!G$Pc1iEZoB<@Qy6R(0K9Q^~_6^2+5K;#sOWoaGe!7tu5-BM;X)x~;4{$HL^ujdsY*1h27?Ue)w> zps{Gt4CiCLg7MK}kAw5UElIKSfXjB7=LYYYm-*g&OLE z>QgNEM7;CCILm6|oOxvsus?ez?IsG;r!G1Gn|j5OJF_`=Lz|#RXpkSa`9PRB=sGsu zBgO0*#h9YdOqQ!RMUskN>;3KdNlC-dsI+dWynZfcq@oVvffCAz9NHBzxbw{#$~Y*i zg~s|_%QkW?Xg~5dF3(Q7_nY$WPd`;?ZTO|H`-QCgC9nHk`m8n95G(eEg2)%QLAj(Exy*va8*$|q2Edv)&+v?(n%<~RwZYutd!sqMV9f^8H@{cmapFl7-aO8rf{mRLD#MxRk*%eCRs%;IK z$!sop-0EM!$#@0JL6Q~0d}cgoRICMJ87A17Nd%t1|5pE@?g7$|U_MgGX-M7v^VzAc zGaw3kP=rcu=85cj))Ojfr#h>UQ%g~-W(Bdr@u4dw%rD3vDk7aRM9g;N6v5fVEeRe; zI`Wy72+Fq#NA~0wR_MnxRgpvNfa2;FCk^8R>V|e&;u`^s66wJGxOXhfl~F>}JPZ#n z3XeQxL&wGemqj}!cR1V+G=Zdm!^Zf>jda>Q9a7XvdS{w6B$GX|(N+|bw2j5ixuDyo z^ao@W^PUvi3>k|PmrBGLO^?=?Uj&tiks;{P9_(HXc`)nfDdoTT8e3)ETL`ok$gf)F zDh8MojTJCkm^F%2U2*|alr*;GE6e@Mzttaq@@%AR5!I>sf~l`qmt=CwraWKnYPU#y zz(R=^FB8EPr;k0;q*LAS38Jq?c=bN=?af@e;Z1-hZ%HM#1uJ%dLeO{*)ByikLhEh-VFsXGQTBisMykZZ}VI6+$skT{@E#M?lY1pfXLA?Y?v>5+BVXiVD=&?}i zqf9iP3ZvN@}YYs!wZk>?()p(M7)jMo&7mKJ*U1>#vF_$>2{i_uBiTUFFV<$n z-IYLfC_>$xgStKYR_u-q(I|jnK-O6nvz@pIUTuDxDZ%4!y(`m&wk(3n9-+<{@W*^l zqJp(M7-0wEV<0^4h|2F*vt80?2rXP+)L`xouN;T+Vj(R)0bVXIn2ku56Wb(?vl(V? zUzn!{{!Dyg;zX4Y@)CXaXnw-F)t&3)v zW=Gzxl?I$=!U?QN11>XRMD^U5CfPx)bybch2_!mCirc)5&81p1kHBliMSsR9ERFV<&m|5*sN8=QXc_Xp00xJO!Q>eWu zXxUiOerniT{zB{i5Zt$0;}dQF9GJO=bw>}OlvEd#j+!*}hzTfG$z__mm5nk7X!sXT z_bKpAYlGJS~f{O=LqfY(bT%dkl6d%q9G}w2vaiCv2e{U=& zN0?tp!2a6}2hpxsF#hGsep$&Mw^{ALP{2*y*y)K74w6tmPRya3g&Hr zA_t}!987Za`)Pc=wB8Z5jaTuXPU6|f*Fl8=t}~57gsvz(#(tEc890sIdI9aD!+APcaUTKSc-hQ*y|AeSs$N_q$_m)uNxdeAN_D@+D z?2ExPXoJ(bGPwj9@n;on9k(&?IOF=2KxWU25?68%7^ce9qpKG%v}zg&W|=3n1A11S zq^JFK3zhv#cR@Ql_Y&*57zUWJvHu5O?;M;-^lpvDwr$(CZQHhO+vXcgoHx$Ib|$tp z@x+|q&hI;?>VD@`-CNaN{m1U=>Zi8Xv)0-}<-EQ!Xyg%@tCNd*Ta#+Bt$6{yH5khE zgOaLcLI_ZviQ&uArYwoco?Q|Wh73~5E zp>8>nYa#9Knx4n)?kP-gSs^YOW!vY(lHLh?ADv4zJ_$3bgF_B39xR@MBWy3=S>!*_ zmus2D%HGj*Kc`)y-r?%hj3Z0l`65=hO~T))9Mty03jVv-iuJy6kIR-xU}Mt zyzvU+K=EuX{uJJmGs}*l{a(=_zc&{OFf0qnTFzm^sNJTdG#2|K z3Kq$OG(HV~13U(>UEARPPBUW(h z#42pvZ~oVSKVxoanR(zx5G?pgI3V|x@4Y}5RmFjS~N)Z|a)ggs#y?lM#^a}Lp3)j{*`3Z+AK8VvSbeEQeuFW9_ zs^gzjH@AuY&`h>1s^m)A86y$W=OIW8=>ERe6KqXTq1dh%xzD`u*OcQXwak8TED>B) zgvT3f@BD5X^uaR4Ffd29410Bl1(yiQWK}{B5#{R^kT_k`t zoxTeH7AgsRenJ5FhCpVK^ zg=%Uv!~Hyn8T+<=_(u#k8;RsFZNL{z+6vlLI zrMAxKB1D-H;hz+`Qj2EDFh6=RIE% zUP4TuR7s7bhcl-T+{71OSm~t}-KtTRV{Qsrv z|Gn@(Q=5`L=9VrVw$4ufov=@xR2pVMi3;|Hk7({-u%vgPg$1B#qd;@PYKQ>lyJ@vp z>#VbH?{KEJvs9?Y?wDLW zX~&T#JT z)VB>2U>6y}Piv512;2e;e8Jq7+JXKhwK4s^*`pMhlV!MO)xRApPVcVsSbrB2?uU=_ z{?M9%ND|6n)krd!#hQ`@(nL*lOxf0vZD0xtkE=7J^ic!K=JIJ)w7!%S^LUSE$u(6% zB<+a{+0LZ1o-L9ONi5rGvP;|cJC#k4E3IMxj?I*28LSH3vB`7^Cd&drpyoK#QC68~ ztDsFSt$In_?-4W3I+=M`h;{F(&yX!>IlGyO8DmOR>y9<6pY2CNWS5mGgm}}}O}4?Q zj>Ah_KNRL3`Ts-62m-lo&jAGifdK!%YxsZDdjE&OxqG|f&oYYqA0*a3ItLVtHT)xQD=SU`1(z~hI+stw3hss zG~)t2D1Ly-mP&o2eosZ)rdEBc(5BJoJAlQz-u>6iF)QjrAg}*T+nP~h?^oNifcwXf zWN@BB4rZ()J?0D7!lX;fkEDRU%R$7~qM3HPS7zPqs)N6HK_v%N%m@axM^?BUlc!jO z9aHPqk;q$-Z(M{O(>~EMo$BLAxHoBY$e!DbbT_G^$vrf~N`!*VG8diNzqWrI1rZ{j zy*5QbM;_=Q3f}?5Je>aN(XoxT%gVIJ#ohKz3BRvT?oc&ukK1dR%kd-;e~?$ilC z$*hx;0*795qQ)f;yhw#eGpJ8mj169M=Znxlg=^Ov(*EQV=k-TkFrVAXxcv}Mj^e}dYF)TvatPp$eE}cthQ%V>0gbO_UyJLNl zL)sI(?g>b$RHy7&-Dm*ss?1zPMpQd{I7bue`#kj0)u(u|LNAT~lRoB0zg~c;eWC>5 z=EGoOk`p$}IQH^8Iib_J7wEE1m0qYi*<(D{Y+seR;AhcmLAY&c^2$+!7Y|1xJkTg5 zj2S(=1^l|bjJ0VY+>DDeDAM{ZC$~1HB8_d_U>@kxQcn0Iv74O0R=(~;b{Q!)t^);( zJgInPWw$9$aq(8zYTa!kQ@y%_cN5bdan3or^LO7r^^k+1hobDyQ0+VDw|~Mrji8#)+FNSZBTn$fcv{H# z&7-@vQl%_2vbKmj%YDSV!#SUHaAS4$tpU@6Z+NC-cv~L-KWRUqzT!F%dKjB`2fGcX z+1fMm5$JXA_9)=cCHr)=gt~huTBFQW)Qp5B5#GA1wB0+Sep@=q$dpc`&u{WD)1Hd4 zu<5Vg60FgVeT3I)Ug{yKrt7A`Ga-x*HzlH#dwiPjd{cKlELP_7TK!`_JMYK9>}$Dl z3bDAbX0d*l^hQ`dfyq)z*lCN`Hl#i6OT&gN+#0S&l=3Jk}*5GqG`E zBO+mNaDU6mfXq@Dnx%X^W`I)b+?$j8m!nWLDbd9hg0xot3RSdg8EFvCca_fEJ#w3{ zIxL)f^+`}87Lfc`%Wp2mebFl}@u?lH3;|cMiqY?}nctL)b@W% zM2>(}LViGDEb2X5W%tivj_6!d13pZJGnQEHhbWZw>SqK16@sZUxgvrAejK-M^#YZ( zK%LNa#^A#Yrx~0u2e$YZLP{&n7uQ2gmNb);3*<`((P8Wm+E=^2cVzvOZR zk;74M?2=(*!$)4X3I%*Fj_7x}5JXxvS7kwlg5lU-`kNtK+upCqK$?s8H{Y@nKN3yj z+1f*)f*yukKE|_e?uDa*2G%BtBm$HZb%v8eJOO#s$3Ql`zbmK1V}LRvcUh15+JiCzx({!|cgZteX1*m?wKyQPOqk(pegb`Lx zLHKn+ zKy6KxTKvono4rkAJl(%*dc^~w?;)t?BUGquY*jED0?m#qX z!PZn^)|U7Jq7Pr03`6nHE?ZbMgIcB zgOa+>K)eEzc z-sM~jpx2-)*FZei(%)uup()oo@8fzB7HMwX7IY!b)fW1Q3Pu~(V!NvJhGj3Cen|Bu zieKEk*83qd*CO9iKd~CQqZoNBjNvDl^;oTT(DT0Qzn%Vtt2?H9!TL2oNuZf{-CIE3 z9cNFV&6DIPQ$szcH&2I|YF*1aHC0e=ng@A6-Q{DJ>N^y6>SCdfuqnUQ!}%>=F7cz&mYwmpISM8QDZ_qW0UPYPTQ(DLz%Z zNcAXF%YbFFc8ow09GTwt)Zk0`t|D+1*RlbNe5&Kh!id;dm-6)Ko!%I@L)o8@0}MyFzX~tGa8|V+3Ph z65|dwf#wx$_{jSr?ynXDvu=kb<5qA|Gk56_cxf&$+oteH$73`uISs=0nYaVC(_)eu z{3hGhDn5r7=?R0opJiRB`O=-jHPwXF9^X@_+8i~B+QEP55BHq2bfTlB8*$9Id-$|d z_RLx;NdJryycJBkYX=1q|7L>koPp|Om{9zxnGarvvM9caZ5(C#R7k-DY-r-dJ|W z=ov&W8|GhaTvL{13@xhd*r&Sq<_@UMX5?x+8!{D%O=MZ^6#IwK;?7;YN7Pk^>&}tU zPGUkk31XX3WKL-n9`rS~{J-|Cc+;K68M?p`w>h+z1kXx{@0|Y>Zb$fczES-=*p0_O z7i!6+ItRT1KsV)knIa2@1#auSs1p}e3i`wnjnXeCb9XKfRgT{x2_}(0Lhzo;ve^h@ zF3s8C2}&-VV{>E&$v&Lh+5xO>Xg}kaDy(f0xp^lWISZHxZ3eX8E)Uwhh=f_RTp#jA ztJ17wda#GrekRhg4_4fP`UAIiccP69X4#?rxx_)k76`iWzJYqNgY%l)l zgv6ue5be0=@#q}2IyoKcgZ!ZRd8JNctAWQ3vf(H~*O}F@8(t;Jl?kQVb}yUWQ!xzU zmWY_5hEHT=smI9ta%o5KN><3*|F(nsDhfj~Iat68sHR_kUQIZ1PIUev& zknSvP@1-;_e5mjaHn<2qtfUP^#~ozpg{+nl{&014pyrb)9+|w}XsSWT^#(kAINtI44b+uzqRDIK^9$P@r6hWL4hhLGJR^=j={r4~|Y z<(>pO^?mnb=7R{+K{!zSsLKVSfgX6Ktl>DsL>=?_`AGr`53LY zZlqbFB*xyzO)1FL%BaiPPF5-ijvpMGJlrNowJS)=HK<5PtT&F796Z_D$jC0$UCGSV z)sB@s9ApCKvtXphBQOR}3d)p$4-x|h2R8?YBm@@*H$(snN{eK6XaI_WHzWtXDhjn+ zB;>zrQ@4)kp>zKI{>Z=k|26dd-vJW+e*~!H>EQ6+xQD8u^O6Wk;AJw8;u2MPMe#hA z9*Hby_HK=aW`&%LBq=Y%(}3fVUTk+qsuzFC#k^@5UHKHJR6{(5QgzY!ABrkQy{aK|Ao0kH7_ ze$7qDp+HFiTU08s=O#D6VMY6^EUX4iSktWjjlS%IqjWhV?EuM6Zi7;zOlLz#+O_+Q zFzXIH>MNZj5HOQnJ|iZlX?bj$G*$vhArL4hoMFyj!pg6u=ImD2_|u%xRF}4xw!&zs zC8nvYZg2`5dab65c^ zrT{hqA2uzdz%2%05+sxY-QA^{B<>~F`!G>jKt*&LHrk*oEWYEi>7r}*vTgTI!!+P+ zulCRRqXN}XkZ|6gi<%4V#$ErXhMJ@nVGxi+F|rJ5HYq#C%PR_!7l^0AD)rfnfry|=jXxqzS09^!BXJj@7`pFMdd zQ#mU4Pu*OPRQ)cUO$E>Fs>OH#OT>Y+pfiP)z>4tk?8a6xwR~9)verjblER|ov z-eO$@hSTlH2s#0x^EJ=0xG@$2;>-0l&$$%smdmNQ6UgWD%eT(mqN#RdU%Fw&cJe%s zcWx@CwYs){$iAT0L35moc5&M;ibq@zKi%gIoW@YK%?D=Vi!C~JU8z>|YCN=3U6ao|tDk@>^2xl2FW(~=7XAA?;DK1v zi_i3yVBr!-MM$bAq&yp}R#C=Rmu2K~bRwzgCmZd#IPKKa1CVR%ItVxqq3it}g-Er% zrg=Wc@v!rF8%5W99yPm2K3`lh%`P$O&3P{9hZ68kUwYR^_c@EG zUyiJCE?)B?lPTmyjw)0dt!#TccXscs`EHQeS8|x`!JEuvj0!MT9}iYJ7g!rJ7WpWv zaX!1R@3|{^dnGjN`!S8|@ur#{1o%4_F)Vz3&)oH~HQSdSWbKg}<2YAUV9uGX+2CVB>|Jf3`Loi^@W|-`sCYz_iT@~;HkE$9I|(lB z6F0_X%73GP-8iOxUi91QT)@!!Ng$l4d){0d?50efyUT*CSs28-pgShKa(^r@~fI|(b_#vQ%pyV#pshXQu zB3qqPNayH>Z9vRev|T{XSTy=8Dju=yEaZf;kxW`!B8;B=O|qELgDM?y{T-Q@9fIN5 zq9p-aTr#y2VaYUUrtnDUQ}gop{A;l9)I%dr`53+HD3)jji>&0P)4i3nZg1OaKf{WnF=!(0aof@wKegg0n8FStb zkO8In%!gGU?YEXbfggoRr#>6%C zOcn#RVVnqjynY!F_CTXz&88kcojnzNGZv0^&x|)6+&Uv67p*`?$)|fU>Dk8$dU4CA zNXf{ExdPiI9G|TYHkZVjs)j0NF$lN6bE6IDLnov|WdJ^nO_eqd4SxR4RyGOd=;^Rb z_wY8%M+eQRCwe-UzVoG_wrS{wI(Tj50zP}cYDE5&e4weRe~+z=R%q}jLV2bsl$<9p zP9`_6ggv}m_i3!@2**+*uOXyfaCghNRcQbvgsA8&_OC1-L#anhAX!y6cDgm?0S zj;wyWfBJ)+BS z)d_H0(O=nIG%>7NmgrRjY0|xfNT`>`ubHlH%P;e^niz5Ju_@DxXb!ErIXq*p?kc6z zz^5oBaaG<)T-`LJE1{xb7GyXN3S1_GdYPcQ3Tcjh%6@v8R+e+?5Yq}$?YNu z(P*Rk3F{=Zft6GmhDm(Y0^1^D*j%D0-c--Z6n_x-TVh8jYss-WuJdDZV;|$Y>h(bV)--~m>U|TM~$Wj_E<}6RP>+MuHkHUAgtV05f4ouk)&WfC{ns#{% z!Dh89`i?fblzsdzY@BGM^x`Yim)ccVr0L=d zCqZOL8^d>)q6FfNRZO*rxpZrqs@CtExIaG$^BOvf9u0CjFO=6)RK7`hG=8+mT=9?h zL~5?DQ};E1ljy}Ll!K^m4$`}>J{|{9l}ftF?k~r6$!c^J>rI+K! z$8oZbRBzQIbfpsPr`Txi)hXVYwfvFn!l>aG?rNq{230D~ekj4ox*btfgwg=d$YK_8 z0pgmJmmm?4Bf~Xp-i4DzVDlPhDT>z1nyUaaEd0WDVbOa$lpTR9^C;H@1YaLEh1OZ8 zs8SzXN@LCRBBN24wQs5ZT>yBtAGzVzg~e*>Re)9SI4K61xv4f(R_v7W382J4>ar8} z>?}v|)9ma4!whD`4XIK2jC1*UT|ajAjkXXK!dLdY!GQ*O)~>3FOuanjjVg-`eFN#z zFf*|1-Y!ff`l^bCyH-({4^eRvx772Ir+s0W!HipQ=X z&hIGuGUY!eo}QgXopUh`bwh=!_+zvy@DvQ)LcbQeAH7{{fAAJgv?1~W5s8pUG)q=9 z#c+hI_n_%r#!^Pg7nYLR>F*%2x5^?1@pz={rE{^nFcC||cNcsv@D_Y-@X_y4w5fWU)Ml>F zRS~W&U3ja>{&yi2KY56?H%|?Ti7wT+qF@UJ5Re${r*EX_kG*RrLvU_I@y9-|k6rP0 z2mRUg0#brP!L`rsV$h9Wss;v`q3F*Q?Mi)F9;nk>yXligrsGE_K|N;R@If$EAAGd!~94 zrkqI}4(5eyK!fZG-%_;;6-8B)!T!67VJ|S3EcmDzncpD8CztIg3MnkMb!266iX=|6 zm(Z;IgsQdS{O2g_Wn$cg8^y=532u}n4`(`mEI1Z_X$DAAPi0n5I{H(Gc8md5Whd*T zhq5)qv=(G`^i@XXnY||3shMADs`lGY8c2H?6x_!dL0DU_*k3%79W*+1_^W?bo+q%d zsX?qGy^byb8E&}|6i_2CSU-DquWQi?EXa_>n_^{A9cblqZ=4w%>f0j(DQbS2diF$qmp$IcxT}tARY-=JLrA`N! zG~2ogSAyOe&J{@aL<(Qa6AdCPn;2B%3D1(yk=v%p>2mby>Zu0j^2#X#B4cCKFI{!j zezG5XzMlw2bND!q7bWghUE3Fapk9WvQn&$##`ZF0uJ^6qOH=b-{dtLd! z3pbu_WPg2%c*7E7rYusb0%9Suydr)`g?}dQguBa|WFtP)Y+1<+Z;-*6Y}pEmy;HS% zvoa>p`frjjN`w^`s;g#)3z4F2Lxs|8&p5Nb)_-7aPK%(Cu5Ca<^(S(ZwLsza#2PvR zqf===yn>*$5LqaQx1!)496;@LJ4?F=Wc^YcrHUIIW9%?$qG}3mn+x7OIZFw`_h=KP z>;N(k-LE@P{n8iF@xHpiW+sbUe^-RQ%ss_!tG4ogKDwQH8;Ar)n$LLQ+b!->Lx`Ct z08d*O;u>x9iEuX!;$OD#v+n<(J`SK{=glu+Pj&kJ{>E=-iborH^FQ!d?(@zgPIP)^Gi zhx!Ij9w8CMWi`mBP!m)x2xnhMeGZrzVMt~5fnRu~OWPOgi)ZRKpD%7BGtehyzkl_7 zBE9Gs-}ir8iUHrVmH~$yDBi$_`kQln$oSkoxNCW{a6}FDHzaTZ1mT(X@67&RSx|y~ zXvClxra2&1rm+33@ck)5P!5yy>jTs``gvs8hgoL7$t^Z+Uigh|4Dot0t42o#NN{XF zK_OAz1Z?I(7mDiUeq#!%tl~Z#`-H7>M{~1^VPTnkNnnhwK`);Hm4TT1_xwVB^Q)G| zZmyTKnC00nz(>zB7xn>VbjXyOf=afEkWWDq=W6c?J6ur`bI_R5(4|{LVlt91ynoD? z`?dHDA1XMVRDAEy8UKU%@f9g~-~Pie++W7HUpl)V&2{fISllCs8b6eD9M%nWsnr_$YYv5Q7jrIkCqTC3j7ctXy((@ zidr+N<_pH_J zavPiiM?(RhhjAo`^MU`xs1!*DU9u(j(iZdTZSe!{?FDLUx`=Dt)*)spnB_J3gF5ru z;Wikp(;b-1p-4A4QK5Ja>%Dny9E$>mXu;@92+148VVGws(^A0;^^N__-O&HR`qLZ^ zs<8id`6JbuneOFf{D&ksRwnej`sdJmc?&kw{TvZF9l{s)f^Qu7@X?68@eKEN&jl?t3hsV8k;RtoI=~r+9 zRR=g(ArhwoO9!uy(>Ltd&T@Ti19C&5hQ56IB>!Dj1-mKREHTW;GsHGuM zRFT(Ba%V2xzYnUc1>S1X7JMKl2#=eEcB+bf%e*eKF0B>l%`Fi1+vRcx_a@HBO)Gv9 zi0aXnsl zPJ6HzFo`8!(EV3AkLx8%{9=2SOQ|x(+GOlQ6>N)HhQ<8+svf*-qeSxRzjL~(WwPIa zff8n>U=e7`xoF%Qe1<8RTfz%OsvfCTtG>_}5D2Un;g~C)W}faEqCSXO{9chte#NX` zk?4O)-wUkw3S#{zl;tFMI=lGz1Y#k|W^39V65YYUEhlyC?$^jl8p&Hv^A@R{)X%M! z$FEwwX0KhWgaS&-+K;Q2a5dpPcB?45)Uyk7ke`K$*PhkIPoCvH9b;=+8R>*&oSf_$dn)>h zjUyvO?!%ZTts1}QawryUYKLoq!xQKQk{^PfjTx$SAsV%{$g8XR@_U+5LQ9=~?s68= z^eJ8TVr{E(vxOoL8P-b0Li**lgpPskTbC;%{B4+??sj&7#tJ~|hQBKNzeTbbBa$qM z3w6^GjR)HGR#q;Pe3~yEoksURdjW!ZM^M=ShY~@5v<-g!h{Gh1&D`78?a5z$sL8#XkPx+K?t}Qr7<;sXvslWrK*k^zQ;7MXU_v+`F zJpILwSaMazjg2IuW|ZWo>9U~wxCAcDTKzi2X;1m&Tt$7ZEtVG$0Q>m`0iRZ(w=H^i zPRl{7BXJ!wx<1K|(FydpR|XF8(u-!5ghXy*W>#Z51(2T5K0{9#@SW>U>x}H7tPxP`#>hSL2<@B;KcO@xdOrU5~W_B9otVg?He9z zcJ-n5Ib!rt4h#DReSA5+b_R{awmiMwgWLG(xf%rhh!3F$yXdh}fjgcp;Oq!$1{b9i z=Q<97GC=TwtMU;C_mzx$Ped;q+KGu^JS0)Q9!+?e7(c@_n#yN zctqyPT8Ju4{m=qum@P{1zYIfy1;KVHF51EWQXU!qfGN+&yD7(jp((89{bs>Xo znm6z_%s(YQLe~9qnGm!wnPgEuY;1ZUdd)i}?nWH#195SmyzUKWFet9%3#n`$9tYld z2;&t?Zl6B~a&H*ym6{T2H1XZq!TP7!y{- zhVyIGH(^2Dq}jtgzgLCl`O+XKp^s`nR|$(%mUWRQOnOU*FA>vqiF1Cv4+Uhwi>?x9 zu?jnw_yS`Qfs%qTIl0IA2;}PwT++8+WcexBO+U@*=Z4*&(iW~fvsUbx@{=8@L^HK6 zL?A4M$ZWEvun3}s=#B}(cgIr#D!X)OCVo!nEvKVWz;@?jMGDV@eI6}?>qjotKon}i zX0Xrfa``!VagohI%#2bgWT5NTJ)l+sL`0vm?@ish6y5>KMqL7(B6oi?0*cW>LE3*y zk{F*Mu36zejdhoEv#EYSFE(T4JVFv4IDueq!4P?ombWOTOfp3Yc)=oAh{T9(W~s$rbj92w!dl$_-=X3R9ZB zIAvZ0OraAJgqNh4feEnexi(`a;>ve;4j~2QwWXDMmgQ5qHE8V4z`Qxa&@iy%Id=%Q zXED+S9>QYa<|*m*$peN>zUT3-YMpyUZTJJ^F-!tr_4jK0rq(oA0WR?G-8rbmSvb!g z^!%VKNRC};G9J*CJYG@7@|qCWhgVO>p;0$&4OwL z)Ld5%{{q5cYKG3Ub!;s6Cu*WSNmj>ck~^#IyJ1;zcFM51P!>(wxk{-Xu-ab$qav(P zJ8c~EhS&`(pXlsWHtf)fMfa0xIVE8wVRpbYhQX^4;etVXG1bsRQV8xzmaLlEfbtBc zmk#>h3hJa|jW^i0ZP=-x%)Ai|ErQp-92nE0S6}$rchNX8MVI{kc`|ZsCd035<^@Ce zy@UHkmsFwh-9(aMB(rwbjdO(;P(y%#y#bokzeH&OSalZ{$U26qQsZiro=?sliW?xu zc)&T7!TvJ98$sFzcFbA!#8zVobJoMg8cW0{_*k>EDqmlRCmp~_*`$btPa#8QPL2kh z((ElCzB}a6ig-E@hbg9ijZJ=7Kem|_aXZM(cgala&{y?-pccy)Yc%CYyx_)}M1JXf zxon;=N=2ORo;`CyKCvh9SlJp1$%|>&xlrrC2sjenlSC|}EU2zqDE^&N7RMRw`Mj~4 zc&NnySao_hQ@leLL-Tp_MCG&swBhzZvbb`AP4=H8-;1jNuTV-;>87N*`Lw=n6E*bC zJFcIo2D?ig=C*ROMpGd$7<-UM4{BmMo#0ZxD-_ToMSXXxQF+QxdwdC~1r?c+MP&bt zo@>6lYN~say2Wc;+QMd#YE-{i;rZlktSgF8Qv3$1)tn3LiD|Ol2Nh_svE)IcS(r`n z=N;ykG`vWEZFt}#s-#gq@}=Y(F1kqNuS;Tm|7rfs$w#ss<~qbEl7~($f1f0>=e4~7 zxfCnPzKL@z(uH4xn<7OLE=6`2nL?Eq*05+plQ9NE;XX6yFqY7clO7e9vTh2f4bKQ5 zxKANwRr6-W6J`PmS;+3-7(}7+q)Ry22mpMs0PKpXd6t4%?FWVZJ6cP)ZItyW-Rj zWwpoZ7ENXH4A!o%VCfrmtTz|nuy#}2$mXDj{!~l})wAZYD->X}cp!7pA|IpL0{RC1 z{S9f=(o;{4#pFOPxecce%2W;3T%kEHUlSpuhMABy#9~wv8mm?xo;vLaVCcX(7u#!0 zOeIQ57H2***Q%rKk218MZQU@lOyyK>^^cchZB@DN@Q!%d7}(Jlj$yJ^s99ax04i~wioffWB zJ>8FSN;-i0{2+Q?J_PfE)QFElixr_8%Pwb`KW8{ir&xLTL zQ_-nN8{8nAOsd}=adU;~U4=UfpcQoOqpBC->6OccS4{9{oLPTx?9^)}$~9D@$#_Xa zDg0u$7ll)Z_DBT#B>e(zbl$`rEuuDCh|h9*|M?^PAO>-F{}88uSEPXFmvFO;mida3 zX%|BqdT=}cPCV{)u!p|VebQm@_c=|sNdEO_7-!&-;@8lwg+TKsYL&$2OuKn0+;`2( z;O!1d7K=usZA;aV^NDWBy~Dh(xAZ2RzD114Oa%DSC=Ies*+&9-w+-AE`6|knEl;ew z{QWbwCAX?37m_x~gQ;9sS}*2epj%g3b^}6^$aUQ;+!&Yf-(#-7G+{wW@*&UzqYs0_ z&?0ceFx3Gl9tS_dl8d2s-cTk^#7$v#;a^?&g|1-@C27P+$81Cc)fB@w!iVB2OU$=s zh{OQpVa0+B_a-|B7^u}#Nv|32%xy#8OeEbw;$uy0nSx>ePDa2v#L;5s<6bX~K;))$ z@QFs#T1$<%i{-hLr7=xc9jg53r@UfqeW1!8(?R=Px-4(Py)2LN1MHO{I>GnqKw#A+ zL6FE$9mlU5LalLQS3gadM7jjD_v(}9dnGX?6lqCR=aZr?c0h0GyN_6ZRZ@Rd5cZPX zrD(&Avb|sr<{WVH0b@YI%opK}bz$I}eN0ai^mGcCg0SFfa^JEYOYwI4!YsbBO&m{~f*6B}`$8%l(3|oZ zLy8)~()(c6ovr|5qYtEvz!g6X*2gaQF?aX(_wBi4jaztM!*D5Jki5XIdCEzl1N$0Y z8?6z@i-EYjSfQxV3DgI0qCt=2hrGV2;ptI=b*Aq32JJg(JEV^Y8C7B{B#XXVM<#}s zDiB&>Q*IRAB<0i_zr0dZ2E2wduSq#QVPN-4z$ar#E!(0WWujBaVwQ&MMgf`x#^~gb!QyC(pk>g$ zZca^kWa=`a-RYwCs^{j+T$uN=yA@8ca#}s94of`}JRT@OsQG_CLZAVlhaAh(p*H(x zb;u)>Xs=sUwclYmeermg&Q)c?Ap&2d2)~I%NxyL_@0Crlz7c*M81qE1O*}V!iuLCW zlE?GiO%BD6ud_BmgYIC%(PEm2UgIJ+C(!b^2z(e zf|Pxn>36|d7%aCsvv#C@yn|q-`mS+{r6~)+=+kuDtOD@;hM&QBjXz*vs%dJu)qLpx z1o0?tR|i4hN!9$|Us*DAGA}7Wswn_9`Uzh?DKwGVQc_%i81$1LA=TX^XB%8c|}TAR}AZVRp;ZEMt>T>)9H~X2Y$dQu;&kY*^-uynU0Qb-D5a z`4(myqa*G_6v&p9n`E0HRKHy{ zTE7ExLU#*A0{JX{DLx8>>@{;dM4kwq_MV603*vSXy);??GS(R3^Q8J&NhMhH7nSI* zkVL%!B@W0GfnYSVWoh6Lg$5dB-UP8sQF)sCKvFX{K@ce@dmV!wkyM%^p4Rd7NegP* zXp#=F7qfKH9S3xAfXUq?;}Ls9e${IfhCZPy^(sTQbik|s7KB51GnlTdc;1$|EVa>D+t|VOh5hY&vn)0W>q_fD;g-BgIO{sXKZhJH;juDrn0q*vX-t!eS`y8Mhz2)KkL+QTl)1=MH^zkY zOOrSQWc8DOB4HzV#CyMW2Ir8=lSH6o-#pbS&!ZSECsnCTUIBS&mud=(MC^o>U5Um# zVlwwRPgmzS2`~E_Lb^6{i#Ffy6@ZVCVRFx=8(L47P?C0I^BTiH>&~7o_9X3EMWg!m z*WaXllKTxhLMIf*>P&7E7n`W*X^c?UVcoP2GPHw}JLa+yL~e0Ld+@c@0gd~45SJ;| ziZTF38;N{}Kbd5NqJ4xvy`kN1n2vXMCVKr-{qLgaOJsN9JEoPl=$$#r^$WH`j3zF{Y)Ycz6=S2ULe9R zpODGJw8Eo=Lfb^c4L5I7PgrFnYIM;lum4t{2s!pvdFzkY@JCKNc_B6YnkW(+0!m-l z!K-N(oJ+AvSr>c;NeB=g^u~J1=@X>YiNW0Y#_!mfa!xJw*=Y14OO^04DU%0Z<`geg zNu9o6`EP}J#8w0?jegJ&*FFXjaJsy~{EYwb***>$&Ah{plcdLi18)TIP-QzIr#mS# z5mLWkH_7qEPP!sY@%Teu9=A{8{yyHd^rqloL>|q>8ubTTx@YpA1Jg(jvBCBG1bq}B z!b%sfHM6uQPz5Z4YgADCWEiECKe{pmHX`oXD^JCz=h5)|W~E-?%A|0o3%2yu#i<(! zI$pQX2`!vB>!dAPN}#ZDkBm4}Rf5cBTR%XuTraa;M^%FJ7v@rx9P_V>yW=Zsyyqk6 zm?!99S?I*Mq&HXM`I8oLgmoB046Nt6Jf^vPgb_f?_EfDb4DloeA~TBE*Qv9dQ(e}1 zW^kfuWRZhK|^y@O;-yH z+X$EuY67`##mW`l9iQAPa;_AApe4+6t`LVm7GSIXQF3vKe|boQpQ4FRD)|#ddrxv- zoheE^W4ff#jrW*Nd%c!*?cng$apr>y^+P7&)6DQ$>G;q`i5v6chl4&?;DZfB`)K;% zD*9Qz@`g2+xgz*gJb7f^8Uh_Ei4hO+0Iu+vNzEM8P0Q)g@Y@W^gRJKj;-(p2s1m=- zV|86@ghtYm><|(0Vrep30tOL(f*pP~6!TQ2CtBz@Dt?ckXqdF>(3dHbkb|@>U|*373eAzOM-%1FxuZN^ zM|~okDa0)x6v7G2?pMaE?QbLu8eB5)v3Fn>g`XaPNq7h)ctg)t*{@rRNrnWJJ z*Oj>}ETLhf(d{nHZibek_csOHb7au{HEC!j{-ugE;C4c?OnVkUGdEy$qPq?dfcB<~ zHm!Ao@S(l&}Jo65gUyXWf(ds)jA9>(_x*7pV96CS#|0`AyhJ)x0WZuxG_`EHh{fk@=E(q5{y_kwt6PCTPcGl^h zVEfz@40I-tm1$X1lMiGB2QP$8a34DayZ~Y8{UVq zUGZBv0n;B`_i=!CbOZ%4py*$O?~%WL((r7)cy)5j#kF+%6^rKjx5KLS1arVwZnxo5 zxQl+SG?f%M4fA>d6K~na*a(iHpUY0Xf~+c%gkgP(w;-dXt#=^LL2pnQuq^kG^t7G> zGiXsc=ZGW7TensOgSkIq2Tdnf;Kkr}tbF;&*2RWy1o1+#@k-$fBl3QC5vK*l(StE# zk^JrjK2b{7lIdaAVoEbDgQrwonv%m-Iwkwu2gK>wo|cf+qP}nwrwXB z+jeqdqhjB@{qMegZ};dPW3Ny9%N}#han7F4UeE7IdTN7E@Ip`jgXzCgwgR6^9m!M6 z#$S^xKe$p?GkAfVPt3;CV`hSCF5O}t-hM*w|Ca#sCU(}(H){S3(umSG)ap?3q|^({ zFu4}sbf`%#-xEkO{!}ON0>nzr+mA9nW0(9FuT7Z)JbK(dX;&8jdB~QutMWWMWOaI9 z5cW=-ut8-flpupa+bk(&mC2R+lcP9#|4&11aO5mpj>(tNSHEj*Kw}k~#4hUHZ0hcw z-mGu1)No8Z&{=JNyso^Ld_#lg*ja>K7V%{mJZscI;yi?ZX3y{Dzc|-&2mW@fukwLl zlQl~!&}dmvbx7D_d^&`{f62MAN~ru$mrEb*xw zVFJLrY8_!h9%>eLy;k7cdRZ1t)G06lU-(o?S}s{QhF?STgz}s*#SD9kHt?#yaDwwy zV9~)F_qF9v>!85tQlmyK`!Y?Lk!+Y&T_9 z$@MDCdz6eyR=!E$lwFD7?hs4Eog;iA%?wbva_L=`Cfar%ou`^ciCYRkMwaV8hsisO ztx-Es+%prG=35@CaJLvL;ouhLn>&Bd{Y|i*ibEcGHeF}JRUX&QGcj~E*DQa=3zz>1 z1;94q*qVqx)Nezq={v66wXiQeKCjQoscjV&SjAOkh!|8t4o5@|R}gcY0?oBVJ!mr# zlwDDmJJI-|s12oGVu=tjXn-8*fE-E!?*x{=*^De)08Lq^yV?wFp@mY1aE;cf(q~*l z**1<6VyVSqSADM4wyg}Msr8-lV==oYCG5J5oSfcP!@66sgl`5l#i(iaOW%)#8BOzp zUCT0Z1~v3~(=2i(I_3FU&pYcmZC2{GPY1EpQ+UXfo7h|`7A1E-E>?Emu;`GT5>5eS z6P1cU1{Ns6Up(TVp`kw0-l?B)32#&Y=azWV7Ce=`aGr&h;k;uI0ikK)DPmq}JQ33A zj=w*R-s38&Ia?}m{p>=}oQ=zIE-cd`8%86FH5y!!btdnyxpxV2wqwa(r6KyCi!qbZ zoZ-cwVlJBuo@Tsl=ma;CQL!p3dIN8C3+!5*h$~BLMKC5lTQstes52fP%TR_B(Q6>Y zRsk3Av<>Df{loW3y!T6z>skB~V0szwgw)IHfp|mK5}3Q0!^6?JYYVyi#})C0*8<{? zBH5`9gN95nGddqMjv1vI2v&FSxhsfqsMn*gI z5CWS(VR&cuM`9C=dt#FiL!uO!4d<<^UNvH;MX7s_##yxK5Pl0+t<2xpX)#RliTGgH}DW*B317r-Fu6%}CW*m}!<=cNrk^3;5L&+IdD4?Juws2kYvhG6fU9bF{2i z20PRlA!DL)P~k!>sXEA2!(X(I$Npn-L)}^bB)a2N?tM|wU8<J(Hs~%c0s|=^PGXgvZO44J_O94l3bn!nZLq<5P)>@reo_ylqw==(^3y`L zC7DSSCY!PsHVQo@ok=9dn&fYzuTDfDfy;+?W^%0J!TZcmr^plTzrsIQ^giB0hd$qP zL~cO4bVYaZ{4cwHQkB3sf+={2>|!k#_sf0ltQCHoqEB^cCDHJB1duYcy{HN&4g6Uu z+PJYToaIPj1drEV1wKNPH{IRgd(VVB$k}tmH%5R(937Tq(#lL`Ji|3AZnW|4eWNK@ zf<6ZC+6nKE@O$!=@4=?J?C^|F@j z*{gDbb@Lgd-RRmk1Ln~CCR-E1Ud0Xkg_xQ9QwWI&%2bxge0Mdq2gn`V0;z+bRnYVS zR!sTY-|2zpU=d_i&>Nmbi>ZSYt`Gh}zfEonJhdXWPx)-$uDS!qM!}UYu>!DUnbTPR#4ah{iK{?QX|s95czUhoG-!w zW{188ycC*fU*c>0oDwG95+(3I5<=I|iOG3Z0(UKJythlS3DkIm58}G-yQT8s2EGi@ zt1_2_Rh$u&zgi(V6vQ2DAJhS@OgTpOU4C;knmGT9*)doQgc_VF7UbXgl z@A>d@6JMER)ggBfCeNy>{sGti0B=~d1t33o-c$Pejh)5HReXZpE#>Nmzsiy;e!);J z>gpAHKwB(*^^2h7SN`ck83kzC-ENnN*D3GY{VCyVJPHV9LBXA4)~q5OFhD4tK$n_M zb{KMHy#qj(^QMqbm&d*DVYP|QCjJz24=~-Z%CS!TOTlIANl@^Ixp!PL2COwFL`ZHe zK!usXg1NhiPq^FEcL1m+DoQ0vu5An24!X#`XlW46OFf`@oHIG?8Vy3B=na2_PNqnY zVt_8DNN?=sGh+V6%COTZkseut(rIoUUslpND<(hiCsWk|1MTj|vl{rG>Os}wfY1a+ z`-Ch;j(j>r;1$?!CgXz-r>Q>>DQ`oM`{qSziV4>cf>xLdF$}ElBK{VZNQWBYv>WSx z2T@5-uZM7>ik<$zajV767H`o~4yU1Dd&`|o9+d4Tj?2lH?wg&KPa3!LNLh2ikv|qS z=j_gV@T*qCIjuMlsGh@>S^%M!9QFxaDv{601fH&A*rl+-1ZY4inJwh2WCEQxr`z?g zZpaA2f#7Z6XGawALU~9A4yn*9^cSHkoU@)XFS3+4j{`^TcS)U6CY)z7$DiGn*Kr=I zZOAK<7M5coE}>Fe%{`)C7m{uuf4N)(|9Ph68_Kipbj|soH|>0KdILmU;@A}q9*C3# zK7!BngtHQ4^j+@^H6ijYpBQx6tQr&Xw9~bhi_dP*p!@wkM0DC?2cITrLrA@2guXcS zq0u6{BCSR%e1NFNcA^2rtp=WNN*245ILTN3&f9|qX~IOWst!h2=S-`x_G4;}rdRER zA8(eflj=l2?ZK#Mmek93q0p+(24AsI?R~(EDbj{vGhbQrN`s<6#jD6KWmdu@eYT4% z{t)dofWTwyyFm}J$MzN{QRIZ}R$kR3wPE?|7t$!4a_5oj+ne zb>4*1aqu#?-H2?zZhygji}QZ$ZV!k;X(;e)8Fk9zJf6~So`~JA* zmg7<{*!1E&5DQjVw3G#38}JdXh7i6$&(Jvr6%j9_v1Z-jX`3Rdx_dN-T~UdgQ>)$M z^np>jblxzlSS~@cbhO5SttJhjXgFCk^Um3ta4<6$_Tu<+kKwCB8gnk3%9@+C<^`CP zI2klii23#9Ft}C!Qugs9!sh}N3w3>IEu@uo7^sKuy=LxR9b`TA@07!3#0&nix3|q7V z@ai>4rEaTvN{}gQ;GTCAFl-JgC~U{axEvw`Zx`A3JAA05Wez z>=oHi-3N+Cgm0)f3~H;Y#KFFkO6+5Wy*#M+JP!OU4%>D7GIaMRU=$UQliH=7ak z|D9|90i04{tH<#w!m742`0F7u7@vAzHZ3NT4U83C2xqLO7rdeyL#b^X9E2Rt>@KID3q+u_t5S#29bPyfE%<6eIAl#&L zMCerw`6J}61yS6|_nZve5WK=B4_$dX@$Al`V(04|b03JKexPA}y_IAi^aTw#Wfex! z=-BD;&0pE?6dcInl4c6NR!qoN=hx)G1~L)UWE7 z_Ui_{?Hq*@2B%U;kUqbb=R{A2ywarbh+!0gDUJy+Pb0kG7FX@{n4b%!@wwg=L3oys z&-f&OdJ>({jET$;fzE>C^;I5em*Ik|UHy;5m`fV8*3*=wRWo6ks@P|tEjUt_60O&pNHpF7K4CJ)Z*QZX@_)gyVG^5T4k?=GhRO zkb)lSJ2+Z)8!~5UeDRHg5d!!lZLw*17AZzk5u@JG_6=UaA9zj$^$O!wA*zO&Q69)n z;6PUJfV6#)IZtB&gr3+A4`g~_JvbugTzUbY#91}hL5PF;`8`;u=QMSoWR3DWAgQOG z0E-WEH>n*6*|RtOR3G@9Ww?B2H&nDWJOIoGhn7*OeLRl;%)>DN>jSI_mQJwplhE*0 zvTasJzx!TQUH60KXhqjF@Sbf|?t@0l&9-swRd*GA>pL)lhEqy1?x5*{dC)y4OiP;{ zbQ(S#ESaHl3C6b9NxpQzuukKCVb{Vf zvT!{IC39UTsQ{{(-6sE+6g{a+x}m-}QUecEf@b{v9y55cmYMlcSobwXo5xom&tYxc z@L=q)o-^#QijUQAqzwljAYopSKYj%nWNTAV(Z3)JvZmJNv8e*I&2bnln|v}&HQs{8 zhSP$?@i-{}#Y~a~)E7z9qqx$HmOfQP3YZ z;V%onv4HJ!Z%=azYj45s=l%$szG4=ifs>qRmM#7f+}Vd{6Z(Q&dYrMV{FLQN zWk4;r`E;3Cb20DM?f~UfFXn-7X}}aij7-I}iZ}3G6TMG33U`E9WbL1qU(1_ko0ue1 z3*;XAmSqD}0Kd0ZKT95te{+L3ATcO*7v zg9LWUQ??R>fdS77xKPTyrZw_|5(pcD%*NtIv2aX|m~`HMf&Ak&J}%hwA>sb<Xmm z{Og_bq-B06*>H$z)=rHT(V0VpZX!cN=X`{!8tt{_Tx5ZqB0m3zIN2!`qd)zERM2Rt zCef{pI9cs(TQ#_`uM$-_fuwV|TKY=tH(UUMtEd9Wa0J;m?h<{nK%rl~*{zbqOuxd2 zEBf7LLggj(@S%C7MXAQlB*4kxy7G)*K!|jMNf~W4Q#zmAl)$kiaJ#|=MD;p__A4rd zK*z=1`WnR+{8Gv^;tOoJZT|*NSQ!lhx=PHy;gW;pR?9-5K$5u@N1B+SpWeX>Rkm3N zFD#q@nknj$ak0U($#+D!);$G=W#t_6`BLOppD}(wq8Uv-JMIe8_*S^#9)8|MJpDt3kOTFQI&rtr@Xq5)gxggRUC6 z9o1v0Aj=`bn29-A|4g|t1I0_+5@)PSS2r;Qsi*N?HPEzPT1GRV(m=^&(U9&{3T#o}ug2>9UDivBu;MN^_KKzt$F|aWduiYW!FHop8=AB|3T5N4-$~uR7OlD2 zwiNAcvw1XpX|vf^Nq2NKZ6IWi#^xINoD=5B{ZmhDu)FGz2Vuu`-vjVgwdo)lUffxQZ4q~cpG&=N!V|a?+1{V+=8}Xcv#k+S)YlFKF;&air{~Z3~ z_Pz}l(lX@-g&BIr5~92z0}W~K*7{t7iE`aOG?2p^sxu#qkWwMrthr{#+y=3pM5Otk z)lwZ>S$rF5-srr?a=Io<;A09Y>!9^-M6(q`RvNmqMNgQe7|kZ9&!SVsn8h6_&A}_k zg{1WkmxVJJtMGJ@-KuF89MjAWeaq$dqT8m`C4&(0heemISH+lR{w4$K?|cmi_n()&f)*Q0 zFV=P$9kkU89+*p>><|@Vk;985jf8xB7B(8puynb*Yx>_i}(;io5l^$idVg zn20d}oE@9DkXVvsBA-=aT1%GBDQ0V8_?&_B8pSdBHch3pR-KRj1m3#)viMM0rp}@D*;p=a7 zlj*;6^M9W)hVH{_^~97xy)6jR-6Nqy8A%8LHYu6X!D6%O)|HfQF#bbW2n>8wq6$WY zP^}uBW%9u3H7R$fiqayMe#5kEI!vS=ERk(Ywc*?;TMoHMUQ)a`3AHGvP~te54@Q;| zq`S|Cs549jjK8N0`DaM+;^~_BWVIi)Tg2}|iyGkkp5r-^=+9N&=uYc=3GaeI?lu@J#i+rTU%4j(JruK-xCsIVv^Q z_)4yZ(-3|V0pJ(3WE#oE;^nLpp(kq(_o&b6mp{vXpG3_7?srgCiR#6l)`XUd!4A!} zX-Ma|lc@8BF)Q_b=G~E&$nGK@*|B4-iDP^Rt;N?P4Q{X05v4AeL*b zb&KU&7`KDYy zBpYx@>oG}fRBq0+OqETxbIpm7Le({x3qnTImD5q1@5@!lhD4bJG!{h19C44974>UJ zBc?!co?VDPUCp>g9Z~_@4cBptmnpU)m$84w6eplOvCn>~sw&E`%1a56owJ*vtZ7M5>f3s-y#1^wj#e#{pUR_W#a@V%d_~R9j_f== zeJylk&h%)s)Ql;iqQc3Vm=K4UI@O2mj-o5BP34{(v~ZeTnZPtv`jt*6gIVi5oK0Tv z$5~A_0fty!Z1`)l5WYhsj!noL2&q~bI-60J9^_CZcLR+C;tS#novGI_)g7BMZw`P?)mYY<2kl} zs1}aePq)*zFQ6pv3F!@?^Xqkw=*2iKazZ|oN-mb_6zY_6-5%z$J;p^lQh8N6epRqd zJNE8WP=~#dry}i9@HVG&*HfAJ-UNS0~ljA47b$IiD4241fbYw zJ)$BBMHx2do;A2SD1ARqPR!Og>c)k17HAO)`4)I5&eqxB0%>;6?uQR*ZK+Hk-zyqR z$9pV(9oE7J1VUM@6T*3jJ$F10-`}B5d4+3J03`8k%-$fayLg|V+IsT!^@W3S2j`RF z+D{qG4K|-lUvjX0LS)4^o0sUcW4GnBQ;e~vLi7GV64UF7A(&8Z0P>7- z(5g69*nMWiT%IV@>1Aa@oR|z&RRx$!Ydwbi2GD4;{&FWTBKHl6563K1QXN~lo9&`) z%_Iq1LxOF7kl(4Z=Xyxn#ogC)F;5g*Ja#vniJKhBC-vb8ZGNB2NC{c&LrP{4Kbg>` zlxA&11y8Lhm|Ho}f63U+igQj;biRbv2Q`@4V|{}FJxCHP%^BM@nD|hhgBirHyNj|5 zmnPFjw-K`DatJppd=speJ|P>NpCv#B*c)^7AQ9cLo}&LqICqdtW&H~6-M@+RX9@5# z7Qjt`dWjh^BCi8LeC!0z|@Yiml0(YY|z#+Ng5 zs!BU^D4MM`5sT@rufoW={8NztvN(-2NxuYtKyts3?BH18ggaA+>?Ci0Iy#0CBOAOY zVOpa1E&@cBOIMnwCnKwu#ZdSRwTuvxFHP8QinO2tj;a=QWY!r0-fN)Osad^0cOe2a? z#~`1x8SkYmoPm4#=_E9|6xEVHtFPF^#rRRjcyOeH%lk83yI5I`1bO9Lbx%cUUEnQQ z1fBfy+KL&nJfl4>$V=PYeY4$WY*(sjott7YdPE@LuHz)99><6MF!4NFhDH+VeMSV%g>nj#r8*#dQm*!!Y;KJ-WU0nBj%=P+&jQ= zn1(knXD=Ij#EM({aDyevLHW#vAeI5YW>{WNWH95T9#)-cY|VZmb4Khvq}@v?MqhHP znP>8}ufPIvXw`tCC+8LTpPj?mf6g@jrh^%Nk2U`@O^)Ed?VN+How0+HySS;1t%LEu zCY#_mX~_XT_>i6Imbq8u?yxYW-}h#{ma+mwDprc~CqoOYu=;`>nyi@upBWIoe!LP{ zZgmhKu#*sXJWSAcFAtwUyQpNiG2Hju*icT#B~6f9m06%Nc*g)Ilc|WR%HeX>6dT6& z6kt>N@@$RyNXkXRQm*RgL>Ub2pIX0{qH-m(U;nD!h>}vI7U6WmfYD~AhhZaWG0f{s zbR7_Zf8{YHRu=66(Rt(y?|<7M=eQ9iGZPH|cBsQSRKP`5qA)C`gWd|VBeJuxJ~RgS z|G9=gu~rF=j6x)vwcYG_nd9Tj8|n#O*I4}ww{~KGYCpH%*7r`G9m0J)|BDh}=Qm*c zPd%v|<-~!$>)G-7U~+|8a~nAx7eQP!cy)8uG+%p^RS7918|{Q@yhUC6CFu`HB##^YR5HOzy5^}l6mGvkjLir ztKiKi)=ps?v7B0;?7+Q!N7CKB-i*P}|LjA@3C-m&npN^$oVIs|06wEK&yE|gil9-v zRyo!L85B{)@`6x-SWy;Uk@wl{sg}Bq=qhL-*hXoHq`9gyjs|ZC(W(1SeY=~~Cy~Bu zJNLiV_rKBX6rCK*ZA|~wr~e6el=(NfBdiE`PJ-7r(ecl2LcwI0lL$BhjCAflSjT_I zGnTOsfvDQ~n9DmNk_Zjb*)r~KFB|A#VW9X}xh%zzy71+0J$ z(Z2uT16db0Sd1RXV6P9ZrbkZ;k*0@WGRl5--sV^t9xsH1*Bi>1lcMgI{~c&4^X2v7 z`Fi*E0<-%Q0-FN{IuesmEh4~BJp=`&Qf*)DcvbIb?oUm(Qs_Rf{4sb=S58#HP52gN zPxL10r*W%?@&v}LmNnaqnz(jdX!q8=99nwpR?V|5E|=2=`C1lk)m7~Y8YUrb(<}y~ zzhH%?JQ>A3=B|?aloSRqGgdpwQ~3f8R*Ysa$9>kCXaYL%S;V*!Kk|`9*?A7vQF0E? z!UPiaB}Z6YoGuJv4Ru9<#X~NnLZMH~U(*KTo^6x#Id}n|R_sj|G0a*j(pY6B^^O+D ziLs+oDYEtF)j8j!6`E4G1R}ma!nJwqvTF8?PvDC{$&0)6-dd}(%9xdw(wg8@={t#|H>Vcx|%cs4&XPy-i+(d&hO(*$DX@xUDuqK1vXqTJA%&>QK+lG z`<5BOuoHH%(7FkL3C2yT0ac^t3TP1Uo+DBCro^@LyL$zN4SMDf(6e#=!35kza^sGoH5rXmlR83I4g5Zt8t2 z^#f9wIOZmQ< zlBi|c=xj&Q`A%T$WJ@~@>f*}0x`+Wam)1&_u&v!n7bmgQTwkuzNnJN4VUg@>samVA zT)J4g0oRddr;}~rSldXoo=_;lmF^^r-^u$y0%*I&KVePWux!s1vsr0X7D@BkK}feE zgHy6^=6lI}bW!VG6QUHqktOQn+-liRh8l9FsP4KFk`?fLm{c&K9E#v|rP%-3(06e~v^9Pv@XT__RUK0$H^JVJ zZ0bVd5nRQa$g?r5vXnZ0+rnc#)`;+U@xg-eyl z(2BJ37ZDB0W%*L9^f7GZi^FOgHj#g0t&Z+kqVNilI1`h>q+a0fFDuE1Vy>!W$na4) z{vXpwyFXYBJb%;%)G*i&YGS>1bW}AhnM3sWY2ol;ErZQQECE%e0w}9s^k7uLZU`_~ zN9{;d=1?RCjdACi4;(>zO&ENK`7+cr(0(mht5>$B?lM5GsJX~erT}C}Q$`09%B`pu zRyHyvOsl7VAQH~b)P-_X2|ZItY33py4mFgcH<}JhT(^Wtu0}EFAp#R`zH|Gn+<5#j z<=dhi-HAuWnz*Vn*o&;!!i;t+=G73|d3*0M_@mx(dw zq>g3IjfdzDZG+U-pog73S0FFs^dC0EBVtXXCoaTLyk7%R+D=W}*{m2){_T=2+e)3r z>ql5;DKc=ozPFw!3ClvHL=IOe7x29s&mc%9las?jnb$W8R*u^$ldudFd0J)Fiw5Pd zN=3w(6eY2H8Dbs3O*~XL!tTT$k2?k4Yh!%I&i52LuG&gg# zv^#)i8`M@F(znv(oj1mg6l4NhkZL43%)jVRVzdatR9dq%)wFs)D}${o&}hZ=wAzW= zPu-*Me2STvmh53A!56R3aoS*By?~R5#bPp_AE7t7foP+1{UT;C0xI!_vw)Pcgw{$p z$aZ;PWxFoe$BpTYZic-_0FiI819X+Y)WKp9g)w-l-cEju913mpDidJ=P{Q)Ut@kA+ zdk@3*e=RDc1tXg>2&;>fu-<*w3dX8Wg|9ZqJJ?!l#?LY>Oba{%=5Zq8jy`JB(?<7i zGm&Z{kt)3pB0qxBBxKa@?=!SouMYrDG5b+PxT7)%{etW=P-9WZBm#bp8qjfTA@?Z` zIhX!<@^m#fQu10N2@~GQ7`#CHA3!oZJC_g$+~GGRH_u3A+`^qwVVyWzsmBl8V29YQ z3N)QI2mr zs}8|9MP~j&x2Duv3~VqnM(2@eod8_hj#m3=Gm|iX;YOt+YP=h}wO?UpA!^jHshmYe z8V@XDX?qwN9_LxwA@k-EPW>5Tf5)k~F_#)JWq@nl3w-th;zi5X6pbI4X_E`vsFH`} zom!9MBN?K*9zoym3Gw`K)xh2E0OM#1v_4MApbeM+m5wm8_GRC1Q)}Ek4;}eE8a(nl zC>-QHWKPB&7svK5#TssZQeYJStBCtrUN^#+zc5RhXI$1ZxdjO+1MqQS%pI^+fobLl z3HrdT4&@P5&^x9+9{#qDnq#|O9uLK!bNIBe>BQdR_t3{(i+BTDyv&Tm+AbsCAir)tN3>4mWVJ% z*}OBQB0i9Kq%_Rfi&W?#s=z@l@lq~cvQxqk{2ObDSN7^#P}$sr7p5S$2nFsbwHF>< z&s<~hH=xD^$4MDp160oHVl6StXrde&qj0ti&7rbJo^dJ>O~5Eu=F2qCR>|d64f5Db zf9bpM+=$A=ZOOtORMrNO>%ImTu(XICF*0`)CD)l0+1Y!7y*KAQsxUF7Y0ThhkRvc> zzBy`eNpuA=q2)~8pOmWL2 zu=@lc2aU;Vy~Y!#ljmZ!nT99mE>(mmbQZBYQ~a9PAX8>H;HHT{Di#_50>ID`GG<7O zB$&h$cqo4ooSMcHx$83_8{AP$wq@FR_ZR3EB-l1)@uE8}Ga?vq%8apdL8yv(YjZGv zR9Buh$d8EmJ9~~J9)l3B*@VX7_t)-S>>x8|xxrXDo=*R4lQQ1scPPh))A)@R;2O!; zLhsp>OrGe9^I9xsja@yc!cP-SudKdIjsR2{U7rOvQJKWR0@$Qnyi7ik<<36SBIZTd zNS#^7pF^scEuj(+QSn=ONz5zHPPpMhF}t zWM|SI6LtIyOel{gDd~AwOEKw^xFf zg4etk&otS@$lk)p@p497Ds8L1-f9)(%f-@gM%<20^YS;oqN1J@xk)wBa&H*^C{!R; zug}NR@(9tD`@L^WY9C5=N$9eh-n9ut6m~#U(3WQ}>-`jm@{Bp~nuU~b1C;A@LoO1a z?Cg}_p;bUTP+S2-r9=c!O~N>yi4JX;#0P~*Q61v zy0qjbZQYB}j9^=C?WU<6$V;jC^|UXqJznc_kg$b8+M<)9&G7k*(7J!NzrM+@Tmy4W zD2wt8%5&PbWfkQfOH<*$O22evqFb_BHI#<3J=DzeQq5wQzoU6Y^*2&B`WehJQgWkb z`ZiL9fqwrSepvOv&`NpK_h%2~Sma-uoBM)xP84cR#@6xW3rCKXY!Q{b$G8#igJ%yZ zMK-;X4g~uL1g$cg5?tOCs2Y3_apDAQ`BbPz&PPbX+SDz7u~UbL^f&6Rq;qP+C3=x? zhe)Dv!x-|32rVzzYOh;ubi86_c^YXYNhIf@a{D5T+eB0O#m=%B#f%N|DW6HXR>PK# zK#IM{Hn9h^qHtr5&(!*n_#CFuzn80# zQiYpJhL^;qcgh?WdvDI?ZE?sIlr7n1(At!aHz$aTj(7qNU!*z{oUzU-Cv~6ndoTwH zAMjJkLTAfj_8cDQYm{R5ES!IBEE%52?+E02V6#<_*)@6~ww9IJWqM$`R$QZ$J>?bZ zz;SVLy>0cwo-`^oMdm6?gPmo=UaKQMfC693k0@C#@=m%4jewz4KWG&lYKlsftQTRi z=~a3mGK>BGvpT?FSAQ>@tgBo%OcM`L8y z%q+t)&mIn}&Q0>Qawq73IJH<{s%c4M1aanWaS8T)Dl`4zn?UryIIUW%*WnROaL;M6 zgu%H@Cs*ndUVH|_T&9~Z+#Rm+U|FT|r%&Vom9=umVye10)x9ip=GL+{O8H!Yb)(Wr zwi(@bCb^H+Drdi-GCM~?z}|8?xpj}V`aBw4{C5EW3V@q3PKO!1A$dt@6$P(&X5vZ&34R_!8l(~7vLB2I`Z{zQ)?aD?-m=_A3r$$zg&#} zDop)1;Y8KJ{QG3izYBb-kl%5ND4*BV?uq)Nj7B7RL~=io@PU;n@(>Y086d^z!@~Zi zb;S`Rx(`rOH>;d4t5`N)^--!-s##0cCFHfusWiDLTWVLRRJ$}bS5^yCeq4Lok}{1= z9zT&>Z*e?rHhvv%K3$B&a>MGy*m=}Lub>SC*N%(!MOnB>*Kp~M z_95wV1_|hTV)4wL^FvAx;=3_nC1Xkt19@|9_lV!ccpk?uO}n2NdrUmt0SQZ5kSO@BpMvlfPbPl7II@ksz9=3E53 z(8(U2Z0KXiw%1A8zzLItG4wN(GL03BVKx>UnY6j#LmaAgRjW;_padw;EO91Mxh5K1 z8BF`X%{I%eXVD11JId=RP?-v}Ux&l^dkTU9X6)`6eAeDRDW};=n^nlEEg^*>o)xx* z2)Z;+pzqZtVzEwVw{`E{fD-A5;h!)5jWy-3*Kub(5FU5uj=A@xY&^XP+ z@*{p*vF5ZJj6K2!qOlgvM+b3I(O{Cq#$U$GSu7Z~1aD8uub(dO+k1!dIeQZf$rxLF zW9S_D7ha$7=5Kx_N*s|&8Ze})2#^=9#37rINS9N`wG%RV6O$^QRM@IegcT!JC1$*K zl@f;n z378PakTcfJNP~aT@Y@)x+XOK3s2(oQ#i(_p3?H7UqeJJ2Jg#?rr=50Zyx#pXF)!S- zp=g^Tjzk@6=)#BkjXWWmWKCN2GULWIsl;uRg^==@1Zz8$farBHSjp3rzZHt2CLVhC z6GOZi`PGh9yL>)%O?HIH6M{mjyj|un$-Ns;0v5|qdwL67;kcYpEulvZt1{$`YhA!oY_ELQoDxsZChn#Ll2mZkthwayg{L(oD0)=nNSTqVM4k zxYA=DGgDEc)m+F zYS&o>A> zaY=>H(kWb4zj)qdIZq{qNh-FsJc#wpo>xN+soAw6ELjNBAOJV|TrLOC$ya{HL`)M` z3Ur$4#y#b;>8x&pK?>RK9{DdW1}$YrxWBjcQ*QzSL@gR(tFFQ`Hy8tF*9ysgrH#CB zGhNeD$@M55h?~4R343qXTtpS4m+IlR6J=_ZBzLqHO%^c}+@UdxOk;rujbQ;)I?Cs0 zbX~$tNCo^c4415Yq)9H1n`m?z&ia$3D^=;#mvS~n_J>IgJ@+MkkKvLW3p@MM09DJ% zhIkl(q`ircO>u6U;Ea>C)6mSMWXU;;&3rr%4QEyPufM(%$y~X!VvHSy<>Up~b6_Y7 zozdd(7fjpr51Va2Pt4&hy+vU+HKkD~KWCf~QFR=yrC2$m4g_G&wq!7>Cp)x7kHg69 z7CT|sW(lLmGSy=Po8G2^RKFkF?X8m>BklNbxGdt5#TGa|-)N6BWvdMwx4)z8_XJ*3 z^bv&RIr3unHQe~H2Ohc|F|<7uiXk@Z4fwb{QkYx5aKmEeavIwlgz|+kcFI8o-rGnG zlV*)*F1h#V%VPp+2_>pTLJVWV^!gmGjQqntj6`{P@ z*4ymv3rRmZlb~eRqCx?VdeK^J+)?#fSADCj6eh#)64n%*^4Qep$++!Bjvx|}>5Bpn zK-9)o5@vz-7CfqqgtS%w%DydRnL!n5BSWo-nM6m3LT`qBH%RaHBp=;jc{dK$eThSR zKZj`pZdQ86`6r{{C*pnNf*#r$?^%iQ^L6GVvQ+`P?T@aQd5=RQ4&hDC2CaJkh4bKiF2BK3F6CvQ#Uybyds9i zOTP(5i*eAdaB=l=ElUA9RoFufqRkQV)$%?PwJ=<_XV)kz)**9wW}&P~BOix`h19WW zEiNu<>TatKcnfgGUUCJjSd-wE)fNg(CFb0+?S{y^FwS?#f=TFT+K{7-|4eq6a;MaQ6k23Mp&*(ZQ#0NMW4_~cQ4$RzWz;U?Qe*kqg3yEzR7ML z(b^Zzf4lkr>=0A#5Wa2?qjYiTM7xq7YHLkIZqsym6-yd0p0kKRbG0!=4R59It!4)g zbGAvw803SyUNT4p2L|`v3r0!!awj%sUS>6`?JB{DxN{*EAO(C<{K|#^n1u0?+-86+ zmUHlB4~|2`$gPN4m3|o(exX0GhqNoP#5Qy2vNuZPlR(wkuuD!@I>1k8c35A8x+ptM zEbi!|4KsJr&p+HSH7hN# zI4jejYtsULF`$fuo2OBn*+-=1uzVdEbEk(|SBY1iS?pGw)J3;QO#dD~GjPXgtuiTX zXn5ASp&tev!Y_F$9L2-_i7Oz;iwc?x3b70AznlfMYKMLm;%^l-)4*UekU4_&X3rhV zhT9un4QIg0b_{J`^M{)pK*QqYL3aKKzsUtSJTLNb3kYOazsj1A{e{a@tc>b50DlCt z$CSXcQ!qpJK`gFI9~KP4?R17OV~7{8q{Akox+ti&7>npYhbfdeF9!HKg|AePP1^X@ zsnoll*6Y{WOO`@^Eh$fuLWI9gubvf5QIOncJ7QHI5XOOZSrDkZeyrF1?S8VSCEW9} zLO|Q4tOr^Ni*Dl&va3Al-zva*ij-cZ^01S$8dfYon+fOXqAqwRjwlzR-8U9ZG1g*< zrl=_PN(oOFkJ4y*DC-rraHg90bnGJhDMN`@3!O^d)HCA$3D!f`IMKh?!9Cy{tc^;R zH+Zb4J;@zm;6m_(5XBo2u7%@Y*{`gvt)8=xKzrCdP+_svGn5Q=o`(Bnz!8zT<^j&Q zR8bP%MqbG{!I-QbQt9T{Bvlq-=&qt4AtgGg{4T6{TmA@E!_I#BLj%0tXz(3T)x?~7 z+KhTQ^~N|1L7*0w?;G>Y?ihu6ew2QrMSC$OYuT*cb67-D{XOicXxMpcXxMp*DoA-AKLSr z^Gy;Ge$17bo!#tx@6KMMD~-D~vAT{?q)p)kQ&S|au}A|yx*)}1PFbGTQf;#^C5?cQ zP;Jt$iZFuIYy0aY>|6>u0F7D|P4yCPcZr4VYXgUxMW2D`q79Ahk(yT{AfJL>!(!n} z)tt@20q(T1$n<<46h@MDeuaYCd`@2(S%@e~-j*)Y{8@ntxn>i^U|sU` zbzZC;iRzhJf6+-bqH*fA7BpyT9ud7INVr4uMWK-5 zQ|U^r7zq zC$%l1_;CCEjDNI}Jh z4K96WDcJKTtd&kt7A(PS@?(qHF4*X>WXC{^@5Rovl%xj;w&1N)>EIu z8)Z=CJ>?XhO5dMfj!_bH;?d7WzTf7;WIj_#?~JJhxp^Xn;kVrx_Mq?y~Z+9=QzL}JCX zh~EK{%vWZJ4si>;r}5KHE0dAuL~;zE64BL^26<&71DpQE*q`jF_PeMpM{I z#K!0KAI}*-(wt``Z)piDFz3oK$cjY=!Y(;7ZWS#NKddnFUhHQ0NS-h90^kF4jK^Gp zJw(8c*O{l^jT(mFAL@BOu~G`k#jz2+YwXGh3JHo;L)mDz49dC*Ifkpp^3X*AQ2>Non)nkuA?iV>#~$1Mr& z{k}NOz1`2Ab3Xk?=9F2el1de@GT$%A*F*o$+j6wmLthCXPR#J{N|mOvsJ`0~LMav56!f(X>-wPtL>B37?&*8Jhw+dD@wzh4V;BrST0 z!NiJQ9n2oPY;$d!JU!jtVz;0`GgPcsd9inSM*5~gB4d#WU$?M5;OCzkCbPt~+%}b|jpjONUL_b1fx^|vmz8goB2Q_?#wZz0~U z!JsB~0A?tV5oHJ`&KRn~&_EJafS({;NnN~DY304%ZltY%iF3em_Gp5yoF?ON1bw%dmEM5dq2S9(mj|I zZs!$KktS;msM3N8mCiF%Tgf3gU#P$xUfUGhQcMU7%8r>F4dlgr#25|zlpVyuEgL#M z>bbqfpX5lL5*jMW zFpK;NA0|`m4%Ww)%Q?Y7#curcX4_erm>$IlbpleVe3yk0!WI9{QnRRZk@S}IGFxEb zAmSkvUlG!FA3`53*NXuuBMy2)_y?aVm%x0oZdcvjpln{cZB_@4$(iR7!hvkxyR87I6;tf0VAqzV4NMiDSM z@vjN=AEW4>v!|_$`pZc(9{y-Ed*#%hE7fTzv!B->E(<--(?rA5NGBmaWcTaE8YGGu zWIxcl;1kE)fIUceam{y8XPT8+A182J5Aj?N9e@1j`oB_jE*k}2#{n4}FgebMF)PS{KS+zcL_86Wcx)sV1D zrM$?nR6MyI-lx^6^vSpM=(LFvj=U>Eb&n_)2elc_@jRwwdU8gQ2}u_!kT%l%D%v%Z zUfN7%l1Esov1E%B5(z1EOr3`_Qdy6+8SP&})%68Q#kYM3xlkY0Er?}Q1^bNhj(?15 zYX$=-m&C|Y`B0m!xRD+uGHYpbP|4bo_L)A+BdW~!BH#yd1n%`;WvwwQ3-f1alVdEHWw9Z~LRzF7H&m7MG5FCAO64(6Tb){1^PTT?%pOXsnU(i)GRZTVX3k&UjNLeg# zEMEf{q4;hZH`wfXfNPtJ*3Z|@hvDd&p!Bgx_PUTu_G@5lC{H^b$qO;=@QWqu!)9`8 zbh$V0K4h;!J;?htbDY|<$(+K&J)^|^FutkwdY-fpYFAEu4)(JCY@uQBF_dr!yftv& z$E0O=P3-|ftz&rp(@GTC5V5t0sCIbUkq{9_LPT2Vc%bD?I`x#t^gUKBvsJ%K9!zA0 z7!@G>jSPH5Te@`J$;lVP5EwG!670>0)KLUXOv+CBK$kM78kAU>fDxmNiF9Txnl*z` z>7M*ijKHq1%tNB;k} zA0q(SMmCWHYBX!&lRH?UR&oA{>iN>C6XPtDVXc^0sP)FAgJEd`ezRr`e3>$z{Pt^F zKF;*XZDnwj8P-}PQ3-n5Y;){7&6dmfQ3mEEGA{=P>hye3!SDPWsv}J~xuPpwIR)@H z_6?7!8x`uWL5Q6Qm4#a_N4$JLZ=eNRzih;georXGfgI3 zs}VB_$;_8LGz3Pkn> zZss(+(hzq$d9GLtKiQe3*;6$=2i{idscT?b(-g_miw!`RAB%5;BVo`esbfKlLpC;D zTOq~E9z+^`JRF*v5S;lCuiHo-CZNs50*>9uZrkPR!4MtcNrOL*=niI%2s5RK&5gq_ zTYXJXa%DNDVi$|4TZy=jqee+tryrr4FmO>Pl8;&$Xc~#=t0Fm85a6?C)zj7rL3Y}J z=YL@Yh#5H^dc-F0PJ#nH+(` z(BV>}YZpujzk70(YtA7*zax11VP4!x$f6LoyXokkvg{HP=2K?;SWq*NQ1(z3rQxOW zcv58w&01ox?;fdeC$;bH(b`BOH8zH1qN~$Q%5-Fk{W-z2BCQT$AJ1Z1Kt*-$vvph8 z3d_=uG?UEr{Tm3wJH6H}O^WnkWG@Y3raku0`!QZ^oL5@K;Zyq+zp!k+W{@TlcI>h| zy6F{;3+c?_&bD@K?Q&KkbSLuEw~D~eUJ4l*nwtd11Zr6mbECr3QC;7GJ0i> zP7dYP$_7;hiP4w@U(Tb|MT=^b>oux_i`Y(1yDwDk(aaFKw)-*q>ioo5eQO6XBvZA~ z@OERw{gJ39VNM|jWkKdS8K~TI@VwgCmm^qmNlnr%F!vlToJUBjV@P)xmO10!9YUFO ztsE?;7I5Iu&ji;q5;+$o>unz1((SQ(Dq>>pU$7*M?C$F%RCEHoYQBlXS)!_!i@e``2WCvwa-xTM}Gl)7ehVpox7N(SJ5^JRX=yC$oI#5Ab#HN~GL zb?_W>lHH1mvSX>pXn*gm4<4cJqa|+0&vbn>v`y2fB3*LDxF)+*Mwx(l&O z%OuOgmoA7ENT%xx4YdWCf@u`TV=a02uwoNFKJuwbC6Xm-C`cDIgWdLRSyEyJoKPs! zLU|mu7j>%!!h~?C`0>(gKb`EWH7)3*X@fbY`brYD41MucGh)Spje)FXSt4RN%;Y)C z8udn&nA?ecFsu>#t`eg9fLKfh)W-J>zM3390Rq%~HWcIwfewo}Q7(6wZ0}ay3+KB} zdYncpnG)zIf=y2mZ05unb{H35CtTX;b`NOENoz=}w`GkK(^08fSOX5zfF&tivEb_v z-uGiyF%ZIcp$M_E5LC%K6&JMepXuzgv^YvWZ?#gO`I!}duZF%f6es_0}*xw^ad zf-9$UiF;oTVey!|2Jn&CfmpPYam1hN@Z^FE;7oR zAU+yHh${Z?7}OFvD{Z_{U^iKO=k(XNNsO5(5C(eNr|aEXnn%YT>*O+&kLngpAc0bm z*Pv>jYl5-O+NeYhJv6w_M0+%Q5Z+_-H+w$xv%W=M{e^v_*wKvnK((dm*b+bG`$mkb zgnR|ps0zq!hgU9-bCMNbm=CH^JbM;=(3WBs0P6tR|LJEvrcgUmBQk$X3o6E}Z>kvA z8XGt#gE*`f6Ku&l_u7TNzGXk|1uyv;+{>Au%Y&uB8ZZXCAvC+g?b*cYaw_|h`y+$t z#qOi8hWv-R-aJD=oNbNhGgr@@Q|P(|4A0!}J%uelH6g9l=qun3r-KET@_pFWAYIsI z=zyw6mQ3IWuic>Ar^Ydyy)ygNANBmP|NE)L?g{P9TqwiB`keo-cAld~3%KiyL;fKP z$tkwlL)@kh>E6yvfmc3{7|aV?V@APq@Y#)EcJr-fi-7HqksA*({2CZ#wIOR_06^v7 z8cvIVFGfsVfDW zpAjb!LpBEKB-2K_fZf=G&Qoz-u`q7*jXi$5nG^NsTviUzlahHcsxE%?vO#XMyY>yO z(E3}*2~l3sYzr2RPHGqU^Apamr{AgdW2%roenv3Y#vNx{&GzcDRt{7?c+8%qqi84t z87?_`za{^R-ysU@JBV<*Hl8d-2Z2+^nO?Ta6>Jjb_6vYM;sy>`k`l2(#vd6lR#UM*YG6P;e9CKP# zKXkYgU}jh#0aX=Z{1)V}UA#UuGwt#^&yW84r=ZR!9Vo=B$CR`N7&y>bscBvNDOU>YzCZ4Qi^Lc zJbKb5@6&@qmP9){3bAh-^Jm#)gzjB$+3Tbo;=`lZqy%J}hZr#^IFa3|CDxSTazJoM z2CQ{$e9j*3RhV~w^Xp-oUXW9fM*sa%J{QBK{=FO|vO3XylH2@oBB?uJdnM$`+?LkP z$4^e4kRfG*h{G1#C_nn`q=d3QAQ=0>8fSc52bqeo+DL4B_oMBpGqEiNnQ8WlbiYAj zU~Z5ANYbqB$9+0-z?;z)Xzwc5LCK=G85p!)XNO776x-;=;d%Dv5u-15cA*VrUas0` z?F+^^`&NZ+z39$CsfA#51w^lzHix8AnQxJKH@SJ_jISxjjMALvo?Xp>>>_SYuf=hf zlBVBqZ^rq2D6saik}W!#kE3#0&<)M!4R!LzAcu7Q^fJ9dSQ5sC!;`lzbK2C5BB3PP zbq4SdXDQ73;@efdeHEm*xp-|kEkB)MYs&O3EP1_SJ8TkS^5+KKz$8+_^rzLy~; z6z5@1F6W09a}T;9GC=A0a8iz^;))(s(S6J+FmLK(VChKfjLvHeKOn8OClz*M906s7UYz8E!HC5WN^DLV zqS9v~OQOIwEUdtHfvrMV!GjTjG!g!V%x~sy9_QOUMvWy}B z2yVkevsUI6b@Kd0#e6 zsKh0Ion|ATeu7KwIjX6MH^c4{eNI=e!BnI@FkzHz0y1#UzyMM&?H-GAcV)Lu3wxu~g5&?IcjCrQgHXRKVCckZ{2 zi~&Jfusq&WKIZbAe!UlrS))`j!pnjo5*Bt`z5pBO`5pNolj7C)PPq1?*P{|2R|>8m zlCnOmAtZJoI>8KwLQOxIbOTQ4OPm9BA85Nci}MH=1*#6mR0Gd2t-O$V zi9Dp01-QY?xt=}Ap7OeP6i>1XrvZ_%g$+DYFv&AWKwCBHyJjtC3Y2(Af8d5b;pvOs zKR$Enz$AeOlLr9+KG)SDwNK~;$jDlF)LP@RM}Jn-EL5PM;49vs+SToUg0M z6b>RNdvgZctS_(x?GfD%)69y+C`1@gH%jZ7^&Wh#2tJ&2Bi_$Y)`*BQPFxCDZo*h^ z@syC?r)`^=po%@EJLzwtv-*h18+fUYwSP(Y!`mGGLi=)gs^7wkB)$K`PV!`-=oyKU z=ss81HiY&im24hL>xps08Uf4?`TOAXhQupK2_2)RY!N)&+c%CSo6dfj>p#FZJ>P%$ zxUHhOat_<7yF~_)7aDa6_fxxYm;m1_7ksc022-|;4CIz6ab_XtP4`IE!ZxR$YRu<; zrWCa8%t*J(xj6>m5)IYV#qQ!(8rj9F++56D%p-5a9+5>b`=)N1w3`FW+{7D`)THBa zuG3mt7mbaDsJ`R$aUh*V(?Jx*VT-o^Wt4x3#^m5oHnxW#)Fm8q+(`0u8h2FGuo@<4u~sx z?2lxRQ29kWW{w?At_*a|&+1Rafr(YQDqc~mE*KmIrKDK(4(lxxMoWbW&tQvg->7ef z2OIUyNL`ce0sd$FPbflU2=|3-=w*v=JPS0y5-K- z-MSDslHU@6)H1}o+mdC+n`@;wfw)h&V-(?ij+%4FX@WYRbRAF()`{i(87~JpmD7zN z9lVZqiBgrHZ5izZQ9nVzorCcvkH|rW$GbfbxqCvop-A9+KbtT$UiI?5^1YU0`mI(_8xC1+&L@%ZH)oJv;()nu@d`yE4NPBq41 zl7ZemYx_1FB@V?iMK&~ zk8M_a+k(ET-T=upUo@A-)lY{OezcrZy~Eoj6#l;72+Q@G*7U8M+cKsDYqA-WOr`sh zfn?0X(CJd!u;2$mt&{N`FbV6nVbSB%k+tq#l2ErA{VaTA(K5M%UiB_A)c80bpU^L| zumcV6mA6CIJ$Qzy-Md2i-)eJfwU&_mJU@xIpe71B9SQeMFe>k%Zs~G%8pa<7?MJs_ z>cv3l##~Sfo8+KgnNr>{T&W@MXE5}Tfa3wXUm@6D(ekpaD#{-wEntS48a@~tj6;;@ z+hJtv6cjZfg_2CS3v7`spW^fUZU%Z0N~9_T8`$BhF4yK|nw$UoRN{ zx#dps$AYmGkU~-4ir?JKz}V2%O54WR-0WW)@L{IrV^S#H&(U`2C3SFm;vGCIE?SEb zdgcLj7>L`S^%fa>7EU~CCxTGxry|OZE2%vMkU#zep4vXje1nYr-8$*0w)wdh{^O7D z_iwZyC7Bl_iF^Z@ZMa3GFQj6G+qfmtsHgNCWd*!^s={UrM&1YS-`keYX_2!$q^Ry* zelNCi8ew1KTYmqw$^OU&@(n!hvU6`r^YT2`-GmA5^xz|D`vUs>(;O^V_x=^8Qan~c zHTMS163cDoV2J6(4Qg@C!oEV+_qP;EP4@bbsk=3kA%2N`M%6CXD|N8t^+DSn#TXH1 zTTt#Q=O2*`Qdb?SIBE`N`26kFpsr|+l1^F>9p&WOVZ67b`b|sib04Z}a<=;qZ#*|^ zz7AHl>PbGTx_1F(AcZi9f+|3D8z2>)^fq(2*9A=+mftS6%utE~ zRK_bzzwe#zw=YOF{Hy>xhxc%F@1Vm%18b;GL1hB)<=u#hGce#C`9tD7Ho5~51q5`y zkXl|7F6_U{#_UtTIs7?f^29ez$_z-d6<75&!rhbZ*$zNNNoV)?Y68!oOU^$a(d$^p zw*p3yJSJ|~@eO%5T~7JKadOT^TC5=P1(J+8%a}EVqV9!)&c#q}xtJ5WfSu1oxKo$I z^T!JTVh!0;9EAW;(#URKV4pa^EUz>>nfo`U<5x zUx25J0l)Fg{kbXpTdp>6JL~rY#)^(Fx!TW*%FE(-dW;BY$oSM=2uSJgq(xi25J=(> zKD(KuHHmxmdgvL%#3HnyW=^TM`hlCmRmIg!cqxJU*%qthMX5y7+LRYQ-bp?i-(TjZ zjW0W%GeT*b#JgNC+yl3~7Rr;kx|iX z559oEBJ_sMc!uOHn==D;wL=NE=A{mV8S29H+XYg&>i#2K(4z^9Xsx5DMrV%;4Y=!G z7x$k$8V8+^piM_zU~aS91gq{E3Et*4rJ717ePC9j{GfPfCxAE0NGCpCyzuYWq~VsQ zPH^FZp@R1p9n{z_zTFf_@eq8F{Oa(9H)-mG2X5HtrpX1a#YV5LflKdg@9}VAXlpf|mtxO<8t54Td?(T%FG;n*f;5 zG^!9c^)lL6=)pTOlr!wKQz=11Labb+Y2entB2qv|qMIMpP1n-rvoNO3$a?wDMI5^R zd%|w>;g$X0RKB5*Mh)}}rGes9;%EmsfvctgwD&M0`kmU;jS0Fci33~Eu!dziRjYXr z0!Z3NMcM)lQLP5J(nE=Pn69R>s)n@iMM*UX^2*hsHD%%>dvtBO-A+9ajk7P2voN67 zoe5h7T71C0CD9F;zOVvJe__aHba1E=jxLF80qct>jtF#gX^pL<7DiD3;4P_2NpMv4 ziF1-^FgJMtS*#W|G9x=%gTDCoYU-^bblK${j)#FNChh#6%eJ5;#(`n5~=%CTf(2%n3?I7JP zW|Ve2B><{EDp1nc0}F#ow~mTiyvD+&F?~u@vF`u|;9Np+#kR~WaT4neK8*_k5(0kK z)@2V}85Fe6-$L^w5{#%KPjvV9_w&3n#Z_F#!aZIo0kvuHPp-54+&z4f^fQ^Mtotj$ zT63{31?|-78(uv>eM=~QwW6bx{dxbo-RQK8*6#A=T z|A8ms9gIz8`vB1_-vd0|c>rw}U&rs5nss)2&hq#42DM<~ShJ;Gjy z1QAsu<0EDnrz_d#2fQCzN!X?2aJQxJ^k76AY!KP2t^~q4pN#xsGePN18E5)c;uH)< z!X@|(k%DpR(`D8$Bw+cyJ@Rf_8|*Mkm82MRPA;giQNQ-04`N@nb%2;yVE0H>R)QZaR##OZLOOIi(6B1-7fLE873`g$IP zTnRb*L85O?iJj)W@@08VBMPrJ0$27hqX;as(3sYIwHgJMGN_}c{Xdo|xU4ObVDIk( z>}U98O#Gg`r5RZ!?I_^(OpJ4km0N@B4ECA}3^p@6Sc-GM8S?pM?!YKsyAlQ zj_U{?i>^#C7ZCyGHo4AthM*B`xUP@gpYPQW z^&P4hf;p~1Aw!Ui0+(_+( zpS2Mk$Z7L1nU{RcH5k*L!Y>FY{9*3u_3c2#0PE2MtN>?q3cv?50a=7qwI}$Z6^_8<7>2t76-0khx~Wxo(U- zWP4KKjk~n+D*{eSH}9vkJq6D)$Afg%-Z*648py6Px^DW*JjO5$Do#Qw ze$0wixp)%gj}f;Pr>9{&%6yuj(n*Ni6lT!Z3RphQkh32bz8=}WPQ$oPg>{ztb)P#3 z7I5-CzzY&UgDz8US@CO!^sdTatr|66{5uPigupWCICP-G+nZHR@IX%gJC3>R7!&Nw zTGGL#z7!N|KEmAU3pj_|%ZW#e+hHv7O8C@I7aDSVA(L0U83@HM$PGZq3t17(Ic~I6kY%v`h?j&1O2L+;-8aeC`Agi^|$uWUp8H#X|9==>m|hwMoNTD z2X{LZ6b(*yR;lq0s|u!cl?%JeR4f97+oL97`@gD+J#MaL%RF-!cNpL{^KJXDgx`AI??@F*)Njv|cZXPP$1JS4J7 zaF-0tjHrCdr;9@QK(#^zDn@W?Hd_(zQFRl7-7Jx3L(s2%JA+jOK1D)SWNVv7>*x`Xby! zwERe(m8IJEhW$NY@(g!;>cB4NX@cyw=u5V)s8?Qs^N{EHdFBo;=wMUE2g5_VJQu^J zd;A8*N=44W@MF{?vi$Lwx}J&5GxZDr4~49AX8y;?XiLci9tCl2#rT|M`5t*bart-# zbx(RRTdk_S4(>HdIoR#|LZu8Ri_$qSp~?Q_)cI1CQkeX2mYH?$-yC^P4(=#ak2F>j zq?!pA*MZGXez!TsJCJd8E<28+5rUF|`rz3`;L5C+0S+J>`FAgb@UAJP*XE+_-7R2H0=tBFP zZ;1z2_ft-^2f1eZ<4f96Iib!E9bn?N<3D)s-hiTjpn$x4_YUOcQk|z#I4lo%5pNB= zh(`ed{`pM+f^vK`q7p)M06qy(AwgL=T7b|~-^;z|D-<+H$rmLc$Ug+?U+@2XJ9)W5 z_&3V`QiK0ZjRKe<^?z!n+IIS8bpJ~k<2Pla|5P@&GNk=#ZT`PeaDPK7`5!3%2?cCQ zXAIuz7uGB{;EU=vsK@^wl!dt|t;Iic<&E{NUwc{(1SXsVH=%n60-^xSttb8scnBD< zKbq#u!T=12p_+3AJ=>cfJ70M|iYNggoU80ahAKfadV-29vIzbNTm zL%j5GV%|;Aw?HSSfw{{sH=}<^1u)=$K!_V#+x({`FEBD8h!Aza#LZwJfh6)@7{E`@ z1g~I3Bl`p3w|nH*{=DF@5z@v+;(&nM3xI(9 z-tUKit3?0j&kLnHpOuxi1L4= zU@$L%N49?tk-z94NPzzm<@pUN$QYmr9l+NMtK47Gr1%Gfq|R4;U7LUBmA|&-rES^} zQfD`SUNr!{!utya_$gWG?|~$2O-%m2gK8j^_o(X=r_BVGXEaufAoWwwtvkj2^vzAV>i)oaO_A`YIj@g*0Oy!jV%7Bu=J(TFuR&gH zd7a(R{NL}=Z|6e(#CV+`{gMa&my{3wiSeJ^`o)UZE9SpXI2FUcBmAfS zOJrUzYQC(i|0SE7zw7_kRrWufdVTrzdyw3Aeuw-c*5JU24+Mk=_{alJxl|V~|NTG3 CKm$Yo literal 0 HcmV?d00001 diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000000000000000000000000000000000000..7454180f2ae8848c63b8b4dea2cb829da983f2fa GIT binary patch literal 59536 zcma&NbC71ylI~qywr$(CZQJHswz}-9F59+k+g;UV+cs{`J?GrGXYR~=-ydruB3JCa zB64N^cILAcWk5iofq)<(fq;O7{th4@;QxID0)qN`mJ?GIqLY#rX8-|G{5M0pdVW5^ zzXk$-2kQTAC?_N@B`&6-N-rmVFE=$QD?>*=4<|!MJu@}isLc4AW#{m2if&A5T5g&~ ziuMQeS*U5sL6J698wOd)K@oK@1{peP5&Esut<#VH^u)gp`9H4)`uE!2$>RTctN+^u z=ASkePDZA-X8)rp%D;p*~P?*a_=*Kwc<^>QSH|^<0>o37lt^+Mj1;4YvJ(JR-Y+?%Nu}JAYj5 z_Qc5%Ao#F?q32i?ZaN2OSNhWL;2oDEw_({7ZbgUjna!Fqn3NzLM@-EWFPZVmc>(fZ z0&bF-Ch#p9C{YJT9Rcr3+Y_uR^At1^BxZ#eo>$PLJF3=;t_$2|t+_6gg5(j{TmjYU zK12c&lE?Eh+2u2&6Gf*IdKS&6?rYbSEKBN!rv{YCm|Rt=UlPcW9j`0o6{66#y5t9C zruFA2iKd=H%jHf%ypOkxLnO8#H}#Zt{8p!oi6)7#NqoF({t6|J^?1e*oxqng9Q2Cc zg%5Vu!em)}Yuj?kaP!D?b?(C*w!1;>R=j90+RTkyEXz+9CufZ$C^umX^+4|JYaO<5 zmIM3#dv`DGM;@F6;(t!WngZSYzHx?9&$xEF70D1BvfVj<%+b#)vz)2iLCrTeYzUcL z(OBnNoG6Le%M+@2oo)&jdOg=iCszzv59e zDRCeaX8l1hC=8LbBt|k5?CXgep=3r9BXx1uR8!p%Z|0+4Xro=xi0G!e{c4U~1j6!) zH6adq0}#l{%*1U(Cb%4AJ}VLWKBPi0MoKFaQH6x?^hQ!6em@993xdtS%_dmevzeNl z(o?YlOI=jl(`L9^ z0O+H9k$_@`6L13eTT8ci-V0ljDMD|0ifUw|Q-Hep$xYj0hTO@0%IS^TD4b4n6EKDG z??uM;MEx`s98KYN(K0>c!C3HZdZ{+_53DO%9k5W%pr6yJusQAv_;IA}925Y%;+!tY z%2k!YQmLLOr{rF~!s<3-WEUs)`ix_mSU|cNRBIWxOox_Yb7Z=~Q45ZNe*u|m^|)d* zog=i>`=bTe!|;8F+#H>EjIMcgWcG2ORD`w0WD;YZAy5#s{65~qfI6o$+Ty&-hyMyJ z3Ra~t>R!p=5ZpxA;QkDAoPi4sYOP6>LT+}{xp}tk+<0k^CKCFdNYG(Es>p0gqD)jP zWOeX5G;9(m@?GOG7g;e74i_|SmE?`B2i;sLYwRWKLy0RLW!Hx`=!LH3&k=FuCsM=9M4|GqzA)anEHfxkB z?2iK-u(DC_T1};KaUT@3nP~LEcENT^UgPvp!QC@Dw&PVAhaEYrPey{nkcn(ro|r7XUz z%#(=$7D8uP_uU-oPHhd>>^adbCSQetgSG`e$U|7mr!`|bU0aHl_cmL)na-5x1#OsVE#m*+k84Y^+UMeSAa zbrVZHU=mFwXEaGHtXQq`2ZtjfS!B2H{5A<3(nb-6ARVV8kEmOkx6D2x7~-6hl;*-*}2Xz;J#a8Wn;_B5=m zl3dY;%krf?i-Ok^Pal-}4F`{F@TYPTwTEhxpZK5WCpfD^UmM_iYPe}wpE!Djai6_{ z*pGO=WB47#Xjb7!n2Ma)s^yeR*1rTxp`Mt4sfA+`HwZf%!7ZqGosPkw69`Ix5Ku6G z@Pa;pjzV&dn{M=QDx89t?p?d9gna*}jBly*#1!6}5K<*xDPJ{wv4& zM$17DFd~L*Te3A%yD;Dp9UGWTjRxAvMu!j^Tbc}2v~q^59d4bz zvu#!IJCy(BcWTc`;v$9tH;J%oiSJ_i7s;2`JXZF+qd4C)vY!hyCtl)sJIC{ebI*0> z@x>;EzyBv>AI-~{D6l6{ST=em*U( z(r$nuXY-#CCi^8Z2#v#UXOt`dbYN1z5jzNF2 z411?w)whZrfA20;nl&C1Gi+gk<`JSm+{|*2o<< zqM#@z_D`Cn|0H^9$|Tah)0M_X4c37|KQ*PmoT@%xHc3L1ZY6(p(sNXHa&49Frzto& zR`c~ClHpE~4Z=uKa5S(-?M8EJ$zt0&fJk~p$M#fGN1-y$7!37hld`Uw>Urri(DxLa;=#rK0g4J)pXMC zxzraOVw1+kNWpi#P=6(qxf`zSdUC?D$i`8ZI@F>k6k zz21?d+dw7b&i*>Kv5L(LH-?J%@WnqT7j#qZ9B>|Zl+=> z^U-pV@1y_ptHo4hl^cPRWewbLQ#g6XYQ@EkiP z;(=SU!yhjHp%1&MsU`FV1Z_#K1&(|5n(7IHbx&gG28HNT)*~-BQi372@|->2Aw5It z0CBpUcMA*QvsPy)#lr!lIdCi@1k4V2m!NH)%Px(vu-r(Q)HYc!p zJ^$|)j^E#q#QOgcb^pd74^JUi7fUmMiNP_o*lvx*q%_odv49Dsv$NV;6J z9GOXKomA{2Pb{w}&+yHtH?IkJJu~}Z?{Uk++2mB8zyvh*xhHKE``99>y#TdD z&(MH^^JHf;g(Tbb^&8P*;_i*2&fS$7${3WJtV7K&&(MBV2~)2KB3%cWg#1!VE~k#C z!;A;?p$s{ihyojEZz+$I1)L}&G~ml=udD9qh>Tu(ylv)?YcJT3ihapi!zgPtWb*CP zlLLJSRCj-^w?@;RU9aL2zDZY1`I3d<&OMuW=c3$o0#STpv_p3b9Wtbql>w^bBi~u4 z3D8KyF?YE?=HcKk!xcp@Cigvzy=lnFgc^9c%(^F22BWYNAYRSho@~*~S)4%AhEttv zvq>7X!!EWKG?mOd9&n>vvH1p4VzE?HCuxT-u+F&mnsfDI^}*-d00-KAauEaXqg3k@ zy#)MGX!X;&3&0s}F3q40ZmVM$(H3CLfpdL?hB6nVqMxX)q=1b}o_PG%r~hZ4gUfSp zOH4qlEOW4OMUc)_m)fMR_rl^pCfXc{$fQbI*E&mV77}kRF z&{<06AJyJ!e863o-V>FA1a9Eemx6>^F$~9ppt()ZbPGfg_NdRXBWoZnDy2;#ODgf! zgl?iOcF7Meo|{AF>KDwTgYrJLb$L2%%BEtO>T$C?|9bAB&}s;gI?lY#^tttY&hfr# zKhC+&b-rpg_?~uVK%S@mQleU#_xCsvIPK*<`E0fHE1&!J7!xD#IB|SSPW6-PyuqGn3^M^Rz%WT{e?OI^svARX&SAdU77V(C~ zM$H{Kg59op{<|8ry9ecfP%=kFm(-!W&?U0@<%z*+!*<e0XesMxRFu9QnGqun6R_%T+B%&9Dtk?*d$Q zb~>84jEAPi@&F@3wAa^Lzc(AJz5gsfZ7J53;@D<;Klpl?sK&u@gie`~vTsbOE~Cd4 z%kr56mI|#b(Jk&;p6plVwmNB0H@0SmgdmjIn5Ne@)}7Vty(yb2t3ev@22AE^s!KaN zyQ>j+F3w=wnx7w@FVCRe+`vUH)3gW%_72fxzqX!S&!dchdkRiHbXW1FMrIIBwjsai8`CB2r4mAbwp%rrO>3B$Zw;9=%fXI9B{d(UzVap7u z6piC-FQ)>}VOEuPpuqznpY`hN4dGa_1Xz9rVg(;H$5Te^F0dDv*gz9JS<|>>U0J^# z6)(4ICh+N_Q`Ft0hF|3fSHs*?a=XC;e`sJaU9&d>X4l?1W=|fr!5ShD|nv$GK;j46@BV6+{oRbWfqOBRb!ir88XD*SbC(LF}I1h#6@dvK%Toe%@ zhDyG$93H8Eu&gCYddP58iF3oQH*zLbNI;rN@E{T9%A8!=v#JLxKyUe}e}BJpB{~uN zqgxRgo0*-@-iaHPV8bTOH(rS(huwK1Xg0u+e!`(Irzu@Bld&s5&bWgVc@m7;JgELd zimVs`>vQ}B_1(2#rv#N9O`fJpVfPc7V2nv34PC);Dzbb;p!6pqHzvy?2pD&1NE)?A zt(t-ucqy@wn9`^MN5apa7K|L=9>ISC>xoc#>{@e}m#YAAa1*8-RUMKwbm|;5p>T`Z zNf*ph@tnF{gmDa3uwwN(g=`Rh)4!&)^oOy@VJaK4lMT&5#YbXkl`q?<*XtsqD z9PRK6bqb)fJw0g-^a@nu`^?71k|m3RPRjt;pIkCo1{*pdqbVs-Yl>4E>3fZx3Sv44grW=*qdSoiZ9?X0wWyO4`yDHh2E!9I!ZFi zVL8|VtW38}BOJHW(Ax#KL_KQzarbuE{(%TA)AY)@tY4%A%P%SqIU~8~-Lp3qY;U-} z`h_Gel7;K1h}7$_5ZZT0&%$Lxxr-<89V&&TCsu}LL#!xpQ1O31jaa{U34~^le*Y%L za?7$>Jk^k^pS^_M&cDs}NgXlR>16AHkSK-4TRaJSh#h&p!-!vQY%f+bmn6x`4fwTp z$727L^y`~!exvmE^W&#@uY!NxJi`g!i#(++!)?iJ(1)2Wk;RN zFK&O4eTkP$Xn~4bB|q8y(btx$R#D`O@epi4ofcETrx!IM(kWNEe42Qh(8*KqfP(c0 zouBl6>Fc_zM+V;F3znbo{x#%!?mH3`_ANJ?y7ppxS@glg#S9^MXu|FM&ynpz3o&Qh z2ujAHLF3($pH}0jXQsa#?t--TnF1P73b?4`KeJ9^qK-USHE)4!IYgMn-7z|=ALF5SNGkrtPG@Y~niUQV2?g$vzJN3nZ{7;HZHzWAeQ;5P|@Tl3YHpyznGG4-f4=XflwSJY+58-+wf?~Fg@1p1wkzuu-RF3j2JX37SQUc? zQ4v%`V8z9ZVZVqS8h|@@RpD?n0W<=hk=3Cf8R?d^9YK&e9ZybFY%jdnA)PeHvtBe- zhMLD+SSteHBq*q)d6x{)s1UrsO!byyLS$58WK;sqip$Mk{l)Y(_6hEIBsIjCr5t>( z7CdKUrJTrW%qZ#1z^n*Lb8#VdfzPw~OIL76aC+Rhr<~;4Tl!sw?Rj6hXj4XWa#6Tp z@)kJ~qOV)^Rh*-?aG>ic2*NlC2M7&LUzc9RT6WM%Cpe78`iAowe!>(T0jo&ivn8-7 zs{Qa@cGy$rE-3AY0V(l8wjI^uB8Lchj@?L}fYal^>T9z;8juH@?rG&g-t+R2dVDBe zq!K%{e-rT5jX19`(bP23LUN4+_zh2KD~EAYzhpEO3MUG8@}uBHH@4J zd`>_(K4q&>*k82(dDuC)X6JuPrBBubOg7qZ{?x!r@{%0);*`h*^F|%o?&1wX?Wr4b z1~&cy#PUuES{C#xJ84!z<1tp9sfrR(i%Tu^jnXy;4`Xk;AQCdFC@?V%|; zySdC7qS|uQRcH}EFZH%mMB~7gi}a0utE}ZE_}8PQH8f;H%PN41Cb9R%w5Oi5el^fd z$n{3SqLCnrF##x?4sa^r!O$7NX!}&}V;0ZGQ&K&i%6$3C_dR%I7%gdQ;KT6YZiQrW zk%q<74oVBV>@}CvJ4Wj!d^?#Zwq(b$E1ze4$99DuNg?6t9H}k_|D7KWD7i0-g*EO7 z;5{hSIYE4DMOK3H%|f5Edx+S0VI0Yw!tsaRS2&Il2)ea^8R5TG72BrJue|f_{2UHa z@w;^c|K3da#$TB0P3;MPlF7RuQeXT$ zS<<|C0OF(k)>fr&wOB=gP8!Qm>F41u;3esv7_0l%QHt(~+n; zf!G6%hp;Gfa9L9=AceiZs~tK+Tf*Wof=4!u{nIO90jH@iS0l+#%8=~%ASzFv7zqSB^?!@N7)kp0t&tCGLmzXSRMRyxCmCYUD2!B`? zhs$4%KO~m=VFk3Buv9osha{v+mAEq=ik3RdK@;WWTV_g&-$U4IM{1IhGX{pAu%Z&H zFfwCpUsX%RKg);B@7OUzZ{Hn{q6Vv!3#8fAg!P$IEx<0vAx;GU%}0{VIsmFBPq_mb zpe^BChDK>sc-WLKl<6 zwbW|e&d&dv9Wu0goueyu>(JyPx1mz0v4E?cJjFuKF71Q1)AL8jHO$!fYT3(;U3Re* zPPOe%*O+@JYt1bW`!W_1!mN&=w3G9ru1XsmwfS~BJ))PhD(+_J_^N6j)sx5VwbWK| zwRyC?W<`pOCY)b#AS?rluxuuGf-AJ=D!M36l{ua?@SJ5>e!IBr3CXIxWw5xUZ@Xrw z_R@%?{>d%Ld4p}nEsiA@v*nc6Ah!MUs?GA7e5Q5lPpp0@`%5xY$C;{%rz24$;vR#* zBP=a{)K#CwIY%p} zXVdxTQ^HS@O&~eIftU+Qt^~(DGxrdi3k}DdT^I7Iy5SMOp$QuD8s;+93YQ!OY{eB24%xY7ml@|M7I(Nb@K_-?F;2?et|CKkuZK_>+>Lvg!>JE~wN`BI|_h6$qi!P)+K-1Hh(1;a`os z55)4Q{oJiA(lQM#;w#Ta%T0jDNXIPM_bgESMCDEg6rM33anEr}=|Fn6)|jBP6Y}u{ zv9@%7*#RI9;fv;Yii5CI+KrRdr0DKh=L>)eO4q$1zmcSmglsV`*N(x=&Wx`*v!!hn6X-l0 zP_m;X??O(skcj+oS$cIdKhfT%ABAzz3w^la-Ucw?yBPEC+=Pe_vU8nd-HV5YX6X8r zZih&j^eLU=%*;VzhUyoLF;#8QsEfmByk+Y~caBqSvQaaWf2a{JKB9B>V&r?l^rXaC z8)6AdR@Qy_BxQrE2Fk?ewD!SwLuMj@&d_n5RZFf7=>O>hzVE*seW3U?_p|R^CfoY`?|#x9)-*yjv#lo&zP=uI`M?J zbzC<^3x7GfXA4{FZ72{PE*-mNHyy59Q;kYG@BB~NhTd6pm2Oj=_ zizmD?MKVRkT^KmXuhsk?eRQllPo2Ubk=uCKiZ&u3Xjj~<(!M94c)Tez@9M1Gfs5JV z->@II)CDJOXTtPrQudNjE}Eltbjq>6KiwAwqvAKd^|g!exgLG3;wP+#mZYr`cy3#39e653d=jrR-ulW|h#ddHu(m9mFoW~2yE zz5?dB%6vF}+`-&-W8vy^OCxm3_{02royjvmwjlp+eQDzFVEUiyO#gLv%QdDSI#3W* z?3!lL8clTaNo-DVJw@ynq?q!%6hTQi35&^>P85G$TqNt78%9_sSJt2RThO|JzM$iL zg|wjxdMC2|Icc5rX*qPL(coL!u>-xxz-rFiC!6hD1IR%|HSRsV3>Kq~&vJ=s3M5y8SG%YBQ|{^l#LGlg!D?E>2yR*eV%9m$_J6VGQ~AIh&P$_aFbh zULr0Z$QE!QpkP=aAeR4ny<#3Fwyw@rZf4?Ewq`;mCVv}xaz+3ni+}a=k~P+yaWt^L z@w67!DqVf7D%7XtXX5xBW;Co|HvQ8WR1k?r2cZD%U;2$bsM%u8{JUJ5Z0k= zZJARv^vFkmWx15CB=rb=D4${+#DVqy5$C%bf`!T0+epLJLnh1jwCdb*zuCL}eEFvE z{rO1%gxg>1!W(I!owu*mJZ0@6FM(?C+d*CeceZRW_4id*D9p5nzMY&{mWqrJomjIZ z97ZNnZ3_%Hx8dn;H>p8m7F#^2;T%yZ3H;a&N7tm=Lvs&lgJLW{V1@h&6Vy~!+Ffbb zv(n3+v)_D$}dqd!2>Y2B)#<+o}LH#%ogGi2-?xRIH)1!SD)u-L65B&bsJTC=LiaF+YOCif2dUX6uAA|#+vNR z>U+KQekVGon)Yi<93(d!(yw1h3&X0N(PxN2{%vn}cnV?rYw z$N^}_o!XUB!mckL`yO1rnUaI4wrOeQ(+&k?2mi47hzxSD`N#-byqd1IhEoh!PGq>t z_MRy{5B0eKY>;Ao3z$RUU7U+i?iX^&r739F)itdrTpAi-NN0=?^m%?{A9Ly2pVv>Lqs6moTP?T2-AHqFD-o_ znVr|7OAS#AEH}h8SRPQ@NGG47dO}l=t07__+iK8nHw^(AHx&Wb<%jPc$$jl6_p(b$ z)!pi(0fQodCHfM)KMEMUR&UID>}m^(!{C^U7sBDOA)$VThRCI0_+2=( zV8mMq0R(#z;C|7$m>$>`tX+T|xGt(+Y48@ZYu#z;0pCgYgmMVbFb!$?%yhZqP_nhn zy4<#3P1oQ#2b51NU1mGnHP$cf0j-YOgAA}A$QoL6JVLcmExs(kU{4z;PBHJD%_=0F z>+sQV`mzijSIT7xn%PiDKHOujX;n|M&qr1T@rOxTdxtZ!&u&3HHFLYD5$RLQ=heur zb>+AFokUVQeJy-#LP*^)spt{mb@Mqe=A~-4p0b+Bt|pZ+@CY+%x}9f}izU5;4&QFE zO1bhg&A4uC1)Zb67kuowWY4xbo&J=%yoXlFB)&$d*-}kjBu|w!^zbD1YPc0-#XTJr z)pm2RDy%J3jlqSMq|o%xGS$bPwn4AqitC6&e?pqWcjWPt{3I{>CBy;hg0Umh#c;hU3RhCUX=8aR>rmd` z7Orw(5tcM{|-^J?ZAA9KP|)X6n9$-kvr#j5YDecTM6n z&07(nD^qb8hpF0B^z^pQ*%5ePYkv&FabrlI61ntiVp!!C8y^}|<2xgAd#FY=8b*y( zuQOuvy2`Ii^`VBNJB&R!0{hABYX55ooCAJSSevl4RPqEGb)iy_0H}v@vFwFzD%>#I>)3PsouQ+_Kkbqy*kKdHdfkN7NBcq%V{x^fSxgXpg7$bF& zj!6AQbDY(1u#1_A#1UO9AxiZaCVN2F0wGXdY*g@x$ByvUA?ePdide0dmr#}udE%K| z3*k}Vv2Ew2u1FXBaVA6aerI36R&rzEZeDDCl5!t0J=ug6kuNZzH>3i_VN`%BsaVB3 zQYw|Xub_SGf{)F{$ZX5`Jc!X!;eybjP+o$I{Z^Hsj@D=E{MnnL+TbC@HEU2DjG{3-LDGIbq()U87x4eS;JXnSh;lRlJ z>EL3D>wHt-+wTjQF$fGyDO$>d+(fq@bPpLBS~xA~R=3JPbS{tzN(u~m#Po!?H;IYv zE;?8%^vle|%#oux(Lj!YzBKv+Fd}*Ur-dCBoX*t{KeNM*n~ZPYJ4NNKkI^MFbz9!v z4(Bvm*Kc!-$%VFEewYJKz-CQN{`2}KX4*CeJEs+Q(!kI%hN1!1P6iOq?ovz}X0IOi z)YfWpwW@pK08^69#wSyCZkX9?uZD?C^@rw^Y?gLS_xmFKkooyx$*^5#cPqntNTtSG zlP>XLMj2!VF^0k#ole7`-c~*~+_T5ls?x4)ah(j8vo_ zwb%S8qoaZqY0-$ZI+ViIA_1~~rAH7K_+yFS{0rT@eQtTAdz#8E5VpwnW!zJ_^{Utv zlW5Iar3V5t&H4D6A=>?mq;G92;1cg9a2sf;gY9pJDVKn$DYdQlvfXq}zz8#LyPGq@ z+`YUMD;^-6w&r-82JL7mA8&M~Pj@aK!m{0+^v<|t%APYf7`}jGEhdYLqsHW-Le9TL z_hZZ1gbrz7$f9^fAzVIP30^KIz!!#+DRLL+qMszvI_BpOSmjtl$hh;&UeM{ER@INV zcI}VbiVTPoN|iSna@=7XkP&-4#06C};8ajbxJ4Gcq8(vWv4*&X8bM^T$mBk75Q92j z1v&%a;OSKc8EIrodmIiw$lOES2hzGDcjjB`kEDfJe{r}yE6`eZL zEB`9u>Cl0IsQ+t}`-cx}{6jqcANucqIB>Qmga_&<+80E2Q|VHHQ$YlAt{6`Qu`HA3 z03s0-sSlwbvgi&_R8s={6<~M^pGvBNjKOa>tWenzS8s zR>L7R5aZ=mSU{f?ib4Grx$AeFvtO5N|D>9#)ChH#Fny2maHWHOf2G=#<9Myot#+4u zWVa6d^Vseq_0=#AYS(-m$Lp;*8nC_6jXIjEM`omUmtH@QDs3|G)i4j*#_?#UYVZvJ z?YjT-?!4Q{BNun;dKBWLEw2C-VeAz`%?A>p;)PL}TAZn5j~HK>v1W&anteARlE+~+ zj>c(F;?qO3pXBb|#OZdQnm<4xWmn~;DR5SDMxt0UK_F^&eD|KZ=O;tO3vy4@4h^;2 zUL~-z`-P1aOe?|ZC1BgVsL)2^J-&vIFI%q@40w0{jjEfeVl)i9(~bt2z#2Vm)p`V_ z1;6$Ae7=YXk#=Qkd24Y23t&GvRxaOoad~NbJ+6pxqzJ>FY#Td7@`N5xp!n(c!=RE& z&<<@^a$_Ys8jqz4|5Nk#FY$~|FPC0`*a5HH!|Gssa9=~66&xG9)|=pOOJ2KE5|YrR zw!w6K2aC=J$t?L-;}5hn6mHd%hC;p8P|Dgh6D>hGnXPgi;6r+eA=?f72y9(Cf_ho{ zH6#)uD&R=73^$$NE;5piWX2bzR67fQ)`b=85o0eOLGI4c-Tb@-KNi2pz=Ke@SDcPn za$AxXib84`!Sf;Z3B@TSo`Dz7GM5Kf(@PR>Ghzi=BBxK8wRp>YQoXm+iL>H*Jo9M3 z6w&E?BC8AFTFT&Tv8zf+m9<&S&%dIaZ)Aoqkak_$r-2{$d~0g2oLETx9Y`eOAf14QXEQw3tJne;fdzl@wV#TFXSLXM2428F-Q}t+n2g%vPRMUzYPvzQ9f# zu(liiJem9P*?0%V@RwA7F53r~|I!Ty)<*AsMX3J{_4&}{6pT%Tpw>)^|DJ)>gpS~1rNEh z0$D?uO8mG?H;2BwM5a*26^7YO$XjUm40XmBsb63MoR;bJh63J;OngS5sSI+o2HA;W zdZV#8pDpC9Oez&L8loZO)MClRz!_!WD&QRtQxnazhT%Vj6Wl4G11nUk8*vSeVab@N#oJ}`KyJv+8Mo@T1-pqZ1t|?cnaVOd;1(h9 z!$DrN=jcGsVYE-0-n?oCJ^4x)F}E;UaD-LZUIzcD?W^ficqJWM%QLy6QikrM1aKZC zi{?;oKwq^Vsr|&`i{jIphA8S6G4)$KGvpULjH%9u(Dq247;R#l&I0{IhcC|oBF*Al zvLo7Xte=C{aIt*otJD}BUq)|_pdR>{zBMT< z(^1RpZv*l*m*OV^8>9&asGBo8h*_4q*)-eCv*|Pq=XNGrZE)^(SF7^{QE_~4VDB(o zVcPA_!G+2CAtLbl+`=Q~9iW`4ZRLku!uB?;tWqVjB0lEOf}2RD7dJ=BExy=<9wkb- z9&7{XFA%n#JsHYN8t5d~=T~5DcW4$B%3M+nNvC2`0!#@sckqlzo5;hhGi(D9=*A4` z5ynobawSPRtWn&CDLEs3Xf`(8^zDP=NdF~F^s&={l7(aw&EG}KWpMjtmz7j_VLO;@ zM2NVLDxZ@GIv7*gzl1 zjq78tv*8#WSY`}Su0&C;2F$Ze(q>F(@Wm^Gw!)(j;dk9Ad{STaxn)IV9FZhm*n+U} zi;4y*3v%A`_c7a__DJ8D1b@dl0Std3F||4Wtvi)fCcBRh!X9$1x!_VzUh>*S5s!oq z;qd{J_r79EL2wIeiGAqFstWtkfIJpjVh%zFo*=55B9Zq~y0=^iqHWfQl@O!Ak;(o*m!pZqe9 z%U2oDOhR)BvW8&F70L;2TpkzIutIvNQaTjjs5V#8mV4!NQ}zN=i`i@WI1z0eN-iCS z;vL-Wxc^Vc_qK<5RPh(}*8dLT{~GzE{w2o$2kMFaEl&q zP{V=>&3kW7tWaK-Exy{~`v4J0U#OZBk{a9{&)&QG18L@6=bsZ1zC_d{{pKZ-Ey>I> z;8H0t4bwyQqgu4hmO`3|4K{R*5>qnQ&gOfdy?z`XD%e5+pTDzUt3`k^u~SaL&XMe= z9*h#kT(*Q9jO#w2Hd|Mr-%DV8i_1{J1MU~XJ3!WUplhXDYBpJH><0OU`**nIvPIof z|N8@I=wA)sf45SAvx||f?Z5uB$kz1qL3Ky_{%RPdP5iN-D2!p5scq}buuC00C@jom zhfGKm3|f?Z0iQ|K$Z~!`8{nmAS1r+fp6r#YDOS8V*;K&Gs7Lc&f^$RC66O|)28oh`NHy&vq zJh+hAw8+ybTB0@VhWN^0iiTnLsCWbS_y`^gs!LX!Lw{yE``!UVzrV24tP8o;I6-65 z1MUiHw^{bB15tmrVT*7-#sj6cs~z`wk52YQJ*TG{SE;KTm#Hf#a~|<(|ImHH17nNM z`Ub{+J3dMD!)mzC8b(2tZtokKW5pAwHa?NFiso~# z1*iaNh4lQ4TS)|@G)H4dZV@l*Vd;Rw;-;odDhW2&lJ%m@jz+Panv7LQm~2Js6rOW3 z0_&2cW^b^MYW3)@o;neZ<{B4c#m48dAl$GCc=$>ErDe|?y@z`$uq3xd(%aAsX)D%l z>y*SQ%My`yDP*zof|3@_w#cjaW_YW4BdA;#Glg1RQcJGY*CJ9`H{@|D+*e~*457kd z73p<%fB^PV!Ybw@)Dr%(ZJbX}xmCStCYv#K3O32ej{$9IzM^I{6FJ8!(=azt7RWf4 z7ib0UOPqN40X!wOnFOoddd8`!_IN~9O)#HRTyjfc#&MCZ zZAMzOVB=;qwt8gV?{Y2?b=iSZG~RF~uyx18K)IDFLl})G1v@$(s{O4@RJ%OTJyF+Cpcx4jmy|F3euCnMK!P2WTDu5j z{{gD$=M*pH!GGzL%P)V2*ROm>!$Y=z|D`!_yY6e7SU$~a5q8?hZGgaYqaiLnkK%?0 zs#oI%;zOxF@g*@(V4p!$7dS1rOr6GVs6uYCTt2h)eB4?(&w8{#o)s#%gN@BBosRUe z)@P@8_Zm89pr~)b>e{tbPC~&_MR--iB{=)y;INU5#)@Gix-YpgP<-c2Ms{9zuCX|3 z!p(?VaXww&(w&uBHzoT%!A2=3HAP>SDxcljrego7rY|%hxy3XlODWffO_%g|l+7Y_ zqV(xbu)s4lV=l7M;f>vJl{`6qBm>#ZeMA}kXb97Z)?R97EkoI?x6Lp0yu1Z>PS?2{ z0QQ(8D)|lc9CO3B~e(pQM&5(1y&y=e>C^X$`)_&XuaI!IgDTVqt31wX#n+@!a_A0ZQkA zCJ2@M_4Gb5MfCrm5UPggeyh)8 zO9?`B0J#rkoCx(R0I!ko_2?iO@|oRf1;3r+i)w-2&j?=;NVIdPFsB)`|IC0zk6r9c zRrkfxWsiJ(#8QndNJj@{@WP2Ackr|r1VxV{7S&rSU(^)-M8gV>@UzOLXu9K<{6e{T zXJ6b92r$!|lwjhmgqkdswY&}c)KW4A)-ac%sU;2^fvq7gfUW4Bw$b!i@duy1CAxSn z(pyh$^Z=&O-q<{bZUP+$U}=*#M9uVc>CQVgDs4swy5&8RAHZ~$)hrTF4W zPsSa~qYv_0mJnF89RnnJTH`3}w4?~epFl=D(35$ zWa07ON$`OMBOHgCmfO(9RFc<)?$x)N}Jd2A(<*Ll7+4jrRt9w zwGxExUXd9VB#I|DwfxvJ;HZ8Q{37^wDhaZ%O!oO(HpcqfLH%#a#!~;Jl7F5>EX_=8 z{()l2NqPz>La3qJR;_v+wlK>GsHl;uRA8%j`A|yH@k5r%55S9{*Cp%uw6t`qc1!*T za2OeqtQj7sAp#Q~=5Fs&aCR9v>5V+s&RdNvo&H~6FJOjvaj--2sYYBvMq;55%z8^o z|BJDA4vzfow#DO#ZQHh;Oq_{r+qP{R9ox2TOgwQiv7Ow!zjN+A@BN;0tA2lUb#+zO z(^b89eV)D7UVE+h{mcNc6&GtpOqDn_?VAQ)Vob$hlFwW%xh>D#wml{t&Ofmm_d_+; zKDxzdr}`n2Rw`DtyIjrG)eD0vut$}dJAZ0AohZ+ZQdWXn_Z@dI_y=7t3q8x#pDI-K z2VVc&EGq445Rq-j0=U=Zx`oBaBjsefY;%)Co>J3v4l8V(T8H?49_@;K6q#r~Wwppc z4XW0(4k}cP=5ex>-Xt3oATZ~bBWKv)aw|I|Lx=9C1s~&b77idz({&q3T(Y(KbWO?+ zmcZ6?WeUsGk6>km*~234YC+2e6Zxdl~<_g2J|IE`GH%n<%PRv-50; zH{tnVts*S5*_RxFT9eM0z-pksIb^drUq4>QSww=u;UFCv2AhOuXE*V4z?MM`|ABOC4P;OfhS(M{1|c%QZ=!%rQTDFx`+}?Kdx$&FU?Y<$x;j7z=(;Lyz+?EE>ov!8vvMtSzG!nMie zsBa9t8as#2nH}n8xzN%W%U$#MHNXmDUVr@GX{?(=yI=4vks|V)!-W5jHsU|h_&+kY zS_8^kd3jlYqOoiI`ZqBVY!(UfnAGny!FowZWY_@YR0z!nG7m{{)4OS$q&YDyw6vC$ zm4!$h>*|!2LbMbxS+VM6&DIrL*X4DeMO!@#EzMVfr)e4Tagn~AQHIU8?e61TuhcKD zr!F4(kEebk(Wdk-?4oXM(rJwanS>Jc%<>R(siF+>+5*CqJLecP_we33iTFTXr6W^G z7M?LPC-qFHK;E!fxCP)`8rkxZyFk{EV;G-|kwf4b$c1k0atD?85+|4V%YATWMG|?K zLyLrws36p%Qz6{}>7b>)$pe>mR+=IWuGrX{3ZPZXF3plvuv5Huax86}KX*lbPVr}L z{C#lDjdDeHr~?l|)Vp_}T|%$qF&q#U;ClHEPVuS+Jg~NjC1RP=17=aQKGOcJ6B3mp z8?4*-fAD~}sX*=E6!}^u8)+m2j<&FSW%pYr_d|p_{28DZ#Cz0@NF=gC-o$MY?8Ca8 zr5Y8DSR^*urS~rhpX^05r30Ik#2>*dIOGxRm0#0YX@YQ%Mg5b6dXlS!4{7O_kdaW8PFSdj1=ryI-=5$fiieGK{LZ+SX(1b=MNL!q#lN zv98?fqqTUH8r8C7v(cx#BQ5P9W>- zmW93;eH6T`vuJ~rqtIBg%A6>q>gnWb3X!r0wh_q;211+Om&?nvYzL1hhtjB zK_7G3!n7PL>d!kj){HQE zE8(%J%dWLh1_k%gVXTZt zEdT09XSKAx27Ncaq|(vzL3gm83q>6CAw<$fTnMU05*xAe&rDfCiu`u^1)CD<>sx0i z*hr^N_TeN89G(nunZoLBf^81#pmM}>JgD@Nn1l*lN#a=B=9pN%tmvYFjFIoKe_(GF z-26x{(KXdfsQL7Uv6UtDuYwV`;8V3w>oT_I<`Ccz3QqK9tYT5ZQzbop{=I=!pMOCb zCU68`n?^DT%^&m>A%+-~#lvF!7`L7a{z<3JqIlk1$<||_J}vW1U9Y&eX<}l8##6i( zZcTT@2`9(Mecptm@{3A_Y(X`w9K0EwtPq~O!16bq{7c0f7#(3wn-^)h zxV&M~iiF!{-6A@>o;$RzQ5A50kxXYj!tcgme=Qjrbje~;5X2xryU;vH|6bE(8z^<7 zQ>BG7_c*JG8~K7Oe68i#0~C$v?-t@~@r3t2inUnLT(c=URpA9kA8uq9PKU(Ps(LVH zqgcqW>Gm?6oV#AldDPKVRcEyQIdTT`Qa1j~vS{<;SwyTdr&3*t?J)y=M7q*CzucZ&B0M=joT zBbj@*SY;o2^_h*>R0e({!QHF0=)0hOj^B^d*m>SnRrwq>MolNSgl^~r8GR#mDWGYEIJA8B<|{{j?-7p zVnV$zancW3&JVDtVpIlI|5djKq0(w$KxEFzEiiL=h5Jw~4Le23@s(mYyXWL9SX6Ot zmb)sZaly_P%BeX_9 zw&{yBef8tFm+%=--m*J|o~+Xg3N+$IH)t)=fqD+|fEk4AAZ&!wcN5=mi~Vvo^i`}> z#_3ahR}Ju)(Px7kev#JGcSwPXJ2id9%Qd2A#Uc@t8~egZ8;iC{e! z%=CGJOD1}j!HW_sgbi_8suYnn4#Ou}%9u)dXd3huFIb!ytlX>Denx@pCS-Nj$`VO&j@(z!kKSP0hE4;YIP#w9ta=3DO$7f*x zc9M4&NK%IrVmZAe=r@skWD`AEWH=g+r|*13Ss$+{c_R!b?>?UaGXlw*8qDmY#xlR= z<0XFbs2t?8i^G~m?b|!Hal^ZjRjt<@a? z%({Gn14b4-a|#uY^=@iiKH+k?~~wTj5K1A&hU z2^9-HTC)7zpoWK|$JXaBL6C z#qSNYtY>65T@Zs&-0cHeu|RX(Pxz6vTITdzJdYippF zC-EB+n4}#lM7`2Ry~SO>FxhKboIAF#Z{1wqxaCb{#yEFhLuX;Rx(Lz%T`Xo1+a2M}7D+@wol2)OJs$TwtRNJ={( zD@#zTUEE}#Fz#&(EoD|SV#bayvr&E0vzmb%H?o~46|FAcx?r4$N z&67W3mdip-T1RIxwSm_&(%U|+WvtGBj*}t69XVd&ebn>KOuL(7Y8cV?THd-(+9>G7*Nt%T zcH;`p={`SOjaf7hNd(=37Lz3-51;58JffzIPgGs_7xIOsB5p2t&@v1mKS$2D$*GQ6 zM(IR*j4{nri7NMK9xlDy-hJW6sW|ZiDRaFiayj%;(%51DN!ZCCCXz+0Vm#};70nOx zJ#yA0P3p^1DED;jGdPbQWo0WATN=&2(QybbVdhd=Vq*liDk`c7iZ?*AKEYC#SY&2g z&Q(Ci)MJ{mEat$ZdSwTjf6h~roanYh2?9j$CF@4hjj_f35kTKuGHvIs9}Re@iKMxS-OI*`0S z6s)fOtz}O$T?PLFVSeOjSO26$@u`e<>k(OSP!&YstH3ANh>)mzmKGNOwOawq-MPXe zy4xbeUAl6tamnx))-`Gi2uV5>9n(73yS)Ukma4*7fI8PaEwa)dWHs6QA6>$}7?(L8 ztN8M}?{Tf!Zu22J5?2@95&rQ|F7=FK-hihT-vDp!5JCcWrVogEnp;CHenAZ)+E+K5 z$Cffk5sNwD_?4+ymgcHR(5xgt20Z8M`2*;MzOM#>yhk{r3x=EyM226wb&!+j`W<%* zSc&|`8!>dn9D@!pYow~(DsY_naSx7(Z4i>cu#hA5=;IuI88}7f%)bRkuY2B;+9Uep zpXcvFWkJ!mQai63BgNXG26$5kyhZ2&*3Q_tk)Ii4M>@p~_~q_cE!|^A;_MHB;7s#9 zKzMzK{lIxotjc};k67^Xsl-gS!^*m*m6kn|sbdun`O?dUkJ{0cmI0-_2y=lTAfn*Y zKg*A-2sJq)CCJgY0LF-VQvl&6HIXZyxo2#!O&6fOhbHXC?%1cMc6y^*dOS{f$=137Ds1m01qs`>iUQ49JijsaQ( zksqV9@&?il$|4Ua%4!O15>Zy&%gBY&wgqB>XA3!EldQ%1CRSM(pp#k~-pkcCg4LAT zXE=puHbgsw)!xtc@P4r~Z}nTF=D2~j(6D%gTBw$(`Fc=OOQ0kiW$_RDd=hcO0t97h zb86S5r=>(@VGy1&#S$Kg_H@7G^;8Ue)X5Y+IWUi`o;mpvoV)`fcVk4FpcT|;EG!;? zHG^zrVVZOm>1KFaHlaogcWj(v!S)O(Aa|Vo?S|P z5|6b{qkH(USa*Z7-y_Uvty_Z1|B{rTS^qmEMLEYUSk03_Fg&!O3BMo{b^*`3SHvl0 zhnLTe^_vVIdcSHe)SQE}r~2dq)VZJ!aSKR?RS<(9lzkYo&dQ?mubnWmgMM37Nudwo z3Vz@R{=m2gENUE3V4NbIzAA$H1z0pagz94-PTJyX{b$yndsdKptmlKQKaaHj@3=ED zc7L?p@%ui|RegVYutK$64q4pe9+5sv34QUpo)u{1ci?)_7gXQd{PL>b0l(LI#rJmN zGuO+%GO`xneFOOr4EU(Wg}_%bhzUf;d@TU+V*2#}!2OLwg~%D;1FAu=Un>OgjPb3S z7l(riiCwgghC=Lm5hWGf5NdGp#01xQ59`HJcLXbUR3&n%P(+W2q$h2Qd z*6+-QXJ*&Kvk9ht0f0*rO_|FMBALen{j7T1l%=Q>gf#kma zQlg#I9+HB+z*5BMxdesMND`_W;q5|FaEURFk|~&{@qY32N$G$2B=&Po{=!)x5b!#n zxLzblkq{yj05#O7(GRuT39(06FJlalyv<#K4m}+vs>9@q-&31@1(QBv82{}Zkns~K ze{eHC_RDX0#^A*JQTwF`a=IkE6Ze@j#-8Q`tTT?k9`^ZhA~3eCZJ-Jr{~7Cx;H4A3 zcZ+Zj{mzFZbVvQ6U~n>$U2ZotGsERZ@}VKrgGh0xM;Jzt29%TX6_&CWzg+YYMozrM z`nutuS)_0dCM8UVaKRj804J4i%z2BA_8A4OJRQ$N(P9Mfn-gF;4#q788C@9XR0O3< zsoS4wIoyt046d+LnSCJOy@B@Uz*#GGd#+Ln1ek5Dv>(ZtD@tgZlPnZZJGBLr^JK+!$$?A_fA3LOrkoDRH&l7 zcMcD$Hsjko3`-{bn)jPL6E9Ds{WskMrivsUu5apD z?grQO@W7i5+%X&E&p|RBaEZ(sGLR@~(y^BI@lDMot^Ll?!`90KT!JXUhYS`ZgX3jnu@Ja^seA*M5R@f`=`ynQV4rc$uT1mvE?@tz)TN<=&H1%Z?5yjxcpO+6y_R z6EPuPKM5uxKpmZfT(WKjRRNHs@ib)F5WAP7QCADvmCSD#hPz$V10wiD&{NXyEwx5S z6NE`3z!IS^$s7m}PCwQutVQ#~w+V z=+~->DI*bR2j0^@dMr9`p>q^Ny~NrAVxrJtX2DUveic5vM%#N*XO|?YAWwNI$Q)_) zvE|L(L1jP@F%gOGtnlXtIv2&1i8q<)Xfz8O3G^Ea~e*HJsQgBxWL(yuLY+jqUK zRE~`-zklrGog(X}$9@ZVUw!8*=l`6mzYLtsg`AvBYz(cxmAhr^j0~(rzXdiOEeu_p zE$sf2(w(BPAvO5DlaN&uQ$4@p-b?fRs}d7&2UQ4Fh?1Hzu*YVjcndqJLw0#q@fR4u zJCJ}>_7-|QbvOfylj+e^_L`5Ep9gqd>XI3-O?Wp z-gt*P29f$Tx(mtS`0d05nHH=gm~Po_^OxxUwV294BDKT>PHVlC5bndncxGR!n(OOm znsNt@Q&N{TLrmsoKFw0&_M9$&+C24`sIXGWgQaz=kY;S{?w`z^Q0JXXBKFLj0w0U6P*+jPKyZHX9F#b0D1$&(- zrm8PJd?+SrVf^JlfTM^qGDK&-p2Kdfg?f>^%>1n8bu&byH(huaocL>l@f%c*QkX2i znl}VZ4R1en4S&Bcqw?$=Zi7ohqB$Jw9x`aM#>pHc0x z0$!q7iFu zZ`tryM70qBI6JWWTF9EjgG@>6SRzsd}3h+4D8d~@CR07P$LJ}MFsYi-*O%XVvD@yT|rJ+Mk zDllJ7$n0V&A!0flbOf)HE6P_afPWZmbhpliqJuw=-h+r;WGk|ntkWN(8tKlYpq5Ow z(@%s>IN8nHRaYb*^d;M(D$zGCv5C|uqmsDjwy4g=Lz>*OhO3z=)VD}C<65;`89Ye} zSCxrv#ILzIpEx1KdLPlM&%Cctf@FqTKvNPXC&`*H9=l=D3r!GLM?UV zOxa(8ZsB`&+76S-_xuj?G#wXBfDY@Z_tMpXJS7^mp z@YX&u0jYw2A+Z+bD#6sgVK5ZgdPSJV3>{K^4~%HV?rn~4D)*2H!67Y>0aOmzup`{D zzDp3c9yEbGCY$U<8biJ_gB*`jluz1ShUd!QUIQJ$*1;MXCMApJ^m*Fiv88RZ zFopLViw}{$Tyhh_{MLGIE2~sZ)t0VvoW%=8qKZ>h=adTe3QM$&$PO2lfqH@brt!9j ziePM8$!CgE9iz6B<6_wyTQj?qYa;eC^{x_0wuwV~W+^fZmFco-o%wsKSnjXFEx02V zF5C2t)T6Gw$Kf^_c;Ei3G~uC8SM-xyycmXyC2hAVi-IfXqhu$$-C=*|X?R0~hu z8`J6TdgflslhrmDZq1f?GXF7*ALeMmOEpRDg(s*H`4>_NAr`2uqF;k;JQ+8>A|_6ZNsNLECC%NNEb1Y1dP zbIEmNpK)#XagtL4R6BC{C5T(+=yA-(Z|Ap}U-AfZM#gwVpus3(gPn}Q$CExObJ5AC z)ff9Yk?wZ}dZ-^)?cbb9Fw#EjqQ8jxF4G3=L?Ra zg_)0QDMV1y^A^>HRI$x?Op@t;oj&H@1xt4SZ9(kifQ zb59B*`M99Td7@aZ3UWvj1rD0sE)d=BsBuW*KwkCds7ay(7*01_+L}b~7)VHI>F_!{ zyxg-&nCO?v#KOUec0{OOKy+sjWA;8rTE|Lv6I9H?CI?H(mUm8VXGwU$49LGpz&{nQp2}dinE1@lZ1iox6{ghN&v^GZv9J${7WaXj)<0S4g_uiJ&JCZ zr8-hsu`U%N;+9N^@&Q0^kVPB3)wY(rr}p7{p0qFHb3NUUHJb672+wRZs`gd1UjKPX z4o6zljKKA+Kkj?H>Ew63o%QjyBk&1!P22;MkD>sM0=z_s-G{mTixJCT9@_|*(p^bz zJ8?ZZ&;pzV+7#6Mn`_U-)k8Pjg?a;|Oe^us^PoPY$Va~yi8|?+&=y$f+lABT<*pZr zP}D{~Pq1Qyni+@|aP;ixO~mbEW9#c0OU#YbDZIaw=_&$K%Ep2f%hO^&P67hApZe`x zv8b`Mz@?M_7-)b!lkQKk)JXXUuT|B8kJlvqRmRpxtQDgvrHMXC1B$M@Y%Me!BSx3P z#2Eawl$HleZhhTS6Txm>lN_+I`>eV$&v9fOg)%zVn3O5mI*lAl>QcHuW6!Kixmq`X zBCZ*Ck6OYtDiK!N47>jxI&O2a9x7M|i^IagRr-fmrmikEQGgw%J7bO|)*$2FW95O4 zeBs>KR)izRG1gRVL;F*sr8A}aRHO0gc$$j&ds8CIO1=Gwq1%_~E)CWNn9pCtBE}+`Jelk4{>S)M)`Ll=!~gnn1yq^EX(+y*ik@3Ou0qU`IgYi3*doM+5&dU!cho$pZ zn%lhKeZkS72P?Cf68<#kll_6OAO26bIbueZx**j6o;I0cS^XiL`y+>{cD}gd%lux} z)3N>MaE24WBZ}s0ApfdM;5J_Ny}rfUyxfkC``Awo2#sgLnGPewK};dORuT?@I6(5~ z?kE)Qh$L&fwJXzK){iYx!l5$Tt|^D~MkGZPA}(o6f7w~O2G6Vvzdo*a;iXzk$B66$ zwF#;wM7A+(;uFG4+UAY(2`*3XXx|V$K8AYu#ECJYSl@S=uZW$ksfC$~qrrbQj4??z-)uz0QL}>k^?fPnJTPw% zGz)~?B4}u0CzOf@l^um}HZzbaIwPmb<)< zi_3@E9lc)Qe2_`*Z^HH;1CXOceL=CHpHS{HySy3T%<^NrWQ}G0i4e1xm_K3(+~oi$ zoHl9wzb?Z4j#90DtURtjtgvi7uw8DzHYmtPb;?%8vb9n@bszT=1qr)V_>R%s!92_` zfnHQPANx z<#hIjIMm#*(v*!OXtF+w8kLu`o?VZ5k7{`vw{Yc^qYclpUGIM_PBN1+c{#Vxv&E*@ zxg=W2W~JuV{IuRYw3>LSI1)a!thID@R=bU+cU@DbR^_SXY`MC7HOsCN z!dO4OKV7(E_Z8T#8MA1H`99?Z!r0)qKW_#|29X3#Jb+5+>qUidbeP1NJ@)(qi2S-X zao|f0_tl(O+$R|Qwd$H{_ig|~I1fbp_$NkI!0E;Y z6JrnU{1Ra6^on{9gUUB0mwzP3S%B#h0fjo>JvV~#+X0P~JV=IG=yHG$O+p5O3NUgG zEQ}z6BTp^Fie)Sg<){Z&I8NwPR(=mO4joTLHkJ>|Tnk23E(Bo`FSbPc05lF2-+)X? z6vV3*m~IBHTy*^E!<0nA(tCOJW2G4DsH7)BxLV8kICn5lu6@U*R`w)o9;Ro$i8=Q^V%uH8n3q=+Yf;SFRZu z!+F&PKcH#8cG?aSK_Tl@K9P#8o+jry@gdexz&d(Q=47<7nw@e@FFfIRNL9^)1i@;A z28+$Z#rjv-wj#heI|<&J_DiJ*s}xd-f!{J8jfqOHE`TiHHZVIA8CjkNQ_u;Ery^^t zl1I75&u^`1_q)crO+JT4rx|z2ToSC>)Or@-D zy3S>jW*sNIZR-EBsfyaJ+Jq4BQE4?SePtD2+jY8*%FsSLZ9MY>+wk?}}}AFAw)vr{ml)8LUG-y9>^t!{~|sgpxYc0Gnkg`&~R z-pilJZjr@y5$>B=VMdZ73svct%##v%wdX~9fz6i3Q-zOKJ9wso+h?VME7}SjL=!NUG{J?M&i!>ma`eoEa@IX`5G>B1(7;%}M*%-# zfhJ(W{y;>MRz!Ic8=S}VaBKqh;~7KdnGEHxcL$kA-6E~=!hrN*zw9N+_=odt<$_H_8dbo;0=42wcAETPCVGUr~v(`Uai zb{=D!Qc!dOEU6v)2eHSZq%5iqK?B(JlCq%T6av$Cb4Rko6onlG&?CqaX7Y_C_cOC3 zYZ;_oI(}=>_07}Oep&Ws7x7-R)cc8zfe!SYxJYP``pi$FDS)4Fvw5HH=FiU6xfVqIM!hJ;Rx8c0cB7~aPtNH(Nmm5Vh{ibAoU#J6 zImRCr?(iyu_4W_6AWo3*vxTPUw@vPwy@E0`(>1Qi=%>5eSIrp^`` zK*Y?fK_6F1W>-7UsB)RPC4>>Ps9)f+^MqM}8AUm@tZ->j%&h1M8s*s!LX5&WxQcAh z8mciQej@RPm?660%>{_D+7er>%zX_{s|$Z+;G7_sfNfBgY(zLB4Ey}J9F>zX#K0f6 z?dVNIeEh?EIShmP6>M+d|0wMM85Sa4diw1hrg|ITJ}JDg@o8y>(rF9mXk5M z2@D|NA)-7>wD&wF;S_$KS=eE84`BGw3g0?6wGxu8ys4rwI?9U=*^VF22t3%mbGeOh z`!O-OpF7#Vceu~F`${bW0nYVU9ecmk31V{tF%iv&5hWofC>I~cqAt@u6|R+|HLMMX zVxuSlMFOK_EQ86#E8&KwxIr8S9tj_goWtLv4f@!&h8;Ov41{J~496vp9vX=(LK#j! zAwi*21RAV-LD>9Cw3bV_9X(X3)Kr0-UaB*7Y>t82EQ%!)(&(XuAYtTsYy-dz+w=$ir)VJpe!_$ z6SGpX^i(af3{o=VlFPC);|J8#(=_8#vdxDe|Cok+ANhYwbE*FO`Su2m1~w+&9<_9~ z-|tTU_ACGN`~CNW5WYYBn^B#SwZ(t4%3aPp z;o)|L6Rk569KGxFLUPx@!6OOa+5OjQLK5w&nAmwxkC5rZ|m&HT8G%GVZxB_@ME z>>{rnXUqyiJrT(8GMj_ap#yN_!9-lO5e8mR3cJiK3NE{_UM&=*vIU`YkiL$1%kf+1 z4=jk@7EEj`u(jy$HnzE33ZVW_J4bj}K;vT?T91YlO(|Y0FU4r+VdbmQ97%(J5 zkK*Bed8+C}FcZ@HIgdCMioV%A<*4pw_n}l*{Cr4}a(lq|injK#O?$tyvyE`S%(1`H z_wwRvk#13ElkZvij2MFGOj`fhy?nC^8`Zyo%yVcUAfEr8x&J#A{|moUBAV_^f$hpaUuyQeY3da^ zS9iRgf87YBwfe}>BO+T&Fl%rfpZh#+AM?Dq-k$Bq`vG6G_b4z%Kbd&v>qFjow*mBl z-OylnqOpLg}or7_VNwRg2za3VBK6FUfFX{|TD z`Wt0Vm2H$vdlRWYQJqDmM?JUbVqL*ZQY|5&sY*?!&%P8qhA~5+Af<{MaGo(dl&C5t zE%t!J0 zh6jqANt4ABdPxSTrVV}fLsRQal*)l&_*rFq(Ez}ClEH6LHv{J#v?+H-BZ2)Wy{K@9 z+ovXHq~DiDvm>O~r$LJo!cOuwL+Oa--6;UFE2q@g3N8Qkw5E>ytz^(&($!O47+i~$ zKM+tkAd-RbmP{s_rh+ugTD;lriL~`Xwkad#;_aM?nQ7L_muEFI}U_4$phjvYgleK~`Fo`;GiC07&Hq1F<%p;9Q;tv5b?*QnR%8DYJH3P>Svmv47Y>*LPZJy8_{9H`g6kQpyZU{oJ`m%&p~D=K#KpfoJ@ zn-3cqmHsdtN!f?~w+(t+I`*7GQA#EQC^lUA9(i6=i1PqSAc|ha91I%X&nXzjYaM{8$s&wEx@aVkQ6M{E2 zfzId#&r(XwUNtPcq4Ngze^+XaJA1EK-%&C9j>^9(secqe{}z>hR5CFNveMsVA)m#S zk)_%SidkY-XmMWlVnQ(mNJ>)ooszQ#vaK;!rPmGKXV7am^_F!Lz>;~{VrIO$;!#30XRhE1QqO_~#+Ux;B_D{Nk=grn z8Y0oR^4RqtcYM)7a%@B(XdbZCOqnX#fD{BQTeLvRHd(irHKq=4*jq34`6@VAQR8WG z^%)@5CXnD_T#f%@-l${>y$tfb>2LPmc{~5A82|16mH)R?&r#KKLs7xpN-D`=&Cm^R zvMA6#Ahr<3X>Q7|-qfTY)}32HkAz$_mibYV!I)u>bmjK`qwBe(>za^0Kt*HnFbSdO z1>+ryKCNxmm^)*$XfiDOF2|{-v3KKB?&!(S_Y=Ht@|ir^hLd978xuI&N{k>?(*f8H z=ClxVJK_%_z1TH0eUwm2J+2To7FK4o+n_na)&#VLn1m;!+CX+~WC+qg1?PA~KdOlC zW)C@pw75_xoe=w7i|r9KGIvQ$+3K?L{7TGHwrQM{dCp=Z*D}3kX7E-@sZnup!BImw z*T#a=+WcTwL78exTgBn|iNE3#EsOorO z*kt)gDzHiPt07fmisA2LWN?AymkdqTgr?=loT7z@d`wnlr6oN}@o|&JX!yPzC*Y8d zu6kWlTzE1)ckyBn+0Y^HMN+GA$wUO_LN6W>mxCo!0?oiQvT`z$jbSEu&{UHRU0E8# z%B^wOc@S!yhMT49Y)ww(Xta^8pmPCe@eI5C*ed96)AX9<>))nKx0(sci8gwob_1}4 z0DIL&vsJ1_s%<@y%U*-eX z5rN&(zef-5G~?@r79oZGW1d!WaTqQn0F6RIOa9tJ=0(kdd{d1{<*tHT#cCvl*i>YY zH+L7jq8xZNcTUBqj(S)ztTU!TM!RQ}In*n&Gn<>(60G7}4%WQL!o>hbJqNDSGwl#H z`4k+twp0cj%PsS+NKaxslAEu9!#U3xT1|_KB6`h=PI0SW`P9GTa7caD1}vKEglV8# zjKZR`pluCW19c2fM&ZG)c3T3Um;ir3y(tSCJ7Agl6|b524dy5El{^EQBG?E61H0XY z`bqg!;zhGhyMFl&(o=JWEJ8n~z)xI}A@C0d2hQGvw7nGv)?POU@(kS1m=%`|+^ika zXl8zjS?xqW$WlO?Ewa;vF~XbybHBor$f<%I&*t$F5fynwZlTGj|IjZtVfGa7l&tK} zW>I<69w(cZLu)QIVG|M2xzW@S+70NinQzk&Y0+3WT*cC)rx~04O-^<{JohU_&HL5XdUKW!uFy|i$FB|EMu0eUyW;gsf`XfIc!Z0V zeK&*hPL}f_cX=@iv>K%S5kL;cl_$v?n(Q9f_cChk8Lq$glT|=e+T*8O4H2n<=NGmn z+2*h+v;kBvF>}&0RDS>)B{1!_*XuE8A$Y=G8w^qGMtfudDBsD5>T5SB;Qo}fSkkiV ze^K^M(UthkwrD!&*tTsu>Dacdj_q`~V%r_twr$(Ct&_dKeeXE?fA&4&yASJWJ*}~- zel=@W)tusynfC_YqH4ll>4Eg`Xjs5F7Tj>tTLz<0N3)X<1px_d2yUY>X~y>>93*$) z5PuNMQLf9Bu?AAGO~a_|J2akO1M*@VYN^VxvP0F$2>;Zb9;d5Yfd8P%oFCCoZE$ z4#N$^J8rxYjUE_6{T%Y>MmWfHgScpuGv59#4u6fpTF%~KB^Ae`t1TD_^Ud#DhL+Dm zbY^VAM#MrAmFj{3-BpVSWph2b_Y6gCnCAombVa|1S@DU)2r9W<> zT5L8BB^er3zxKt1v(y&OYk!^aoQisqU zH(g@_o)D~BufUXcPt!Ydom)e|aW{XiMnes2z&rE?og>7|G+tp7&^;q?Qz5S5^yd$i z8lWr4g5nctBHtigX%0%XzIAB8U|T6&JsC4&^hZBw^*aIcuNO47de?|pGXJ4t}BB`L^d8tD`H`i zqrP8?#J@8T#;{^B!KO6J=@OWKhAerih(phML`(Rg7N1XWf1TN>=Z3Do{l_!d~DND&)O)D>ta20}@Lt77qSnVsA7>)uZAaT9bsB>u&aUQl+7GiY2|dAEg@%Al3i316y;&IhQL^8fw_nwS>f60M_-m+!5)S_6EPM7Y)(Nq^8gL7(3 zOiot`6Wy6%vw~a_H?1hLVzIT^i1;HedHgW9-P#)}Y6vF%C=P70X0Tk^z9Te@kPILI z_(gk!k+0%CG)%!WnBjjw*kAKs_lf#=5HXC00s-}oM-Q1aXYLj)(1d!_a7 z*Gg4Fe6F$*ujVjI|79Z5+Pr`us%zW@ln++2l+0hsngv<{mJ%?OfSo_3HJXOCys{Ug z00*YR-(fv<=&%Q!j%b-_ppA$JsTm^_L4x`$k{VpfLI(FMCap%LFAyq;#ns5bR7V+x zO!o;c5y~DyBPqdVQX)8G^G&jWkBy2|oWTw>)?5u}SAsI$RjT#)lTV&Rf8;>u*qXnb z8F%Xb=7#$m)83z%`E;49)t3fHInhtc#kx4wSLLms!*~Z$V?bTyUGiS&m>1P(952(H zuHdv=;o*{;5#X-uAyon`hP}d#U{uDlV?W?_5UjJvf%11hKwe&(&9_~{W)*y1nR5f_ z!N(R74nNK`y8>B!0Bt_Vr!;nc3W>~RiKtGSBkNlsR#-t^&;$W#)f9tTlZz>n*+Fjz z3zXZ;jf(sTM(oDzJt4FJS*8c&;PLTW(IQDFs_5QPy+7yhi1syPCarvqrHFcf&yTy)^O<1EBx;Ir`5W{TIM>{8w&PB>ro4;YD<5LF^TjTb0!zAP|QijA+1Vg>{Afv^% zmrkc4o6rvBI;Q8rj4*=AZacy*n8B{&G3VJc)so4$XUoie0)vr;qzPZVbb<#Fc=j+8CGBWe$n|3K& z_@%?{l|TzKSlUEO{U{{%Fz_pVDxs7i9H#bnbCw7@4DR=}r_qV!Zo~CvD4ZI*+j3kO zW6_=|S`)(*gM0Z;;}nj`73OigF4p6_NPZQ-Od~e$c_);;4-7sR>+2u$6m$Gf%T{aq zle>e3(*Rt(TPD}03n5)!Ca8Pu!V}m6v0o1;5<1h$*|7z|^(3$Y&;KHKTT}hV056wuF0Xo@mK-52~r=6^SI1NC%c~CC?n>yX6wPTgiWYVz!Sx^atLby9YNn1Rk{g?|pJaxD4|9cUf|V1_I*w zzxK)hRh9%zOl=*$?XUjly5z8?jPMy%vEN)f%T*|WO|bp5NWv@B(K3D6LMl!-6dQg0 zXNE&O>Oyf%K@`ngCvbGPR>HRg5!1IV$_}m@3dWB7x3t&KFyOJn9pxRXCAzFr&%37wXG;z^xaO$ekR=LJG ztIHpY8F5xBP{mtQidqNRoz= z@){+N3(VO5bD+VrmS^YjG@+JO{EOIW)9=F4v_$Ed8rZtHvjpiEp{r^c4F6Ic#ChlC zJX^DtSK+v(YdCW)^EFcs=XP7S>Y!4=xgmv>{S$~@h=xW-G4FF9?I@zYN$e5oF9g$# zb!eVU#J+NjLyX;yb)%SY)xJdvGhsnE*JEkuOVo^k5PyS=o#vq!KD46UTW_%R=Y&0G zFj6bV{`Y6)YoKgqnir2&+sl+i6foAn-**Zd1{_;Zb7Ki=u394C5J{l^H@XN`_6XTKY%X1AgQM6KycJ+= zYO=&t#5oSKB^pYhNdzPgH~aEGW2=ec1O#s-KG z71}LOg@4UEFtp3GY1PBemXpNs6UK-ax*)#$J^pC_me;Z$Je(OqLoh|ZrW*mAMBFn< zHttjwC&fkVfMnQeen8`Rvy^$pNRFVaiEN4Pih*Y3@jo!T0nsClN)pdrr9AYLcZxZ| zJ5Wlj+4q~($hbtuY zVQ7hl>4-+@6g1i`1a)rvtp-;b0>^`Dloy(#{z~ytgv=j4q^Kl}wD>K_Y!l~ zp(_&7sh`vfO(1*MO!B%<6E_bx1)&s+Ae`O)a|X=J9y~XDa@UB`m)`tSG4AUhoM=5& znWoHlA-(z@3n0=l{E)R-p8sB9XkV zZ#D8wietfHL?J5X0%&fGg@MH~(rNS2`GHS4xTo7L$>TPme+Is~!|79=^}QbPF>m%J zFMkGzSndiPO|E~hrhCeo@&Ea{M(ieIgRWMf)E}qeTxT8Q#g-!Lu*x$v8W^M^>?-g= zwMJ$dThI|~M06rG$Sv@C@tWR>_YgaG&!BAbkGggVQa#KdtDB)lMLNVLN|51C@F^y8 zCRvMB^{GO@j=cHfmy}_pCGbP%xb{pNN>? z?7tBz$1^zVaP|uaatYaIN+#xEN4jBzwZ|YI_)p(4CUAz1ZEbDk>J~Y|63SZaak~#0 zoYKruYsWHoOlC1(MhTnsdUOwQfz5p6-D0}4;DO$B;7#M{3lSE^jnTT;ns`>!G%i*F?@pR1JO{QTuD0U+~SlZxcc8~>IB{)@8p`P&+nDxNj`*gh|u?yrv$phpQcW)Us)bi`kT%qLj(fi{dWRZ%Es2!=3mI~UxiW0$-v3vUl?#g{p6eF zMEUAqo5-L0Ar(s{VlR9g=j7+lt!gP!UN2ICMokAZ5(Agd>})#gkA2w|5+<%-CuEP# zqgcM}u@3(QIC^Gx<2dbLj?cFSws_f3e%f4jeR?4M^M3cx1f+Qr6ydQ>n)kz1s##2w zk}UyQc+Z5G-d-1}{WzjkLXgS-2P7auWSJ%pSnD|Uivj5u!xk0 z_^-N9r9o;(rFDt~q1PvE#iJZ_f>J3gcP$)SOqhE~pD2|$=GvpL^d!r z6u=sp-CrMoF7;)}Zd7XO4XihC4ji?>V&(t^?@3Q&t9Mx=qex6C9d%{FE6dvU6%d94 zIE;hJ1J)cCqjv?F``7I*6bc#X)JW2b4f$L^>j{*$R`%5VHFi*+Q$2;nyieduE}qdS{L8y8F08yLs?w}{>8>$3236T-VMh@B zq-nujsb_1aUv_7g#)*rf9h%sFj*^mIcImRV*k~Vmw;%;YH(&ylYpy!&UjUVqqtfG` zox3esju?`unJJA_zKXRJP)rA3nXc$m^{S&-p|v|-0x9LHJm;XIww7C#R$?00l&Yyj z=e}gKUOpsImwW?N)+E(awoF@HyP^EhL+GlNB#k?R<2>95hz!h9sF@U20DHSB3~WMa zk90+858r@-+vWwkawJ)8ougd(i#1m3GLN{iSTylYz$brAsP%=&m$mQQrH$g%3-^VR zE%B`Vi&m8f3T~&myTEK28BDWCVzfWir1I?03;pX))|kY5ClO^+bae z*7E?g=3g7EiisYOrE+lA)2?Ln6q2*HLNpZEWMB|O-JI_oaHZB%CvYB(%=tU= zE*OY%QY58fW#RG5=gm0NR#iMB=EuNF@)%oZJ}nmm=tsJ?eGjia{e{yuU0l3{d^D@)kVDt=1PE)&tf_hHC%0MB znL|CRCPC}SeuVTdf>-QV70`0(EHizc21s^sU>y%hW0t!0&y<7}Wi-wGy>m%(-jsDj zP?mF|>p_K>liZ6ZP(w5(|9Ga%>tLgb$|doDDfkdW>Z z`)>V2XC?NJT26mL^@ zf+IKr27TfM!UbZ@?zRddC7#6ss1sw%CXJ4FWC+t3lHZupzM77m^=9 z&(a?-LxIq}*nvv)y?27lZ{j zifdl9hyJudyP2LpU$-kXctshbJDKS{WfulP5Dk~xU4Le4c#h^(YjJit4#R8_khheS z|8(>2ibaHES4+J|DBM7I#QF5u-*EdN{n=Kt@4Zt?@Tv{JZA{`4 zU#kYOv{#A&gGPwT+$Ud}AXlK3K7hYzo$(fBSFjrP{QQ zeaKg--L&jh$9N}`pu{Bs>?eDFPaWY4|9|foN%}i;3%;@4{dc+iw>m}{3rELqH21G! z`8@;w-zsJ1H(N3%|1B@#ioLOjib)j`EiJqPQVSbPSPVHCj6t5J&(NcWzBrzCiDt{4 zdlPAUKldz%6x5II1H_+jv)(xVL+a;P+-1hv_pM>gMRr%04@k;DTokASSKKhU1Qms| zrWh3a!b(J3n0>-tipg{a?UaKsP7?+|@A+1WPDiQIW1Sf@qDU~M_P65_s}7(gjTn0X zucyEm)o;f8UyshMy&>^SC3I|C6jR*R_GFwGranWZe*I>K+0k}pBuET&M~ z;Odo*ZcT?ZpduHyrf8E%IBFtv;JQ!N_m>!sV6ly$_1D{(&nO~w)G~Y`7sD3#hQk%^ zp}ucDF_$!6DAz*PM8yE(&~;%|=+h(Rn-=1Wykas_-@d&z#=S}rDf`4w(rVlcF&lF! z=1)M3YVz7orwk^BXhslJ8jR);sh^knJW(Qmm(QdSgIAIdlN4Te5KJisifjr?eB{FjAX1a0AB>d?qY4Wx>BZ8&}5K0fA+d{l8 z?^s&l8#j7pR&ijD?0b%;lL9l$P_mi2^*_OL+b}4kuLR$GAf85sOo02?Y#90}CCDiS zZ%rbCw>=H~CBO=C_JVV=xgDe%b4FaEFtuS7Q1##y686r%F6I)s-~2(}PWK|Z8M+Gu zl$y~5@#0Ka%$M<&Cv%L`a8X^@tY&T7<0|(6dNT=EsRe0%kp1Qyq!^43VAKYnr*A5~ zsI%lK1ewqO;0TpLrT9v}!@vJK{QoVa_+N4FYT#h?Y8rS1S&-G+m$FNMP?(8N`MZP zels(*?kK{{^g9DOzkuZXJ2;SrOQsp9T$hwRB1(phw1c7`!Q!by?Q#YsSM#I12RhU{$Q+{xj83axHcftEc$mNJ8_T7A-BQc*k(sZ+~NsO~xAA zxnbb%dam_fZlHvW7fKXrB~F&jS<4FD2FqY?VG?ix*r~MDXCE^WQ|W|WM;gsIA4lQP zJ2hAK@CF*3*VqPr2eeg6GzWFlICi8S>nO>5HvWzyZTE)hlkdC_>pBej*>o0EOHR|) z$?};&I4+_?wvL*g#PJ9)!bc#9BJu1(*RdNEn>#Oxta(VWeM40ola<0aOe2kSS~{^P zDJBd}0L-P#O-CzX*%+$#v;(x%<*SPgAje=F{Zh-@ucd2DA(yC|N_|ocs*|-!H%wEw z@Q!>siv2W;C^^j^59OAX03&}&D*W4EjCvfi(ygcL#~t8XGa#|NPO+*M@Y-)ctFA@I z-p7npT1#5zOLo>7q?aZpCZ=iecn3QYklP;gF0bq@>oyBq94f6C=;Csw3PkZ|5q=(c zfs`aw?II0e(h=|7o&T+hq&m$; zBrE09Twxd9BJ2P+QPN}*OdZ-JZV7%av@OM7v!!NL8R;%WFq*?{9T3{ct@2EKgc8h) zMxoM$SaF#p<`65BwIDfmXG6+OiK0e)`I=!A3E`+K@61f}0e z!2a*FOaDrOe>U`q%K!QN`&=&0C~)CaL3R4VY(NDt{Xz(Xpqru5=r#uQN1L$Je1*dkdqQ*=lofQaN%lO!<5z9ZlHgxt|`THd>2 zsWfU$9=p;yLyJyM^t zS2w9w?Bpto`@H^xJpZDKR1@~^30Il6oFGfk5%g6w*C+VM)+%R@gfIwNprOV5{F^M2 zO?n3DEzpT+EoSV-%OdvZvNF+pDd-ZVZ&d8 zKeIyrrfPN=EcFRCPEDCVflX#3-)Ik_HCkL(ejmY8vzcf-MTA{oHk!R2*36`O68$7J zf}zJC+bbQk--9Xm!u#lgLvx8TXx2J258E5^*IZ(FXMpq$2LUUvhWQPs((z1+2{Op% z?J}9k5^N=z;7ja~zi8a_-exIqWUBJwohe#4QJ`|FF*$C{lM18z^#hX6!5B8KAkLUX ziP=oti-gpV(BsLD{0(3*dw}4JxK23Y7M{BeFPucw!sHpY&l%Ws4pSm`+~V7;bZ%Dx zeI)MK=4vC&5#;2MT7fS?^ch9?2;%<8Jlu-IB&N~gg8t;6S-#C@!NU{`p7M8@2iGc& zg|JPg%@gCoCQ&s6JvDU&`X2S<57f(k8nJ1wvBu{8r?;q3_kpZZ${?|( z+^)UvR33sjSd)aT!UPkA;ylO6{aE3MQa{g%Mcf$1KONcjO@&g5zPHWtzM1rYC{_K> zgQNcs<{&X{OA=cEWw5JGqpr0O>x*Tfak2PE9?FuWtz^DDNI}rwAaT0(bdo-<+SJ6A z&}S%boGMWIS0L}=S>|-#kRX;e^sUsotry(MjE|3_9duvfc|nwF#NHuM-w7ZU!5ei8 z6Mkf>2)WunY2eU@C-Uj-A zG(z0Tz2YoBk>zCz_9-)4a>T46$(~kF+Y{#sA9MWH%5z#zNoz)sdXq7ZR_+`RZ%0(q zC7&GyS_|BGHNFl8Xa%@>iWh%Gr?=J5<(!OEjauj5jyrA-QXBjn0OAhJJ9+v=!LK`` z@g(`^*84Q4jcDL`OA&ZV60djgwG`|bcD*i50O}Q{9_noRg|~?dj%VtKOnyRs$Uzqg z191aWoR^rDX#@iSq0n z?9Sg$WSRPqSeI<}&n1T3!6%Wj@5iw5`*`Btni~G=&;J+4`7g#OQTa>u`{4ZZ(c@s$ zK0y;ySOGD-UTjREKbru{QaS>HjN<2)R%Nn-TZiQ(Twe4p@-saNa3~p{?^V9Nixz@a zykPv~<@lu6-Ng9i$Lrk(xi2Tri3q=RW`BJYOPC;S0Yly%77c727Yj-d1vF!Fuk{Xh z)lMbA69y7*5ufET>P*gXQrxsW+ zz)*MbHZv*eJPEXYE<6g6_M7N%#%mR{#awV3i^PafNv(zyI)&bH?F}2s8_rR(6%!V4SOWlup`TKAb@ee>!9JKPM=&8g#BeYRH9FpFybxBXQI2|g}FGJfJ+ zY-*2hB?o{TVL;Wt_ek;AP5PBqfDR4@Z->_182W z{P@Mc27j6jE*9xG{R$>6_;i=y{qf(c`5w9fa*`rEzX6t!KJ(p1H|>J1pC-2zqWENF zmm=Z5B4u{cY2XYl(PfrInB*~WGWik3@1oRhiMOS|D;acnf-Bs(QCm#wR;@Vf!hOPJ zgjhDCfDj$HcyVLJ=AaTbQ{@vIv14LWWF$=i-BDoC11}V;2V8A`S>_x)vIq44-VB-v z*w-d}$G+Ql?En8j!~ZkCpQ$|cA0|+rrY>tiCeWxkRGPoarxlGU2?7%k#F693RHT24 z-?JsiXlT2PTqZqNb&sSc>$d;O4V@|b6VKSWQb~bUaWn1Cf0+K%`Q&Wc<>mQ>*iEGB zbZ;aYOotBZ{vH3y<0A*L0QVM|#rf*LIsGx(O*-7)r@yyBIzJnBFSKBUSl1e|8lxU* zzFL+YDVVkIuzFWeJ8AbgN&w(4-7zbiaMn{5!JQXu)SELk*CNL+Fro|2v|YO)1l15t zs(0^&EB6DPMyaqvY>=KL>)tEpsn;N5Q#yJj<9}ImL((SqErWN3Q=;tBO~ExTCs9hB z2E$7eN#5wX4<3m^5pdjm#5o>s#eS_Q^P)tm$@SawTqF*1dj_i#)3};JslbLKHXl_N z)Fxzf>FN)EK&Rz&*|6&%Hs-^f{V|+_vL1S;-1K-l$5xiC@}%uDuwHYhmsV?YcOUlk zOYkG5v2+`+UWqpn0aaaqrD3lYdh0*!L`3FAsNKu=Q!vJu?Yc8n|CoYyDo_`r0mPoo z8>XCo$W4>l(==h?2~PoRR*kEe)&IH{1sM41mO#-36`02m#nTX{r*r`Q5rZ2-sE|nA zhnn5T#s#v`52T5|?GNS`%HgS2;R(*|^egNPDzzH_z^W)-Q98~$#YAe)cEZ%vge965AS_am#DK#pjPRr-!^za8>`kksCAUj(Xr*1NW5~e zpypt_eJpD&4_bl_y?G%>^L}=>xAaV>KR6;^aBytqpiHe%!j;&MzI_>Sx7O%F%D*8s zSN}cS^<{iiK)=Ji`FpO#^zY!_|D)qeRNAtgmH)m;qC|mq^j(|hL`7uBz+ULUj37gj zksdbnU+LSVo35riSX_4z{UX=%n&}7s0{WuZYoSfwAP`8aKN9P@%e=~1`~1ASL-z%# zw>DO&ixr}c9%4InGc*_y42bdEk)ZdG7-mTu0bD@_vGAr*NcFoMW;@r?@LUhRI zCUJgHb`O?M3!w)|CPu~ej%fddw20lod?Ufp8Dmt0PbnA0J%KE^2~AIcnKP()025V> zG>noSM3$5Btmc$GZoyP^v1@Poz0FD(6YSTH@aD0}BXva?LphAiSz9f&Y(aDAzBnUh z?d2m``~{z;{}kZJ>a^wYI?ry(V9hIoh;|EFc0*-#*`$T0DRQ1;WsqInG;YPS+I4{g zJGpKk%%Sdc5xBa$Q^_I~(F97eqDO7AN3EN0u)PNBAb+n+ zWBTxQx^;O9o0`=g+Zrt_{lP!sgWZHW?8bLYS$;1a@&7w9rD9|Ge;Gb?sEjFoF9-6v z#!2)t{DMHZ2@0W*fCx;62d#;jouz`R5Y(t{BT=$N4yr^^o$ON8d{PQ=!O zX17^CrdM~7D-;ZrC!||<+FEOxI_WI3CA<35va%4v>gc zEX-@h8esj=a4szW7x{0g$hwoWRQG$yK{@3mqd-jYiVofJE!Wok1* znV7Gm&Ssq#hFuvj1sRyHg(6PFA5U*Q8Rx>-blOs=lb`qa{zFy&n4xY;sd$fE+<3EI z##W$P9M{B3c3Si9gw^jlPU-JqD~Cye;wr=XkV7BSv#6}DrsXWFJ3eUNrc%7{=^sP> zrp)BWKA9<}^R9g!0q7yWlh;gr_TEOD|#BmGq<@IV;ueg+D2}cjpp+dPf&Q(36sFU&K8}hA85U61faW&{ zlB`9HUl-WWCG|<1XANN3JVAkRYvr5U4q6;!G*MTdSUt*Mi=z_y3B1A9j-@aK{lNvx zK%p23>M&=KTCgR!Ee8c?DAO2_R?B zkaqr6^BSP!8dHXxj%N1l+V$_%vzHjqvu7p@%Nl6;>y*S}M!B=pz=aqUV#`;h%M0rU zHfcog>kv3UZAEB*g7Er@t6CF8kHDmKTjO@rejA^ULqn!`LwrEwOVmHx^;g|5PHm#B zZ+jjWgjJ!043F+&#_;D*mz%Q60=L9Ove|$gU&~As5^uz@2-BfQ!bW)Khn}G+Wyjw- z19qI#oB(RSNydn0t~;tAmK!P-d{b-@@E5|cdgOS#!>%#Rj6ynkMvaW@37E>@hJP^8 z2zk8VXx|>#R^JCcWdBCy{0nPmYFOxN55#^-rlqobe0#L6)bi?E?SPymF*a5oDDeSd zO0gx?#KMoOd&G(2O@*W)HgX6y_aa6iMCl^~`{@UR`nMQE`>n_{_aY5nA}vqU8mt8H z`oa=g0SyiLd~BxAj2~l$zRSDHxvDs;I4>+M$W`HbJ|g&P+$!U7-PHX4RAcR0szJ*( ze-417=bO2q{492SWrqDK+L3#ChUHtz*@MP)e^%@>_&#Yk^1|tv@j4%3T)diEX zATx4K*hcO`sY$jk#jN5WD<=C3nvuVsRh||qDHnc~;Kf59zr0;c7VkVSUPD%NnnJC_ zl3F^#f_rDu8l}l8qcAz0FFa)EAt32IUy_JLIhU_J^l~FRH&6-ivSpG2PRqzDdMWft>Zc(c)#tb%wgmWN%>IOPm zZi-noqS!^Ftb81pRcQi`X#UhWK70hy4tGW1mz|+vI8c*h@ zfFGJtW3r>qV>1Z0r|L>7I3un^gcep$AAWfZHRvB|E*kktY$qQP_$YG60C@X~tTQjB3%@`uz!qxtxF+LE!+=nrS^07hn` zEgAp!h|r03h7B!$#OZW#ACD+M;-5J!W+{h|6I;5cNnE(Y863%1(oH}_FTW})8zYb$7czP zg~Szk1+_NTm6SJ0MS_|oSz%e(S~P-&SFp;!k?uFayytV$8HPwuyELSXOs^27XvK-D zOx-Dl!P|28DK6iX>p#Yb%3`A&CG0X2S43FjN%IB}q(!hC$fG}yl1y9W&W&I@KTg6@ zK^kpH8=yFuP+vI^+59|3%Zqnb5lTDAykf z9S#X`3N(X^SpdMyWQGOQRjhiwlj!0W-yD<3aEj^&X%=?`6lCy~?`&WSWt z?U~EKFcCG_RJ(Qp7j=$I%H8t)Z@6VjA#>1f@EYiS8MRHZphp zMA_5`znM=pzUpBPO)pXGYpQ6gkine{6u_o!P@Q+NKJ}k!_X7u|qfpAyIJb$_#3@wJ z<1SE2Edkfk9C!0t%}8Yio09^F`YGzpaJHGk*-ffsn85@)%4@`;Fv^8q(-Wk7r=Q8p zT&hD`5(f?M{gfzGbbwh8(}G#|#fDuk7v1W)5H9wkorE0ZZjL0Q1=NRGY>zwgfm81DdoaVwNH;or{{eSyybt)m<=zXoA^RALYG-2t zouH|L*BLvmm9cdMmn+KGopyR@4*=&0&4g|FLoreZOhRmh=)R0bg~ zT2(8V_q7~42-zvb)+y959OAv!V$u(O3)%Es0M@CRFmG{5sovIq4%8Ahjk#*5w{+)+ zMWQoJI_r$HxL5km1#6(e@{lK3Udc~n0@g`g$s?VrnQJ$!oPnb?IHh-1qA`Rz$)Ai< z6w$-MJW-gKNvOhL+XMbE7&mFt`x1KY>k4(!KbbpZ`>`K@1J<(#vVbjx@Z@(6Q}MF# zMnbr-f55(cTa^q4+#)=s+ThMaV~E`B8V=|W_fZWDwiso8tNMTNse)RNBGi=gVwgg% zbOg8>mbRN%7^Um-7oj4=6`$|(K7!+t^90a{$18Z>}<#!bm%ZEFQ{X(yBZMc>lCz0f1I2w9Sq zuGh<9<=AO&g6BZte6hn>Qmvv;Rt)*cJfTr2=~EnGD8P$v3R|&1RCl&7)b+`=QGapi zPbLg_pxm`+HZurtFZ;wZ=`Vk*do~$wB zxoW&=j0OTbQ=Q%S8XJ%~qoa3Ea|au5o}_(P;=!y-AjFrERh%8la!z6Fn@lR?^E~H12D?8#ht=1F;7@o4$Q8GDj;sSC%Jfn01xgL&%F2 zwG1|5ikb^qHv&9hT8w83+yv&BQXOQyMVJSBL(Ky~p)gU3#%|blG?IR9rP^zUbs7rOA0X52Ao=GRt@C&zlyjNLv-} z9?*x{y(`509qhCV*B47f2hLrGl^<@SuRGR!KwHei?!CM10Tq*YDIoBNyRuO*>3FU? zHjipIE#B~y3FSfOsMfj~F9PNr*H?0oHyYB^G(YyNh{SxcE(Y-`x5jFMKb~HO*m+R% zrq|ic4fzJ#USpTm;X7K+E%xsT_3VHKe?*uc4-FsILUH;kL>_okY(w`VU*8+l>o>Jm ziU#?2^`>arnsl#)*R&nf_%>A+qwl%o{l(u)M?DK1^mf260_oteV3#E_>6Y4!_hhVD zM8AI6MM2V*^_M^sQ0dmHu11fy^kOqXqzpr?K$`}BKWG`=Es(9&S@K@)ZjA{lj3ea7_MBP zk(|hBFRjHVMN!sNUkrB;(cTP)T97M$0Dtc&UXSec<+q?y>5=)}S~{Z@ua;1xt@=T5 zI7{`Z=z_X*no8s>mY;>BvEXK%b`a6(DTS6t&b!vf_z#HM{Uoy_5fiB(zpkF{})ruka$iX*~pq1ZxD?q68dIo zIZSVls9kFGsTwvr4{T_LidcWtt$u{kJlW7moRaH6+A5hW&;;2O#$oKyEN8kx`LmG)Wfq4ykh+q{I3|RfVpkR&QH_x;t41Uw z`P+tft^E2B$domKT@|nNW`EHwyj>&}K;eDpe z1bNOh=fvIfk`&B61+S8ND<(KC%>y&?>opCnY*r5M+!UrWKxv0_QvTlJc>X#AaI^xo zaRXL}t5Ej_Z$y*|w*$6D+A?Lw-CO-$itm^{2Ct82-<0IW)0KMNvJHgBrdsIR0v~=H z?n6^}l{D``Me90`^o|q!olsF?UX3YSq^6Vu>Ijm>>PaZI8G@<^NGw{Cx&%|PwYrfw zR!gX_%AR=L3BFsf8LxI|K^J}deh0ZdV?$3r--FEX`#INxsOG6_=!v)DI>0q|BxT)z z-G6kzA01M?rba+G_mwNMQD1mbVbNTWmBi*{s_v_Ft9m2Avg!^78(QFu&n6mbRJ2bA zv!b;%yo{g*9l2)>tsZJOOp}U~8VUH`}$ z8p_}t*XIOehezolNa-a2x0BS})Y9}&*TPgua{Ewn-=wVrmJUeU39EKx+%w%=ixQWK zDLpwaNJs65#6o7Ln7~~X+p_o2BR1g~VCfxLzxA{HlWAI6^H;`juI=&r1jQrUv_q0Z z1Ja-tjdktrrP>GOC*#p?*xfQU5MqjMsBe!9lh(u8)w$e@Z|>aUHI5o;MGw*|Myiz3 z-f0;pHg~Q#%*Kx8MxH%AluVXjG2C$)WL-K63@Q`#y9_k_+}eR(x4~dp7oV-ek0H>I zgy8p#i4GN{>#v=pFYUQT(g&b$OeTy-X_#FDgNF8XyfGY6R!>inYn8IR2RDa&O!(6< znXs{W!bkP|s_YI*Yx%4stI`=ZO45IK6rBs`g7sP40ic}GZ58s?Mc$&i`kq_tfci>N zIHrC0H+Qpam1bNa=(`SRKjixBTtm&e`j9porEci!zdlg1RI0Jw#b(_Tb@RQK1Zxr_ z%7SUeH6=TrXt3J@js`4iDD0=IoHhK~I7^W8^Rcp~Yaf>2wVe|Hh1bUpX9ATD#moByY57-f2Ef1TP^lBi&p5_s7WGG9|0T}dlfxOx zXvScJO1Cnq`c`~{Dp;{;l<-KkCDE+pmexJkd}zCgE{eF=)K``-qC~IT6GcRog_)!X z?fK^F8UDz$(zFUrwuR$qro5>qqn>+Z%<5>;_*3pZ8QM|yv9CAtrAx;($>4l^_$_-L z*&?(77!-=zvnCVW&kUcZMb6;2!83si518Y%R*A3JZ8Is|kUCMu`!vxDgaWjs7^0j( ziTaS4HhQ)ldR=r)_7vYFUr%THE}cPF{0H45FJ5MQW^+W>P+eEX2kLp3zzFe*-pFVA zdDZRybv?H|>`9f$AKVjFWJ=wegO7hOOIYCtd?Vj{EYLT*^gl35|HQ`R=ti+ADm{jyQE7K@kdjuqJhWVSks>b^ zxha88-h3s;%3_5b1TqFCPTxVjvuB5U>v=HyZ$?JSk+&I%)M7KE*wOg<)1-Iy)8-K! z^XpIt|0ibmk9RtMmlUd7#Ap3Q!q9N4atQy)TmrhrFhfx1DAN`^vq@Q_SRl|V z#lU<~n67$mT)NvHh`%als+G-)x1`Y%4Bp*6Un5Ri9h=_Db zA-AdP!f>f0m@~>7X#uBM?diI@)Egjuz@jXKvm zJo+==juc9_<;CqeRaU9_Mz@;3e=E4=6TK+c`|uu#pIqhSyNm`G(X)&)B`8q0RBv#> z`gGlw(Q=1Xmf55VHj%C#^1lpc>LY8kfA@|rlC1EA<1#`iuyNO z(=;irt{_&K=i4)^x%;U(Xv<)+o=dczC5H3W~+e|f~{*ucxj@{Yi-cw^MqYr3fN zF5D+~!wd$#al?UfMnz(@K#wn`_5na@rRr8XqN@&M&FGEC@`+OEv}sI1hw>Up0qAWf zL#e4~&oM;TVfjRE+10B_gFlLEP9?Q-dARr3xi6nQqnw>k-S;~b z;!0s2VS4}W8b&pGuK=7im+t(`nz@FnT#VD|!)eQNp-W6)@>aA+j~K*H{$G`y2|QHY z|Hmy+CR@#jWY4~)lr1qBJB_RfHJFfP<}pK5(#ZZGSqcpyS&}01LnTWk5fzmXMGHkJ zTP6L^B+uj;lmB_W<~4=${+v0>z31M!-_O@o-O9GyW)j_mjx}!0@br_LE-7SIuPP84 z;5=O(U*g_um0tyG|61N@d9lEuOeiRd+#NY^{nd5;-CVlw&Ap7J?qwM^?E29wvS}2d zbzar4Fz&RSR(-|s!Z6+za&Z zY#D<5q_JUktIzvL0)yq_kLWG6DO{ri=?c!y!f(Dk%G{8)k`Gym%j#!OgXVDD3;$&v@qy#ISJfp=Vm>pls@9-mapVQChAHHd-x+OGx)(*Yr zC1qDUTZ6mM(b_hi!TuFF2k#8uI2;kD70AQ&di$L*4P*Y-@p`jdm%_c3f)XhYD^6M8&#Y$ZpzQMcR|6nsH>b=*R_Von!$BTRj7yGCXokoAQ z&ANvx0-Epw`QIEPgI(^cS2f(Y85yV@ygI{ewyv5Frng)e}KCZF7JbR(&W618_dcEh(#+^zZFY;o<815<5sOHQdeax9_!PyM&;{P zkBa5xymca0#)c#tke@3KNEM8a_mT&1gm;p&&JlMGH(cL(b)BckgMQ^9&vRwj!~3@l zY?L5}=Jzr080OGKb|y`ee(+`flQg|!lo6>=H)X4`$Gz~hLmu2a%kYW_Uu8x09Pa0J zKZ`E$BKJ=2GPj_3l*TEcZ*uYRr<*J^#5pILTT;k_cgto1ZL-%slyc16J~OH-(RgDA z%;EjEnoUkZ&acS{Q8`{i6T5^nywgqQI5bDIymoa7CSZG|WWVk>GM9)zy*bNih|QIm z%0+(Nnc*a_xo;$=!HQYaapLms>J1ToyjtFByY`C2H1wT#178#4+|{H0BBqtCdd$L% z_3Hc60j@{t9~MjM@LBalR&6@>B;9?r<7J~F+WXyYu*y3?px*=8MAK@EA+jRX8{CG?GI-< z54?Dc9CAh>QTAvyOEm0^+x;r2BWX|{3$Y7)L5l*qVE*y0`7J>l2wCmW zL1?|a`pJ-l{fb_N;R(Z9UMiSj6pQjOvQ^%DvhIJF!+Th7jO2~1f1N+(-TyCFYQZYw z4)>7caf^Ki_KJ^Zx2JUb z&$3zJy!*+rCV4%jqwyuNY3j1ZEiltS0xTzd+=itTb;IPYpaf?8Y+RSdVdpacB(bVQ zC(JupLfFp8y43%PMj2}T|VS@%LVp>hv4Y!RPMF?pp8U_$xCJ)S zQx!69>bphNTIb9yn*_yfj{N%bY)t{L1cs8<8|!f$;UQ*}IN=2<6lA;x^(`8t?;+ST zh)z4qeYYgZkIy{$4x28O-pugO&gauRh3;lti9)9Pvw+^)0!h~%m&8Q!AKX%urEMnl z?yEz?g#ODn$UM`+Q#$Q!6|zsq_`dLO5YK-6bJM6ya>}H+vnW^h?o$z;V&wvuM$dR& zeEq;uUUh$XR`TWeC$$c&Jjau2it3#%J-y}Qm>nW*s?En?R&6w@sDXMEr#8~$=b(gk zwDC3)NtAP;M2BW_lL^5ShpK$D%@|BnD{=!Tq)o(5@z3i7Z){} zGr}Exom_qDO{kAVkZ*MbLNHE666Kina#D{&>Jy%~w7yX$oj;cYCd^p9zy z8*+wgSEcj$4{WxKmCF(5o7U4jqwEvO&dm1H#7z}%VXAbW&W24v-tS6N3}qrm1OnE)fUkoE8yMMn9S$?IswS88tQWm4#Oid#ckgr6 zRtHm!mfNl-`d>O*1~d7%;~n+{Rph6BBy^95zqI{K((E!iFQ+h*C3EsbxNo_aRm5gj zKYug($r*Q#W9`p%Bf{bi6;IY0v`pB^^qu)gbg9QHQ7 zWBj(a1YSu)~2RK8Pi#C>{DMlrqFb9e_RehEHyI{n?e3vL_}L>kYJC z_ly$$)zFi*SFyNrnOt(B*7E$??s67EO%DgoZL2XNk8iVx~X_)o++4oaK1M|ou73vA0K^503j@uuVmLcHH4ya-kOIDfM%5%(E z+Xpt~#7y2!KB&)PoyCA+$~DXqxPxxALy!g-O?<9+9KTk4Pgq4AIdUkl`1<1#j^cJg zgU3`0hkHj_jxV>`Y~%LAZl^3o0}`Sm@iw7kwff{M%VwtN)|~!p{AsfA6vB5UolF~d zHWS%*uBDt<9y!9v2Xe|au&1j&iR1HXCdyCjxSgG*L{wmTD4(NQ=mFjpa~xooc6kju z`~+d{j7$h-;HAB04H!Zscu^hZffL#9!p$)9>sRI|Yovm)g@F>ZnosF2EgkU3ln0bR zTA}|+E(tt)!SG)-bEJi_0m{l+(cAz^pi}`9=~n?y&;2eG;d9{M6nj>BHGn(KA2n|O zt}$=FPq!j`p&kQ8>cirSzkU0c08%8{^Qyqi-w2LoO8)^E7;;I1;HQ6B$u0nNaX2CY zSmfi)F`m94zL8>#zu;8|{aBui@RzRKBlP1&mfFxEC@%cjl?NBs`cr^nm){>;$g?rhKr$AO&6qV_Wbn^}5tfFBry^e1`%du2~o zs$~dN;S_#%iwwA_QvmMjh%Qo?0?rR~6liyN5Xmej8(*V9ym*T`xAhHih-v$7U}8=dfXi2i*aAB!xM(Xekg*ix@r|ymDw*{*s0?dlVys2e)z62u1 z+k3esbJE=-P5S$&KdFp+2H7_2e=}OKDrf( z9-207?6$@f4m4B+9E*e((Y89!q?zH|mz_vM>kp*HGXldO0Hg#!EtFhRuOm$u8e~a9 z5(roy7m$Kh+zjW6@zw{&20u?1f2uP&boD}$#Zy)4o&T;vyBoqFiF2t;*g=|1=)PxB z8eM3Mp=l_obbc?I^xyLz?4Y1YDWPa+nm;O<$Cn;@ane616`J9OO2r=rZr{I_Kizyc zP#^^WCdIEp*()rRT+*YZK>V@^Zs=ht32x>Kwe zab)@ZEffz;VM4{XA6e421^h~`ji5r%)B{wZu#hD}f3$y@L0JV9f3g{-RK!A?vBUA}${YF(vO4)@`6f1 z-A|}e#LN{)(eXloDnX4Vs7eH|<@{r#LodP@Nz--$Dg_Par%DCpu2>2jUnqy~|J?eZ zBG4FVsz_A+ibdwv>mLp>P!(t}E>$JGaK$R~;fb{O3($y1ssQQo|5M;^JqC?7qe|hg zu0ZOqeFcp?qVn&Qu7FQJ4hcFi&|nR!*j)MF#b}QO^lN%5)4p*D^H+B){n8%VPUzi! zDihoGcP71a6!ab`l^hK&*dYrVYzJ0)#}xVrp!e;lI!+x+bfCN0KXwUAPU9@#l7@0& QuEJmfE|#`Dqx|px0L@K;Y5)KL literal 0 HcmV?d00001 diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 00000000..a71c7a7d --- /dev/null +++ b/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,5 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-7.3.3-bin.zip +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/gradlew b/gradlew new file mode 100755 index 00000000..c53aefaa --- /dev/null +++ b/gradlew @@ -0,0 +1,234 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# https://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/master/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +APP_HOME=$( cd "${APP_HOME:-./}" && pwd -P ) || exit + +APP_NAME="Gradle" +APP_BASE_NAME=${0##*/} + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +else + JAVACMD=java + which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + done +fi + +# Collect all arguments for the java command; +# * $DEFAULT_JVM_OPTS, $JAVA_OPTS, and $GRADLE_OPTS can contain fragments of +# shell script including quotes and variable substitutions, so put them in +# double quotes to make sure that they get re-expanded; and +# * put everything else in single quotes, so that it's not re-expanded. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/gradlew.bat b/gradlew.bat new file mode 100644 index 00000000..ac1b06f9 --- /dev/null +++ b/gradlew.bat @@ -0,0 +1,89 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem + +@if "%DEBUG%" == "" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%" == "" set DIRNAME=. +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if "%ERRORLEVEL%" == "0" goto execute + +echo. +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if "%ERRORLEVEL%"=="0" goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1 +exit /b 1 + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/settings.gradle b/settings.gradle new file mode 100644 index 00000000..aa06df79 --- /dev/null +++ b/settings.gradle @@ -0,0 +1,27 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2022' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name 'frcHome' + url frcHomeMaven + } + } +} diff --git a/simConfig.txt b/simConfig.txt new file mode 100644 index 00000000..d5986bb4 --- /dev/null +++ b/simConfig.txt @@ -0,0 +1,102 @@ +{ + "logFilePath": "sim_robot_logs", + "drive": { + "leftMotor": { + "deviceId": 6, + "sensorScale": 0.0524 + }, + "rightMotor": { + "deviceId": 4, + "sensorScale": 0.0524 + }, + "leftEncoder": { + "ports": [0, 1], + "distancePerPulse": 0.0524 + }, + "rightEncoder": { + "ports": [2, 3], + "distancePerPulse": 0.0524 + }, + "gyro": { + "port": 12 + }, + "frontLeftDriveMotor": { + "deviceId": 84, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "backLeftDriveMotor": { + "deviceId": 85, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "frontRightDriveMotor": { + "deviceId": 86, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "backRightDriveMotor": { + "deviceId": 87, + "sensorScale": 0.0008866, + "sensorScaledUnits": "meter" + }, + "frontLeftSteerMotor": { + "deviceId": 88, + "inverted": true, + "sensorScaledUnits": "degree" + }, + "backLeftSteerMotor": { + "deviceId": 89, + "inverted": true, + "sensorScaledUnits": "degree" + }, + "frontRightSteerMotor": { + "deviceId": 90, + "inverted": true, + "sensorScaledUnits": "degree" + }, + "backRightSteerMotor": { + "deviceId": 91, + "inverted": true, + "sensorScaledUnits": "degree" + } + }, + "intakeWheels": { + "deviceId": 10 + }, + "intakeArm": { + "port": 0 + }, + "launch": { + "port": 1 + }, + "climber": { + "elevator": { + "deviceId": 10 + }, + "arms": {"port": 0} + }, + "lineSensorLeft": { + "port": 4 + }, + "lineSensorCenter": { + "port": 5 + }, + "lineSensorRight": { + "port": 6 + }, + + "intake": { + "extend": {"port": 0}, + "frontWheels": {"deviceId": 10}, + "topWheels": {"deviceId": 12} + }, + "shooter": { + "motor": {"deviceId": 14} + }, + "storage": { + "proximitySensor": {"port": 2}, + "left": {"deviceId": 6}, + "right": {"deviceId": 4} + } +} \ No newline at end of file diff --git a/src/main/deploy/example.txt b/src/main/deploy/example.txt new file mode 100644 index 00000000..70c79b6b --- /dev/null +++ b/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'FileUtilities.getFilePath' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/src/main/java/com/team766/config/AbstractConfigMultiValue.java b/src/main/java/com/team766/config/AbstractConfigMultiValue.java new file mode 100644 index 00000000..c3a769c1 --- /dev/null +++ b/src/main/java/com/team766/config/AbstractConfigMultiValue.java @@ -0,0 +1,35 @@ +package com.team766.config; + +import java.lang.reflect.Array; +import java.util.function.IntFunction; +import org.json.JSONArray; + +abstract class AbstractConfigMultiValue extends AbstractConfigValue { + private final IntFunction m_arrayFactory; + + @SuppressWarnings("unchecked") + protected AbstractConfigMultiValue(String key, Class elementClass) { + super(key); + m_arrayFactory = (int length) -> (E[])Array.newInstance(elementClass, length); + } + + @Override + protected final E[] parseJsonValue(Object configValue) { + JSONArray jsonArray; + try { + jsonArray = (JSONArray)configValue; + } catch (ClassCastException ex) { + final E[] valueArray = m_arrayFactory.apply(1); + valueArray[0] = parseJsonElement(configValue); + return valueArray; + } + final int length = jsonArray.length(); + final E[] valueArray = m_arrayFactory.apply(length); + for (int i = 0; i < length; ++i) { + valueArray[i] = parseJsonElement(jsonArray.get(i)); + } + return valueArray; + } + + protected abstract E parseJsonElement(Object configElement); +} \ No newline at end of file diff --git a/src/main/java/com/team766/config/AbstractConfigValue.java b/src/main/java/com/team766/config/AbstractConfigValue.java new file mode 100644 index 00000000..78d470f7 --- /dev/null +++ b/src/main/java/com/team766/config/AbstractConfigValue.java @@ -0,0 +1,93 @@ +package com.team766.config; + +import java.util.ArrayList; +import java.util.Collection; +import java.util.Collections; +import com.team766.library.SettableValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public abstract class AbstractConfigValue implements SettableValueProvider { + protected String m_key; + private E m_cachedValue; + private boolean m_cachedHasValue; + private int m_cachedGeneration = -1; + + private static ArrayList> c_accessedValues = new ArrayList>(); + + static Collection> accessedValues() { + return Collections.unmodifiableCollection(c_accessedValues); + } + + static void resetStatics() { + c_accessedValues.clear(); + } + + protected AbstractConfigValue(String key) { + m_key = key; + c_accessedValues.add(this); + // Querying for this config setting's key will add a placeholder entry + // in the config file if this setting does not already exist there. + ConfigFileReader.instance.getRawValue(m_key); + } + + private void sync() { + if (ConfigFileReader.instance.getGeneration() != m_cachedGeneration) { + m_cachedGeneration = ConfigFileReader.instance.getGeneration(); + var rawValue = ConfigFileReader.instance.getRawValue(m_key); + m_cachedHasValue = rawValue != null; + if (m_cachedHasValue) { + try { + m_cachedValue = parseJsonValue(rawValue); + } catch (Exception ex) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Failed to parse " + m_key + " from the config file: " + LoggerExceptionUtils.exceptionToString(ex)); + m_cachedValue = null; + m_cachedHasValue = false; + } + } + } + } + + public String getKey() { + return m_key; + } + + @Override + public boolean hasValue() { + sync(); + return m_cachedHasValue; + } + + @Override + public E get() { + sync(); + if (!m_cachedHasValue) { + throw new IllegalArgumentException(m_key + " not found in the config file"); + } + return m_cachedValue; + } + + public void set(E value) { + ConfigFileReader.instance.setValue(m_key, value); + } + + public void clear() { + ConfigFileReader.instance.setValue(m_key, null); + } + + protected abstract E parseJsonValue(Object configValue); + + @Override + public String toString() { + sync(); + if (!m_cachedHasValue) { + return ""; + } + if (m_cachedValue == null) { + return ""; + } + return m_cachedValue.toString(); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/config/ConfigFileReader.java b/src/main/java/com/team766/config/ConfigFileReader.java new file mode 100755 index 00000000..60b12606 --- /dev/null +++ b/src/main/java/com/team766/config/ConfigFileReader.java @@ -0,0 +1,182 @@ +package com.team766.config; + +import java.io.FileWriter; +import java.io.IOException; +import java.io.StringReader; +import java.nio.file.Files; +import java.nio.file.Paths; +import java.util.regex.Pattern; +import org.json.JSONObject; +import org.json.JSONTokener; +import com.team766.library.SettableValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +/** + * Class for loading in config from the Config file. + * Constants that need to be tuned / changed + * + * Data is read from a file in JSON format + * + * @author Brett Levenson + */ +public class ConfigFileReader { + // this.getClass().getClassLoader().getResource(fileName).getPath() + + public static ConfigFileReader instance; + + private static final String KEY_DELIMITER = "."; + + // This is incremented each time the config file is reloaded to ensure that ConfigValues use the most recent setting. + private int m_generation = 0; + + private String m_fileName; + private JSONObject m_values = new JSONObject(); + + public static ConfigFileReader getInstance() { + return instance; + } + + public ConfigFileReader(String fileName) { + m_fileName = fileName; + + try { + reloadFromFile(); + } catch (Exception e) { + System.err.println("Failed to load config file!"); + e.printStackTrace(); + LoggerExceptionUtils.logException(new IOException("Failed to load config file!", e)); + } + } + + public void reloadFromFile() throws IOException { + System.out.println("Loading config file: " + m_fileName); + String jsonString = Files.readString(Paths.get(m_fileName)); + reloadFromJson(jsonString); + } + + public void reloadFromJson(String jsonString) { + JSONObject newValues; + try (StringReader reader = new StringReader(jsonString)) { + newValues = new JSONObject(new JSONTokener(reader)); + } + for (AbstractConfigValue param : AbstractConfigValue.accessedValues()) { + var rawValue = getRawValue(newValues, param.getKey()); + if (rawValue == null) { + continue; + } + try { + param.parseJsonValue(rawValue); + } catch (Exception ex) { + throw new ConfigValueParseException("Could not parse config value for " + param.getKey(), ex); + } + } + m_values = newValues; + ++m_generation; + } + + public int getGeneration() { + return m_generation; + } + + public boolean containsKey(String key) { + return getRawValue(key) != null; + } + + public SettableValueProvider getInts(String key) { + return new IntegerConfigMultiValue(key); + } + + public SettableValueProvider getInt(String key) { + return new IntegerConfigValue(key); + } + + public SettableValueProvider getDoubles(String key) { + return new DoubleConfigMultiValue(key); + } + + public SettableValueProvider getDouble(String key) { + return new DoubleConfigValue(key); + } + + public SettableValueProvider getBoolean(String key) { + return new BooleanConfigValue(key); + } + + public SettableValueProvider getString(String key) { + return new StringConfigValue(key); + } + + public > SettableValueProvider getEnum(Class enumClass, String key) { + return new EnumConfigValue(enumClass, key); + } + + public void setValue(String key, E value) { + String[] keyParts = splitKey(key); + JSONObject parentObj = getParent(m_values, keyParts); + parentObj.putOpt( + keyParts[keyParts.length - 1], + value == null ? JSONObject.NULL : value); + } + + Object getRawValue(String key) { + return getRawValue(m_values, key); + } + + private static Object getRawValue(JSONObject obj, String key) { + String[] keyParts = splitKey(key); + JSONObject parentObj = getParent(obj, keyParts); + var rawValue = parentObj.opt(keyParts[keyParts.length - 1]); + if (rawValue instanceof JSONObject) { + throw new IllegalArgumentException( + "The config file cannot store both a single config " + + "setting and a group of config settings with the name " + + key + " Please pick a different name"); + } + if (rawValue == null) { + parentObj.put(keyParts[keyParts.length - 1], JSONObject.NULL); + } + if (rawValue == JSONObject.NULL) { + rawValue = null; + } + return rawValue; + } + + private static String[] splitKey(String key) { + return key.split(Pattern.quote(KEY_DELIMITER)); + } + + private static JSONObject getParent(JSONObject obj, String[] keyParts) { + for (int i = 0; i < keyParts.length - 1; ++i) { + JSONObject subObj; + try { + subObj = (JSONObject)obj.opt(keyParts[i]); + } catch (ClassCastException ex) { + throw new IllegalArgumentException( + "The config file cannot store both a single config " + + "setting and a group of config settings with the name " + + String.join(KEY_DELIMITER, keyParts) + + " Please pick a different name for one of them."); + } + if (subObj == null) { + subObj = new JSONObject(); + obj.put(keyParts[i], subObj); + } + obj = subObj; + } + return obj; + } + + public String getJsonString() { + return m_values.toString(2); + } + + public void saveFile(String jsonString) throws IOException { + try(FileWriter writer = new FileWriter(m_fileName)) { + writer.write(jsonString); + } + Logger.get(Category.CONFIGURATION).logRaw(Severity.INFO, "Config file written to " + m_fileName); + } +} diff --git a/src/main/java/com/team766/config/ConfigValue.java b/src/main/java/com/team766/config/ConfigValue.java new file mode 100644 index 00000000..c6e876f8 --- /dev/null +++ b/src/main/java/com/team766/config/ConfigValue.java @@ -0,0 +1,94 @@ +package com.team766.config; + +import java.util.Arrays; +import java.util.stream.Collectors; + +class DoubleConfigValue extends AbstractConfigValue { + protected DoubleConfigValue(String key) { + super(key); + } + + @Override + public Double parseJsonValue(Object configValue) { + return ((Number)configValue).doubleValue(); + } +} + +class IntegerConfigValue extends AbstractConfigValue { + protected IntegerConfigValue(String key) { + super(key); + } + + @Override + public Integer parseJsonValue(Object configValue) { + return ((Number)configValue).intValue(); + } +} + +class DoubleConfigMultiValue extends AbstractConfigMultiValue { + protected DoubleConfigMultiValue(String key) { + super(key, Double.class); + } + + @Override + public Double parseJsonElement(Object configElement) { + return ((Number)configElement).doubleValue(); + } +} + +class IntegerConfigMultiValue extends AbstractConfigMultiValue { + protected IntegerConfigMultiValue(String key) { + super(key, Integer.class); + } + + @Override + public Integer parseJsonElement(Object configElement) { + return ((Number)configElement).intValue(); + } +} + +class BooleanConfigValue extends AbstractConfigValue { + protected BooleanConfigValue(String key) { + super(key); + } + + @Override + public Boolean parseJsonValue(Object configValue) { + return (Boolean)configValue; + } +} + +class StringConfigValue extends AbstractConfigValue { + protected StringConfigValue(String key) { + super(key); + } + + @Override + public String parseJsonValue(Object configValue) { + return (String)configValue; + } +} + +class EnumConfigValue> extends AbstractConfigValue { + Class enumClass; + + protected EnumConfigValue(Class enumClass, String key) { + super(key); + this.enumClass = enumClass; + } + + @Override + public E parseJsonValue(Object configValue) { + String enumName = (String)configValue; + for (E each : enumClass.getEnumConstants()) { + if (each.name().compareToIgnoreCase(enumName) == 0) { + return each; + } + } + throw new IllegalArgumentException( + "Unrecognized enum value: " + + enumName + + "; values are " + + Arrays.stream(enumClass.getEnumConstants()).map(e -> e.name()).collect(Collectors.joining(", "))); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/config/ConfigValueParseException.java b/src/main/java/com/team766/config/ConfigValueParseException.java new file mode 100644 index 00000000..c07709d5 --- /dev/null +++ b/src/main/java/com/team766/config/ConfigValueParseException.java @@ -0,0 +1,13 @@ +package com.team766.config; + +public class ConfigValueParseException extends RuntimeException { + private static final long serialVersionUID = -3235627203813966130L; + + public ConfigValueParseException(String message) { + super(message); + } + + public ConfigValueParseException(String message, Throwable cause) { + super(message, cause); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/controllers/MotionLockout.java b/src/main/java/com/team766/controllers/MotionLockout.java new file mode 100644 index 00000000..04646e69 --- /dev/null +++ b/src/main/java/com/team766/controllers/MotionLockout.java @@ -0,0 +1,57 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.library.SetValueProvider; +import com.team766.library.ValueProvider; + +/* + * Restricts the command to be between minCommand and maxCommand when the + * sensor position is between minPosition and maxPosition. + */ +public class MotionLockout { + private ValueProvider m_minPosition; + private ValueProvider m_maxPosition; + private ValueProvider m_minCommand; + private ValueProvider m_maxCommand; + + public static MotionLockout loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new MotionLockout( + ConfigFileReader.getInstance().getDouble(configPrefix + "minPosition"), + ConfigFileReader.getInstance().getDouble(configPrefix + "maxPosition"), + ConfigFileReader.getInstance().getDouble(configPrefix + "minCommand"), + ConfigFileReader.getInstance().getDouble(configPrefix + "maxCommand")); + } + + public MotionLockout(double minPosition, double maxPosition, double minCommand, double maxCommand) { + m_minPosition = new SetValueProvider(minPosition); + m_maxPosition = new SetValueProvider(maxPosition); + m_minCommand = new SetValueProvider(minCommand); + m_maxCommand = new SetValueProvider(maxCommand); + } + + public MotionLockout( + ValueProvider minPosition, + ValueProvider maxPosition, + ValueProvider minCommand, + ValueProvider maxCommand) { + m_minPosition = minPosition; + m_maxPosition = maxPosition; + m_minCommand = minCommand; + m_maxCommand = maxCommand; + } + + public double filter(double inputCommand, double sensorPosition) { + if (sensorPosition >= m_minPosition.get() && sensorPosition <= m_maxPosition.get()) { + if (inputCommand < m_minCommand.get()) { + return m_minCommand.get(); + } + if (inputCommand < m_maxCommand.get()) { + return m_maxCommand.get(); + } + } + return inputCommand; + } +} diff --git a/src/main/java/com/team766/controllers/PIDController.java b/src/main/java/com/team766/controllers/PIDController.java new file mode 100755 index 00000000..93fd4e86 --- /dev/null +++ b/src/main/java/com/team766/controllers/PIDController.java @@ -0,0 +1,350 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.hal.RobotProvider; +import com.team766.library.SetValueProvider; +import com.team766.library.SettableValueProvider; +import com.team766.library.ValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +/** + * When attempting to move something with a control loop, a PID controller can + * smoothly decrease the error. This class is used for the elevator, driving during + * autonmous, and angle correction with the gyro during the tele-operated period of the + * match. + * + * Because FRC's PID only supports a narrow range of things - you have to send + * the output directly to a motor controller, etc. + * + *

+ * Possibly later we may create a second class that allows for different PID + * constants depending on which direction - this might be useful for things like + * arms where behavior is different depending on direction. + * + * + * @author Blevenson + * + */ + +public class PIDController { + private int printCounter = 0; + private boolean print = false; + + private final ValueProvider Kp; + private final ValueProvider Ki; + private final ValueProvider Kd; + private final ValueProvider Kff; + private final ValueProvider maxoutput_low; + private final ValueProvider maxoutput_high; + private final ValueProvider endthreshold; + + private double setpoint = Double.NaN; + + private boolean needsUpdate = true; + + private double cur_error = 0; + private double prev_error = 0; + private double error_rate = 0; + private double total_error = 0; + + private double output_value = 0; + + TimeProviderI timeProvider; + private double lastTime; + + public static PIDController loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new PIDController( + ConfigFileReader.getInstance().getDouble(configPrefix + "pGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "iGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "dGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "ffGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxLow"), + ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxHigh"), + ConfigFileReader.getInstance().getDouble(configPrefix + "threshold")); + } + + /** + * + * @param P + * P constant + * @param I + * I constant + * @param D + * D constant + * @param outputmax_low + * Largest output in the negative direction + * @param outputmax_high + * Largest output in the positive direction + * @param threshold + * threshold for declaring the PID 'done' + */ + public PIDController(double P, double I, double D, double outputmax_low, + double outputmax_high, double threshold) { + Kp = new SetValueProvider(P); + Ki = new SetValueProvider(I); + Kd = new SetValueProvider(D); + Kff = new SetValueProvider(); + maxoutput_low = new SetValueProvider(outputmax_low); + maxoutput_high = new SetValueProvider(outputmax_high); + endthreshold = new SetValueProvider(threshold); + setTimeProvider(RobotProvider.getTimeProvider()); + } + + public PIDController(double P, double I, double D, double FF, double outputmax_low, + double outputmax_high, double threshold) { + this(P,I,D,outputmax_low,outputmax_high,threshold); + ((SetValueProvider)Kff).set(FF); + } + + private void setTimeProvider(TimeProviderI timeProvider) { + this.timeProvider = timeProvider; + lastTime = timeProvider.get(); + } + + public PIDController( + ValueProvider P, + ValueProvider I, + ValueProvider D, + ValueProvider FF, + ValueProvider outputmax_low, + ValueProvider outputmax_high, + ValueProvider threshold) { + Kp = P; + Ki = I; + Kd = D; + Kff = FF; + maxoutput_low = outputmax_low; + maxoutput_high = outputmax_high; + endthreshold = threshold; + setTimeProvider(RobotProvider.getTimeProvider()); + } + + /** + * Constructs a PID controller, with the specified P,I,D values, along with the end threshold. + * @param P Proportional value used in the PID controller + * @param I Integral value used in the PID controller + * @param D Derivative value used in the PID controller + * @param threshold the end threshold for declaring the PID 'done' + * @param timeProvider + */ + public PIDController(double P, double I, double D, double threshold, TimeProviderI timeProvider) { + Kp = new SetValueProvider(P); + Ki = new SetValueProvider(I); + Kd = new SetValueProvider(D); + Kff = new SetValueProvider(); + maxoutput_low = new SetValueProvider(); + maxoutput_high = new SetValueProvider(); + endthreshold = new SetValueProvider(threshold); + setTimeProvider(timeProvider); + } + + public PIDController(double P, double I, double D, double FF, double threshold, TimeProviderI timeProvider) { + Kp = new SetValueProvider(P); + Ki = new SetValueProvider(I); + Kd = new SetValueProvider(D); + Kff = new SetValueProvider(FF); + maxoutput_low = new SetValueProvider(); + maxoutput_high = new SetValueProvider(); + endthreshold = new SetValueProvider(threshold); + setTimeProvider(timeProvider); + } + + /** + * We may want to use same PID object, but with different setpoints, so this + * is separated from constructor + * + * @param set + * Target point to match + */ + public void setSetpoint(double set) { + setpoint = set; + needsUpdate = true; + } + + public void disable() { + setpoint = Double.NaN; + needsUpdate = true; + reset(); + } + + /** + * If we want to set values, such as with SmartDash + * + * @param P Proportional value used in the PID controller + * @param I Integral value used in the PID controller + * @param D Derivative value used in the PID controller + */ + public void setConstants(double P, double I, double D) { + ((SettableValueProvider)Kp).set(P); + ((SettableValueProvider)Ki).set(I); + ((SettableValueProvider)Kd).set(D); + needsUpdate = true; + } + + public void setP(double P) { + ((SettableValueProvider)Kp).set(P); + needsUpdate = true; + } + + public void setI(double I) { + ((SettableValueProvider)Ki).set(I); + needsUpdate = true; + } + + public void setD(double D) { + ((SettableValueProvider)Kd).set(D); + needsUpdate = true; + } + + public void setFF(double FF) { + ((SettableValueProvider)Kff).set(FF); + needsUpdate = true; + } + + /** Same as calculate() except that it prints debugging information + * + * @param cur_input The current input to be plugged into the PID controller + * @param smart True if you want the output to be dynamically adjusted to the motor controller + */ + public void calculateDebug(double cur_input) { + print = true; + calculate(cur_input); + } + + /** + * Calculate PID value. Run only once per loop. Use getOutput to get output. + * + * @param cur_input Input value from sensor + */ + public void calculate(double cur_input) { + if (Double.isNaN(setpoint)) { + // Setpoint has not been set yet. + output_value = 0; + return; + } + + cur_error = (setpoint - cur_input); + /* + if (isDone()) { + output_value = 0; + pr("pid done"); + return; + } + */ + + double delta_time = timeProvider.get() - lastTime; + + if (delta_time > 0) { // This condition basically only false in the simulator + error_rate = (cur_error - prev_error) / delta_time; + } + + total_error += cur_error * delta_time; + + double ki = Ki.valueOr(0.0); + if ((total_error * ki) > 1) { + total_error = 1 / ki; + } else if ((total_error * ki) < -1) { + total_error = -1 / ki; + } + + double out = + Kp.valueOr(0.0) * cur_error + + Ki.valueOr(0.0) * total_error + + Kd.valueOr(0.0) * error_rate + + Kff.valueOr(0.0) * setpoint; + prev_error = cur_error; + + pr("Pre-clip output: " + out); + + output_value = clip(out); + + needsUpdate = false; + + lastTime = timeProvider.get(); + + pr(" Total Error: " + total_error + " Current Error: " + cur_error + + " Output: " + output_value + " Setpoint: " + setpoint); + } + + public double getOutput() { + return output_value; + } + + public boolean isDone() { + final double TIME_HORIZON = 0.5; + return !needsUpdate && + Math.abs(cur_error) < endthreshold.get() && + Math.abs(cur_error + error_rate * TIME_HORIZON) < endthreshold.get(); + } + + /** + * Reset all accumulated errors + */ + public void reset() { + cur_error = 0; + prev_error = 0; + error_rate = 0; + total_error = 0; + needsUpdate = true; + } + + /** + * Clips value for sending to motor controllers. This deals with if you + * don't want to run an arm or wheels at full speed under PID. + * + * @param clipped + * @return clipped value, safe for setting to controllers + */ + private double clip(double clipped) { + double out = clipped; + if (maxoutput_high.hasValue() && out > maxoutput_high.get()) { + out = maxoutput_high.get(); + } + if (maxoutput_low.hasValue() && out < maxoutput_low.get()) { + out = maxoutput_low.get(); + } + return out; + } + + public double getError() { + return total_error; + } + + public double getCurrentError() { + return cur_error; + } + + public void setMaxoutputHigh(Double in) { + if (in == null) { + ((SettableValueProvider)maxoutput_high).clear(); + } else { + ((SettableValueProvider)maxoutput_high).set(in); + } + } + + public void setMaxoutputLow(Double in) { + if (in == null) { + ((SettableValueProvider)maxoutput_low).clear(); + } else { + ((SettableValueProvider)maxoutput_low).set(in); + } + } + + public double getSetpoint(){ + return setpoint; + } + + private void pr(Object text) { + if (print && printCounter > 0){ + Logger.get(Category.PID_CONTROLLER).logRaw(Severity.DEBUG, "PID: " + text); + printCounter = 0; + } + printCounter++; + } + +} diff --git a/src/main/java/com/team766/controllers/RangeBound.java b/src/main/java/com/team766/controllers/RangeBound.java new file mode 100644 index 00000000..ed732fa8 --- /dev/null +++ b/src/main/java/com/team766/controllers/RangeBound.java @@ -0,0 +1,36 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.library.SetValueProvider; +import com.team766.library.ValueProvider; + +/* + * Limits the given value to be between between configured min and max values + */ +public class RangeBound { + private ValueProvider m_min; + private ValueProvider m_max; + + public static RangeBound loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new RangeBound( + ConfigFileReader.getInstance().getDouble(configPrefix + "min"), + ConfigFileReader.getInstance().getDouble(configPrefix + "max")); + } + + public RangeBound(double min, double max) { + m_min = new SetValueProvider(min); + m_max = new SetValueProvider(max); + } + + public RangeBound(ValueProvider min, ValueProvider max) { + m_min = min; + m_max = max; + } + + public double filter(double input) { + return Math.min(Math.max(input, m_min.get()), m_max.get()); + } +} diff --git a/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java b/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java new file mode 100644 index 00000000..619133ca --- /dev/null +++ b/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java @@ -0,0 +1,54 @@ +package com.team766.controllers; + +import com.team766.config.ConfigFileReader; +import com.team766.library.SetValueProvider; +import com.team766.library.ValueProvider; + +/* + * Coerces the given motor command to not allow the mechanism to be driven + * outside of the range of sensor positions between minPosition and maxPosition + */ +public class RangeOfMotionMotorCommandBound { + private ValueProvider m_minPosition; + private ValueProvider m_maxPosition; + private ValueProvider m_sensorInverted; + + public static RangeOfMotionMotorCommandBound loadFromConfig(String configPrefix) { + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + return new RangeOfMotionMotorCommandBound( + ConfigFileReader.getInstance().getDouble(configPrefix + "minPosition"), + ConfigFileReader.getInstance().getDouble(configPrefix + "maxPosition"), + ConfigFileReader.getInstance().getBoolean(configPrefix + "sensorInverted")); + } + + public RangeOfMotionMotorCommandBound(double minPosition, double maxPosition, boolean sensorInverted) { + m_minPosition = new SetValueProvider(minPosition); + m_maxPosition = new SetValueProvider(maxPosition); + m_sensorInverted = new SetValueProvider(sensorInverted); + } + + public RangeOfMotionMotorCommandBound( + ValueProvider minPosition, + ValueProvider maxPosition, + ValueProvider sensorInverted) { + m_minPosition = minPosition; + m_maxPosition = maxPosition; + m_sensorInverted = sensorInverted; + } + + public double filter(double inputCommand, double sensorPosition) { + double normalizedCommand = inputCommand; + if (m_sensorInverted.get()) { + normalizedCommand *= -1; + } + if (sensorPosition < m_minPosition.get() && normalizedCommand < 0) { + inputCommand = 0; + } + if (sensorPosition >= m_maxPosition.get() && normalizedCommand > 0) { + inputCommand = 0; + } + return inputCommand; + } +} diff --git a/src/main/java/com/team766/controllers/TimeProviderI.java b/src/main/java/com/team766/controllers/TimeProviderI.java new file mode 100644 index 00000000..a59c51ea --- /dev/null +++ b/src/main/java/com/team766/controllers/TimeProviderI.java @@ -0,0 +1,5 @@ +package com.team766.controllers; + +public interface TimeProviderI { + double get(); +} diff --git a/src/main/java/com/team766/framework/AutonomousMode.java b/src/main/java/com/team766/framework/AutonomousMode.java new file mode 100644 index 00000000..d29337be --- /dev/null +++ b/src/main/java/com/team766/framework/AutonomousMode.java @@ -0,0 +1,30 @@ +package com.team766.framework; + +import java.util.function.Supplier; + +public class AutonomousMode { + private final Supplier m_constructor; + private final String m_name; + + public AutonomousMode(String name, Supplier constructor) { + m_constructor = constructor; + m_name = name; + } + + public Procedure instantiate() { + return m_constructor.get(); + } + + public String name() { + return m_name; + } + + @Override + public String toString() { + return name(); + } + + public AutonomousMode clone() { + return new AutonomousMode(m_name, m_constructor); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Context.java b/src/main/java/com/team766/framework/Context.java new file mode 100644 index 00000000..367134c3 --- /dev/null +++ b/src/main/java/com/team766/framework/Context.java @@ -0,0 +1,454 @@ +package com.team766.framework; + +import java.lang.StackWalker.StackFrame; +import java.util.Arrays; +import java.util.HashSet; +import java.util.Set; +import java.util.function.BooleanSupplier; +import com.team766.hal.RobotProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +/** + * Context is the framework's representation of a single thread of execution. + * + * We may want to have multiple procedures running at the same time on a robot. + * For example, the robot could be raising an arm mechanism while also driving. + * Each of those procedures would have a separate Context. Each of those + * procedures may call other procedures directly; those procedures would share + * the same Context. Each Context can only be running a single procedure at a + * time. If a procedure wants to call multiple other procedures at the same + * time, it has to create new Contexts for them (using the {@link #startAsync} + * method). + * + * Use the Context instance passed to your procedure whenever you want your + * procedure to wait for something. For example, to have your procedure pause + * for a certain amount of time, call context.waitForSeconds. Multiple Contexts + * run at the same time using cooperative multitasking, which means procedures + * have to explicitly indicate when another Context should be allowed to run. + * Using Context's wait* methods will allow other Contexts to run while this one + * is waiting. If your procedure will run for a while without needing to wait + * (this often happens if your procedure has a while loop), then it should + * periodically call context.yield() (for example, at the start of each + * iteration of the while loop) to still allow other Contexts to run. + * + * This cooperative multitasking paradigm is used by the framework to ensure + * that only one Context is actually running at a time, which allows us to avoid + * needing to deal with concurrency issues like data race conditions. Even + * though only one Context is running at once, it's still incredibly helpful to + * express the code using this separate-threads-of-execution paradigm, as it + * allows each procedure to be written in procedural style + * (https://en.wikipedia.org/wiki/Procedural_programming "procedural languages + * model execution of the program as a sequence of imperative commands"), rather + * than as state machines or in continuation-passing style, which can be much + * more complicated to reason about, especially for new programmers. + * + * Currently, threads of execution are implemented using OS threads, but this + * should be considered an implementation detail and may change in the future. + * Even though the framework creates multiple OS threads, it uses Java's + * monitors to implement a "baton passing" pattern in order to ensure that only + * one of threads is actually running at once (the others will be sleeping, + * waiting for the baton to be passed to them). + */ +public final class Context implements Runnable, LaunchedContext { + /** + * Represents the baton-passing state (see class comments). Instead of + * passing a baton directly from one Context's thread to the next, each + * Context has its own baton that gets passed from the program's main thread + * to the Context's thread and back. While this is less efficient (double + * the number of OS context switches required), it makes the code simpler + * and more modular. + */ + private static enum ControlOwner { + MAIN_THREAD, + SUBROUTINE, + } + /** + * Indicates the lifetime state of this Context. + */ + private static enum State { + /** + * The Context has been started (a Context is started immediately upon + * construction). + */ + RUNNING, + /** + * stop() has been called on this Context (but it has not been allowed + * to respond to the stop request yet). + */ + CANCELED, + /** + * The Context's execution has come to an end. + */ + DONE, + } + + private static Context c_currentContext = null; + + /** + * Returns the currently-executing Context. + * + * This is maintained for things like checking Mechanism ownership, but + * intentionally only has package-private visibility - code outside of the + * framework should ideally pass around references to the current context + * object rather than cheating with this static accessor. + */ + static Context currentContext() { + return c_currentContext; + } + + /** + * The top-level procedure being run by this Context. + */ + private final RunnableWithContext m_func; + /** + * If this Context was created by another context using + * {@link #startAsync}, this will contain a reference to that originating + * Context. + */ + private final Context m_parentContext; + /** + * The OS thread that this Context is executing on. + */ + private final Thread m_thread; + /** + * Used to synchronize access to this Context's state variable. + */ + private final Object m_threadSync; + /** + * This Context's lifetime state. + */ + private State m_state; + /** + * If one of the wait* methods has been called on this Context, this + * contains the predicate which should be checked to determine whether + * the Context's execution should be resumed. This makes it more efficient + * to poll completion criteria without needing to context-switch between + * threads. + */ + private BooleanSupplier m_blockingPredicate; + /** + * Set to SUBROUTINE when this Context is executing and MAIN_THREAD + * otherwise. + */ + private ControlOwner m_controlOwner; + /** + * Contains the method name and line number at which this Context most + * recently yielded. + */ + private String m_previousWaitPoint; + /** + * The mechanisms that have been claimed by this Context using + * takeOwnership. These will be automatically released when the Context + * finishes executing. + */ + private Set m_ownedMechanisms = new HashSet(); + + /* + * Constructors are intentionally private or package-private. New contexts + * should be created with {@link Context#startAsync} or + * {@link Scheduler#startAsync}. + */ + + private Context(RunnableWithContext func, Context parentContext) { + m_func = func; + m_parentContext = parentContext; + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Starting context " + getContextName() + " for " + func.toString()); + m_threadSync = new Object(); + m_previousWaitPoint = null; + m_controlOwner = ControlOwner.MAIN_THREAD; + m_state = State.RUNNING; + m_thread = new Thread(this::threadFunction, getContextName()); + m_thread.start(); + Scheduler.getInstance().add(this); + } + Context(RunnableWithContext func) { + this(func, null); + } + + private Context(Runnable func, Context parentContext) { + this((context) -> func.run()); + } + Context(Runnable func) { + this(func, null); + } + + /** + * Returns a string meant to uniquely identify this Context (e.g. for use in + * logging). + */ + public String getContextName() { + return "Context/" + Integer.toHexString(hashCode()) + "/" + m_func.toString(); + } + + @Override + public String toString() { + String repr = getContextName(); + if (currentContext() == this) { + repr += " running"; + } + repr += "\n"; + repr += StackTraceUtils.getStackTrace(m_thread); + return repr; + } + + /** + * Walks up the call stack until it reaches a frame that isn't from the + * Context class, then returns a string representation of that frame. This + * is used to generate a concise string representation of from where the + * user called into framework code. + */ + private String getExecutionPoint() { + StackWalker walker = StackWalker.getInstance(); + return walker + .walk(s -> s.dropWhile(f -> f.getClassName() != Context.this.getClass().getName()) + .filter(f -> f.getClassName() != Context.this.getClass().getName()) + .findFirst() + .map(StackFrame::toString) + .orElse(null)); + } + + /** + * Wait until the baton (see the class comments) has been passed to this + * thread. + * + * @param thisOwner the thread from which this function is being called + * (and thus the baton-passing state that should be waited for) + * @throws ContextStoppedException if stop() is called on this Context while + * waiting. + */ + private void waitForControl(ControlOwner thisOwner) { + // If this is being called from the worker thread, log from where in the + // user's code that the context is waiting. This is provided as a + // convenience so the user can track the progress of execution through + // their procedures. + if (thisOwner == ControlOwner.SUBROUTINE) { + String waitPointTrace = getExecutionPoint(); + if (waitPointTrace != null && !waitPointTrace.equals(m_previousWaitPoint)) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.DEBUG, getContextName() + " is waiting at " + waitPointTrace); + m_previousWaitPoint = waitPointTrace; + } + } + // Wait for the baton to be passed to us. + synchronized (m_threadSync) { + while (m_controlOwner != thisOwner && m_state != State.DONE) { + try { + m_threadSync.wait(); + } catch (InterruptedException e) { + } + } + m_controlOwner = thisOwner; + if (m_state != State.RUNNING && m_controlOwner == ControlOwner.SUBROUTINE) { + throw new ContextStoppedException(); + } + } + } + + /** + * Pass the baton (see the class comments) to the other thread and then wait + * for it to be passed back. + * + * @param thisOwner the thread from which this function is being called + * (and thus the baton-passing state that should be waited for) + * @param desiredOwner the thread to which the baton should be passed + * @throws ContextStoppedException if stop() is called on this Context while + * waiting. + */ + private void transferControl(ControlOwner thisOwner, ControlOwner desiredOwner) { + synchronized (m_threadSync) { + // Make sure we currently have the baton before trying to give it to + // someone else. + if (m_controlOwner != thisOwner) { + throw new IllegalStateException("Subroutine had control owner " + m_controlOwner + " but assumed control owner " + thisOwner); + } + // Pass the baton. + m_controlOwner = desiredOwner; + if (m_controlOwner == ControlOwner.SUBROUTINE) { + c_currentContext = this; + } else { + c_currentContext = null; + } + m_threadSync.notifyAll(); + // Wait for the baton to be passed back. + waitForControl(thisOwner); + } + } + + /** + * This is the entry point for this Context's worker thread. + */ + private void threadFunction() { + // OS threads run independently of one another, so we need to wait until + // the baton is passed to us before we can start running the user's code + waitForControl(ControlOwner.SUBROUTINE); + try { + // Call into the user's code. + m_func.run(this); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Context " + getContextName() + " finished"); + } catch (ContextStoppedException ex) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, getContextName() + " was stopped"); + } catch (Exception ex) { + ex.printStackTrace(); + LoggerExceptionUtils.logException(ex); + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, "Context " + getContextName() + " died"); + } finally { + for (Mechanism m : m_ownedMechanisms) { + // Don't use this.releaseOwnership here, because that would cause a + // ConcurrentModificationException since we're iterating over m_ownedMechanisms + try { + m.releaseOwnership(this); + } catch (Exception ex) { + LoggerExceptionUtils.logException(ex); + } + } + synchronized (m_threadSync) { + m_state = State.DONE; + c_currentContext = null; + m_threadSync.notifyAll(); + } + m_ownedMechanisms.clear(); + } + } + + /** + * Pauses the execution of this Context until the given predicate returns + * true. Yields to other Contexts in the meantime. + * + * Note that the predicate will be evaluated repeatedly (possibly on a + * different thread) while the Context is paused to determine whether it + * should continue waiting. + */ + public void waitFor(BooleanSupplier predicate) { + if (!predicate.getAsBoolean()) { + m_blockingPredicate = predicate; + transferControl(ControlOwner.SUBROUTINE, ControlOwner.MAIN_THREAD); + } + } + + /** + * Pauses the execution of this Context until the given LaunchedContext has + * finished running. + */ + public void waitFor(LaunchedContext otherContext) { + waitFor(otherContext::isDone); + } + + /** + * Pauses the execution of this Context until all of the given + * LaunchedContexts have finished running. + */ + public void waitFor(LaunchedContext... otherContexts) { + waitFor(() -> Arrays.stream(otherContexts).allMatch(LaunchedContext::isDone)); + } + + /** + * Momentarily pause execution of this Context to allow other Contexts to + * execute. Execution of this Context will resume as soon as possible after + * the other Contexts have been given a chance to run. + * + * Procedures should call this periodically if they wouldn't otherwise call + * one of the wait* methods for a while. + */ + public void yield() { + m_blockingPredicate = null; + transferControl(ControlOwner.SUBROUTINE, ControlOwner.MAIN_THREAD); + } + + /** + * Pauses the execution of this Context for the given length of time. + */ + public void waitForSeconds(double seconds) { + double startTime = RobotProvider.instance.getClock().getTime(); + waitFor(() -> RobotProvider.instance.getClock().getTime() - startTime > seconds); + } + + /** + * Start running a new Context so the given procedure can run in parallel. + */ + public LaunchedContext startAsync(RunnableWithContext func) { + return new Context(func, this); + } + + /** + * Start running a new Context so the given procedure can run in parallel. + */ + public LaunchedContext startAsync(Runnable func) { + return new Context(func, this); + } + + /** + * Interrupt the running of this Context and force it to terminate. + * + * A ContextStoppedException will be raised on this Context at the point + * where the Context most recently waited or yielded -- if this Context is + * currently executing, a ContextStoppedException will be raised + * immediately. + */ + @Override + public void stop() { + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Stopping requested of " + getContextName()); + synchronized (m_threadSync) { + if (m_state != State.DONE) { + m_state = State.CANCELED; + } + if (m_controlOwner == ControlOwner.SUBROUTINE) { + throw new ContextStoppedException(); + } + } + } + + /** + * Entry point for the Scheduler to execute this Context. + * + * This should only be called from framework code; it is public only as an + * implementation detail. + */ + @Override + public final void run() { + if (m_state == State.DONE) { + Scheduler.getInstance().cancel(this); + return; + } + if (m_state == State.CANCELED || m_blockingPredicate == null || m_blockingPredicate.getAsBoolean()) { + transferControl(ControlOwner.MAIN_THREAD, ControlOwner.SUBROUTINE); + } + } + + /** + * Returns true if this Context has finished running, false otherwise. + */ + public boolean isDone() { + return m_state == State.DONE; + } + + /** + * Take ownership of the given Mechanism with this Context. + * + * Only one Context can own a Mechanism at one time. If any Context + * previously owned this Mechanism, it will be terminated. + * Ownership of this Mechanism can be released by calling releaseOwnership, + * or it will be automatically released when this Context finishes running. + * + * @see Mechanism#takeOwnership(Context, Context) + */ + public void takeOwnership(Mechanism mechanism) { + mechanism.takeOwnership(this, m_parentContext); + m_ownedMechanisms.add(mechanism); + } + + /** + * Release ownership of the given Mechanism. + * + * It is an error to call this method with a Mechanism that was not + * previously passed to takeOwnership. + * + * @see #takeOwnership(Mechanism) + * @see Mechanism#releaseOwnership(Context) + */ + public void releaseOwnership(Mechanism mechanism) { + mechanism.releaseOwnership(this); + m_ownedMechanisms.remove(mechanism); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/ContextStoppedException.java b/src/main/java/com/team766/framework/ContextStoppedException.java new file mode 100644 index 00000000..8b65be6d --- /dev/null +++ b/src/main/java/com/team766/framework/ContextStoppedException.java @@ -0,0 +1,10 @@ +package com.team766.framework; + +/** + * This exception is thrown in the code running in a Context to indicate that + * the Context has been terminated and that the code should immediately exit + * (after doing any necessary cleanup). + */ +public class ContextStoppedException extends Error { + private static final long serialVersionUID = 370773292108890929L; +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/LaunchedContext.java b/src/main/java/com/team766/framework/LaunchedContext.java new file mode 100644 index 00000000..f04b0e3f --- /dev/null +++ b/src/main/java/com/team766/framework/LaunchedContext.java @@ -0,0 +1,19 @@ +package com.team766.framework; + +public interface LaunchedContext { + /** + * Returns a string meant to uniquely identify this Context (e.g. for use in + * logging). + */ + public String getContextName(); + + /** + * Returns true if this Context has finished running, false otherwise. + */ + public boolean isDone(); + + /** + * Interrupt the running of this Context and force it to terminate. + */ + public void stop(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/LoggingBase.java b/src/main/java/com/team766/framework/LoggingBase.java new file mode 100644 index 00000000..4dc02335 --- /dev/null +++ b/src/main/java/com/team766/framework/LoggingBase.java @@ -0,0 +1,27 @@ +package com.team766.framework; + +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public abstract class LoggingBase { + protected Category loggerCategory = Category.PROCEDURES; + + public abstract String getName(); + + protected void log(String message) { + log(Severity.INFO, message); + } + + protected void log(Severity severity, String message) { + Logger.get(loggerCategory).logRaw(severity, getName() + ": " + message); + } + + protected void log(String format, Object... args) { + log(Severity.INFO, format, args); + } + + protected void log(Severity severity, String format, Object... args) { + Logger.get(loggerCategory).logData(severity, getName() + ": " + format, args); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Mechanism.java b/src/main/java/com/team766/framework/Mechanism.java new file mode 100644 index 00000000..b6dbd6e9 --- /dev/null +++ b/src/main/java/com/team766/framework/Mechanism.java @@ -0,0 +1,85 @@ +package com.team766.framework; + +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public abstract class Mechanism extends LoggingBase { + private Context m_owningContext = null; + private Thread m_runningPeriodic = null; + + public Mechanism() { + loggerCategory = Category.MECHANISMS; + + Scheduler.getInstance().add(new Runnable() { + @Override + public void run() { + try { + Mechanism.this.m_runningPeriodic = Thread.currentThread(); + Mechanism.this.run(); + } + finally { + Mechanism.this.m_runningPeriodic = null; + } + } + + @Override + public String toString() { + String repr = Mechanism.this.getName(); + if (Mechanism.this.m_runningPeriodic != null) { + repr += " running\n" + StackTraceUtils.getStackTrace(m_runningPeriodic); + } + return repr; + } + }); + } + + public String getName() { + return this.getClass().getName(); + } + + protected void checkContextOwnership() { + if (Context.currentContext() != m_owningContext && m_runningPeriodic == null) { + String message = getName() + " tried to be used by " + Context.currentContext().getContextName(); + if (m_owningContext != null) { + message += " while owned by " + m_owningContext.getContextName(); + } else { + message += " without taking ownership of it"; + } + Logger.get(Category.FRAMEWORK).logRaw(Severity.ERROR, message); + throw new IllegalStateException(message); + } + } + + void takeOwnership(Context context, Context parentContext) { + if (m_owningContext != null && m_owningContext == parentContext) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is inheriting ownership of " + getName() + " from " + parentContext.getContextName()); + } else { + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is taking ownership of " + getName()); + while (m_owningContext != null && m_owningContext != context) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, "Stopping previous owner of " + getName() + ": " + m_owningContext.getContextName()); + m_owningContext.stop(); + var stoppedContext = m_owningContext; + context.yield(); + if (m_owningContext == stoppedContext) { + Logger.get(Category.FRAMEWORK).logRaw(Severity.ERROR, "Previous owner of " + getName() + ", " + m_owningContext.getContextName() + " did not release ownership when requested. Release will be forced."); + m_owningContext.releaseOwnership(this); + break; + } + } + } + m_owningContext = context; + } + + void releaseOwnership(Context context) { + if (m_owningContext != context) { + LoggerExceptionUtils.logException(new Exception(context.getContextName() + " tried to release ownership of " + getName() + " but it doesn't own it")); + return; + } + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is releasing ownership of " + getName()); + m_owningContext = null; + } + + public void run () {} +} diff --git a/src/main/java/com/team766/framework/Procedure.java b/src/main/java/com/team766/framework/Procedure.java new file mode 100644 index 00000000..c63564a5 --- /dev/null +++ b/src/main/java/com/team766/framework/Procedure.java @@ -0,0 +1,32 @@ +package com.team766.framework; + +public abstract class Procedure extends LoggingBase implements RunnableWithContext { + // A reusable Procedure that does nothing. + private static final class NoOpProcedure extends Procedure { + @Override + public void run(Context context) { + } + } + public static final Procedure NO_OP = new NoOpProcedure(); + + private static int c_idCounter = 0; + + private static synchronized int createNewId() { + return c_idCounter++; + } + + protected final int m_id; + + public Procedure() { + m_id = createNewId(); + } + + public String getName() { + return this.getClass().getName() + "/" + m_id; + } + + @Override + public String toString() { + return getName(); + } +} diff --git a/src/main/java/com/team766/framework/RunnableWithContext.java b/src/main/java/com/team766/framework/RunnableWithContext.java new file mode 100644 index 00000000..6aeb1ec8 --- /dev/null +++ b/src/main/java/com/team766/framework/RunnableWithContext.java @@ -0,0 +1,6 @@ +package com.team766.framework; + +@FunctionalInterface +public interface RunnableWithContext { + public abstract void run(Context context); +} \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Scheduler.java b/src/main/java/com/team766/framework/Scheduler.java new file mode 100644 index 00000000..760b0cd3 --- /dev/null +++ b/src/main/java/com/team766/framework/Scheduler.java @@ -0,0 +1,96 @@ +package com.team766.framework; + +import java.util.LinkedList; +import java.util.stream.Collectors; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class Scheduler implements Runnable { + private static final Scheduler c_instance; + private static final Thread c_monitor; + + static { + c_instance = new Scheduler(); + c_monitor = new Thread(Scheduler::monitor); + c_monitor.setDaemon(true); + c_monitor.start(); + } + + public static Scheduler getInstance() { + return c_instance; + } + + private static void monitor() { + int lastIterationCount = 0; + Runnable lastRunning = null; + while (true) { + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + } + + if (c_instance.m_running != null && + c_instance.m_iterationCount == lastIterationCount && + c_instance.m_running == lastRunning) { + Logger.get(Category.FRAMEWORK).logRaw( + Severity.ERROR, + "The code has gotten stuck in " + + c_instance.m_running.toString() + + ". You probably have an unintended infinite loop or need to add a call to context.yield()"); + Logger.get(Category.FRAMEWORK).logRaw( + Severity.INFO, + Thread.getAllStackTraces() + .entrySet() + .stream() + .map(e -> + e.getKey().getName() + ":\n" + + StackTraceUtils.getStackTrace(e.getValue())) + .collect(Collectors.joining("\n"))); + } + + lastIterationCount = c_instance.m_iterationCount; + lastRunning = c_instance.m_running; + } + } + + private LinkedList m_runnables = new LinkedList(); + private int m_iterationCount = 0; + private Runnable m_running = null; + + public void add(Runnable runnable) { + m_runnables.add(runnable); + } + + public void cancel(Runnable runnable) { + m_runnables.remove(runnable); + } + + public void reset() { + m_runnables.clear(); + } + + public LaunchedContext startAsync(RunnableWithContext func) { + return new Context(func); + } + + public LaunchedContext startAsync(Runnable func) { + return new Context(func); + } + + public void run() { + ++m_iterationCount; + for (Runnable runnable : new LinkedList(m_runnables)) { + try { + m_running = runnable; + runnable.run(); + } catch (Exception ex) { + ex.printStackTrace(); + LoggerExceptionUtils.logException(ex); + } finally { + m_running = null; + } + } + } +} diff --git a/src/main/java/com/team766/framework/StackTraceUtils.java b/src/main/java/com/team766/framework/StackTraceUtils.java new file mode 100644 index 00000000..f325221c --- /dev/null +++ b/src/main/java/com/team766/framework/StackTraceUtils.java @@ -0,0 +1,25 @@ +package com.team766.framework; + +class StackTraceUtils { + public static String getStackTrace(Thread thread) { + StackTraceElement[] stackTrace; + try { + stackTrace = thread.getStackTrace(); + } catch (Exception ex) { + ex.printStackTrace(); + return ""; + } + return getStackTrace(stackTrace); + } + + public static String getStackTrace(StackTraceElement[] stackTrace) { + String repr = ""; + for (var stackFrame : stackTrace) { + repr += " at " + stackFrame.getClassName() + "." + stackFrame.getMethodName(); + if (stackFrame.getFileName() != null) { + repr += " (" + stackFrame.getFileName() + ":" + stackFrame.getLineNumber() + ")\n"; + } + } + return repr; + } +} diff --git a/src/main/java/com/team766/framework/WPILibCommandProcedure.java b/src/main/java/com/team766/framework/WPILibCommandProcedure.java new file mode 100644 index 00000000..720db197 --- /dev/null +++ b/src/main/java/com/team766/framework/WPILibCommandProcedure.java @@ -0,0 +1,48 @@ +package com.team766.framework; + +import edu.wpi.first.wpilibj2.command.Command; + +/** + * This wraps a class that confroms to WPILib's Command interface, and allows + * it to be used in the Maroon Framework as a Procedure. + */ +public class WPILibCommandProcedure extends Procedure { + + private final Command command; + private Mechanism[] requirements; + + /** + * @param command The WPILib Command to adapt + * @param requirements This Procedure will take ownership of the Mechanisms + * given here during the time it is executing. + */ + public WPILibCommandProcedure(Command command, Mechanism... requirements) { + this.command = command; + this.requirements = requirements; + } + + @Override + public void run(Context context) { + for (Mechanism req : this.requirements) { + context.takeOwnership(req); + } + boolean interrupted = false; + try { + this.command.initialize(); + while (!this.command.isFinished()) { + this.command.execute(); + context.yield(); + } + } catch (Throwable ex) { + interrupted = true; + this.command.cancel(); + throw ex; + } finally { + this.command.end(interrupted); + for (Mechanism req : this.requirements) { + context.releaseOwnership(req); + } + } + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/AnalogInputReader.java b/src/main/java/com/team766/hal/AnalogInputReader.java new file mode 100755 index 00000000..e41750a4 --- /dev/null +++ b/src/main/java/com/team766/hal/AnalogInputReader.java @@ -0,0 +1,23 @@ +package com.team766.hal; + +public interface AnalogInputReader extends ControlInputReader { + /** + * Get a scaled sample straight from this channel. The value is scaled to units of Volts using the + * calibrated scaling data from getLSBWeight() and getOffset(). + * + * @return A scaled sample straight from this channel. + */ + public double getVoltage(); + + // Implementation for ControlInputReader interface + @Override + public default double getPosition() { + return getVoltage(); + } + + // Implementation for ControlInputReader interface + @Override + public default double getRate() { + throw new UnsupportedOperationException("Analog input sensor does not have support for velocity"); + } +} diff --git a/src/main/java/com/team766/hal/BasicMotorController.java b/src/main/java/com/team766/hal/BasicMotorController.java new file mode 100644 index 00000000..6111b2e0 --- /dev/null +++ b/src/main/java/com/team766/hal/BasicMotorController.java @@ -0,0 +1,20 @@ +package com.team766.hal; + +public interface BasicMotorController { + + /** + * Common interface for getting the output power of a motor controller. + * + * @return The current set power. Value is between -1.0 and 1.0. + */ + double get(); + + /** + * Common interface for setting the output power of a motor controller. + * + * @param power The power to set. Value should be between -1.0 and 1.0. + */ + void set(double power); + + void restoreFactoryDefault(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/CameraInterface.java b/src/main/java/com/team766/hal/CameraInterface.java new file mode 100755 index 00000000..ac7d698c --- /dev/null +++ b/src/main/java/com/team766/hal/CameraInterface.java @@ -0,0 +1,9 @@ +package com.team766.hal; + +import org.opencv.core.Mat; + +public interface CameraInterface { + public void startAutomaticCapture(); + public void getFrame(Mat img); + public void putFrame(Mat img); +} diff --git a/src/main/java/com/team766/hal/CameraReader.java b/src/main/java/com/team766/hal/CameraReader.java new file mode 100755 index 00000000..5d8a3ace --- /dev/null +++ b/src/main/java/com/team766/hal/CameraReader.java @@ -0,0 +1,7 @@ +package com.team766.hal; + +import org.opencv.core.Mat; + +public interface CameraReader { + public Mat getImage(); +} diff --git a/src/main/java/com/team766/hal/Clock.java b/src/main/java/com/team766/hal/Clock.java new file mode 100644 index 00000000..19541c18 --- /dev/null +++ b/src/main/java/com/team766/hal/Clock.java @@ -0,0 +1,5 @@ +package com.team766.hal; + +public interface Clock { + public double getTime(); +} diff --git a/src/main/java/com/team766/hal/ControlInputReader.java b/src/main/java/com/team766/hal/ControlInputReader.java new file mode 100644 index 00000000..a360209f --- /dev/null +++ b/src/main/java/com/team766/hal/ControlInputReader.java @@ -0,0 +1,13 @@ +package com.team766.hal; + +public interface ControlInputReader { + /** + * Get the current position of the mechanism read by the sensor. + */ + public double getPosition(); + + /** + * Get the current rate of change of the position. + */ + public double getRate(); +} diff --git a/src/main/java/com/team766/hal/DigitalInputReader.java b/src/main/java/com/team766/hal/DigitalInputReader.java new file mode 100755 index 00000000..8dfe9c3a --- /dev/null +++ b/src/main/java/com/team766/hal/DigitalInputReader.java @@ -0,0 +1,11 @@ +package com.team766.hal; + +public interface DigitalInputReader { + /** + * Get the value from a digital input channel. Retrieve the value of a + * single digital input channel from the FPGA. + * + * @return the status of the digital input + */ + public boolean get(); +} diff --git a/src/main/java/com/team766/hal/DoubleSolenoid.java b/src/main/java/com/team766/hal/DoubleSolenoid.java new file mode 100755 index 00000000..6bed6c38 --- /dev/null +++ b/src/main/java/com/team766/hal/DoubleSolenoid.java @@ -0,0 +1,62 @@ +package com.team766.hal; + +public class DoubleSolenoid implements SolenoidController { + + private SolenoidController forward; + private SolenoidController back; + private boolean boolState; + + public enum State { + Forward, Neutral, Backward + } + + public DoubleSolenoid(SolenoidController forward, SolenoidController back) { + this.forward = forward; + this.back = back; + + set(State.Neutral); + } + + @Override + public boolean get() { + return boolState; + } + + public void set(State state) { + switch(state) { + case Forward: + boolState = true; + if (forward != null) { + forward.set(true); + } + if (back != null) { + back.set(false); + } + break; + case Backward: + boolState = false; + if (forward != null) { + forward.set(false); + } + if (back != null) { + back.set(true); + } + break; + case Neutral: + boolState = false; + if (forward != null) { + forward.set(false); + } + if (back != null) { + back.set(false); + } + break; + } + } + + @Override + public void set(boolean on) { + set(on ? State.Forward : State.Backward); + } + +} diff --git a/src/main/java/com/team766/hal/EncoderReader.java b/src/main/java/com/team766/hal/EncoderReader.java new file mode 100755 index 00000000..03daed87 --- /dev/null +++ b/src/main/java/com/team766/hal/EncoderReader.java @@ -0,0 +1,73 @@ +package com.team766.hal; + +public interface EncoderReader extends ControlInputReader { + + /** + * Gets the current count. Returns the current count on the Encoder. This + * method compensates for the decoding type. + * + * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x + * scale factor. + */ + public int get(); + + /** + * Reset the Encoder distance to zero. Resets the current count to zero on + * the encoder. + */ + public void reset(); + + /** + * Determine if the encoder is stopped. Using the MaxPeriod value, a boolean + * is returned that is true if the encoder is considered stopped and false + * if it is still moving. A stopped encoder is one where the most recent + * pulse width exceeds the MaxPeriod. + * + * @return True if the encoder is considered stopped. + */ + public boolean getStopped(); + + /** + * The last direction the encoder value changed. + * + * @return The last direction the encoder value changed. + */ + public boolean getDirection(); + + /** + * Get the distance the robot has driven since the last reset. + * + * @return The distance driven since the last reset as scaled by the value + * from setDistancePerPulse(). + */ + public double getDistance(); + + /** + * Get the current rate of the encoder. Units are distance per second as + * scaled by the value from setDistancePerPulse(). + * + * @return The current rate of the encoder. + */ + public double getRate(); + + /** + * Set the distance per pulse for this encoder. This sets the multiplier + * used to determine the distance driven based on the count value from the + * encoder. Do not include the decoding type in this scale. The library + * already compensates for the decoding type. Set this value based on the + * encoder's rated Pulses per Revolution and factor in gearing reductions + * following the encoder shaft. This distance can be in any units you like, + * linear or angular. + * + * @param distancePerPulse + * The scale factor that will be used to convert pulses to useful + * units. + */ + public void setDistancePerPulse(double distancePerPulse); + + // Implementation for ControlInputReader interface + @Override + public default double getPosition() { + return getDistance(); + } +} diff --git a/src/main/java/com/team766/hal/GenericRobotMain.java b/src/main/java/com/team766/hal/GenericRobotMain.java new file mode 100755 index 00000000..599f9ff3 --- /dev/null +++ b/src/main/java/com/team766/hal/GenericRobotMain.java @@ -0,0 +1,136 @@ +package com.team766.hal; + +import com.team766.framework.Scheduler; +import com.team766.framework.AutonomousMode; +import com.team766.framework.LaunchedContext; +import com.team766.framework.Procedure; +import com.team766.hal.GenericRobotMain; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; +import com.team766.robot.AutonomousModes; +import com.team766.robot.OI; +import com.team766.robot.Robot; +import com.team766.web.AutonomousSelector; +import com.team766.web.ConfigUI; +import com.team766.web.Dashboard; +import com.team766.web.DriverInterface; +import com.team766.web.LogViewer; +import com.team766.web.ReadLogs; +import com.team766.web.WebServer; + +// Team 766 - Robot Interface Base class + +public final class GenericRobotMain { + private OI m_oi; + + private WebServer m_webServer; + private AutonomousSelector m_autonSelector; + private AutonomousMode m_autonMode = null; + private LaunchedContext m_autonomous = null; + private LaunchedContext m_oiContext = null; + + // Reset the autonomous routine if the robot is disabled for more than this + // number of seconds. + private static final double RESET_IN_DISABLED_PERIOD = 10.0; + private double m_disabledModeStartTime; + + public GenericRobotMain() { + m_autonSelector = new AutonomousSelector(AutonomousModes.AUTONOMOUS_MODES); + m_webServer = new WebServer(); + m_webServer.addHandler(new Dashboard()); + m_webServer.addHandler(new DriverInterface(m_autonSelector)); + m_webServer.addHandler(new ConfigUI()); + m_webServer.addHandler(new LogViewer()); + m_webServer.addHandler(new ReadLogs()); + m_webServer.addHandler(m_autonSelector); + m_webServer.start(); + } + + public void robotInit() { + Robot.robotInit(); + + m_oi = new OI(); + } + + public void disabledInit() { + m_disabledModeStartTime = RobotProvider.instance.getClock().getTime(); + } + + public void disabledPeriodic() { + // The robot can enter disabled mode for two reasons: + // - The field control system set the robots to disabled. + // - The robot loses communication with the driver station. + // In the former case, we want to reset the autonomous routine, as there + // may have been a field fault, which would mean the match is going to + // be replayed (and thus we would want to run the autonomous routine + // from the beginning). In the latter case, we don't want to reset the + // autonomous routine because the communication drop was likely caused + // by some short-lived (less than a second long, or so) interference; + // when the communications are restored, we want to continue executing + // the routine that was interrupted, since it has knowledge of where the + // robot is on the field, the state of the robot's mechanisms, etc. + // Thus, we set a threshold on the amount of time spent in autonomous of + // 10 seconds. It is almost certain that it will take longer than 10 + // seconds to reset the field if a match is to be replayed, but it is + // also almost certain that a communication drop will be much shorter + // than 10 seconds. + double timeInState = + RobotProvider.instance.getClock().getTime() - m_disabledModeStartTime; + if (timeInState > RESET_IN_DISABLED_PERIOD) { + resetAutonomousMode("time in disabled mode"); + } + } + + public void resetAutonomousMode(String reason) { + if (m_autonomous != null) { + m_autonomous.stop(); + m_autonomous = null; + m_autonMode = null; + Logger.get(Category.AUTONOMOUS).logRaw( + Severity.INFO, "Resetting autonomus procedure from " + reason); + } + } + + public void autonomousInit() { + if (m_oiContext != null) { + m_oiContext.stop(); + m_oiContext = null; + } + + if (m_autonomous != null) { + Logger.get(Category.AUTONOMOUS).logRaw(Severity.INFO, "Continuing previous autonomus procedure " + m_autonomous.getContextName()); + } else if (m_autonSelector.getSelectedAutonMode() == null) { + Logger.get(Category.AUTONOMOUS).logRaw(Severity.WARNING, "No autonomous mode selected"); + } + } + + public void autonomousPeriodic() { + final AutonomousMode autonomousMode = m_autonSelector.getSelectedAutonMode(); + if (autonomousMode != null && m_autonMode != autonomousMode) { + final Procedure autonProcedure = autonomousMode.instantiate(); + m_autonomous = Scheduler.getInstance().startAsync(autonProcedure); + m_autonMode = autonomousMode; + Logger.get(Category.AUTONOMOUS).logRaw(Severity.INFO, "Starting new autonomus procedure " + autonProcedure.getName()); + } + } + + public void teleopInit() { + if (m_autonomous != null) { + m_autonomous.stop(); + m_autonomous = null; + m_autonMode = null; + } + + if (m_oiContext == null) { + m_oiContext = Scheduler.getInstance().startAsync(m_oi); + } + } + + public void teleopPeriodic() { + if (m_oiContext.isDone()) { + m_oiContext = Scheduler.getInstance().startAsync(m_oi); + Logger.get(Category.OPERATOR_INTERFACE).logRaw(Severity.WARNING, "Restarting OI context"); + } + } +} diff --git a/src/main/java/com/team766/hal/GyroReader.java b/src/main/java/com/team766/hal/GyroReader.java new file mode 100755 index 00000000..0eae1632 --- /dev/null +++ b/src/main/java/com/team766/hal/GyroReader.java @@ -0,0 +1,61 @@ +package com.team766.hal; + +public interface GyroReader { + /** + * Calibrate the gyro by running for a number of samples and computing the + * center value. Then use the center value as the Accumulator center value for + * subsequent measurements. It's important to make sure that the robot is not + * moving while the centering calculations are in progress, this is typically + * done when the robot is first turned on while it's sitting at rest before + * the competition starts. + */ + public void calibrate(); + + /** + * Reset the gyro. Resets the gyro to a heading of zero. This can be used if + * there is significant drift in the gyro and it needs to be recalibrated + * after it has been running. + */ + public void reset(); + + /** + * Return the actual angle in degrees that the robot is currently facing. + * + * The angle is based on the current accumulator value corrected by the + * oversampling rate, the gyro type and the A/D calibration values. The angle + * is continuous, that is it will continue from 360 to 361 degrees. This + * allows algorithms that wouldn't want to see a discontinuity in the gyro + * output as it sweeps past from 360 to 0 on the second time around. + * + * @return the current heading of the robot in degrees. This heading is based + * on integration of the returned rate from the gyro. + */ + public double getAngle(); + + /** + * Return the rate of rotation of the gyro + * + * The rate is based on the most recent reading of the gyro analog value + * + * @return the current rate in degrees per second + */ + public double getRate(); + + /** + * Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor. + * This is the angle that the robot is tilted forward or backward. + * Should return 0 degrees if the robot is sitting flat on the floor. + * + * @return pitch angle (in degrees, -180 to 180) + */ + public double getPitch(); + + /** + * Returns the current roll value (in degrees, from -180 to 180) reported by the sensor. + * This is the angle that the robot is tilted left or right. + * Should return 0 degrees if the robot is sitting flat on the floor. + * + * @return roll angle (in degrees, -180 to 180) + */ + public double getRoll(); +} diff --git a/src/main/java/com/team766/hal/JoystickReader.java b/src/main/java/com/team766/hal/JoystickReader.java new file mode 100755 index 00000000..ffb40e62 --- /dev/null +++ b/src/main/java/com/team766/hal/JoystickReader.java @@ -0,0 +1,46 @@ +package com.team766.hal; + +public interface JoystickReader { + /** + * Get the value of the axis. + * + * @param axis The axis to read, starting at 0. + * @return The value of the axis. + */ + public double getAxis(int axis); + + /** + * Get the button value (starting at button 1) + * + * The appropriate button is returned as a boolean value. + * + * @param button The button number to be read (starting at 1). + * @return The state of the button. + */ + public boolean getButton(int button); + + /** + * Whether the button was pressed since the last check. Button indexes begin at + * 1. + * + * @param button The button index, beginning at 1. + * @return Whether the button was pressed since the last check. + */ + public boolean getButtonPressed(int button); + + /** + * Whether the button was released since the last check. Button indexes begin at + * 1. + * + * @param button The button index, beginning at 1. + * @return Whether the button was released since the last check. + */ + public boolean getButtonReleased(int button); + + /** + * Get the value of the POV + * + * @return the value of the POV + */ + public int getPOV(); +} diff --git a/src/main/java/com/team766/hal/LocalMotorController.java b/src/main/java/com/team766/hal/LocalMotorController.java new file mode 100644 index 00000000..41f3f170 --- /dev/null +++ b/src/main/java/com/team766/hal/LocalMotorController.java @@ -0,0 +1,271 @@ +package com.team766.hal; + +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.team766.controllers.PIDController; +import com.team766.framework.Scheduler; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class LocalMotorController implements MotorController { + private BasicMotorController motor; + private ControlInputReader sensor; + private PIDController pidController; + + private boolean inverted = false; + private boolean sensorInverted = false; + private double sensorOffset = 0.0; + + private ControlMode controlMode = ControlMode.PercentOutput; + private double setpoint = 0.0; + private MotorController leader = null; + + public LocalMotorController(String configPrefix, BasicMotorController motor, ControlInputReader sensor){ + this.motor = motor; + this.sensor = sensor; + + if (!configPrefix.endsWith(".")) { + configPrefix += "."; + } + this.pidController = PIDController.loadFromConfig(configPrefix + "pid."); + + Scheduler.getInstance().add(new Runnable() { + @Override + public void run() { + switch (LocalMotorController.this.controlMode) { + case Current: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support Current control mode")); + stopMotor(); + break; + case Disabled: + // support proper output disabling if this.motor is a MotorController + if (LocalMotorController.this.motor instanceof MotorController) { + ((MotorController)LocalMotorController.this.motor).set(ControlMode.Disabled, 0); + } else { + setPower(0); + } + break; + case Follower: + setPower(leader.get()); + break; + case MotionMagic: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionMagic control mode")); + stopMotor(); + break; + case MotionProfile: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionProfile control mode")); + stopMotor(); + break; + case MotionProfileArc: + LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionProfileArc control mode")); + stopMotor(); + break; + case PercentOutput: + setPower(setpoint); + break; + case Position: + pidController.calculate(getSensorPosition()); + setPower(pidController.getOutput()); + break; + case Velocity: + pidController.calculate(getSensorVelocity()); + setPower(pidController.getOutput()); + break; + case Voltage: + setPower(setpoint / RobotProvider.instance.getBatteryVoltage()); + break; + } + } + + @Override + public String toString() { + return LocalMotorController.this.toString(); + } + }); + } + + @Override + public String toString() { + return "LocalMotorController:" + LocalMotorController.this.motor.toString(); + } + + private void setPower(double power) { + if (this.inverted) { + power *= -1; + } + this.motor.set(power); + } + + @Override + public double get() { + double value = motor.get(); + if (this.inverted) { + value *= -1; + } + return value; + } + + @Override + public void set(double power) { + set(ControlMode.PercentOutput, power); + } + + @Override + public void setInverted(boolean isInverted) { + this.inverted = isInverted; + } + + @Override + public boolean getInverted() { + return this.inverted; + } + + @Override + public void stopMotor() { + set(ControlMode.PercentOutput, 0); + } + + @Override + public void setSensorPosition(double position) { + if (this.sensor == null) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + return; + } + if (this.sensorInverted != this.inverted) { + position *= -1; + } + sensorOffset = position - sensor.getPosition(); + } + + @Override + public double getSensorPosition() { + if (this.sensor == null) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + return 0.0; + } + double position = sensor.getPosition() + sensorOffset; + if (this.sensorInverted != this.inverted) { + position *= -1; + } + return position; + } + + @Override + public double getSensorVelocity() { + if (this.sensor == null) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + return 0.0; + } + double velocity = sensor.getRate(); + if (this.sensorInverted != this.inverted) { + velocity *= -1; + } + return velocity; + } + + @Override + public void set(ControlMode mode, double value) { + if (mode == ControlMode.Follower) { + throw new IllegalArgumentException("Use follow() method instead of passing Follower to set()"); + } + if (this.controlMode != mode) { + pidController.reset(); + } + this.controlMode = mode; + this.setpoint = value; + this.pidController.setSetpoint(setpoint); + } + + public ControlMode getControlMode() { + return this.controlMode; + } + + @Override + public void follow(MotorController leader) { + if (leader == null) { + throw new IllegalArgumentException("leader argument to follow() is null"); + } + // TODO: detect if this.motor is a MotorController, and delegate to its follow() method if so. + this.controlMode = ControlMode.Follower; + this.leader = leader; + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + if (this.motor instanceof MotorController) { + ((MotorController)this.motor).setNeutralMode(neutralMode); + } else { + LoggerExceptionUtils.logException(new UnsupportedOperationException(this.toString() + " - setNeutralMode() is only supported with CAN motor controllers")); + } + } + + @Override + public void setP(double value) { + pidController.setP(value); + } + + @Override + public void setI(double value) { + pidController.setI(value); + } + + @Override + public void setD(double value) { + pidController.setD(value); + } + + @Override + public void setFF(double value) { + pidController.setFF(value); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setSelectedFeedbsckSensor() is currently unsupported by LocalMotorController")); + } + + @Override + public void setSensorInverted(boolean inverted) { + this.sensorInverted = inverted; + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + pidController.setMaxoutputLow(minOutput); + pidController.setMaxoutputHigh(maxOutput); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setCurrentLimit() is currently unsupported by LocalMotorController")); + } + + @Override + public void restoreFactoryDefault() { + this.motor.restoreFactoryDefault(); + + this.setP(0.0); + this.setI(0.0); + this.setD(0.0); + this.setFF(0.0); + this.pidController.setMaxoutputLow(null); + this.pidController.setMaxoutputHigh(null); + + this.inverted = false; + this.sensorInverted = false; + this.controlMode = ControlMode.Disabled; + this.setpoint = 0.0; + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setOpenLoopRamp() is currently unsupported by LocalMotorController")); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + LoggerExceptionUtils.logException(new UnsupportedOperationException("setClosedLoopRamp() is currently unsupported by LocalMotorController")); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/MotorController.java b/src/main/java/com/team766/hal/MotorController.java new file mode 100755 index 00000000..80635f30 --- /dev/null +++ b/src/main/java/com/team766/hal/MotorController.java @@ -0,0 +1,138 @@ +package com.team766.hal; + +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; + +/** + * Interface for motor controlling devices. + */ + +public interface MotorController extends BasicMotorController { + + public enum Type { + VictorSP, + VictorSPX, + TalonSRX, + SparkMax, + TalonFX, + } + + public enum ControlMode { + PercentOutput, + Position, + Velocity, + Current, + Voltage, + Follower, + MotionProfile, + MotionMagic, + MotionProfileArc, + Disabled, + } + + /** + * Common interface for getting the current power output by a motor controller. + * + * @return The current set power. Value is between -1.0 and 1.0. + */ + double get(); + + + /** + * Common interface for setting the power outputu by a motor controller. + * + * @param power The power to set. Value should be between -1.0 and 1.0. + */ + void set(double power); + + /** + * Sets the appropriate output on the motor controller, depending on the mode. + * @param mode The output mode to apply. + * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. + * In Current mode, output value is in amperes. + * In Velocity mode, output value is in position change / 100ms. + * In Position mode, output value is in encoder ticks or an analog value, + * depending on the sensor. + * In Follower mode, the output value is the integer device ID of the talon to + * duplicate. + * + * @param value The setpoint value, as described above. + */ + void set(ControlMode mode, double value); + + /** + * Common interface for inverting direction of a motor controller. + * + * This changes the direction of the motor and sensor together. To change the + * direction of the sensor relative to the direction of the motor, + * use setSensorInverted. + * + * @param isInverted The state of inversion true is inverted. + */ + void setInverted(boolean isInverted); + + /** + * Common interface for returning if a motor controller is in the inverted + * state or not. + * + * @return isInverted The state of the inversion true is inverted. + */ + boolean getInverted(); + + /** + * Stops motor movement. Motor can be moved again by calling set without having + * to re-enable the motor. + */ + void stopMotor(); + + /** + * Read the motor position from the sensor attached to the motor controller. + */ + double getSensorPosition(); + + /** + * Read the motor velocity from the sensor attached to the motor controller. + */ + double getSensorVelocity(); + + /** + * Sets the motors encoder value to the given position. + * + * @param position The desired set position + */ + void setSensorPosition(double position); + + void follow(MotorController leader); + + void setNeutralMode(NeutralMode neutralMode); + + void setP(double value); + + void setI(double value); + + void setD(double value); + + void setFF(double value); + + void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice); + + /** + * Set whether to reverse the sensor relative to the direction of the motor. + * + * This is different from setInverted, which sets the direction of both the + * motor and sensor together. + * + * @param inverted The state of inversion true is inverted. + */ + void setSensorInverted(boolean inverted); + + void setOutputRange(double minOutput, double maxOutput); + + void setCurrentLimit(double ampsLimit); + + void restoreFactoryDefault(); + + void setOpenLoopRamp(double secondsFromNeutralToFull); + + void setClosedLoopRamp(double secondsFromNeutralToFull); +} diff --git a/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java b/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java new file mode 100644 index 00000000..76efb847 --- /dev/null +++ b/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java @@ -0,0 +1,13 @@ +package com.team766.hal; + +public class MotorControllerCommandFailedException extends RuntimeException { + + public MotorControllerCommandFailedException(String message) { + super(message); + } + + public MotorControllerCommandFailedException(String message, Throwable cause) { + super(message, cause); + } + +} diff --git a/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java b/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java new file mode 100644 index 00000000..50fb01dc --- /dev/null +++ b/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java @@ -0,0 +1,158 @@ +package com.team766.hal; + +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; + +public class MotorControllerWithSensorScale implements MotorController { + private MotorController delegate; + private double scale; + + public MotorControllerWithSensorScale(MotorController delegate, double scale) { + this.delegate = delegate; + this.scale = scale; + } + + @Override + public double getSensorPosition() { + return delegate.getSensorPosition() * scale; + } + + @Override + public double getSensorVelocity() { + return delegate.getSensorVelocity() * scale; + } + + @Override + public void set(ControlMode mode, double value) { + switch (mode) { + case PercentOutput: + delegate.set(mode, value); + return; + case Position: + delegate.set(mode, value / scale); + return; + case Velocity: + delegate.set(mode, value / scale); + return; + case Current: + delegate.set(mode, value); + return; + case Voltage: + delegate.set(mode, value); + case Follower: + delegate.set(mode, value); + return; + case MotionProfile: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case MotionMagic: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case MotionProfileArc: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case Disabled: + delegate.set(mode, value); + return; + } + throw new UnsupportedOperationException("Unimplemented control mode in MotorControllerWithSensorScale"); + } + + @Override + public void setInverted(boolean isInverted) { + delegate.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return delegate.getInverted(); + } + + @Override + public void stopMotor() { + delegate.stopMotor(); + } + + @Override + public void setSensorPosition(double position) { + delegate.setSensorPosition(position / scale); + } + + @Override + public void follow(MotorController leader) { + delegate.follow(leader); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + delegate.setNeutralMode(neutralMode); + } + + @Override + public void setP(double value) { + delegate.setP(value / scale); + } + + @Override + public void setI(double value) { + delegate.setI(value / scale); + } + + @Override + public void setD(double value) { + delegate.setD(value / scale); + } + + @Override + public void setFF(double value) { + delegate.setFF(value / scale); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + delegate.setSelectedFeedbackSensor(feedbackDevice); + } + + @Override + public void setSensorInverted(boolean inverted) { + delegate.setSensorInverted(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + delegate.setOutputRange(minOutput, maxOutput); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + delegate.setCurrentLimit(ampsLimit); + } + + @Override + public void restoreFactoryDefault() { + delegate.restoreFactoryDefault(); + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + delegate.setOpenLoopRamp(secondsFromNeutralToFull); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + delegate.setClosedLoopRamp(secondsFromNeutralToFull); + } + + @Override + public double get() { + return delegate.get(); + } + + @Override + public void set(double power) { + delegate.set(power); + } +} diff --git a/src/main/java/com/team766/hal/MultiSolenoid.java b/src/main/java/com/team766/hal/MultiSolenoid.java new file mode 100644 index 00000000..39a47aea --- /dev/null +++ b/src/main/java/com/team766/hal/MultiSolenoid.java @@ -0,0 +1,27 @@ +package com.team766.hal; + +public class MultiSolenoid implements SolenoidController { + + private SolenoidController[] solenoids; + private boolean state; + + public MultiSolenoid(SolenoidController... solenoids) { + this.solenoids = solenoids; + + set(false); + } + + @Override + public boolean get() { + return state; + } + + @Override + public void set(boolean on) { + state = on; + for (SolenoidController s : solenoids) { + s.set(on); + } + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/PositionReader.java b/src/main/java/com/team766/hal/PositionReader.java new file mode 100644 index 00000000..452c4579 --- /dev/null +++ b/src/main/java/com/team766/hal/PositionReader.java @@ -0,0 +1,24 @@ +package com.team766.hal; + +public interface PositionReader { + /** + * Return the position of the robot along the global X axis. + * + * @return the current position coordinate in meters + */ + public double getX(); + + /** + * Return the position of the robot along the global Y axis. + * + * @return the current position coordinate in meters + */ + public double getY(); + + /** + * Return the angle that the robot is currently facing. + * + * @return the current heading angle in degrees + */ + public double getHeading(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/RelayOutput.java b/src/main/java/com/team766/hal/RelayOutput.java new file mode 100755 index 00000000..e6e7bd96 --- /dev/null +++ b/src/main/java/com/team766/hal/RelayOutput.java @@ -0,0 +1,16 @@ +package com.team766.hal; + + +/** + * Interface for digital output devices + */ + +public interface RelayOutput { + + public void set(Value val); + + enum Value{ + kOff, kOn, kForward, kReverse + } + +} diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java new file mode 100755 index 00000000..40f3f218 --- /dev/null +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -0,0 +1,234 @@ +package com.team766.hal; + +import java.util.Arrays; +import java.util.HashMap; + +import com.team766.config.ConfigFileReader; +import com.team766.controllers.TimeProviderI; +import com.team766.hal.mock.MockAnalogInput; +import com.team766.hal.mock.MockDigitalInput; +import com.team766.hal.mock.MockEncoder; +import com.team766.hal.mock.MockGyro; +import com.team766.hal.mock.MockRelay; +import com.team766.hal.mock.MockMotorController; +import com.team766.library.ValueProvider; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public abstract class RobotProvider { + + public static RobotProvider instance; + + protected EncoderReader[] encoders = new EncoderReader[20]; + protected SolenoidController[] solenoids = new SolenoidController[10]; + protected GyroReader[] gyros = new GyroReader[13]; + protected HashMap cams = new HashMap(); + protected JoystickReader[] joysticks = new JoystickReader[8]; + protected DigitalInputReader[] digInputs = new DigitalInputReader[8]; + protected AnalogInputReader[] angInputs = new AnalogInputReader[5]; + protected RelayOutput[] relays = new RelayOutput[5]; + protected PositionReader positionSensor = null; + + private HashMap motorDeviceIdNames = new HashMap(); + private HashMap motorPortNames = new HashMap(); + private HashMap digitalIoNames = new HashMap(); + private HashMap analogInputNames = new HashMap(); + private HashMap relayNames = new HashMap(); + private HashMap solenoidNames = new HashMap(); + private HashMap gyroNames = new HashMap(); + + //HAL + protected abstract MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor); + + public abstract EncoderReader getEncoder(int index1, int index2); + + public abstract DigitalInputReader getDigitalInput(int index); + + public abstract AnalogInputReader getAnalogInput(int index); + + public abstract RelayOutput getRelay(int index); + + public abstract SolenoidController getSolenoid(int index); + + public abstract GyroReader getGyro(int index); + + public abstract CameraReader getCamera(String id, String value); + + public abstract PositionReader getPositionSensor(); + + public static TimeProviderI getTimeProvider(){ + return () -> instance.getClock().getTime(); + } + + // Config-driven methods + + private void checkDeviceName(String deviceType, HashMap deviceNames, Integer portId, String configName) { + String previousName = deviceNames.putIfAbsent(portId, configName); + if (previousName != null && previousName != configName) { + Logger.get(Category.CONFIGURATION).logRaw( + Severity.ERROR, + "Multiple " + deviceType + " devices for port ID " + portId + ": " + previousName + ", " + configName); + } + } + + public MotorController getMotor(String configName) { + final String encoderConfigName = configName + ".encoder"; + final String analogInputConfigName = configName + ".analogInput"; + final ControlInputReader sensor = + ConfigFileReader.getInstance().containsKey(encoderConfigName) ? getEncoder(encoderConfigName) : + ConfigFileReader.getInstance().containsKey(analogInputConfigName) ? getAnalogInput(analogInputConfigName) : + null; + + try { + ValueProvider deviceId = ConfigFileReader.getInstance().getInt(configName + ".deviceId"); + final ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + final ValueProvider sensorScaleConfig = ConfigFileReader.getInstance().getDouble(configName + ".sensorScale"); + final ValueProvider invertedConfig = ConfigFileReader.getInstance().getBoolean(configName + ".inverted"); + final ValueProvider sensorInvertedConfig = ConfigFileReader.getInstance().getBoolean(configName + ".sensorInverted"); + final ValueProvider type = ConfigFileReader.getInstance().getEnum(MotorController.Type.class, configName + ".type"); + + if (deviceId.hasValue() && port.hasValue()) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s configuration should have only one of `deviceId` or `port`", configName); + } + + MotorController.Type defaultType = MotorController.Type.TalonSRX; + if (!deviceId.hasValue()) { + deviceId = port; + defaultType = MotorController.Type.VictorSP; + checkDeviceName("PWM motor controller", motorPortNames, port.get(), configName); + } else { + checkDeviceName("CAN motor controller", motorDeviceIdNames, deviceId.get(), configName); + } + + var motor = getMotor(deviceId.get(), configName, type.valueOr(defaultType), sensor); + if (sensorScaleConfig.hasValue()) { + motor = new MotorControllerWithSensorScale(motor, sensorScaleConfig.get()); + } + if (invertedConfig.valueOr(false)) { + motor.setInverted(true); + } + if (sensorInvertedConfig.valueOr(false)) { + motor.setSensorInverted(true); + } + return motor; + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s not found in config file, using mock motor instead", configName); + return new LocalMotorController(configName, new MockMotorController(0), sensor); + } + } + + public EncoderReader getEncoder(String configName) { + try { + final ValueProvider ports = ConfigFileReader.getInstance().getInts(configName + ".ports"); + final ValueProvider distancePerPulseConfig = ConfigFileReader.getInstance().getDouble(configName + ".distancePerPulse"); + + final var portsValue = ports.get(); + if (portsValue.length != 2) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Encoder %s has %d config values, but expected 2", configName, portsValue.length); + return new MockEncoder(0, 0); + } + checkDeviceName("encoder/digital input", digitalIoNames, portsValue[0], configName); + checkDeviceName("encoder/digital input", digitalIoNames, portsValue[1], configName); + final EncoderReader reader = getEncoder(portsValue[0], portsValue[1]); + if (distancePerPulseConfig.hasValue()) { + reader.setDistancePerPulse(distancePerPulseConfig.get()); + } + return reader; + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Encoder %s not found in config file, using mock encoder instead", configName); + return new MockEncoder(0, 0); + } + } + + public DigitalInputReader getDigitalInput(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("encoder/digital input", digitalIoNames, port.get(), configName); + + return getDigitalInput(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Digital input %s not found in config file, using mock digital input instead", configName); + return new MockDigitalInput(); + } + } + + public AnalogInputReader getAnalogInput(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("analog input", analogInputNames, port.get(), configName); + + return getAnalogInput(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Analog input %s not found in config file, using mock analog input instead", configName); + return new MockAnalogInput(); + } + } + + public RelayOutput getRelay(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("relay", relayNames, port.get(), configName); + + return getRelay(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Relay %s not found in config file, using mock relay instead", configName); + return new MockRelay(0); + } + } + + public DoubleSolenoid getSolenoid(String configName) { + try { + final String legacyConfigKey = configName + ".port"; + ValueProvider forwardPorts = + ConfigFileReader.getInstance().containsKey(legacyConfigKey) + ? ConfigFileReader.getInstance().getInts(legacyConfigKey) + : ConfigFileReader.getInstance().getInts(configName + ".forwardPort"); + ValueProvider reversePorts = + ConfigFileReader.getInstance().getInts(configName + ".reversePort"); + + for (Integer port : forwardPorts.valueOr(new Integer[0])) { + checkDeviceName("solenoid", solenoidNames, port, configName); + } + for (Integer port : reversePorts.valueOr(new Integer[0])) { + checkDeviceName("solenoid", solenoidNames, port, configName); + } + + SolenoidController forwardSolenoids = new MultiSolenoid( + Arrays.stream(forwardPorts.valueOr(new Integer[0])) + .map(this::getSolenoid) + .toArray(SolenoidController[]::new)); + SolenoidController reverseSolenoids = new MultiSolenoid( + Arrays.stream(reversePorts.valueOr(new Integer[0])) + .map(this::getSolenoid) + .toArray(SolenoidController[]::new)); + return new DoubleSolenoid(forwardSolenoids, reverseSolenoids); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Solenoid %s not found in config file, using mock solenoid instead", configName); + return new DoubleSolenoid(null, null); + } + } + + public GyroReader getGyro(String configName) { + try { + ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + checkDeviceName("gyro", gyroNames, port.get(), configName); + + return getGyro(port.get()); + } catch (IllegalArgumentException ex) { + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Gyro %s not found in config file, using mock gyro instead", configName); + return new MockGyro(); + } + } + + //Operator Devices + public abstract JoystickReader getJoystick(int index); + + public abstract CameraInterface getCamServer(); + + public abstract Clock getClock(); + + public abstract double getBatteryVoltage(); + + public abstract boolean hasNewDriverStationData(); +} diff --git a/src/main/java/com/team766/hal/SolenoidController.java b/src/main/java/com/team766/hal/SolenoidController.java new file mode 100755 index 00000000..8a6605c5 --- /dev/null +++ b/src/main/java/com/team766/hal/SolenoidController.java @@ -0,0 +1,19 @@ +package com.team766.hal; + +public interface SolenoidController { + + /** + * Set the value of a solenoid. + * + * @param on + * Turn the solenoid output off or on. + */ + public void set(boolean on); + + /** + * Read the current value of the solenoid. + * + * @return The current value of the solenoid. + */ + public boolean get(); +} diff --git a/src/main/java/com/team766/hal/VidSourceInterface.java b/src/main/java/com/team766/hal/VidSourceInterface.java new file mode 100755 index 00000000..22b9eef6 --- /dev/null +++ b/src/main/java/com/team766/hal/VidSourceInterface.java @@ -0,0 +1,5 @@ +package com.team766.hal; + +public interface VidSourceInterface { + public String getName(); +} diff --git a/src/main/java/com/team766/hal/mock/MockAnalogInput.java b/src/main/java/com/team766/hal/mock/MockAnalogInput.java new file mode 100755 index 00000000..fdeeccd4 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockAnalogInput.java @@ -0,0 +1,18 @@ +package com.team766.hal.mock; + +import com.team766.hal.AnalogInputReader; + +public class MockAnalogInput implements AnalogInputReader { + + private double sensor = 0.0; + + public void set(double value){ + sensor = value; + } + + @Override + public double getVoltage() { + return sensor; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockCamera.java b/src/main/java/com/team766/hal/mock/MockCamera.java new file mode 100755 index 00000000..125fbc3b --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockCamera.java @@ -0,0 +1,25 @@ +package com.team766.hal.mock; + +import org.opencv.core.Mat; +import org.opencv.imgcodecs.Imgcodecs; + +import com.team766.hal.CameraReader; + +public class MockCamera implements CameraReader{ + + private String nextImage; + + @Override + public Mat getImage() { + if(nextImage == null) { + return null; + } + + return Imgcodecs.imread(nextImage); + } + + public void setNextImage(String nextImage){ + this.nextImage = this.getClass().getClassLoader().getResource(nextImage).getPath(); + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockDigitalInput.java b/src/main/java/com/team766/hal/mock/MockDigitalInput.java new file mode 100755 index 00000000..e8cfe1f4 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockDigitalInput.java @@ -0,0 +1,17 @@ +package com.team766.hal.mock; + +import com.team766.hal.DigitalInputReader; + +public class MockDigitalInput implements DigitalInputReader{ + + private boolean sensor = false; + + public boolean get() { + return sensor; + } + + public void set(boolean on){ + sensor = on; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockEncoder.java b/src/main/java/com/team766/hal/mock/MockEncoder.java new file mode 100755 index 00000000..6eccab0d --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockEncoder.java @@ -0,0 +1,57 @@ +package com.team766.hal.mock; + +import com.team766.hal.EncoderReader; + +public class MockEncoder implements EncoderReader{ + + private double distance = 0; + private double rate = 0; + private double distancePerPulse = 1; + + public MockEncoder(int a, int b){ + } + + @Override + public int get() { + return (int)Math.round(distance / distancePerPulse); + } + + @Override + public void reset() { + distance = 0; + } + + @Override + public boolean getStopped() { + return this.rate == 0; + } + + @Override + public boolean getDirection() { + return this.rate > 0; + } + + @Override + public double getDistance() { + return this.distance; + } + + @Override + public double getRate() { + return this.rate; + } + + public void setDistance(double distance) { + this.distance = distance; + } + + public void setRate(double rate){ + this.rate = rate; + } + + @Override + public void setDistancePerPulse(double distancePerPulse) { + this.distancePerPulse = distancePerPulse; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockGyro.java b/src/main/java/com/team766/hal/mock/MockGyro.java new file mode 100755 index 00000000..32b8db2d --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockGyro.java @@ -0,0 +1,52 @@ +package com.team766.hal.mock; + +import com.team766.hal.GyroReader; + +public class MockGyro implements GyroReader{ + + private double angle = 0; + private double rate = 0; + private double pitch = 0; + private double roll = 0; + + public void calibrate() { + reset(); + } + + public void reset() { + angle = 0; + } + + public double getAngle() { + return angle; + } + + public double getRate() { + return rate; + } + + public double getPitch() { + return pitch; + } + + public double getRoll() { + return roll; + } + + public void setAngle(double angle) { + this.angle = angle; + } + + public void setRate(double rate) { + this.rate = rate; + } + + public void setPitch(double pitch) { + this.pitch = pitch; + } + + public void setRoll(double roll) { + this.roll = roll; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockJoystick.java b/src/main/java/com/team766/hal/mock/MockJoystick.java new file mode 100755 index 00000000..89c2fe70 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockJoystick.java @@ -0,0 +1,69 @@ +package com.team766.hal.mock; + +import com.team766.hal.JoystickReader; + +public class MockJoystick implements JoystickReader { + + private double[] axisValues; + private boolean[] buttonValues; + private boolean[] prevButtonValues; + private int povValue; + + public MockJoystick(){ + axisValues = new double[12]; + buttonValues = new boolean[20]; + prevButtonValues = new boolean[20]; + } + + @Override + public double getAxis(int axis) { + return axisValues[axis]; + } + + @Override + public boolean getButton(int button) { + // Button indexes begin at 1 in WPILib, so match that here + if (button <= 0) { + return false; + } + return buttonValues[button - 1]; + } + + public void setAxisValue(int axis, double value){ + axisValues[axis] = value; + } + + public void setButton(int button, boolean val){ + // Button indexes begin at 1 in WPILib, so match that here + prevButtonValues[button - 1] = buttonValues[button - 1]; + buttonValues[button - 1] = val; + } + + @Override + public int getPOV() { + return povValue; + } + + public void setPOV(int value) { + povValue = value; + } + + @Override + public boolean getButtonPressed(int button) { + // Button indexes begin at 1 in WPILib, so match that here + if (button <= 0) { + return false; + } + return buttonValues[button - 1] && !prevButtonValues[button - 1]; + } + + @Override + public boolean getButtonReleased(int button) { + // Button indexes begin at 1 in WPILib, so match that here + if (button <= 0) { + return false; + } + return !buttonValues[button - 1] && prevButtonValues[button - 1]; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockMotorController.java b/src/main/java/com/team766/hal/mock/MockMotorController.java new file mode 100755 index 00000000..d3115af9 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockMotorController.java @@ -0,0 +1,28 @@ +package com.team766.hal.mock; + +import com.team766.hal.BasicMotorController; + +public class MockMotorController implements BasicMotorController { + + private double output; + + public MockMotorController(int index) { + output = 0; + } + + @Override + public double get() { + return output; + } + + @Override + public void set(double power) { + output = power; + } + + @Override + public void restoreFactoryDefault() { + // No-op + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockPositionSensor.java b/src/main/java/com/team766/hal/mock/MockPositionSensor.java new file mode 100644 index 00000000..0501e345 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockPositionSensor.java @@ -0,0 +1,38 @@ +package com.team766.hal.mock; + +import com.team766.hal.PositionReader; + +public class MockPositionSensor implements PositionReader { + + private double x = 0; + private double y = 0; + private double heading = 0; + + @Override + public double getX() { + return x; + } + + @Override + public double getY() { + return y; + } + + @Override + public double getHeading() { + return heading; + } + + public void setX(double x) { + this.x = x; + } + + public void setY(double y) { + this.y = y; + } + + public void setHeading(double heading) { + this.heading = heading; + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/mock/MockRelay.java b/src/main/java/com/team766/hal/mock/MockRelay.java new file mode 100755 index 00000000..ab07476e --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockRelay.java @@ -0,0 +1,22 @@ +package com.team766.hal.mock; + +import com.team766.hal.RelayOutput; + +public class MockRelay implements RelayOutput{ + + private Value val; + + public MockRelay(int port){ + val = Value.kOff; + } + + @Override + public void set(Value out) { + val = out; + } + + public Value get(){ + return val; + } + +} diff --git a/src/main/java/com/team766/hal/mock/MockSolenoid.java b/src/main/java/com/team766/hal/mock/MockSolenoid.java new file mode 100755 index 00000000..7018330c --- /dev/null +++ b/src/main/java/com/team766/hal/mock/MockSolenoid.java @@ -0,0 +1,21 @@ +package com.team766.hal.mock; + +import com.team766.hal.SolenoidController; + +public class MockSolenoid implements SolenoidController{ + + private boolean pist; + + public MockSolenoid(int port){ + pist = false; + } + + public void set(boolean on) { + pist = on; + } + + public boolean get() { + return pist; + } + +} diff --git a/src/main/java/com/team766/hal/mock/TestRobotProvider.java b/src/main/java/com/team766/hal/mock/TestRobotProvider.java new file mode 100755 index 00000000..208cc991 --- /dev/null +++ b/src/main/java/com/team766/hal/mock/TestRobotProvider.java @@ -0,0 +1,129 @@ +package com.team766.hal.mock; + +import com.team766.hal.AnalogInputReader; +import com.team766.hal.CameraInterface; +import com.team766.hal.CameraReader; +import com.team766.hal.Clock; +import com.team766.hal.ControlInputReader; +import com.team766.hal.DigitalInputReader; +import com.team766.hal.EncoderReader; +import com.team766.hal.GyroReader; +import com.team766.hal.JoystickReader; +import com.team766.hal.LocalMotorController; +import com.team766.hal.PositionReader; +import com.team766.hal.RelayOutput; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.MotorController; +import com.team766.hal.wpilib.SystemClock; + +public class TestRobotProvider extends RobotProvider{ + + private MotorController[] motors = new MotorController[64]; + private boolean m_hasDriverStationUpdate = false; + private double m_batteryVoltage = 12.0; + + @Override + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + if(motors[index] == null) { + motors[index] = new LocalMotorController( + configPrefix, + new MockMotorController(index), + localSensor != null ? localSensor : new MockEncoder(-1, -1)); + } + return motors[index]; + } + + @Override + public EncoderReader getEncoder(int index1, int index2) { + if(encoders[index1] == null) + encoders[index1] = new MockEncoder(index1, index2); + return encoders[index1]; + } + + @Override + public SolenoidController getSolenoid(int index) { + if(solenoids[index] == null) + solenoids[index] = new MockSolenoid(index); + return solenoids[index]; + } + + @Override + public GyroReader getGyro(int index) { + if(gyros[0] == null) + gyros[0] = new MockGyro(); + return gyros[0]; + } + + @Override + public CameraReader getCamera(String id, String value) { + if(!cams.containsKey(id)) + cams.put(id, new MockCamera()); + return cams.get(id); + } + + @Override + public JoystickReader getJoystick(int index) { + if(joysticks[index] == null) + joysticks[index] = new MockJoystick(); + return joysticks[index]; + } + + @Override + public DigitalInputReader getDigitalInput(int index) { + if(digInputs[index] == null) + digInputs[index] = new MockDigitalInput(); + return digInputs[index]; + } + + @Override + public CameraInterface getCamServer() { + return null; + } + + @Override + public AnalogInputReader getAnalogInput(int index) { + if(angInputs[index] == null) + angInputs[index] = new MockAnalogInput(); + return angInputs[index]; + } + + public RelayOutput getRelay(int index) { + if(relays[index] == null) + relays[index] = new MockRelay(index); + return relays[index]; + } + + @Override + public PositionReader getPositionSensor() { + if (positionSensor == null) + positionSensor = new MockPositionSensor(); + return positionSensor; + } + + @Override + public Clock getClock() { + // TODO Replace this with a controlled clock + return SystemClock.instance; + } + + @Override + public boolean hasNewDriverStationData() { + boolean result = m_hasDriverStationUpdate; + m_hasDriverStationUpdate = false; + return result; + } + + public void setHasNewDriverStationData() { + m_hasDriverStationUpdate = true; + } + + @Override + public double getBatteryVoltage() { + return m_batteryVoltage; + } + + public void setBatteryVoltage(double voltage) { + m_batteryVoltage = voltage; + } +} diff --git a/src/main/java/com/team766/hal/simulator/AnalogInput.java b/src/main/java/com/team766/hal/simulator/AnalogInput.java new file mode 100755 index 00000000..83e5766b --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/AnalogInput.java @@ -0,0 +1,19 @@ +package com.team766.hal.simulator; + +import com.team766.hal.AnalogInputReader; +import com.team766.simulator.ProgramInterface; + +public class AnalogInput implements AnalogInputReader{ + + private final int channel; + + public AnalogInput(int channel) { + this.channel = channel; + } + + @Override + public double getVoltage() { + return ProgramInterface.analogChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/Camera.java b/src/main/java/com/team766/hal/simulator/Camera.java new file mode 100755 index 00000000..7f6bb1e8 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Camera.java @@ -0,0 +1,14 @@ +package com.team766.hal.simulator; + +import org.opencv.core.Mat; + +import com.team766.hal.CameraReader; + +public class Camera implements CameraReader{ + + @Override + public Mat getImage() { + return null; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/DigitalInput.java b/src/main/java/com/team766/hal/simulator/DigitalInput.java new file mode 100755 index 00000000..7e3b3a17 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/DigitalInput.java @@ -0,0 +1,18 @@ +package com.team766.hal.simulator; + +import com.team766.hal.DigitalInputReader; +import com.team766.simulator.ProgramInterface; + +public class DigitalInput implements DigitalInputReader{ + + private final int channel; + + public DigitalInput(int channel) { + this.channel = channel; + } + + public boolean get() { + return ProgramInterface.digitalChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/Encoder.java b/src/main/java/com/team766/hal/simulator/Encoder.java new file mode 100755 index 00000000..092c3cb5 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Encoder.java @@ -0,0 +1,54 @@ +package com.team766.hal.simulator; + +import com.team766.hal.EncoderReader; +import com.team766.simulator.ProgramInterface; + +public class Encoder implements EncoderReader{ + + private final int channel; + private double distancePerPulse = 1.0; + + public Encoder(int a, int b){ + this.channel = a; + } + + @Override + public int get() { + return (int)ProgramInterface.encoderChannels[channel].distance; + } + + @Override + public void reset() { + set(0); + } + + @Override + public boolean getStopped() { + return getRate() == 0; + } + + @Override + public boolean getDirection() { + return getRate() > 0; + } + + @Override + public double getDistance() { + return get() * distancePerPulse; + } + + @Override + public double getRate() { + return ProgramInterface.encoderChannels[channel].rate * distancePerPulse; + } + + @Override + public void setDistancePerPulse(double distancePerPulse) { + this.distancePerPulse = distancePerPulse; + } + + public void set(int tick){ + ProgramInterface.encoderChannels[channel].distance = tick; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/Gyro.java b/src/main/java/com/team766/hal/simulator/Gyro.java new file mode 100755 index 00000000..124973d9 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Gyro.java @@ -0,0 +1,32 @@ +package com.team766.hal.simulator; + +import com.team766.hal.GyroReader; +import com.team766.simulator.ProgramInterface; + +public class Gyro implements GyroReader{ + + public void calibrate() { + reset(); + } + + public void reset() { + ProgramInterface.gyro.angle = 0; + } + + public double getAngle() { + return ProgramInterface.gyro.angle; + } + + public double getRate() { + return ProgramInterface.gyro.rate; + } + + public double getPitch() { + return ProgramInterface.gyro.pitch; + } + + public double getRoll() { + return ProgramInterface.gyro.roll; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/PositionSensor.java b/src/main/java/com/team766/hal/simulator/PositionSensor.java new file mode 100644 index 00000000..c8f9dd75 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/PositionSensor.java @@ -0,0 +1,23 @@ +package com.team766.hal.simulator; + +import com.team766.hal.PositionReader; +import com.team766.simulator.ProgramInterface; + +public class PositionSensor implements PositionReader { + + @Override + public double getX() { + return ProgramInterface.robotPosition.x; + } + + @Override + public double getY() { + return ProgramInterface.robotPosition.y; + } + + @Override + public double getHeading() { + return ProgramInterface.robotPosition.heading; + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/simulator/Relay.java b/src/main/java/com/team766/hal/simulator/Relay.java new file mode 100755 index 00000000..f8c0caa4 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Relay.java @@ -0,0 +1,32 @@ +package com.team766.hal.simulator; + +import com.team766.hal.RelayOutput; +import com.team766.simulator.ProgramInterface; + +public class Relay implements RelayOutput{ + + private int channel; + + public Relay(int channel){ + this.channel = channel; + } + + @Override + public void set(Value out) { + switch(out) { + case kForward: + ProgramInterface.relayChannels[channel] = 1; + break; + case kOff: + ProgramInterface.relayChannels[channel] = 0; + break; + case kOn: + ProgramInterface.relayChannels[channel] = 1; + break; + case kReverse: + ProgramInterface.relayChannels[channel] = -1; + break; + } + } + +} diff --git a/src/main/java/com/team766/hal/simulator/RobotMain.java b/src/main/java/com/team766/hal/simulator/RobotMain.java new file mode 100755 index 00000000..1a64e9e3 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/RobotMain.java @@ -0,0 +1,123 @@ +package com.team766.hal.simulator; + +import java.io.IOException; + +import com.team766.config.ConfigFileReader; +import com.team766.framework.Scheduler; +import com.team766.hal.GenericRobotMain; +import com.team766.hal.RobotProvider; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.simulator.Program; +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.Simulator; + +public class RobotMain { + static enum Mode { + MaroonSim, + VrConnector, + } + + private GenericRobotMain robot; + private Runnable simulator; + + public RobotMain(Mode mode) { + try { + // TODO: update this to come from deploy directory? + ConfigFileReader.instance = new ConfigFileReader("simConfig.txt"); + RobotProvider.instance = new SimulationRobotProvider(); + + Scheduler.getInstance().reset(); + + robot = new GenericRobotMain(); + + robot.robotInit(); + + ProgramInterface.program = new Program() { + ProgramInterface.RobotMode prevRobotMode = null; + + @Override + public void step() { + switch (ProgramInterface.robotMode) { + case DISABLED: + if (prevRobotMode != ProgramInterface.RobotMode.DISABLED) { + robot.disabledInit(); + prevRobotMode = ProgramInterface.RobotMode.DISABLED; + } + robot.disabledPeriodic(); + Scheduler.getInstance().run(); + break; + case AUTON: + if (prevRobotMode != ProgramInterface.RobotMode.AUTON) { + robot.autonomousInit(); + prevRobotMode = ProgramInterface.RobotMode.AUTON; + } + robot.autonomousPeriodic(); + Scheduler.getInstance().run(); + break; + case TELEOP: + if (prevRobotMode != ProgramInterface.RobotMode.TELEOP) { + robot.teleopInit(); + prevRobotMode = ProgramInterface.RobotMode.TELEOP; + } + robot.teleopPeriodic(); + Scheduler.getInstance().run(); + break; + } + } + + @Override + public void reset() { + robot.resetAutonomousMode("simulation reset"); + } + }; + } catch (Exception exc) { + exc.printStackTrace(); + LoggerExceptionUtils.logException(exc); + } + + switch (mode) { + case MaroonSim: + simulator = new Simulator(); + break; + case VrConnector: + ProgramInterface.robotMode = ProgramInterface.RobotMode.DISABLED; + try { + simulator = new VrConnector(); + } catch (IOException ex) { + throw new RuntimeException("Error initializing communication with 3d Simulator", ex); + } + break; + } + + } + + public void run(){ + try { + simulator.run(); + } catch (Exception exc) { + exc.printStackTrace(); + LoggerExceptionUtils.logException(exc); + } + } + + public static void main(String[] args) { + if (args.length != 1) { + System.err.println("Needs -maroon_sim or -vr_connector"); + System.exit(1); + } + Mode mode; + switch (args[0]) { + case "-maroon_sim": + mode = Mode.MaroonSim; + break; + case "-vr_connector": + mode = Mode.VrConnector; + break; + default: + System.err.println("Needs -maroon_sim or -vr_connector"); + System.exit(1); + return; + } + new RobotMain(mode).run(); + } +} diff --git a/src/main/java/com/team766/hal/simulator/SimMotorController.java b/src/main/java/com/team766/hal/simulator/SimMotorController.java new file mode 100755 index 00000000..4ca0fc8e --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/SimMotorController.java @@ -0,0 +1,54 @@ +package com.team766.hal.simulator; + +import com.team766.hal.ControlInputReader; +import com.team766.hal.BasicMotorController; +import com.team766.hal.LocalMotorController; +import com.team766.simulator.ProgramInterface; + +public class SimMotorController extends LocalMotorController { + public SimMotorController(String configPrefix, int address) { + this(configPrefix, ProgramInterface.canMotorControllerChannels[address]); + } + + SimMotorController(String configPrefix, ProgramInterface.CANMotorControllerCommunication channel) { + super(configPrefix, new SimBasicMotorController(channel), new ControlInputReader() { + @Override + public double getPosition() { + return channel.status.sensorPosition; + } + + @Override + public double getRate() { + return channel.status.sensorVelocity; + } + }); + } +} + +class SimBasicMotorController implements BasicMotorController { + private final ProgramInterface.CANMotorControllerCommunication channel; + + public SimBasicMotorController(int address) { + this(ProgramInterface.canMotorControllerChannels[address]); + } + + public SimBasicMotorController(ProgramInterface.CANMotorControllerCommunication channel) { + this.channel = channel; + } + + @Override + public double get() { + return channel.command.output; + } + + @Override + public void set(double power) { + power = Math.min(Math.max(-1, power), 1); + channel.command.output = power; + channel.command.controlMode = + ProgramInterface.CANMotorControllerCommand.ControlMode.PercentOutput; + } + + @Override + public void restoreFactoryDefault() {} +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/simulator/SimulationClock.java b/src/main/java/com/team766/hal/simulator/SimulationClock.java new file mode 100644 index 00000000..ffb9c4be --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/SimulationClock.java @@ -0,0 +1,15 @@ +package com.team766.hal.simulator; + +import com.team766.hal.Clock; +import com.team766.simulator.ProgramInterface; + +public class SimulationClock implements Clock { + + public static final SimulationClock instance = new SimulationClock(); + + @Override + public double getTime() { + return ProgramInterface.simulationTime; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java new file mode 100755 index 00000000..7972440a --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java @@ -0,0 +1,120 @@ +package com.team766.hal.simulator; + +import com.team766.hal.AnalogInputReader; +import com.team766.hal.CameraInterface; +import com.team766.hal.CameraReader; +import com.team766.hal.Clock; +import com.team766.hal.ControlInputReader; +import com.team766.hal.DigitalInputReader; +import com.team766.hal.EncoderReader; +import com.team766.hal.GyroReader; +import com.team766.hal.JoystickReader; +import com.team766.hal.LocalMotorController; +import com.team766.hal.PositionReader; +import com.team766.hal.RelayOutput; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.MotorController; +import com.team766.simulator.ProgramInterface; + +public class SimulationRobotProvider extends RobotProvider{ + + private MotorController[] motors = new MotorController[100]; + private int m_dsUpdateNumber = 0; + + @Override + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + if(motors[index] == null) { + if (localSensor != null) { + motors[index] = new LocalMotorController(configPrefix, new SimBasicMotorController(index), localSensor); + } else { + motors[index] = new SimMotorController(configPrefix, index); + } + } + return motors[index]; + } + + @Override + public EncoderReader getEncoder(int index1, int index2) { + if(encoders[index1] == null) + encoders[index1] = new Encoder(index1, index2); + return encoders[index1]; + } + + @Override + public SolenoidController getSolenoid(int index) { + if(solenoids[index] == null) + solenoids[index] = new Solenoid(index); + return solenoids[index]; + } + + @Override + public GyroReader getGyro(int index) { + if(gyros[0] == null) + gyros[0] = new Gyro(); + return gyros[0]; + } + + @Override + public CameraReader getCamera(String id, String value) { + if(!cams.containsKey(id)) + cams.put(id, new Camera()); + return cams.get(id); + } + + @Override + public JoystickReader getJoystick(int index) { + return ProgramInterface.joystickChannels[index]; + } + + @Override + public DigitalInputReader getDigitalInput(int index) { + if(digInputs[index] == null) + digInputs[index] = new DigitalInput(index); + return digInputs[index]; + } + + @Override + public CameraInterface getCamServer() { + return null; + } + + @Override + public AnalogInputReader getAnalogInput(int index) { + if(angInputs[index] == null) + angInputs[index] = new AnalogInput(index); + return angInputs[index]; + } + + public RelayOutput getRelay(int index) { + if(relays[index] == null) + relays[index] = new Relay(index); + return relays[index]; + } + + @Override + public PositionReader getPositionSensor() { + if (positionSensor == null) + positionSensor = new PositionSensor(); + return positionSensor; + } + + @Override + public Clock getClock() { + return SimulationClock.instance; + } + + @Override + public boolean hasNewDriverStationData() { + int newUpdateNumber = ProgramInterface.driverStationUpdateNumber; + boolean result = m_dsUpdateNumber != newUpdateNumber; + m_dsUpdateNumber = newUpdateNumber; + return result; + } + + @Override + public double getBatteryVoltage() { + // TODO: The simulator currently doesn't include a simulation of electrical load. + return 12.0; + } +} diff --git a/src/main/java/com/team766/hal/simulator/Solenoid.java b/src/main/java/com/team766/hal/simulator/Solenoid.java new file mode 100755 index 00000000..cdd2aec9 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/Solenoid.java @@ -0,0 +1,22 @@ +package com.team766.hal.simulator; + +import com.team766.hal.SolenoidController; +import com.team766.simulator.ProgramInterface; + +public class Solenoid implements SolenoidController{ + + private int channel; + + public Solenoid(int channel){ + this.channel = channel; + } + + public void set(boolean on) { + ProgramInterface.solenoidChannels[channel] = on; + } + + public boolean get() { + return ProgramInterface.solenoidChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/hal/simulator/VrConnector.java b/src/main/java/com/team766/hal/simulator/VrConnector.java new file mode 100644 index 00000000..25f6d5b0 --- /dev/null +++ b/src/main/java/com/team766/hal/simulator/VrConnector.java @@ -0,0 +1,339 @@ +package com.team766.hal.simulator; + +import static com.team766.math.Math.normalizeAngleDegrees; + +import java.io.IOException; +import java.net.InetAddress; +import java.net.InetSocketAddress; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.nio.channels.DatagramChannel; +import java.nio.channels.SelectionKey; +import java.nio.channels.Selector; +import java.util.Arrays; +import java.util.List; +import java.util.Map; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.simulator.ProgramInterface; + +public class VrConnector implements Runnable { + private static class PortMapping { + public final int messageDataIndex; + public final int robotPortIndex; + + public PortMapping(int messageIndex, int robotIndex) { + this.messageDataIndex = messageIndex; + this.robotPortIndex = robotIndex; + } + } + + private static class CANPortMapping { + public final int canId; + public final int motorCommandMessageDataIndex; + public final int sensorFeedbackMessageDataIndex; + + public CANPortMapping( + int canId, + int motorCommandMessageDataIndex, + int sensorFeedbackMessageDataIndex) { + this.canId = canId; + this.motorCommandMessageDataIndex = motorCommandMessageDataIndex; + this.sensorFeedbackMessageDataIndex = sensorFeedbackMessageDataIndex; + } + } + + /// Command indexes + + private static final int MAX_COMMANDS = 100; + + private static final int RESET_SIM_CHANNEL = 0; + + private static final List PWM_CHANNELS = Arrays.asList( + //new PortMapping(10, 6), // Left motor + //new PortMapping(11, 4), // Right motor + //new PortMapping(14, 1), // Auxiliary / Center motor + //new PortMapping(12, 0) // Intake + ); + private static final List SOLENOID_CHANNELS = Arrays.asList( + new PortMapping(15, 0), // Intake arm + new PortMapping(13, 1) // Catapult launch + ); + private static final List RELAY_CHANNELS = Arrays.asList(); + + private static final List CAN_MOTOR_CHANNELS = Arrays.asList( + new CANPortMapping(6, 10, 10), // Left motor + new CANPortMapping(4, 11, 11), // Right motor + new CANPortMapping(10, 12, 13), // Intake + new CANPortMapping(12, 14, 0), // Aux/center motor + new CANPortMapping(14, 16, 0), // Aux2 motor + + new CANPortMapping(84, 84, 84), // FLD motor + new CANPortMapping(85, 85, 85), // BLD motor + new CANPortMapping(86, 86, 86), // FRD motor + new CANPortMapping(87, 87, 87), // BRD motor + new CANPortMapping(88, 88, 88), // FLS motor + new CANPortMapping(89, 89, 89), // BLS motor + new CANPortMapping(90, 90, 90), // FRS motor + new CANPortMapping(91, 91, 91) // BRS motor + ); + + /// Feedback indexes + + private static final int TIMESTAMP_LSW_CHANNEL = 5; + private static final int TIMESTAMP_MSW_CHANNEL = 4; + + private static final int RESET_COUNTER_CHANNEL = 6; + + private static final int ROBOT_MODE_CHANNEL = 3; + private static final Map ROBOT_MODES = Map.of( + 0, ProgramInterface.RobotMode.DISABLED, + 1, ProgramInterface.RobotMode.AUTON, + 2, ProgramInterface.RobotMode.TELEOP + ); + + private static final int ROBOT_X_CHANNEL = 8; + private static final int ROBOT_Y_CHANNEL = 9; + + private static final List ENCODER_CHANNELS = Arrays.asList( + new PortMapping(10, 0), // Left encoder + new PortMapping(11, 2), // Right encoder + new PortMapping(13, 4) // Mechanism encoder + ); + private static final int GYRO_CHANNEL = 15; + private static final int GYRO_RATE_CHANNEL = 16; + private static final int GYRO_PITCH_CHANNEL = 80; + private static final int GYRO_ROLL_CHANNEL = 81; + private static final List DIGITAL_CHANNELS = Arrays.asList( + new PortMapping(13, 0), // Intake state + new PortMapping(14, 1), // Ball presence + new PortMapping(17, 4), // Line Sensor 1 + new PortMapping(18, 5), // Line Sensor 2 + new PortMapping(19, 6) // Line Sensor 3 + ); + private static final List ANALOG_CHANNELS = Arrays.asList(); + + private static final int NUM_JOYSTICK = 4; + private static final int BASE_AXIS_START = 20; + private static final int BASE_AXES_PER_JOYSTICK = 4; + private static final int ADDITIONAL_AXIS_START = 100; + private static final int ADDITIONAL_AXES_PER_JOYSTICK = 4; + private static final int JOYSTICK_BUTTON_START = 72; + private static final int BUTTONS_PER_JOYSTICK = 20; + + /// Socket Communication + + private static final int commandsPort = 7661; + private static final int feedbackPort = 7662; + private static final int BUF_SZ = 1024; + + private long startTime; + private boolean started = false; + + private Selector selector; + private InetSocketAddress sendAddr; + private ByteBuffer feedback = ByteBuffer.allocate(BUF_SZ); + private ByteBuffer commands = ByteBuffer.allocate(BUF_SZ); + private int resetCounter = 0; + + private int lastResetCounter = 0; + private double lastGyroValue = Double.NaN; + private long[] lastEncoderValue = new long[ProgramInterface.encoderChannels.length]; + private long[] lastCANSensorValue = new long[ProgramInterface.canMotorControllerChannels.length]; + + private int getFeedback(int index) { + return feedback.getInt(index * 4); + } + + private static long assembleLong(int msw, int lsw) { + return ((long)msw << 32) | (lsw & 0xffffffffL); + } + + private void putCommand(int index, int value) { + commands.putInt(index * 4, value); + } + + private void putCommandFloat(int index, double value) { + putCommand(index, (int) (value * 512.0)); + } + + private void putCommandTristate(int index, int value) { + if (value == 0) + putCommand(index, 0); + else if (value > 0) + putCommand(index, 511); + else + putCommand(index, -512); + } + + private void putCommandBool(int index, boolean value) { + putCommand(index, value ? 511 : -512); + } + + public VrConnector() throws IOException { + selector = Selector.open(); + DatagramChannel channel = DatagramChannel.open(); + InetSocketAddress receiveAddr = new InetSocketAddress(feedbackPort); + channel.bind(receiveAddr); + sendAddr = new InetSocketAddress(InetAddress.getLoopbackAddress(), commandsPort); + channel.configureBlocking(false); + channel.register(selector, SelectionKey.OP_READ); + commands.limit(MAX_COMMANDS * 4); + commands.order(ByteOrder.LITTLE_ENDIAN); + feedback.order(ByteOrder.LITTLE_ENDIAN); + startTime = System.currentTimeMillis(); + } + + private boolean process() throws IOException { + for (PortMapping m : PWM_CHANNELS) { + putCommandFloat(m.messageDataIndex, ProgramInterface.pwmChannels[m.robotPortIndex]); + } + for (PortMapping m : SOLENOID_CHANNELS) { + putCommandBool(m.messageDataIndex, ProgramInterface.solenoidChannels[m.robotPortIndex]); + } + for (PortMapping m : RELAY_CHANNELS) { + putCommandTristate(m.messageDataIndex, ProgramInterface.relayChannels[m.robotPortIndex]); + } + for (CANPortMapping m : CAN_MOTOR_CHANNELS) { + putCommandFloat( + m.motorCommandMessageDataIndex, + ProgramInterface.canMotorControllerChannels[m.canId].command.output); + } + + selector.selectedKeys().clear(); + selector.select(); + boolean newData = false; + for (SelectionKey key : selector.selectedKeys()) { + if (!key.isValid()) { + continue; + } + + DatagramChannel chan = (DatagramChannel) key.channel(); + if (key.isReadable()) { + feedback.clear(); + chan.receive(feedback); + newData = true; + key.interestOps(SelectionKey.OP_WRITE); + } + if (key.isWritable()) { + if (started) { + chan.send(commands.duplicate(), sendAddr); + putCommand(RESET_SIM_CHANNEL, 0); + } + key.interestOps(SelectionKey.OP_READ); + } + } + + if (newData) { + double prevSimTime = ProgramInterface.simulationTime; + // Time is sent in milliseconds + ProgramInterface.simulationTime = assembleLong( + getFeedback(TIMESTAMP_MSW_CHANNEL), getFeedback(TIMESTAMP_LSW_CHANNEL)) * 0.001; + + resetCounter = getFeedback(RESET_COUNTER_CHANNEL); + + ProgramInterface.robotMode = ROBOT_MODES.get(getFeedback(ROBOT_MODE_CHANNEL)); + + final double gyroValue = getFeedback(GYRO_CHANNEL) / 10.0; + if (Double.isNaN(lastGyroValue)) { + lastGyroValue = gyroValue; + } + ProgramInterface.gyro.angle += gyroValue - lastGyroValue; + lastGyroValue = gyroValue; + + ProgramInterface.robotPosition.x = getFeedback(ROBOT_X_CHANNEL) / 1000.0; + ProgramInterface.robotPosition.y = getFeedback(ROBOT_Y_CHANNEL) / 1000.0; + ProgramInterface.robotPosition.heading = gyroValue; + + ProgramInterface.gyro.rate = getFeedback(GYRO_RATE_CHANNEL) / 100.0; + ProgramInterface.gyro.pitch = normalizeAngleDegrees(getFeedback(GYRO_PITCH_CHANNEL) / 10.0); + ProgramInterface.gyro.roll = normalizeAngleDegrees(getFeedback(GYRO_ROLL_CHANNEL) / 10.0); + + for (PortMapping m : ENCODER_CHANNELS) { + final long value = getFeedback(m.messageDataIndex); + final long delta = value - lastEncoderValue[m.robotPortIndex]; + lastEncoderValue[m.robotPortIndex] = value; + + ProgramInterface.encoderChannels[m.robotPortIndex].distance += delta; + if (ProgramInterface.simulationTime > prevSimTime) { + ProgramInterface.encoderChannels[m.robotPortIndex].rate = delta / (ProgramInterface.simulationTime - prevSimTime); + } + } + for (CANPortMapping m : CAN_MOTOR_CHANNELS) { + var status = ProgramInterface.canMotorControllerChannels[m.canId].status; + + long value = getFeedback(m.sensorFeedbackMessageDataIndex); + long delta = value - lastCANSensorValue[m.canId]; + lastCANSensorValue[m.canId] = value; + + status.sensorPosition += delta; + if (ProgramInterface.simulationTime > prevSimTime) { + status.sensorVelocity = delta / (ProgramInterface.simulationTime - prevSimTime); + } + } + for (PortMapping m : DIGITAL_CHANNELS) { + ProgramInterface.digitalChannels[m.robotPortIndex] = getFeedback(m.messageDataIndex) > 0; + } + for (PortMapping m : ANALOG_CHANNELS) { + ProgramInterface.analogChannels[m.robotPortIndex] = getFeedback(m.messageDataIndex) * 5.0 / 1024.0; + } + for (int j = 0; j < NUM_JOYSTICK; ++j) { + for (int a = 0; a < BASE_AXES_PER_JOYSTICK; ++a) { + ProgramInterface.joystickChannels[j].setAxisValue(a, getFeedback(j * BASE_AXES_PER_JOYSTICK + a + BASE_AXIS_START) / 100.0); + } + for (int a = 0; a < ADDITIONAL_AXES_PER_JOYSTICK; ++a) { + ProgramInterface.joystickChannels[j].setAxisValue(a + BASE_AXES_PER_JOYSTICK, getFeedback(j * ADDITIONAL_AXES_PER_JOYSTICK + a + ADDITIONAL_AXIS_START) / 100.0); + } + int denseButtonState = getFeedback(j + JOYSTICK_BUTTON_START); + for (int b = 0; b < BUTTONS_PER_JOYSTICK; ++b) { + ProgramInterface.joystickChannels[j].setButton(b + 1, ((denseButtonState >> b) & 1) != 0); + } + } + + ++ProgramInterface.driverStationUpdateNumber; + } + + return newData; + } + + public void run() { + while (true) { + boolean newData = false; + try { + newData = process(); + } catch (Exception e) { + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + try { + Thread.sleep(10); + } catch (InterruptedException e1) {} + } + if (ProgramInterface.simulationTime == 0) { + // Wait for a connection to the simulator before starting to run the robot code. + startTime = System.currentTimeMillis(); + continue; + } + if (resetCounter != lastResetCounter) { + lastResetCounter = resetCounter; + ProgramInterface.program.reset(); + } + if (!newData) { + continue; + } + if (!started) { + // When the simulator has already been running, we seem to need to allow the socket + // service loop to run for a bit to allow buffers in the sockets that communicate + // with the simulator to flush, otherwise the messages queue up which results in a + // significant control latency. + if (System.currentTimeMillis() - startTime > 1000) { + System.out.println("Starting simulation"); + started = true; + } else { + continue; + } + } + if (ProgramInterface.program != null) { + ProgramInterface.program.step(); + } + } + } +} diff --git a/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java b/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java new file mode 100755 index 00000000..cf71649b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java @@ -0,0 +1,26 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.GyroReader; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; +import edu.wpi.first.wpilibj.SPI; + +public class ADXRS450_Gyro extends edu.wpi.first.wpilibj.ADXRS450_Gyro implements GyroReader { + public ADXRS450_Gyro(SPI.Port port) { + super(port); + if (!isConnected()) { + Logger.get(Category.HAL).logData(Severity.ERROR, "ADXRS450 Gyro is not connected!"); + } else { + Logger.get(Category.HAL).logData(Severity.INFO, "ADXRS450 Gyro is connected"); + } + } + + public double getPitch() { + return 0.0; + } + + public double getRoll() { + return 0.0; + } +} diff --git a/src/main/java/com/team766/hal/wpilib/AnalogGyro.java b/src/main/java/com/team766/hal/wpilib/AnalogGyro.java new file mode 100755 index 00000000..7417cf86 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/AnalogGyro.java @@ -0,0 +1,17 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.GyroReader; + +public class AnalogGyro extends edu.wpi.first.wpilibj.AnalogGyro implements GyroReader { + public AnalogGyro(int channel) { + super(channel); + } + + public double getPitch() { + return 0.0; + } + + public double getRoll() { + return 0.0; + } +} diff --git a/src/main/java/com/team766/hal/wpilib/AnalogInput.java b/src/main/java/com/team766/hal/wpilib/AnalogInput.java new file mode 100755 index 00000000..eca6ae4a --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/AnalogInput.java @@ -0,0 +1,9 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.AnalogInputReader; + +public class AnalogInput extends edu.wpi.first.wpilibj.AnalogInput implements AnalogInputReader { + public AnalogInput(int channel) { + super(channel); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java b/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java new file mode 100644 index 00000000..b33b2736 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java @@ -0,0 +1,30 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.ErrorCode; +import com.team766.hal.MotorControllerCommandFailedException; +import com.team766.logging.LoggerExceptionUtils; + +class BaseCTREMotorController { + + protected static final int TIMEOUT_MS = 20; + + protected static enum ExceptionTarget { + THROW, + LOG, + } + + protected static void errorCodeToException(ExceptionTarget throwEx, ErrorCode err) { + if (err == ErrorCode.OK) { + return; + } + var ex = new MotorControllerCommandFailedException(err.toString()); + switch (throwEx) { + case THROW: + throw ex; + case LOG: + LoggerExceptionUtils.logException(ex); + break; + } + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java new file mode 100644 index 00000000..4825f211 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java @@ -0,0 +1,232 @@ +package com.team766.hal.wpilib; + +import java.util.function.Function; +import java.util.function.Supplier; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.revrobotics.CANSparkMax; +import com.revrobotics.REVLibError; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.SparkMaxAnalogSensor; +import com.team766.hal.MotorController; +import com.team766.hal.MotorControllerCommandFailedException; +import com.team766.logging.LoggerExceptionUtils; + +public class CANSparkMaxMotorController extends CANSparkMax implements MotorController { + + private Supplier sensorPositionSupplier; + private Supplier sensorVelocitySupplier; + private Function sensorPositionSetter; + private Function sensorInvertedSetter; + private boolean sensorInverted = false; + + public CANSparkMaxMotorController(int deviceId) { + super(deviceId, MotorType.kBrushless); + + // Set default feedback device. This ensures that our implementations of + // getSensorPosition/getSensorVelocity return values that match what the + // device's PID controller is using. + setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + } + + private static enum ExceptionTarget { + THROW, + LOG, + } + + private static void revErrorToException(ExceptionTarget throwEx, REVLibError err) { + if (err == REVLibError.kOk) { + return; + } + var ex = new MotorControllerCommandFailedException(err.toString()); + switch (throwEx) { + case THROW: + throw ex; + case LOG: + LoggerExceptionUtils.logException(ex); + break; + } + } + + @Override + public double getSensorPosition() { + return sensorPositionSupplier.get(); + } + + @Override + public double getSensorVelocity() { + return sensorVelocitySupplier.get(); + } + + @Override + public void set(ControlMode mode, double value) { + switch (mode) { + case Current: + getPIDController().setReference(value, CANSparkMax.ControlType.kCurrent); + break; + case Disabled: + disable(); + break; + case Follower: + throw new IllegalArgumentException("Use follow() method instead"); + case MotionMagic: + throw new IllegalArgumentException("SparkMax does not support MotionMagic"); + case MotionProfile: + throw new IllegalArgumentException("SparkMax does not support MotionProfile"); + case MotionProfileArc: + throw new IllegalArgumentException("SparkMax does not support MotionProfileArc"); + case PercentOutput: + getPIDController().setReference(value, CANSparkMax.ControlType.kDutyCycle); + break; + case Position: + getPIDController().setReference(value, CANSparkMax.ControlType.kPosition); + break; + case Velocity: + getPIDController().setReference(value, CANSparkMax.ControlType.kVelocity); + break; + case Voltage: + getPIDController().setReference(value, CANSparkMax.ControlType.kVoltage); + default: + throw new IllegalArgumentException("Unsupported control mode " + mode); + } + } + + @Override + public void setSensorPosition(double position) { + revErrorToException(ExceptionTarget.THROW, sensorPositionSetter.apply(position)); + } + + @Override + public void follow(MotorController leader) { + try { + revErrorToException(ExceptionTarget.LOG, super.follow((CANSparkMax)leader)); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Spark Max can only follow another Spark Max", ex)); + } + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + switch (neutralMode) { + case Brake: + revErrorToException(ExceptionTarget.LOG, setIdleMode(IdleMode.kBrake)); + case Coast: + revErrorToException(ExceptionTarget.LOG, setIdleMode(IdleMode.kCoast)); + default: + LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported neutral mode " + neutralMode)); + } + } + + @Override + public void setP(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setP(value)); + } + + @Override + public void setI(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setI(value)); + } + + @Override + public void setD(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setD(value)); + } + + @Override + public void setFF(double value) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setFF(value)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + switch (feedbackDevice) { + case Analog: { + SparkMaxAnalogSensor analog = getAnalog(SparkMaxAnalogSensor.Mode.kAbsolute); + revErrorToException(ExceptionTarget.LOG, analog.setInverted(sensorInverted)); + sensorPositionSupplier = analog::getPosition; + sensorVelocitySupplier = analog::getVelocity; + sensorPositionSetter = (pos) -> REVLibError.kOk; + sensorInvertedSetter = analog::setInverted; + revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(analog)); + return; + } + case CTRE_MagEncoder_Absolute: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); + case CTRE_MagEncoder_Relative: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); + case IntegratedSensor: { + RelativeEncoder encoder = getEncoder(); + // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the integrated sensor returns an error. + // revErrorToException(ExceptionTarget.LOG, encoder.setInverted(sensorInverted)); + sensorPositionSupplier = encoder::getPosition; + sensorVelocitySupplier = encoder::getVelocity; + sensorPositionSetter = encoder::setPosition; + // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the integrated sensor returns an error. + // sensorInvertedSetter = encoder::setInverted; + sensorInvertedSetter = (inverted) -> REVLibError.kOk; + revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(encoder)); + return; + } + case None: + return; + case PulseWidthEncodedPosition: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support PWM sensors")); + case QuadEncoder: { + // TODO: should we pass a real counts-per-rev scale here? + RelativeEncoder encoder = getAlternateEncoder(1); + revErrorToException(ExceptionTarget.LOG, encoder.setInverted(sensorInverted)); + sensorPositionSupplier = encoder::getPosition; + sensorVelocitySupplier = encoder::getVelocity; + sensorPositionSetter = encoder::setPosition; + sensorInvertedSetter = encoder::setInverted; + revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(encoder)); + return; + } + case RemoteSensor0: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support remote sensors")); + case RemoteSensor1: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support remote sensors")); + case SensorDifference: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SensorDifference")); + case SensorSum: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SensorSum")); + case SoftwareEmulatedSensor: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SoftwareEmulatedSensor")); + case Tachometer: + LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support Tachometer")); + default: + LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported sensor type " + feedbackDevice)); + } + } + + @Override + public void setSensorInverted(boolean inverted) { + sensorInverted = inverted; + revErrorToException(ExceptionTarget.LOG, sensorInvertedSetter.apply(inverted)); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + revErrorToException(ExceptionTarget.LOG, getPIDController().setOutputRange(minOutput, maxOutput)); + } + + public void setCurrentLimit(double ampsLimit) { + revErrorToException(ExceptionTarget.LOG, setSmartCurrentLimit((int)ampsLimit)); + } + + @Override + public void restoreFactoryDefault() { + revErrorToException(ExceptionTarget.LOG, restoreFactoryDefaults()); + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + revErrorToException(ExceptionTarget.LOG, setOpenLoopRampRate(secondsFromNeutralToFull)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + revErrorToException(ExceptionTarget.LOG, setClosedLoopRampRate(secondsFromNeutralToFull)); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java new file mode 100644 index 00000000..ec30728a --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java @@ -0,0 +1,190 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.IMotorController; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class CANTalonFxMotorController extends BaseCTREMotorController implements MotorController { + + private WPI_TalonFX m_device; + private double m_feedForward = 0.0; + + public CANTalonFxMotorController(int deviceNumber) { + m_device = new WPI_TalonFX(deviceNumber); + } + + @Override + public void set(ControlMode mode, double value) { + com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; + boolean useFourTermSet = true; + switch (mode) { + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + } + if (ctre_mode == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "CAN ControlMode is not translatable: " + mode); + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + } + if (useFourTermSet) { + m_device.set(ctre_mode, value, DemandType.ArbitraryFeedForward, m_feedForward); + } else { + m_device.set(ctre_mode, value); + } + } + + @Override + public void stopMotor() { + m_device.set(com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput, 0); + } + + @Override + public double getSensorPosition() { + return m_device.getSelectedSensorPosition(0); + } + + @Override + public double getSensorVelocity() { + // Sensor velocity is returned in units per 100ms. + return m_device.getSelectedSensorVelocity(0) * 10.0; + } + + @Override + public void setSensorPosition(double position){ + errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 0)); + } + + @Override + public void follow(MotorController leader) { + try { + m_device.follow((IMotorController)leader); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Talon can only follow another CTRE motor controller", ex)); + } + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setFF(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); + } + + @Override + public void setP(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value)); + } + + @Override + public void setI(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value)); + } + + @Override + public void setD(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + } + + @Override + public void setSensorInverted(boolean inverted) { + m_device.setSensorPhase(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSupplyCurrentLimit( + new SupplyCurrentLimitConfiguration(true, ampsLimit, 0, 0.01))); + } + + @Override + public void restoreFactoryDefault() { + errorCodeToException(ExceptionTarget.LOG, m_device.configFactoryDefault()); + } + + @Override + public double get() { + return m_device.get(); + } + + @Override + public void set(double power) { + m_device.set(power); + } + + @Override + public void setInverted(boolean isInverted) { + m_device.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return m_device.getInverted(); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + m_device.setNeutralMode(neutralMode); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java new file mode 100644 index 00000000..7eae784b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java @@ -0,0 +1,191 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.IMotorController; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class CANTalonMotorController extends BaseCTREMotorController implements MotorController { + + private WPI_TalonSRX m_device; + private double m_feedForward = 0.0; + + public CANTalonMotorController(int deviceNumber) { + m_device = new WPI_TalonSRX(deviceNumber); + } + + @Override + public void set(ControlMode mode, double value) { + com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; + boolean useFourTermSet = true; + switch (mode) { + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + } + if (ctre_mode == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "CAN ControlMode is not translatable: " + mode); + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + } + if (useFourTermSet) { + m_device.set(ctre_mode, value, DemandType.ArbitraryFeedForward, m_feedForward); + } else { + m_device.set(ctre_mode, value); + } + } + + @Override + public void stopMotor() { + m_device.set(com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput, 0); + } + + @Override + public double getSensorPosition() { + return m_device.getSelectedSensorPosition(0); + } + + @Override + public double getSensorVelocity() { + // Sensor velocity is returned in units per 100ms. + return m_device.getSelectedSensorVelocity(0) * 10.0; + } + + @Override + public void setSensorPosition(double position){ + errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 0)); + } + + @Override + public void follow(MotorController leader) { + try { + m_device.follow((IMotorController)leader); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Talon can only follow another CTRE motor controller", ex)); + } + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setFF(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); + } + + @Override + public void setP(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value)); + } + + @Override + public void setI(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value)); + } + + @Override + public void setD(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + } + + @Override + public void setSensorInverted(boolean inverted) { + m_device.setSensorPhase(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakCurrentLimit(0)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakCurrentDuration(10)); + errorCodeToException(ExceptionTarget.LOG, m_device.configContinuousCurrentLimit((int)ampsLimit)); + m_device.enableCurrentLimit(true); + } + + @Override + public void restoreFactoryDefault() { + errorCodeToException(ExceptionTarget.LOG, m_device.configFactoryDefault()); + } + + @Override + public double get() { + return m_device.get(); + } + + @Override + public void set(double power) { + m_device.set(power); + } + + @Override + public void setInverted(boolean isInverted) { + m_device.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return m_device.getInverted(); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + m_device.setNeutralMode(neutralMode); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java b/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java new file mode 100644 index 00000000..1dffa99b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java @@ -0,0 +1,188 @@ +package com.team766.hal.wpilib; + +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.motorcontrol.IMotorController; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +public class CANVictorMotorController extends BaseCTREMotorController implements MotorController { + + private WPI_VictorSPX m_device; + private double m_feedForward = 0.0; + + public CANVictorMotorController(int deviceNumber) { + m_device = new WPI_VictorSPX(deviceNumber); + } + + @Override + public void set(ControlMode mode, double value) { + com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; + boolean useFourTermSet = true; + switch (mode) { + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + } + if (ctre_mode == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "CAN ControlMode is not translatable: " + mode); + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + } + if (useFourTermSet) { + m_device.set(ctre_mode, value, DemandType.ArbitraryFeedForward, m_feedForward); + } else { + m_device.set(ctre_mode, value); + } + } + + @Override + public void stopMotor() { + m_device.set(com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput, 0); + } + + @Override + public double getSensorPosition() { + return m_device.getSelectedSensorPosition(0); + } + + @Override + public double getSensorVelocity() { + // Sensor velocity is returned in units per 100ms. + return m_device.getSelectedSensorVelocity(0) * 10.0; + } + + @Override + public void setSensorPosition(double position){ + errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 20)); + } + + @Override + public void follow(MotorController leader) { + try { + m_device.follow((IMotorController)leader); + } catch (ClassCastException ex) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Victor can only follow another CTRE motor controller", ex)); + } + } + + @Override + public void setOpenLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setClosedLoopRamp(double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + } + + @Override + public void setFF(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); + } + + @Override + public double get() { + return m_device.get(); + } + + @Override + public void set(double power) { + m_device.set(power); + } + + @Override + public void setInverted(boolean isInverted) { + m_device.setInverted(isInverted); + } + + @Override + public boolean getInverted() { + return m_device.getInverted(); + } + + @Override + public void setNeutralMode(NeutralMode neutralMode) { + m_device.setNeutralMode(neutralMode); + } + + @Override + public void setP(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value, TIMEOUT_MS)); + } + + @Override + public void setI(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value, TIMEOUT_MS)); + } + + @Override + public void setD(double value) { + errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value, TIMEOUT_MS)); + } + + @Override + public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + } + + @Override + public void setSensorInverted(boolean inverted) { + m_device.setSensorPhase(inverted); + } + + @Override + public void setOutputRange(double minOutput, double maxOutput) { + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); + errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); + } + + @Override + public void setCurrentLimit(double ampsLimit) { + LoggerExceptionUtils.logException( + new UnsupportedOperationException("VictorSPX does not support current limiting")); + } + + @Override + public void restoreFactoryDefault() { + errorCodeToException(ExceptionTarget.LOG, m_device.configFactoryDefault()); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/hal/wpilib/CameraInterface.java b/src/main/java/com/team766/hal/wpilib/CameraInterface.java new file mode 100755 index 00000000..4f5122c5 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/CameraInterface.java @@ -0,0 +1,39 @@ +package com.team766.hal.wpilib; + +import edu.wpi.first.cscore.CvSource; +import edu.wpi.first.cscore.VideoSource; +import edu.wpi.first.cameraserver.CameraServer; + +import org.opencv.core.Mat; + +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public class CameraInterface implements com.team766.hal.CameraInterface { + + private CvSource vidSource; + + @Override + public void startAutomaticCapture() { + try{ + CameraServer.startAutomaticCapture(VideoSource.enumerateSources()[0]); + } catch(Exception e){ + Logger.get(Category.CAMERA).logRaw(Severity.ERROR, e.toString()); + } + } + + @Override + public void getFrame(Mat img) { + CameraServer.getVideo().grabFrame(img); + } + + @Override + public void putFrame(Mat img){ + if(vidSource == null){ + vidSource = CameraServer.putVideo("VisionTracking", img.width(), img.height()); + } + + vidSource.putFrame(img); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/DigitalInput.java b/src/main/java/com/team766/hal/wpilib/DigitalInput.java new file mode 100755 index 00000000..d9abc338 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/DigitalInput.java @@ -0,0 +1,9 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.DigitalInputReader; + +public class DigitalInput extends edu.wpi.first.wpilibj.DigitalInput implements DigitalInputReader { + public DigitalInput(int channel) { + super(channel); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Encoder.java b/src/main/java/com/team766/hal/wpilib/Encoder.java new file mode 100755 index 00000000..509ddee2 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Encoder.java @@ -0,0 +1,9 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.EncoderReader; + +public class Encoder extends edu.wpi.first.wpilibj.Encoder implements EncoderReader { + public Encoder(int channelA, int channelB) { + super(channelA, channelB); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Joystick.java b/src/main/java/com/team766/hal/wpilib/Joystick.java new file mode 100755 index 00000000..b5a267f2 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Joystick.java @@ -0,0 +1,29 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.JoystickReader; + +public class Joystick extends edu.wpi.first.wpilibj.Joystick implements JoystickReader { + public Joystick(int port) { + super(port); + } + + @Override + public double getAxis(int axis) { + return getRawAxis(axis); + } + + @Override + public boolean getButton(int button) { + return getRawButton(button); + } + + @Override + public boolean getButtonPressed(int button) { + return getRawButtonPressed(button); + } + + @Override + public boolean getButtonReleased(int button) { + return getRawButtonReleased(button); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/NavXGyro.java b/src/main/java/com/team766/hal/wpilib/NavXGyro.java new file mode 100644 index 00000000..65430501 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/NavXGyro.java @@ -0,0 +1,55 @@ +package com.team766.hal.wpilib; + +import com.kauailabs.navx.frc.AHRS; +import com.team766.hal.GyroReader; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; +import edu.wpi.first.wpilibj.I2C; + +public class NavXGyro implements GyroReader { + private AHRS m_gyro; + + public NavXGyro(I2C.Port port) { + m_gyro = new AHRS(port); + // NOTE: It takes a bit of time until the gyro reader thread updates + // the connected status, so we can't check it immediately. + // TODO: Replace this with a status indicator + /*if (!m_gyro.isConnected()) { + Logger.get(Category.HAL).logData(Severity.ERROR, "NavX Gyro is not connected!"); + } else { + Logger.get(Category.HAL).logData(Severity.INFO, "NavX Gyro is connected"); + }*/ + } + + @Override + public void calibrate() { + m_gyro.calibrate(); + } + + @Override + public void reset() { + m_gyro.reset(); + } + + @Override + public double getAngle() { + return m_gyro.getAngle(); + } + + @Override + public double getRate() { + return m_gyro.getRate(); + } + + @Override + public double getPitch() { + return m_gyro.getPitch(); + } + + @Override + public double getRoll() { + return m_gyro.getRoll(); + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java b/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java new file mode 100755 index 00000000..553cf741 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java @@ -0,0 +1,16 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.BasicMotorController; + +import edu.wpi.first.wpilibj.motorcontrol.VictorSP; + +public class PWMVictorSP extends VictorSP implements BasicMotorController { + public PWMVictorSP(int channel) { + super(channel); + } + + @Override + public void restoreFactoryDefault() { + // No-op + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Relay.java b/src/main/java/com/team766/hal/wpilib/Relay.java new file mode 100755 index 00000000..7b9fbeec --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Relay.java @@ -0,0 +1,38 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.RelayOutput; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public class Relay extends edu.wpi.first.wpilibj.Relay implements RelayOutput { + public Relay(int channel) { + super(channel); + } + + @Override + public void set(com.team766.hal.RelayOutput.Value value) { + edu.wpi.first.wpilibj.Relay.Value wpi_value = null; + switch (value) { + case kOff: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOff; + break; + case kOn: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOn; + break; + case kForward: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kForward; + break; + case kReverse: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kReverse; + break; + } + if (wpi_value == null) { + Logger.get(Category.HAL).logRaw( + Severity.ERROR, + "Relay value is not translatable: " + value); + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOff; + } + super.set(wpi_value); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/RobotMain.java b/src/main/java/com/team766/hal/wpilib/RobotMain.java new file mode 100755 index 00000000..1459ba6b --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/RobotMain.java @@ -0,0 +1,151 @@ +package com.team766.hal.wpilib; + +import java.io.File; +import java.nio.file.Files; +import java.nio.file.Path; +import java.util.function.Supplier; +import com.team766.config.ConfigFileReader; +import com.team766.framework.Scheduler; +import com.team766.hal.GenericRobotMain; +import com.team766.hal.RobotProvider; +import com.team766.logging.LoggerExceptionUtils; +import edu.wpi.first.wpilibj.Filesystem; +import edu.wpi.first.wpilibj.RobotBase; +import edu.wpi.first.wpilibj.TimedRobot; + +public class RobotMain extends TimedRobot { + // this file, if present, will be a symlink to one of several config files in the deploy directory. + // this allows for the same code to be deployed to multiple physical robots, each with their own + // config file with CAN bus port mappings, etc, with the actual file used for a specific robot + // to be "selected" via this symlink to the actual file. + private final static String SELECTED_CONFIG_FILE = "/home/lvuser/selectedConfig.txt"; + + // if the symlink (above) is not present, back off to this file in the deploy directory. + private final static String DEFAULT_CONFIG_FILE = "configs/defaultRobotConfig.txt"; + + // for backwards compatibility, back off to the previous config file location if the above are not + // found in the deploy directory. + private final static String LEGACY_CONFIG_FILE = "/home/lvuser/robotConfig.txt"; + + private GenericRobotMain robot; + + public static void main(String... args) { + Supplier supplier = new Supplier() { + RobotMain instance; + @Override + public RobotMain get() { + if (instance == null) { + instance = new RobotMain(); + } + return instance; + } + }; + try { + RobotBase.startRobot(supplier); + } catch (Throwable ex) { + ex.printStackTrace(); + LoggerExceptionUtils.logException(ex); + } + } + + public RobotMain() { + super(0.005); + } + + private static String checkForAndReturnPathToConfigFile(String file) { + Path configPath = Filesystem.getDeployDirectory().toPath().resolve(file); + File configFile = configPath.toFile(); + if (configFile.exists()) { + return configFile.getPath(); + } + return null; + } + + @Override + public void robotInit() { + try { + String filename = null; + filename = checkForAndReturnPathToConfigFile(SELECTED_CONFIG_FILE); + + if (filename == null) { + filename = checkForAndReturnPathToConfigFile(DEFAULT_CONFIG_FILE); + } + + if (filename == null) { + filename = LEGACY_CONFIG_FILE; + } + + ConfigFileReader.instance = new ConfigFileReader(filename); + RobotProvider.instance = new WPIRobotProvider(); + robot = new GenericRobotMain(); + + robot.robotInit(); + } catch (Exception e) { + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void disabledInit() { + try{ + robot.disabledInit(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void autonomousInit() { + try{ + robot.autonomousInit(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void teleopInit() { + try{ + robot.teleopInit(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void disabledPeriodic() { + try{ + robot.disabledPeriodic(); + Scheduler.getInstance().run(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void autonomousPeriodic() { + try{ + robot.autonomousPeriodic(); + Scheduler.getInstance().run(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } + + @Override + public void teleopPeriodic() { + try{ + robot.teleopPeriodic(); + Scheduler.getInstance().run(); + }catch (Exception e){ + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + } +} diff --git a/src/main/java/com/team766/hal/wpilib/Solenoid.java b/src/main/java/com/team766/hal/wpilib/Solenoid.java new file mode 100755 index 00000000..e72f4694 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/Solenoid.java @@ -0,0 +1,11 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.SolenoidController; + +import edu.wpi.first.wpilibj.PneumaticsModuleType; + +public class Solenoid extends edu.wpi.first.wpilibj.Solenoid implements SolenoidController { + public Solenoid(int channel) { + super(PneumaticsModuleType.CTREPCM, channel); + } +} diff --git a/src/main/java/com/team766/hal/wpilib/SystemClock.java b/src/main/java/com/team766/hal/wpilib/SystemClock.java new file mode 100644 index 00000000..de5c9d4f --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/SystemClock.java @@ -0,0 +1,12 @@ +package com.team766.hal.wpilib; + +public class SystemClock implements com.team766.hal.Clock { + + public static final SystemClock instance = new SystemClock(); + + @Override + public double getTime() { + return System.currentTimeMillis() * 0.001; + } + +} diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java new file mode 100755 index 00000000..4b8a7301 --- /dev/null +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -0,0 +1,184 @@ +package com.team766.hal.wpilib; + +import com.team766.hal.AnalogInputReader; +import com.team766.hal.CameraInterface; +import com.team766.hal.CameraReader; +import com.team766.hal.Clock; +import com.team766.hal.ControlInputReader; +import com.team766.hal.DigitalInputReader; +import com.team766.hal.EncoderReader; +import com.team766.hal.GyroReader; +import com.team766.hal.JoystickReader; +import com.team766.hal.LocalMotorController; +import com.team766.hal.PositionReader; +import com.team766.hal.RelayOutput; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.MotorController; +import com.team766.hal.mock.MockGyro; +import com.team766.hal.mock.MockPositionSensor; +import com.team766.hal.mock.MockMotorController; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; +import com.team766.logging.Severity; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.PneumaticsControlModule; +import edu.wpi.first.wpilibj.RobotController; +import edu.wpi.first.wpilibj.SPI; + +public class WPIRobotProvider extends RobotProvider { + + private MotorController[][] motors = new MotorController[MotorController.Type.values().length][64]; + + // The presence of this object allows the compressor to run before we've declared any solenoids. + @SuppressWarnings("unused") + private PneumaticsControlModule pcm = new PneumaticsControlModule(); + + @Override + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + if (motors[type.ordinal()][index] != null) { + return motors[type.ordinal()][index]; + } + MotorController motor = null; + switch (type) { + case SparkMax: + try { + motor = new CANSparkMaxMotorController(index); + } catch (Exception ex) { + LoggerExceptionUtils.logException(ex); + motor = new LocalMotorController(configPrefix, new MockMotorController(index), localSensor); + localSensor = null; + } + break; + case TalonSRX: + motor = new CANTalonMotorController(index); + break; + case VictorSPX: + motor = new CANVictorMotorController(index); + break; + case TalonFX: + motor = new CANTalonFxMotorController(index); + break; + case VictorSP: + motor = new LocalMotorController(configPrefix, new PWMVictorSP(index), localSensor); + localSensor = null; + break; + } + if (motor == null) { + LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported motor type " + type)); + motor = new LocalMotorController(configPrefix, new MockMotorController(index), localSensor); + localSensor = null; + } + if (localSensor != null) { + motor = new LocalMotorController(configPrefix, motor, localSensor); + } + motors[type.ordinal()][index] = motor; + return motor; + } + + @Override + public EncoderReader getEncoder(int index1, int index2) { + if(encoders[index1] == null) + encoders[index1] = new Encoder(index1, index2); + return encoders[index1]; + } + + @Override + public SolenoidController getSolenoid(int index) { + if(solenoids[index] == null) + solenoids[index] = new Solenoid(index); + return solenoids[index]; + } + + @Override + //Gyro index values: + // -1 = Spartan Gyro + // 0+ = Analog Gyro on port index + public GyroReader getGyro(int index) { + if(gyros[index + 2] == null){ + if(index < -2) { + Logger.get(Category.CONFIGURATION).logRaw( + Severity.ERROR, + "Invalid gyro port " + index + ". Must be -2, -1, or a non-negative integer" + ); + return new MockGyro(); + } + else if(index == -2) + gyros[index + 2] = new NavXGyro(I2C.Port.kOnboard); + else if(index == -1) + gyros[index + 2] = new ADXRS450_Gyro(SPI.Port.kOnboardCS0); + else + gyros[index + 2] = new AnalogGyro(index); + } + return gyros[index + 2]; + } + + @Override + public CameraReader getCamera(String id, String value) { + System.err.println("Camera support not yet avaible"); + return null; + } + + @Override + public JoystickReader getJoystick(int index) { + if(joysticks[index] == null) + joysticks[index] = new Joystick(index); + return joysticks[index]; + } + + @Override + public CameraInterface getCamServer(){ + return new com.team766.hal.wpilib.CameraInterface(); + } + + @Override + public DigitalInputReader getDigitalInput(int index) { + if (digInputs[index] == null) + digInputs[index] = new DigitalInput(index); + return digInputs[index]; + } + + @Override + public AnalogInputReader getAnalogInput(int index){ + if(angInputs[index] == null) + angInputs[index] = new AnalogInput(index); + return angInputs[index]; + } + + @Override + public RelayOutput getRelay(int index) { + if(relays[index] == null) + relays[index] = new Relay(index); + return relays[index]; + } + + @Override + public PositionReader getPositionSensor() { + if (positionSensor == null) { + positionSensor = new MockPositionSensor(); + Logger.get(Category.CONFIGURATION).logRaw( + Severity.ERROR, + "Position sensor does not exist on real robots. Using mock position sensor instead - it will always return a position of 0" + ); + } + return positionSensor; + } + + @Override + public Clock getClock() { + return SystemClock.instance; + } + + @Override + public boolean hasNewDriverStationData() { + return DriverStation.isNewControlData(); + } + + @Override + public double getBatteryVoltage() { + return RobotController.getBatteryVoltage(); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/library/CircularBuffer.java b/src/main/java/com/team766/library/CircularBuffer.java new file mode 100644 index 00000000..d14c8fb9 --- /dev/null +++ b/src/main/java/com/team766/library/CircularBuffer.java @@ -0,0 +1,72 @@ +package com.team766.library; + +import java.util.AbstractCollection; +import java.util.Iterator; + +public class CircularBuffer extends AbstractCollection { + private Object[] buffer; + private int count = 0; + private int headIndex = 0; + + public CircularBuffer(int bufferLength) { + buffer = new Object[bufferLength]; + } + + @Override + public Iterator iterator() { + return new Iterator() { + int index = 0; + + @Override + public boolean hasNext() { + return index < count; + } + + @SuppressWarnings("unchecked") + @Override + public E next() { + return (E) buffer[(headIndex + index++) % buffer.length]; + } + }; + } + + @SuppressWarnings("unchecked") + public E peek() { + if (count == 0) { + return null; + } + return (E) buffer[headIndex]; + } + + public E poll() { + if (count == 0) { + return null; + } + E element = peek(); + headIndex = (headIndex + 1) % buffer.length; + --count; + return element; + } + + @Override + public boolean add(E element) { + if (count < buffer.length) { + buffer[(headIndex + count) % buffer.length] = element; + ++count; + } else { + buffer[headIndex] = element; + headIndex = (headIndex + 1) % buffer.length; + } + return true; + } + + @Override + public int size() { + return count; + } + + @Override + public void clear() { + count = 0; + } +} diff --git a/src/main/java/com/team766/library/LossyPriorityQueue.java b/src/main/java/com/team766/library/LossyPriorityQueue.java new file mode 100644 index 00000000..5837bf11 --- /dev/null +++ b/src/main/java/com/team766/library/LossyPriorityQueue.java @@ -0,0 +1,61 @@ +package com.team766.library; + +import java.util.Comparator; +import java.util.PriorityQueue; +import java.util.concurrent.locks.Condition; +import java.util.concurrent.locks.Lock; +import java.util.concurrent.locks.ReentrantLock; + +public class LossyPriorityQueue { + private final Lock m_lock = new ReentrantLock(); + private final Condition m_empty = m_lock.newCondition(); + private final Condition m_notEmpty = m_lock.newCondition(); + + private final PriorityQueue m_items; + private final int m_capacity; + + public LossyPriorityQueue(int capacity, Comparator comparator) { + m_capacity = capacity; + m_items = new PriorityQueue(m_capacity, comparator); + } + + public void add(E element) { + m_lock.lock(); + try { + while (m_items.size() > m_capacity - 1) { + m_items.poll(); + } + m_items.add(element); + m_notEmpty.signal(); + } finally { + m_lock.unlock(); + } + } + + public E poll() throws InterruptedException { + m_lock.lock(); + try { + while (m_items.size() == 0) { + m_notEmpty.await(); + } + E element = m_items.poll(); + if (m_items.size() == 0) { + m_empty.signal(); + } + return element; + } finally { + m_lock.unlock(); + } + } + + public void waitForEmpty() throws InterruptedException { + m_lock.lock(); + try { + while (!m_items.isEmpty()) { + m_empty.await(); + } + } finally { + m_lock.unlock(); + } + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/library/RateLimiter.java b/src/main/java/com/team766/library/RateLimiter.java new file mode 100644 index 00000000..371ecd54 --- /dev/null +++ b/src/main/java/com/team766/library/RateLimiter.java @@ -0,0 +1,27 @@ +package com.team766.library; + +import com.team766.hal.RobotProvider; + +public class RateLimiter { + private final double periodSeconds; + private double nextTime = 0; + + public RateLimiter(double periodSeconds) { + this.periodSeconds = periodSeconds; + } + + public boolean next() { + final double now = RobotProvider.getTimeProvider().get(); + if (now > nextTime) { + if (nextTime == 0) { + // Lazy-initialize the first time, because TimeProvider in + // simulation often isn't ready at construction time. + nextTime = now; + } + nextTime += periodSeconds; + return true; + } else { + return false; + } + } +} diff --git a/src/main/java/com/team766/library/SetValueProvider.java b/src/main/java/com/team766/library/SetValueProvider.java new file mode 100644 index 00000000..b751e481 --- /dev/null +++ b/src/main/java/com/team766/library/SetValueProvider.java @@ -0,0 +1,36 @@ +package com.team766.library; + +public class SetValueProvider implements SettableValueProvider { + private E m_value; + private boolean m_hasValue; + + public SetValueProvider() { + m_value = null; + m_hasValue = false; + } + + public SetValueProvider(E value) { + m_value = value; + m_hasValue = true; + } + + @Override + public E get() { + return m_value; + } + + @Override + public boolean hasValue() { + return m_hasValue; + } + + public void set(E value) { + m_value = value; + m_hasValue = true; + } + + public void clear() { + m_value = null; + m_hasValue = false; + } +} diff --git a/src/main/java/com/team766/library/SettableValueProvider.java b/src/main/java/com/team766/library/SettableValueProvider.java new file mode 100644 index 00000000..565ef7cf --- /dev/null +++ b/src/main/java/com/team766/library/SettableValueProvider.java @@ -0,0 +1,7 @@ +package com.team766.library; + +public interface SettableValueProvider extends ValueProvider { + public void set(E value); + + public void clear(); +} \ No newline at end of file diff --git a/src/main/java/com/team766/library/ValueProvider.java b/src/main/java/com/team766/library/ValueProvider.java new file mode 100644 index 00000000..49ffc6a1 --- /dev/null +++ b/src/main/java/com/team766/library/ValueProvider.java @@ -0,0 +1,14 @@ +package com.team766.library; + +public interface ValueProvider { + public E get(); + + public boolean hasValue(); + + default E valueOr(E default_value) { + if (hasValue()) { + return get(); + } + return default_value; + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/LogEntryComparator.java b/src/main/java/com/team766/logging/LogEntryComparator.java new file mode 100644 index 00000000..b4c90ee7 --- /dev/null +++ b/src/main/java/com/team766/logging/LogEntryComparator.java @@ -0,0 +1,30 @@ +package com.team766.logging; + +import java.util.Arrays; +import java.util.Comparator; + +class LogEntryComparator implements Comparator { + // This LogEntry should be ordered after any normal LogEntries. + // It is used to signal to the log writing thread that it should exit. + // We want it to come last in the priority queue so that any pending log + // entries get written before the thread terminates. + public static final LogEntry TERMINATION_SENTINAL = + LogEntry.newBuilder() + .setSeverity(Arrays.stream(Severity.values()).min(Comparator.naturalOrder()).get()) + .setTime(Long.MAX_VALUE) + .build(); + + @Override + public int compare(LogEntry o1, LogEntry o2) { + // Sort by highest severity first + int severityResult = -o1.getSeverity().compareTo(o2.getSeverity()); + if (severityResult != 0) { + return severityResult; + } + // Then sort by earliest time. + // Each Category's logger ensures these are unique. This is important + // because we don't want two different log entries to accidentally + // compare as equal. + return Long.compare(o1.getTime(), o2.getTime()); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/LogEntryRenderer.java b/src/main/java/com/team766/logging/LogEntryRenderer.java new file mode 100644 index 00000000..29c10021 --- /dev/null +++ b/src/main/java/com/team766/logging/LogEntryRenderer.java @@ -0,0 +1,17 @@ +package com.team766.logging; + +public class LogEntryRenderer { + public static String renderLogEntry(LogEntry entry, LogReader reader) { + String message = entry.hasMessageStr() ? entry.getMessageStr() + : reader.getFormatString(entry.getMessageIndex()); + final int argCount = entry.getArgCount(); + if (argCount == 0) { + return message; + } else { + final Object[] args = + entry.getArgList().stream() + .map(SerializationUtils::protoToValue).toArray(); + return String.format(message, args); + } + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/LogReader.java b/src/main/java/com/team766/logging/LogReader.java new file mode 100644 index 00000000..2bfbc05f --- /dev/null +++ b/src/main/java/com/team766/logging/LogReader.java @@ -0,0 +1,51 @@ +package com.team766.logging; + +import java.io.FileInputStream; +import java.io.IOException; +import java.util.ArrayList; +import com.google.protobuf.CodedInputStream; +import com.google.protobuf.ExtensionRegistryLite; + +public class LogReader { + + private FileInputStream m_fileStream; + private CodedInputStream m_dataStream; + private LogEntry.Builder m_entryBuilder; + private ArrayList m_formatStrings; + + public LogReader(String filename) throws IOException { + m_fileStream = new FileInputStream(filename); + m_dataStream = CodedInputStream.newInstance(m_fileStream); + m_entryBuilder = LogEntry.newBuilder(); + m_formatStrings = new ArrayList(); + } + + public LogEntry readNext() throws IOException { + m_entryBuilder.clear(); + m_dataStream.readMessage(m_entryBuilder, ExtensionRegistryLite.getEmptyRegistry()); + LogEntry entry = m_entryBuilder.build(); + if (entry.hasMessageIndex() && entry.hasMessageStr()) { + final int index = entry.getMessageIndex(); + final String format = entry.getMessageStr(); + m_formatStrings.ensureCapacity(index + 1); + while (m_formatStrings.size() <= index) { + m_formatStrings.add(null); + } + m_formatStrings.set(index, format); + } + return entry; + } + + String getFormatString(int index) { + String str; + try { + str = m_formatStrings.get(index); + } catch (IndexOutOfBoundsException ex) { + throw new IllegalArgumentException("Unknown format string index: " + index); + } + if (str == null) { + throw new IllegalArgumentException("Unknown format string index: " + index); + } + return str; + } +} diff --git a/src/main/java/com/team766/logging/LogWriter.java b/src/main/java/com/team766/logging/LogWriter.java new file mode 100644 index 00000000..4cd06718 --- /dev/null +++ b/src/main/java/com/team766/logging/LogWriter.java @@ -0,0 +1,108 @@ +package com.team766.logging; + +import java.io.FileOutputStream; +import java.io.IOException; +import java.util.HashMap; +import com.google.protobuf.CodedOutputStream; +import com.team766.library.LossyPriorityQueue; + +public class LogWriter { + private static final int QUEUE_SIZE = 50; + + private LossyPriorityQueue m_entriesQueue; + + private Thread m_workerThread; + private boolean m_running = true; + + private HashMap m_formatStringIndices = new HashMap(); + + private FileOutputStream m_fileStream; + private CodedOutputStream m_dataStream; + + private Severity m_minSeverity = Severity.INFO; + + public LogWriter(String filename) throws IOException { + m_entriesQueue = new LossyPriorityQueue(QUEUE_SIZE, new LogEntryComparator()); + m_fileStream = new FileOutputStream(filename); + m_dataStream = CodedOutputStream.newInstance(m_fileStream); + m_workerThread = new Thread(new Runnable() { + public void run() { + while (true) { + LogEntry entry; + try { + entry = m_entriesQueue.poll(); + } catch (InterruptedException e) { + System.out.println("Logger thread received interruption"); + continue; + } + if (entry == LogEntryComparator.TERMINATION_SENTINAL) { + // close() sends this sentinel element when it's time to exit + return; + } + try { + m_dataStream.writeMessageNoTag(entry); + } catch (IOException e) { + e.printStackTrace(); + Logger.get(Category.JAVA_EXCEPTION).logOnlyInMemory( + Severity.ERROR, + LoggerExceptionUtils.exceptionToString(e)); + } + } + } + }); + m_workerThread.start(); + } + + public void close() throws IOException, InterruptedException { + m_running = false; + m_entriesQueue.add(LogEntryComparator.TERMINATION_SENTINAL); + + m_entriesQueue.waitForEmpty(); + m_workerThread.join(); + + m_dataStream.flush(); + m_fileStream.flush(); + + m_fileStream.getFD().sync(); + + m_fileStream.close(); + } + + public void setSeverityFilter(Severity threshold) { + m_minSeverity = threshold; + } + + public void logStoredFormat(LogEntry.Builder entry) { + if (entry.getSeverity().compareTo(m_minSeverity) < 0) { + return; + } + if (!m_running) { + System.out.println("Log message during shutdown: " + LogEntryRenderer.renderLogEntry(entry.build(), null)); + return; + } + final String format = entry.getMessageStr(); + Integer index = m_formatStringIndices.get(format); + if (index == null) { + index = m_formatStringIndices.size() + 1; + m_formatStringIndices.put(format, index); + if (m_formatStringIndices.size() % 100 == 0) { + System.out.println("You're logging a lot of unique messages. Please switch to using logRaw()"); + } + } else { + entry.clearMessageStr(); + } + entry.setMessageIndex(index); + m_entriesQueue.add(entry.build()); + } + + public void log(LogEntry entry) { + if (entry.getSeverity().compareTo(m_minSeverity) < 0) { + return; + } + if (!m_running) { + System.out.println("Log message during shutdown: " + LogEntryRenderer.renderLogEntry(entry, null)); + return; + } + m_entriesQueue.add(entry); + } +} diff --git a/src/main/java/com/team766/logging/Loggable.java b/src/main/java/com/team766/logging/Loggable.java new file mode 100644 index 00000000..14bf6e7d --- /dev/null +++ b/src/main/java/com/team766/logging/Loggable.java @@ -0,0 +1,5 @@ +package com.team766.logging; + +public interface Loggable { + public abstract void toLogValue(LogValue.Builder value); +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/Logger.java b/src/main/java/com/team766/logging/Logger.java new file mode 100644 index 00000000..473dd5d4 --- /dev/null +++ b/src/main/java/com/team766/logging/Logger.java @@ -0,0 +1,132 @@ +package com.team766.logging; + +import java.io.File; +import java.text.SimpleDateFormat; +import java.util.Collection; +import java.util.Collections; +import java.util.Date; +import java.util.EnumMap; + +import com.team766.config.ConfigFileReader; +import com.team766.library.CircularBuffer; + +public class Logger { + private static class LogUncaughtException implements Thread.UncaughtExceptionHandler { + public void uncaughtException(Thread t, Throwable e) { + e.printStackTrace(); + + LoggerExceptionUtils.logException(e); + + if (m_logWriter != null) { + try { + m_logWriter.close(); + } catch (Exception e1) { + e1.printStackTrace(); + } + } + + System.exit(1); + } + } + + private static final int MAX_NUM_RECENT_ENTRIES = 100; + + private static EnumMap m_loggers = new EnumMap(Category.class); + private static LogWriter m_logWriter = null; + private CircularBuffer m_recentEntries = new CircularBuffer(MAX_NUM_RECENT_ENTRIES); + private static Object s_lastWriteTimeSync = new Object(); + private static long s_lastWriteTime = 0L; + + public static String logFilePathBase = null; + + static { + for (Category category : Category.values()) { + m_loggers.put(category, new Logger(category)); + } + try { + ConfigFileReader config_file = ConfigFileReader.getInstance(); + if (config_file != null) { + logFilePathBase = config_file.getString("logFilePath").get(); + new File(logFilePathBase).mkdirs(); + final String timestamp = new SimpleDateFormat("yyyyMMdd'T'HHmmss").format(new Date()); + final String logFilePath = new File(logFilePathBase, timestamp).getAbsolutePath(); + m_logWriter = new LogWriter(logFilePath); + get(Category.CONFIGURATION).logRaw(Severity.INFO, "Logging to " + logFilePath); + } else { + get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Config file is not available. Logs will only be in-memory and will be lost when the robot is turned off."); + } + } catch (Exception e) { + e.printStackTrace(); + LoggerExceptionUtils.logException(e); + } + + Thread.setDefaultUncaughtExceptionHandler(new LogUncaughtException()); + } + + public static Logger get(Category category) { + return m_loggers.get(category); + } + + static long getTime() { + long nowNanosec = new Date().getTime() * 1000000; + synchronized(s_lastWriteTimeSync) { + // Ensure that log entries' timestamps are unique. This is important + // because the log viewer uses an entry's timestamp as a unique ID, + // and we don't want two different log entries to accidentally + // compare as equal. + nowNanosec = s_lastWriteTime = Math.max(nowNanosec, s_lastWriteTime); + } + return nowNanosec; + } + + private final Category m_category; + + private Logger(Category category) { + m_category = category; + } + + public Collection recentEntries() { + return Collections.unmodifiableCollection(m_recentEntries); + } + + public void logData(Severity severity, String format, Object... args) { + var entry = LogEntry.newBuilder() + .setTime(getTime()) + .setSeverity(severity) + .setCategory(m_category); + { + entry.setMessageStr(String.format(format, args)); + m_recentEntries.add(entry.build()); + } + entry.setMessageStr(format); + for (Object arg : args) { + SerializationUtils.valueToProto(arg, entry.addArgBuilder()); + } + if (m_logWriter != null) { + m_logWriter.logStoredFormat(entry); + } + } + + public void logRaw(Severity severity, String message) { + var entry = LogEntry.newBuilder() + .setTime(getTime()) + .setSeverity(severity) + .setCategory(m_category) + .setMessageStr(message) + .build(); + m_recentEntries.add(entry); + if (m_logWriter != null) { + m_logWriter.log(entry); + } + } + + void logOnlyInMemory(Severity severity, String message) { + var entry = LogEntry.newBuilder() + .setTime(getTime()) + .setSeverity(severity) + .setCategory(m_category) + .setMessageStr(message) + .build(); + m_recentEntries.add(entry); + } +} diff --git a/src/main/java/com/team766/logging/LoggerExceptionUtils.java b/src/main/java/com/team766/logging/LoggerExceptionUtils.java new file mode 100644 index 00000000..2f13388a --- /dev/null +++ b/src/main/java/com/team766/logging/LoggerExceptionUtils.java @@ -0,0 +1,25 @@ +package com.team766.logging; + +import java.io.PrintWriter; +import java.io.StringWriter; + +public class LoggerExceptionUtils { + public static String exceptionToString(Throwable e) { + StringWriter sw = new StringWriter(); + PrintWriter pw = new PrintWriter(sw); + pw.print("Uncaught exception: "); + e.printStackTrace(pw); + pw.flush(); + return sw.toString(); + } + + public static String logException(Throwable e) { + String str = exceptionToString(e); + try { + Logger.get(Category.JAVA_EXCEPTION).logRaw(Severity.ERROR, str); + } catch (Exception exc) { + exc.printStackTrace(); + } + return str; + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/logging/SerializationUtils.java b/src/main/java/com/team766/logging/SerializationUtils.java new file mode 100644 index 00000000..ac6b7997 --- /dev/null +++ b/src/main/java/com/team766/logging/SerializationUtils.java @@ -0,0 +1,50 @@ +package com.team766.logging; + +public class SerializationUtils { + public static void valueToProto(Object object, LogValue.Builder value) { + if (object instanceof Byte || + object instanceof Short || + object instanceof Integer || + object instanceof Long) { + value.setIntValue(((Number)object).longValue()); + } else if (object instanceof Character) { + value.setStringValue(((Character)object).toString()); + } else if (object instanceof Number) { + // If object is a Number but not one of the integer types, treat it + // as a double (this primarily handles Float and Double values, but + // also handles any weird other type that might inherit from Number) + value.setFloatValue(((Number)object).doubleValue()); + } else if (object instanceof Boolean) { + value.setBoolValue(((Boolean)object).booleanValue()); + } else if (object instanceof String) { + value.setStringValue((String)object); + } else if (object == null) { + value.clearKind(); + } else if (object instanceof Loggable) { + ((Loggable)object).toLogValue(value); + } else { + throw new IllegalArgumentException( + "Value of type " + object.getClass().getName() + " isn't loggable"); + } + } + + public static Object protoToValue(LogValue value) { + switch (value.getKindCase()) { + case KIND_NOT_SET: + return null; + case BOOL_VALUE: + return value.getBoolValue(); + case FLOAT_VALUE: + return value.getFloatValue(); + case INT_VALUE: + return value.getIntValue(); + case LIST: + return value.getList().getElementList().stream() + .map(SerializationUtils::protoToValue).toArray(); + case STRING_VALUE: + return value.getStringValue(); + } + throw new IllegalArgumentException( + "Unsupported LogValue kind: " + value.getKindCase()); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/math/Algebraic.java b/src/main/java/com/team766/math/Algebraic.java new file mode 100644 index 00000000..3bce828d --- /dev/null +++ b/src/main/java/com/team766/math/Algebraic.java @@ -0,0 +1,7 @@ +package com.team766.math; + +public interface Algebraic> { + public E add(E b); + + public E scale(double b); +} diff --git a/src/main/java/com/team766/math/Filter.java b/src/main/java/com/team766/math/Filter.java new file mode 100644 index 00000000..146980b5 --- /dev/null +++ b/src/main/java/com/team766/math/Filter.java @@ -0,0 +1,7 @@ +package com.team766.math; + +public interface Filter { + public void push(double sample); + + public double getValue(); +} diff --git a/src/main/java/com/team766/math/FirFilter.java b/src/main/java/com/team766/math/FirFilter.java new file mode 100644 index 00000000..4bad9289 --- /dev/null +++ b/src/main/java/com/team766/math/FirFilter.java @@ -0,0 +1,21 @@ +package com.team766.math; + +import java.util.stream.Collectors; + +import com.team766.library.CircularBuffer; + +public class FirFilter implements Filter { + private CircularBuffer buffer; + + public FirFilter(int bufferLength) { + buffer = new CircularBuffer<>(bufferLength); + } + + public void push(double sample) { + buffer.add(sample); + } + + public double getValue() { + return buffer.stream().collect(Collectors.averagingDouble(Double::doubleValue)); + } +} diff --git a/src/main/java/com/team766/math/IirFilter.java b/src/main/java/com/team766/math/IirFilter.java new file mode 100644 index 00000000..ac146be4 --- /dev/null +++ b/src/main/java/com/team766/math/IirFilter.java @@ -0,0 +1,27 @@ +package com.team766.math; + +public class IirFilter implements Filter { + private double decay; + private double value; + + public IirFilter(double decay, double initialValue) { + this.decay = decay; + this.value = initialValue; + if (decay > 1.0 || decay <= 0.0) { + throw new IllegalArgumentException("decay should be in (0.0, 1.0]"); + } + } + + public IirFilter(double decay) { + this(decay, 0.0); + } + + public void push(double sample) { + value *= (1.0 - decay); + value += sample * decay; + } + + public double getValue() { + return value; + } +} diff --git a/src/main/java/com/team766/math/IsometricTransform.java b/src/main/java/com/team766/math/IsometricTransform.java new file mode 100644 index 00000000..dc75c294 --- /dev/null +++ b/src/main/java/com/team766/math/IsometricTransform.java @@ -0,0 +1,40 @@ +package com.team766.math; + +import org.apache.commons.math3.geometry.euclidean.threed.Rotation; +import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +public class IsometricTransform { + public final Rotation rotation; + public final Vector3D translation; + + public static final IsometricTransform IDENTITY = + new IsometricTransform(Rotation.IDENTITY, Vector3D.ZERO); + + public IsometricTransform(Rotation rotation, Vector3D translation) { + this.rotation = rotation; + this.translation = translation; + } + + Vector3D applyInverseTo(Vector3D u) { + return rotation.applyInverseTo(u.subtract(translation)); + } + + Vector3D applyTo(Vector3D u) { + return rotation.applyTo(u).add(translation); + } + + IsometricTransform compose(IsometricTransform other) { + return new IsometricTransform(rotation.compose(other.rotation, RotationConvention.VECTOR_OPERATOR), + rotation.applyTo(other.translation).add(translation)); + } + + IsometricTransform composeInverse(IsometricTransform other) { + return new IsometricTransform(rotation.composeInverse(other.rotation, RotationConvention.VECTOR_OPERATOR), + rotation.applyInverseTo(other.translation).subtract(translation)); + } + + IsometricTransform invert() { + return new IsometricTransform(rotation.revert(), rotation.applyInverseTo(translation)); + } +} diff --git a/src/main/java/com/team766/math/LinearInterpolation.java b/src/main/java/com/team766/math/LinearInterpolation.java new file mode 100644 index 00000000..41a1f2a8 --- /dev/null +++ b/src/main/java/com/team766/math/LinearInterpolation.java @@ -0,0 +1,53 @@ +package com.team766.math; + +/*import java.util.Arrays; + +public class LinearInterpolation { + private static class LerpArgs { + public E a; + public E b; + public double t; + } + + private static LerpArgs getArgs(double[] t, E[] x, double q) { + if (t.length != x.length) { + throw new IllegalArgumentException("Keys and values must have the same length"); + } + if (t.length == 0) { + throw new IllegalArgumentException("Interpolated data must have at least one point"); + } + LerpArgs args = new LerpArgs(); + int lower, upper; + if (t.length == 1) { + // 0-th order regression if we only have one point. + lower = upper = 0; + args.t = 0; + } else { + int index = Arrays.binarySearch(t, q); + if (index >= 0) { + // Exact match. + lower = upper = index; + args.t = 0; + } else { + upper = -index - 1; + lower = upper - 1; + double a_t = t[lower]; + double b_t = t[upper]; + args.t = (q - a_t) / (b_t - a_t); + } + } + args.a = x[lower]; + args.b = x[upper]; + return args; + } + + public static double get(double[] t, Double[] x, double q) { + LerpArgs args = getArgs(t, x, q); + return args.a * (1 - args.t) + (args.b * args.t); + } + + public static > E get(double[] t, E[] x, double q) { + LerpArgs args = getArgs(t, x, q); + return args.a.scale(1 - args.t).add(args.b.scale(args.t)); + } +}*/ \ No newline at end of file diff --git a/src/main/java/com/team766/math/Math.java b/src/main/java/com/team766/math/Math.java new file mode 100644 index 00000000..84b109d9 --- /dev/null +++ b/src/main/java/com/team766/math/Math.java @@ -0,0 +1,22 @@ +package com.team766.math; + +public class Math { + public static double clamp(double x, double min, double max) { + if (x < min) return min; + if (x > max) return max; + return x; + } + + /** + * Returns the given angle, normalized to be within the range [-180, 180) + */ + public static double normalizeAngleDegrees(double angle) { + while (angle < -180) { + angle += 360; + } + while (angle >= 180) { + angle -= 360; + } + return angle; + } +} diff --git a/src/main/java/com/team766/math/TransformTree.java b/src/main/java/com/team766/math/TransformTree.java new file mode 100644 index 00000000..6e73823e --- /dev/null +++ b/src/main/java/com/team766/math/TransformTree.java @@ -0,0 +1,83 @@ +package com.team766.math; + +import java.util.ArrayList; +import java.util.Hashtable; + +public class TransformTree { + private ArrayList tree; + + private final String name; + private TransformTree parent; + private IsometricTransform transform; + + public TransformTree(String rootName) { + this.name = rootName; + } + + private TransformTree(String name, TransformTree parent) { + this.name = name; + this.parent = parent; + } + + public TransformTree addSubordinateTransform(String name) { + TransformTree subtree = new TransformTree(name, this); + tree.add(subtree); + return subtree; + } + + public void setLocalTransform(IsometricTransform xf) { + transform = xf; + } + public IsometricTransform getLocalTransform() { + return transform; + } + + public IsometricTransform getTransformRelativeTo(String name) { + TransformTree other = getRoot().findTransform(name); + if (other == null) { + throw new IllegalArgumentException("Can't find a transform named " + name); + } + return getTransformRelativeTo(other); + } + public IsometricTransform getTransformRelativeTo(TransformTree other) { + Hashtable parentChain = new Hashtable(); + IsometricTransform xf = transform; + parentChain.put(name, xf); + TransformTree iterator = this.parent; + while (iterator != null) { + xf = iterator.transform.compose(xf); + parentChain.put(iterator.name, xf); + iterator = iterator.parent; + } + iterator = other; + xf = other.transform; + while (iterator != null) { + IsometricTransform first = parentChain.get(iterator.name); + if (first != null) { + return first.compose(xf.invert()); + } + } + throw new IllegalArgumentException("Transforms aren't part of the same tree"); + } + + public TransformTree findTransform(String name) { + if (this.name == name) { + return this; + } + for (TransformTree sub : tree) { + TransformTree subResult = sub.findTransform(name); + if (subResult != null) { + return subResult; + } + } + return null; + } + + private TransformTree getRoot() { + TransformTree iterator = this; + while (iterator.parent != null) { + iterator = iterator.parent; + } + return iterator; + } +} diff --git a/src/main/java/com/team766/math/Vector3.java b/src/main/java/com/team766/math/Vector3.java new file mode 100644 index 00000000..0cd38152 --- /dev/null +++ b/src/main/java/com/team766/math/Vector3.java @@ -0,0 +1,60 @@ +package com.team766.math; + +public class Vector3 implements Algebraic { + public static final Vector3 ZERO = new Vector3(0, 0, 0); + public static final Vector3 UNIT_X = new Vector3(1, 0, 0); + public static final Vector3 UNIT_Y = new Vector3(0, 1, 0); + public static final Vector3 UNIT_Z = new Vector3(0, 0, 1); + + public final double x; + public final double y; + public final double z; + + public Vector3(double x, double y, double z) { + this.x = x; + this.y = y; + this.z = z; + } + + public Vector3(Vector3 other) { + this.x = other.x; + this.y = other.y; + this.z = other.z; + } + + public Vector3 add(Vector3 b) { + return new Vector3(x + b.x, y + b.y, z + b.z); + } + + public Vector3 subtract(Vector3 b) { + return new Vector3(x - b.x, y - b.y, z - b.z); + } + + public double dot(Vector3 b) { + return x * b.x + y * b.y + z * b.z; + } + + public Vector3 cross(Vector3 b) { + return new Vector3(y * b.z - z * b.y, + z * b.x - x * b.z, + x * b.y - y * b.x); + } + + public Vector3 scale(double b) { + return new Vector3(x * b, y * b, z * b); + } + + @Override + public boolean equals(Object other) { + if (!(other instanceof Vector3)) { + return false; + } + Vector3 otherVector = (Vector3)other; + return x != otherVector.x || y != otherVector.y || z != otherVector.z; + } + + @Override + public String toString() { + return String.format("[%s, %s, %s]", x, y, z); + } +} diff --git a/src/main/java/com/team766/odometry/Odometry.java b/src/main/java/com/team766/odometry/Odometry.java new file mode 100644 index 00000000..9bcd9fcd --- /dev/null +++ b/src/main/java/com/team766/odometry/Odometry.java @@ -0,0 +1,127 @@ +package com.team766.odometry; + +import com.team766.framework.LoggingBase; +import com.team766.hal.MotorController; +import com.team766.library.RateLimiter; +import com.ctre.phoenix.sensors.CANCoder; +import com.team766.logging.Category; +import com.team766.robot.*; + +public class Odometry extends LoggingBase { + + private RateLimiter odometryLimiter; + + private MotorController[] motorList; + //The order of CANCoders should be the same as in motorList + private CANCoder[] CANCoderList; + private int motorCount; + + private PointDir[] prevPositions; + private PointDir[] currPositions; + private double[] prevEncoderValues; + private double[] currEncoderValues; + private double gyroPosition; + + private PointDir currentPosition; + + //In Meters + private static double WHEEL_CIRCUMFERENCE; + public static double GEAR_RATIO; + public static int ENCODER_TO_REVOLUTION_CONSTANT; + + //In the same order as motorList, relative to the center of the robot + private Point[] wheelPositions; + + public Odometry(MotorController[] motors, CANCoder[] CANCoders, Point[] wheelLocations, double wheelCircumference, double gearRatio, int encoderToRevolutionConstant, double rateLimiterTime) { + loggerCategory = Category.ODOMETRY; + + odometryLimiter = new RateLimiter(rateLimiterTime); + motorList = motors; + CANCoderList = CANCoders; + motorCount = motorList.length; + log("Motor count " + motorCount); + prevPositions = new PointDir[motorCount]; + currPositions = new PointDir[motorCount]; + prevEncoderValues = new double[motorCount]; + currEncoderValues = new double[motorCount]; + + wheelPositions = wheelLocations; + WHEEL_CIRCUMFERENCE = wheelCircumference; + GEAR_RATIO = gearRatio; + ENCODER_TO_REVOLUTION_CONSTANT = encoderToRevolutionConstant; + + currentPosition = new PointDir(0, 0, 0); + for (int i = 0; i < motorCount; i++) { + prevPositions[i] = new PointDir(0,0, 0); + currPositions[i] = new PointDir(0,0, 0); + prevEncoderValues[i] = 0; + currEncoderValues[i] = 0; + } + } + + public String getName() { + return "Odometry"; + } + + public void resetCurrentPosition() { + currentPosition.set(0, 0); + for (int i = 0; i < motorCount; i++) { + prevPositions[i].set(currentPosition.add(wheelPositions[i])); + currPositions[i].set(0,0); + } + } + + private void setCurrentEncoderValues() { + for (int i = 0; i < motorCount; i++) { + prevEncoderValues[i] = currEncoderValues[i]; + currEncoderValues[i] = motorList[i].getSensorPosition(); + } + } + + private void updateCurrentPositions() { + double angleChange; + double radius; + double deltaX; + double deltaY; + gyroPosition = Robot.gyro.getGyroYaw(); + Point slopeFactor = new Point(Math.sqrt(Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroPitch()) * Math.cos(Robot.gyro.getGyroPitch()) + Math.sin(Robot.gyro.getGyroYaw()) * Math.sin(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroRoll()) * Math.cos(Robot.gyro.getGyroRoll())), Math.sqrt(Math.sin(Robot.gyro.getGyroYaw()) * Math.sin(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroPitch()) * Math.cos(Robot.gyro.getGyroPitch()) + Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroRoll()) * Math.cos(Robot.gyro.getGyroRoll()))); + + for (int i = 0; i < motorCount; i++) { + //prevPositions[i] = new PointDir(currentPosition.getX() + 0.5 * DISTANCE_BETWEEN_WHEELS / Math.sin(Math.PI / motorCount) * Math.cos(currentPosition.getHeading() + ((Math.PI + 2 * Math.PI * i) / motorCount)), currentPosition.getY() + 0.5 * DISTANCE_BETWEEN_WHEELS / Math.sin(Math.PI / motorCount) * Math.sin(currentPosition.getHeading() + ((Math.PI + 2 * Math.PI * i) / motorCount)), currPositions[i].getHeading()); + prevPositions[i].set(currentPosition.add(wheelPositions[i]), currPositions[i].getHeading()); + currPositions[i].setHeading(CANCoderList[i].getAbsolutePosition() + gyroPosition); + angleChange = currPositions[i].getHeading() - prevPositions[i].getHeading(); + + if (angleChange != 0) { + radius = 180 * (currEncoderValues[i] - prevEncoderValues[i]) / (Math.PI * angleChange); + deltaX = radius * Math.sin(Math.toRadians(angleChange)); + deltaY = radius * (1 - Math.cos(Math.toRadians(angleChange))); + currPositions[i].setX(prevPositions[i].getX() + (Math.cos(Math.toRadians(prevPositions[i].getHeading())) * deltaX - Math.sin(Math.toRadians(prevPositions[i].getHeading())) * deltaY) * slopeFactor.getX() * WHEEL_CIRCUMFERENCE / (GEAR_RATIO * ENCODER_TO_REVOLUTION_CONSTANT)); + currPositions[i].setY(prevPositions[i].getY() + (Math.sin(Math.toRadians(prevPositions[i].getHeading())) * deltaX + Math.cos(Math.toRadians(prevPositions[i].getHeading())) * deltaY) * slopeFactor.getY() * WHEEL_CIRCUMFERENCE / (GEAR_RATIO * ENCODER_TO_REVOLUTION_CONSTANT)); + } else { + currPositions[i].setX(prevPositions[i].getX() + (currEncoderValues[i] - prevEncoderValues[i]) * Math.cos(Math.toRadians(prevPositions[i].getHeading())) * slopeFactor.getX() * WHEEL_CIRCUMFERENCE / (GEAR_RATIO * ENCODER_TO_REVOLUTION_CONSTANT)); + currPositions[i].setY(prevPositions[i].getY() + (currEncoderValues[i] - prevEncoderValues[i]) * Math.sin(Math.toRadians(prevPositions[i].getHeading())) * slopeFactor.getY() * WHEEL_CIRCUMFERENCE / (GEAR_RATIO * ENCODER_TO_REVOLUTION_CONSTANT)); + } + } + } + + private void findRobotPosition() { + double sumX = 0; + double sumY = 0; + for (int i = 0; i < motorCount; i++) { + sumX += currPositions[i].getX(); + sumY += currPositions[i].getY(); + } + currentPosition.set(sumX / motorCount, sumY / motorCount, gyroPosition); + } + + //Intended to be placed inside Robot.drive.run() + public PointDir run() { + if (odometryLimiter.next()) { + setCurrentEncoderValues(); + updateCurrentPositions(); + findRobotPosition(); + } + return currentPosition; + } +} diff --git a/src/main/java/com/team766/odometry/Point.java b/src/main/java/com/team766/odometry/Point.java new file mode 100644 index 00000000..d28d0454 --- /dev/null +++ b/src/main/java/com/team766/odometry/Point.java @@ -0,0 +1,81 @@ +package com.team766.odometry; + +import com.team766.framework.LoggingBase; +import java.lang.Math; + +public class Point extends LoggingBase { + private double x; + private double y; + + public String getName() { + return "Points"; + } + + public Point(double x, double y){ + this.x = x; + this.y = y; + } + + public double getX() { + return x; + } + + public double getY() { + return y; + } + + public void set(double x, double y) { + this.x = x; + this.y = y; + } + + public void set(Point P) { + this.x = P.getX(); + this.y = P.getY(); + } + + public void setX(double x) { + this.x = x; + } + + public void setY(double y) { + this.y = y; + } + + public double distance(Point a) { + return Math.sqrt(Math.pow(a.getX() - getX(), 2.0) + Math.pow(a.getY() - getY(), 2.0)); + } + + public double slope(Point a) { + double s; + final int MAX = 1000; + if (a.getX() == getX()) { + //If the points are on top of each other, returns positive or negative MAX. + if (a.getY() < getY()) { + s = -MAX; + } else { + s = MAX; + } + } else { + s = (getY() - a.getY()) / (getX() - a.getX()); + } + if (Math.abs(s) > MAX) { + s = Math.signum(s) * MAX; + } + return s; + } + + //Gets a vector with length scale between the point and another point. Used for swerve drive method input. + public Point scaleVector(Point inputPoint, double scale) { + double d = distance(inputPoint); + return new Point((inputPoint.getX() - getX()) * scale / d, (inputPoint.getY() - getY()) * scale / d); + } + + public Point add(Point p) { + return new Point(getX() + p.getX(), getY() + p.getY()); + } + + public String toString() { + return "X: " + getX() + " Y: " + getY(); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/odometry/PointDir.java b/src/main/java/com/team766/odometry/PointDir.java new file mode 100644 index 00000000..6d64dcc5 --- /dev/null +++ b/src/main/java/com/team766/odometry/PointDir.java @@ -0,0 +1,70 @@ +package com.team766.odometry; + +import com.team766.logging.Category; +import java.lang.Math; + +public class PointDir extends Point { + private double heading; + + public PointDir(double x, double y, double h){ + super(x, y); + heading = h; + loggerCategory = Category.DRIVE; + } + + public PointDir(Point P, double h) { + super(P.getX(), P.getY()); + heading = h; + loggerCategory = Category.DRIVE; + } + + public double getHeading() { + return heading; + } + + public void set(double x, double y, double h) { + super.set(x, y); + heading = h; + } + + public void set(Point P, double h) { + super.set(P); + heading = h; + } + + public void setHeading(double h) { + heading = h; + } + + public double getAngleDifference(Point a) { + //Returns a number between -1 and 1 to represent the number of rotations between the two angles. + PointDir unitVector; + if (distance(a) == 0) { + unitVector = new PointDir(1, 0, 0); + } else { + unitVector = new PointDir((a.getX() - getX()) / distance(a), (a.getY() - getY()) / distance(a), Math.toDegrees(Math.atan2((a.getY() - getY()) / distance(a), (a.getX() - getX()) / distance(a)))); + } + double headingAngle = getHeading() % 360; + if (headingAngle < 0) { + headingAngle += 360; + } + if (unitVector.getHeading() < 0) { + unitVector.setHeading(unitVector.getHeading() + 360); + } + double diff = headingAngle - unitVector.getHeading(); + if (diff < -180) { + diff += 360; + } else if (diff > 180) { + diff -= 360; + } + return diff / 180; + } + + public String toString() { + return super.toString() + " Heading: " + getHeading(); + } + + public PointDir clone() { + return new PointDir(getX(), getY(), getHeading()); + } +} diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java new file mode 100644 index 00000000..c37e6041 --- /dev/null +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -0,0 +1,21 @@ +package com.team766.robot; + +import com.team766.framework.AutonomousMode; +import com.team766.robot.procedures.*; +import com.team766.odometry.Point; +import com.team766.odometry.PointDir; + +public class AutonomousModes { + public static final AutonomousMode[] AUTONOMOUS_MODES = new AutonomousMode[] { + // Add autonomous modes here like this: + // new AutonomousMode("NameOfAutonomousMode", () -> new MyAutonomousProcedure()), + // + // If your autonomous procedure has constructor arguments, you can + // define one or more different autonomous modes with it like this: + // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), + // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), + new AutonomousMode("FollowPoints", () -> new FollowPoints()), + new AutonomousMode("FollowPointsH", () -> new FollowPoints(new Point[]{new Point(0, 0), new Point(2, 0), new Point(1, 0), new Point(1, 1), new Point(2, 1), new Point(0, 1)})), + new AutonomousMode("DoNothing", () -> new DoNothing()), + }; +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/InputConstants.java b/src/main/java/com/team766/robot/InputConstants.java new file mode 100644 index 00000000..2b95d074 --- /dev/null +++ b/src/main/java/com/team766/robot/InputConstants.java @@ -0,0 +1,22 @@ +package com.team766.robot; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + * TODO: consider moving this into a config file. + */ +public final class InputConstants { + + //Joysticks + public static final int LEFT_JOYSTICK = 0; + public static final int RIGHT_JOYSTICK = 1; + public static final int CONTROL_PANEL = 2; + + //Navigation + public static final int AXIS_LEFT_RIGHT = 0; + public static final int AXIS_FORWARD_BACKWARD = 1; + public static final int AXIS_TWIST =3; + // Joystick buttons + public static final int CROSS_DEFENSE = 7; + //Other buttons +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java new file mode 100644 index 00000000..59297781 --- /dev/null +++ b/src/main/java/com/team766/robot/OI.java @@ -0,0 +1,144 @@ +package com.team766.robot; + +import com.team766.framework.Procedure; +import com.team766.framework.Context; +import com.team766.hal.JoystickReader; +import com.team766.hal.RobotProvider; +import com.team766.logging.Category; +import com.team766.robot.procedures.*; + +/** + * This class is the glue that binds the controls on the physical operator + * interface to the code that allow control of the robot. + */ +public class OI extends Procedure { + private JoystickReader joystick0; + private JoystickReader joystick1; + private JoystickReader joystick2; + private double RightJoystick_X = 0; + private double RightJoystick_Y = 0; + private double RightJoystick_Z = 0; + private double RightJoystick_Theta = 0; + private double LeftJoystick_X = 0; + private double LeftJoystick_Y = 0; + private double LeftJoystick_Z = 0; + private double LeftJoystick_Theta = 0; + double turningValue = 0; + + public OI() { + loggerCategory = Category.OPERATOR_INTERFACE; + + joystick0 = RobotProvider.instance.getJoystick(0); + joystick1 = RobotProvider.instance.getJoystick(1); + joystick2 = RobotProvider.instance.getJoystick(2); + } + + public void run(Context context) { + double prev_time = RobotProvider.instance.getClock().getTime(); + context.takeOwnership(Robot.gyro); + context.takeOwnership(Robot.drive); + //Robot.gyro.resetGyro(); + Robot.drive.setFrontRightEncoders(); + Robot.drive.setFrontLeftEncoders(); + Robot.drive.setBackRightEncoders(); + Robot.drive.setBackLeftEncoders(); + + while (true) { + // Add driver controls here - make sure to take/release ownership + // of mechanisms when appropriate. + if(joystick1.getButton(2)){ + Robot.drive.setGyro(0); + }else{ + Robot.drive.setGyro(Robot.gyro.getGyroYaw()); + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ + RightJoystick_Y = joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + } else { + RightJoystick_Y = 0; + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ + RightJoystick_X = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; + if(joystick1.getButton(3)){ + RightJoystick_X *= 2; + } + } else { + RightJoystick_X = 0; + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ + RightJoystick_Theta = joystick1.getAxis(InputConstants.AXIS_TWIST); + } else { + RightJoystick_Theta = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ + LeftJoystick_Y = joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + } else { + LeftJoystick_Y = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ + LeftJoystick_X = joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT); + } else { + LeftJoystick_X = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ + LeftJoystick_Theta = joystick0.getAxis(InputConstants.AXIS_TWIST); + } else { + LeftJoystick_Theta = 0; + } + //log(Robot.gyro.getGyroYaw()); + //TODO: fix defense: the robot basically locks up if there is defense + // if(joystick0.getButton(InputConstants.CROSS_DEFENSE)){ + // context.startAsync(new DefenseCross()); + // } + + /*if(Math.pow(Math.pow(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT),2) + Math.pow(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD),2), 0.5) > 0.15 ){ + Robot.drive.drive2D( + ((joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT))), + ((joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD))) + ); + } else { + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST))>=0.1){ + Robot.drive.turning(joystick0.getAxis(InputConstants.AXIS_TWIST)); + } else { + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + } + }*/ + if(joystick0.getButtonPressed(1)) + Robot.gyro.resetGyro(); + + if(joystick0.getButtonPressed(2)){ + Robot.drive.setFrontRightEncoders(); + Robot.drive.setFrontLeftEncoders(); + Robot.drive.setBackRightEncoders(); + Robot.drive.setBackLeftEncoders(); + } + // if(joystick1.getButton(1)){ + // turningValue = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT); + // } else { + // turningValue = 0; + // } + if(Math.abs(LeftJoystick_X)+ + Math.abs(LeftJoystick_Y)+ Math.abs(RightJoystick_X) > 0){ + Robot.drive.swerveDrive( + (LeftJoystick_X), + (LeftJoystick_Y), + (RightJoystick_X) + );} else{ + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + } + + if (joystick0.getButtonPressed(11)) { + Robot.drive.resetCurrentPosition(); + } + + if (joystick1.getButtonPressed(11)) { + context.takeOwnership(Robot.drive); + new FollowPoints().run(context); + } + + double cur_time = RobotProvider.instance.getClock().getTime(); + context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); + } + } +} diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java new file mode 100644 index 00000000..f693fd73 --- /dev/null +++ b/src/main/java/com/team766/robot/Robot.java @@ -0,0 +1,15 @@ +package com.team766.robot; + +import com.team766.robot.mechanisms.*; + +public class Robot { + // Declare mechanisms here + public static Drive drive; + public static Gyro gyro; + + public static void robotInit() { + // Initialize mechanisms here + drive = new Drive(); + gyro = new Gyro(); + } +} diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java new file mode 100644 index 00000000..1fd22a0e --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -0,0 +1,405 @@ +package com.team766.robot.mechanisms; +import com.team766.framework.Mechanism; +import com.team766.hal.EncoderReader; +import com.team766.hal.RobotProvider; +import com.team766.hal.MotorController; +import com.team766.hal.MotorController.ControlMode; +import com.team766.hal.simulator.Encoder; +import com.team766.hal.MotorController; +import com.team766.library.RateLimiter; +import com.team766.library.ValueProvider; +import com.team766.logging.Category; +import com.team766.simulator.ProgramInterface.RobotMode; +import com.team766.config.ConfigFileReader; +import com.team766.framework.Mechanism; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.sensors.AbsoluteSensorRange; +import com.ctre.phoenix.sensors.CANCoder; +import com.ctre.phoenix.sensors.CANCoderConfiguration; +import com.team766.odometry.Odometry; +import com.team766.odometry.Point; +import com.team766.odometry.PointDir; + + +public class Drive extends Mechanism { + + private MotorController m_DriveFrontRight; + private MotorController m_DriveFrontLeft; + private MotorController m_DriveBackRight; + private MotorController m_DriveBackLeft; + + private MotorController m_SteerFrontRight; + private MotorController m_SteerFrontLeft; + private MotorController m_SteerBackRight; + private MotorController m_SteerBackLeft; + + private CANCoder e_FrontRight; + private CANCoder e_FrontLeft; + private CANCoder e_BackRight; + private CANCoder e_BackLeft; + + private ValueProvider drivePower; + + private double gyroValue; + + private static PointDir currentPosition; + + private MotorController[] motorList; + private CANCoder[] CANCoderList; + private Point[] wheelPositions; + private Odometry swerveOdometry; + + public static final double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; + + public Drive() { + + loggerCategory = Category.DRIVE; + // Initializations of motors + //Initialize the drive motors + m_DriveFrontRight = RobotProvider.instance.getMotor("drive.DriveFrontRight"); + m_DriveFrontLeft = RobotProvider.instance.getMotor("drive.DriveFrontLeft"); + m_DriveBackRight = RobotProvider.instance.getMotor("drive.DriveBackRight"); + m_DriveBackLeft = RobotProvider.instance.getMotor("drive.DriveBackLeft"); + //Initialize the steering motors + m_SteerFrontRight = RobotProvider.instance.getMotor("drive.SteerFrontRight"); + m_SteerFrontLeft = RobotProvider.instance.getMotor("drive.SteerFrontLeft"); + m_SteerBackRight = RobotProvider.instance.getMotor("drive.SteerBackRight"); + m_SteerBackLeft = RobotProvider.instance.getMotor("drive.SteerBackLeft"); + + //Setting up the "config" + CANCoderConfiguration config = new CANCoderConfiguration(); + config.absoluteSensorRange = AbsoluteSensorRange.Signed_PlusMinus180; + //The encoders output "encoder" values, so we need to convert that to degrees (because that is what the cool kids are using) + config.sensorCoefficient = 360.0 / 4096.0; + //The offset is going to be changed in ctre, but we can change it here too. + //config.magnetOffsetDegrees = Math.toDegrees(configuration.getOffset()); + config.sensorDirection = true; + + //initialize the encoders + e_FrontRight = new CANCoder(1); + //e_FrontRight.configAllSettings(config, 250); + e_FrontLeft = new CANCoder(2); + //e_FrontLeft.configAllSettings(config, 250); + e_BackRight = new CANCoder(4); + //e_BackRight.configAllSettings(config, 250); + e_BackLeft = new CANCoder(3); + //e_BackLeft.configAllSettings(config, 250); + + + //Current limit for motors to avoid breaker problems (mostly to avoid getting electrical people to yell at us) + m_DriveFrontRight.setCurrentLimit(35); + m_DriveFrontLeft.setCurrentLimit(35); + m_DriveBackRight.setCurrentLimit(35); + m_DriveBackLeft.setCurrentLimit(35); + m_DriveBackLeft.setInverted(true); + m_DriveBackRight.setInverted(true); + m_SteerFrontRight.setCurrentLimit(30); + m_SteerFrontLeft.setCurrentLimit(30); + m_SteerBackRight.setCurrentLimit(30); + m_SteerBackLeft.setCurrentLimit(30); + + //Setting up the connection between steering motors and cancoders + //m_SteerFrontRight.setRemoteFeedbackSensor(e_FrontRight, 0); + //m_SteerFrontLeft.setRemoteFeedbackSensor(e_FrontLeft, 0); + //m_SteerBackRight.setRemoteFeedbackSensor(e_BackRight, 0); + //m_SteerBackLeft.setRemoteFeedbackSensor(e_BackLeft, 0); + + m_SteerFrontRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerFrontLeft.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerBackRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerBackLeft.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + configPID(); + + currentPosition = new PointDir(0, 0, 0); + motorList = new MotorController[]{m_DriveFrontRight, m_DriveFrontLeft, m_DriveBackLeft, m_DriveBackRight}; + CANCoderList = new CANCoder[]{e_FrontRight, e_FrontLeft, e_BackLeft, e_BackRight}; + wheelPositions = new Point[]{new Point(DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2), new Point(DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), new Point(-DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), new Point(-DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2)}; + log("MotorList Length: " + motorList.length); + log("CANCoderList Length: " + CANCoderList.length); + //The wheelCircumference is somewhere between 30.4cm and 30.6cm + swerveOdometry = new Odometry(motorList, CANCoderList, wheelPositions, 30.5 / 100, 6.75, 2048, 0.05); + } + //If you want me to repeat code, then no. + public double pythagorean(double x, double y) { + return Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2)); + } + public double getAngle(double LR, double FB){ + return Math.toDegrees(Math.atan2(LR ,-FB)); + } + public double round(double value, int places) { + double scale = Math.pow(10, places); + return Math.round(value * scale) / scale; + } + public double NewAng(double FirstMag, double FirstAng, double SecondMag, double SecondAng){ + double FinalX = FirstMag*Math.cos(Math.toRadians(FirstAng)) + SecondMag*Math.cos(Math.toRadians(SecondAng)); + double FinalY = FirstMag*Math.sin(Math.toRadians(FirstAng)) + SecondMag*Math.sin(Math.toRadians(SecondAng)); + return round(Math.toDegrees(Math.atan2(FinalY,FinalX)),5); + } + public double NewMag(double FirstMag, double FirstAng, double SecondMag, double SecondAng){ + double FinalX = FirstMag*Math.cos(Math.toRadians(FirstAng)) + SecondMag*Math.cos(Math.toRadians(SecondAng)); + double FinalY = FirstMag*Math.sin(Math.toRadians(FirstAng)) + SecondMag*Math.sin(Math.toRadians(SecondAng)); + return round(Math.sqrt(Math.pow(FinalX,2) + Math.pow(FinalY,2)),5); + } + + public static double correctedJoysticks(double Joystick){ + if(Joystick >= 0) + return(3.0*Math.pow(Joystick,2)-2.0*Math.pow(Joystick,3)); + else + return(-1*3.0*Math.pow(-1*Joystick,2)+2.0*Math.pow(-1*Joystick,3)); + } + + + public static double fieldAngle(double angle, double gyro){ + double newAngle; + newAngle = angle - gyro; + if(newAngle < 0){ + newAngle = newAngle + 360; + } + if(newAngle >= 180){ + newAngle = newAngle -360; + } + return newAngle; + } + public static double newAngle(double newAngle, double lastAngle){ + while(newAngle<0) newAngle += 360; + while(newAngle < (lastAngle - 180)) newAngle+=360; + while(newAngle > (lastAngle + 180)) newAngle-=360; + return newAngle; + } + //Not the actual gyro, but I am passing it through the OI.java to get it here + public void setGyro(double value){ + gyroValue = value; + } + //This is the method that is called to drive the robot in the 2D plane + public void drive2D(double JoystickX, double JoystickY) { + checkContextOwnership(); + //logs(); + //double power = pythagorean((JoystickX), correctedJoysticks(JoystickY))/Math.sqrt(2); + double power = Math.max(Math.abs(JoystickX),Math.abs(JoystickY)); + double angle = fieldAngle(getAngle(JoystickX, JoystickY),gyroValue); + log("Given angle: " + getAngle(JoystickX,JoystickY) + " || Gyro: " + gyroValue + " || New angle: " + angle); + //Temporary Drive code, kinda sucks + m_DriveFrontRight.set(power); + m_DriveFrontLeft.set(power); + m_DriveBackRight.set(power); + m_DriveBackLeft.set(power); + //Steer code + setFrontRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + } + + public void drive2D(Point joystick) { + drive2D(joystick.getX(), joystick.getY()); + } + + public void stopDriveMotors() { + checkContextOwnership(); + m_DriveFrontRight.stopMotor(); + m_DriveFrontLeft.stopMotor(); + m_DriveBackRight.stopMotor(); + m_DriveBackLeft.stopMotor(); + } + public void stopSteerMotors() { + checkContextOwnership(); + m_SteerFrontRight.stopMotor(); + m_SteerFrontLeft.stopMotor(); + m_SteerBackRight.stopMotor(); + m_SteerBackLeft.stopMotor(); + } + + + public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta){ + checkContextOwnership(); + double power = Math.max(Math.abs(JoystickX),Math.abs(JoystickY)); + double angle = fieldAngle(getAngle(JoystickX, JoystickY),gyroValue); + double frPower; + double flPower; + double brPower; + double blPower; + double frAngle; + double flAngle; + double brAngle; + double blAngle; + if(JoystickTheta >= 0){ + frPower = NewMag(power, angle, JoystickTheta, 135); + flPower = NewMag(power, angle, JoystickTheta, 45); + brPower = NewMag(power, angle, JoystickTheta, -135); + blPower = NewMag(power, angle, JoystickTheta, -45); + frAngle = NewAng(power, angle, JoystickTheta, 135); + flAngle = NewAng(power, angle, JoystickTheta, 45); + brAngle = NewAng(power, angle, JoystickTheta, -135); + blAngle = NewAng(power, angle, JoystickTheta, -45); + } + else{ + frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); + flPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); + brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); + blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); + frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + flAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); + brAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); + blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); + } + if(Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)) > 1){ + frPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + flPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + brPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + blPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + } + m_DriveFrontRight.set(frPower); + m_DriveFrontLeft.set(flPower); + m_DriveBackRight.set(brPower); + m_DriveBackLeft.set(blPower); + //Steer code + setFrontRightAngle(newAngle(frAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(flAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(brAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(blAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + } + + public void swerveDrive(PointDir joystick) { + swerveDrive(joystick.getY(), -1 * joystick.getX(), joystick.getHeading()); + } + +public void turning(double Joystick){ + checkContextOwnership(); + if(Joystick > 0){ + setFrontRightAngle(newAngle(135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(-135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(-45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + m_DriveFrontRight.set(Math.abs(Joystick)); + m_DriveFrontLeft.set(Math.abs(Joystick)); + m_DriveBackRight.set(Math.abs(Joystick)); + m_DriveBackLeft.set(Math.abs(Joystick)); + } + if(Joystick < 0){ + setFrontRightAngle(newAngle(-45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(-135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + m_DriveFrontRight.set(Math.abs(Joystick)); + m_DriveFrontLeft.set(Math.abs(Joystick)); + m_DriveBackRight.set(Math.abs(Joystick)); + m_DriveBackLeft.set(Math.abs(Joystick)); + } +} + + //Logging the encoder values (also I love Github Copilot <3) + public void logs(){ + log("Front Right Encoder: " + getFrontRight() + " Front Left Encoder: " + getFrontLeft() + " Back Right Encoder: " + getBackRight() + " Back Left Encoder: " + getBackLeft()); + } + public void setFrontRightEncoders(){ + m_SteerFrontRight.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontRight.getAbsolutePosition())); + } + public void setFrontLeftEncoders(){ + m_SteerFrontLeft.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontLeft.getAbsolutePosition())); + //log("New encoder value: " + (int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontLeft.getAbsolutePosition()) + " || Motor value: " + m_SteerFrontLeft.getSensorPosition()); + } + public void setBackRightEncoders(){ + m_SteerBackRight.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_BackRight.getAbsolutePosition())); + } + public void setBackLeftEncoders(){ + m_SteerBackLeft.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_BackLeft.getAbsolutePosition())); + } + //To control each steering individually with a PID + public void setFrontRightAngle(double angle){ + //log("Angle: " + getFrontRight() + " || Motor angle: " + 360.0/ 2048.0 * m_SteerFrontRight.getSensorPosition()); + m_SteerFrontRight.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setFrontLeftAngle(double angle){ + //log("Angle: " + getFrontLeft() + " || Motor angle: " + Math.pow((2048.0/360.0 * (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); + //log("Angle: %f Motor angle: %f", getFrontLeft(), Math.pow((2048.0/360.0 * (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); + m_SteerFrontLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setBackRightAngle(double angle){ + //log("Angle: " + getBackRight() + " || Motor angle: " + m_SteerBackRight.getSensorPosition()); + m_SteerBackRight.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setBackLeftAngle(double angle){ + //log("Angle: " + getBackLeft() + " || Motor angle: " + m_SteerBackLeft.getSensorPosition()); + m_SteerBackLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setSFR(double angle){ + setFrontRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void setSFL(double angle){ + setFrontLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void setSBR(double angle){ + setBackRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void setSBL(double angle){ + setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void configPID(){ + //PID for turning the various steering motors. Here is a good link to a tuning website: https://www.robotsforroboticists.com/pid-control/ + m_SteerFrontRight.setP(0.2); + m_SteerFrontRight.setI(0); + m_SteerFrontRight.setD(0.1); + m_SteerFrontRight.setFF(0); + + m_SteerFrontLeft.setP(0.2); + m_SteerFrontLeft.setI(0); + m_SteerFrontLeft.setD(0.1); + m_SteerFrontLeft.setFF(0); + + m_SteerBackRight.setP(0.2); + m_SteerBackRight.setI(0); + m_SteerBackRight.setD(0.1); + m_SteerBackRight.setFF(0); + + m_SteerBackLeft.setP(0.2); + m_SteerBackLeft.setI(0); + m_SteerBackLeft.setD(0.1); + m_SteerBackLeft.setFF(0); + + //pid values from sds for Flacons 500: P = 0.2 I = 0.0 D = 0.1 FF = 0.0 + + //IDK what those do tbh, but I like to keep them here. + //m_SteerFrontRight.setSensorInverted(false); + //m_SteerFrontLeft.setSensorInverted(false); + //m_SteerBackRight.setSensorInverted(false); + //m_SteerBackLeft.setSensorInverted(false); + } + + //Method to get the encoder values, the encoders are in degrees from -180 to 180. To change that, we need to change the syntax and use getPosition() + public double getFrontRight(){ + return e_FrontRight.getAbsolutePosition(); + } + public double getFrontLeft(){ + return e_FrontLeft.getAbsolutePosition(); + } + public double getBackRight(){ + return e_BackRight.getAbsolutePosition(); + } + public double getBackLeft(){ + return e_BackLeft.getAbsolutePosition(); + } + + public PointDir getCurrentPosition() { + return currentPosition; + } + + public void resetCurrentPosition() { + swerveOdometry.resetCurrentPosition(); + } + + public void resetDriveEncoders() { + m_DriveBackLeft.setSensorPosition(0); + m_DriveBackRight.setSensorPosition(0); + m_DriveFrontLeft.setSensorPosition(0); + m_DriveFrontRight.setSensorPosition(0); + } + + //Odometry + @Override + public void run() { + currentPosition = swerveOdometry.run(); + log (currentPosition.toString()); + } +} + +//AS \ No newline at end of file diff --git a/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java b/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java new file mode 100644 index 00000000..75f24df9 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java @@ -0,0 +1,22 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.RobotProvider; +import com.team766.hal.MotorController; + +public class ExampleMechanism extends Mechanism { + private MotorController leftMotor; + private MotorController rightMotor; + + public ExampleMechanism() { + leftMotor = RobotProvider.instance.getMotor("exampleMechanism.leftMotor"); + rightMotor = RobotProvider.instance.getMotor("exampleMechanism.rightMotor"); + } + + public void setMotorPower(double leftPower, double rightPower){ + checkContextOwnership(); + + leftMotor.set(leftPower); + rightMotor.set(rightPower); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/mechanisms/Gyro.java b/src/main/java/com/team766/robot/mechanisms/Gyro.java new file mode 100644 index 00000000..03421ce7 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Gyro.java @@ -0,0 +1,54 @@ +package com.team766.robot.mechanisms; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.SerialPort; +import edu.wpi.first.wpilibj.I2C.Port; + +import com.team766.framework.Mechanism; +import com.team766.hal.EncoderReader; +import com.team766.hal.RobotProvider; +import com.team766.hal.MotorController; +import com.team766.library.RateLimiter; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +//import edu.wpi.first.wpilibj.I2C.Port; +//import com.team766.hal.GyroReader; +//import com.kauailabs.navx.frc.*; +import com.ctre.phoenix.sensors.Pigeon2; + +public class Gyro extends Mechanism { + Pigeon2 g_gyro = new Pigeon2(0); + double[] gyroArray = new double[3]; + private RateLimiter l_loggingRate = new RateLimiter(0.05); + public Gyro() { + loggerCategory = Category.GYRO; + } + public void resetGyro(){ + g_gyro.setYaw(0); + } + public double getGyroPitch() { + double angle = g_gyro.getPitch(); + return angle; + + } + + public double getGyroYaw() { + double angle = -1* g_gyro.getYaw(); + return angle; + } + + public double getGyroRoll() { + double angle = g_gyro.getRoll(); + return angle; + } + + @Override + public void run() { + if (l_loggingRate.next()) { + gyroArray[0] = getGyroYaw(); + gyroArray[1] = getGyroPitch(); + gyroArray[2] = getGyroRoll(); + g_gyro.getYawPitchRoll(gyroArray); + log("Yaw: " + gyroArray[0] + "// Real yaw: " + getGyroYaw() + " || Pitch: " + gyroArray[1] + " || Roll: " + gyroArray[2]); + } + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/mechanisms/README b/src/main/java/com/team766/robot/mechanisms/README new file mode 100644 index 00000000..a6f5072f --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/README @@ -0,0 +1 @@ +Add mechanism classes here \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/DoNothing.java b/src/main/java/com/team766/robot/procedures/DoNothing.java new file mode 100644 index 00000000..566ad756 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/DoNothing.java @@ -0,0 +1,11 @@ +package com.team766.robot.procedures; + +import com.team766.framework.Context; +import com.team766.framework.Procedure; + +public class DoNothing extends Procedure { + + public void run(Context context) { + } + +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java new file mode 100644 index 00000000..f73f0e84 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -0,0 +1,188 @@ +package com.team766.robot.procedures; + +import com.team766.framework.Procedure; +import com.team766.framework.Context; +import com.team766.framework.LaunchedContext; +import com.team766.robot.Robot; +import com.team766.library.ValueProvider; +import com.team766.hal.RobotProvider; +import com.team766.odometry.Point; +import com.team766.odometry.PointDir; +import com.team766.hal.PositionReader; +import com.team766.config.ConfigFileReader; +import com.team766.logging.Category; +import com.team766.controllers.PIDController; + +public class FollowPoints extends Procedure { + private PointDir currentPos = new PointDir(0.0, 0.0, 0.0); + private Point[] pointList; + private Procedure[] proceduresAtPoints; + private static double radius = ConfigFileReader.getInstance().getDouble("trajectory.radius").get(); + private static double leniency = ConfigFileReader.getInstance().getDouble("trajectory.leniency").get(); + private static double speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); + private double finalHeader; + + public FollowPoints() { + parsePointList(); + proceduresAtPoints = new Procedure[pointList.length]; + for (int i = 0; i < proceduresAtPoints.length; i++) { + proceduresAtPoints[i] = new DoNothing(); + } + loggerCategory = Category.AUTONOMOUS; + } + + public FollowPoints(Procedure[] procedureList) { + parsePointList(); + proceduresAtPoints = procedureList; + loggerCategory = Category.AUTONOMOUS; + } + + public FollowPoints(Point[] points) { + pointList = points; + finalHeader = Robot.drive.getCurrentPosition().getHeading(); + proceduresAtPoints = new Procedure[pointList.length]; + for (int i = 0; i < proceduresAtPoints.length; i++) { + proceduresAtPoints[i] = new DoNothing(); + } + loggerCategory = Category.AUTONOMOUS; + } + + public FollowPoints(Point[] points, Procedure[] procedureList) { + pointList = points; + finalHeader = Robot.drive.getCurrentPosition().getHeading(); + proceduresAtPoints = procedureList; + loggerCategory = Category.AUTONOMOUS; + } + + //Takes pairs of points from pointDoubles (set in the config file) and converts them to Points, which are placed in pointList. + private void parsePointList() { + Double[] pointDoubles = ConfigFileReader.getInstance().getDoubles("trajectory.points").get(); + pointList = new Point[pointDoubles.length / 2]; + double pointX = 0; + double pointY = 0; + for (int i = 0; i < pointDoubles.length / 2 * 2; i++) { + if (i % 2 == 0) + pointX = pointDoubles[i]; + else { + pointY = pointDoubles[i]; + pointList[i / 2] = new Point(pointX, pointY); + } + } + if (pointDoubles.length % 2 == 1) { + finalHeader = pointDoubles[pointDoubles.length - 1]; + } else { + finalHeader = Robot.drive.getCurrentPosition().getHeading(); + } + + while (finalHeader > Math.round(Robot.drive.getCurrentPosition().getHeading() / 360) * 360 + 180) { + finalHeader -= 360; + } + while (finalHeader <= Math.round(Robot.drive.getCurrentPosition().getHeading() / 360) * 360 - 180) { + finalHeader += 360; + } + if (finalHeader - Robot.drive.getCurrentPosition().getHeading() >= 180) { + finalHeader -= 360; + } + if (finalHeader - Robot.drive.getCurrentPosition().getHeading() < -180) { + finalHeader += 360; + } + } + + public void run(Context context) { + speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); + context.takeOwnership(Robot.drive); + context.takeOwnership(Robot.gyro); + log("Starting FollowPoints"); + Robot.drive.resetCurrentPosition(); + Robot.gyro.resetGyro(); + for (int i = 0; i < pointList.length; i++) { + log(pointList[i].toString()); + } + if (pointList.length > 0) { + int targetNum = 0; + Point targetPoint = new Point(0.0, 0.0); + + currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); + while (currentPos.distance(pointList[pointList.length - 1]) > leniency || targetNum != pointList.length - 1) { + currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); + if (currentPos.distance(pointList[targetNum]) <= radius && checkIntersection(targetNum, currentPos, pointList, radius)) { + if (proceduresAtPoints.length < targetNum) { + context.startAsync(proceduresAtPoints[targetNum]); + } + targetNum++; + log("Going to Next Point!"); + } + targetPoint = selectTargetPoint(targetNum, currentPos, pointList, radius); + //double diff = currentPos.getAngleDifference(targetPoint); + //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); + + Robot.drive.setGyro(Robot.gyro.getGyroYaw()); + Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), 0)); + log("Current Position: " + currentPos.toString()); + log("Target Point: " + targetPoint.toString()); + log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), 0).toString()); + + context.yield(); + } + Robot.drive.drive2D(0, 0); + log("Finished method!"); + } else { + log("No points!"); + } + } + + //Returns whether the circle around the robot intersects the line connecting the two next points. + public static boolean checkIntersection(int targetNum, PointDir currentPos, Point[] pointList, double radius) { + double aValue; + double bValue; + double cValue; + double slope; + if (targetNum < pointList.length - 1) { + slope = pointList[targetNum].slope(pointList[targetNum + 1]); + aValue = slope * slope + 1; + bValue = -2 * currentPos.getX() - 2 * slope * slope * pointList[targetNum].getX() + 2 * slope * pointList[targetNum].getY() - 2 * currentPos.getY() * slope; + cValue = currentPos.getX() * currentPos.getX() + slope * slope * pointList[targetNum].getX() * pointList[targetNum].getX() - 2 * slope * pointList[targetNum].getX() * pointList[targetNum].getY() + pointList[targetNum].getY() * pointList[targetNum].getY() + 2 * currentPos.getY() * slope * pointList[targetNum].getX() - 2 * currentPos.getY() * pointList[targetNum].getY() + currentPos.getY() * currentPos.getY() - radius * radius; + if (bValue * bValue - 4 * aValue * cValue > 0) { + return true; + } + } + return false; + } + + //If the circle around the robot intersects the line connecting the previous and next points, returns whichever intersection point is closest to the next point. Otherwise, returns the next point. + public static Point selectTargetPoint(int targetNum, PointDir currentPos, Point[] pointList, double radius) { + double aValue; + double bValue; + double cValue; + double slope; + double potX1; + double potX2; + double potY1; + double potY2; + Point pot1 = new Point(0.0, 0.0); + Point pot2 = new Point(0.0, 0.0); + if (targetNum == 0) { + return pointList[0]; + } else { + slope = pointList[targetNum - 1].slope(pointList[targetNum]); + aValue = slope * slope + 1; + bValue = -2 * currentPos.getX() - 2 * slope * slope * pointList[targetNum - 1].getX() + 2 * slope * pointList[targetNum - 1].getY() - 2 * currentPos.getY() * slope; + cValue = currentPos.getX() * currentPos.getX() + slope * slope * pointList[targetNum - 1].getX() * pointList[targetNum - 1].getX() - 2 * slope * pointList[targetNum - 1].getX() * pointList[targetNum - 1].getY() + pointList[targetNum - 1].getY() * pointList[targetNum - 1].getY() + 2 * currentPos.getY() * slope * pointList[targetNum - 1].getX() - 2 * currentPos.getY() * pointList[targetNum - 1].getY() + currentPos.getY() * currentPos.getY() - radius * radius; + if (bValue * bValue - 4 * aValue * cValue < 0) { + return pointList[targetNum]; + } else { + potX1 = (-1 * bValue + Math.sqrt(bValue * bValue - 4 * aValue * cValue))/ (2 * aValue); + potX2 = (-1 * bValue - Math.sqrt(bValue * bValue - 4 * aValue * cValue))/ (2 * aValue); + potY1 = slope * (potX1 - pointList[targetNum - 1].getX()) + pointList[targetNum - 1].getY(); + potY2 = slope * (potX2 - pointList[targetNum - 1].getX()) + pointList[targetNum - 1].getY(); + pot1.set(potX1, potY1); + pot2.set(potX2, potY2); + if (pot1.distance(pointList[targetNum]) <= pot2.distance(pointList[targetNum])) { + return pot1; + } else { + return pot2; + } + } + } + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/README b/src/main/java/com/team766/robot/procedures/README new file mode 100644 index 00000000..fd6888a5 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/README @@ -0,0 +1 @@ +Add procedure classes here \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ElectricalSystem.java b/src/main/java/com/team766/simulator/ElectricalSystem.java new file mode 100644 index 00000000..398d497b --- /dev/null +++ b/src/main/java/com/team766/simulator/ElectricalSystem.java @@ -0,0 +1,35 @@ +package com.team766.simulator; + +import java.util.ArrayList; + +import com.team766.simulator.interfaces.ElectricalDevice; + +public class ElectricalSystem { + private double nominalVoltage = Parameters.BATTERY_VOLTAGE; + private double primaryResistance = Parameters.PRIMARY_ELECTRICAL_RESISTANCE; + + private ArrayList branchCircuits = new ArrayList(); + + private ElectricalDevice.Input systemState; + + public ElectricalSystem() { + systemState = new ElectricalDevice.Input(nominalVoltage); + } + + public void addDevice(ElectricalDevice device) { + branchCircuits.add(device); + } + + public void step() { + double current = 0.0; + for (ElectricalDevice device : branchCircuits) { + ElectricalDevice.Output deviceState = device.step(systemState); + current += deviceState.current; + } + systemState = new ElectricalDevice.Input(Math.max(0, nominalVoltage - primaryResistance * current)); + } + + public double getSystemVoltage() { + return systemState.voltage; + } +} diff --git a/src/main/java/com/team766/simulator/Parameters.java b/src/main/java/com/team766/simulator/Parameters.java new file mode 100644 index 00000000..0a226972 --- /dev/null +++ b/src/main/java/com/team766/simulator/Parameters.java @@ -0,0 +1,28 @@ +package com.team766.simulator; + +public class Parameters { + public static final double TIME_STEP = 0.001; // seconds + public static final double DURATION = 5.0; // seconds + + // Robot mode to run in the simulator + public static final ProgramInterface.RobotMode INITIAL_ROBOT_MODE = ProgramInterface.RobotMode.AUTON; + + public static final double BATTERY_VOLTAGE = 12.6; // volts + public static final double PRIMARY_ELECTRICAL_RESISTANCE = 0.018 + 0.01; // ohms + + public static final double STARTING_PRESSURE = 0; // pascals (relative); 120 psi = 827370.875 pascals + + public static final double DRIVE_WHEEL_DIAMETER = 0.1524; // 6 inches in meters + public static final double DRIVE_GEAR_RATIO = 8.0; + public static final int NUM_LOADED_WHEELS = 2; + public static final int ENCODER_TICKS_PER_REVOLUTION = 256; + + public static final double ROBOT_MASS = 66; // approx. 145 lbs in kg + public static final double ROBOT_LENGTH = 1.0; // meters + public static final double ROBOT_WIDTH = 0.8; // meters + public static final double ROBOT_MOMENT_OF_INERTIA = 1.0/12.0 * ROBOT_MASS * (ROBOT_WIDTH*ROBOT_WIDTH + ROBOT_LENGTH*ROBOT_LENGTH); + + public static final double WHEEL_COEFFICIENT_OF_FRICTION = 1.1; + public static final double ROLLING_RESISTANCE = 0.09; + public static final double TURNING_RESISTANCE_FACTOR = 0.15; +} diff --git a/src/main/java/com/team766/simulator/PhysicalConstants.java b/src/main/java/com/team766/simulator/PhysicalConstants.java new file mode 100644 index 00000000..bcba78d5 --- /dev/null +++ b/src/main/java/com/team766/simulator/PhysicalConstants.java @@ -0,0 +1,7 @@ +package com.team766.simulator; + +public class PhysicalConstants { + public static final double GRAVITY_ACCELERATION = 9.81; // m/s^2 + + public static final double ATMOSPHERIC_PRESSURE = 101325; // Pascals +} diff --git a/src/main/java/com/team766/simulator/PneumaticsSystem.java b/src/main/java/com/team766/simulator/PneumaticsSystem.java new file mode 100644 index 00000000..768b8aba --- /dev/null +++ b/src/main/java/com/team766/simulator/PneumaticsSystem.java @@ -0,0 +1,61 @@ +package com.team766.simulator; + +import java.util.ArrayList; + +import com.team766.simulator.interfaces.PneumaticDevice; + +public class PneumaticsSystem { + public static final double PSI_TO_PASCALS = 6894.75729; + + private static class BranchCircuit { + public PneumaticDevice device; + public double regulatedPressure; + } + + private ArrayList branchCircuits = new ArrayList(); + + private double systemPressure = Parameters.STARTING_PRESSURE; + private double compressedAirVolume = 0.0; + private boolean initialized = false; + + public void addDevice(PneumaticDevice device, double regulatedPressure) { + BranchCircuit circuit = new BranchCircuit(); + circuit.device = device; + circuit.regulatedPressure = regulatedPressure; + branchCircuits.add(circuit); + } + + public void step() { + double flowVolume = 0.0; + double systemVolume = 0.0; + for (BranchCircuit circuit : branchCircuits) { + double devicePressure = Math.min(circuit.regulatedPressure, systemPressure); + PneumaticDevice.Input inputState = new PneumaticDevice.Input(devicePressure); + PneumaticDevice.Output deviceState = circuit.device.step(inputState); + // TODO: implement relieving pressure regulator (make sure device pressure doesn't exceed + // circuit.regulatedPressure, even when including flow volume) + flowVolume += deviceState.flowVolume; + systemVolume += deviceState.deviceVolume; + } + compressedAirVolume += flowVolume; + if (systemVolume == 0.) { + throw new RuntimeException("Your pneumatics system has no storage volume"); + } + if (!initialized) { + compressedAirVolume = systemVolume * (systemPressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE; + initialized = true; + } + systemPressure = compressedAirVolume / systemVolume * PhysicalConstants.ATMOSPHERIC_PRESSURE - PhysicalConstants.ATMOSPHERIC_PRESSURE; + } + + public double getSystemPressure() { + return systemPressure; + } + + // Simulate the system venting all of its compressed air (e.g. someone opened the release valve; + // to simulate the pneumatics system becoming compromised, call this method on every simulation tick) + public void ventPressure() { + systemPressure = 0; + initialized = false; + } +} diff --git a/src/main/java/com/team766/simulator/Program.java b/src/main/java/com/team766/simulator/Program.java new file mode 100644 index 00000000..c83d2cb0 --- /dev/null +++ b/src/main/java/com/team766/simulator/Program.java @@ -0,0 +1,7 @@ +package com.team766.simulator; + +public interface Program { + public void step(); + + public void reset(); +} diff --git a/src/main/java/com/team766/simulator/ProgramInterface.java b/src/main/java/com/team766/simulator/ProgramInterface.java new file mode 100644 index 00000000..6f7aca38 --- /dev/null +++ b/src/main/java/com/team766/simulator/ProgramInterface.java @@ -0,0 +1,99 @@ +package com.team766.simulator; + +import java.lang.reflect.Array; +import com.team766.hal.mock.MockJoystick; + +public class ProgramInterface { + public static Program program = null; + + public static double simulationTime; + + public static int driverStationUpdateNumber = 0; + + public static enum RobotMode { + DISABLED, AUTON, TELEOP + } + + public static RobotMode robotMode = Parameters.INITIAL_ROBOT_MODE; + + public static final double[] pwmChannels = new double[20]; + + public static class CANMotorControllerCommand { + public enum ControlMode { + PercentOutput, + Position, + Velocity, + Current, + Follower, + MotionProfile, + MotionMagic, + MotionProfileArc, + Voltage, + Disabled, + } + + public double output; + public ControlMode controlMode; + } + public static class CANMotorControllerStatus { + public double sensorPosition; + public double sensorVelocity; + } + public static class CANMotorControllerCommunication { + public final CANMotorControllerCommand command = new CANMotorControllerCommand(); + public final CANMotorControllerStatus status = new CANMotorControllerStatus(); + } + + public static final CANMotorControllerCommunication[] canMotorControllerChannels = + initializeArray(256, CANMotorControllerCommunication.class); + + public static final double[] analogChannels = new double[20]; + + public static final boolean[] digitalChannels = new boolean[20]; + + public static final int[] relayChannels = new int[20]; + + public static final boolean[] solenoidChannels = new boolean[20]; + + public static class EncoderChannel { + public long distance = 0; + public double rate = 0; + } + + public static final EncoderChannel[] encoderChannels = + initializeArray(20, EncoderChannel.class); + + public static class GyroCommunication { + public double angle; // Yaw angle (accumulative) + public double rate; // Yaw rate + public double pitch; + public double roll; + } + + public static final GyroCommunication gyro = new GyroCommunication(); + + public static class RobotPosition { + public double x; + public double y; + public double heading; + } + + public static final RobotPosition robotPosition = new RobotPosition(); + + public static final MockJoystick[] joystickChannels = + initializeArray(6, MockJoystick.class); + + + private static E[] initializeArray(int size, Class clazz) { + @SuppressWarnings("unchecked") + E[] array = (E[]) Array.newInstance(clazz, size); + for (int i = 0; i < size; ++i) { + try { + array[i] = clazz.getConstructor().newInstance(); + } catch (Throwable e) { + throw new ExceptionInInitializerError(e); + } + } + return array; + } +} diff --git a/src/main/java/com/team766/simulator/Simulator.java b/src/main/java/com/team766/simulator/Simulator.java new file mode 100644 index 00000000..792ae667 --- /dev/null +++ b/src/main/java/com/team766/simulator/Simulator.java @@ -0,0 +1,82 @@ +package com.team766.simulator; + +import java.util.ArrayList; + +import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; +import org.apache.commons.math3.geometry.euclidean.threed.RotationOrder; + +import com.team766.simulator.elements.AirCompressor; +import com.team766.simulator.elements.AirReservoir; +import com.team766.simulator.mechanisms.WestCoastDrive; +import com.team766.simulator.ui.Metrics; +import com.team766.simulator.ui.Trajectory; + +public class Simulator implements Runnable { + private ElectricalSystem electricalSystem = new ElectricalSystem(); + private PneumaticsSystem pneumaticsSystem = new PneumaticsSystem(); + private WestCoastDrive drive = new WestCoastDrive(electricalSystem); + private AirCompressor compressor = new AirCompressor(); + + private double time; + private ArrayList metrics = new ArrayList(); + private ArrayList trajectory = new ArrayList(); + + public Simulator() { + electricalSystem.addDevice(compressor); + pneumaticsSystem.addDevice(compressor, 120 * PneumaticsSystem.PSI_TO_PASCALS); + pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL + pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL + } + + public void step() { + time += Parameters.TIME_STEP; + ProgramInterface.simulationTime = time; + + electricalSystem.step(); + pneumaticsSystem.step(); + drive.step(); + + if (ProgramInterface.program != null) { + ProgramInterface.program.step(); + } + + metrics.add(new Double[] { + time, + drive.getPosition().getX(), + drive.getPosition().getY(), + Math.toDegrees(drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2]), + drive.getLinearVelocity().getX(), + drive.getLinearAcceleration().getX(), + electricalSystem.getSystemVoltage(), + pneumaticsSystem.getSystemPressure() / PneumaticsSystem.PSI_TO_PASCALS, + }); + trajectory.add(new Double[] { + drive.getPosition().getX(), + drive.getPosition().getY(), + drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2], + drive.getLinearVelocity().getX(), + drive.getLinearVelocity().getY(), + }); + } + + public void run() { + metrics.clear(); + time = 0.0; + while (time <= Parameters.DURATION) { + step(); + if (Math.abs(time - 3.0) < Parameters.TIME_STEP) { + pneumaticsSystem.ventPressure(); + } + } + Trajectory.makePlotFrame(trajectory); + Metrics.makePlotFrame(metrics, new String[] { + "X Position (m)", + "Y Position (m)", + "Rotation (deg)", + "Velocity (m/s)", + "Acceleration (m/s^2)", + "System Voltage (V)", + "System Pressure (PSI)", + }); + } +} diff --git a/src/main/java/com/team766/simulator/elements/AirCompressor.java b/src/main/java/com/team766/simulator/elements/AirCompressor.java new file mode 100644 index 00000000..febca8b3 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/AirCompressor.java @@ -0,0 +1,56 @@ +package com.team766.simulator.elements; + +import java.util.Arrays; + +import org.apache.commons.math3.analysis.interpolation.LinearInterpolator; +import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction; + +import com.team766.simulator.Parameters; +import com.team766.simulator.PneumaticsSystem; +import com.team766.simulator.interfaces.ElectricalDevice; +import com.team766.simulator.interfaces.PneumaticDevice; + +public class AirCompressor implements ElectricalDevice, PneumaticDevice { + private static final double CFM_TO_M3_PER_SEC = 0.000471947443; + + // Values for http://www.andymark.com/product-p/am-2005.htm + private static final double NOMINAL_VOLTAGE = 12; + private static final double[] PRESSURES_PSI = { 0., 10., 20., 30., 40., 50., 60., 70., 80., 90., 100., 110. }; + private static final double[] FLOW_RATES_CFM = { 0.88, 0.50, 0.43, 0.36, 0.30, 0.27, 0.25, 0.24, 0.24, 0.23, 0.22, 0.22 }; + private static final double[] CURRENTS = { 7., 8., 8., 9., 9., 9., 10., 10., 10., 11., 11., 10. }; + private static final double[] PRESSURES = Arrays.stream(PRESSURES_PSI).map(psi -> psi * PneumaticsSystem.PSI_TO_PASCALS).toArray(); + private static final double[] FLOW_RATES = Arrays.stream(FLOW_RATES_CFM).map(cfm -> cfm * CFM_TO_M3_PER_SEC).toArray(); + + PolynomialSplineFunction currentFunction = new LinearInterpolator().interpolate(PRESSURES, CURRENTS); + PolynomialSplineFunction flowRateFunction = new LinearInterpolator().interpolate(PRESSURES, FLOW_RATES); + + private boolean isOn = true; + + private ElectricalDevice.Input electricalState = new ElectricalDevice.Input(0); + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); + + public void setIsOn(boolean on) { + isOn = on; + } + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + electricalState = input; + if (isOn) { + double nominalCurrent = currentFunction.value(pneumaticState.pressure); + double adjustedCurrent = nominalCurrent * electricalState.voltage / NOMINAL_VOLTAGE; + return new ElectricalDevice.Output(adjustedCurrent); + } else { + return new ElectricalDevice.Output(0); + } + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + pneumaticState = input; + double nominalFlowRate = flowRateFunction.value(pneumaticState.pressure); + double adjustedFlowRate = nominalFlowRate * electricalState.voltage / NOMINAL_VOLTAGE; + double flowVolume = adjustedFlowRate * Parameters.TIME_STEP; + return new PneumaticDevice.Output(flowVolume, 0); + } +} diff --git a/src/main/java/com/team766/simulator/elements/AirReservoir.java b/src/main/java/com/team766/simulator/elements/AirReservoir.java new file mode 100644 index 00000000..0faf6870 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/AirReservoir.java @@ -0,0 +1,17 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.PneumaticDevice; + +public class AirReservoir implements PneumaticDevice { + + private double volume; + + public AirReservoir(double volume) { + this.volume = volume; + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + return new PneumaticDevice.Output(0, volume); + } +} diff --git a/src/main/java/com/team766/simulator/elements/CanMotorController.java b/src/main/java/com/team766/simulator/elements/CanMotorController.java new file mode 100644 index 00000000..685e8ca1 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/CanMotorController.java @@ -0,0 +1,21 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.interfaces.ElectricalDevice; + +public class CanMotorController extends MotorController { + + private int address; + + public CanMotorController(int address, ElectricalDevice downstream) { + super(downstream); + + this.address = address; + } + + @Override + protected double getCommand() { + return ProgramInterface.canMotorControllerChannels[address].command.output; + } + +} diff --git a/src/main/java/com/team766/simulator/elements/DCMotor.java b/src/main/java/com/team766/simulator/elements/DCMotor.java new file mode 100644 index 00000000..5cb95ba5 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/DCMotor.java @@ -0,0 +1,49 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.ElectricalDevice; +import com.team766.simulator.interfaces.MechanicalAngularDevice; + +public class DCMotor implements ElectricalDevice, MechanicalAngularDevice { + // TODO: Add rotor inertia + // TODO: Add thermal effects + + public static DCMotor makeCIM() { + return new DCMotor(46.513, 0.018397, 0.091603053435115); + } + public static DCMotor make775Pro() { + return new DCMotor(163.450, 0.0052985, 0.08955223880597); + } + + // Motor velocity constant in radian/second/volt + // (motor velocity) = kV * (motor voltage) + private final double kV; + + // Motor torque constant in newton-meter/ampere + // (motor torque) = kT * (motor current) + private final double kT; + + // Motor resistance is calculated as 12V / (stall current at 12V) + private final double motorResistance; + + private ElectricalDevice.Output electricalState = new ElectricalDevice.Output(0); + private MechanicalAngularDevice.Input mechanicalState = new MechanicalAngularDevice.Input(0); + + public DCMotor(double kV, double kT, double motorResistance) { + this.kV = kV; + this.kT = kT; + this.motorResistance = motorResistance; + } + + @Override + public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + mechanicalState = new MechanicalAngularDevice.Input(input); + + return new MechanicalAngularDevice.Output(kT * electricalState.current); + } + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + electricalState = new ElectricalDevice.Output((input.voltage - mechanicalState.angularVelocity / kV) / motorResistance); + return electricalState; + } +} diff --git a/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java new file mode 100644 index 00000000..bf6295c0 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java @@ -0,0 +1,52 @@ +package com.team766.simulator.elements; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.interfaces.MechanicalDevice; +import com.team766.simulator.interfaces.PneumaticDevice; + +public class DoubleActingPneumaticCylinder implements PneumaticDevice, MechanicalDevice { + private static final Vector3D FORWARD = new Vector3D(1, 0, 0); + + private final double boreDiameter; + private final double stroke; + + private boolean isExtended = false; + private boolean commandExtended = false; + + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); + + public DoubleActingPneumaticCylinder(double boreDiameter, double stroke) { + this.boreDiameter = boreDiameter; + this.stroke = stroke; + } + + public void setExtended(boolean state) { + commandExtended = state; + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + pneumaticState = input; + PneumaticDevice.Output output; + double deviceVolume = boreArea() * stroke; + if (commandExtended != isExtended) { + output = new PneumaticDevice.Output(-deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE, deviceVolume); + } else { + output = new PneumaticDevice.Output(0, deviceVolume); + } + isExtended = commandExtended; + return output; + } + + @Override + public MechanicalDevice.Output step(MechanicalDevice.Input input) { + Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); + return new MechanicalDevice.Output(direction.scalarMultiply(boreArea() * pneumaticState.pressure)); + } + + private double boreArea() { + return Math.PI * Math.pow(boreDiameter / 2., 2); + } +} diff --git a/src/main/java/com/team766/simulator/elements/DriveBase.java b/src/main/java/com/team766/simulator/elements/DriveBase.java new file mode 100644 index 00000000..9dff5032 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/DriveBase.java @@ -0,0 +1,4 @@ +package com.team766.simulator.elements; + +public class DriveBase { +} diff --git a/src/main/java/com/team766/simulator/elements/ElectricalResistance.java b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java new file mode 100644 index 00000000..c4d3a621 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java @@ -0,0 +1,35 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.ElectricalDevice; + +public class ElectricalResistance implements ElectricalDevice { + // Wire AWG -> Ohms/m (copper) + // http://www.daycounter.com/Calculators/AWG.phtml + private static double[] WIRE_RESISTANCE_PER_M = new double[] { + 0.000323, 0.000407, 0.000513, 0.000647, 0.000815, 0.00103, 0.00130, 0.00163, 0.00206, 0.00260, // 0-9 + 0.00328, 0.00413, 0.00521, 0.00657, 0.00829, 0.0104, 0.0132, 0.0166, 0.0210, 0.0264, // 10-19 + 0.0333, 0.0420, 0.0530, 0.0668, 0.0842, 0.106, 0.134, 0.169, 0.213, 0.268, // 20-29 + 0.339, 0.427, 0.538, 0.679, 0.856, 1.08, 1.36, 1.72, 2.16, 2.73, 3.44, // 30-40 + }; + public static ElectricalResistance makeWires(int awg, double length, ElectricalDevice downstream) { + return new ElectricalResistance(WIRE_RESISTANCE_PER_M[awg] * length / 1000., downstream); + } + + private final double resistance; + + private ElectricalDevice downstream; + + private ElectricalDevice.Output state; + + public ElectricalResistance(double resistance, ElectricalDevice downstream) { + this.resistance = resistance; + this.downstream = downstream; + } + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage - resistance * state.current); + state = downstream.step(downstreamInput); + return state; + } +} diff --git a/src/main/java/com/team766/simulator/elements/Gears.java b/src/main/java/com/team766/simulator/elements/Gears.java new file mode 100644 index 00000000..220b00dc --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/Gears.java @@ -0,0 +1,26 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.MechanicalAngularDevice; + +public class Gears implements MechanicalAngularDevice { + // TODO: Add rotational inertia + // TODO: Add losses + + // Torque ratio (output / input) + private final double torqueRatio; + + private MechanicalAngularDevice upstream; + + public Gears(double torqueRatio, MechanicalAngularDevice upstream) { + this.torqueRatio = torqueRatio; + this.upstream = upstream; + } + + @Override + public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + MechanicalAngularDevice.Input upstreamInput = + new MechanicalAngularDevice.Input(input.angularVelocity * torqueRatio); + MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); + return new MechanicalAngularDevice.Output(upstreamOutput.torque * torqueRatio); + } +} diff --git a/src/main/java/com/team766/simulator/elements/MotorController.java b/src/main/java/com/team766/simulator/elements/MotorController.java new file mode 100644 index 00000000..d837e20a --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/MotorController.java @@ -0,0 +1,22 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.interfaces.ElectricalDevice; + +public abstract class MotorController implements ElectricalDevice { + private ElectricalDevice downstream; + + public MotorController(ElectricalDevice downstream) { + this.downstream = downstream; + } + + // [-1, 1] representing the command sent from the application processor + protected abstract double getCommand(); + + @Override + public ElectricalDevice.Output step(ElectricalDevice.Input input) { + double command = getCommand(); + ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage * command); + ElectricalDevice.Output downstreamOutput = downstream.step(downstreamInput); + return new Output(downstreamOutput.current * Math.signum(command)); + } +} diff --git a/src/main/java/com/team766/simulator/elements/PwmMotorController.java b/src/main/java/com/team766/simulator/elements/PwmMotorController.java new file mode 100644 index 00000000..a0791220 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/PwmMotorController.java @@ -0,0 +1,21 @@ +package com.team766.simulator.elements; + +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.interfaces.ElectricalDevice; + +public class PwmMotorController extends MotorController { + + private int channel; + + public PwmMotorController(int channel, ElectricalDevice downstream) { + super(downstream); + + this.channel = channel; + } + + @Override + protected double getCommand() { + return ProgramInterface.pwmChannels[channel]; + } + +} diff --git a/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java new file mode 100644 index 00000000..a8263dbf --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java @@ -0,0 +1,55 @@ +package com.team766.simulator.elements; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.interfaces.MechanicalDevice; +import com.team766.simulator.interfaces.PneumaticDevice; + +public class SingleActingPneumaticCylinder implements PneumaticDevice, MechanicalDevice { + private static final Vector3D FORWARD = new Vector3D(1, 0, 0); + + private final double boreDiameter; + private final double stroke; + private final double returnSpringForce; + + private boolean isExtended = false; + private boolean commandExtended = false; + + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); + + public SingleActingPneumaticCylinder(double boreDiameter, double stroke, double returnSpringForce) { + this.boreDiameter = boreDiameter; + this.stroke = stroke; + this.returnSpringForce = returnSpringForce; + } + + public void setExtended(boolean state) { + commandExtended = state; + } + + @Override + public PneumaticDevice.Output step(PneumaticDevice.Input input) { + pneumaticState = input; + PneumaticDevice.Output output; + double deviceVolume = isExtended ? boreArea() * stroke : 0; + if (isExtended && !commandExtended) { + output = new PneumaticDevice.Output(-deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE, deviceVolume); + } else { + output = new PneumaticDevice.Output(0, deviceVolume); + } + isExtended = commandExtended; + return output; + } + + @Override + public MechanicalDevice.Output step(MechanicalDevice.Input input) { + Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); + double force = isExtended ? boreArea() * pneumaticState.pressure : returnSpringForce; + return new MechanicalDevice.Output(direction.scalarMultiply(force)); + } + + private double boreArea() { + return Math.PI * Math.pow(boreDiameter / 2., 2); + } +} diff --git a/src/main/java/com/team766/simulator/elements/Wheel.java b/src/main/java/com/team766/simulator/elements/Wheel.java new file mode 100644 index 00000000..1f6efc18 --- /dev/null +++ b/src/main/java/com/team766/simulator/elements/Wheel.java @@ -0,0 +1,40 @@ +package com.team766.simulator.elements; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.Parameters; +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.interfaces.MechanicalAngularDevice; +import com.team766.simulator.interfaces.MechanicalDevice; + +// Simulate a wheel revolving around the positive Y axis. +public class Wheel implements MechanicalDevice { + // TODO: Add transverse friction + // TODO: Add traction limit/wheel slip (static vs kinetic friction) + // TODO: Add rotational inertia + + private static final Vector3D FORWARD = new Vector3D(-1, 0, 0); + + // Diameter of the wheel in meters + private final double diameter; + + private MechanicalAngularDevice upstream; + + public Wheel(double diameter, MechanicalAngularDevice upstream) { + this.diameter = diameter; + this.upstream = upstream; + } + + @Override + public MechanicalDevice.Output step(MechanicalDevice.Input input) { + MechanicalAngularDevice.Input upstreamInput = + new MechanicalAngularDevice.Input(FORWARD.dotProduct(input.velocity) * 2. / diameter); + MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); + double appliedForce = upstreamOutput.torque * 2. / diameter; + double maxFriction = Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION / Parameters.NUM_LOADED_WHEELS; + if (Math.abs(appliedForce) > maxFriction) { + appliedForce = Math.signum(appliedForce) * maxFriction; + } + return new MechanicalDevice.Output(FORWARD.scalarMultiply(appliedForce)); + } +} diff --git a/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java new file mode 100644 index 00000000..f4472268 --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java @@ -0,0 +1,27 @@ +package com.team766.simulator.interfaces; + +public interface ElectricalDevice { + public class Input { + public Input(double voltage) { + this.voltage = voltage; + } + public Input(Input other) { + voltage = other.voltage; + } + + public final double voltage; + } + + public class Output { + public Output(double current) { + this.current = current; + } + public Output(Output other) { + current = other.current; + } + + public final double current; + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java new file mode 100644 index 00000000..a3ea3526 --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java @@ -0,0 +1,27 @@ +package com.team766.simulator.interfaces; + +public interface MechanicalAngularDevice { + public class Input { + public Input(double angularVelocity) { + this.angularVelocity = angularVelocity; + } + public Input(Input other) { + this.angularVelocity = other.angularVelocity; + } + + public final double angularVelocity; + } + + public class Output { + public Output(double torque) { + this.torque = torque; + } + public Output(Output other) { + this.torque = other.torque; + } + + public final double torque; + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java new file mode 100644 index 00000000..c943b093 --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java @@ -0,0 +1,32 @@ +package com.team766.simulator.interfaces; + +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +public interface MechanicalDevice { + public class Input { + public Input(Vector3D position, Vector3D velocity) { + this.position = position; + this.velocity = velocity; + } + public Input(Input other) { + position = other.position; + velocity = other.velocity; + } + + public final Vector3D position; + public final Vector3D velocity; + } + + public class Output { + public Output(Vector3D force) { + this.force = force; + } + public Output(Output other) { + force = other.force; + } + + public final Vector3D force; + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java new file mode 100644 index 00000000..72a0fc4a --- /dev/null +++ b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java @@ -0,0 +1,40 @@ +package com.team766.simulator.interfaces; + +public interface PneumaticDevice { + public class Input { + public Input(double pressure) { + this.pressure = pressure; + } + public Input(Input other) { + pressure = other.pressure; + } + + // Pascals (relative pressure) + public final double pressure; + } + + public class Output { + public Output(double flowVolume, double deviceVolume) { + this.flowVolume = flowVolume; + this.deviceVolume = deviceVolume; + } + public Output(Output other) { + flowVolume = other.flowVolume; + deviceVolume = other.deviceVolume; + } + + // Volumetric flow (delta m^3 at atmospheric pressure) + // Positive flow is into the system, e.g. from a compressor + // Negative flow is out of the system, e.g. from venting to atmosphere + public final double flowVolume; + + // Volume of air that the device contains (m^3) + public final double deviceVolume; + + // Note that an expanding volume (such as a cylinder expanding) + // should increase volume, but have 0 flow volume because no + // pressurized air is actually leaving the system. + } + + public Output step(Input input); +} diff --git a/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java new file mode 100644 index 00000000..25a4de82 --- /dev/null +++ b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java @@ -0,0 +1,147 @@ +package com.team766.simulator.mechanisms; + +import org.apache.commons.math3.geometry.euclidean.threed.Rotation; +import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; +import org.apache.commons.math3.geometry.euclidean.threed.RotationOrder; +import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; + +import com.team766.simulator.ElectricalSystem; +import com.team766.simulator.Parameters; +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.ProgramInterface; +import com.team766.simulator.elements.DCMotor; +import com.team766.simulator.elements.DriveBase; +import com.team766.simulator.elements.Gears; +import com.team766.simulator.elements.PwmMotorController; +import com.team766.simulator.elements.MotorController; +import com.team766.simulator.elements.Wheel; +import com.team766.simulator.interfaces.MechanicalDevice; + +public class WestCoastDrive extends DriveBase { + private DCMotor leftMotor = DCMotor.makeCIM(); + private DCMotor rightMotor = DCMotor.makeCIM(); + + private MotorController leftController = new PwmMotorController(6, leftMotor); + private MotorController rightController = new PwmMotorController(4, rightMotor); + + private Gears leftGears = new Gears(Parameters.DRIVE_GEAR_RATIO, leftMotor); + private Gears rightGears = new Gears(Parameters.DRIVE_GEAR_RATIO, rightMotor); + + private Wheel leftWheels = new Wheel(Parameters.DRIVE_WHEEL_DIAMETER, leftGears); + private static final Vector3D LEFT_WHEEL_POSITION = new Vector3D(0., 0.3302, 0.); + private Wheel rightWheels = new Wheel(Parameters.DRIVE_WHEEL_DIAMETER, rightGears); + private static final Vector3D RIGHT_WHEEL_POSITION = new Vector3D(0., -0.3302, 0.); + private static final double WHEEL_BASE = 0.585; + private static final double ENCODER_TICKS_PER_METER = Parameters.ENCODER_TICKS_PER_REVOLUTION / (Parameters.DRIVE_WHEEL_DIAMETER * Math.PI); + + private Vector3D robotPosition = Vector3D.ZERO; + private Rotation robotRotation = Rotation.IDENTITY; + private Vector3D linearVelocity = Vector3D.ZERO; + private Vector3D angularVelocity = Vector3D.ZERO; + private Vector3D linearAcceleration = Vector3D.ZERO; + private Vector3D angularAcceleration = Vector3D.ZERO; + + private double leftEncoderResidual = 0; + private double rightEncoderResidual = 0; + + public WestCoastDrive(ElectricalSystem electricalSystem) { + electricalSystem.addDevice(leftController); + electricalSystem.addDevice(rightController); + } + + private static double softSignum(double x) { + x /= 0.01; + if (x > 1.0) { + x = 1.0; + } else if (x < -1.0) { + x = -1.0; + } + return x; + } + + public void step() { + Vector3D wheelForce; + Vector3D netForce = Vector3D.ZERO; + Vector3D netTorque = Vector3D.ZERO; + MechanicalDevice.Input leftWheelInput = new MechanicalDevice.Input( + LEFT_WHEEL_POSITION, + linearVelocity.scalarMultiply(-1.)); + wheelForce = leftWheels.step(leftWheelInput).force.scalarMultiply(-1.0); + netForce = netForce.add(wheelForce); + netTorque = netTorque.add(Vector3D.crossProduct(LEFT_WHEEL_POSITION, wheelForce)); + MechanicalDevice.Input rightWheelInput = new MechanicalDevice.Input( + RIGHT_WHEEL_POSITION, + linearVelocity.scalarMultiply(-1.)); + wheelForce = rightWheels.step(rightWheelInput).force.scalarMultiply(-1.0); + netForce = netForce.add(wheelForce); + netTorque = netTorque.add(Vector3D.crossProduct(RIGHT_WHEEL_POSITION, wheelForce)); + + Vector3D ego_velocity = robotRotation.applyInverseTo(linearVelocity); + + double rateLeft = ENCODER_TICKS_PER_METER * (ego_velocity.getX() - angularVelocity.getZ() * LEFT_WHEEL_POSITION.getNorm()); + double rateRight = ENCODER_TICKS_PER_METER * (ego_velocity.getX() + angularVelocity.getZ() * RIGHT_WHEEL_POSITION.getNorm()); + leftEncoderResidual += rateLeft * Parameters.TIME_STEP; + rightEncoderResidual += rateRight * Parameters.TIME_STEP; + ProgramInterface.encoderChannels[0].distance += (long)leftEncoderResidual; + ProgramInterface.encoderChannels[0].rate = rateLeft; + ProgramInterface.encoderChannels[2].distance += (long)rightEncoderResidual; + ProgramInterface.encoderChannels[2].rate = rateRight; + leftEncoderResidual %= 1; + rightEncoderResidual %= 1; + + ProgramInterface.gyro.angle = Math.toDegrees(robotRotation.getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2]); + ProgramInterface.gyro.rate = Math.toDegrees(angularVelocity.getZ()); + + Vector3D rollingResistance = new Vector3D(-softSignum(ego_velocity.getX()), 0.0, 0.0).scalarMultiply( + Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION * Parameters.ROLLING_RESISTANCE); + netForce = netForce.add(rollingResistance); + + Vector3D transverseFriction = new Vector3D(0., -softSignum(ego_velocity.getY()), 0.).scalarMultiply( + Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION); + netForce = netForce.add(transverseFriction); + + double maxFriction = Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION * Parameters.TURNING_RESISTANCE_FACTOR; + netTorque = netTorque.add( + new Vector3D(0, 0, -softSignum(angularVelocity.getZ())).scalarMultiply( + maxFriction * WHEEL_BASE / 2)); + + linearAcceleration = robotRotation.applyTo(netForce).scalarMultiply(1.0 / Parameters.ROBOT_MASS); + linearVelocity = linearVelocity.add(linearAcceleration.scalarMultiply(Parameters.TIME_STEP)); + robotPosition = robotPosition.add(linearVelocity.scalarMultiply(Parameters.TIME_STEP)); + + angularAcceleration = netTorque.scalarMultiply(1.0 / Parameters.ROBOT_MOMENT_OF_INERTIA); + angularVelocity = angularVelocity.add(angularAcceleration.scalarMultiply(Parameters.TIME_STEP)); + Vector3D angularDelta = angularVelocity.scalarMultiply(Parameters.TIME_STEP); + robotRotation = robotRotation.compose( + new Rotation(RotationOrder.XYZ, + RotationConvention.VECTOR_OPERATOR, + angularDelta.getX(), + angularDelta.getY(), + angularDelta.getZ()), + RotationConvention.VECTOR_OPERATOR); + } + + public Vector3D getPosition() { + return robotPosition; + } + + public Rotation getRotation() { + return robotRotation; + } + + public Vector3D getLinearVelocity() { + return linearVelocity; + } + + public Vector3D getAngularVelocity() { + return angularVelocity; + } + + public Vector3D getLinearAcceleration() { + return linearAcceleration; + } + + public Vector3D getAngularAcceleration() { + return angularAcceleration; + } +} diff --git a/src/main/java/com/team766/simulator/ui/Metrics.java b/src/main/java/com/team766/simulator/ui/Metrics.java new file mode 100644 index 00000000..2615c6ea --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/Metrics.java @@ -0,0 +1,160 @@ +package com.team766.simulator.ui; + +import java.awt.BorderLayout; +import java.awt.Color; +import java.awt.event.ActionEvent; +import java.awt.event.ActionListener; +import java.awt.event.KeyEvent; +import java.awt.event.KeyListener; +import java.awt.event.MouseAdapter; +import java.awt.event.MouseEvent; +import java.util.Arrays; +import java.util.Collection; + +import javax.swing.JFrame; +import javax.swing.JPanel; +import javax.swing.JSlider; +import javax.swing.Timer; + +import com.team766.simulator.Parameters; + +import de.erichseifert.gral.data.DataSeries; +import de.erichseifert.gral.data.DataSource; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; +import de.erichseifert.gral.plots.lines.DefaultLineRenderer2D; +import de.erichseifert.gral.plots.lines.LineRenderer; +import de.erichseifert.gral.ui.InteractivePanel; + +@SuppressWarnings("serial") +public class Metrics extends JPanel { + // Color palette from http://www.mulinblog.com/a-color-palette-optimized-for-data-visualization/ + private static final String[] COLORS = { + "#4D4D4D", // gray + "#5DA5DA", // blue + "#FAA43A", // orange + "#60BD68", // green + "#F17CB0", // pink + "#B2912F", // brown + "#B276B2", // purple + "#DECF3F", // yellow + "#F15854", // red + }; + + private static class Inspector extends MouseAdapter implements KeyListener { + private int sourceIndex = 0; + private double selectedTime = Double.NaN; + private XYPlot plot; + + public Inspector(XYPlot plot) { + this.plot = plot; + } + + void update() { + if (!Double.isNaN(selectedTime)) { + DataSource source = plot.getData().get(sourceIndex); + int index = Arrays.binarySearch(source.getColumn(0).toArray(null), selectedTime); + if (index < 0) { + index = -index - 1; + } + System.out.println(String.format("(%s, %f): %f", source.getName(), selectedTime, source.get(1, index))); + } + } + + @Override + public void mouseClicked(MouseEvent e) { + double x = e.getX() - plot.getPlotArea().getX(); + selectedTime = plot.getAxisRenderer(XYPlot.AXIS_X).viewToWorld(plot.getAxis(XYPlot.AXIS_X), x, false).doubleValue(); + + update(); + } + + @Override + public void keyTyped(KeyEvent e) { + if (e.getKeyChar() >= '1' && e.getKeyChar() <= '9') { + int index = e.getKeyChar() - '1'; + if (index < plot.getData().size()) { + sourceIndex = index; + System.out.println("Selected " + plot.getData().get(sourceIndex).getName()); + update(); + } + } + } + + @Override + public void keyReleased(KeyEvent e) {} + + @Override + public void keyPressed(KeyEvent e) {} + } + + public static JFrame makePlotFrame(Collection series, String[] labels) { + JFrame frame = new JFrame(); + frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); + frame.setSize(800, 600); + frame.setContentPane(new Metrics(series, labels)); + frame.setVisible(true); + return frame; + } + + XYPlot plot; + JSlider slider; + DataTable data; + JPanel plotPanel; + Timer playbackTimer; + + public Metrics(Collection series, String[] labels) { + Double[] first = series.iterator().next(); + @SuppressWarnings("unchecked") + Class[] types = new Class[first.length]; + Arrays.fill(types, Double.class); + data = new DataTable(types); + for (Double[] values : series) { + if (first.length != values.length) { + throw new IllegalArgumentException("Data values must be the same length"); + } + data.add(values); + } + if (first.length - 1 != labels.length) { + throw new IllegalArgumentException("Number of labels does not match the size of data values"); + } + DataSource[] sources = new DataSource[labels.length]; + for (int i = 0; i < labels.length; ++i) { + sources[i] = new DataSeries(labels[i], data, 0, i + 1); + } + plot = new XYPlot(sources); + int colorIndex = 0; + for (DataSource source : sources) { + LineRenderer lines = new DefaultLineRenderer2D(); + plot.setLineRenderers(source, lines); + Color color = Color.decode(COLORS[colorIndex++ % COLORS.length]); + plot.getPointRenderers(source).get(0).setColor(color); + plot.getLineRenderers(source).get(0).setColor(color); + } + plot.setLegendVisible(true); + + InteractivePanel panel = new InteractivePanel(plot); + plotPanel = panel; + setLayout(new BorderLayout()); + add(panel, BorderLayout.CENTER); + + final int TIMER_PERIOD_MS = 50; + playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; + int newValue = slider.getValue() + (int)deltaSteps; + if (newValue > slider.getMaximum()) { + newValue = slider.getMaximum(); + playbackTimer.stop(); + } + slider.setValue(newValue); + } + }); + playbackTimer.setRepeats(true); + + Inspector inspector = new Inspector(plot); + addKeyListener(inspector); + panel.addMouseListener(inspector); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ui/Trajectory.java b/src/main/java/com/team766/simulator/ui/Trajectory.java new file mode 100644 index 00000000..bc97b9fe --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/Trajectory.java @@ -0,0 +1,143 @@ +package com.team766.simulator.ui; + +import java.awt.BorderLayout; +import java.awt.Color; +import java.awt.Graphics; +import java.awt.Graphics2D; +import java.awt.event.ActionEvent; +import java.awt.event.ActionListener; +import java.awt.geom.AffineTransform; +import java.util.Arrays; +import java.util.Collection; + +import javax.swing.BoxLayout; +import javax.swing.JButton; +import javax.swing.JFrame; +import javax.swing.JPanel; +import javax.swing.JSlider; +import javax.swing.Timer; +import javax.swing.event.ChangeEvent; +import javax.swing.event.ChangeListener; + +import com.team766.simulator.Parameters; + +import de.erichseifert.gral.data.DataSeries; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; +import de.erichseifert.gral.ui.InteractivePanel; + +@SuppressWarnings("serial") +public class Trajectory extends JPanel { + public static JFrame makePlotFrame(Collection series) { + JFrame frame = new JFrame(); + frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); + frame.setSize(800, 600); + frame.setContentPane(new Trajectory(series)); + frame.setVisible(true); + return frame; + } + + XYPlot plot; + JSlider slider; + DataTable data; + JPanel plotPanel; + Timer playbackTimer; + + public Trajectory(Collection series) { + Double[] first = series.iterator().next(); + @SuppressWarnings("unchecked") + Class[] types = new Class[first.length]; + Arrays.fill(types, Double.class); + data = new DataTable(types); + for (Double[] values : series) { + if (first.length != values.length) { + throw new IllegalArgumentException("Data values must be the same length"); + } + data.add(values); + } + plot = new XYPlot(new DataSeries("Trajectory", data, 0, 1)); + plot.getAxis(XYPlot.AXIS_X).setRange(-10.0, 10.0); + plot.getAxis(XYPlot.AXIS_Y).setRange(-10.0, 10.0); + + InteractivePanel panel = new InteractivePanel(plot); + plotPanel = panel; + setLayout(new BorderLayout()); + add(panel, BorderLayout.CENTER); + + final int TIMER_PERIOD_MS = 50; + playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; + int newValue = slider.getValue() + (int)deltaSteps; + if (newValue > slider.getMaximum()) { + newValue = slider.getMaximum(); + playbackTimer.stop(); + } + slider.setValue(newValue); + } + }); + playbackTimer.setRepeats(true); + + JPanel controlsPanel = new JPanel(); + controlsPanel.setLayout(new BoxLayout(controlsPanel, BoxLayout.LINE_AXIS)); + slider = new JSlider(0, data.getRowCount() - 1); + slider.setValue(0); + slider.addChangeListener(new ChangeListener() { + public void stateChanged(ChangeEvent e) { + Trajectory.this.repaint(); + } + }); + controlsPanel.add(slider); + JButton playButton = new JButton(">"); + playButton.addActionListener(new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + if (playbackTimer.isRunning()) { + playbackTimer.stop(); + } else { + playbackTimer.start(); + if (slider.getValue() == slider.getMaximum()) { + slider.setValue(slider.getMinimum()); + } + } + } + }); + controlsPanel.add(playButton); + add(controlsPanel, BorderLayout.SOUTH); + } + + @Override + public void paint(Graphics g) { + super.paint(g); + + int slider_value = slider.getValue(); + double x = (Double)data.get(0, slider_value); + double y = (Double)data.get(1, slider_value); + double orientation = (Double)data.get(2, slider_value); + double vel_x = (Double)data.get(3, slider_value); + double vel_y = (Double)data.get(4, slider_value); + + double pixelX = plot.getAxisRenderer(XYPlot.AXIS_X).worldToView(plot.getAxis(XYPlot.AXIS_X), x, false); + double pixelY = plot.getAxisRenderer(XYPlot.AXIS_Y).worldToView(plot.getAxis(XYPlot.AXIS_Y), y, false); + + double plotAreaHeight = plot.getPlotArea().getHeight(); + double plotAreaX = plot.getPlotArea().getX(); + double plotAreaY = plot.getPlotArea().getY(); + + pixelX = plotAreaX + pixelX; + pixelY = plotAreaY + plotAreaHeight - pixelY; + + Graphics2D g2d = (Graphics2D)g; + + final int SIZE_X = 30; + final int SIZE_Y = 20; + g2d.setColor(new Color(128, 128, 255)); + AffineTransform saveXf = g2d.getTransform(); + g2d.rotate(-orientation, pixelX, pixelY); + g2d.fillRect((int)pixelX - SIZE_X / 2, (int)pixelY - SIZE_Y / 2, SIZE_X, SIZE_Y); + g2d.setTransform(saveXf); + //g2d.setColor(Color.red); + //g2d.drawLine((int)pixelX, (int)pixelY, (int)(pixelX + vel_x * 20), (int)(pixelY - vel_y * 20)); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/web/AutonomousSelector.java b/src/main/java/com/team766/web/AutonomousSelector.java new file mode 100644 index 00000000..22170e55 --- /dev/null +++ b/src/main/java/com/team766/web/AutonomousSelector.java @@ -0,0 +1,96 @@ +package com.team766.web; + +import java.util.Arrays; +import java.util.Map; +import java.util.Optional; +import java.util.stream.Collectors; +import com.team766.framework.AutonomousMode; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.Severity; + +public class AutonomousSelector implements WebServer.Handler { + private static final String ENDPOINT = "/auton"; + + private final AutonomousMode[] m_autonModes; + private final String[] m_autonModeNames; + private AutonomousMode m_selectedAutonMode; + + public AutonomousSelector(AutonomousMode[] autonModes) { + m_autonModes = autonModes; + m_autonModeNames = + Arrays.stream(autonModes).map(m -> m.name()).toArray(String[]::new); + if (m_autonModeNames.length > 0) { + m_selectedAutonMode = m_autonModes[0]; + } else { + Logger.get(Category.AUTONOMOUS).logRaw( + Severity.WARNING, + "No autonomous modes were declared in AutonomousModes.java"); + m_selectedAutonMode = null; + } + } + + public AutonomousMode getSelectedAutonMode() { + return m_selectedAutonMode; + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String handle(Map params) { + String locationReplaceScript = ""; + { + final String selectedAutonModeName = (String)params.get("AutoMode"); + if (selectedAutonModeName != null) { + final Optional selectedAutonMode = + Arrays.stream(m_autonModes).filter(m -> m.name().equals(selectedAutonModeName)).findFirst(); + if (selectedAutonMode.isEmpty()) { + Logger.get(Category.AUTONOMOUS).logData( + Severity.ERROR, + "Internal framework error: Inconsistent name for selected autonomous mode (selected: %s ; available: %s). Autonomous mode will not run.", + selectedAutonModeName, + Arrays.stream(m_autonModes).map(m -> m.name()).collect(Collectors.joining(","))); + } else { + m_selectedAutonMode = selectedAutonMode.get().clone(); + } + + locationReplaceScript = ""; + } + } + + final String selectedAutonModeName = m_selectedAutonMode != null ? m_selectedAutonMode.name() : ""; + return String.join("\n", new String[]{ + locationReplaceScript, + "

Autonomous Mode Selector

", + "

Current Mode: " + selectedAutonModeName + "

", + "
", + "

" + HtmlElements.buildDropDown("AutoMode", selectedAutonModeName, m_autonModeNames) + "

", + "
", + "", + }); + } + + @Override + public String title() { + return "Autonomous Selector"; + } +} diff --git a/src/main/java/com/team766/web/ConfigUI.java b/src/main/java/com/team766/web/ConfigUI.java new file mode 100644 index 00000000..86dfe69f --- /dev/null +++ b/src/main/java/com/team766/web/ConfigUI.java @@ -0,0 +1,89 @@ +package com.team766.web; + +import java.util.ArrayList; +import java.util.Map; +import com.team766.config.ConfigFileReader; +import com.team766.config.ConfigValueParseException; + +public class ConfigUI implements WebServer.Handler { + @Override + public String endpoint() { + return "/config"; + } + + @Override + public String handle(Map params) { + String r = "

Configuration

"; + + r += "
\n"; + if (params.containsKey("configJson")) { + String configJsonString = (String)params.get("configJson"); + ArrayList validationErrors = new ArrayList(); + try { + ConfigFileReader.getInstance().reloadFromJson(configJsonString); + } catch (ConfigValueParseException ex) { + validationErrors.add(ex.toString()); + } catch (Exception ex) { + validationErrors.add("Failed to parse config json: " + ex); + } + if (validationErrors.isEmpty()) { + r += "

New configuration (v" + ConfigFileReader.getInstance().getGeneration() + ") has been applied

"; + r += "

Remember to click Restart Robot Code in the driver station if you have changed any motor/sensor settings

"; + if (params.containsKey("saveToFile")) { + try { + ConfigFileReader.getInstance().saveFile(configJsonString); + } catch (Exception ex) { + validationErrors.add("Could not save config file: " + ex.toString()); + } + } + } + if (validationErrors.size() > 0) { + r += "

Errors:\n"; + r += "

    \n"; + for (String error : validationErrors) { + r += "
  • " + error + "
  • \n"; + } + r += "

\n"; + } + } + r += "
\n"; + + r += String.join("\n", new String[]{ + "", + }); + + r += "
\n"; + r += "\n"; + r += "

Save to config file on robot?

\n"; + r += "

\n"; + + return r; + } + + @Override + public String title() { + return "Config Values"; + } +} diff --git a/src/main/java/com/team766/web/Dashboard.java b/src/main/java/com/team766/web/Dashboard.java new file mode 100644 index 00000000..e6d1bad5 --- /dev/null +++ b/src/main/java/com/team766/web/Dashboard.java @@ -0,0 +1,60 @@ +package com.team766.web; + +import java.util.Map; +import com.team766.web.dashboard.Widget; + +public class Dashboard implements WebServer.Handler { + private static final String ENDPOINT = "/dashboard"; + + static String makeDashboardPage() { + String page = "

Dashboard Widgets

\n"; + page += "
\n"; + for (var widget : Widget.listWidgets()) { + page += widget.render(); + page += '\n'; + } + page += "
\n"; + page += String.join("\n", new String[]{ + "", + }); + return page; + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String title() { + return "Dashboard"; + } + + @Override + public String handle(Map params) { + return makeDashboardPage(); + } + + @Override + public boolean showInMenu() { + return false; + } +} diff --git a/src/main/java/com/team766/web/DriverInterface.java b/src/main/java/com/team766/web/DriverInterface.java new file mode 100644 index 00000000..9c49086e --- /dev/null +++ b/src/main/java/com/team766/web/DriverInterface.java @@ -0,0 +1,30 @@ +package com.team766.web; + +import java.util.Map; + +public class DriverInterface implements WebServer.Handler { + + AutonomousSelector autonomousSelector; + + public DriverInterface(AutonomousSelector autonomousSelector) { + this.autonomousSelector = autonomousSelector; + } + + @Override + public String endpoint() { + return "/driver"; + } + + @Override + public String title() { + return "Driver Interface"; + } + + @Override + public String handle(Map params) { + return Dashboard.makeDashboardPage() + + LogViewer.makeAllErrorsPage() + + autonomousSelector.handle(params); + } + +} diff --git a/src/main/java/com/team766/web/HtmlElements.java b/src/main/java/com/team766/web/HtmlElements.java new file mode 100644 index 00000000..010d8c77 --- /dev/null +++ b/src/main/java/com/team766/web/HtmlElements.java @@ -0,0 +1,31 @@ +package com.team766.web; + +class HtmlElements { + public static String buildDropDown(String valueName, String current, String... options){ + String id = valueName.replace(' ', '_'); + String out = ""; + } + + public static String buildForm(String valueName, double v){ + return buildForm(valueName, Double.toString(v)); + } + + public static String buildForm(String valueName, String v){ + String id = valueName.replace(' ', '_'); + return "" + + ""; + } + + public static String buildForm(String valueName){ + return buildForm(valueName, 0.0); + } +} diff --git a/src/main/java/com/team766/web/LogViewer.java b/src/main/java/com/team766/web/LogViewer.java new file mode 100644 index 00000000..8738594c --- /dev/null +++ b/src/main/java/com/team766/web/LogViewer.java @@ -0,0 +1,109 @@ +package com.team766.web; + +import java.text.SimpleDateFormat; +import java.util.Arrays; +import java.util.Date; +import java.util.Map; +import java.util.stream.Stream; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LogEntry; +import com.team766.logging.LogEntryRenderer; +import com.team766.logging.Severity; + +public class LogViewer implements WebServer.Handler { + private static final String ENDPOINT = "/logs"; + private static final String ALL_ERRORS_NAME = "All Errors"; + + private static final SimpleDateFormat timeFormat = new SimpleDateFormat("yyyy-MM-dd HH:mm:ss"); + + private static String makeLogEntriesTable(Iterable entries) { + String r = "\n"; + for (LogEntry entry : entries) { + r += String.format( + "\n", + entry.getCategory(), timeFormat.format(new Date(entry.getTime() / 1000000)), entry.getSeverity(), LogEntryRenderer.renderLogEntry(entry, null)); + } + r += "
%s%s%s%s
"; + return r; + } + + private static String makePage(String categoryName, Iterable entries) { + return String.join("\n", new String[]{ + "

Log: " + categoryName + "

", + "

", + HtmlElements.buildDropDown( + "category", + categoryName, + Stream.concat( + Stream.of(ALL_ERRORS_NAME), + Arrays.stream(Category.values()).map(Category::name) + ).toArray(String[]::new)), + "", + "

", + makeLogEntriesTable(entries), + "", + "", + "", + "", + }); + } + + static String makeAllErrorsPage() { + return makePage( + ALL_ERRORS_NAME, + Arrays.stream(Category.values()) + .flatMap(category -> Logger.get(category).recentEntries().stream()) + .filter(entry -> entry.getSeverity() == Severity.ERROR) + ::iterator); + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String handle(Map params) { + String categoryName = (String)params.get("category"); + if (categoryName == null || categoryName.equals(ALL_ERRORS_NAME)) { + return makeAllErrorsPage(); + } else { + Category category = Enum.valueOf(Category.class, categoryName); + return makePage(category.name(), Logger.get(category).recentEntries()); + } + } + + @Override + public String title() { + return "Log Viewer"; + } +} diff --git a/src/main/java/com/team766/web/ReadLogs.java b/src/main/java/com/team766/web/ReadLogs.java new file mode 100644 index 00000000..91aca8a7 --- /dev/null +++ b/src/main/java/com/team766/web/ReadLogs.java @@ -0,0 +1,158 @@ +package com.team766.web; + +import java.io.EOFException; +import java.io.File; +import java.io.IOException; +import java.text.NumberFormat; +import java.util.Arrays; +import java.util.HashMap; +import java.util.Iterator; +import java.util.Locale; +import java.util.Map; +import java.util.function.Function; +import java.util.stream.Stream; +import com.team766.logging.Category; +import com.team766.logging.Logger; +import com.team766.logging.LogEntry; +import com.team766.logging.LogEntryRenderer; +import com.team766.logging.LogReader; +import com.team766.logging.Severity; + +public class ReadLogs implements WebServer.Handler { + private static final String ENDPOINT = "/readlogs"; + private static final String ALL_ERRORS_NAME = "All Errors"; + private static final int ENTRIES_PER_PAGE = 100; + + private HashMap logReaders = new HashMap(); + private HashMap readerDescriptions = new HashMap(); + private HashMap> readerStreams = new HashMap>(); + + private static String makeLogEntriesTable(LogReader reader, Iterator entries) { + String r = "\n"; + for (int i = 0; i < ENTRIES_PER_PAGE; ++i) { + if (!entries.hasNext()) { + break; + } + LogEntry entry = entries.next(); + r += String.format( + "\n", + entry.getCategory(), entry.getTime(), entry.getSeverity(), LogEntryRenderer.renderLogEntry(entry, reader)); + } + r += "
%s%s%s%s
"; + return r; + } + + private String makePage(String id) { + String r = String.join("\n", new String[]{ + "

Free disk space: " + + NumberFormat.getNumberInstance(Locale.US).format( + new File(Logger.logFilePathBase).getUsableSpace()) + + "

", + "

", + HtmlElements.buildDropDown( + "logFile", + "", + Logger.logFilePathBase == null + ? new String[0] + : new File(Logger.logFilePathBase).list()), + HtmlElements.buildDropDown( + "category", + "", + Stream.concat( + Stream.of("", ALL_ERRORS_NAME), + Arrays.stream(Category.values()).map(Category::name) + ).toArray(String[]::new)), + "", + "

", + }); + if (id != null) { + r += String.join("\n", new String[]{ + "

Log: " + readerDescriptions.get(id) + "

", + makeLogEntriesTable(logReaders.get(id), readerStreams.get(id)), + "", + }); + } + return r; + } + + private String makeReader( + String logFile, + String description, + Function, Stream> filter + ) { + LogReader reader; + try { + reader = new LogReader(new File(Logger.logFilePathBase, logFile).getAbsolutePath()); + } catch (IOException e) { + throw new RuntimeException(e); + } + String id = Integer.toString(logReaders.size()); + logReaders.put(id, reader); + readerDescriptions.put(id, logFile + " " + description); + readerStreams.put(id, filter.apply(Stream.generate(() -> { + try { + return reader.readNext(); + } catch (EOFException e) { + return null; + } catch (IOException e) { + throw new RuntimeException(e); + } + }).takeWhile(e -> e != null)).iterator()); + return id; + } + + private String makeUnfilteredReader(String logFile) { + return makeReader( + logFile, + "", + s -> s + ); + } + + private String makeCategoryReader(String logFile, Category category) { + return makeReader( + logFile, + category.name(), + s -> s.filter(e -> e.getCategory() == category) + ); + } + + private String makeAllErrorsReader(String logFile) { + return makeReader( + logFile, + ALL_ERRORS_NAME, + s -> s.filter(entry -> entry.getSeverity() == Severity.ERROR) + ); + } + + @Override + public String endpoint() { + return ENDPOINT; + } + + @Override + public String handle(Map params) { + String id = (String)params.get("id"); + String logFile = (String)params.get("logFile"); + String categoryName = (String)params.get("category"); + if (!logReaders.containsKey(id)) { + id = null; + } + if (logFile != null) { + if (categoryName == null || categoryName.equals("")) { + id = makeUnfilteredReader(logFile); + } else if (categoryName.equals(ALL_ERRORS_NAME)) { + id = makeAllErrorsReader(logFile); + } else { + Category category = Enum.valueOf(Category.class, categoryName); + id = makeCategoryReader(logFile, category); + } + } + return makePage(id); + } + + @Override + public String title() { + return "Log Reader"; + } +} diff --git a/src/main/java/com/team766/web/WebServer.java b/src/main/java/com/team766/web/WebServer.java new file mode 100644 index 00000000..56e59fed --- /dev/null +++ b/src/main/java/com/team766/web/WebServer.java @@ -0,0 +1,213 @@ +package com.team766.web; + +import java.io.BufferedReader; +import java.io.IOException; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.io.UnsupportedEncodingException; +import java.net.InetSocketAddress; +import java.net.URI; +import java.net.URLDecoder; +import java.util.ArrayList; +import java.util.HashMap; +import java.util.LinkedHashMap; +import java.util.List; +import java.util.Map; + +import com.sun.net.httpserver.HttpExchange; +import com.sun.net.httpserver.HttpHandler; +import com.sun.net.httpserver.HttpServer; + +/* + * Creates an HTTP Server on the robot that can change the + * settings of it. It is initially just used to change robot + * values. Hopefully this will be later updated to support + * graphing and even small changes in the robot's actual code. + * + * Can be reached at: + * roboRio-766.local:5800/values + */ + +public class WebServer { + + public interface Handler { + String endpoint(); + default boolean showInMenu() { return true; } + String title(); + String handle(Map params); + } + + private HttpServer server; + private LinkedHashMap pages = new LinkedHashMap(); + + public WebServer() { + addHandler(new Handler() { + @Override + public String endpoint() { + return "/"; + } + + @Override + public String title() { + return "Menu"; + } + + @Override + public boolean showInMenu() { + return false; + } + + @Override + public String handle(Map params) { + return ""; + } + }); + } + + public void addHandler(Handler handler) { + pages.put(handler.endpoint(), handler); + } + + public void start(){ + try { + server = HttpServer.create(new InetSocketAddress(5800), 0); + } catch (IOException e) { + throw new RuntimeException(e); + } + for (Map.Entry page : pages.entrySet()) { + HttpHandler httpHandler = new HttpHandler() { + @Override + public void handle(HttpExchange exchange) throws IOException { + Map params = parseParams(exchange); + String response = ""; + response += buildPageHeader(); + try { + response += page.getValue().handle(params); + } catch (Exception ex) { + ex.printStackTrace(); + throw ex; + } + response += ""; + exchange.sendResponseHeaders(200, response.getBytes().length); + try (OutputStream os = exchange.getResponseBody()) { + os.write(response.getBytes()); + } + } + }; + server.createContext(page.getKey(), httpHandler); + } + addLineNumbersSvgHandler(); + server.start(); + } + + protected String buildPageHeader() { + String result = ""; + result += "\n"; + result += "

\n"; + for (Map.Entry page : pages.entrySet()) { + if (page.getValue().showInMenu()) + result += String.format("%s
\n", page.getKey(), page.getValue().title()); + } + result += "

\n"; + return result; + } + + private void addLineNumbersSvgHandler() { + HttpHandler httpHandler = new HttpHandler() { + @Override + public void handle(HttpExchange exchange) throws IOException { + String response = "\n"; + response += "\n"; + response += "\n"; + response += "\n"; + for (int i = 1; i < 1000; ++i) { + response += "" + i + ".\n"; + } + response += "\n"; + response += ""; + exchange.getResponseHeaders().set("Content-Type", "image/svg+xml"); + exchange.sendResponseHeaders(200, response.getBytes().length); + try (OutputStream os = exchange.getResponseBody()) { + os.write(response.getBytes()); + } + } + }; + server.createContext("/line_numbers.svg", httpHandler); + } + + public Map parseParams(HttpExchange exchange) throws IOException { + Map parameters = new HashMap(); + parseGetParameters(exchange, parameters); + parsePostParameters(exchange, parameters); + return parameters; + } + + private void parseGetParameters(HttpExchange exchange, Map parameters) + throws UnsupportedEncodingException { + URI requestedUri = exchange.getRequestURI(); + String query = requestedUri.getRawQuery(); + parseQuery(query, parameters); + } + + private void parsePostParameters(HttpExchange exchange, Map parameters) + throws IOException { + + if ("post".equalsIgnoreCase(exchange.getRequestMethod())) { + InputStreamReader isr = + new InputStreamReader(exchange.getRequestBody(), "utf-8"); + BufferedReader br = new BufferedReader(isr); + String query = br.readLine(); + parseQuery(query, parameters); + } + } + + private void parseQuery(String query, Map parameters) + throws UnsupportedEncodingException { + + if (query != null) { + String pairs[] = query.split("[&]"); + + for (String pair : pairs) { + String param[] = pair.split("[=]"); + + String key = null; + String value = null; + if (param.length > 0) { + key = URLDecoder.decode(param[0], System.getProperty("file.encoding")); + } + + if (param.length > 1) { + value = URLDecoder.decode(param[1], System.getProperty("file.encoding")); + } + + if (parameters.containsKey(key)) { + Object obj = parameters.get(key); + if(obj instanceof List) { + @SuppressWarnings("unchecked") + List values = (List)obj; + + values.add(value); + } else if(obj instanceof String) { + List values = new ArrayList(); + values.add((String)obj); + values.add(value); + parameters.put(key, values); + } + } else { + parameters.put(key, value); + } + } + } + } +} diff --git a/src/main/java/com/team766/web/dashboard/NewSection.java b/src/main/java/com/team766/web/dashboard/NewSection.java new file mode 100644 index 00000000..69655dea --- /dev/null +++ b/src/main/java/com/team766/web/dashboard/NewSection.java @@ -0,0 +1,30 @@ +package com.team766.web.dashboard; + +public class NewSection extends Widget { + private String m_name; + + public NewSection() { + this("", DEFAULT_SORT_ORDER); + } + + public NewSection(String name) { + this(name, DEFAULT_SORT_ORDER); + } + + public NewSection(String name, int sortOrder) { + super(sortOrder); + + m_name = name; + } + + @Override + public String render() { + String page = "
"; + if (!m_name.isEmpty()) { + page += "

" + m_name + "

"; + } + page += "
"; + return page; + } + +} diff --git a/src/main/java/com/team766/web/dashboard/StatusLight.java b/src/main/java/com/team766/web/dashboard/StatusLight.java new file mode 100644 index 00000000..57de7cb3 --- /dev/null +++ b/src/main/java/com/team766/web/dashboard/StatusLight.java @@ -0,0 +1,45 @@ +package com.team766.web.dashboard; + +public class StatusLight extends Widget { + private String m_name; + private String m_color = "gray"; + private int m_width = 150; + private int m_height = 150; + private String m_style = ""; + + public StatusLight(String name) { + this(name, DEFAULT_SORT_ORDER); + } + + public StatusLight(String name, int sortOrder) { + super(sortOrder); + + m_name = name; + } + + public void setName(String name) { + m_name = name; + } + + public void setSize(int width, int height) { + m_width = width; + m_height = height; + } + + public void setColor(String color) { + m_color = color; + } + + public void setStyle(String style) { + m_style = style; + } + + @Override + public String render() { + return "
" + m_name + "
"; + } +} diff --git a/src/main/java/com/team766/web/dashboard/Widget.java b/src/main/java/com/team766/web/dashboard/Widget.java new file mode 100644 index 00000000..3a2573ca --- /dev/null +++ b/src/main/java/com/team766/web/dashboard/Widget.java @@ -0,0 +1,31 @@ +package com.team766.web.dashboard; + +import java.util.Collections; +import java.util.Map; +import java.util.WeakHashMap; +import java.util.stream.Collectors; + +public abstract class Widget { + public static final int DEFAULT_SORT_ORDER = 0; + + private static int c_orderCounter = 0; + private static Map c_widgets = + Collections.synchronizedMap(new WeakHashMap()); + + public static Iterable listWidgets() { + synchronized (c_widgets) { + return c_widgets.entrySet().stream() + .sorted(Map.Entry.comparingByValue()) + .map(Map.Entry::getKey) + .collect(Collectors.toList()); + } + } + + public Widget(int sortOrder) { + synchronized (c_widgets) { + c_widgets.put(this, (((long)sortOrder) << 32) | (c_orderCounter++)); + } + } + + public abstract String render(); +} diff --git a/src/main/proto/com/team766/logging/logging.proto b/src/main/proto/com/team766/logging/logging.proto new file mode 100644 index 00000000..39a72f4f --- /dev/null +++ b/src/main/proto/com/team766/logging/logging.proto @@ -0,0 +1,65 @@ +syntax = "proto2"; + +package com.team766.logging; + +option java_multiple_files = true; + +message LogEntry { + // Time as nanoseconds since January 1, 1970, 00:00:00 GMT + optional int64 time = 1; + optional Severity severity = 2; + optional Category category = 3; + + optional string message_str = 6; + optional int32 message_index = 7; + repeated LogValue arg = 8; +} + +enum Severity { + DEBUG = 10; + INFO = 20; + WARNING = 30; + ERROR = 40; +} + +enum Category { + // Don't change the numbers. When adding a new option, just use the next + // available number. + JAVA_EXCEPTION = 0; + FRAMEWORK = 1; + HAL = 2; + CONFIGURATION = 3; + MECHANISMS = 4; + PROCEDURES = 5; + AUTONOMOUS = 6; + CAMERA = 7; + PID_CONTROLLER = 8; + TRAJECTORY = 9; + OPERATOR_INTERFACE = 10; + DRIVE = 11; + GYRO = 12; + ODOMETRY = 13; +} + +// `Value` represents a dynamically typed value which can be either a number, +// a string, a boolean, or a list of values. Absence of all fields indicates +// a null value. +message LogValue { + oneof kind { + int64 int_value = 1; + // Represents a double value. + double float_value = 2; + // Represents a string value. + string string_value = 3; + // Represents a boolean value. + bool bool_value = 4; + // Represents an array or list. + LogListValue list = 5; + + // Add schemas for other serialized types here + } +} + +message LogListValue { + repeated LogValue element = 1; +} \ No newline at end of file diff --git a/src/test/java/com/team766/TestCase.java b/src/test/java/com/team766/TestCase.java new file mode 100644 index 00000000..a81de41c --- /dev/null +++ b/src/test/java/com/team766/TestCase.java @@ -0,0 +1,22 @@ +package com.team766; + +import com.team766.config.ConfigFileReader; +import com.team766.framework.Scheduler; +import com.team766.hal.RobotProvider; +import com.team766.hal.mock.TestRobotProvider; + +public abstract class TestCase extends junit.framework.TestCase { + + @Override + protected void setUp() throws Exception { + ConfigFileReader.instance = new ConfigFileReader(this.getClass().getClassLoader().getResource("testConfig.txt").getPath()); + RobotProvider.instance = new TestRobotProvider(); + + Scheduler.getInstance().reset(); + } + + protected void step(){ + Scheduler.getInstance().run(); + } + +} diff --git a/src/test/java/com/team766/config/ConfigFileReaderTest.java b/src/test/java/com/team766/config/ConfigFileReaderTest.java new file mode 100644 index 00000000..9a6b3531 --- /dev/null +++ b/src/test/java/com/team766/config/ConfigFileReaderTest.java @@ -0,0 +1,43 @@ +package com.team766.config; + +import static org.junit.Assert.*; +import java.io.File; +import java.io.FileWriter; +import java.io.IOException; +import org.junit.Before; +import org.junit.Test; + +public class ConfigFileReaderTest { + @Before + public void setup() { + AbstractConfigValue.resetStatics(); + } + + @Test + public void getJsonStringFromEmptyConfigFile() throws IOException { + File testConfigFile = File.createTempFile("config_file_test", ".json"); + try (FileWriter fos = new FileWriter(testConfigFile)) { + fos.append("{}"); + } + + ConfigFileReader.instance = new ConfigFileReader(testConfigFile.getPath()); + ConfigFileReader.getInstance().getString("test.sub.key"); + assertEquals("{\"test\": {\"sub\": {\"key\": null}}}", ConfigFileReader.getInstance().getJsonString()); + } + + @Test + public void getJsonStringFromPartialConfigFile() throws IOException { + File testConfigFile = File.createTempFile("config_file_test", ".json"); + try (FileWriter fos = new FileWriter(testConfigFile)) { + fos.append("{\"test\": {\"sub\": {\"key\": \"pi\", \"value\": 3.14159}}}"); + } + + ConfigFileReader.instance = new ConfigFileReader(testConfigFile.getPath()); + assertEquals("pi", ConfigFileReader.getInstance().getString("test.sub.key").get()); + assertEquals(3.14159, ConfigFileReader.getInstance().getDouble("test.sub.value").get().doubleValue(), 1e-6); + assertFalse(ConfigFileReader.getInstance().getInts("test.other.value").hasValue()); + assertEquals( + "{\"test\": {\n \"sub\": {\n \"value\": 3.14159,\n \"key\": \"pi\"\n },\n \"other\": {\"value\": null}\n}}", + ConfigFileReader.getInstance().getJsonString()); + } +} \ No newline at end of file diff --git a/src/test/java/com/team766/library/LossyPriorityQueueTest.java b/src/test/java/com/team766/library/LossyPriorityQueueTest.java new file mode 100644 index 00000000..73172577 --- /dev/null +++ b/src/test/java/com/team766/library/LossyPriorityQueueTest.java @@ -0,0 +1,26 @@ +package com.team766.library; + +import static org.junit.Assert.*; + +import java.util.Comparator; + +import org.junit.Test; + +public class LossyPriorityQueueTest { + @Test + public void test() throws InterruptedException { + final int N = 100; + var queue = + new LossyPriorityQueue(N, Comparator.naturalOrder()); + var producerThread = new Thread(() -> { + for (Integer i = 0; i < N; ++i) { + queue.add(i); + } + }); + producerThread.start(); + for (Integer i = 0; i < N; ++i) { + assertEquals(i, queue.poll()); + } + producerThread.join(); + } +} \ No newline at end of file diff --git a/src/test/java/com/team766/logging/LoggerTest.java b/src/test/java/com/team766/logging/LoggerTest.java new file mode 100644 index 00000000..a287fa14 --- /dev/null +++ b/src/test/java/com/team766/logging/LoggerTest.java @@ -0,0 +1,90 @@ +package com.team766.logging; + +import static org.junit.Assert.*; + +import java.io.File; +import java.io.IOException; +import java.util.ArrayList; +import org.junit.Rule; +import org.junit.Test; +import org.junit.rules.TemporaryFolder; + +public class LoggerTest { + @Rule + public TemporaryFolder workingDir = new TemporaryFolder(); + + @Test + public void test() throws IOException, InterruptedException { + String logFile = new File(workingDir.getRoot(), "test.log").getPath(); + LogWriter writer = new LogWriter(logFile); + writer.logStoredFormat( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.ERROR) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("num: %d str: %s") + .addArg(LogValue.newBuilder().setIntValue(42)) + .addArg(LogValue.newBuilder().setStringValue("my string"))); + writer.logStoredFormat( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.ERROR) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("num: %d str: %s") + .addArg(LogValue.newBuilder().setIntValue(63)) + .addArg(LogValue.newBuilder().setStringValue("second blurb"))); + writer.log( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.WARNING) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("Test raw log") + .build()); + writer.close(); + + LogReader reader = new LogReader(logFile); + String logString1 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); + assertEquals("num: 42 str: my string", logString1); + String logString2 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); + assertEquals("num: 63 str: second blurb", logString2); + String logString3 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); + assertEquals("Test raw log", logString3); + } + + @Test + public void stressTest() throws IOException, InterruptedException { + final long NUM_THREADS = 8; + final long RUN_TIME_SECONDS = 3; + + LogWriter writer = new LogWriter(new File(workingDir.getRoot(), "stress_test.log").getPath()); + ArrayList threads = new ArrayList(); + for (int j = 0; j < NUM_THREADS; ++j) { + Thread t = new Thread(() ->{ + long end = System.currentTimeMillis() + RUN_TIME_SECONDS * 1000; + while (System.currentTimeMillis() < end) { + writer.logStoredFormat( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.ERROR) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("num: %d str: %s") + .addArg(LogValue.newBuilder().setIntValue(42)) + .addArg(LogValue.newBuilder().setStringValue("my string"))); + writer.log( + LogEntry.newBuilder() + .setTime(Logger.getTime()) + .setSeverity(Severity.WARNING) + .setCategory(Category.AUTONOMOUS) + .setMessageStr("Test raw log") + .build()); + } + }); + t.start(); + threads.add(t); + } + for (Thread t : threads) { + t.join(); + } + writer.close(); + } +} \ No newline at end of file diff --git a/to-do.txt b/to-do.txt new file mode 100644 index 00000000..4f10a487 --- /dev/null +++ b/to-do.txt @@ -0,0 +1 @@ +Add to do here: diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix.json new file mode 100644 index 00000000..789d831f --- /dev/null +++ b/vendordeps/Phoenix.json @@ -0,0 +1,257 @@ +{ + "fileName": "Phoenix.json", + "name": "CTRE-Phoenix", + "version": "5.20.2", + "frcYear": 2022, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix-frc2022-latest.json", + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.20.2" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.20.2" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonSRX", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonFX", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simVictorSPX", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simPigeonIMU", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simCANCoder", + "version": "5.20.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.20.2", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.20.2", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.20.2", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.20.2", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.20.2", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.20.2", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonSRX", + "version": "5.20.2", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonFX", + "version": "5.20.2", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simVictorSPX", + "version": "5.20.2", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simPigeonIMU", + "version": "5.20.2", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simCANCoder", + "version": "5.20.2", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 00000000..997e2a46 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,73 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2022.1.1", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2022.1.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2022.1.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2022.1.1", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2022.1.1", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json new file mode 100644 index 00000000..83de291e --- /dev/null +++ b/vendordeps/WPILibNewCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "2020.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxaarch64bionic", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/WPILibOldCommands.json b/vendordeps/WPILibOldCommands.json new file mode 100644 index 00000000..7bdad212 --- /dev/null +++ b/vendordeps/WPILibOldCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibOldCommands.json", + "name": "WPILib-Old-Commands", + "version": "2020.0.0", + "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibOldCommands", + "artifactId": "wpilibOldCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibOldCommands", + "artifactId": "wpilibOldCommands-cpp", + "version": "wpilib", + "libName": "wpilibOldCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxaarch64bionic", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} diff --git a/vendordeps/navx_frc.json b/vendordeps/navx_frc.json new file mode 100644 index 00000000..0fb49a7e --- /dev/null +++ b/vendordeps/navx_frc.json @@ -0,0 +1,35 @@ +{ + "fileName": "navx_frc.json", + "name": "KauaiLabs_navX_FRC", + "version": "4.0.442", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "mavenUrls": [ + "https://repo1.maven.org/maven2/" + ], + "jsonUrl": "https://www.kauailabs.com/dist/frc/2022/navx_frc.json", + "javaDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-java", + "version": "4.0.442" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-cpp", + "version": "4.0.442", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": false, + "libName": "navx_frc", + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "windowsx86-64" + ] + } + ] +} \ No newline at end of file From e0185cfe803b3fb1e06a04ffc643b3c019e2aeee Mon Sep 17 00:00:00 2001 From: qntmcube Date: Sat, 14 Jan 2023 14:10:44 -0800 Subject: [PATCH 003/103] Update to WPILib 2023 Changes initially made by VS Code import tool. Updated from there to make sure Maroon Framework continues to build. This change contains a temporary implementation of WPIRobotProvider.hasNewDriverStationData() (underlying method removed in WPILib 2023) until we make a longer-term fix. --- .wpilib/wpilib_preferences.json | 2 +- build.gradle | 18 +- gradle/wrapper/gradle-wrapper.jar | Bin 59536 -> 60756 bytes gradle/wrapper/gradle-wrapper.properties | 2 +- gradlew | 16 +- gradlew.bat | 14 +- settings.gradle | 2 +- .../team766/hal/wpilib/WPIRobotProvider.java | 4 +- vendordeps/Phoenix.json | 298 ++++++++++++++---- vendordeps/REVLib.json | 30 +- vendordeps/WPILibNewCommands.json | 72 ++--- vendordeps/WPILibOldCommands.json | 37 --- vendordeps/navx_frc.json | 6 +- 13 files changed, 326 insertions(+), 175 deletions(-) delete mode 100644 vendordeps/WPILibOldCommands.json diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index c19547e9..d8e8ef34 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { "enableCppIntellisense": false, "currentLanguage": "java", - "projectYear": "2022", + "projectYear": "2023", "teamNumber": 766 } \ No newline at end of file diff --git a/build.gradle b/build.gradle index a8517abc..cacb0d99 100644 --- a/build.gradle +++ b/build.gradle @@ -1,8 +1,8 @@ plugins { - id 'java' + id "java" id 'java-library' id 'maven-publish' - id 'edu.wpi.first.GradleRIO' version '2022.4.1' + id "edu.wpi.first.GradleRIO" version "2023.1.1" id 'com.google.protobuf' version '0.8.19' } @@ -67,7 +67,7 @@ wpi.java.debugJni = false def includeDesktopSupport = false // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. -// Also defines JUnit 4. +// Also defines JUnit 5. dependencies { implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() @@ -87,6 +87,9 @@ dependencies { simulationRelease wpi.sim.enableRelease() testImplementation 'junit:junit:4.12' + testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2' + testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2' + testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2' // our files implementation "com.google.protobuf:protobuf-java:${protobufVersion}" @@ -98,6 +101,11 @@ dependencies { implementation files('deps/json-20190722.jar') } +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' +} + // Simulation configuration (e.g. environment variables). wpi.sim.addGui().defaultEnabled = true wpi.sim.addDriverstation() @@ -116,6 +124,10 @@ deployArtifact.jarTask = jar wpi.java.configureExecutableTasks(jar) wpi.java.configureTestTasks(test) +// Configure string concat to always inline compile +tasks.withType(JavaCompile) { + options.compilerArgs.add '-XDstringConcat=inline' +} allprojects { group 'com.team766' version '2.1.0' diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar index 7454180f2ae8848c63b8b4dea2cb829da983f2fa..249e5832f090a2944b7473328c07c9755baa3196 100644 GIT binary patch delta 10158 zcmaKSbyOWsmn~e}-QC?axCPf>!2<-jxI0|j{UX8L-QC?axDz};a7}ppGBe+Nv*x{5 zy?WI?=j^WT(_Md5*V*xNP>X9&wM>xUvNiMuKDK=Xg!N%oM>Yru2rh7#yD-sW0Ov#$ zCKBSOD3>TM%&1T5t&#FK@|@1f)Ze+EE6(7`}J(Ek4})CD@I+W;L{ zO>K;wokKMA)EC6C|D@nz%D2L3U=Nm(qc>e4GM3WsHGu-T?l^PV6m-T-(igun?PZ8U z{qbiLDMcGSF1`FiKhlsV@qPMRm~h9@z3DZmWp;Suh%5BdP6jqHn}$-gu`_xNg|j{PSJ0n$ zbE;Azwq8z6IBlgKIEKc4V?*##hGW#t*rh=f<;~RFWotXS$vr;Mqz>A99PMH3N5BMi zWLNRjc57*z`2)gBV0o4rcGM(u*EG8_H5(|kThAnp|}u2xz>>X6tN zv)$|P2Nr1D*fk4wvqf(7;NmdRV3eL{!>DO-B98(s*-4$g{)EnRYAw+DP-C`=k)B!* zHU7!ejcbavGCYuz9k@$aZQaU%#K%6`D}=N_m?~^)IcmQZun+K)fSIoS>Ws zwvZ%Rfmw>%c!kCd~Pmf$E%LCj2r>+FzKGDm+%u88|hHprot{*OIVpi`Vd^^aumtx2L}h} zPu$v~zdHaWPF<`LVQX4i7bk82h#RwRyORx*z3I}o&>>eBDCif%s7&*vF6kU%1` zf(bvILch^~>cQ{=Y#?nx(8C-Uuv7!2_YeCfo?zkP;FK zX+KdjKS;HQ+7 zj>MCBI=d$~9KDJ1I2sb_3=T6D+Mu9{O&vcTnDA(I#<=L8csjEqsOe=&`=QBc7~>u2 zfdcO44PUOST%PcN+8PzKFYoR0;KJ$-Nwu#MgSM{_!?r&%rVM}acp>53if|vpH)q=O z;6uAi__am8g$EjZ33?PmCrg@(M!V_@(^+#wAWNu&e3*pGlfhF2<3NobAC zlusz>wMV--3ytd@S047g)-J@eOD;DMnC~@zvS=Gnw3=LnRzkeV`LH4#JGPklE4!Q3 zq&;|yGR0FiuE-|&1p2g{MG!Z3)oO9Jf4@0h*3!+RHv=SiEf*oGQCSRQf=LqT5~sajcJ8XjE>E*@q$n z!4|Rz%Lv8TgI23JV6%)N&`Otk6&RBdS|lCe7+#yAfdyEWNTfFb&*S6-;Q}d`de!}*3vM(z71&3 z37B%@GWjeQ_$lr%`m-8B&Zl4Gv^X{+N{GCsQGr!LLU4SHmLt3{B*z-HP{73G8u>nK zHxNQ4eduv>lARQfULUtIlLx#7ea+O;w?LH}FF28c9pg#*M`pB~{jQmPB*gA;Hik#e zZpz&X#O}}r#O_#oSr4f`zN^wedt>ST791bAZ5(=g<Oj)m9X8J^>Th}fznPY0T zsD9ayM7Hrlb6?jHXL<{kdA*Q#UPCYce0p`fHxoZ7_P`cF-$1YY9Pi;0QFt{CCf%C# zuF60A_NTstTQeFR3)O*ThlWKk08}7Nshh}J-sGY=gzE!?(_ZI4ovF6oZ$)&Zt~WZi z_0@Bk!~R4+<&b6CjI{nGj+P{*+9}6;{RwZ7^?H)xjhiRi;?A|wb0UxjPr?L@$^v|0= z@6d3+eU|&re3+G*XgFS}tih3;>2-R1x>`2hmUb5+Z~eM4P|$ zAxvE$l@sIhf_#YLnF|Wcfp(Gh@@dJ-yh|FhKqsyQp_>7j1)w|~5OKETx2P$~`}5huK;{gw_~HXP6=RsG)FKSZ=VYkt+0z&D zr?`R3bqVV?Zmqj&PQ`G3b^PIrd{_K|Hhqt zAUS#|*WpEOeZ{@h*j6%wYsrL`oHNV=z*^}yT1NCTgk1-Gl(&+TqZhODTKb9|0$3;| z;{UUq7X9Oz`*gwbi|?&USWH?Fr;6=@Be4w=8zu>DLUsrwf+7A`)lpdGykP`^SA8{ok{KE3sM$N@l}kB2GDe7MEN? zWcQ2I0fJ1ZK%s-YKk?QbEBO6`C{bg$%le0FTgfmSan-Kih0A7)rGy|2gd)_gRH7qp z*bNlP0u|S^5<)kFcd&wQg*6QP5;y(3ZgI%vUgWk#`g!sMf`02>@xz{Ie9_-fXllyw zh>P%cK+-HkQ;D$Jh=ig(ASN^zJ7|q*#m;}2M*T#s0a^nF_>jI(L(|*}#|$O&B^t!W zv-^-vP)kuu+b%(o3j)B@do)n*Y0x%YNy`sYj*-z2ncYoggD6l z6{1LndTQUh+GCX;7rCrT z@=vy&^1zyl{#7vRPv;R^PZPaIks8okq)To8!Cks0&`Y^Xy5iOWC+MmCg0Jl?1ufXO zaK8Q5IO~J&E|<;MnF_oXLc=LU#m{6yeomA^Ood;)fEqGPeD|fJiz(`OHF_f*{oWJq z1_$NF&Mo7@GKae#f4AD|KIkGVi~ubOj1C>>WCpQq>MeDTR_2xL01^+K1+ zr$}J>d=fW{65hi2bz&zqRKs8zpDln z*7+Gtfz6rkgfj~#{MB=49FRP;ge*e0=x#czw5N{@T1{EAl;G&@tpS!+&2&Stf<%<+55R18u2%+}`?PZo8xg|Y9Xli(fSQyC7 z+O5{;ZyW$!eYR~gy>;l6cA+e`oXN6a6t(&kUkWus*Kf<m$W7L)w5uXYF)->OeWMSUVXi;N#sY zvz4c?GkBU{D;FaQ)9|HU7$?BX8DFH%hC11a@6s4lI}y{XrB~jd{w1x&6bD?gemdlV z-+ZnCcldFanu`P=S0S7XzwXO(7N9KV?AkgZzm|J&f{l-Dp<)|-S7?*@HBIfRxmo1% zcB4`;Al{w-OFD08g=Qochf9=gb56_FPc{C9N5UAjTcJ(`$>)wVhW=A<8i#!bmKD#6~wMBak^2(p56d2vs&O6s4>#NB0UVr24K z%cw|-Yv}g5`_zcEqrZBaRSoBm;BuXJM^+W$yUVS9?u(`87t)IokPgC_bQ3g_#@0Yg zywb?u{Di7zd3XQ$y!m^c`6~t-7@g-hwnTppbOXckS-^N?w1`kRMpC!mfMY?K#^Ldm zYL>771%d{+iqh4a&4RdLNt3_(^^*{U2!A>u^b{7e@}Azd_PiZ>d~(@(Q@EYElLAx3LgQ5(ZUf*I%EbGiBTG!g#=t zXbmPhWH`*B;aZI)$+PWX+W)z?3kTOi{2UY9*b9bpSU!GWcVu+)!^b4MJhf=U9c?jj z%V)EOF8X3qC5~+!Pmmmd@gXzbycd5Jdn!N#i^50a$4u}8^O}DG2$w-U|8QkR-WU1mk4pF z#_imS#~c2~Z{>!oE?wfYc+T+g=eJL`{bL6=Gf_lat2s=|RxgP!e#L|6XA8w{#(Po(xk1~rNQ4UiG``U`eKy7`ot;xv4 zdv54BHMXIq;#^B%W(b8xt%JRueW5PZsB2eW=s3k^Pe1C$-NN8~UA~)=Oy->22yJ%e zu=(XD^5s{MkmWB)AF_qCFf&SDH%ytqpt-jgs35XK8Ez5FUj?uD3++@2%*9+-65LGQ zvu1eopeQoFW98@kzU{+He9$Yj#`vaQkqu%?1wCoBd%G=)TROYl2trZa{AZ@#^LARR zdzg-?EUnt9dK2;W=zCcVj18RTj-%w^#pREbgpD0aL@_v-XV2&Cd@JB^(}GRBU}9gV z6sWmVZmFZ9qrBN%4b?seOcOdOZ+6cx8-#R(+LYKJu~Y%pF5#85aF9$MnP7r^Bu%D? zT{b-KBujiy>7_*9{8u0|mTJ(atnnnS%qBDM_Gx5>3V+2~Wt=EeT4cXOdud$+weM(>wdBg+cV$}6%(ccP;`!~CzW{0O2aLY z?rQtBB6`ZztPP@_&`kzDzxc==?a{PUPUbbX31Vy?_(;c+>3q*!df!K(LQYZNrZ>$A*8<4M%e8vj1`%(x9)d~);ym4p zoo518$>9Pe| zZaFGj);h?khh*kgUI-Xvj+Dr#r&~FhU=eQ--$ZcOY9;x%&3U(&)q}eJs=)K5kUgi5 zNaI-m&4?wlwFO^`5l-B?17w4RFk(IKy5fpS0K%txp0qOj$e=+1EUJbLd-u>TYNna~ z+m?gU0~xlcnP>J>%m_y_*7hVMj3d&)2xV8>F%J;6ncm)ILGzF2sPAV|uYk5!-F%jL(53^51BKr zc3g7+v^w<4WIhk7a#{N6Ku_u{F`eo;X+u!C(lIaiY#*V5!sMed39%-AgV*`(nI)Im zemHE^2foBMPyIP<*yuD21{6I?Co?_{pqp-*#N6sZRQAzEBV4HQheOyZT5UBd)>G85 zw^xHvCEP4AJk<{v2kQQ;g;C)rCY=X!c8rNpNJ4mHETN}t1rwSe7=s8u&LzW-+6AEB z)LX0o7`EqC94HM{4p}d2wOwj2EB|O;?&^FeG9ZrT%c!J&x`Z3D2!cm(UZbFBb`+h ztfhjq75yuSn2~|Pc)p$Ul6=)}7cfXtBsvc15f&(K{jnEsw5Gh0GM^O=JC+X-~@r1kI$=FH=yBzsO#PxR1xU9+T{KuPx7sMe~GX zSP>AT3%(Xs@Ez**e@GAn{-GvB^oa6}5^2s+Mg~Gw?#$u&ZP;u~mP|FXsVtr>3k9O?%v>`Ha-3QsOG<7KdXlqKrsN25R|K<<;- z8kFY!&J&Yrqx3ptevOHiqPxKo_wwAPD)$DWMz{0>{T5qM%>rMqGZ!dJdK(&tP1#89 zVcu}I1I-&3%nMyF62m%MDpl~p)PM(%YoR zD)=W)E7kjwzAr!?^P*`?=fMHd1q4yjLGTTRUidem^Ocjrfgk2Jp|6SabEVHKC3c>RX@tNx=&Z7gC z0ztZoZx+#o36xH8mv6;^e{vU;G{JW17kn(RO&0L%q^fpWSYSkr1Cb92@bV->VO5P z;=V{hS5wcROQfbah6ND{2a$zFnj>@yuOcw}X~E20g7)5=Z#(y)RC878{_rObmGQ;9 zUy>&`YT^2R@jqR1z9Fx&x)WBstIE#*UhAa>WrMm<10={@$UN@Cog+#pxq{W@l0DOf zJGs^Jv?t8HgIXk(;NFHXun$J{{p})cJ^BWn4BeQo6dMNp%JO@$9z{(}qqEHuZOUQP zZiwo70Oa@lMYL(W*R4(!oj`)9kRggJns-A|w+XL=P07>QBMTEbG^gPS)H zu^@MFTFZtsKGFHgj|hupbK({r>PX3_kc@|4Jdqr@gyyKrHw8Tu<#0&32Hh?S zsVm_kQ2K`4+=gjw1mVhdOz7dI7V!Iu8J1LgI+_rF`Wgx5-XwU~$h>b$%#$U3wWC-ea0P(At2SjPAm57kd;!W5k{do1}X681o}`!c*(w!kCjtGTh7`=!M)$9 zWjTns{<-WX+Xi;&d!lyV&1KT9dKL??8)fu2(?Ox<^?EAzt_(#5bp4wAfgIADYgLU` z;J7f8g%-tfmTI1ZHjgufKcAT4SO(vx?xSo4pdWh`3#Yk;DqPGQE0GD?!_CfXb(E8WoJt6*Yutnkvmb?7H9B zVICAYowwxK;VM4(#~|}~Ooyzm*1ddU_Yg%Ax*_FcZm^AzYc$<+9bv;Eucr(SSF}*JsjTfb*DY>qmmkt z;dRkB#~SylP~Jcmr&Bl9TxHf^DcGUelG%rA{&s)5*$|-ww}Kwx-lWnNeghVm@z zqi3@-oJnN%r2O4t9`5I5Zfc;^ROHmY6C9 z1VRRX*1+aBlbO_p>B+50f1p&%?_A*16R0n+l}HKWI$yIH3oq2`k4O?tEVd~a4~>iI zo{d}b8tr+$q<%%K%Ett*i|RAJEMnk9hU7LtL!lxOB45xO1g)ycDBd=NbpaE3j?Gw& z0M&xx13EkCgNHu%Z8rBLo93XH-zQUfF3{Iy>65-KSPniqIzF+?x$3>`L?oBOBeEsv zs_y7@7>IbS&w2Vju^#vBpPWQuUv=dDRGm(-MH|l+8T?vfgD;{nE_*-h?@D;GN>4hA z9{!G@ANfHZOxMq5kkoh4h*p3+zE7z$13ocDJR$XA*7uKtG5Cn_-ibn%2h{ z;J0m5aCjg(@_!G>i2FDAvcn5-Aby8b;J0u%u)!`PK#%0FS-C3(cq9J{V`DJEbbE|| zYpTDd+ulcjEd5`&v!?=hVgz&S0|C^We?2|>9|2T6?~nn^_CpLn&kuI|VG7_E{Ofu9 zAqe0Reuq5Zunlx@zyTqEL+ssT15X|Z0LUfZAr-i$1_SJ{j}BHmBm}s8{OgK3lm%4F zzC%jz!y!8WUJo2FLkU(mVh7-uzC+gcbkV^bM}&Y6=HTTca{!7ZSoB!)l|v<(3ly!jq&P5A2q(U5~h)))aj-`-6&aM~LBySnAy zA0{Z{FHiUb8rW|Yo%kQwi`Kh>EEE$0g7UxeeeVkcY%~87yCmSjYyxoqq(%Jib*lH; zz`t5y094U`k_o{-*U^dFH~+1I@GsgwqmGsQC9-Vr0X94TLhlV;Kt#`9h-N?oKHqpx zzVAOxltd%gzb_Qu{NHnE8vPp=G$#S)Y%&6drobF_#NeY%VLzeod delta 9041 zcmY*t@kVBCBP!g$Qih>$!M(|j-I?-C8+=cK0w!?cVWy9LXH zd%I}(h%K_>9Qvap&`U=={XcolW-VA%#t9ljo~WmY8+Eb|zcKX3eyx7qiuU|a)zU5cYm5{k5IAa3ibZf_B&=YT!-XyLap%QRdebT+PIcg$KjM3HqA3uZ5|yBj2vv8$L{#$>P=xi+J&zLILkooDarGpiupEiuy`9uy&>yEr95d)64m+~`y*NClGrY|5MLlv!)d5$QEtqW)BeBhrd)W5g1{S@J-t8_J1 zthp@?CJY}$LmSecnf3aicXde(pXfeCei4=~ZN=7VoeU|rEEIW^!UBtxGc6W$x6;0fjRs7Nn)*b9JW5*9uVAwi) zj&N7W;i<Qy80(5gsyEIEQm>_+4@4Ol)F?0{YzD(6V~e=zXmc2+R~P~< zuz5pju;(akH2+w5w!vnpoikD5_{L<6T`uCCi@_Uorr`L(8zh~x!yEK*!LN02Q1Iri z>v*dEX<(+_;6ZAOIzxm@PbfY4a>ws4D82&_{9UHCfll!x`6o8*i0ZB+B#Ziv%RgtG z*S}<4!&COp)*ZMmXzl0A8mWA$)fCEzk$Wex*YdB}_-v|k9>jKy^Y>3me;{{|Ab~AL zQC(naNU=JtU3aP6P>Fm-!_k1XbhdS0t~?uJ$ZvLbvow10>nh*%_Kh>7AD#IflU8SL zMRF1fmMX#v8m=MGGb7y5r!Qf~Y}vBW}fsG<{1CHX7Yz z=w*V9(vOs6eO>CDuhurDTf3DVVF^j~rqP*7S-$MLSW7Ab>8H-80ly;9Q0BWoNV zz8Wr2CdK!rW0`sMD&y{Ue{`mEkXm0%S2k;J^iMe|sV5xQbt$ojzfQE+6aM9LWH`t& z8B;Ig7S<1Dwq`3W*w59L(opjq)ll4E-c?MivCh!4>$0^*=DKI&T2&j?;Z82_iZV$H zKmK7tEs7;MI-Vo(9wc1b)kc(t(Yk? z#Hgo8PG_jlF1^|6ge%;(MG~6fuKDFFd&}>BlhBTh&mmuKsn>2buYS=<5BWw^`ncCb zrCRWR5`IwKC@URU8^aOJjSrhvO>s}O&RBD8&V=Fk2@~zYY?$qO&!9%s>YecVY0zhK zBxKGTTyJ(uF`p27CqwPU1y7*)r}y;{|0FUO)-8dKT^>=LUoU_6P^^utg|* zuj}LBA*gS?4EeEdy$bn#FGex)`#y|vg77NVEjTUn8%t z@l|7T({SM!y$PZy9lb2N;BaF}MfGM%rZk10aqvUF`CDaC)&Av|eED$x_;qSoAka*2 z2rR+OTZTAPBx`vQ{;Z{B4Ad}}qOBqg>P4xf%ta|}9kJ2$od>@gyC6Bf&DUE>sqqBT zYA>(sA=Scl2C_EF8)9d8xwdBSnH5uL=I4hch6KCHj-{99IywUD{HR`d(vk@Kvl)WD zXC(v{ZTsyLy{rio*6Wi6Lck%L(7T~Is-F_`2R}q z!H1ylg_)Mv&_|b1{tVl!t{;PDa!0v6^Zqs_`RdxI%@vR)n|`i`7O<>CIMzqI00y{;` zhoMyy>1}>?kAk~ND6}`qlUR=B+a&bvA)BWf%`@N)gt@@Ji2`p1GzRGC$r1<2KBO3N z++YMLD9c|bxC;za_UVJ*r6&Ea;_YC>-Ebe-H=VAgDmx+?Q=DxCE4=yQXrn z7(0X#oIjyfZUd}fv2$;4?8y|0!L^ep_rMz|1gU-hcgVYIlI~o>o$K&)$rwo(KJO~R zDcGKo-@im7C<&2$6+q-xtxlR`I4vL|wFd<`a|T}*Nt;(~Vwx&2QG_j$r0DktR+6I4W)gUx*cDVBwGe00aa803ZYiwy;d{1p)y0?*IT8ddPS`E~MiS z1d%Vm0Hb4LN2*f8FZ|6xRQev@ZK-?(oPs+mT*{%NqhGL_0dJ$?rAxA{2 z`r3MBv&)xblcd>@hArncJpL~C(_HTo&D&CS!_J5Giz$^2EfR_)xjgPg`Bq^u%1C*+ z7W*HGp|{B?dOM}|E)Cs$61y8>&-rHBw;A8 zgkWw}r$nT%t(1^GLeAVyj1l@)6UkHdM!%LJg|0%BO74M593&LlrksrgoO{iEz$}HK z4V>WXgk|7Ya!Vgm#WO^ZLtVjxwZ&k5wT6RteViH3ds{VO+2xMJZ`hToOz~_+hRfY{ z%M;ZDKRNTsK5#h6goUF(h#VXSB|7byWWle*d0$IHP+FA`y)Q^5W!|&N$ndaHexdTn z{vf?T$(9b&tI&O`^+IqpCheAFth;KY(kSl2su_9|Y1B{o9`mm)z^E`Bqw!n+JCRO) zGbIpJ@spvz=*Jki{wufWm|m`)XmDsxvbJR5dLF=kuf_C>dl}{nGO(g4I$8 zSSW#5$?vqUDZHe_%`Zm?Amd^>I4SkBvy+i}wiQYBxj0F1a$*%T+6}Yz?lX&iQ}zaU zI@%8cwVGtF3!Ke3De$dL5^j-$Bh3+By zrSR3c2a>XtaE#TB}^#hq@!vnZ1(An#bk_eKR{?;Z&0cgh4$cMNU2HL=m=YjMTI zT$BRltXs4T=im;Ao+$Bk3Dz(3!C;rTqelJ?RF)d~dP9>$_6dbz=_8#MQFMMX0S$waWxY#mtDn}1U{4PGeRH5?a>{>TU@1UlucMAmzrd@PCwr|il)m1fooO7Z{Vyr z6wn=2A5z(9g9-OU10X_ei50@~)$}w4u)b+mt)z-sz0X32m}NKTt4>!O{^4wA(|3A8 zkr(DxtMnl$Hol>~XNUE?h9;*pGG&kl*q_pb z&*$lH70zI=D^s)fU~A7cg4^tUF6*Oa+3W0=7FFB*bf$Kbqw1&amO50YeZM)SDScqy zTw$-M$NA<_We!@4!|-?V3CEPnfN4t}AeM9W$iSWYz8f;5H)V$pRjMhRV@Z&jDz#FF zXyWh7UiIc7=0U9L35=$G54RjAupR&4j`(O3i?qjOk6gb!WjNtl1Fj-VmltDTos-Bl z*OLfOleS~o3`?l!jTYIG!V7?c<;Xu(&#~xf-f(-jwow-0Hv7JZG>}YKvB=rRbdMyv zmao*-!L?)##-S#V^}oRm7^Db zT5C2RFY4>ov~?w!3l_H}t=#X=vY-*LQy(w>u%r`zQ`_RukSqIv@WyGXa-ppbk-X=g zyn?TH(`-m*in(w=Ny$%dHNSVxsL|_+X=+kM+v_w{ZC(okof9k1RP5qDvcA-d&u{5U z?)a9LXht1f6|Tdy5FgXo;sqR|CKxDKruU9RjK~P6xN+4;0eAc|^x%UO^&NM4!nK_! z6X14Zkk=5tqpl&d6FYuMmlLGQZep0UE3`fT>xzgH>C*hQ2VzCQlO`^kThU6q%3&K^ zf^kfQm|7SeU#c%f8e?A<9mALLJ-;)p_bv6$pp~49_o;>Y=GyUQ)*prjFbkU;z%HkOW_*a#j^0b@GF|`6c}7>=W{Ef!#dz5lpkN>@IH+(sx~QMEFe4 z1GeKK67;&P%ExtO>}^JxBeHii)ykX8W@aWhJO!H(w)DH4sPatQ$F-Phiqx_clj`9m zK;z7X6gD2)8kG^aTr|oY>vmgOPQ4`_W+xj2j!$YT9x(DH6pF~ zd_C#8c>Gfb)k2Ku4~t=Xb>T^8KW;2HPN#%}@@hC1lNf~Xk)~oj=w-Y11a@DtIyYk8 z9^|_RIAA(1qUSs3rowxr&OuRVFL8(zSqU_rGlqHpkeYT4z7DGdS0q4V-b!3fsv$Yb zPq4UP^3XFd(G%JAN|0y>?&sLzNir30K(lyzNYvCtE2gDyy-nthPlrXXU75fhoS7kA zg%GYyBEFQ(xgdjtv+>?>Q!G!8& z3+F>)4|N+F1a^T?XC8 zxRRx7-{DV%uUYt&*$z2uQTbZDbUn)PozID*(i^{JDjNq`v?;&OW^&~{ZPE_e+?RMk z!7O5CUKJSnGZvjTbLX2$zwYRZs_$f{T!hvVHuTg77|O;zBHlA|GIUu_bh4`Bl?7KE zYB~a`b?O;0SfD?0EZiPYpVf=P4=|zr(u_w}oP0S`YOZziX9cuwpll&%QMv4bBC_JdP#rT3>MliqySv0& zh)r=vw?no&;5T}QVTkHKY%t`%{#*#J;aw!wPs}?q2$(e0Y#cdBG1T09ypI@#-y24+fzhJem1NSZ$TCAjU2|ebYG&&6p(0f>wQoNqVa#6J^W!3$gIWEw7d<^k!U~O5v=8goq$jC`p8CS zrox#Jw3w`k&Ty7UVbm35nZ}FYT5`fN)TO6R`tEUFotxr^BTXZGt|n(Ymqmr^pCu^^w?uX!ONbm?q{y9FehdmcJuV8V%A-ma zgl=n9+op{wkj-}N;6t;(JA1A#VF3S9AFh6EXRa0~7qop~3^~t1>hc6rdS_4!+D?Xh z5y?j}*p@*-pmlTb#7C0x{E(E@%eepK_YycNkhrYH^0m)YR&gRuQi4ZqJNv6Rih0zQ zqjMuSng>Ps;?M0YVyh<;D3~;60;>exDe)Vq3x@GRf!$wgFY5w4=Jo=g*E{76%~jqr zxTtb_L4Cz_E4RTfm@0eXfr1%ho?zP(>dsRarS>!^uAh~bd0lEhe2x7AEZQmBc%rU; z&FUrs&mIt8DL`L4JpiFp3NNyk3N>iL6;Nohp*XbZZn%BDhF_y{&{X3UtX(7aAyG63P zELC;>2L`jnFS#vC->A(hZ!tGi7N7^YtW7-LB6!SVdEM&7N?g}r4rW2wLn{Ni*I~$Y z@#;KwJIl0^?eX{JWiHQxDvccnNKBhHW0h6`j=)OH1`)7)69B$XNT@)l1s25M+~o2_ zpa&X<_vHxN_oR|B#ir2p*VNB~o6Z1OE&~a+_|AxS)(@Dgznq(b(|K8BN_nQ7+>N`= zXOx_@AhcmmcRvp6eX#4z6sn=V0%KonKFVY@+m&)Rx!Z5U@WdyHMCF4_qzJNpzc9Fw z7Bdzx54(e7>wcEqHKqH-Paiut;~ZVJpS6_q>ub)zD#TQ4j*i(I8DvS$BfyX~A%<#} z*=g2$8s;YYjEHl`7cKw!a9PFRt8tVR zM&X|bs?B1#ycjl>AzgbdRkr-@NmBc^ys)aoT75F(yweV&Y-3hNNXj-valA&=)G{NL zX?smr5sQWi3n;GGPW{%vW)xw-#D0QY%zjXxYj?($b4JzpW0sWY!fkwC5bJMkhTp$J z6CNVLd=-Ktt7D<^-f|=wjNjf0l%@iu2dR+zdQ&9NLa(B_okKdRy^!Q!F$Ro=hF$-r z!3@ocUs^7?cvdTMPbn*8S-o!PsF;>FcBkBkg&ET`W`lp?j`Z}4>DF|}9407lK9y~^No&pT7J|rVQ9Dh>qg|%=gxxg=! z>WX$!;7s~gDPmPF<--(?CvEnvV*E1KdXpr>XVv!DN~PyISE7d+K_9+W^pnR6cX&?E ziLr{0`JIs@NcA|;8L|p!3H~9y8mga2Dsm4I?rBS7$3wcT!_l*$^8U3hKUri|_I3N2 zz$xY`)IWA7P*Y1BJtyBEh?8EEvs8Oyl^{(+`gi{9hwpcN#I%Z0j$^yBp?z<;Ny!G$ zra3J_^i0(~LiKuITs%v)qE+YrJr?~w+)`Rcte^O=nwmPg@&!Q7FGTtjpTdI6wH&ZV z)2}VZY6(MbP`tgoew++(pt$jVj- zvPK)pSJ)U(XfUqBqZNo|za#Xx+IVEb?HGQ^wUVH&wTdWgP(z#ijyvXjwk>tFBUn*2 zuj5ENQjT{2&T`k;q54*Z>O~djuUBNwc6l(BzY?Ed4SIt9QA&8+>qaRIck?WdD0rh@ zh`VTZPwSNNCcLH3J}(q zdEtu@HfxDTpEqWruG=86m;QVO{}E&q8qYWhmA>(FjW`V&rg!CEL1oZCZcAX@yX(2tg8`>m1psG0ZpO+Rnph@Bhjj!~|+S=@+U{*ukwGrBj{5xfIHHP7|} z^7@g2;d%FMO8f(MS&6c##mrX2i(5uiX1o(=Vw89IQcHw)n{ZTS@``xT$Af@CQTP#w zl3kn6+MJP+l(;K-rWgjpdBU|CB4>W%cObZBH^Am~EvRO%D>uU^HVRXi$1 zb?Pr~ZlopLfT5l%03SjI7>YiGZZs=n(A!c;N9%%aByY~5(-hS4z_i2wgKYsG%OhhxH#^5i%&9ESb(@# zV_f5${Gf=$BK)1VY=NX#f+M}6f`OWmpC*OU3&+P@n>$Xvco*Nm$c<=`S|lY6S}Ut- z80}ztIpkV>W%^Ox`enpk<25_i7`RPiDugxHfUDBD8$bp9XR15>a?r^#&!1Ne6n{MI z){H`!jwrx}8b-w@@E8H0v)l!5!W8En=u67v+`iNoz<_h4{V*qQK+@)JP^JqsKAedZ zNh4toE+I7;^}7kkj|hzNVFWkZ$N9rxPl9|_@2kbW*4}&o%(L`WpQCN2M?gz>cyWHk zulMwRxpdpx+~P(({@%UY20LwM7sA&1M|`bEoq)Id zyUHt>@vfu**UOL9wiW*C75cc&qBX37qLd`<;$gS+mvL^v3Z8i4p6(@Wv`N|U6Exn< zd`@WxqU^8u^Aw+uw#vuDEIByaD)vucU2{4xRseczf_TJXUwaUK+E_IoItXJq88${0 z=K5jGehPa2)CnH&Lcxv&1jQ=T8>*vgp1^%)c&C2TL69;vSN)Q)e#Hj7!oS0 zlrEmJ=w4N9pID5KEY5qz;?2Q}0|4ESEio&cLrp221LTt~j3KjUB`LU?tP=p;B=WSXo;C?8(pnF6@?-ZD0m3DYZ* z#SzaXh|)hmTC|zQOG>aEMw%4&2XU?prlk5(M3ay-YC^QLRMN+TIB*;TB=wL_atpeD zh-!sS%A`3 z=^?niQx+^za_wQd2hRR=hsR0uzUoyOcrY!z7W)G2|C-_gqc`wrG5qCuU!Z?g*GL^H z?j^<_-A6BC^Dp`p(i0!1&?U{YlF@!|W{E@h=qQ&5*|U~V8wS;m!RK(Q6aX~oH9ToE zZYKXZoRV~!?P1ADJ74J-PFk2A{e&gh2o)@yZOZuBi^0+Hkp`dX;cZs9CRM+##;P!*BlA%M48TuR zWUgfD1DLsLs+-4XC>o>wbv-B)!t*47ON5wgoMX%llnmXG%L8209Vi;yZ`+N2v2Ox+ zMe7JHunQE$ckHHhEYRA+e`A3=XO5L%fMau71`XL7v)b{f1rkTY+WWSIkH#sG=pLqe zA(xZIp>_=4$zKq0t_G7q9@L zZ5D-0{8o%7f>0szA#c;rjL;4Y%hl}wYrx1R`Viq|Pz}c-{{LJY070ym@E~mt*pTyG z79bfcWTGGEje;PLD;N-XHw=`wS^howfzb$%oP8n)lN$o$ZWjZx|6iSsi2piI_7s7z zX#b$@z6kIJ^9{-Y^~wJ!s0V^Td5V7#4&pyU#NHw#9)N&qbpNFDR1jqC00W}91OnnS z{$J@GBz%bka`xsz;rb_iJ|rgmpUVyEZ)Xi*SO5U&|NFkTHb3y@e@%{WrvE&Jp#Lw^ zcj13CbsW+V>i@rj@SEfFf0@yjS@nbPB0)6D`lA;e%61nh`-qhydO!uS7jXGQd%i7opEnOL;| zDn!3EUm(V796;f?fA+RDF<@%qKlo)`0VtL74`!~516_aogYP%QfG#<2kQ!pijthz2 zpaFX3|D$%C7!bL242U?-e@2QZ`q$~lgZbvgfLLyVfT1OC5<8@6lLi=A{stK#zJmWd zlx+(HbgX)l$RGwH|2rV@P3o@xCrxch0$*z1ASpy(n+d4d2XWd~2AYjQm`xZU3af8F p+x$Nxf1895@0bJirXkdpJh+N7@Nb7x007(DEB&^Lm}dWn{T~m64-^0Z diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties index a71c7a7d..74147692 100644 --- a/gradle/wrapper/gradle-wrapper.properties +++ b/gradle/wrapper/gradle-wrapper.properties @@ -1,5 +1,5 @@ distributionBase=GRADLE_USER_HOME distributionPath=permwrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-7.3.3-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-7.5.1-bin.zip zipStoreBase=GRADLE_USER_HOME zipStorePath=permwrapper/dists diff --git a/gradlew b/gradlew index c53aefaa..a69d9cb6 100755 --- a/gradlew +++ b/gradlew @@ -1,7 +1,7 @@ #!/bin/sh # -# Copyright © 2015-2021 the original authors. +# Copyright © 2015-2021 the original authors. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -32,10 +32,10 @@ # Busybox and similar reduced shells will NOT work, because this script # requires all of these POSIX shell features: # * functions; -# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», -# «${var#prefix}», «${var%suffix}», and «$( cmd )»; -# * compound commands having a testable exit status, especially «case»; -# * various built-in commands including «command», «set», and «ulimit». +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». # # Important for patching: # @@ -205,6 +205,12 @@ set -- \ org.gradle.wrapper.GradleWrapperMain \ "$@" +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + # Use "xargs" to parse quoted args. # # With -n1 it outputs one arg per line, with the quotes and backslashes removed. diff --git a/gradlew.bat b/gradlew.bat index ac1b06f9..53a6b238 100644 --- a/gradlew.bat +++ b/gradlew.bat @@ -14,7 +14,7 @@ @rem limitations under the License. @rem -@if "%DEBUG%" == "" @echo off +@if "%DEBUG%"=="" @echo off @rem ########################################################################## @rem @rem Gradle startup script for Windows @@ -25,7 +25,7 @@ if "%OS%"=="Windows_NT" setlocal set DIRNAME=%~dp0 -if "%DIRNAME%" == "" set DIRNAME=. +if "%DIRNAME%"=="" set DIRNAME=. set APP_BASE_NAME=%~n0 set APP_HOME=%DIRNAME% @@ -40,7 +40,7 @@ if defined JAVA_HOME goto findJavaFromJavaHome set JAVA_EXE=java.exe %JAVA_EXE% -version >NUL 2>&1 -if "%ERRORLEVEL%" == "0" goto execute +if %ERRORLEVEL% equ 0 goto execute echo. echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. @@ -75,13 +75,15 @@ set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar :end @rem End local scope for the variables with windows NT shell -if "%ERRORLEVEL%"=="0" goto mainEnd +if %ERRORLEVEL% equ 0 goto mainEnd :fail rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of rem the _cmd.exe /c_ return code! -if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1 -exit /b 1 +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% :mainEnd if "%OS%"=="Windows_NT" endlocal diff --git a/settings.gradle b/settings.gradle index aa06df79..ae1af1c0 100644 --- a/settings.gradle +++ b/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2022' + String frcYear = '2023' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 4b8a7301..86798458 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -174,7 +174,9 @@ public Clock getClock() { @Override public boolean hasNewDriverStationData() { - return DriverStation.isNewControlData(); + // TODO: replace implementation with event counting one + // return DriverStation.isNewControlData(); + return true; } @Override diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix.json index 789d831f..72371c03 100644 --- a/vendordeps/Phoenix.json +++ b/vendordeps/Phoenix.json @@ -1,150 +1,248 @@ { "fileName": "Phoenix.json", - "name": "CTRE-Phoenix", - "version": "5.20.2", - "frcYear": 2022, + "name": "CTRE-Phoenix (v5)", + "version": "5.30.3", + "frcYear": 2023, "uuid": "ab676553-b602-441f-a38d-f1296eff6537", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix-frc2022-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2023-latest.json", "javaDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "api-java", - "version": "5.20.2" + "version": "5.30.3" }, { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-java", - "version": "5.20.2" + "version": "5.30.3" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.20.2", + "version": "5.30.3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", "linuxathena" - ] + ], + "simMode": "hwsim" }, { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.20.2", + "version": "5.30.3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro", + "artifactId": "tools", + "version": "23.0.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "tools-sim", + "version": "23.0.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", - "version": "5.20.2", + "version": "23.0.2", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", - "version": "5.20.2", + "version": "23.0.2", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", - "version": "5.20.2", + "version": "23.0.2", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", - "version": "5.20.2", + "version": "23.0.2", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", - "version": "5.20.2", + "version": "23.0.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "simProTalonFX", + "version": "23.0.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "simProCANcoder", + "version": "23.0.2", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "simProPigeon2", + "version": "23.0.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" } ], "cppDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-cpp", - "version": "5.20.2", + "version": "5.30.3", "libName": "CTRE_Phoenix_WPI", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", "linuxathena" - ] + ], + "simMode": "hwsim" }, { "groupId": "com.ctre.phoenix", "artifactId": "api-cpp", - "version": "5.20.2", + "version": "5.30.3", "libName": "CTRE_Phoenix", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", "linuxathena" - ] + ], + "simMode": "hwsim" }, { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.20.2", + "version": "5.30.3", "libName": "CTRE_PhoenixCCI", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenixpro", + "artifactId": "tools", + "version": "23.0.2", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", "linuxathena" - ] + ], + "simMode": "hwsim" }, { "groupId": "com.ctre.phoenix.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.20.2", + "version": "5.30.3", "libName": "CTRE_Phoenix_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -152,13 +250,14 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { "groupId": "com.ctre.phoenix.sim", "artifactId": "api-cpp-sim", - "version": "5.20.2", + "version": "5.30.3", "libName": "CTRE_PhoenixSim", "headerClassifier": "headers", "sharedLibrary": true, @@ -166,13 +265,14 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.20.2", + "version": "5.30.3", "libName": "CTRE_PhoenixCCISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -180,13 +280,29 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "tools-sim", + "version": "23.0.2", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", - "version": "5.20.2", + "version": "23.0.2", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -194,13 +310,14 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", - "version": "5.20.2", + "version": "23.0.2", "libName": "CTRE_SimTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -208,13 +325,14 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", - "version": "5.20.2", + "version": "23.0.2", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -222,13 +340,14 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", - "version": "5.20.2", + "version": "23.0.2", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -236,13 +355,14 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", - "version": "5.20.2", + "version": "23.0.2", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -250,8 +370,54 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxx86-64" - ] + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "simProTalonFX", + "version": "23.0.2", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "simProCANcoder", + "version": "23.0.2", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenixpro.sim", + "artifactId": "simProPigeon2", + "version": "23.0.2", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" } ] } \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index 997e2a46..cdbbe6ed 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,34 +1,34 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2022.1.1", + "version": "2023.1.2", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", "javaDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2022.1.1" + "version": "2023.1.2" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2022.1.1", + "version": "2023.1.2", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ "windowsx86-64", "windowsx86", - "linuxaarch64bionic", + "linuxarm64", "linuxx86-64", "linuxathena", - "linuxraspbian", - "osxx86-64" + "linuxarm32", + "osxuniversal" ] } ], @@ -36,7 +36,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2022.1.1", + "version": "2023.1.2", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -44,17 +44,17 @@ "binaryPlatforms": [ "windowsx86-64", "windowsx86", - "linuxaarch64bionic", + "linuxarm64", "linuxx86-64", "linuxathena", - "linuxraspbian", - "osxx86-64" + "linuxarm32", + "osxuniversal" ] }, { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2022.1.1", + "version": "2023.1.2", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, @@ -62,11 +62,11 @@ "binaryPlatforms": [ "windowsx86-64", "windowsx86", - "linuxaarch64bionic", + "linuxarm64", "linuxx86-64", "linuxathena", - "linuxraspbian", - "osxx86-64" + "linuxarm32", + "osxuniversal" ] } ] diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json index 83de291e..65dcc03c 100644 --- a/vendordeps/WPILibNewCommands.json +++ b/vendordeps/WPILibNewCommands.json @@ -1,37 +1,37 @@ { - "fileName": "WPILibNewCommands.json", - "name": "WPILib-New-Commands", - "version": "2020.0.0", - "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", - "mavenUrls": [], - "jsonUrl": "", - "javaDependencies": [ - { - "groupId": "edu.wpi.first.wpilibNewCommands", - "artifactId": "wpilibNewCommands-java", - "version": "wpilib" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "edu.wpi.first.wpilibNewCommands", - "artifactId": "wpilibNewCommands-cpp", - "version": "wpilib", - "libName": "wpilibNewCommands", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxraspbian", - "linuxaarch64bionic", - "windowsx86-64", - "windowsx86", - "linuxx86-64", - "osxx86-64" - ] - } - ] -} \ No newline at end of file + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "1.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxarm32", + "linuxarm64", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxuniversal" + ] + } + ] +} diff --git a/vendordeps/WPILibOldCommands.json b/vendordeps/WPILibOldCommands.json deleted file mode 100644 index 7bdad212..00000000 --- a/vendordeps/WPILibOldCommands.json +++ /dev/null @@ -1,37 +0,0 @@ -{ - "fileName": "WPILibOldCommands.json", - "name": "WPILib-Old-Commands", - "version": "2020.0.0", - "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e", - "mavenUrls": [], - "jsonUrl": "", - "javaDependencies": [ - { - "groupId": "edu.wpi.first.wpilibOldCommands", - "artifactId": "wpilibOldCommands-java", - "version": "wpilib" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "edu.wpi.first.wpilibOldCommands", - "artifactId": "wpilibOldCommands-cpp", - "version": "wpilib", - "libName": "wpilibOldCommands", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxraspbian", - "linuxaarch64bionic", - "windowsx86-64", - "windowsx86", - "linuxx86-64", - "osxx86-64" - ] - } - ] -} diff --git a/vendordeps/navx_frc.json b/vendordeps/navx_frc.json index 0fb49a7e..17186925 100644 --- a/vendordeps/navx_frc.json +++ b/vendordeps/navx_frc.json @@ -1,7 +1,7 @@ { "fileName": "navx_frc.json", "name": "KauaiLabs_navX_FRC", - "version": "4.0.442", + "version": "4.0.447", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", "mavenUrls": [ "https://repo1.maven.org/maven2/" @@ -11,7 +11,7 @@ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-java", - "version": "4.0.442" + "version": "4.0.447" } ], "jniDependencies": [], @@ -19,7 +19,7 @@ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-cpp", - "version": "4.0.442", + "version": "4.0.447", "headerClassifier": "headers", "sourcesClassifier": "sources", "sharedLibrary": false, From 2985ad2914b03c9daeccd3f4c1ede83c72c1e92d Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Sat, 14 Jan 2023 15:08:33 -0800 Subject: [PATCH 004/103] more merges from WPILib 2023 changes --- gradle/wrapper/gradle-wrapper.jar | Bin 59536 -> 60756 bytes vendordeps/WPILibOldCommands.json | 37 ------------------------------ 2 files changed, 37 deletions(-) delete mode 100644 vendordeps/WPILibOldCommands.json diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar index 7454180f2ae8848c63b8b4dea2cb829da983f2fa..249e5832f090a2944b7473328c07c9755baa3196 100644 GIT binary patch delta 10158 zcmaKSbyOWsmn~e}-QC?axCPf>!2<-jxI0|j{UX8L-QC?axDz};a7}ppGBe+Nv*x{5 zy?WI?=j^WT(_Md5*V*xNP>X9&wM>xUvNiMuKDK=Xg!N%oM>Yru2rh7#yD-sW0Ov#$ zCKBSOD3>TM%&1T5t&#FK@|@1f)Ze+EE6(7`}J(Ek4})CD@I+W;L{ zO>K;wokKMA)EC6C|D@nz%D2L3U=Nm(qc>e4GM3WsHGu-T?l^PV6m-T-(igun?PZ8U z{qbiLDMcGSF1`FiKhlsV@qPMRm~h9@z3DZmWp;Suh%5BdP6jqHn}$-gu`_xNg|j{PSJ0n$ zbE;Azwq8z6IBlgKIEKc4V?*##hGW#t*rh=f<;~RFWotXS$vr;Mqz>A99PMH3N5BMi zWLNRjc57*z`2)gBV0o4rcGM(u*EG8_H5(|kThAnp|}u2xz>>X6tN zv)$|P2Nr1D*fk4wvqf(7;NmdRV3eL{!>DO-B98(s*-4$g{)EnRYAw+DP-C`=k)B!* zHU7!ejcbavGCYuz9k@$aZQaU%#K%6`D}=N_m?~^)IcmQZun+K)fSIoS>Ws zwvZ%Rfmw>%c!kCd~Pmf$E%LCj2r>+FzKGDm+%u88|hHprot{*OIVpi`Vd^^aumtx2L}h} zPu$v~zdHaWPF<`LVQX4i7bk82h#RwRyORx*z3I}o&>>eBDCif%s7&*vF6kU%1` zf(bvILch^~>cQ{=Y#?nx(8C-Uuv7!2_YeCfo?zkP;FK zX+KdjKS;HQ+7 zj>MCBI=d$~9KDJ1I2sb_3=T6D+Mu9{O&vcTnDA(I#<=L8csjEqsOe=&`=QBc7~>u2 zfdcO44PUOST%PcN+8PzKFYoR0;KJ$-Nwu#MgSM{_!?r&%rVM}acp>53if|vpH)q=O z;6uAi__am8g$EjZ33?PmCrg@(M!V_@(^+#wAWNu&e3*pGlfhF2<3NobAC zlusz>wMV--3ytd@S047g)-J@eOD;DMnC~@zvS=Gnw3=LnRzkeV`LH4#JGPklE4!Q3 zq&;|yGR0FiuE-|&1p2g{MG!Z3)oO9Jf4@0h*3!+RHv=SiEf*oGQCSRQf=LqT5~sajcJ8XjE>E*@q$n z!4|Rz%Lv8TgI23JV6%)N&`Otk6&RBdS|lCe7+#yAfdyEWNTfFb&*S6-;Q}d`de!}*3vM(z71&3 z37B%@GWjeQ_$lr%`m-8B&Zl4Gv^X{+N{GCsQGr!LLU4SHmLt3{B*z-HP{73G8u>nK zHxNQ4eduv>lARQfULUtIlLx#7ea+O;w?LH}FF28c9pg#*M`pB~{jQmPB*gA;Hik#e zZpz&X#O}}r#O_#oSr4f`zN^wedt>ST791bAZ5(=g<Oj)m9X8J^>Th}fznPY0T zsD9ayM7Hrlb6?jHXL<{kdA*Q#UPCYce0p`fHxoZ7_P`cF-$1YY9Pi;0QFt{CCf%C# zuF60A_NTstTQeFR3)O*ThlWKk08}7Nshh}J-sGY=gzE!?(_ZI4ovF6oZ$)&Zt~WZi z_0@Bk!~R4+<&b6CjI{nGj+P{*+9}6;{RwZ7^?H)xjhiRi;?A|wb0UxjPr?L@$^v|0= z@6d3+eU|&re3+G*XgFS}tih3;>2-R1x>`2hmUb5+Z~eM4P|$ zAxvE$l@sIhf_#YLnF|Wcfp(Gh@@dJ-yh|FhKqsyQp_>7j1)w|~5OKETx2P$~`}5huK;{gw_~HXP6=RsG)FKSZ=VYkt+0z&D zr?`R3bqVV?Zmqj&PQ`G3b^PIrd{_K|Hhqt zAUS#|*WpEOeZ{@h*j6%wYsrL`oHNV=z*^}yT1NCTgk1-Gl(&+TqZhODTKb9|0$3;| z;{UUq7X9Oz`*gwbi|?&USWH?Fr;6=@Be4w=8zu>DLUsrwf+7A`)lpdGykP`^SA8{ok{KE3sM$N@l}kB2GDe7MEN? zWcQ2I0fJ1ZK%s-YKk?QbEBO6`C{bg$%le0FTgfmSan-Kih0A7)rGy|2gd)_gRH7qp z*bNlP0u|S^5<)kFcd&wQg*6QP5;y(3ZgI%vUgWk#`g!sMf`02>@xz{Ie9_-fXllyw zh>P%cK+-HkQ;D$Jh=ig(ASN^zJ7|q*#m;}2M*T#s0a^nF_>jI(L(|*}#|$O&B^t!W zv-^-vP)kuu+b%(o3j)B@do)n*Y0x%YNy`sYj*-z2ncYoggD6l z6{1LndTQUh+GCX;7rCrT z@=vy&^1zyl{#7vRPv;R^PZPaIks8okq)To8!Cks0&`Y^Xy5iOWC+MmCg0Jl?1ufXO zaK8Q5IO~J&E|<;MnF_oXLc=LU#m{6yeomA^Ood;)fEqGPeD|fJiz(`OHF_f*{oWJq z1_$NF&Mo7@GKae#f4AD|KIkGVi~ubOj1C>>WCpQq>MeDTR_2xL01^+K1+ zr$}J>d=fW{65hi2bz&zqRKs8zpDln z*7+Gtfz6rkgfj~#{MB=49FRP;ge*e0=x#czw5N{@T1{EAl;G&@tpS!+&2&Stf<%<+55R18u2%+}`?PZo8xg|Y9Xli(fSQyC7 z+O5{;ZyW$!eYR~gy>;l6cA+e`oXN6a6t(&kUkWus*Kf<m$W7L)w5uXYF)->OeWMSUVXi;N#sY zvz4c?GkBU{D;FaQ)9|HU7$?BX8DFH%hC11a@6s4lI}y{XrB~jd{w1x&6bD?gemdlV z-+ZnCcldFanu`P=S0S7XzwXO(7N9KV?AkgZzm|J&f{l-Dp<)|-S7?*@HBIfRxmo1% zcB4`;Al{w-OFD08g=Qochf9=gb56_FPc{C9N5UAjTcJ(`$>)wVhW=A<8i#!bmKD#6~wMBak^2(p56d2vs&O6s4>#NB0UVr24K z%cw|-Yv}g5`_zcEqrZBaRSoBm;BuXJM^+W$yUVS9?u(`87t)IokPgC_bQ3g_#@0Yg zywb?u{Di7zd3XQ$y!m^c`6~t-7@g-hwnTppbOXckS-^N?w1`kRMpC!mfMY?K#^Ldm zYL>771%d{+iqh4a&4RdLNt3_(^^*{U2!A>u^b{7e@}Azd_PiZ>d~(@(Q@EYElLAx3LgQ5(ZUf*I%EbGiBTG!g#=t zXbmPhWH`*B;aZI)$+PWX+W)z?3kTOi{2UY9*b9bpSU!GWcVu+)!^b4MJhf=U9c?jj z%V)EOF8X3qC5~+!Pmmmd@gXzbycd5Jdn!N#i^50a$4u}8^O}DG2$w-U|8QkR-WU1mk4pF z#_imS#~c2~Z{>!oE?wfYc+T+g=eJL`{bL6=Gf_lat2s=|RxgP!e#L|6XA8w{#(Po(xk1~rNQ4UiG``U`eKy7`ot;xv4 zdv54BHMXIq;#^B%W(b8xt%JRueW5PZsB2eW=s3k^Pe1C$-NN8~UA~)=Oy->22yJ%e zu=(XD^5s{MkmWB)AF_qCFf&SDH%ytqpt-jgs35XK8Ez5FUj?uD3++@2%*9+-65LGQ zvu1eopeQoFW98@kzU{+He9$Yj#`vaQkqu%?1wCoBd%G=)TROYl2trZa{AZ@#^LARR zdzg-?EUnt9dK2;W=zCcVj18RTj-%w^#pREbgpD0aL@_v-XV2&Cd@JB^(}GRBU}9gV z6sWmVZmFZ9qrBN%4b?seOcOdOZ+6cx8-#R(+LYKJu~Y%pF5#85aF9$MnP7r^Bu%D? zT{b-KBujiy>7_*9{8u0|mTJ(atnnnS%qBDM_Gx5>3V+2~Wt=EeT4cXOdud$+weM(>wdBg+cV$}6%(ccP;`!~CzW{0O2aLY z?rQtBB6`ZztPP@_&`kzDzxc==?a{PUPUbbX31Vy?_(;c+>3q*!df!K(LQYZNrZ>$A*8<4M%e8vj1`%(x9)d~);ym4p zoo518$>9Pe| zZaFGj);h?khh*kgUI-Xvj+Dr#r&~FhU=eQ--$ZcOY9;x%&3U(&)q}eJs=)K5kUgi5 zNaI-m&4?wlwFO^`5l-B?17w4RFk(IKy5fpS0K%txp0qOj$e=+1EUJbLd-u>TYNna~ z+m?gU0~xlcnP>J>%m_y_*7hVMj3d&)2xV8>F%J;6ncm)ILGzF2sPAV|uYk5!-F%jL(53^51BKr zc3g7+v^w<4WIhk7a#{N6Ku_u{F`eo;X+u!C(lIaiY#*V5!sMed39%-AgV*`(nI)Im zemHE^2foBMPyIP<*yuD21{6I?Co?_{pqp-*#N6sZRQAzEBV4HQheOyZT5UBd)>G85 zw^xHvCEP4AJk<{v2kQQ;g;C)rCY=X!c8rNpNJ4mHETN}t1rwSe7=s8u&LzW-+6AEB z)LX0o7`EqC94HM{4p}d2wOwj2EB|O;?&^FeG9ZrT%c!J&x`Z3D2!cm(UZbFBb`+h ztfhjq75yuSn2~|Pc)p$Ul6=)}7cfXtBsvc15f&(K{jnEsw5Gh0GM^O=JC+X-~@r1kI$=FH=yBzsO#PxR1xU9+T{KuPx7sMe~GX zSP>AT3%(Xs@Ez**e@GAn{-GvB^oa6}5^2s+Mg~Gw?#$u&ZP;u~mP|FXsVtr>3k9O?%v>`Ha-3QsOG<7KdXlqKrsN25R|K<<;- z8kFY!&J&Yrqx3ptevOHiqPxKo_wwAPD)$DWMz{0>{T5qM%>rMqGZ!dJdK(&tP1#89 zVcu}I1I-&3%nMyF62m%MDpl~p)PM(%YoR zD)=W)E7kjwzAr!?^P*`?=fMHd1q4yjLGTTRUidem^Ocjrfgk2Jp|6SabEVHKC3c>RX@tNx=&Z7gC z0ztZoZx+#o36xH8mv6;^e{vU;G{JW17kn(RO&0L%q^fpWSYSkr1Cb92@bV->VO5P z;=V{hS5wcROQfbah6ND{2a$zFnj>@yuOcw}X~E20g7)5=Z#(y)RC878{_rObmGQ;9 zUy>&`YT^2R@jqR1z9Fx&x)WBstIE#*UhAa>WrMm<10={@$UN@Cog+#pxq{W@l0DOf zJGs^Jv?t8HgIXk(;NFHXun$J{{p})cJ^BWn4BeQo6dMNp%JO@$9z{(}qqEHuZOUQP zZiwo70Oa@lMYL(W*R4(!oj`)9kRggJns-A|w+XL=P07>QBMTEbG^gPS)H zu^@MFTFZtsKGFHgj|hupbK({r>PX3_kc@|4Jdqr@gyyKrHw8Tu<#0&32Hh?S zsVm_kQ2K`4+=gjw1mVhdOz7dI7V!Iu8J1LgI+_rF`Wgx5-XwU~$h>b$%#$U3wWC-ea0P(At2SjPAm57kd;!W5k{do1}X681o}`!c*(w!kCjtGTh7`=!M)$9 zWjTns{<-WX+Xi;&d!lyV&1KT9dKL??8)fu2(?Ox<^?EAzt_(#5bp4wAfgIADYgLU` z;J7f8g%-tfmTI1ZHjgufKcAT4SO(vx?xSo4pdWh`3#Yk;DqPGQE0GD?!_CfXb(E8WoJt6*Yutnkvmb?7H9B zVICAYowwxK;VM4(#~|}~Ooyzm*1ddU_Yg%Ax*_FcZm^AzYc$<+9bv;Eucr(SSF}*JsjTfb*DY>qmmkt z;dRkB#~SylP~Jcmr&Bl9TxHf^DcGUelG%rA{&s)5*$|-ww}Kwx-lWnNeghVm@z zqi3@-oJnN%r2O4t9`5I5Zfc;^ROHmY6C9 z1VRRX*1+aBlbO_p>B+50f1p&%?_A*16R0n+l}HKWI$yIH3oq2`k4O?tEVd~a4~>iI zo{d}b8tr+$q<%%K%Ett*i|RAJEMnk9hU7LtL!lxOB45xO1g)ycDBd=NbpaE3j?Gw& z0M&xx13EkCgNHu%Z8rBLo93XH-zQUfF3{Iy>65-KSPniqIzF+?x$3>`L?oBOBeEsv zs_y7@7>IbS&w2Vju^#vBpPWQuUv=dDRGm(-MH|l+8T?vfgD;{nE_*-h?@D;GN>4hA z9{!G@ANfHZOxMq5kkoh4h*p3+zE7z$13ocDJR$XA*7uKtG5Cn_-ibn%2h{ z;J0m5aCjg(@_!G>i2FDAvcn5-Aby8b;J0u%u)!`PK#%0FS-C3(cq9J{V`DJEbbE|| zYpTDd+ulcjEd5`&v!?=hVgz&S0|C^We?2|>9|2T6?~nn^_CpLn&kuI|VG7_E{Ofu9 zAqe0Reuq5Zunlx@zyTqEL+ssT15X|Z0LUfZAr-i$1_SJ{j}BHmBm}s8{OgK3lm%4F zzC%jz!y!8WUJo2FLkU(mVh7-uzC+gcbkV^bM}&Y6=HTTca{!7ZSoB!)l|v<(3ly!jq&P5A2q(U5~h)))aj-`-6&aM~LBySnAy zA0{Z{FHiUb8rW|Yo%kQwi`Kh>EEE$0g7UxeeeVkcY%~87yCmSjYyxoqq(%Jib*lH; zz`t5y094U`k_o{-*U^dFH~+1I@GsgwqmGsQC9-Vr0X94TLhlV;Kt#`9h-N?oKHqpx zzVAOxltd%gzb_Qu{NHnE8vPp=G$#S)Y%&6drobF_#NeY%VLzeod delta 9041 zcmY*t@kVBCBP!g$Qih>$!M(|j-I?-C8+=cK0w!?cVWy9LXH zd%I}(h%K_>9Qvap&`U=={XcolW-VA%#t9ljo~WmY8+Eb|zcKX3eyx7qiuU|a)zU5cYm5{k5IAa3ibZf_B&=YT!-XyLap%QRdebT+PIcg$KjM3HqA3uZ5|yBj2vv8$L{#$>P=xi+J&zLILkooDarGpiupEiuy`9uy&>yEr95d)64m+~`y*NClGrY|5MLlv!)d5$QEtqW)BeBhrd)W5g1{S@J-t8_J1 zthp@?CJY}$LmSecnf3aicXde(pXfeCei4=~ZN=7VoeU|rEEIW^!UBtxGc6W$x6;0fjRs7Nn)*b9JW5*9uVAwi) zj&N7W;i<Qy80(5gsyEIEQm>_+4@4Ol)F?0{YzD(6V~e=zXmc2+R~P~< zuz5pju;(akH2+w5w!vnpoikD5_{L<6T`uCCi@_Uorr`L(8zh~x!yEK*!LN02Q1Iri z>v*dEX<(+_;6ZAOIzxm@PbfY4a>ws4D82&_{9UHCfll!x`6o8*i0ZB+B#Ziv%RgtG z*S}<4!&COp)*ZMmXzl0A8mWA$)fCEzk$Wex*YdB}_-v|k9>jKy^Y>3me;{{|Ab~AL zQC(naNU=JtU3aP6P>Fm-!_k1XbhdS0t~?uJ$ZvLbvow10>nh*%_Kh>7AD#IflU8SL zMRF1fmMX#v8m=MGGb7y5r!Qf~Y}vBW}fsG<{1CHX7Yz z=w*V9(vOs6eO>CDuhurDTf3DVVF^j~rqP*7S-$MLSW7Ab>8H-80ly;9Q0BWoNV zz8Wr2CdK!rW0`sMD&y{Ue{`mEkXm0%S2k;J^iMe|sV5xQbt$ojzfQE+6aM9LWH`t& z8B;Ig7S<1Dwq`3W*w59L(opjq)ll4E-c?MivCh!4>$0^*=DKI&T2&j?;Z82_iZV$H zKmK7tEs7;MI-Vo(9wc1b)kc(t(Yk? z#Hgo8PG_jlF1^|6ge%;(MG~6fuKDFFd&}>BlhBTh&mmuKsn>2buYS=<5BWw^`ncCb zrCRWR5`IwKC@URU8^aOJjSrhvO>s}O&RBD8&V=Fk2@~zYY?$qO&!9%s>YecVY0zhK zBxKGTTyJ(uF`p27CqwPU1y7*)r}y;{|0FUO)-8dKT^>=LUoU_6P^^utg|* zuj}LBA*gS?4EeEdy$bn#FGex)`#y|vg77NVEjTUn8%t z@l|7T({SM!y$PZy9lb2N;BaF}MfGM%rZk10aqvUF`CDaC)&Av|eED$x_;qSoAka*2 z2rR+OTZTAPBx`vQ{;Z{B4Ad}}qOBqg>P4xf%ta|}9kJ2$od>@gyC6Bf&DUE>sqqBT zYA>(sA=Scl2C_EF8)9d8xwdBSnH5uL=I4hch6KCHj-{99IywUD{HR`d(vk@Kvl)WD zXC(v{ZTsyLy{rio*6Wi6Lck%L(7T~Is-F_`2R}q z!H1ylg_)Mv&_|b1{tVl!t{;PDa!0v6^Zqs_`RdxI%@vR)n|`i`7O<>CIMzqI00y{;` zhoMyy>1}>?kAk~ND6}`qlUR=B+a&bvA)BWf%`@N)gt@@Ji2`p1GzRGC$r1<2KBO3N z++YMLD9c|bxC;za_UVJ*r6&Ea;_YC>-Ebe-H=VAgDmx+?Q=DxCE4=yQXrn z7(0X#oIjyfZUd}fv2$;4?8y|0!L^ep_rMz|1gU-hcgVYIlI~o>o$K&)$rwo(KJO~R zDcGKo-@im7C<&2$6+q-xtxlR`I4vL|wFd<`a|T}*Nt;(~Vwx&2QG_j$r0DktR+6I4W)gUx*cDVBwGe00aa803ZYiwy;d{1p)y0?*IT8ddPS`E~MiS z1d%Vm0Hb4LN2*f8FZ|6xRQev@ZK-?(oPs+mT*{%NqhGL_0dJ$?rAxA{2 z`r3MBv&)xblcd>@hArncJpL~C(_HTo&D&CS!_J5Giz$^2EfR_)xjgPg`Bq^u%1C*+ z7W*HGp|{B?dOM}|E)Cs$61y8>&-rHBw;A8 zgkWw}r$nT%t(1^GLeAVyj1l@)6UkHdM!%LJg|0%BO74M593&LlrksrgoO{iEz$}HK z4V>WXgk|7Ya!Vgm#WO^ZLtVjxwZ&k5wT6RteViH3ds{VO+2xMJZ`hToOz~_+hRfY{ z%M;ZDKRNTsK5#h6goUF(h#VXSB|7byWWle*d0$IHP+FA`y)Q^5W!|&N$ndaHexdTn z{vf?T$(9b&tI&O`^+IqpCheAFth;KY(kSl2su_9|Y1B{o9`mm)z^E`Bqw!n+JCRO) zGbIpJ@spvz=*Jki{wufWm|m`)XmDsxvbJR5dLF=kuf_C>dl}{nGO(g4I$8 zSSW#5$?vqUDZHe_%`Zm?Amd^>I4SkBvy+i}wiQYBxj0F1a$*%T+6}Yz?lX&iQ}zaU zI@%8cwVGtF3!Ke3De$dL5^j-$Bh3+By zrSR3c2a>XtaE#TB}^#hq@!vnZ1(An#bk_eKR{?;Z&0cgh4$cMNU2HL=m=YjMTI zT$BRltXs4T=im;Ao+$Bk3Dz(3!C;rTqelJ?RF)d~dP9>$_6dbz=_8#MQFMMX0S$waWxY#mtDn}1U{4PGeRH5?a>{>TU@1UlucMAmzrd@PCwr|il)m1fooO7Z{Vyr z6wn=2A5z(9g9-OU10X_ei50@~)$}w4u)b+mt)z-sz0X32m}NKTt4>!O{^4wA(|3A8 zkr(DxtMnl$Hol>~XNUE?h9;*pGG&kl*q_pb z&*$lH70zI=D^s)fU~A7cg4^tUF6*Oa+3W0=7FFB*bf$Kbqw1&amO50YeZM)SDScqy zTw$-M$NA<_We!@4!|-?V3CEPnfN4t}AeM9W$iSWYz8f;5H)V$pRjMhRV@Z&jDz#FF zXyWh7UiIc7=0U9L35=$G54RjAupR&4j`(O3i?qjOk6gb!WjNtl1Fj-VmltDTos-Bl z*OLfOleS~o3`?l!jTYIG!V7?c<;Xu(&#~xf-f(-jwow-0Hv7JZG>}YKvB=rRbdMyv zmao*-!L?)##-S#V^}oRm7^Db zT5C2RFY4>ov~?w!3l_H}t=#X=vY-*LQy(w>u%r`zQ`_RukSqIv@WyGXa-ppbk-X=g zyn?TH(`-m*in(w=Ny$%dHNSVxsL|_+X=+kM+v_w{ZC(okof9k1RP5qDvcA-d&u{5U z?)a9LXht1f6|Tdy5FgXo;sqR|CKxDKruU9RjK~P6xN+4;0eAc|^x%UO^&NM4!nK_! z6X14Zkk=5tqpl&d6FYuMmlLGQZep0UE3`fT>xzgH>C*hQ2VzCQlO`^kThU6q%3&K^ zf^kfQm|7SeU#c%f8e?A<9mALLJ-;)p_bv6$pp~49_o;>Y=GyUQ)*prjFbkU;z%HkOW_*a#j^0b@GF|`6c}7>=W{Ef!#dz5lpkN>@IH+(sx~QMEFe4 z1GeKK67;&P%ExtO>}^JxBeHii)ykX8W@aWhJO!H(w)DH4sPatQ$F-Phiqx_clj`9m zK;z7X6gD2)8kG^aTr|oY>vmgOPQ4`_W+xj2j!$YT9x(DH6pF~ zd_C#8c>Gfb)k2Ku4~t=Xb>T^8KW;2HPN#%}@@hC1lNf~Xk)~oj=w-Y11a@DtIyYk8 z9^|_RIAA(1qUSs3rowxr&OuRVFL8(zSqU_rGlqHpkeYT4z7DGdS0q4V-b!3fsv$Yb zPq4UP^3XFd(G%JAN|0y>?&sLzNir30K(lyzNYvCtE2gDyy-nthPlrXXU75fhoS7kA zg%GYyBEFQ(xgdjtv+>?>Q!G!8& z3+F>)4|N+F1a^T?XC8 zxRRx7-{DV%uUYt&*$z2uQTbZDbUn)PozID*(i^{JDjNq`v?;&OW^&~{ZPE_e+?RMk z!7O5CUKJSnGZvjTbLX2$zwYRZs_$f{T!hvVHuTg77|O;zBHlA|GIUu_bh4`Bl?7KE zYB~a`b?O;0SfD?0EZiPYpVf=P4=|zr(u_w}oP0S`YOZziX9cuwpll&%QMv4bBC_JdP#rT3>MliqySv0& zh)r=vw?no&;5T}QVTkHKY%t`%{#*#J;aw!wPs}?q2$(e0Y#cdBG1T09ypI@#-y24+fzhJem1NSZ$TCAjU2|ebYG&&6p(0f>wQoNqVa#6J^W!3$gIWEw7d<^k!U~O5v=8goq$jC`p8CS zrox#Jw3w`k&Ty7UVbm35nZ}FYT5`fN)TO6R`tEUFotxr^BTXZGt|n(Ymqmr^pCu^^w?uX!ONbm?q{y9FehdmcJuV8V%A-ma zgl=n9+op{wkj-}N;6t;(JA1A#VF3S9AFh6EXRa0~7qop~3^~t1>hc6rdS_4!+D?Xh z5y?j}*p@*-pmlTb#7C0x{E(E@%eepK_YycNkhrYH^0m)YR&gRuQi4ZqJNv6Rih0zQ zqjMuSng>Ps;?M0YVyh<;D3~;60;>exDe)Vq3x@GRf!$wgFY5w4=Jo=g*E{76%~jqr zxTtb_L4Cz_E4RTfm@0eXfr1%ho?zP(>dsRarS>!^uAh~bd0lEhe2x7AEZQmBc%rU; z&FUrs&mIt8DL`L4JpiFp3NNyk3N>iL6;Nohp*XbZZn%BDhF_y{&{X3UtX(7aAyG63P zELC;>2L`jnFS#vC->A(hZ!tGi7N7^YtW7-LB6!SVdEM&7N?g}r4rW2wLn{Ni*I~$Y z@#;KwJIl0^?eX{JWiHQxDvccnNKBhHW0h6`j=)OH1`)7)69B$XNT@)l1s25M+~o2_ zpa&X<_vHxN_oR|B#ir2p*VNB~o6Z1OE&~a+_|AxS)(@Dgznq(b(|K8BN_nQ7+>N`= zXOx_@AhcmmcRvp6eX#4z6sn=V0%KonKFVY@+m&)Rx!Z5U@WdyHMCF4_qzJNpzc9Fw z7Bdzx54(e7>wcEqHKqH-Paiut;~ZVJpS6_q>ub)zD#TQ4j*i(I8DvS$BfyX~A%<#} z*=g2$8s;YYjEHl`7cKw!a9PFRt8tVR zM&X|bs?B1#ycjl>AzgbdRkr-@NmBc^ys)aoT75F(yweV&Y-3hNNXj-valA&=)G{NL zX?smr5sQWi3n;GGPW{%vW)xw-#D0QY%zjXxYj?($b4JzpW0sWY!fkwC5bJMkhTp$J z6CNVLd=-Ktt7D<^-f|=wjNjf0l%@iu2dR+zdQ&9NLa(B_okKdRy^!Q!F$Ro=hF$-r z!3@ocUs^7?cvdTMPbn*8S-o!PsF;>FcBkBkg&ET`W`lp?j`Z}4>DF|}9407lK9y~^No&pT7J|rVQ9Dh>qg|%=gxxg=! z>WX$!;7s~gDPmPF<--(?CvEnvV*E1KdXpr>XVv!DN~PyISE7d+K_9+W^pnR6cX&?E ziLr{0`JIs@NcA|;8L|p!3H~9y8mga2Dsm4I?rBS7$3wcT!_l*$^8U3hKUri|_I3N2 zz$xY`)IWA7P*Y1BJtyBEh?8EEvs8Oyl^{(+`gi{9hwpcN#I%Z0j$^yBp?z<;Ny!G$ zra3J_^i0(~LiKuITs%v)qE+YrJr?~w+)`Rcte^O=nwmPg@&!Q7FGTtjpTdI6wH&ZV z)2}VZY6(MbP`tgoew++(pt$jVj- zvPK)pSJ)U(XfUqBqZNo|za#Xx+IVEb?HGQ^wUVH&wTdWgP(z#ijyvXjwk>tFBUn*2 zuj5ENQjT{2&T`k;q54*Z>O~djuUBNwc6l(BzY?Ed4SIt9QA&8+>qaRIck?WdD0rh@ zh`VTZPwSNNCcLH3J}(q zdEtu@HfxDTpEqWruG=86m;QVO{}E&q8qYWhmA>(FjW`V&rg!CEL1oZCZcAX@yX(2tg8`>m1psG0ZpO+Rnph@Bhjj!~|+S=@+U{*ukwGrBj{5xfIHHP7|} z^7@g2;d%FMO8f(MS&6c##mrX2i(5uiX1o(=Vw89IQcHw)n{ZTS@``xT$Af@CQTP#w zl3kn6+MJP+l(;K-rWgjpdBU|CB4>W%cObZBH^Am~EvRO%D>uU^HVRXi$1 zb?Pr~ZlopLfT5l%03SjI7>YiGZZs=n(A!c;N9%%aByY~5(-hS4z_i2wgKYsG%OhhxH#^5i%&9ESb(@# zV_f5${Gf=$BK)1VY=NX#f+M}6f`OWmpC*OU3&+P@n>$Xvco*Nm$c<=`S|lY6S}Ut- z80}ztIpkV>W%^Ox`enpk<25_i7`RPiDugxHfUDBD8$bp9XR15>a?r^#&!1Ne6n{MI z){H`!jwrx}8b-w@@E8H0v)l!5!W8En=u67v+`iNoz<_h4{V*qQK+@)JP^JqsKAedZ zNh4toE+I7;^}7kkj|hzNVFWkZ$N9rxPl9|_@2kbW*4}&o%(L`WpQCN2M?gz>cyWHk zulMwRxpdpx+~P(({@%UY20LwM7sA&1M|`bEoq)Id zyUHt>@vfu**UOL9wiW*C75cc&qBX37qLd`<;$gS+mvL^v3Z8i4p6(@Wv`N|U6Exn< zd`@WxqU^8u^Aw+uw#vuDEIByaD)vucU2{4xRseczf_TJXUwaUK+E_IoItXJq88${0 z=K5jGehPa2)CnH&Lcxv&1jQ=T8>*vgp1^%)c&C2TL69;vSN)Q)e#Hj7!oS0 zlrEmJ=w4N9pID5KEY5qz;?2Q}0|4ESEio&cLrp221LTt~j3KjUB`LU?tP=p;B=WSXo;C?8(pnF6@?-ZD0m3DYZ* z#SzaXh|)hmTC|zQOG>aEMw%4&2XU?prlk5(M3ay-YC^QLRMN+TIB*;TB=wL_atpeD zh-!sS%A`3 z=^?niQx+^za_wQd2hRR=hsR0uzUoyOcrY!z7W)G2|C-_gqc`wrG5qCuU!Z?g*GL^H z?j^<_-A6BC^Dp`p(i0!1&?U{YlF@!|W{E@h=qQ&5*|U~V8wS;m!RK(Q6aX~oH9ToE zZYKXZoRV~!?P1ADJ74J-PFk2A{e&gh2o)@yZOZuBi^0+Hkp`dX;cZs9CRM+##;P!*BlA%M48TuR zWUgfD1DLsLs+-4XC>o>wbv-B)!t*47ON5wgoMX%llnmXG%L8209Vi;yZ`+N2v2Ox+ zMe7JHunQE$ckHHhEYRA+e`A3=XO5L%fMau71`XL7v)b{f1rkTY+WWSIkH#sG=pLqe zA(xZIp>_=4$zKq0t_G7q9@L zZ5D-0{8o%7f>0szA#c;rjL;4Y%hl}wYrx1R`Viq|Pz}c-{{LJY070ym@E~mt*pTyG z79bfcWTGGEje;PLD;N-XHw=`wS^howfzb$%oP8n)lN$o$ZWjZx|6iSsi2piI_7s7z zX#b$@z6kIJ^9{-Y^~wJ!s0V^Td5V7#4&pyU#NHw#9)N&qbpNFDR1jqC00W}91OnnS z{$J@GBz%bka`xsz;rb_iJ|rgmpUVyEZ)Xi*SO5U&|NFkTHb3y@e@%{WrvE&Jp#Lw^ zcj13CbsW+V>i@rj@SEfFf0@yjS@nbPB0)6D`lA;e%61nh`-qhydO!uS7jXGQd%i7opEnOL;| zDn!3EUm(V796;f?fA+RDF<@%qKlo)`0VtL74`!~516_aogYP%QfG#<2kQ!pijthz2 zpaFX3|D$%C7!bL242U?-e@2QZ`q$~lgZbvgfLLyVfT1OC5<8@6lLi=A{stK#zJmWd zlx+(HbgX)l$RGwH|2rV@P3o@xCrxch0$*z1ASpy(n+d4d2XWd~2AYjQm`xZU3af8F p+x$Nxf1895@0bJirXkdpJh+N7@Nb7x007(DEB&^Lm}dWn{T~m64-^0Z diff --git a/vendordeps/WPILibOldCommands.json b/vendordeps/WPILibOldCommands.json deleted file mode 100644 index 7bdad212..00000000 --- a/vendordeps/WPILibOldCommands.json +++ /dev/null @@ -1,37 +0,0 @@ -{ - "fileName": "WPILibOldCommands.json", - "name": "WPILib-Old-Commands", - "version": "2020.0.0", - "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e", - "mavenUrls": [], - "jsonUrl": "", - "javaDependencies": [ - { - "groupId": "edu.wpi.first.wpilibOldCommands", - "artifactId": "wpilibOldCommands-java", - "version": "wpilib" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "edu.wpi.first.wpilibOldCommands", - "artifactId": "wpilibOldCommands-cpp", - "version": "wpilib", - "libName": "wpilibOldCommands", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxraspbian", - "linuxaarch64bionic", - "windowsx86-64", - "windowsx86", - "linuxx86-64", - "osxx86-64" - ] - } - ] -} From d9b8e5828835332e65a3b3f94382b3d6c0994d4f Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Sat, 14 Jan 2023 15:14:31 -0800 Subject: [PATCH 005/103] Removed Repeated element from LogListValue --- src/main/proto/com/team766/logging/logging.proto | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/main/proto/com/team766/logging/logging.proto b/src/main/proto/com/team766/logging/logging.proto index 10b37cb4..46dca665 100644 --- a/src/main/proto/com/team766/logging/logging.proto +++ b/src/main/proto/com/team766/logging/logging.proto @@ -63,6 +63,3 @@ message LogValue { message LogListValue { repeated LogValue element = 1; } -message LogListValue { - repeated LogValue element = 1; -} \ No newline at end of file From 577a30d7106f7cdb8cf20ec0074b204cba069f35 Mon Sep 17 00:00:00 2001 From: dejabot Date: Mon, 16 Jan 2023 14:50:26 -0800 Subject: [PATCH 006/103] update implementation of WPIRobotProvider.hasNewDriverStationData(). Add a background thread (thought in progress) that refreshes data hasNewDriverStationData will compare refresh count with member variable it maintains. --- .../team766/hal/wpilib/WPIRobotProvider.java | 53 +++++++++++++++++-- 1 file changed, 49 insertions(+), 4 deletions(-) diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 86798458..2027350b 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -1,5 +1,7 @@ package com.team766.hal.wpilib; +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.atomic.AtomicInteger; import com.team766.hal.AnalogInputReader; import com.team766.hal.CameraInterface; import com.team766.hal.CameraReader; @@ -22,7 +24,9 @@ import com.team766.logging.Logger; import com.team766.logging.LoggerExceptionUtils; import com.team766.logging.Severity; - +import com.team766.simulator.elements.AirCompressor; +import edu.wpi.first.hal.DriverStationJNI; +import edu.wpi.first.util.WPIUtilJNI; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.I2C; import edu.wpi.first.wpilibj.PneumaticsControlModule; @@ -31,6 +35,48 @@ public class WPIRobotProvider extends RobotProvider { + private static class DataRefreshRunnable implements Runnable { + private final AtomicBoolean m_keepAlive = new AtomicBoolean(); + private final AtomicInteger m_dataCount = new AtomicInteger(); + + public DataRefreshRunnable() { + m_keepAlive.set(true); + } + + @Override + public void run() { + int handle = WPIUtilJNI.createEvent(false, false); + DriverStationJNI.provideNewDataEventHandle(handle); + + while (m_keepAlive.get()) { + try { + if (!WPIUtilJNI.waitForObjectTimeout(handle, 0.1)) { + m_dataCount.incrementAndGet(); + } + } catch (InterruptedException e) { + DriverStationJNI.removeNewDataEventHandle(handle); + WPIUtilJNI.destroyEvent(handle); + Thread.currentThread().interrupt(); + return; + } + DriverStation.refreshData(); + } + + DriverStationJNI.removeNewDataEventHandle(handle); + WPIUtilJNI.destroyEvent(handle); + } + } + + private DataRefreshRunnable m_DataRefreshRunnable = new DataRefreshRunnable(); + private Thread m_dataRefreshThread; + private AtomicInteger m_lastDataCount = new AtomicInteger(); + + public WPIRobotProvider() { + m_dataRefreshThread = new Thread(m_DataRefreshRunnable, "DataRefreshThread"); + // FIXME: where is the right place to close this? should this be auto-cloesable? + m_dataRefreshThread.start(); + } + private MotorController[][] motors = new MotorController[MotorController.Type.values().length][64]; // The presence of this object allows the compressor to run before we've declared any solenoids. @@ -174,9 +220,8 @@ public Clock getClock() { @Override public boolean hasNewDriverStationData() { - // TODO: replace implementation with event counting one - // return DriverStation.isNewControlData(); - return true; + int currentDataCount = m_DataRefreshRunnable.m_dataCount.get(); + return m_lastDataCount.getAndSet(currentDataCount) != currentDataCount; } @Override From b88b9c2af70c7a0281debf31cdf0084f913df881 Mon Sep 17 00:00:00 2001 From: dejabot Date: Mon, 16 Jan 2023 20:08:49 -0800 Subject: [PATCH 007/103] more fixes for WPILib 2023 clean up code for WPIRobotProvider move DriverStation.refreshData() to OI (wrapped in new HAL API) --- .../java/com/team766/hal/RobotProvider.java | 2 + .../team766/hal/mock/TestRobotProvider.java | 5 +++ .../simulator/SimulationRobotProvider.java | 6 +++ .../team766/hal/wpilib/WPIRobotProvider.java | 38 +++++++++++++++---- src/main/java/com/team766/robot/OI.java | 6 ++- 5 files changed, 49 insertions(+), 8 deletions(-) diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java index 40f3f218..abafe6b6 100755 --- a/src/main/java/com/team766/hal/RobotProvider.java +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -230,5 +230,7 @@ public GyroReader getGyro(String configName) { public abstract double getBatteryVoltage(); + public abstract void refreshData(); + public abstract boolean hasNewDriverStationData(); } diff --git a/src/main/java/com/team766/hal/mock/TestRobotProvider.java b/src/main/java/com/team766/hal/mock/TestRobotProvider.java index 208cc991..d87e604c 100755 --- a/src/main/java/com/team766/hal/mock/TestRobotProvider.java +++ b/src/main/java/com/team766/hal/mock/TestRobotProvider.java @@ -107,6 +107,11 @@ public Clock getClock() { return SystemClock.instance; } + @Override + public void refreshData() { + // no-op + } + @Override public boolean hasNewDriverStationData() { boolean result = m_hasDriverStationUpdate; diff --git a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java index 7972440a..a4950527 100755 --- a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java +++ b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java @@ -104,6 +104,12 @@ public Clock getClock() { return SimulationClock.instance; } + @Override + public void refreshData() { + // no-op on simulator + return; + } + @Override public boolean hasNewDriverStationData() { int newUpdateNumber = ProgramInterface.driverStationUpdateNumber; diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 2027350b..554d008b 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -35,6 +35,10 @@ public class WPIRobotProvider extends RobotProvider { + /** + * Runnable that counts the number of times we receive new data from the driver station. + * Used as part of impl of {@link #hasNewDriverStationData()}. + */ private static class DataRefreshRunnable implements Runnable { private final AtomicBoolean m_keepAlive = new AtomicBoolean(); private final AtomicInteger m_dataCount = new AtomicInteger(); @@ -43,23 +47,36 @@ public DataRefreshRunnable() { m_keepAlive.set(true); } + public void cancel() { + m_keepAlive.set(false); + } + @Override public void run() { + // create and register a handle that gets notified whenever there's new DS data. int handle = WPIUtilJNI.createEvent(false, false); DriverStationJNI.provideNewDataEventHandle(handle); while (m_keepAlive.get()) { try { + // wait for new data or timeout + // (timeout returns true) if (!WPIUtilJNI.waitForObjectTimeout(handle, 0.1)) { m_dataCount.incrementAndGet(); } } catch (InterruptedException e) { + // should only happen during failures + LoggerExceptionUtils.logException(e); + + // clean up handle DriverStationJNI.removeNewDataEventHandle(handle); WPIUtilJNI.destroyEvent(handle); - Thread.currentThread().interrupt(); - return; + + // re-register handle in an attempt to keep data flowing. + handle = WPIUtilJNI.createEvent(false, false); + DriverStationJNI.provideNewDataEventHandle(handle); + // TODO: reset counter to 0? } - DriverStation.refreshData(); } DriverStationJNI.removeNewDataEventHandle(handle); @@ -69,11 +86,10 @@ public void run() { private DataRefreshRunnable m_DataRefreshRunnable = new DataRefreshRunnable(); private Thread m_dataRefreshThread; - private AtomicInteger m_lastDataCount = new AtomicInteger(); + private int m_lastDataCount = 0; public WPIRobotProvider() { m_dataRefreshThread = new Thread(m_DataRefreshRunnable, "DataRefreshThread"); - // FIXME: where is the right place to close this? should this be auto-cloesable? m_dataRefreshThread.start(); } @@ -218,10 +234,18 @@ public Clock getClock() { return SystemClock.instance; } + @Override + public void refreshData() { + DriverStation.refreshData(); + } + @Override public boolean hasNewDriverStationData() { - int currentDataCount = m_DataRefreshRunnable.m_dataCount.get(); - return m_lastDataCount.getAndSet(currentDataCount) != currentDataCount; + // see if the thread has counted more data changes than the last time this method was called + int currentDataRefreshThreadCount = m_DataRefreshRunnable.m_dataCount.get(); + boolean dataChanged = m_lastDataCount != currentDataRefreshThreadCount; + m_lastDataCount = currentDataRefreshThreadCount; + return dataChanged; } @Override diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 1163a781..bd6c43a0 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -6,6 +6,7 @@ import com.team766.hal.RobotProvider; import com.team766.logging.Category; import com.team766.robot.procedures.*; +import edu.wpi.first.wpilibj.DriverStation; /** * This class is the glue that binds the controls on the physical operator @@ -26,10 +27,13 @@ public OI() { public void run(Context context) { while (true) { + // get the latest data (joystick input etc) from the driver station + // at the end of this loop, we'll wait until there are more data available. + RobotProvider.instance.refreshData(); + // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. - context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); } } From e8b1efb59d8b8b14ee67d9973aeda64a60401b9f Mon Sep 17 00:00:00 2001 From: dejabot Date: Mon, 16 Jan 2023 21:03:15 -0800 Subject: [PATCH 008/103] fix formatting --- .../java/com/team766/hal/wpilib/WPIRobotProvider.java | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 554d008b..980a9fd1 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -61,22 +61,21 @@ public void run() { try { // wait for new data or timeout // (timeout returns true) - if (!WPIUtilJNI.waitForObjectTimeout(handle, 0.1)) { + if (!WPIUtilJNI.waitForObjectTimeout(handle, 0.1)) { m_dataCount.incrementAndGet(); } - } catch (InterruptedException e) { + } catch (InterruptedException e) { // should only happen during failures LoggerExceptionUtils.logException(e); // clean up handle - DriverStationJNI.removeNewDataEventHandle(handle); - WPIUtilJNI.destroyEvent(handle); + DriverStationJNI.removeNewDataEventHandle(handle); + WPIUtilJNI.destroyEvent(handle); // re-register handle in an attempt to keep data flowing. handle = WPIUtilJNI.createEvent(false, false); DriverStationJNI.provideNewDataEventHandle(handle); - // TODO: reset counter to 0? - } + } } DriverStationJNI.removeNewDataEventHandle(handle); From ce537b84636930fc75bcac3ed3075da16566b0df Mon Sep 17 00:00:00 2001 From: dejabot Date: Mon, 16 Jan 2023 23:14:34 -0800 Subject: [PATCH 009/103] respond to PR comments 1. rename refreshData() to refreshDriverStationData() for clarity. 2. move context.waitFor(...hasNewDriverStationData()) to top of loop. also fixed some formatting issues in WPIRobotProvider.java --- .../java/com/team766/hal/RobotProvider.java | 2 +- .../team766/hal/mock/TestRobotProvider.java | 2 +- .../simulator/SimulationRobotProvider.java | 2 +- .../team766/hal/wpilib/WPIRobotProvider.java | 66 +++++++++---------- src/main/java/com/team766/robot/OI.java | 5 +- 5 files changed, 38 insertions(+), 39 deletions(-) diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java index abafe6b6..b9eb1562 100755 --- a/src/main/java/com/team766/hal/RobotProvider.java +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -230,7 +230,7 @@ public GyroReader getGyro(String configName) { public abstract double getBatteryVoltage(); - public abstract void refreshData(); + public abstract void refreshDriverStationData(); public abstract boolean hasNewDriverStationData(); } diff --git a/src/main/java/com/team766/hal/mock/TestRobotProvider.java b/src/main/java/com/team766/hal/mock/TestRobotProvider.java index d87e604c..5f436147 100755 --- a/src/main/java/com/team766/hal/mock/TestRobotProvider.java +++ b/src/main/java/com/team766/hal/mock/TestRobotProvider.java @@ -108,7 +108,7 @@ public Clock getClock() { } @Override - public void refreshData() { + public void refreshDriverStationData() { // no-op } diff --git a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java index a4950527..0f1b7b61 100755 --- a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java +++ b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java @@ -105,7 +105,7 @@ public Clock getClock() { } @Override - public void refreshData() { + public void refreshDriverStationData() { // no-op on simulator return; } diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 980a9fd1..21bf67cd 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -36,8 +36,8 @@ public class WPIRobotProvider extends RobotProvider { /** - * Runnable that counts the number of times we receive new data from the driver station. - * Used as part of impl of {@link #hasNewDriverStationData()}. + * Runnable that counts the number of times we receive new data from the driver station. Used as + * part of impl of {@link #hasNewDriverStationData()}. */ private static class DataRefreshRunnable implements Runnable { private final AtomicBoolean m_keepAlive = new AtomicBoolean(); @@ -79,7 +79,7 @@ public void run() { } DriverStationJNI.removeNewDataEventHandle(handle); - WPIUtilJNI.destroyEvent(handle); + WPIUtilJNI.destroyEvent(handle); } } @@ -92,14 +92,16 @@ public WPIRobotProvider() { m_dataRefreshThread.start(); } - private MotorController[][] motors = new MotorController[MotorController.Type.values().length][64]; + private MotorController[][] motors = + new MotorController[MotorController.Type.values().length][64]; // The presence of this object allows the compressor to run before we've declared any solenoids. @SuppressWarnings("unused") private PneumaticsControlModule pcm = new PneumaticsControlModule(); @Override - public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { + public MotorController getMotor(int index, String configPrefix, MotorController.Type type, + ControlInputReader localSensor) { if (motors[type.ordinal()][index] != null) { return motors[type.ordinal()][index]; } @@ -110,7 +112,8 @@ public MotorController getMotor(int index, String configPrefix, MotorController. motor = new CANSparkMaxMotorController(index); } catch (Exception ex) { LoggerExceptionUtils.logException(ex); - motor = new LocalMotorController(configPrefix, new MockMotorController(index), localSensor); + motor = new LocalMotorController(configPrefix, new MockMotorController(index), + localSensor); localSensor = null; } break; @@ -129,8 +132,10 @@ public MotorController getMotor(int index, String configPrefix, MotorController. break; } if (motor == null) { - LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported motor type " + type)); - motor = new LocalMotorController(configPrefix, new MockMotorController(index), localSensor); + LoggerExceptionUtils + .logException(new IllegalArgumentException("Unsupported motor type " + type)); + motor = new LocalMotorController(configPrefix, new MockMotorController(index), + localSensor); localSensor = null; } if (localSensor != null) { @@ -142,34 +147,31 @@ public MotorController getMotor(int index, String configPrefix, MotorController. @Override public EncoderReader getEncoder(int index1, int index2) { - if(encoders[index1] == null) + if (encoders[index1] == null) encoders[index1] = new Encoder(index1, index2); return encoders[index1]; } @Override public SolenoidController getSolenoid(int index) { - if(solenoids[index] == null) + if (solenoids[index] == null) solenoids[index] = new Solenoid(index); return solenoids[index]; } @Override - //Gyro index values: - // -1 = Spartan Gyro - // 0+ = Analog Gyro on port index + // Gyro index values: + // -1 = Spartan Gyro + // 0+ = Analog Gyro on port index public GyroReader getGyro(int index) { - if(gyros[index + 2] == null){ - if(index < -2) { - Logger.get(Category.CONFIGURATION).logRaw( - Severity.ERROR, - "Invalid gyro port " + index + ". Must be -2, -1, or a non-negative integer" - ); + if (gyros[index + 2] == null) { + if (index < -2) { + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Invalid gyro port " + + index + ". Must be -2, -1, or a non-negative integer"); return new MockGyro(); - } - else if(index == -2) + } else if (index == -2) gyros[index + 2] = new NavXGyro(I2C.Port.kOnboard); - else if(index == -1) + else if (index == -1) gyros[index + 2] = new ADXRS450_Gyro(SPI.Port.kOnboardCS0); else gyros[index + 2] = new AnalogGyro(index); @@ -185,13 +187,13 @@ public CameraReader getCamera(String id, String value) { @Override public JoystickReader getJoystick(int index) { - if(joysticks[index] == null) + if (joysticks[index] == null) joysticks[index] = new Joystick(index); return joysticks[index]; } @Override - public CameraInterface getCamServer(){ + public CameraInterface getCamServer() { return new com.team766.hal.wpilib.CameraInterface(); } @@ -203,15 +205,15 @@ public DigitalInputReader getDigitalInput(int index) { } @Override - public AnalogInputReader getAnalogInput(int index){ - if(angInputs[index] == null) + public AnalogInputReader getAnalogInput(int index) { + if (angInputs[index] == null) angInputs[index] = new AnalogInput(index); return angInputs[index]; } @Override public RelayOutput getRelay(int index) { - if(relays[index] == null) + if (relays[index] == null) relays[index] = new Relay(index); return relays[index]; } @@ -220,10 +222,8 @@ public RelayOutput getRelay(int index) { public PositionReader getPositionSensor() { if (positionSensor == null) { positionSensor = new MockPositionSensor(); - Logger.get(Category.CONFIGURATION).logRaw( - Severity.ERROR, - "Position sensor does not exist on real robots. Using mock position sensor instead - it will always return a position of 0" - ); + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, + "Position sensor does not exist on real robots. Using mock position sensor instead - it will always return a position of 0"); } return positionSensor; } @@ -234,7 +234,7 @@ public Clock getClock() { } @Override - public void refreshData() { + public void refreshDriverStationData() { DriverStation.refreshData(); } @@ -251,4 +251,4 @@ public boolean hasNewDriverStationData() { public double getBatteryVoltage() { return RobotController.getBatteryVoltage(); } -} \ No newline at end of file +} diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index bd6c43a0..f0128016 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -29,12 +29,11 @@ public void run(Context context) { while (true) { // get the latest data (joystick input etc) from the driver station // at the end of this loop, we'll wait until there are more data available. - RobotProvider.instance.refreshData(); + RobotProvider.instance.refreshDriverStationData(); + context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. - - context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); } } } From 9d96ed0eff6ca2885caa16277453858dc67d5eac Mon Sep 17 00:00:00 2001 From: dejabot Date: Tue, 17 Jan 2023 18:46:22 -0800 Subject: [PATCH 010/103] code review feedback: wait then refresh --- src/main/java/com/team766/robot/OI.java | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index f0128016..b33f97e4 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -27,10 +27,9 @@ public OI() { public void run(Context context) { while (true) { - // get the latest data (joystick input etc) from the driver station - // at the end of this loop, we'll wait until there are more data available. - RobotProvider.instance.refreshDriverStationData(); + // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); + RobotProvider.instance.refreshDriverStationData(); // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. From 11026a6af37b39922d16033bc7c29548f42c1605 Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Thu, 12 Jan 2023 07:07:25 -0800 Subject: [PATCH 011/103] rev Maroon Framework version (#16) --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index cacb0d99..2914ef71 100644 --- a/build.gradle +++ b/build.gradle @@ -130,7 +130,7 @@ tasks.withType(JavaCompile) { } allprojects { group 'com.team766' - version '2.1.0' + version '2.1.1' repositories { mavenCentral() From 1a97891da28ff92626de1083767bc3a2194194af Mon Sep 17 00:00:00 2001 From: dejabot Date: Sat, 14 Jan 2023 01:27:51 -0800 Subject: [PATCH 012/103] Disable editing via /config. Point developers to new deploy process for configuration files. --- src/main/java/com/team766/web/ConfigUI.java | 71 ++------------------- 1 file changed, 7 insertions(+), 64 deletions(-) diff --git a/src/main/java/com/team766/web/ConfigUI.java b/src/main/java/com/team766/web/ConfigUI.java index 86dfe69f..09be38fa 100644 --- a/src/main/java/com/team766/web/ConfigUI.java +++ b/src/main/java/com/team766/web/ConfigUI.java @@ -13,72 +13,15 @@ public String endpoint() { @Override public String handle(Map params) { - String r = "

Configuration

"; - - r += "
\n"; - if (params.containsKey("configJson")) { - String configJsonString = (String)params.get("configJson"); - ArrayList validationErrors = new ArrayList(); - try { - ConfigFileReader.getInstance().reloadFromJson(configJsonString); - } catch (ConfigValueParseException ex) { - validationErrors.add(ex.toString()); - } catch (Exception ex) { - validationErrors.add("Failed to parse config json: " + ex); - } - if (validationErrors.isEmpty()) { - r += "

New configuration (v" + ConfigFileReader.getInstance().getGeneration() + ") has been applied

"; - r += "

Remember to click Restart Robot Code in the driver station if you have changed any motor/sensor settings

"; - if (params.containsKey("saveToFile")) { - try { - ConfigFileReader.getInstance().saveFile(configJsonString); - } catch (Exception ex) { - validationErrors.add("Could not save config file: " + ex.toString()); - } - } - } - if (validationErrors.size() > 0) { - r += "

Errors:\n"; - r += "

    \n"; - for (String error : validationErrors) { - r += "
  • " + error + "
  • \n"; - } - r += "

\n"; - } - } - r += "
\n"; - - r += String.join("\n", new String[]{ - "", - }); + String r = "

Configuration (READ ONLY)

"; + r += "To edit, copy contents and place in src/main/deploy/configs directory.
"; + r += "See
docs for more information.
"; + r += "

"; - r += "

\n"; - r += "\n"; - r += "

Save to config file on robot?

\n"; - r += "

\n"; - return r; } From 028a5c2fc470327aaf6e5822d29b1cf84841c783 Mon Sep 17 00:00:00 2001 From: dejabot Date: Sun, 15 Jan 2023 20:03:50 -0800 Subject: [PATCH 013/103] Fix HTML formatting in /config --- src/main/java/com/team766/web/ConfigUI.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/team766/web/ConfigUI.java b/src/main/java/com/team766/web/ConfigUI.java index 09be38fa..fe8dcfad 100644 --- a/src/main/java/com/team766/web/ConfigUI.java +++ b/src/main/java/com/team766/web/ConfigUI.java @@ -14,9 +14,10 @@ public String endpoint() { @Override public String handle(Map params) { String r = "

Configuration (READ ONLY)

"; + r += "

"; r += "To edit, copy contents and place in src/main/deploy/configs directory.
"; r += "See docs for more information.
"; - r += "

"; + r += "

"; // TODO: handle empty config file case. r += "\n"; + r += "

Save to config file on robot?

\n"; + r += "

\n"; + return r; } From 651132ae5d6c3f3d3a95ec257ff2b2b99512171f Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Sat, 21 Jan 2023 16:30:35 -0800 Subject: [PATCH 019/103] Added FollowPoints stopping robot during procdure --- .../java/com/team766/odometry/PointDir.java | 10 +++ .../com/team766/robot/AutonomousModes.java | 4 +- .../robot/procedures/FollowPoints.java | 78 +++++++++++++++++-- 3 files changed, 84 insertions(+), 8 deletions(-) diff --git a/src/main/java/com/team766/odometry/PointDir.java b/src/main/java/com/team766/odometry/PointDir.java index 6d64dcc5..30d2a433 100644 --- a/src/main/java/com/team766/odometry/PointDir.java +++ b/src/main/java/com/team766/odometry/PointDir.java @@ -12,6 +12,16 @@ public PointDir(double x, double y, double h){ loggerCategory = Category.DRIVE; } + public PointDir(double x, double y){ + super(x, y); + loggerCategory = Category.DRIVE; + } + + public PointDir(Point P){ + super(P.getX(), P.getY()); + loggerCategory = Category.DRIVE; + } + public PointDir(Point P, double h) { super(P.getX(), P.getY()); heading = h; diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java index c37e6041..36008b02 100644 --- a/src/main/java/com/team766/robot/AutonomousModes.java +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -4,8 +4,10 @@ import com.team766.robot.procedures.*; import com.team766.odometry.Point; import com.team766.odometry.PointDir; +import com.team766.framework.Procedure; public class AutonomousModes { + public static final AutonomousMode[] AUTONOMOUS_MODES = new AutonomousMode[] { // Add autonomous modes here like this: // new AutonomousMode("NameOfAutonomousMode", () -> new MyAutonomousProcedure()), @@ -15,7 +17,7 @@ public class AutonomousModes { // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), new AutonomousMode("FollowPoints", () -> new FollowPoints()), - new AutonomousMode("FollowPointsH", () -> new FollowPoints(new Point[]{new Point(0, 0), new Point(2, 0), new Point(1, 0), new Point(1, 1), new Point(2, 1), new Point(0, 1)})), + new AutonomousMode("FollowPointsH", () -> new FollowPoints(new PointDir[]{new PointDir(0, 0), new PointDir(2, 0), new PointDir(1, 0), new PointDir(1, 1), new PointDir(2, 1), new PointDir(0, 1)})), new AutonomousMode("DoNothing", () -> new DoNothing()), }; } \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index f73f0e84..1f2ac6ed 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -9,55 +9,114 @@ import com.team766.odometry.Point; import com.team766.odometry.PointDir; import com.team766.hal.PositionReader; + +import java.util.ArrayList; +import java.util.List; + import com.team766.config.ConfigFileReader; import com.team766.logging.Category; import com.team766.controllers.PIDController; public class FollowPoints extends Procedure { + public static class Step { + public PointDir wayPoint; + public boolean criticalPoint; + public Procedure procedure; + public boolean stopRobot; + // ... + + public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { + this.wayPoint = wayPoint; + this.procedure = procedure; + } + } + + private List steps = new ArrayList(); + private PointDir currentPos = new PointDir(0.0, 0.0, 0.0); - private Point[] pointList; + private PointDir[] pointList; private Procedure[] proceduresAtPoints; + private boolean[] criticalPointList; + private boolean[] stopRobotList; private static double radius = ConfigFileReader.getInstance().getDouble("trajectory.radius").get(); private static double leniency = ConfigFileReader.getInstance().getDouble("trajectory.leniency").get(); private static double speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); private double finalHeader; - public FollowPoints() { + /*public FollowPoints() { parsePointList(); proceduresAtPoints = new Procedure[pointList.length]; for (int i = 0; i < proceduresAtPoints.length; i++) { proceduresAtPoints[i] = new DoNothing(); } loggerCategory = Category.AUTONOMOUS; + }*/ + + private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { + steps.add(new Step(wayPoint, criticalPoint, procedure, stopRobot)); + } + + public FollowPoints() { + addStep(new PointDir(0,0, 0), false, new DoNothing(), false); + addStep(new PointDir(0,20, 30), false, null /* don't execute procedure */, false); + addWaypoints(); + } + + private void addWaypoints() { + pointList = new PointDir[steps.size()]; + proceduresAtPoints = new Procedure[steps.size()]; + stopRobotList = new boolean[pointList.length]; + criticalPointList = new boolean[pointList.length]; + for (int i = 0; i < steps.size(); i++) { + if (steps.get(i).wayPoint == null) continue; + else { + pointList[i] = steps.get(i).wayPoint; + } + if (steps.get(i).procedure != null) { + proceduresAtPoints[i] = steps.get(i).procedure; + // run procedure + // TODO: make sure we're handling contexts correctly + } else { + proceduresAtPoints[i] = new DoNothing(); + } + criticalPointList[i] = steps.get(i).criticalPoint; + stopRobotList[i] = steps.get(i).stopRobot; + } } public FollowPoints(Procedure[] procedureList) { parsePointList(); proceduresAtPoints = procedureList; + criticalPointList = new boolean[pointList.length]; + stopRobotList = new boolean[pointList.length]; loggerCategory = Category.AUTONOMOUS; } - public FollowPoints(Point[] points) { + public FollowPoints(PointDir[] points) { pointList = points; finalHeader = Robot.drive.getCurrentPosition().getHeading(); proceduresAtPoints = new Procedure[pointList.length]; for (int i = 0; i < proceduresAtPoints.length; i++) { proceduresAtPoints[i] = new DoNothing(); } + criticalPointList = new boolean[pointList.length]; + stopRobotList = new boolean[pointList.length]; loggerCategory = Category.AUTONOMOUS; } - public FollowPoints(Point[] points, Procedure[] procedureList) { + public FollowPoints(PointDir[] points, Procedure[] procedureList) { pointList = points; finalHeader = Robot.drive.getCurrentPosition().getHeading(); proceduresAtPoints = procedureList; + criticalPointList = new boolean[pointList.length]; + stopRobotList = new boolean[pointList.length]; loggerCategory = Category.AUTONOMOUS; } //Takes pairs of points from pointDoubles (set in the config file) and converts them to Points, which are placed in pointList. private void parsePointList() { Double[] pointDoubles = ConfigFileReader.getInstance().getDoubles("trajectory.points").get(); - pointList = new Point[pointDoubles.length / 2]; + pointList = new PointDir[pointDoubles.length / 2]; double pointX = 0; double pointY = 0; for (int i = 0; i < pointDoubles.length / 2 * 2; i++) { @@ -65,7 +124,7 @@ private void parsePointList() { pointX = pointDoubles[i]; else { pointY = pointDoubles[i]; - pointList[i / 2] = new Point(pointX, pointY); + pointList[i / 2] = new PointDir(pointX, pointY); } } if (pointDoubles.length % 2 == 1) { @@ -95,6 +154,7 @@ public void run(Context context) { log("Starting FollowPoints"); Robot.drive.resetCurrentPosition(); Robot.gyro.resetGyro(); + for (int i = 0; i < pointList.length; i++) { log(pointList[i].toString()); } @@ -107,7 +167,11 @@ public void run(Context context) { currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); if (currentPos.distance(pointList[targetNum]) <= radius && checkIntersection(targetNum, currentPos, pointList, radius)) { if (proceduresAtPoints.length < targetNum) { - context.startAsync(proceduresAtPoints[targetNum]); + if (stopRobotList[targetNum]) { + context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); + } else { + context.startAsync(proceduresAtPoints[targetNum]); + } } targetNum++; log("Going to Next Point!"); From 395cafb131ff84338cd98fecd17d4236e99c92aa Mon Sep 17 00:00:00 2001 From: dejabot Date: Sun, 22 Jan 2023 22:48:46 -0800 Subject: [PATCH 020/103] update deployconfigFiles to occur before the deploy task kills the robot code --- build.gradle | 1 + 1 file changed, 1 insertion(+) diff --git a/build.gradle b/build.gradle index 2914ef71..ba753964 100644 --- a/build.gradle +++ b/build.gradle @@ -50,6 +50,7 @@ deploy { // Just the (static) config files configFiles(getArtifactTypeClass('FileTreeArtifact')) { + setDeployStage(it, 'BeforeProgramKill') files = project.fileTree('src/main/deploy/configs') directory = '/home/lvuser/deploy/configs' } From b0153e2a5b85069cf4503f8303de3389c2b8d3b0 Mon Sep 17 00:00:00 2001 From: Ryan Cahoon Date: Sun, 22 Jan 2023 23:11:36 -0800 Subject: [PATCH 021/103] Create pull_request_template.md --- .github/pull_request_template.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 .github/pull_request_template.md diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md new file mode 100644 index 00000000..dd3756d0 --- /dev/null +++ b/.github/pull_request_template.md @@ -0,0 +1,13 @@ +## Description + +Please include a summary of the changes in this PR. If it is fixing an issue, describe the issue. Please also include relevant motivation and context such that a newer programmer could understand your changes just by reading this description. + + +## How Has This Been Tested? + +Please describe the tests that you ran to verify your changes. Be detailed so that your code reviewer can understand exactly how much and what kinds of testing were done, and which might still be worthwhile to do. + +- [ ] Unit tests: [Add your description here] +- [ ] Simulator testing: [Add your description here] +- [ ] On-robot bench testing: [Add your description here] +- [ ] On-robot field testing: [Add your description here] From 6563d0fca3b524e30b8b6b19dbcb3bdcdade2b72 Mon Sep 17 00:00:00 2001 From: qntmcube <100043837+qntmcube@users.noreply.github.com> Date: Mon, 23 Jan 2023 18:23:22 +0000 Subject: [PATCH 022/103] Added seperate CANBus compatability (hopefully) --- .../hal/wpilib/CANTalonFxMotorController.java | 4 + .../team766/hal/wpilib/WPIRobotProvider.java | 1 + .../com/team766/robot/mechanisms/Drive.java | 386 ++++++++++++++++++ .../com/team766/robot/mechanisms/Gyro.java | 54 +++ 4 files changed, 445 insertions(+) create mode 100644 src/main/java/com/team766/robot/mechanisms/Drive.java create mode 100644 src/main/java/com/team766/robot/mechanisms/Gyro.java diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java index ec30728a..0d827299 100644 --- a/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java +++ b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java @@ -17,6 +17,10 @@ public class CANTalonFxMotorController extends BaseCTREMotorController implement private WPI_TalonFX m_device; private double m_feedForward = 0.0; + public CANTalonFxMotorController(int deviceNumber, String CANBus) { + m_device = new WPI_TalonFX(deviceNumber, CANBus); + } + public CANTalonFxMotorController(int deviceNumber) { m_device = new WPI_TalonFX(deviceNumber); } diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 21bf67cd..c6fd2312 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -124,6 +124,7 @@ public MotorController getMotor(int index, String configPrefix, MotorController. motor = new CANVictorMotorController(index); break; case TalonFX: + final ValueProvider CANBus = ConfigFileReader.getInstance().getString(configName + ".CANBus"); motor = new CANTalonFxMotorController(index); break; case VictorSP: diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java new file mode 100644 index 00000000..54c252e7 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -0,0 +1,386 @@ +package com.team766.robot.mechanisms; +import com.team766.framework.Mechanism; +import com.team766.hal.EncoderReader; +import com.team766.hal.RobotProvider; +import com.team766.hal.MotorController; +import com.team766.hal.MotorController.ControlMode; +import com.team766.hal.simulator.Encoder; +import com.team766.hal.MotorController; +import com.team766.library.RateLimiter; +import com.team766.library.ValueProvider; +import com.team766.logging.Category; +import com.team766.simulator.ProgramInterface.RobotMode; +import com.team766.config.ConfigFileReader; +import com.team766.framework.Mechanism; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; +import com.ctre.phoenix.sensors.AbsoluteSensorRange; +import com.ctre.phoenix.sensors.CANCoder; +import com.ctre.phoenix.sensors.CANCoderConfiguration; + + +public class Drive extends Mechanism { + + private MotorController m_DriveFrontRight; + private MotorController m_DriveFrontLeft; + private MotorController m_DriveBackRight; + private MotorController m_DriveBackLeft; + + private MotorController m_SteerFrontRight; + private MotorController m_SteerFrontLeft; + private MotorController m_SteerBackRight; + private MotorController m_SteerBackLeft; + + private CANCoder e_FrontRight; + private CANCoder e_FrontLeft; + private CANCoder e_BackRight; + private CANCoder e_BackLeft; + + private ValueProvider drivePower; + + private double gyroValue; + + private static PointDir currentPosition; + + private MotorController[] motorList; + private CANCoder[] CANCoderList; + + public static final double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; + + public Drive() { + + loggerCategory = Category.DRIVE; + // Initializations of motors + //Initialize the drive motors + m_DriveFrontRight = RobotProvider.instance.getMotor("drive.DriveFrontRight"); + m_DriveFrontLeft = RobotProvider.instance.getMotor("drive.DriveFrontLeft"); + m_DriveBackRight = RobotProvider.instance.getMotor("drive.DriveBackRight"); + m_DriveBackLeft = RobotProvider.instance.getMotor("drive.DriveBackLeft"); + //Initialize the steering motors + m_SteerFrontRight = RobotProvider.instance.getMotor("drive.SteerFrontRight"); + m_SteerFrontLeft = RobotProvider.instance.getMotor("drive.SteerFrontLeft"); + m_SteerBackRight = RobotProvider.instance.getMotor("drive.SteerBackRight"); + m_SteerBackLeft = RobotProvider.instance.getMotor("drive.SteerBackLeft"); + + //Setting up the "config" + CANCoderConfiguration config = new CANCoderConfiguration(); + config.absoluteSensorRange = AbsoluteSensorRange.Signed_PlusMinus180; + //The encoders output "encoder" values, so we need to convert that to degrees (because that is what the cool kids are using) + config.sensorCoefficient = 360.0 / 4096.0; + //The offset is going to be changed in ctre, but we can change it here too. + //config.magnetOffsetDegrees = Math.toDegrees(configuration.getOffset()); + config.sensorDirection = true; + + //initialize the encoders + e_FrontRight = new CANCoder(1, "Swerve"); + //e_FrontRight.configAllSettings(config, 250); + e_FrontLeft = new CANCoder(2, "Swerve"); + //e_FrontLeft.configAllSettings(config, 250); + e_BackRight = new CANCoder(4, "Swerve"); + //e_BackRight.configAllSettings(config, 250); + e_BackLeft = new CANCoder(3, "Swerve"); + //e_BackLeft.configAllSettings(config, 250); + + + //Current limit for motors to avoid breaker problems (mostly to avoid getting electrical people to yell at us) + m_DriveFrontRight.setCurrentLimit(35); + m_DriveFrontLeft.setCurrentLimit(35); + m_DriveBackRight.setCurrentLimit(35); + m_DriveBackLeft.setCurrentLimit(35); + m_DriveBackLeft.setInverted(true); + m_DriveBackRight.setInverted(true); + m_SteerFrontRight.setCurrentLimit(30); + m_SteerFrontLeft.setCurrentLimit(30); + m_SteerBackRight.setCurrentLimit(30); + m_SteerBackLeft.setCurrentLimit(30); + + //Setting up the connection between steering motors and cancoders + //m_SteerFrontRight.setRemoteFeedbackSensor(e_FrontRight, 0); + //m_SteerFrontLeft.setRemoteFeedbackSensor(e_FrontLeft, 0); + //m_SteerBackRight.setRemoteFeedbackSensor(e_BackRight, 0); + //m_SteerBackLeft.setRemoteFeedbackSensor(e_BackLeft, 0); + + m_SteerFrontRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerFrontLeft.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerBackRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerBackLeft.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + configPID(); + + } + //If you want me to repeat code, then no. + public double pythagorean(double x, double y) { + return Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2)); + } + public double getAngle(double LR, double FB){ + return Math.toDegrees(Math.atan2(LR ,-FB)); + } + public double round(double value, int places) { + double scale = Math.pow(10, places); + return Math.round(value * scale) / scale; + } + public double NewAng(double FirstMag, double FirstAng, double SecondMag, double SecondAng){ + double FinalX = FirstMag*Math.cos(Math.toRadians(FirstAng)) + SecondMag*Math.cos(Math.toRadians(SecondAng)); + double FinalY = FirstMag*Math.sin(Math.toRadians(FirstAng)) + SecondMag*Math.sin(Math.toRadians(SecondAng)); + return round(Math.toDegrees(Math.atan2(FinalY,FinalX)),5); + } + public double NewMag(double FirstMag, double FirstAng, double SecondMag, double SecondAng){ + double FinalX = FirstMag*Math.cos(Math.toRadians(FirstAng)) + SecondMag*Math.cos(Math.toRadians(SecondAng)); + double FinalY = FirstMag*Math.sin(Math.toRadians(FirstAng)) + SecondMag*Math.sin(Math.toRadians(SecondAng)); + return round(Math.sqrt(Math.pow(FinalX,2) + Math.pow(FinalY,2)),5); + } + + public static double correctedJoysticks(double Joystick){ + if(Joystick >= 0) + return(3.0*Math.pow(Joystick,2)-2.0*Math.pow(Joystick,3)); + else + return(-1*3.0*Math.pow(-1*Joystick,2)+2.0*Math.pow(-1*Joystick,3)); + } + + + public static double fieldAngle(double angle, double gyro){ + double newAngle; + newAngle = angle - gyro; + if(newAngle < 0){ + newAngle = newAngle + 360; + } + if(newAngle >= 180){ + newAngle = newAngle -360; + } + return newAngle; + } + public static double newAngle(double newAngle, double lastAngle){ + while(newAngle<0) newAngle += 360; + while(newAngle < (lastAngle - 180)) newAngle+=360; + while(newAngle > (lastAngle + 180)) newAngle-=360; + return newAngle; + } + //Not the actual gyro, but I am passing it through the OI.java to get it here + public void setGyro(double value){ + gyroValue = value; + } + //This is the method that is called to drive the robot in the 2D plane + public void drive2D(double JoystickX, double JoystickY) { + checkContextOwnership(); + //logs(); + //double power = pythagorean((JoystickX), correctedJoysticks(JoystickY))/Math.sqrt(2); + double power = Math.max(Math.abs(JoystickX),Math.abs(JoystickY)); + double angle = fieldAngle(getAngle(JoystickX, JoystickY),gyroValue); + log("Given angle: " + getAngle(JoystickX,JoystickY) + " || Gyro: " + gyroValue + " || New angle: " + angle); + //Temporary Drive code, kinda sucks + m_DriveFrontRight.set(power); + m_DriveFrontLeft.set(power); + m_DriveBackRight.set(power); + m_DriveBackLeft.set(power); + //Steer code + setFrontRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + } + + public void drive2D(Point joystick) { + drive2D(joystick.getX(), joystick.getY()); + } + + public void stopDriveMotors() { + checkContextOwnership(); + m_DriveFrontRight.stopMotor(); + m_DriveFrontLeft.stopMotor(); + m_DriveBackRight.stopMotor(); + m_DriveBackLeft.stopMotor(); + } + public void stopSteerMotors() { + checkContextOwnership(); + m_SteerFrontRight.stopMotor(); + m_SteerFrontLeft.stopMotor(); + m_SteerBackRight.stopMotor(); + m_SteerBackLeft.stopMotor(); + } + + + public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta){ + checkContextOwnership(); + double power = Math.max(Math.abs(JoystickX),Math.abs(JoystickY)); + double angle = fieldAngle(getAngle(JoystickX, JoystickY),gyroValue); + double frPower; + double flPower; + double brPower; + double blPower; + double frAngle; + double flAngle; + double brAngle; + double blAngle; + if(JoystickTheta >= 0){ + frPower = NewMag(power, angle, JoystickTheta, 135); + flPower = NewMag(power, angle, JoystickTheta, 45); + brPower = NewMag(power, angle, JoystickTheta, -135); + blPower = NewMag(power, angle, JoystickTheta, -45); + frAngle = NewAng(power, angle, JoystickTheta, 135); + flAngle = NewAng(power, angle, JoystickTheta, 45); + brAngle = NewAng(power, angle, JoystickTheta, -135); + blAngle = NewAng(power, angle, JoystickTheta, -45); + } + else{ + frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); + flPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); + brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); + blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); + frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + flAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); + brAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); + blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); + } + if(Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)) > 1){ + frPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + flPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + brPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + blPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + } + m_DriveFrontRight.set(frPower); + m_DriveFrontLeft.set(flPower); + m_DriveBackRight.set(brPower); + m_DriveBackLeft.set(blPower); + //Steer code + setFrontRightAngle(newAngle(frAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(flAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(brAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(blAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + } + + public void swerveDrive(PointDir joystick) { + swerveDrive(joystick.getY(), -1 * joystick.getX(), joystick.getHeading()); + } + +public void turning(double Joystick){ + checkContextOwnership(); + if(Joystick > 0){ + setFrontRightAngle(newAngle(135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(-135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(-45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + m_DriveFrontRight.set(Math.abs(Joystick)); + m_DriveFrontLeft.set(Math.abs(Joystick)); + m_DriveBackRight.set(Math.abs(Joystick)); + m_DriveBackLeft.set(Math.abs(Joystick)); + } + if(Joystick < 0){ + setFrontRightAngle(newAngle(-45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(-135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + m_DriveFrontRight.set(Math.abs(Joystick)); + m_DriveFrontLeft.set(Math.abs(Joystick)); + m_DriveBackRight.set(Math.abs(Joystick)); + m_DriveBackLeft.set(Math.abs(Joystick)); + } +} + + //Logging the encoder values (also I love Github Copilot <3) + public void logs(){ + log("Front Right Encoder: " + getFrontRight() + " Front Left Encoder: " + getFrontLeft() + " Back Right Encoder: " + getBackRight() + " Back Left Encoder: " + getBackLeft()); + } + public void setFrontRightEncoders(){ + m_SteerFrontRight.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontRight.getAbsolutePosition())); + } + public void setFrontLeftEncoders(){ + m_SteerFrontLeft.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontLeft.getAbsolutePosition())); + //log("New encoder value: " + (int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontLeft.getAbsolutePosition()) + " || Motor value: " + m_SteerFrontLeft.getSensorPosition()); + } + public void setBackRightEncoders(){ + m_SteerBackRight.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_BackRight.getAbsolutePosition())); + } + public void setBackLeftEncoders(){ + m_SteerBackLeft.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_BackLeft.getAbsolutePosition())); + } + //To control each steering individually with a PID + public void setFrontRightAngle(double angle){ + //log("Angle: " + getFrontRight() + " || Motor angle: " + 360.0/ 2048.0 * m_SteerFrontRight.getSensorPosition()); + m_SteerFrontRight.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setFrontLeftAngle(double angle){ + //log("Angle: " + getFrontLeft() + " || Motor angle: " + Math.pow((2048.0/360.0 * (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); + //log("Angle: %f Motor angle: %f", getFrontLeft(), Math.pow((2048.0/360.0 * (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); + m_SteerFrontLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setBackRightAngle(double angle){ + //log("Angle: " + getBackRight() + " || Motor angle: " + m_SteerBackRight.getSensorPosition()); + m_SteerBackRight.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setBackLeftAngle(double angle){ + //log("Angle: " + getBackLeft() + " || Motor angle: " + m_SteerBackLeft.getSensorPosition()); + m_SteerBackLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); + } + public void setSFR(double angle){ + setFrontRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void setSFL(double angle){ + setFrontLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void setSBR(double angle){ + setBackRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void setSBL(double angle){ + setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + } + public void configPID(){ + //PID for turning the various steering motors. Here is a good link to a tuning website: https://www.robotsforroboticists.com/pid-control/ + m_SteerFrontRight.setP(0.2); + m_SteerFrontRight.setI(0); + m_SteerFrontRight.setD(0.1); + m_SteerFrontRight.setFF(0); + + m_SteerFrontLeft.setP(0.2); + m_SteerFrontLeft.setI(0); + m_SteerFrontLeft.setD(0.1); + m_SteerFrontLeft.setFF(0); + + m_SteerBackRight.setP(0.2); + m_SteerBackRight.setI(0); + m_SteerBackRight.setD(0.1); + m_SteerBackRight.setFF(0); + + m_SteerBackLeft.setP(0.2); + m_SteerBackLeft.setI(0); + m_SteerBackLeft.setD(0.1); + m_SteerBackLeft.setFF(0); + + //pid values from sds for Flacons 500: P = 0.2 I = 0.0 D = 0.1 FF = 0.0 + + //IDK what those do tbh, but I like to keep them here. + //m_SteerFrontRight.setSensorInverted(false); + //m_SteerFrontLeft.setSensorInverted(false); + //m_SteerBackRight.setSensorInverted(false); + //m_SteerBackLeft.setSensorInverted(false); + } + + //Method to get the encoder values, the encoders are in degrees from -180 to 180. To change that, we need to change the syntax and use getPosition() + public double getFrontRight(){ + return e_FrontRight.getAbsolutePosition(); + } + public double getFrontLeft(){ + return e_FrontLeft.getAbsolutePosition(); + } + public double getBackRight(){ + return e_BackRight.getAbsolutePosition(); + } + public double getBackLeft(){ + return e_BackLeft.getAbsolutePosition(); + } + + public PointDir getCurrentPosition() { + return currentPosition; + } + + public void resetCurrentPosition() { + swerveOdometry.resetCurrentPosition(); + } + + public void resetDriveEncoders() { + m_DriveBackLeft.setSensorPosition(0); + m_DriveBackRight.setSensorPosition(0); + m_DriveFrontLeft.setSensorPosition(0); + m_DriveFrontRight.setSensorPosition(0); + } + +} + +//AS \ No newline at end of file diff --git a/src/main/java/com/team766/robot/mechanisms/Gyro.java b/src/main/java/com/team766/robot/mechanisms/Gyro.java new file mode 100644 index 00000000..e08dffcd --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Gyro.java @@ -0,0 +1,54 @@ +package com.team766.robot.mechanisms; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.SerialPort; +import edu.wpi.first.wpilibj.I2C.Port; + +import com.team766.framework.Mechanism; +import com.team766.hal.EncoderReader; +import com.team766.hal.RobotProvider; +import com.team766.hal.MotorController; +import com.team766.library.RateLimiter; +import com.team766.hal.MotorController; +import com.team766.logging.Category; +//import edu.wpi.first.wpilibj.I2C.Port; +//import com.team766.hal.GyroReader; +//import com.kauailabs.navx.frc.*; +import com.ctre.phoenix.sensors.Pigeon2; + +public class Gyro extends Mechanism { + Pigeon2 g_gyro = new Pigeon2(0, "Swerve"); + double[] gyroArray = new double[3]; + private RateLimiter l_loggingRate = new RateLimiter(0.05); + public Gyro() { + loggerCategory = Category.GYRO; + } + public void resetGyro(){ + g_gyro.setYaw(0); + } + public double getGyroPitch() { + double angle = g_gyro.getPitch(); + return angle; + + } + + public double getGyroYaw() { + double angle = -1* g_gyro.getYaw(); + return angle; + } + + public double getGyroRoll() { + double angle = g_gyro.getRoll(); + return angle; + } + + @Override + public void run() { + if (l_loggingRate.next()) { + gyroArray[0] = getGyroYaw(); + gyroArray[1] = getGyroPitch(); + gyroArray[2] = getGyroRoll(); + g_gyro.getYawPitchRoll(gyroArray); + log("Yaw: " + gyroArray[0] + "// Real yaw: " + getGyroYaw() + " || Pitch: " + gyroArray[1] + " || Roll: " + gyroArray[2]); + } + } +} \ No newline at end of file From 9a242dd9d0b2d806ba578c501c3c83210c5557b6 Mon Sep 17 00:00:00 2001 From: qntmcube <100043837+qntmcube@users.noreply.github.com> Date: Mon, 23 Jan 2023 21:06:16 +0000 Subject: [PATCH 023/103] added robot controls --- src/main/java/com/team766/robot/OI.java | 108 +++++++++++++++++++++ src/main/java/com/team766/robot/Robot.java | 2 + 2 files changed, 110 insertions(+) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index b33f97e4..7c888479 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -16,6 +16,15 @@ public class OI extends Procedure { private JoystickReader joystick0; private JoystickReader joystick1; private JoystickReader joystick2; + private double RightJoystick_X = 0; + private double RightJoystick_Y = 0; + private double RightJoystick_Z = 0; + private double RightJoystick_Theta = 0; + private double LeftJoystick_X = 0; + private double LeftJoystick_Y = 0; + private double LeftJoystick_Z = 0; + private double LeftJoystick_Theta = 0; + double turningValue = 0; public OI() { loggerCategory = Category.OPERATOR_INTERFACE; @@ -26,6 +35,15 @@ public OI() { } public void run(Context context) { + double prev_time = RobotProvider.instance.getClock().getTime(); + context.takeOwnership(Robot.gyro); + context.takeOwnership(Robot.drive); + //Robot.gyro.resetGyro(); + Robot.drive.setFrontRightEncoders(); + Robot.drive.setFrontLeftEncoders(); + Robot.drive.setBackRightEncoders(); + Robot.drive.setBackLeftEncoders(); + while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); @@ -33,6 +51,96 @@ public void run(Context context) { // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. + if(joystick1.getButton(2)){ + Robot.drive.setGyro(0); + }else{ + Robot.drive.setGyro(Robot.gyro.getGyroYaw()); + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ + RightJoystick_Y = joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + } else { + RightJoystick_Y = 0; + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ + RightJoystick_X = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; + if(joystick1.getButton(3)){ + RightJoystick_X *= 2; + } + } else { + RightJoystick_X = 0; + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ + RightJoystick_Theta = joystick1.getAxis(InputConstants.AXIS_TWIST); + } else { + RightJoystick_Theta = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ + LeftJoystick_Y = joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + } else { + LeftJoystick_Y = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ + LeftJoystick_X = joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT); + } else { + LeftJoystick_X = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ + LeftJoystick_Theta = joystick0.getAxis(InputConstants.AXIS_TWIST); + } else { + LeftJoystick_Theta = 0; + } + //log(Robot.gyro.getGyroYaw()); + //TODO: fix defense: the robot basically locks up if there is defense + // if(joystick0.getButton(InputConstants.CROSS_DEFENSE)){ + // context.startAsync(new DefenseCross()); + // } + + /*if(Math.pow(Math.pow(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT),2) + Math.pow(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD),2), 0.5) > 0.15 ){ + Robot.drive.drive2D( + ((joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT))), + ((joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD))) + ); + } else { + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST))>=0.1){ + Robot.drive.turning(joystick0.getAxis(InputConstants.AXIS_TWIST)); + } else { + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + } + }*/ + if(joystick0.getButtonPressed(1)) + Robot.gyro.resetGyro(); + + if(joystick0.getButtonPressed(2)){ + Robot.drive.setFrontRightEncoders(); + Robot.drive.setFrontLeftEncoders(); + Robot.drive.setBackRightEncoders(); + Robot.drive.setBackLeftEncoders(); + } + // if(joystick1.getButton(1)){ + // turningValue = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT); + // } else { + // turningValue = 0; + // } + if(Math.abs(LeftJoystick_X)+ + Math.abs(LeftJoystick_Y)+ Math.abs(RightJoystick_X) > 0){ + Robot.drive.swerveDrive( + (LeftJoystick_X), + (LeftJoystick_Y), + (RightJoystick_X) + );} else{ + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + } + + if (joystick0.getButtonPressed(11)) { + Robot.drive.resetCurrentPosition(); + } + + if (joystick1.getButtonPressed(11)) { + context.takeOwnership(Robot.drive); + new FollowPoints().run(context); + } } } } diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java index b2b3c2a7..1bf3e129 100644 --- a/src/main/java/com/team766/robot/Robot.java +++ b/src/main/java/com/team766/robot/Robot.java @@ -4,10 +4,12 @@ public class Robot { // Declare mechanisms here + public static Drive drive; public static void robotInit() { // Initialize mechanisms here + drive = new Drive(); } } From 3354d2f671ffe31d770e444301e7b19708573ffc Mon Sep 17 00:00:00 2001 From: qntmcube <119382968+IndraGerard@users.noreply.github.com> Date: Mon, 23 Jan 2023 18:50:34 -0800 Subject: [PATCH 024/103] got rid of unnecesary odometry code/fixed errors --- .../team766/hal/wpilib/WPIRobotProvider.java | 6 +++-- .../com/team766/robot/InputConstants.java | 22 +++++++++++++++++++ src/main/java/com/team766/robot/OI.java | 9 -------- src/main/java/com/team766/robot/Robot.java | 2 ++ .../com/team766/robot/mechanisms/Drive.java | 15 ------------- 5 files changed, 28 insertions(+), 26 deletions(-) create mode 100644 src/main/java/com/team766/robot/InputConstants.java diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index c6fd2312..2e8bd957 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -2,6 +2,7 @@ import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; +import com.team766.config.ConfigFileReader; import com.team766.hal.AnalogInputReader; import com.team766.hal.CameraInterface; import com.team766.hal.CameraReader; @@ -19,6 +20,7 @@ import com.team766.hal.MotorController; import com.team766.hal.mock.MockGyro; import com.team766.hal.mock.MockPositionSensor; +import com.team766.library.ValueProvider; import com.team766.hal.mock.MockMotorController; import com.team766.logging.Category; import com.team766.logging.Logger; @@ -124,8 +126,8 @@ public MotorController getMotor(int index, String configPrefix, MotorController. motor = new CANVictorMotorController(index); break; case TalonFX: - final ValueProvider CANBus = ConfigFileReader.getInstance().getString(configName + ".CANBus"); - motor = new CANTalonFxMotorController(index); + final ValueProvider CANBus = ConfigFileReader.getInstance().getString(type + ".CANBus"); + motor = new CANTalonFxMotorController(index, CANBus.get()); break; case VictorSP: motor = new LocalMotorController(configPrefix, new PWMVictorSP(index), localSensor); diff --git a/src/main/java/com/team766/robot/InputConstants.java b/src/main/java/com/team766/robot/InputConstants.java new file mode 100644 index 00000000..2b95d074 --- /dev/null +++ b/src/main/java/com/team766/robot/InputConstants.java @@ -0,0 +1,22 @@ +package com.team766.robot; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + * TODO: consider moving this into a config file. + */ +public final class InputConstants { + + //Joysticks + public static final int LEFT_JOYSTICK = 0; + public static final int RIGHT_JOYSTICK = 1; + public static final int CONTROL_PANEL = 2; + + //Navigation + public static final int AXIS_LEFT_RIGHT = 0; + public static final int AXIS_FORWARD_BACKWARD = 1; + public static final int AXIS_TWIST =3; + // Joystick buttons + public static final int CROSS_DEFENSE = 7; + //Other buttons +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 7c888479..d9560ef6 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -132,15 +132,6 @@ public void run(Context context) { Robot.drive.stopDriveMotors(); Robot.drive.stopSteerMotors(); } - - if (joystick0.getButtonPressed(11)) { - Robot.drive.resetCurrentPosition(); - } - - if (joystick1.getButtonPressed(11)) { - context.takeOwnership(Robot.drive); - new FollowPoints().run(context); - } } } } diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java index 1bf3e129..713f97e5 100644 --- a/src/main/java/com/team766/robot/Robot.java +++ b/src/main/java/com/team766/robot/Robot.java @@ -5,11 +5,13 @@ public class Robot { // Declare mechanisms here public static Drive drive; + public static Gyro gyro; public static void robotInit() { // Initialize mechanisms here drive = new Drive(); + gyro = new Gyro(); } } diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 54c252e7..098baa1b 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -39,8 +39,6 @@ public class Drive extends Mechanism { private double gyroValue; - private static PointDir currentPosition; - private MotorController[] motorList; private CANCoder[] CANCoderList; @@ -177,9 +175,6 @@ public void drive2D(double JoystickX, double JoystickY) { setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); } - public void drive2D(Point joystick) { - drive2D(joystick.getX(), joystick.getY()); - } public void stopDriveMotors() { checkContextOwnership(); @@ -246,9 +241,6 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta setBackLeftAngle(newAngle(blAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); } - public void swerveDrive(PointDir joystick) { - swerveDrive(joystick.getY(), -1 * joystick.getX(), joystick.getHeading()); - } public void turning(double Joystick){ checkContextOwnership(); @@ -366,13 +358,6 @@ public double getBackLeft(){ return e_BackLeft.getAbsolutePosition(); } - public PointDir getCurrentPosition() { - return currentPosition; - } - - public void resetCurrentPosition() { - swerveOdometry.resetCurrentPosition(); - } public void resetDriveEncoders() { m_DriveBackLeft.setSensorPosition(0); From 0cb799bad190cc94a0acb8d964ca0d78fd994b57 Mon Sep 17 00:00:00 2001 From: qntmcube <119382968+IndraGerard@users.noreply.github.com> Date: Wed, 25 Jan 2023 20:15:24 -0800 Subject: [PATCH 025/103] Got swerve working with CANivore --- src/main/java/com/team766/robot/OI.java | 4 ++++ .../java/com/team766/robot/mechanisms/Drive.java | 16 ++++++++-------- src/main/proto/com/team766/logging/logging.proto | 1 + 3 files changed, 13 insertions(+), 8 deletions(-) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index d9560ef6..f8efec08 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -51,6 +51,10 @@ public void run(Context context) { // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. + log("Back Left:" + Robot.drive.getBackLeft()); + log("Front Left:" + Robot.drive.getFrontLeft()); + log("Front Right:" + Robot.drive.getFrontRight()); + log("Back Right:" + Robot.drive.getBackRight()); if(joystick1.getButton(2)){ Robot.drive.setGyro(0); }else{ diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 098baa1b..d401f452 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -209,20 +209,20 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta flPower = NewMag(power, angle, JoystickTheta, 45); brPower = NewMag(power, angle, JoystickTheta, -135); blPower = NewMag(power, angle, JoystickTheta, -45); - frAngle = NewAng(power, angle, JoystickTheta, 135); - flAngle = NewAng(power, angle, JoystickTheta, 45); - brAngle = NewAng(power, angle, JoystickTheta, -135); - blAngle = NewAng(power, angle, JoystickTheta, -45); + frAngle = NewAng(power, angle, JoystickTheta, 45); + flAngle = NewAng(power, angle, JoystickTheta, -45); + brAngle = NewAng(power, angle, JoystickTheta, 135); + blAngle = NewAng(power, angle, JoystickTheta, -135); } else{ frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); flPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); - frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); - flAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); - brAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); - blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); + frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); + flAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); + brAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); } if(Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)) > 1){ frPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); diff --git a/src/main/proto/com/team766/logging/logging.proto b/src/main/proto/com/team766/logging/logging.proto index 40dc4b72..11ef267c 100644 --- a/src/main/proto/com/team766/logging/logging.proto +++ b/src/main/proto/com/team766/logging/logging.proto @@ -37,6 +37,7 @@ enum Category { TRAJECTORY = 9; OPERATOR_INTERFACE = 10; DRIVE = 11; + GYRO = 12; } // `Value` represents a dynamically typed value which can be either a number, From fede0d64076e6a38b2b6ea76c0e364bf0b3bd0b5 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Fri, 27 Jan 2023 20:12:23 -0800 Subject: [PATCH 026/103] Added critical points and rotation to FollowPoints --- .../robot/procedures/FollowPoints.java | 131 ++++++++++-------- 1 file changed, 74 insertions(+), 57 deletions(-) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 1f2ac6ed..9ccd9bf9 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -18,6 +18,8 @@ import com.team766.controllers.PIDController; public class FollowPoints extends Procedure { + + //Steps combine possible data types into one object for flexibility and ease-of-use purposes public static class Step { public PointDir wayPoint; public boolean criticalPoint; @@ -33,15 +35,15 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private List steps = new ArrayList(); - private PointDir currentPos = new PointDir(0.0, 0.0, 0.0); + private static PointDir currentPos = new PointDir(0.0, 0.0, 0.0); + private static PointDir lastPos = new PointDir(0.0, 0.0, 0.0); private PointDir[] pointList; private Procedure[] proceduresAtPoints; private boolean[] criticalPointList; private boolean[] stopRobotList; + //Radius defines the radius of the circle around the robot private static double radius = ConfigFileReader.getInstance().getDouble("trajectory.radius").get(); - private static double leniency = ConfigFileReader.getInstance().getDouble("trajectory.leniency").get(); private static double speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); - private double finalHeader; /*public FollowPoints() { parsePointList(); @@ -52,16 +54,19 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole loggerCategory = Category.AUTONOMOUS; }*/ + //Creates a new Step object from its constituents private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { steps.add(new Step(wayPoint, criticalPoint, procedure, stopRobot)); } + //Default FollowPoints Constructor, Steps must be added here public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); addStep(new PointDir(0,20, 30), false, null /* don't execute procedure */, false); addWaypoints(); } + //When using steps, this sets up the arrays to be used by the FollowPoints method private void addWaypoints() { pointList = new PointDir[steps.size()]; proceduresAtPoints = new Procedure[steps.size()]; @@ -84,6 +89,7 @@ private void addWaypoints() { } } + //Takes an array of procedures and uses points from the config file public FollowPoints(Procedure[] procedureList) { parsePointList(); proceduresAtPoints = procedureList; @@ -92,9 +98,9 @@ public FollowPoints(Procedure[] procedureList) { loggerCategory = Category.AUTONOMOUS; } + //Takes an array of points public FollowPoints(PointDir[] points) { pointList = points; - finalHeader = Robot.drive.getCurrentPosition().getHeading(); proceduresAtPoints = new Procedure[pointList.length]; for (int i = 0; i < proceduresAtPoints.length; i++) { proceduresAtPoints[i] = new DoNothing(); @@ -104,9 +110,9 @@ public FollowPoints(PointDir[] points) { loggerCategory = Category.AUTONOMOUS; } + //Takes an array of points and an array of procedures to do at each point public FollowPoints(PointDir[] points, Procedure[] procedureList) { pointList = points; - finalHeader = Robot.drive.getCurrentPosition().getHeading(); proceduresAtPoints = procedureList; criticalPointList = new boolean[pointList.length]; stopRobotList = new boolean[pointList.length]; @@ -127,24 +133,6 @@ private void parsePointList() { pointList[i / 2] = new PointDir(pointX, pointY); } } - if (pointDoubles.length % 2 == 1) { - finalHeader = pointDoubles[pointDoubles.length - 1]; - } else { - finalHeader = Robot.drive.getCurrentPosition().getHeading(); - } - - while (finalHeader > Math.round(Robot.drive.getCurrentPosition().getHeading() / 360) * 360 + 180) { - finalHeader -= 360; - } - while (finalHeader <= Math.round(Robot.drive.getCurrentPosition().getHeading() / 360) * 360 - 180) { - finalHeader += 360; - } - if (finalHeader - Robot.drive.getCurrentPosition().getHeading() >= 180) { - finalHeader -= 360; - } - if (finalHeader - Robot.drive.getCurrentPosition().getHeading() < -180) { - finalHeader += 360; - } } public void run(Context context) { @@ -161,11 +149,13 @@ public void run(Context context) { if (pointList.length > 0) { int targetNum = 0; Point targetPoint = new Point(0.0, 0.0); - currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); - while (currentPos.distance(pointList[pointList.length - 1]) > leniency || targetNum != pointList.length - 1) { + while (targetNum != pointList.length - 1 && !passedPoint(pointList[pointList.length - 1])) { + lastPos = currentPos.clone(); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); - if (currentPos.distance(pointList[targetNum]) <= radius && checkIntersection(targetNum, currentPos, pointList, radius)) { + //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point + //Otherwise, it uses the checkIntersection() method to follow the circle + if (criticalPointList[targetNum]? passedPoint(pointList[targetNum]) : checkIntersection(targetNum, currentPos, pointList, radius)) { if (proceduresAtPoints.length < targetNum) { if (stopRobotList[targetNum]) { context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); @@ -181,10 +171,10 @@ public void run(Context context) { //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), 0)); + Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint)))); log("Current Position: " + currentPos.toString()); log("Target Point: " + targetPoint.toString()); - log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), 0).toString()); + log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint))).toString()); context.yield(); } @@ -197,16 +187,16 @@ public void run(Context context) { //Returns whether the circle around the robot intersects the line connecting the two next points. public static boolean checkIntersection(int targetNum, PointDir currentPos, Point[] pointList, double radius) { - double aValue; - double bValue; - double cValue; + double a; + double b; + double c; double slope; if (targetNum < pointList.length - 1) { slope = pointList[targetNum].slope(pointList[targetNum + 1]); - aValue = slope * slope + 1; - bValue = -2 * currentPos.getX() - 2 * slope * slope * pointList[targetNum].getX() + 2 * slope * pointList[targetNum].getY() - 2 * currentPos.getY() * slope; - cValue = currentPos.getX() * currentPos.getX() + slope * slope * pointList[targetNum].getX() * pointList[targetNum].getX() - 2 * slope * pointList[targetNum].getX() * pointList[targetNum].getY() + pointList[targetNum].getY() * pointList[targetNum].getY() + 2 * currentPos.getY() * slope * pointList[targetNum].getX() - 2 * currentPos.getY() * pointList[targetNum].getY() + currentPos.getY() * currentPos.getY() - radius * radius; - if (bValue * bValue - 4 * aValue * cValue > 0) { + a = slope * slope + 1; + b = -2 * currentPos.getX() - 2 * slope * slope * pointList[targetNum].getX() + 2 * slope * pointList[targetNum].getY() - 2 * currentPos.getY() * slope; + c = currentPos.getX() * currentPos.getX() + slope * slope * pointList[targetNum].getX() * pointList[targetNum].getX() - 2 * slope * pointList[targetNum].getX() * pointList[targetNum].getY() + pointList[targetNum].getY() * pointList[targetNum].getY() + 2 * currentPos.getY() * slope * pointList[targetNum].getX() - 2 * currentPos.getY() * pointList[targetNum].getY() + currentPos.getY() * currentPos.getY() - radius * radius; + if (b * b - 4 * a * c > 0) { return true; } } @@ -215,38 +205,65 @@ public static boolean checkIntersection(int targetNum, PointDir currentPos, Poin //If the circle around the robot intersects the line connecting the previous and next points, returns whichever intersection point is closest to the next point. Otherwise, returns the next point. public static Point selectTargetPoint(int targetNum, PointDir currentPos, Point[] pointList, double radius) { - double aValue; - double bValue; - double cValue; + double a; + double b; + double c; double slope; - double potX1; - double potX2; - double potY1; - double potY2; - Point pot1 = new Point(0.0, 0.0); - Point pot2 = new Point(0.0, 0.0); + double potentialX1; + double potentialX2; + double potentialY1; + double potentialY2; + Point potentialPoint1 = new Point(0.0, 0.0); + Point potentialPoint2 = new Point(0.0, 0.0); if (targetNum == 0) { return pointList[0]; } else { slope = pointList[targetNum - 1].slope(pointList[targetNum]); - aValue = slope * slope + 1; - bValue = -2 * currentPos.getX() - 2 * slope * slope * pointList[targetNum - 1].getX() + 2 * slope * pointList[targetNum - 1].getY() - 2 * currentPos.getY() * slope; - cValue = currentPos.getX() * currentPos.getX() + slope * slope * pointList[targetNum - 1].getX() * pointList[targetNum - 1].getX() - 2 * slope * pointList[targetNum - 1].getX() * pointList[targetNum - 1].getY() + pointList[targetNum - 1].getY() * pointList[targetNum - 1].getY() + 2 * currentPos.getY() * slope * pointList[targetNum - 1].getX() - 2 * currentPos.getY() * pointList[targetNum - 1].getY() + currentPos.getY() * currentPos.getY() - radius * radius; - if (bValue * bValue - 4 * aValue * cValue < 0) { + a = slope * slope + 1; + b = -2 * currentPos.getX() - 2 * slope * slope * pointList[targetNum - 1].getX() + 2 * slope * pointList[targetNum - 1].getY() - 2 * currentPos.getY() * slope; + c = currentPos.getX() * currentPos.getX() + slope * slope * pointList[targetNum - 1].getX() * pointList[targetNum - 1].getX() - 2 * slope * pointList[targetNum - 1].getX() * pointList[targetNum - 1].getY() + pointList[targetNum - 1].getY() * pointList[targetNum - 1].getY() + 2 * currentPos.getY() * slope * pointList[targetNum - 1].getX() - 2 * currentPos.getY() * pointList[targetNum - 1].getY() + currentPos.getY() * currentPos.getY() - radius * radius; + if (b * b - 4 * a * c < 0) { return pointList[targetNum]; } else { - potX1 = (-1 * bValue + Math.sqrt(bValue * bValue - 4 * aValue * cValue))/ (2 * aValue); - potX2 = (-1 * bValue - Math.sqrt(bValue * bValue - 4 * aValue * cValue))/ (2 * aValue); - potY1 = slope * (potX1 - pointList[targetNum - 1].getX()) + pointList[targetNum - 1].getY(); - potY2 = slope * (potX2 - pointList[targetNum - 1].getX()) + pointList[targetNum - 1].getY(); - pot1.set(potX1, potY1); - pot2.set(potX2, potY2); - if (pot1.distance(pointList[targetNum]) <= pot2.distance(pointList[targetNum])) { - return pot1; + potentialX1 = (-1 * b + Math.sqrt(b * b - 4 * a * c))/ (2 * a); + potentialX2 = (-1 * b - Math.sqrt(b * b - 4 * a * c))/ (2 * a); + potentialY1 = slope * (potentialX1 - pointList[targetNum - 1].getX()) + pointList[targetNum - 1].getY(); + potentialY2 = slope * (potentialX2 - pointList[targetNum - 1].getX()) + pointList[targetNum - 1].getY(); + potentialPoint1.set(potentialX1, potentialY1); + potentialPoint2.set(potentialX2, potentialY2); + if (potentialPoint1.distance(pointList[targetNum]) <= potentialPoint2.distance(pointList[targetNum])) { + return potentialPoint1; } else { - return pot2; + return potentialPoint2; } } } } + + //Returns if the robot has passed a certain point + public static boolean passedPoint(Point P) { + return currentPos.distance(P) > lastPos.distance(P); + } + + //Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point + public static double rotationSpeed(double currentRot, double targetRot) { + double maxSpeed = 0.5; + double angleDistanceForMaxSpeed = 45; + currentRot = mod(currentRot, 360); + targetRot = mod(targetRot, 360); + if (Math.abs(targetRot - currentRot) < Math.abs(targetRot + 360 - currentRot)) { + targetRot += 360; + } + if (Math.abs(targetRot - currentRot) < Math.abs(targetRot - 360 - currentRot)) { + targetRot -= 360; + } + if (Math.abs(targetRot - currentRot) <= angleDistanceForMaxSpeed) { + return (currentRot - targetRot) / angleDistanceForMaxSpeed * maxSpeed; + } + return maxSpeed * Math.signum(currentRot - targetRot); + } + + public static double mod(double d1, double d2) { + return d1 % d2 + (d1 < 0 ? d2 : 0); + } } \ No newline at end of file From 05bbca2b03e7a370fb94a020e66007ac72b0c71f Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Sat, 28 Jan 2023 14:59:11 -0800 Subject: [PATCH 027/103] Signified how to make FollowPoints() field oriented --- src/main/java/com/team766/robot/procedures/FollowPoints.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 9ccd9bf9..4311fd29 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -140,6 +140,8 @@ public void run(Context context) { context.takeOwnership(Robot.drive); context.takeOwnership(Robot.gyro); log("Starting FollowPoints"); + //This resetCurrentPosition() call makes FollowPoints() robot-oriented instead of field-oriented + //If we need to make this method field-oriented, just remove this line Robot.drive.resetCurrentPosition(); Robot.gyro.resetGyro(); From 39ab4cdb2cfd5f4ef83a59cedccd7530c94945e2 Mon Sep 17 00:00:00 2001 From: qntmcube <119382968+IndraGerard@users.noreply.github.com> Date: Sat, 28 Jan 2023 15:06:19 -0800 Subject: [PATCH 028/103] improved swerve code added a wheel cross procedure --- src/main/java/com/team766/robot/OI.java | 24 ++++-- .../com/team766/robot/mechanisms/Drive.java | 81 +++++++++++-------- .../team766/robot/procedures/setCross.java | 16 ++++ 3 files changed, 79 insertions(+), 42 deletions(-) create mode 100644 src/main/java/com/team766/robot/procedures/setCross.java diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index f8efec08..0512e647 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -24,6 +24,7 @@ public class OI extends Procedure { private double LeftJoystick_Y = 0; private double LeftJoystick_Z = 0; private double LeftJoystick_Theta = 0; + private boolean isCross = false; double turningValue = 0; public OI() { @@ -114,6 +115,10 @@ public void run(Context context) { }*/ if(joystick0.getButtonPressed(1)) Robot.gyro.resetGyro(); + + if(joystick1.getButtonPressed(1)) + isCross = !isCross; + if(joystick0.getButtonPressed(2)){ Robot.drive.setFrontRightEncoders(); @@ -126,16 +131,19 @@ public void run(Context context) { // } else { // turningValue = 0; // } - if(Math.abs(LeftJoystick_X)+ - Math.abs(LeftJoystick_Y)+ Math.abs(RightJoystick_X) > 0){ - Robot.drive.swerveDrive( - (LeftJoystick_X), - (LeftJoystick_Y), - (RightJoystick_X) - );} else{ + + if (isCross) { + context.startAsync(new setCross()); + } else if(Math.abs(LeftJoystick_X)+ + Math.abs(LeftJoystick_Y) + Math.abs(RightJoystick_X) > 0) { + Robot.drive.swerveDrive( + (LeftJoystick_X), + (LeftJoystick_Y), + (RightJoystick_X)); + } else { Robot.drive.stopDriveMotors(); Robot.drive.stopSteerMotors(); - } + } } } } diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index d401f452..3225729d 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -3,6 +3,7 @@ import com.team766.hal.EncoderReader; import com.team766.hal.RobotProvider; import com.team766.hal.MotorController; +import com.team766.hal.MotorControllerCommandFailedException; import com.team766.hal.MotorController.ControlMode; import com.team766.hal.simulator.Encoder; import com.team766.hal.MotorController; @@ -169,10 +170,10 @@ public void drive2D(double JoystickX, double JoystickY) { m_DriveBackRight.set(power); m_DriveBackLeft.set(power); //Steer code - setFrontRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerBackLeft))); } @@ -235,36 +236,40 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta m_DriveBackRight.set(brPower); m_DriveBackLeft.set(blPower); //Steer code - setFrontRightAngle(newAngle(frAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(flAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(brAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(blAngle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); + setFrontRightAngle(newAngle(frAngle, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(flAngle, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(brAngle, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(blAngle, getCurrentAngle(m_SteerBackLeft))); } -public void turning(double Joystick){ - checkContextOwnership(); - if(Joystick > 0){ - setFrontRightAngle(newAngle(135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(-135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(-45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); - m_DriveFrontRight.set(Math.abs(Joystick)); - m_DriveFrontLeft.set(Math.abs(Joystick)); - m_DriveBackRight.set(Math.abs(Joystick)); - m_DriveBackLeft.set(Math.abs(Joystick)); - } - if(Joystick < 0){ - setFrontRightAngle(newAngle(-45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(-135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(45, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(135, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerBackLeft.getSensorPosition())); - m_DriveFrontRight.set(Math.abs(Joystick)); - m_DriveFrontLeft.set(Math.abs(Joystick)); - m_DriveBackRight.set(Math.abs(Joystick)); - m_DriveBackLeft.set(Math.abs(Joystick)); + public void turning(double Joystick){ + checkContextOwnership(); + if(Joystick > 0){ + setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); + m_DriveFrontRight.set(Math.abs(Joystick)); + m_DriveFrontLeft.set(Math.abs(Joystick)); + m_DriveBackRight.set(Math.abs(Joystick)); + m_DriveBackLeft.set(Math.abs(Joystick)); + } + if(Joystick < 0){ + setFrontRightAngle(newAngle(-45, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(-135, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(45, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(135, getCurrentAngle(m_SteerBackLeft))); + m_DriveFrontRight.set(Math.abs(Joystick)); + m_DriveFrontLeft.set(Math.abs(Joystick)); + m_DriveBackRight.set(Math.abs(Joystick)); + m_DriveBackLeft.set(Math.abs(Joystick)); + } + } + + private double getCurrentAngle(MotorController motor) { + return Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * motor.getSensorPosition(); } -} //Logging the encoder values (also I love Github Copilot <3) public void logs(){ @@ -302,16 +307,16 @@ public void setBackLeftAngle(double angle){ m_SteerBackLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); } public void setSFR(double angle){ - setFrontRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); } public void setSFL(double angle){ - setFrontLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); } public void setSBR(double angle){ - setBackRightAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); } public void setSBL(double angle){ - setBackLeftAngle(newAngle(angle, Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * m_SteerFrontRight.getSensorPosition())); + setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); } public void configPID(){ //PID for turning the various steering motors. Here is a good link to a tuning website: https://www.robotsforroboticists.com/pid-control/ @@ -358,6 +363,14 @@ public double getBackLeft(){ return e_BackLeft.getAbsolutePosition(); } + public void setCross() { + checkContextOwnership(); + setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); + setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); + setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); + setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); + } + public void resetDriveEncoders() { m_DriveBackLeft.setSensorPosition(0); diff --git a/src/main/java/com/team766/robot/procedures/setCross.java b/src/main/java/com/team766/robot/procedures/setCross.java new file mode 100644 index 00000000..e481c027 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/setCross.java @@ -0,0 +1,16 @@ +package com.team766.robot.procedures; + +import com.team766.framework.Context; +import com.team766.framework.Procedure; +import com.team766.robot.Robot; + +public class setCross extends Procedure { + + public void run(Context context) { + context.takeOwnership(Robot.drive); + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + Robot.drive.setCross(); + } + +} From ddaa03376641e69bb1d96be417b560125bf61c75 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Mon, 30 Jan 2023 18:56:14 -0800 Subject: [PATCH 029/103] Added example FileReader --- .../com/team766/robot/procedures/FollowPoints.java | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 4311fd29..14f29128 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -9,18 +9,24 @@ import com.team766.odometry.Point; import com.team766.odometry.PointDir; import com.team766.hal.PositionReader; - +import java.io.File; +import java.nio.file.Path; import java.util.ArrayList; import java.util.List; import com.team766.config.ConfigFileReader; import com.team766.logging.Category; import com.team766.controllers.PIDController; - +import edu.wpi.first.wpilibj.Filesystem; + public class FollowPoints extends Procedure { //Steps combine possible data types into one object for flexibility and ease-of-use purposes public static class Step { + + Path path = Filesystem.getDeployDirectory().toPath().resolve("BLABLABLA.JSON"); + File file = path.toFile(); + public PointDir wayPoint; public boolean criticalPoint; public Procedure procedure; From fc0c6f77617cf5fb5305ba8cd8f50979ae33a992 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Mon, 6 Feb 2023 20:11:32 -0800 Subject: [PATCH 030/103] Made FollowPoints work with CANivore --- .../java/com/team766/robot/AutonomousModes.java | 2 +- src/main/java/com/team766/robot/OI.java | 3 +++ .../com/team766/robot/procedures/FollowPoints.java | 13 ++++++++----- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java index 36008b02..b2e69393 100644 --- a/src/main/java/com/team766/robot/AutonomousModes.java +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -17,7 +17,7 @@ public class AutonomousModes { // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), new AutonomousMode("FollowPoints", () -> new FollowPoints()), - new AutonomousMode("FollowPointsH", () -> new FollowPoints(new PointDir[]{new PointDir(0, 0), new PointDir(2, 0), new PointDir(1, 0), new PointDir(1, 1), new PointDir(2, 1), new PointDir(0, 1)})), + //new AutonomousMode("FollowPointsH", () -> new FollowPoints(new PointDir[]{new PointDir(0, 0), new PointDir(2, 0), new PointDir(1, 0), new PointDir(1, 1), new PointDir(2, 1), new PointDir(0, 1)})), new AutonomousMode("DoNothing", () -> new DoNothing()), }; } \ No newline at end of file diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index cc3dbb4b..462d31f4 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -112,6 +112,9 @@ public void run(Context context) { if(joystick0.getButtonPressed(1)) Robot.gyro.resetGyro(); + if(joystick0.getButtonPressed(11)) + Robot.drive.resetCurrentPosition(); + if(joystick1.getButtonPressed(1)) isCross = !isCross; diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 14f29128..1b16832c 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -24,8 +24,8 @@ public class FollowPoints extends Procedure { //Steps combine possible data types into one object for flexibility and ease-of-use purposes public static class Step { - Path path = Filesystem.getDeployDirectory().toPath().resolve("BLABLABLA.JSON"); - File file = path.toFile(); + //Path path = Filesystem.getDeployDirectory().toPath().resolve("BLABLABLA.JSON"); + //File file = path.toFile(); public PointDir wayPoint; public boolean criticalPoint; @@ -68,7 +68,10 @@ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedu //Default FollowPoints Constructor, Steps must be added here public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); - addStep(new PointDir(0,20, 30), false, null /* don't execute procedure */, false); + addStep(new PointDir(1,0, 0), false, null /* don't execute procedure */, false); + addStep(new PointDir(1,1, 0), false, null /* don't execute procedure */, false); + addStep(new PointDir(0,1, 0), false, null /* don't execute procedure */, false); + addStep(new PointDir(0,0, 0), false, null /* don't execute procedure */, false); addWaypoints(); } @@ -158,7 +161,7 @@ public void run(Context context) { int targetNum = 0; Point targetPoint = new Point(0.0, 0.0); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); - while (targetNum != pointList.length - 1 && !passedPoint(pointList[pointList.length - 1])) { + while (targetNum != pointList.length - 1 || !passedPoint(pointList[pointList.length - 1])) { lastPos = currentPos.clone(); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point @@ -179,7 +182,7 @@ public void run(Context context) { //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint)))); + Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), 0/*rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint))*/)); log("Current Position: " + currentPos.toString()); log("Target Point: " + targetPoint.toString()); log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint))).toString()); From c9fea671d71baa83507c133b7e6d4ed6d285b9e3 Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Tue, 7 Feb 2023 07:04:08 +0000 Subject: [PATCH 031/103] switch to java lite runtime for protobufs --- build.gradle | 20 ++++++++++++++++++- src/main/java/com/team766/logging/Logger.java | 5 +++-- 2 files changed, 22 insertions(+), 3 deletions(-) diff --git a/build.gradle b/build.gradle index ba753964..324a7c69 100644 --- a/build.gradle +++ b/build.gradle @@ -93,7 +93,7 @@ dependencies { testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2' // our files - implementation "com.google.protobuf:protobuf-java:${protobufVersion}" + implementation "com.google.protobuf:protobuf-javalite:${protobufVersion}" implementation files('deps/commons-math3-3.6.1.jar') implementation files('deps/gral-core-0.11.jar') @@ -154,6 +154,24 @@ protobuf { // Download from repositories artifact = "com.google.protobuf:protoc:${protobufVersion}" } + + + plugins { + javalite { + // The codegen for lite comes as a separate artifact + artifact = 'com.google.protobuf:protoc-gen-javalite:${protobufVersion}' + } + } + + generateProtoTasks { + all().configureEach { task -> + task.builtins { + java { + option "lite" + } + } + } + } } diff --git a/src/main/java/com/team766/logging/Logger.java b/src/main/java/com/team766/logging/Logger.java index 473dd5d4..99018c9f 100644 --- a/src/main/java/com/team766/logging/Logger.java +++ b/src/main/java/com/team766/logging/Logger.java @@ -100,8 +100,9 @@ public void logData(Severity severity, String format, Object... args) { } entry.setMessageStr(format); for (Object arg : args) { - SerializationUtils.valueToProto(arg, entry.addArgBuilder()); - } + var logValue = LogValue.newBuilder(); + SerializationUtils.valueToProto(arg, logValue); + entry.addArg(logValue.build()); } if (m_logWriter != null) { m_logWriter.logStoredFormat(entry); } From 12079b6a5459018ecd7d1a3206d50e79d9c4c843 Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Tue, 7 Feb 2023 07:25:07 +0000 Subject: [PATCH 032/103] accidentally deleted newline (?). fix. --- src/main/java/com/team766/logging/Logger.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/team766/logging/Logger.java b/src/main/java/com/team766/logging/Logger.java index 99018c9f..c08809a2 100644 --- a/src/main/java/com/team766/logging/Logger.java +++ b/src/main/java/com/team766/logging/Logger.java @@ -102,7 +102,8 @@ public void logData(Severity severity, String format, Object... args) { for (Object arg : args) { var logValue = LogValue.newBuilder(); SerializationUtils.valueToProto(arg, logValue); - entry.addArg(logValue.build()); } + entry.addArg(logValue.build()); + } if (m_logWriter != null) { m_logWriter.logStoredFormat(entry); } From 449c6145258d5f9a12ec6c66eb9058f15c18554c Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Wed, 8 Feb 2023 18:42:19 -0800 Subject: [PATCH 033/103] Fixed Robot spinning --- .../com/team766/robot/procedures/FollowPoints.java | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 1b16832c..df5d2744 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -182,7 +182,7 @@ public void run(Context context) { //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), 0/*rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint))*/)); + Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint)))); log("Current Position: " + currentPos.toString()); log("Target Point: " + targetPoint.toString()); log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint))).toString()); @@ -253,19 +253,19 @@ public static Point selectTargetPoint(int targetNum, PointDir currentPos, Point[ //Returns if the robot has passed a certain point public static boolean passedPoint(Point P) { - return currentPos.distance(P) > lastPos.distance(P); + return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2); } //Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point public static double rotationSpeed(double currentRot, double targetRot) { - double maxSpeed = 0.5; + double maxSpeed = 0.2; double angleDistanceForMaxSpeed = 45; currentRot = mod(currentRot, 360); targetRot = mod(targetRot, 360); - if (Math.abs(targetRot - currentRot) < Math.abs(targetRot + 360 - currentRot)) { + if (Math.abs(targetRot - currentRot) > Math.abs(targetRot + 360 - currentRot)) { targetRot += 360; } - if (Math.abs(targetRot - currentRot) < Math.abs(targetRot - 360 - currentRot)) { + if (Math.abs(targetRot - currentRot) > Math.abs(targetRot - 360 - currentRot)) { targetRot -= 360; } if (Math.abs(targetRot - currentRot) <= angleDistanceForMaxSpeed) { From e59c576cb716adbfe1cd633cc490d3cde1e8d917 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Wed, 8 Feb 2023 19:54:30 -0800 Subject: [PATCH 034/103] Made rotation fixes --- .../team766/robot/procedures/FollowPoints.java | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index df5d2744..59451bcc 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -68,10 +68,10 @@ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedu //Default FollowPoints Constructor, Steps must be added here public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); - addStep(new PointDir(1,0, 0), false, null /* don't execute procedure */, false); - addStep(new PointDir(1,1, 0), false, null /* don't execute procedure */, false); - addStep(new PointDir(0,1, 0), false, null /* don't execute procedure */, false); - addStep(new PointDir(0,0, 0), false, null /* don't execute procedure */, false); + addStep(new PointDir(2,0, 0), false, null /* don't execute procedure */, false); + addStep(new PointDir(2,2, 90), false, null /* don't execute procedure */, false); + addStep(new PointDir(0,2, 90), false, null /* don't execute procedure */, false); + addStep(new PointDir(0,0, 90), false, null /* don't execute procedure */, false); addWaypoints(); } @@ -182,10 +182,10 @@ public void run(Context context) { //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint)))); + Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading()))); log("Current Position: " + currentPos.toString()); log("Target Point: " + targetPoint.toString()); - log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getAngleDifference(targetPoint))).toString()); + log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())).toString()); context.yield(); } @@ -259,7 +259,7 @@ public static boolean passedPoint(Point P) { //Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point public static double rotationSpeed(double currentRot, double targetRot) { double maxSpeed = 0.2; - double angleDistanceForMaxSpeed = 45; + double angleDistanceForMaxSpeed = 180; currentRot = mod(currentRot, 360); targetRot = mod(targetRot, 360); if (Math.abs(targetRot - currentRot) > Math.abs(targetRot + 360 - currentRot)) { @@ -269,7 +269,7 @@ public static double rotationSpeed(double currentRot, double targetRot) { targetRot -= 360; } if (Math.abs(targetRot - currentRot) <= angleDistanceForMaxSpeed) { - return (currentRot - targetRot) / angleDistanceForMaxSpeed * maxSpeed; + return Math.pow((currentRot - targetRot) / angleDistanceForMaxSpeed, 3) * maxSpeed; } return maxSpeed * Math.signum(currentRot - targetRot); } From a19ad3b8d752e6263069e006289cd907638b5a01 Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Thu, 9 Feb 2023 00:19:21 -0800 Subject: [PATCH 035/103] switch CI action to run on pushes to *main* --- .github/workflows/main.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index ab5ab753..26ac56d0 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -6,7 +6,7 @@ name: CI on: # Triggers the workflow on push or pull request events but only for the master branch push: - branches: [ master ] + branches: [ main ] pull_request: # Allows you to run this workflow manually from the Actions tab From 1f2bc7a832394f7596670b720d283ce4e073a4f9 Mon Sep 17 00:00:00 2001 From: Ryan Cahoon Date: Tue, 7 Feb 2023 07:24:39 -0800 Subject: [PATCH 036/103] Add JVM heap limits for RoboRIOv1 to prevent out-of-memory crashes --- build.gradle | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/build.gradle b/build.gradle index 324a7c69..dfa09fbc 100644 --- a/build.gradle +++ b/build.gradle @@ -40,6 +40,31 @@ deploy { // getTargetTypeClass is a shortcut to get the class type using a string frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + // This supposedly makes Java save a heap dump on OutOfMemoryError, but + // unfortunately it doesn't seem to work when the error is raised due to a + // native allocation. https://stackoverflow.com/q/27166267 + jvmArgs.add("-XX:+HeapDumpOnOutOfMemoryError") + jvmArgs.add("-XX:HeapDumpPath=/home/lvuser") + // This limits heap memory as a percentage (0-100) of physical memory size. + // `MinRAMPercentage` is a misleading name, which suggests that it is used to + // configure minimum heap size. Rather, the `-XX:MinRAMPercentage` JVM argument + // will be used to compute the maximum Java heap size only if the overall memory + // size in the physical machine is less than 250MB (approximately). Say suppose + // you are configuring `-XX:MinRAMPercentage=50` and overall physical memory is + // 100MB; then your java application's max heap size will be set to 50MB + // (i.e., 50% of 100MB). `-XX:MaxRAMPercentage` has the same effect and applies + // only when physical memory is larger than 250MB. + // Effectively, this limit should apply to RoboRIO V1 (~240MB of RAM available), + // but not RoboRIO V2 (~500MB of RAM available). + // Without this, we get errors like + // OpenJDK Client VM warning: INFO: os::commit_memory(0xb3800000, 1048576, 0) + // failed; error='Not enough space' (errno=12) + // # There is insufficient memory for the Java Runtime Environment to continue. + // # Native memory allocation (mmap) failed to map 1048576 bytes for committing + // reserved memory. + jvmArgs.add("-XX:MinRAMPercentage=15") + // This makes the JVM print the heap memory size on startup. + jvmArgs.add("-XshowSettings:vm") } // Static files artifact From 5928096189ae1285b279b4b21b621e88bdea8837 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Fri, 10 Feb 2023 20:16:03 -0800 Subject: [PATCH 037/103] Fixed Rotation in FollowPoints --- .../robot/procedures/FollowPoints.java | 87 +++++++++++-------- 1 file changed, 53 insertions(+), 34 deletions(-) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 59451bcc..4b172196 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -4,6 +4,7 @@ import com.team766.framework.Context; import com.team766.framework.LaunchedContext; import com.team766.robot.Robot; +import com.team766.library.RateLimiter; import com.team766.library.ValueProvider; import com.team766.hal.RobotProvider; import com.team766.odometry.Point; @@ -43,13 +44,19 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private static PointDir currentPos = new PointDir(0.0, 0.0, 0.0); private static PointDir lastPos = new PointDir(0.0, 0.0, 0.0); + private PointDir[] pointList; private Procedure[] proceduresAtPoints; private boolean[] criticalPointList; private boolean[] stopRobotList; + + private int targetNum = 0; + private RateLimiter followLimiter = new RateLimiter(0.05); + //Radius defines the radius of the circle around the robot private static double radius = ConfigFileReader.getInstance().getDouble("trajectory.radius").get(); private static double speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); + private static PointDir driveSettings = new PointDir(0, 0, 0); /*public FollowPoints() { parsePointList(); @@ -68,10 +75,8 @@ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedu //Default FollowPoints Constructor, Steps must be added here public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); - addStep(new PointDir(2,0, 0), false, null /* don't execute procedure */, false); - addStep(new PointDir(2,2, 90), false, null /* don't execute procedure */, false); - addStep(new PointDir(0,2, 90), false, null /* don't execute procedure */, false); - addStep(new PointDir(0,0, 90), false, null /* don't execute procedure */, false); + addStep(new PointDir(4,0, 90), true, null /* don't execute procedure */, false); + addStep(new PointDir(0,0, 0), false, new DoNothing(), false); addWaypoints(); } @@ -94,6 +99,8 @@ private void addWaypoints() { proceduresAtPoints[i] = new DoNothing(); } criticalPointList[i] = steps.get(i).criticalPoint; + log(Boolean.toString(steps.get(i).criticalPoint)); + stopRobotList[i] = steps.get(i).stopRobot; } } @@ -153,41 +160,46 @@ public void run(Context context) { //If we need to make this method field-oriented, just remove this line Robot.drive.resetCurrentPosition(); Robot.gyro.resetGyro(); + targetNum = 0; for (int i = 0; i < pointList.length; i++) { - log(pointList[i].toString()); + log(Boolean.toString(criticalPointList[i])); } if (pointList.length > 0) { - int targetNum = 0; Point targetPoint = new Point(0.0, 0.0); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); while (targetNum != pointList.length - 1 || !passedPoint(pointList[pointList.length - 1])) { - lastPos = currentPos.clone(); - currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); - //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point - //Otherwise, it uses the checkIntersection() method to follow the circle - if (criticalPointList[targetNum]? passedPoint(pointList[targetNum]) : checkIntersection(targetNum, currentPos, pointList, radius)) { - if (proceduresAtPoints.length < targetNum) { - if (stopRobotList[targetNum]) { - context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); - } else { - context.startAsync(proceduresAtPoints[targetNum]); + if (followLimiter.next()) { + lastPos = currentPos.clone(); + currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); + //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point + //Otherwise, it uses the checkIntersection() method to follow the circle + if (criticalPointList[targetNum]? passedPoint(pointList[targetNum]) : checkIntersection(targetNum, currentPos, pointList, radius)) { + if (proceduresAtPoints.length < targetNum) { + if (stopRobotList[targetNum]) { + context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); + } else { + context.startAsync(proceduresAtPoints[targetNum]); + } } + targetNum++; + log("Going to Next Point!"); } - targetNum++; - log("Going to Next Point!"); - } - targetPoint = selectTargetPoint(targetNum, currentPos, pointList, radius); - //double diff = currentPos.getAngleDifference(targetPoint); - //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); - - Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - Robot.drive.swerveDrive(new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading()))); - log("Current Position: " + currentPos.toString()); - log("Target Point: " + targetPoint.toString()); - log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())).toString()); + targetPoint = selectTargetPoint(targetNum, currentPos, pointList, radius); + //double diff = currentPos.getAngleDifference(targetPoint); + //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); + + Robot.drive.setGyro(Robot.gyro.getGyroYaw()); + driveSettings.set(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); + Robot.drive.swerveDrive(driveSettings); + log("Current Position: " + currentPos.toString()); + log("Target Point: " + targetPoint.toString()); + log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())).toString()); - context.yield(); + context.yield(); + } else { + updateRotation(); + } } Robot.drive.drive2D(0, 0); log("Finished method!"); @@ -196,6 +208,12 @@ public void run(Context context) { } } + public void updateRotation() { + Robot.drive.setGyro(Robot.gyro.getGyroYaw()); + driveSettings.setHeading(rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); + Robot.drive.swerveDrive(driveSettings); + } + //Returns whether the circle around the robot intersects the line connecting the two next points. public static boolean checkIntersection(int targetNum, PointDir currentPos, Point[] pointList, double radius) { double a; @@ -252,14 +270,15 @@ public static Point selectTargetPoint(int targetNum, PointDir currentPos, Point[ } //Returns if the robot has passed a certain point - public static boolean passedPoint(Point P) { + public boolean passedPoint(Point P) { + log(currentPos + " " + P + " " + currentPos.distance(P) + " " + ((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2) ? " true" : " false")); return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2); } //Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point - public static double rotationSpeed(double currentRot, double targetRot) { + public double rotationSpeed(double currentRot, double targetRot) { double maxSpeed = 0.2; - double angleDistanceForMaxSpeed = 180; + double angleDistanceForMaxSpeed = 90; currentRot = mod(currentRot, 360); targetRot = mod(targetRot, 360); if (Math.abs(targetRot - currentRot) > Math.abs(targetRot + 360 - currentRot)) { @@ -269,9 +288,9 @@ public static double rotationSpeed(double currentRot, double targetRot) { targetRot -= 360; } if (Math.abs(targetRot - currentRot) <= angleDistanceForMaxSpeed) { - return Math.pow((currentRot - targetRot) / angleDistanceForMaxSpeed, 3) * maxSpeed; + return -(currentRot - targetRot) / angleDistanceForMaxSpeed * maxSpeed; } - return maxSpeed * Math.signum(currentRot - targetRot); + return maxSpeed * -Math.signum(currentRot - targetRot); } public static double mod(double d1, double d2) { From f2d4626fd28f63496c9055e729759d7367f59480 Mon Sep 17 00:00:00 2001 From: dejabot Date: Fri, 10 Feb 2023 22:47:15 -0800 Subject: [PATCH 038/103] update to WPILib 2023.3.2 --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index dfa09fbc..25c60096 100644 --- a/build.gradle +++ b/build.gradle @@ -2,7 +2,7 @@ plugins { id "java" id 'java-library' id 'maven-publish' - id "edu.wpi.first.GradleRIO" version "2023.1.1" + id "edu.wpi.first.GradleRIO" version "2023.3.2" id 'com.google.protobuf' version '0.8.19' } From 194c652fb6d8af79902d7de13abf8c5aa709ba3b Mon Sep 17 00:00:00 2001 From: Ryan Cahoon Date: Sat, 11 Feb 2023 00:44:47 -0800 Subject: [PATCH 039/103] Add MaroonSim model for the two-joint arm (#10) Simulation model of the 2023 robot's arm. Simulation is implemented using physics-based equations of motion, so should give us a higher-fidelity model than we could get using Unity/PhysX. --- .vscode/launch.json | 7 + simConfig.txt | 8 + .../com/team766/hal/simulator/RobotMain.java | 2 +- .../team766/hal/simulator/VrConnector.java | 6 +- .../team766/simulator/ElectricalSystem.java | 32 +- .../java/com/team766/simulator/Metrics.java | 107 +++++++ .../com/team766/simulator/Parameters.java | 6 +- .../team766/simulator/PneumaticsSystem.java | 6 +- .../java/com/team766/simulator/Program.java | 2 +- .../java/com/team766/simulator/Simulator.java | 115 ++++--- .../simulator/elements/AirCompressor.java | 12 +- .../simulator/elements/AirReservoir.java | 2 +- .../elements/CanMotorController.java | 8 + .../team766/simulator/elements/DCMotor.java | 41 ++- .../DoubleActingPneumaticCylinder.java | 4 +- .../elements/ElectricalResistance.java | 9 +- .../com/team766/simulator/elements/Gears.java | 4 +- .../simulator/elements/MotorController.java | 11 +- .../SingleActingPneumaticCylinder.java | 4 +- .../com/team766/simulator/elements/Wheel.java | 4 +- .../interfaces/ElectricalDevice.java | 4 +- .../interfaces/MechanicalAngularDevice.java | 2 +- .../interfaces/MechanicalDevice.java | 2 +- .../simulator/interfaces/PneumaticDevice.java | 2 +- .../mechanisms/DoubleJointedArm.java | 295 ++++++++++++++++++ .../simulator/mechanisms/WestCoastDrive.java | 22 +- .../team766/simulator/ui/ArmTrajectory.java | 103 ++++++ .../com/team766/simulator/ui/Metrics.java | 160 ---------- .../com/team766/simulator/ui/MetricsPlot.java | 182 +++++++++++ .../simulator/ui/PlaybackControls.java | 70 +++++ .../team766/simulator/ui/PlaybackTimer.java | 138 ++++++++ .../com/team766/simulator/ui/PlotUtils.java | 72 +++++ .../com/team766/simulator/ui/Trajectory.java | 158 ++++------ .../com/team766/simulator/ui/UIFrame.java | 71 +++++ .../com/team766/simulator/MetricsTest.java | 20 ++ 35 files changed, 1332 insertions(+), 359 deletions(-) create mode 100644 src/main/java/com/team766/simulator/Metrics.java create mode 100644 src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java create mode 100644 src/main/java/com/team766/simulator/ui/ArmTrajectory.java delete mode 100644 src/main/java/com/team766/simulator/ui/Metrics.java create mode 100644 src/main/java/com/team766/simulator/ui/MetricsPlot.java create mode 100644 src/main/java/com/team766/simulator/ui/PlaybackControls.java create mode 100644 src/main/java/com/team766/simulator/ui/PlaybackTimer.java create mode 100644 src/main/java/com/team766/simulator/ui/PlotUtils.java create mode 100644 src/main/java/com/team766/simulator/ui/UIFrame.java create mode 100644 src/test/java/com/team766/simulator/MetricsTest.java diff --git a/.vscode/launch.json b/.vscode/launch.json index 8fbfc758..158a5295 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -23,6 +23,13 @@ "request": "launch", "mainClass": "com.team766.hal.simulator.RobotMain", "args": ["-vr_connector"] + }, + { + "type": "java", + "name": "Start Maroon simulation", + "request": "launch", + "mainClass": "com.team766.hal.simulator.RobotMain", + "args": ["-maroon_sim"] } ] } diff --git a/simConfig.txt b/simConfig.txt index d5986bb4..90952046 100644 --- a/simConfig.txt +++ b/simConfig.txt @@ -98,5 +98,13 @@ "proximitySensor": {"port": 2}, "left": {"deviceId": 6}, "right": {"deviceId": 4} + }, + "arm": { + "j1Motor": { + "deviceId": 98 + }, + "j2Motor": { + "deviceId": 99 + } } } \ No newline at end of file diff --git a/src/main/java/com/team766/hal/simulator/RobotMain.java b/src/main/java/com/team766/hal/simulator/RobotMain.java index 1a64e9e3..5437e88e 100755 --- a/src/main/java/com/team766/hal/simulator/RobotMain.java +++ b/src/main/java/com/team766/hal/simulator/RobotMain.java @@ -36,7 +36,7 @@ public RobotMain(Mode mode) { ProgramInterface.RobotMode prevRobotMode = null; @Override - public void step() { + public void step(double dt) { switch (ProgramInterface.robotMode) { case DISABLED: if (prevRobotMode != ProgramInterface.RobotMode.DISABLED) { diff --git a/src/main/java/com/team766/hal/simulator/VrConnector.java b/src/main/java/com/team766/hal/simulator/VrConnector.java index b0e1a054..d8727f85 100644 --- a/src/main/java/com/team766/hal/simulator/VrConnector.java +++ b/src/main/java/com/team766/hal/simulator/VrConnector.java @@ -308,6 +308,7 @@ private boolean process() throws IOException { } public void run() { + double prevSimTime = 0; while (true) { boolean newData = false; try { @@ -342,9 +343,12 @@ public void run() { } else { continue; } + prevSimTime = ProgramInterface.simulationTime; } if (ProgramInterface.program != null) { - ProgramInterface.program.step(); + final double time = ProgramInterface.simulationTime; + ProgramInterface.program.step(time - prevSimTime); + prevSimTime = time; } } } diff --git a/src/main/java/com/team766/simulator/ElectricalSystem.java b/src/main/java/com/team766/simulator/ElectricalSystem.java index 398d497b..5bfb904f 100644 --- a/src/main/java/com/team766/simulator/ElectricalSystem.java +++ b/src/main/java/com/team766/simulator/ElectricalSystem.java @@ -1,14 +1,24 @@ package com.team766.simulator; import java.util.ArrayList; - +import java.util.LinkedHashMap; import com.team766.simulator.interfaces.ElectricalDevice; public class ElectricalSystem { private double nominalVoltage = Parameters.BATTERY_VOLTAGE; private double primaryResistance = Parameters.PRIMARY_ELECTRICAL_RESISTANCE; + + public class BranchInfo { + public final ElectricalDevice device; + public ElectricalDevice.Output flow; + + public BranchInfo(ElectricalDevice device) { + this.device = device; + this.flow = new ElectricalDevice.Output(0); + } + } - private ArrayList branchCircuits = new ArrayList(); + private ArrayList branchCircuits = new ArrayList(); private ElectricalDevice.Input systemState; @@ -17,14 +27,14 @@ public ElectricalSystem() { } public void addDevice(ElectricalDevice device) { - branchCircuits.add(device); + branchCircuits.add(new BranchInfo(device)); } - public void step() { + public void step(double dt) { double current = 0.0; - for (ElectricalDevice device : branchCircuits) { - ElectricalDevice.Output deviceState = device.step(systemState); - current += deviceState.current; + for (BranchInfo branch : branchCircuits) { + branch.flow = branch.device.step(systemState, dt); + current += branch.flow.current; } systemState = new ElectricalDevice.Input(Math.max(0, nominalVoltage - primaryResistance * current)); } @@ -32,4 +42,12 @@ public void step() { public double getSystemVoltage() { return systemState.voltage; } + + public LinkedHashMap getBranchCurrents() { + var currents = new LinkedHashMap(); + for (BranchInfo branch : branchCircuits) { + currents.put(branch.device.name(), branch.flow.current); + } + return currents; + } } diff --git a/src/main/java/com/team766/simulator/Metrics.java b/src/main/java/com/team766/simulator/Metrics.java new file mode 100644 index 00000000..82e82cd8 --- /dev/null +++ b/src/main/java/com/team766/simulator/Metrics.java @@ -0,0 +1,107 @@ +package com.team766.simulator; + +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; + +/** + * Stores a set of parallel time series (i.e. each series has data at the same points in time). + */ +public class Metrics { + /** + * This is a handle to a particular time series. + */ + public class Series { + private final int index; + + private Series(int index) { + this.index = index; + } + + private void check(Metrics m) { + if (m != Metrics.this) { + throw new IllegalArgumentException(); + } + } + } + + /** + * This is a view on a point in time, with the data for all of the time series at that point. + */ + public class Point { + private final Double[] data; + + private Point(Double[] data) { + this.data = data; + } + + /** + * Set the value in a particular series at this point in time. + */ + public Point set(Series series, double value) { + series.check(Metrics.this); + if (series.index >= 0) { + data[series.index] = value; + } + return this; + } + } + + // Each element of this list should be an array of the same length. + // In each element, index 0 is time and subsequent elements are values. + private ArrayList metrics = new ArrayList<>(); + // The labels for the series. + private ArrayList seriesLabels = new ArrayList<>(); + + /** + * Add a new data series. + * + * This can only be called before data is added. + * + * @param name The label for the series. + * @param enabled If false, data from this series will be ignored. This allows for an easy, + * centralized way of selecting which data should be processed/visualized. + * @return A handle to this series, which should be passed when adding data via a Point. + * @throws IllegalStateException if called after data has been added (via {@link #add()}) + */ + public Series addSeries(String name, boolean enabled) { + if (metrics.size() != 0) { + throw new IllegalStateException(); + } + if (!enabled) { + return new Series(-1); + } + seriesLabels.add(name); + return new Series(seriesLabels.size()); + } + public Series addSeries(String name) { + return addSeries(name, true); + } + + /** + * Add a new data point. + * + * Data points should be added in order of increasing time. + */ + public Point add(double time) { + var data = new Double[seriesLabels.size() + 1]; + data[0] = time; + metrics.add(data); + return new Point(data); + } + + /** + * Remove all data points (Series are not removed) + */ + public void clear() { + metrics.clear(); + } + + public List getMetrics() { + return Collections.unmodifiableList(metrics); + } + + public List getLabels() { + return Collections.unmodifiableList(seriesLabels); + } +} diff --git a/src/main/java/com/team766/simulator/Parameters.java b/src/main/java/com/team766/simulator/Parameters.java index 0a226972..c6655f66 100644 --- a/src/main/java/com/team766/simulator/Parameters.java +++ b/src/main/java/com/team766/simulator/Parameters.java @@ -1,8 +1,10 @@ package com.team766.simulator; public class Parameters { - public static final double TIME_STEP = 0.001; // seconds - public static final double DURATION = 5.0; // seconds + public static final double TIME_STEP = 0.0001; // seconds + public static final double DURATION = 10.0; // seconds + + public static final double LOGGING_PERIOD = 0.005; // seconds // Robot mode to run in the simulator public static final ProgramInterface.RobotMode INITIAL_ROBOT_MODE = ProgramInterface.RobotMode.AUTON; diff --git a/src/main/java/com/team766/simulator/PneumaticsSystem.java b/src/main/java/com/team766/simulator/PneumaticsSystem.java index 768b8aba..5e5a8278 100644 --- a/src/main/java/com/team766/simulator/PneumaticsSystem.java +++ b/src/main/java/com/team766/simulator/PneumaticsSystem.java @@ -24,14 +24,14 @@ public void addDevice(PneumaticDevice device, double regulatedPressure) { circuit.regulatedPressure = regulatedPressure; branchCircuits.add(circuit); } - - public void step() { + + public void step(double dt) { double flowVolume = 0.0; double systemVolume = 0.0; for (BranchCircuit circuit : branchCircuits) { double devicePressure = Math.min(circuit.regulatedPressure, systemPressure); PneumaticDevice.Input inputState = new PneumaticDevice.Input(devicePressure); - PneumaticDevice.Output deviceState = circuit.device.step(inputState); + PneumaticDevice.Output deviceState = circuit.device.step(inputState, dt); // TODO: implement relieving pressure regulator (make sure device pressure doesn't exceed // circuit.regulatedPressure, even when including flow volume) flowVolume += deviceState.flowVolume; diff --git a/src/main/java/com/team766/simulator/Program.java b/src/main/java/com/team766/simulator/Program.java index c83d2cb0..62eb21ff 100644 --- a/src/main/java/com/team766/simulator/Program.java +++ b/src/main/java/com/team766/simulator/Program.java @@ -1,7 +1,7 @@ package com.team766.simulator; public interface Program { - public void step(); + public void step(double dt); public void reset(); } diff --git a/src/main/java/com/team766/simulator/Simulator.java b/src/main/java/com/team766/simulator/Simulator.java index 792ae667..71e09e26 100644 --- a/src/main/java/com/team766/simulator/Simulator.java +++ b/src/main/java/com/team766/simulator/Simulator.java @@ -1,82 +1,127 @@ package com.team766.simulator; import java.util.ArrayList; - +import java.util.HashMap; import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; import org.apache.commons.math3.geometry.euclidean.threed.RotationOrder; -import com.team766.simulator.elements.AirCompressor; -import com.team766.simulator.elements.AirReservoir; -import com.team766.simulator.mechanisms.WestCoastDrive; -import com.team766.simulator.ui.Metrics; -import com.team766.simulator.ui.Trajectory; +import com.team766.simulator.elements.*; +import com.team766.simulator.mechanisms.*; +import com.team766.simulator.ui.*; public class Simulator implements Runnable { private ElectricalSystem electricalSystem = new ElectricalSystem(); private PneumaticsSystem pneumaticsSystem = new PneumaticsSystem(); private WestCoastDrive drive = new WestCoastDrive(electricalSystem); private AirCompressor compressor = new AirCompressor(); + private DoubleJointedArm arm = new DoubleJointedArm(electricalSystem); private double time; - private ArrayList metrics = new ArrayList(); - private ArrayList trajectory = new ArrayList(); - + private double nextLogTime; + + private final Metrics metrics = new Metrics(); + private final Metrics.Series xPositionSeries = metrics.addSeries("X Position (m)", false); + private final Metrics.Series yPositionSeries = metrics.addSeries("Y Position (m)", false); + private final Metrics.Series rotationSeries = metrics.addSeries("Rotation (deg)", false); + private final Metrics.Series velocitySeries = metrics.addSeries("Velocity (m/s)", false); + private final Metrics.Series accelerationSeries = metrics.addSeries("Acceleration (m/s^2)", false); + private final Metrics.Series armAngle1Series = metrics.addSeries("Arm angle 1"); + private final Metrics.Series armAngle2Series = metrics.addSeries("Arm angle 2"); + private final Metrics.Series armVelocity1Series = metrics.addSeries("Arm velocity 1"); + private final Metrics.Series armVelocity2Series = metrics.addSeries("Arm velocity 2"); + private final Metrics.Series systemVoltageSeries = metrics.addSeries("System Voltage (V)", false); + private final Metrics.Series systemPressureSeries = metrics.addSeries("System Pressure (PSI)", false); + private final HashMap branchCurrentSeries = new HashMap<>(); + + private ArrayList driveTrajectory = new ArrayList(); + private ArrayList armTrajectory = new ArrayList(); + public Simulator() { - electricalSystem.addDevice(compressor); + // NOTE(rcahoon, 2023-02-09): Disabled the compressor so it won't affect the battery voltage + // available to the arm's motors. This should be re-enabled if we want to simulate + // pneumatics again. + //electricalSystem.addDevice(compressor); pneumaticsSystem.addDevice(compressor, 120 * PneumaticsSystem.PSI_TO_PASCALS); pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL + + for (String branchName : electricalSystem.getBranchCurrents().keySet()) { + branchCurrentSeries.put(branchName, metrics.addSeries(branchName, false)); + } } public void step() { - time += Parameters.TIME_STEP; + double dt = Parameters.TIME_STEP; + time += dt; ProgramInterface.simulationTime = time; - electricalSystem.step(); - pneumaticsSystem.step(); - drive.step(); + electricalSystem.step(dt); + pneumaticsSystem.step(dt); + drive.step(dt); + arm.step(dt); if (ProgramInterface.program != null) { - ProgramInterface.program.step(); + ProgramInterface.program.step(dt); } - metrics.add(new Double[] { + if (nextLogTime <= time) { + nextLogTime += Parameters.LOGGING_PERIOD; + + var metricsPoint = metrics.add(time); + metricsPoint.set(xPositionSeries, drive.getPosition().getX()); + metricsPoint.set(yPositionSeries, drive.getPosition().getY()); + metricsPoint.set(rotationSeries, Math.toDegrees(drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2])); + metricsPoint.set(velocitySeries, drive.getLinearVelocity().getX()); + metricsPoint.set(accelerationSeries, drive.getLinearAcceleration().getX()); + metricsPoint.set(armAngle1Series, arm.getJ1Angle()); + metricsPoint.set(armAngle2Series, arm.getJ2Angle()); + metricsPoint.set(armVelocity1Series, arm.getJ1Velocity()); + metricsPoint.set(armVelocity2Series, arm.getJ2Velocity()); + metricsPoint.set(systemVoltageSeries, electricalSystem.getSystemVoltage()); + metricsPoint.set(systemPressureSeries, pneumaticsSystem.getSystemPressure() / PneumaticsSystem.PSI_TO_PASCALS); + for (var branch : electricalSystem.getBranchCurrents().entrySet()) { + metricsPoint.set(branchCurrentSeries.get(branch.getKey()), branch.getValue()); + } + + driveTrajectory.add(new Double[] { time, - drive.getPosition().getX(), - drive.getPosition().getY(), - Math.toDegrees(drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2]), - drive.getLinearVelocity().getX(), - drive.getLinearAcceleration().getX(), - electricalSystem.getSystemVoltage(), - pneumaticsSystem.getSystemPressure() / PneumaticsSystem.PSI_TO_PASCALS, - }); - trajectory.add(new Double[] { drive.getPosition().getX(), drive.getPosition().getY(), drive.getRotation().getAngles(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR)[2], drive.getLinearVelocity().getX(), drive.getLinearVelocity().getY(), }); + + armTrajectory.add(new Double[] { + time, + arm.getJ1Position().get(0, 0), + arm.getJ1Position().get(1, 0), + arm.getJ2Position().get(0, 0), + arm.getJ2Position().get(1, 0) + }); + } } public void run() { metrics.clear(); time = 0.0; + nextLogTime = 0.0; while (time <= Parameters.DURATION) { step(); if (Math.abs(time - 3.0) < Parameters.TIME_STEP) { pneumaticsSystem.ventPressure(); } } - Trajectory.makePlotFrame(trajectory); - Metrics.makePlotFrame(metrics, new String[] { - "X Position (m)", - "Y Position (m)", - "Rotation (deg)", - "Velocity (m/s)", - "Acceleration (m/s^2)", - "System Voltage (V)", - "System Pressure (PSI)", - }); + + var playbackTimer = new PlaybackTimer(time); + + // var trajectoryPanel = new Trajectory(driveTrajectory, playbackTimer); + // new UIFrame("Trajectory", trajectoryPanel); + + var armTrajectoryPanel = new ArmTrajectory(armTrajectory, playbackTimer); + new UIFrame("ArmTrajectory", armTrajectoryPanel); + + var metricsPanel = new MetricsPlot(metrics, playbackTimer); + new UIFrame("Metrics", metricsPanel); } } diff --git a/src/main/java/com/team766/simulator/elements/AirCompressor.java b/src/main/java/com/team766/simulator/elements/AirCompressor.java index febca8b3..daf7ea55 100644 --- a/src/main/java/com/team766/simulator/elements/AirCompressor.java +++ b/src/main/java/com/team766/simulator/elements/AirCompressor.java @@ -5,7 +5,6 @@ import org.apache.commons.math3.analysis.interpolation.LinearInterpolator; import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction; -import com.team766.simulator.Parameters; import com.team766.simulator.PneumaticsSystem; import com.team766.simulator.interfaces.ElectricalDevice; import com.team766.simulator.interfaces.PneumaticDevice; @@ -34,7 +33,7 @@ public void setIsOn(boolean on) { } @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(ElectricalDevice.Input input, double dt) { electricalState = input; if (isOn) { double nominalCurrent = currentFunction.value(pneumaticState.pressure); @@ -46,11 +45,16 @@ public ElectricalDevice.Output step(ElectricalDevice.Input input) { } @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(PneumaticDevice.Input input, double dt) { pneumaticState = input; double nominalFlowRate = flowRateFunction.value(pneumaticState.pressure); double adjustedFlowRate = nominalFlowRate * electricalState.voltage / NOMINAL_VOLTAGE; - double flowVolume = adjustedFlowRate * Parameters.TIME_STEP; + double flowVolume = adjustedFlowRate * dt; return new PneumaticDevice.Output(flowVolume, 0); } + + @Override + public String name() { + return "AirCompressor"; + } } diff --git a/src/main/java/com/team766/simulator/elements/AirReservoir.java b/src/main/java/com/team766/simulator/elements/AirReservoir.java index 0faf6870..f88e7539 100644 --- a/src/main/java/com/team766/simulator/elements/AirReservoir.java +++ b/src/main/java/com/team766/simulator/elements/AirReservoir.java @@ -11,7 +11,7 @@ public AirReservoir(double volume) { } @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(PneumaticDevice.Input input, double dt) { return new PneumaticDevice.Output(0, volume); } } diff --git a/src/main/java/com/team766/simulator/elements/CanMotorController.java b/src/main/java/com/team766/simulator/elements/CanMotorController.java index 685e8ca1..fe6503dc 100644 --- a/src/main/java/com/team766/simulator/elements/CanMotorController.java +++ b/src/main/java/com/team766/simulator/elements/CanMotorController.java @@ -18,4 +18,12 @@ protected double getCommand() { return ProgramInterface.canMotorControllerChannels[address].command.output; } + public void setSensorPosition(double position) { + ProgramInterface.canMotorControllerChannels[address].status.sensorPosition = position; + } + + public void setSensorVelocity(double velocity) { + ProgramInterface.canMotorControllerChannels[address].status.sensorVelocity = velocity; + } + } diff --git a/src/main/java/com/team766/simulator/elements/DCMotor.java b/src/main/java/com/team766/simulator/elements/DCMotor.java index 5cb95ba5..8c257bb9 100644 --- a/src/main/java/com/team766/simulator/elements/DCMotor.java +++ b/src/main/java/com/team766/simulator/elements/DCMotor.java @@ -7,11 +7,21 @@ public class DCMotor implements ElectricalDevice, MechanicalAngularDevice { // TODO: Add rotor inertia // TODO: Add thermal effects - public static DCMotor makeCIM() { - return new DCMotor(46.513, 0.018397, 0.091603053435115); + // Motor data from https://motors.vex.com/ + public static DCMotor makeCIM(String name) { + return new DCMotor(name, 12, 5330, 2.7, 2.41, 131); } - public static DCMotor make775Pro() { - return new DCMotor(163.450, 0.0052985, 0.08955223880597); + public static DCMotor make775Pro(String name) { + return new DCMotor(name, 12, 18730, 0.7, 0.71, 134); + } + public static DCMotor makeFalcon500(String name) { + return new DCMotor(name, 12, 6380, 1.5, 4.69, 257); + } + public static DCMotor makeNeo(String name) { + return new DCMotor(name, 12, 5880, 1.3, 3.36, 166); + } + public static DCMotor makeNeo550(String name) { + return new DCMotor(name, 12, 11710, 1.1, 1.08, 111); } // Motor velocity constant in radian/second/volt @@ -28,22 +38,31 @@ public static DCMotor make775Pro() { private ElectricalDevice.Output electricalState = new ElectricalDevice.Output(0); private MechanicalAngularDevice.Input mechanicalState = new MechanicalAngularDevice.Input(0); - public DCMotor(double kV, double kT, double motorResistance) { - this.kV = kV; - this.kT = kT; - this.motorResistance = motorResistance; + private final String m_name; + + public DCMotor(String name, double referenceVoltage, double freeSpeedRpm, double freeCurrentAmps, double stallTorqueNewtonMeters, double stallCurrentAmps) { + m_name = name; + + this.motorResistance = referenceVoltage / stallCurrentAmps; + this.kV = freeSpeedRpm / 60.0 * 2 * Math.PI / (referenceVoltage - motorResistance * freeCurrentAmps); + this.kT = stallTorqueNewtonMeters / stallCurrentAmps; } @Override - public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { - mechanicalState = new MechanicalAngularDevice.Input(input); + public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input, double dt) { + mechanicalState = input; return new MechanicalAngularDevice.Output(kT * electricalState.current); } @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(ElectricalDevice.Input input, double dt) { electricalState = new ElectricalDevice.Output((input.voltage - mechanicalState.angularVelocity / kV) / motorResistance); return electricalState; } + + @Override + public String name() { + return m_name; + } } diff --git a/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java index bf6295c0..5165d8be 100644 --- a/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java +++ b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java @@ -27,7 +27,7 @@ public void setExtended(boolean state) { } @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(PneumaticDevice.Input input, double dt) { pneumaticState = input; PneumaticDevice.Output output; double deviceVolume = boreArea() * stroke; @@ -41,7 +41,7 @@ public PneumaticDevice.Output step(PneumaticDevice.Input input) { } @Override - public MechanicalDevice.Output step(MechanicalDevice.Input input) { + public MechanicalDevice.Output step(MechanicalDevice.Input input, double dt) { Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); return new MechanicalDevice.Output(direction.scalarMultiply(boreArea() * pneumaticState.pressure)); } diff --git a/src/main/java/com/team766/simulator/elements/ElectricalResistance.java b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java index c4d3a621..e4711db8 100644 --- a/src/main/java/com/team766/simulator/elements/ElectricalResistance.java +++ b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java @@ -27,9 +27,14 @@ public ElectricalResistance(double resistance, ElectricalDevice downstream) { } @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(ElectricalDevice.Input input, double dt) { ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage - resistance * state.current); - state = downstream.step(downstreamInput); + state = downstream.step(downstreamInput, dt); return state; } + + @Override + public String name() { + return downstream.name() + "+resistance"; + } } diff --git a/src/main/java/com/team766/simulator/elements/Gears.java b/src/main/java/com/team766/simulator/elements/Gears.java index 220b00dc..e1c8b9dd 100644 --- a/src/main/java/com/team766/simulator/elements/Gears.java +++ b/src/main/java/com/team766/simulator/elements/Gears.java @@ -17,10 +17,10 @@ public Gears(double torqueRatio, MechanicalAngularDevice upstream) { } @Override - public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input, double dt) { MechanicalAngularDevice.Input upstreamInput = new MechanicalAngularDevice.Input(input.angularVelocity * torqueRatio); - MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); + MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput, dt); return new MechanicalAngularDevice.Output(upstreamOutput.torque * torqueRatio); } } diff --git a/src/main/java/com/team766/simulator/elements/MotorController.java b/src/main/java/com/team766/simulator/elements/MotorController.java index d837e20a..8afd440c 100644 --- a/src/main/java/com/team766/simulator/elements/MotorController.java +++ b/src/main/java/com/team766/simulator/elements/MotorController.java @@ -13,10 +13,15 @@ public MotorController(ElectricalDevice downstream) { protected abstract double getCommand(); @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(ElectricalDevice.Input input, double dt) { double command = getCommand(); ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage * command); - ElectricalDevice.Output downstreamOutput = downstream.step(downstreamInput); - return new Output(downstreamOutput.current * Math.signum(command)); + ElectricalDevice.Output downstreamOutput = downstream.step(downstreamInput, dt); + return new Output(Math.max(0, downstreamOutput.current * Math.signum(command))); + } + + @Override + public String name() { + return "MotorController:" + downstream.name(); } } diff --git a/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java index a8263dbf..fe842076 100644 --- a/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java +++ b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java @@ -29,7 +29,7 @@ public void setExtended(boolean state) { } @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(PneumaticDevice.Input input, double dt) { pneumaticState = input; PneumaticDevice.Output output; double deviceVolume = isExtended ? boreArea() * stroke : 0; @@ -43,7 +43,7 @@ public PneumaticDevice.Output step(PneumaticDevice.Input input) { } @Override - public MechanicalDevice.Output step(MechanicalDevice.Input input) { + public MechanicalDevice.Output step(MechanicalDevice.Input input, double dt) { Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); double force = isExtended ? boreArea() * pneumaticState.pressure : returnSpringForce; return new MechanicalDevice.Output(direction.scalarMultiply(force)); diff --git a/src/main/java/com/team766/simulator/elements/Wheel.java b/src/main/java/com/team766/simulator/elements/Wheel.java index 1f6efc18..2e5760cb 100644 --- a/src/main/java/com/team766/simulator/elements/Wheel.java +++ b/src/main/java/com/team766/simulator/elements/Wheel.java @@ -26,10 +26,10 @@ public Wheel(double diameter, MechanicalAngularDevice upstream) { } @Override - public MechanicalDevice.Output step(MechanicalDevice.Input input) { + public MechanicalDevice.Output step(MechanicalDevice.Input input, double dt) { MechanicalAngularDevice.Input upstreamInput = new MechanicalAngularDevice.Input(FORWARD.dotProduct(input.velocity) * 2. / diameter); - MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); + MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput, dt); double appliedForce = upstreamOutput.torque * 2. / diameter; double maxFriction = Parameters.WHEEL_COEFFICIENT_OF_FRICTION * Parameters.ROBOT_MASS * PhysicalConstants.GRAVITY_ACCELERATION / Parameters.NUM_LOADED_WHEELS; if (Math.abs(appliedForce) > maxFriction) { diff --git a/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java index f4472268..1531f591 100644 --- a/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java @@ -22,6 +22,8 @@ public Output(Output other) { public final double current; } + + public String name(); - public Output step(Input input); + public Output step(Input input, double dt); } diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java index a3ea3526..df484ae5 100644 --- a/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java @@ -23,5 +23,5 @@ public Output(Output other) { public final double torque; } - public Output step(Input input); + public Output step(Input input, double dt); } diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java index c943b093..a982b952 100644 --- a/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java @@ -28,5 +28,5 @@ public Output(Output other) { public final Vector3D force; } - public Output step(Input input); + public Output step(Input input, double dt); } diff --git a/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java index 72a0fc4a..1b68ff8f 100644 --- a/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java @@ -36,5 +36,5 @@ public Output(Output other) { // pressurized air is actually leaving the system. } - public Output step(Input input); + public Output step(Input input, double dt); } diff --git a/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java b/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java new file mode 100644 index 00000000..a282971f --- /dev/null +++ b/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java @@ -0,0 +1,295 @@ +package com.team766.simulator.mechanisms; + +import com.team766.simulator.ElectricalSystem; +import com.team766.simulator.PhysicalConstants; +import com.team766.simulator.elements.CanMotorController; +import com.team766.simulator.elements.DCMotor; +import com.team766.simulator.elements.Gears; +import com.team766.simulator.interfaces.MechanicalAngularDevice; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.VecBuilder; +import edu.wpi.first.math.Vector; +import edu.wpi.first.math.numbers.*; + +/** + * A simulation model of the 2023 robot arm: two joints, where the second joint is driven by a + * "virtual linkage". + */ +public class DoubleJointedArm { + // General nomenclature: + // J1 refers to the first (shoulder) joint, as well as the first link of the arm. + // J2 refers to the second (elbow) joint, as well as the second link of the arm. + + private static final double J1_INITIAL_ANGLE = Math.toRadians(202.); // radians, relative to "down" + private static final double J2_INITIAL_ANGLE = Math.toRadians(32.); // radians, relative to "down" + + // Joint limits + private static final double J1_MIN = Math.toRadians(90.); // radians, relative to "down" + private static final double J1_MAX = Math.toRadians(205.); // radians, relative to "down" + private static final double J2_MIN = Math.toRadians(-170); // radians, relative to J1 + private static final double J2_MAX = Math.toRadians(170); // radians, relative to J1 + + // Physical characterisics of the arm links. + // NOTE(rcahoon, 2023-02-09): We could determine these from CAD data, but using guessed/approximate values for now. + private static final double J1_LENGTH = 1; // m + private static final double J2_LENGTH = 1; // m + private static final double J1_MASS = 2; // kg + private static final double J2_MASS = 5; // kg + private static final double J1_FIRST_MOMENT_OF_MASS = J1_MASS * J1_LENGTH; // kg m, with the origin/axis at the first joint + private static final double J1_SECOND_MOMENT_OF_MASS = J1_MASS * J1_LENGTH * J1_LENGTH; // kg m^2, with the origin/axis at the first joint - aka moment of inertia + private static final double J2_FIRST_MOMENT_OF_MASS = J2_MASS * J2_LENGTH; // kg m, with the origin/axis at the second joint + private static final double J2_SECOND_MOMENT_OF_MASS = J2_MASS * J2_LENGTH * J2_LENGTH; // kg m^2, with the origin/axis at the second joint - aka moment of inertia + + private static final double J1_GEAR_RATIO = 4. * 4. * 3. * (58. / 14.); + private static final double J2_GEAR_RATIO = 4. * 4. * 3. * (58. / 14.); + + // Simulated CAN Bus IDs for the two motors. + private static final int J1_CAN_CHANNEL = 98; + private static final int J2_CAN_CHANNEL = 99; + + private DCMotor j1Motor = DCMotor.makeNeo("ArmJoint1"); + private DCMotor j2Motor = DCMotor.makeNeo("ArmJoint2"); + + private CanMotorController j1Controller = new CanMotorController(J1_CAN_CHANNEL, j1Motor); + private CanMotorController j2Controller = new CanMotorController(J2_CAN_CHANNEL, j2Motor); + + private Gears j1Gears = new Gears(J1_GEAR_RATIO, j1Motor); + private Gears j2Gears = new Gears(J2_GEAR_RATIO, j2Motor); + + private Matrix state = VecBuilder.fill( + J1_INITIAL_ANGLE, // j1 angle, radians, relative to "down" + J2_INITIAL_ANGLE, // j2 angle, radians, relative to "down" + 0, // j1 velocity, radians/sec + 0 // j2 velocity, radians/sec + ); + + // Derivation of the equations of motion via Lagrangian mechanics. + // This system is often referred to as a "double pendulum", and is a commonly studied problem, + // so literature is available. See this series of videos for an explanation: + // https://youtu.be/tc2ah-KnDXw, https://youtu.be/eBg8gof1RBg, https://youtu.be/QE1_H2vtHLU + // The formulation given below is slightly more generalized to allow arbitrary mass + // distributions along the arm links. + // + // Kinematics: + // x1 = J1_FIRST_MOMENT_OF_MASS / J1_MASS * sin(theta1) + // y1 = -J1_FIRST_MOMENT_OF_MASS / J1_MASS * cos(theta1) + // x2 = J1_LENGTH * sin(theta1) + J2_FIRST_MOMENT_OF_MASS / J2_MASS * sin(theta2) + // y2 = -J1_LENGTH * cos(theta1) - J2_FIRST_MOMENT_OF_MASS / J2_MASS * cos(theta2) + // + // Lagrangian: + // L = T - V + // = 1/2 * J1_MASS * (x1'^2 + y1'^2) + // + 1/2 * (J1_SECOND_MOMENT_OF_MASS - J1_FIRST_MOMENT_OF_MASS^2 / J1_MASS) * theta1'^2 + // + 1/2 * J2_MASS * (x2'^2 + y2'^2) + // + 1/2 * (J2_SECOND_MOMENT_OF_MASS - J2_FIRST_MOMENT_OF_MASS^2 / J2_MASS) * theta2'^2 + // - J1_MASS * y1 * PhysicalConstants.GRAVITY_ACCELERATION + // - J2_MASS * y2 * PhysicalConstants.GRAVITY_ACCELERATION + // = 1/2 * J1_SECOND_MOMENT_OF_MASS * theta1'^2 + // + 1/2 * J2_MASS * ((J1_LENGTH * cos(theta1) * theta1' + J2_FIRST_MOMENT_OF_MASS / J2_MASS * cos(theta2) * theta2')^2 + (J1_LENGTH * sin(theta1) * theta1' + J2_FIRST_MOMENT_OF_MASS / J2_MASS * sin(theta2) * theta2')^2) + // + 1/2 * (J2_SECOND_MOMENT_OF_MASS - J2_FIRST_MOMENT_OF_MASS^2 / J2_MASS) * theta2'^2 + // + J1_FIRST_MOMENT_OF_MASS * cos(theta1) * PhysicalConstants.GRAVITY_ACCELERATION + // + (J2_MASS * J1_LENGTH * cos(theta1) + J2_FIRST_MOMENT_OF_MASS * cos(theta2)) * PhysicalConstants.GRAVITY_ACCELERATION + // = 1/2 * J1_SECOND_MOMENT_OF_MASS * theta1'^2 + // + 1/2 * (J2_MASS * J1_LENGTH^2 * theta1'^2 + 2 * J1_LENGTH * cos(theta1 - theta2) * theta1' * J2_FIRST_MOMENT_OF_MASS * theta2' + J2_FIRST_MOMENT_OF_MASS^2 / J2_MASS * theta2'^2) + // + 1/2 * (J2_SECOND_MOMENT_OF_MASS - J2_FIRST_MOMENT_OF_MASS^2 / J2_MASS) * theta2'^2 + // + J1_FIRST_MOMENT_OF_MASS * cos(theta1) * PhysicalConstants.GRAVITY_ACCELERATION + // + (J2_MASS * J1_LENGTH * cos(theta1) + J2_FIRST_MOMENT_OF_MASS * cos(theta2)) * PhysicalConstants.GRAVITY_ACCELERATION + // = 1/2 * (J1_SECOND_MOMENT_OF_MASS + J2_MASS * J1_LENGTH^2) * theta1'^2 + // + 1/2 * J2_SECOND_MOMENT_OF_MASS * theta2'^2 + // + J2_FIRST_MOMENT_OF_MASS * J1_LENGTH * cos(theta1 - theta2) * theta1' * theta2' + // + (J1_FIRST_MOMENT_OF_MASS + J2_MASS * J1_LENGTH) * PhysicalConstants.GRAVITY_ACCELERATION * cos(theta1) + // + J2_FIRST_MOMENT_OF_MASS * PhysicalConstants.GRAVITY_ACCELERATION * cos(theta2) + // + // Define some constants to simplify the following equations + // I1 = J1_SECOND_MOMENT_OF_MASS + J2_MASS * J1_LENGTH^2 + // I2 = J2_SECOND_MOMENT_OF_MASS + // Ix = J2_FIRST_MOMENT_OF_MASS * J1_LENGTH + // g1 = (J1_FIRST_MOMENT_OF_MASS + J2_MASS * J1_LENGTH) * PhysicalConstants.GRAVITY_ACCELERATION + // g2 = J2_FIRST_MOMENT_OF_MASS * PhysicalConstants.GRAVITY_ACCELERATION + // + // L = 1/2 * I1 * theta1'^2 + 1/2 * I2 * theta2'^2 + Ix * cos(theta1 - theta2) * theta1' * theta2' + g1 * cos(theta1) + g2 * cos(theta2) + // + // Euler-Lagrangian: + // d/dt ∂L/∂theta' - ∂L/∂theta = tau + // + // d/dt ∂L/∂theta1' - ∂L/∂theta1 = I1 * theta1'' + Ix * cos(theta1 - theta2) * theta2'' - Ix * sin(theta1 - theta2) * (theta1' - theta2') * theta2' + // + Ix * sin(theta1 - theta2) * theta1' * theta2' + g1 * sin(theta1) + // = I1 * theta1'' + Ix * cos(theta1 - theta2) * theta2'' + Ix * sin(theta1 - theta2) * theta2'^2 + g1 * sin(theta1) + // = tau1 + // + // d/dt ∂L/∂theta2' - ∂L/∂theta2 = I2 * theta2'' + Ix * cos(theta1 - theta2) * theta1'' - Ix * sin(theta1 - theta2) * (theta1' - theta2') * theta1' + // - Ix * sin(theta1 - theta2) * theta1' * theta2' + g2 * sin(theta2)) + // = I2 * theta2'' + Ix * cos(theta1 - theta2) * theta1'' - Ix * sin(theta1 - theta2) * theta1'^2 + g2 * sin(theta2) + // = tau2 + // + // Rewrite as a matrix equation: + // M * theta'' + G = tau + // theta'' = M^-1 * (tau - G) + // + // M = [ I1, Ix * cos(theta1 - theta2) ] + // = [ Ix * cos(theta1 - theta2), I2 ] + // G = [ Ix * sin(theta1 - theta2) * theta1' * theta2' + g1 * sin(theta1) ] + // [ -Ix * sin(theta1 - theta2) * theta1' * theta2' + g2 * sin(theta2) ] + + public DoubleJointedArm(ElectricalSystem electricalSystem) { + electricalSystem.addDevice(j1Controller); + electricalSystem.addDevice(j2Controller); + } + + /** + * Advance the simulation model by the given amount of time. + */ + public void step(double dt) { + final MechanicalAngularDevice.Output j1Drive = j1Gears.step(new MechanicalAngularDevice.Input(getJ1Velocity()), dt); + final MechanicalAngularDevice.Output j2Drive = j2Gears.step(new MechanicalAngularDevice.Input(getJ2Velocity()), dt); + + double j1Limit = 0.; + if (state.get(0, 0) <= J1_MIN) { + state.set(0, 0, J1_MIN); + state.set(2, 0, 0.0); + j1Limit = 1.; + } + if (state.get(0, 0) >= J1_MAX) { + state.set(0, 0, J1_MAX); + state.set(2, 0, 0.0); + j1Limit = -1.; + } + double j2Limit = 0.; + if (state.get(1, 0) - state.get(0, 0) <= J2_MIN) { + state.set(1, 0, J2_MIN + state.get(0, 0)); + j2Limit = 1.; + } + if (state.get(1, 0) - state.get(0, 0) >= J2_MAX) { + state.set(1, 0, J2_MAX + state.get(0, 0)); + j2Limit = -1.; + } + + if (state.get(2, 0) * j1Limit < 0) { + state.set(2, 0, 0.0); + } + if (state.get(3, 0) * j2Limit < 0) { + state.set(3, 0, 0.0); + } + + final var u = VecBuilder.fill(j1Drive.torque, j2Drive.torque, j1Limit, j2Limit); + final var stateDot = S(state, u); + state = state.plus(stateDot.times(dt)); + + j1Controller.setSensorPosition(state.get(0, 0)); + j2Controller.setSensorPosition(state.get(1, 0)); + j1Controller.setSensorVelocity(state.get(2, 0)); + j2Controller.setSensorVelocity(state.get(3, 0)); + } + + /** + * State space model X'(t) = S(X(t), u(t)) of the system + */ + // Defined as a static method to make sure we don't accidentally refer to any of the state + // stored in class member variables when we should be referring to the state the integrator + // gave us. + private static Vector S(Matrix state, Matrix u) { + Vector motorTorques = VecBuilder.fill(u.get(0, 0), u.get(1, 0)); + Vector jointLimits = VecBuilder.fill(u.get(2, 0), u.get(3, 0)); + Vector velocity = VecBuilder.fill(state.get(2, 0), state.get(3, 0)); + + final double Mx = J2_FIRST_MOMENT_OF_MASS * J1_LENGTH * Math.cos(state.get(0, 0) - state.get(1, 0)); + var M = Matrix.mat(N2.instance, N2.instance).fill( + J1_SECOND_MOMENT_OF_MASS + J2_MASS * J1_LENGTH * J1_LENGTH, Mx, + Mx, J2_SECOND_MOMENT_OF_MASS + ); + + final double C = J2_FIRST_MOMENT_OF_MASS * J1_LENGTH * Math.sin(state.get(0, 0) - state.get(1, 0)) * state.get(2, 0) * state.get(3, 0); + final var G = VecBuilder.fill( + C + (J1_FIRST_MOMENT_OF_MASS + J2_MASS * J1_LENGTH) * PhysicalConstants.GRAVITY_ACCELERATION * Math.sin(state.get(0, 0)), + -C + J2_FIRST_MOMENT_OF_MASS * PhysicalConstants.GRAVITY_ACCELERATION * Math.sin(state.get(1, 0)) + ); + var T = motorTorques.minus(G); + + if (T.get(0, 0) * jointLimits.get(0, 0) < 0) { + M.set(0, 0, 1.0); + M.set(1, 0, 0.0); + M.set(0, 1, 0.0); + T.set(0, 0, 0.0); + } + if (T.get(1, 0) * jointLimits.get(1, 0) < 0) { + M.set(1, 1, 1.0); + M.set(1, 0, 0.0); + M.set(0, 1, 0.0); + T.set(1, 0, 0.0); + } + + final var acceleration = M.inv().times(T); + + return VecBuilder.fill(velocity.get(0, 0), velocity.get(1, 0), acceleration.get(0, 0), acceleration.get(1, 0)); + } + + /** + * Return the angle of the first joint. + */ + public double getJ1Angle() { + return state.get(0, 0); + } + + /** + * Return the angle of the second joint. + */ + public double getJ2Angle() { + return state.get(1, 0); + } + + /** + * Return the velocity of the first joint. + */ + public double getJ1Velocity() { + return state.get(2, 0); + } + + /** + * Return the velocity of the second joint. + */ + public double getJ2Velocity() { + return state.get(3, 0); + } + + /** + * Calculate the total kinetic and potential energy in the arm. + * + * If no energy is added or removed (e.g. by motors or friction), this quantity should remain + * constant (i.e. conservation of energy), so plotting it over time makes a good sanity check of + * the model. + */ + public double getEnergy() { + double y1 = -J1_FIRST_MOMENT_OF_MASS / J1_MASS * Math.cos(getJ1Angle()); + double y2 = -J1_LENGTH * Math.cos(getJ1Angle()) - J2_FIRST_MOMENT_OF_MASS / J2_MASS * Math.cos(getJ2Angle()); + double dx1 = J1_FIRST_MOMENT_OF_MASS / J1_MASS * Math.cos(getJ1Angle()) * getJ1Velocity(); + double dy1 = J1_FIRST_MOMENT_OF_MASS / J1_MASS * Math.sin(getJ1Angle()) * getJ1Velocity(); + double dx2 = J1_LENGTH * Math.cos(getJ1Angle()) * getJ1Velocity() + J2_FIRST_MOMENT_OF_MASS / J2_MASS * Math.cos(getJ2Angle()) * getJ2Velocity(); + double dy2 = J1_LENGTH * Math.sin(getJ1Angle()) * getJ1Velocity() + J2_FIRST_MOMENT_OF_MASS / J2_MASS * Math.sin(getJ2Angle()) * getJ2Velocity(); + + double energy = 0.5 * J1_MASS * (dx1*dx1 + dy1*dy1) + + 0.5 * (J1_SECOND_MOMENT_OF_MASS - J1_FIRST_MOMENT_OF_MASS * J1_FIRST_MOMENT_OF_MASS / J1_MASS) * getJ1Velocity() * getJ1Velocity() + + 0.5 * J2_MASS * (dx2*dx2 + dy2*dy2) + + 0.5 * (J2_SECOND_MOMENT_OF_MASS - J2_FIRST_MOMENT_OF_MASS * J2_FIRST_MOMENT_OF_MASS / J2_MASS) * getJ2Velocity() * getJ2Velocity() + + J1_MASS * y1 * PhysicalConstants.GRAVITY_ACCELERATION + + J2_MASS * y2 * PhysicalConstants.GRAVITY_ACCELERATION; + return energy; + } + + /** + * Calculuate the cartesian coordinates of the end of the first link. + */ + public Vector getJ1Position() { + double x1 = J1_LENGTH * Math.sin(getJ1Angle()); + double y1 = -J1_LENGTH * Math.cos(getJ1Angle()); + return VecBuilder.fill(x1, y1); + } + + /** + * Calculuate the cartesian coordinates of the end of the second link. + */ + public Vector getJ2Position() { + double x2 = J1_LENGTH * Math.sin(getJ1Angle()) + J2_LENGTH * Math.sin(getJ2Angle()); + double y2 = -J1_LENGTH * Math.cos(getJ1Angle()) - J2_LENGTH * Math.cos(getJ2Angle()); + return VecBuilder.fill(x2, y2); + } +} diff --git a/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java index 25a4de82..1c2b460b 100644 --- a/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java +++ b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java @@ -18,8 +18,8 @@ import com.team766.simulator.interfaces.MechanicalDevice; public class WestCoastDrive extends DriveBase { - private DCMotor leftMotor = DCMotor.makeCIM(); - private DCMotor rightMotor = DCMotor.makeCIM(); + private DCMotor leftMotor = DCMotor.makeCIM("DriveLeftMotor"); + private DCMotor rightMotor = DCMotor.makeCIM("DriveRightMotor"); private MotorController leftController = new PwmMotorController(6, leftMotor); private MotorController rightController = new PwmMotorController(4, rightMotor); @@ -59,20 +59,20 @@ private static double softSignum(double x) { return x; } - public void step() { + public void step(double dt) { Vector3D wheelForce; Vector3D netForce = Vector3D.ZERO; Vector3D netTorque = Vector3D.ZERO; MechanicalDevice.Input leftWheelInput = new MechanicalDevice.Input( LEFT_WHEEL_POSITION, linearVelocity.scalarMultiply(-1.)); - wheelForce = leftWheels.step(leftWheelInput).force.scalarMultiply(-1.0); + wheelForce = leftWheels.step(leftWheelInput, dt).force.scalarMultiply(-1.0); netForce = netForce.add(wheelForce); netTorque = netTorque.add(Vector3D.crossProduct(LEFT_WHEEL_POSITION, wheelForce)); MechanicalDevice.Input rightWheelInput = new MechanicalDevice.Input( RIGHT_WHEEL_POSITION, linearVelocity.scalarMultiply(-1.)); - wheelForce = rightWheels.step(rightWheelInput).force.scalarMultiply(-1.0); + wheelForce = rightWheels.step(rightWheelInput, dt).force.scalarMultiply(-1.0); netForce = netForce.add(wheelForce); netTorque = netTorque.add(Vector3D.crossProduct(RIGHT_WHEEL_POSITION, wheelForce)); @@ -80,8 +80,8 @@ public void step() { double rateLeft = ENCODER_TICKS_PER_METER * (ego_velocity.getX() - angularVelocity.getZ() * LEFT_WHEEL_POSITION.getNorm()); double rateRight = ENCODER_TICKS_PER_METER * (ego_velocity.getX() + angularVelocity.getZ() * RIGHT_WHEEL_POSITION.getNorm()); - leftEncoderResidual += rateLeft * Parameters.TIME_STEP; - rightEncoderResidual += rateRight * Parameters.TIME_STEP; + leftEncoderResidual += rateLeft * dt; + rightEncoderResidual += rateRight * dt; ProgramInterface.encoderChannels[0].distance += (long)leftEncoderResidual; ProgramInterface.encoderChannels[0].rate = rateLeft; ProgramInterface.encoderChannels[2].distance += (long)rightEncoderResidual; @@ -106,12 +106,12 @@ public void step() { maxFriction * WHEEL_BASE / 2)); linearAcceleration = robotRotation.applyTo(netForce).scalarMultiply(1.0 / Parameters.ROBOT_MASS); - linearVelocity = linearVelocity.add(linearAcceleration.scalarMultiply(Parameters.TIME_STEP)); - robotPosition = robotPosition.add(linearVelocity.scalarMultiply(Parameters.TIME_STEP)); + linearVelocity = linearVelocity.add(linearAcceleration.scalarMultiply(dt)); + robotPosition = robotPosition.add(linearVelocity.scalarMultiply(dt)); angularAcceleration = netTorque.scalarMultiply(1.0 / Parameters.ROBOT_MOMENT_OF_INERTIA); - angularVelocity = angularVelocity.add(angularAcceleration.scalarMultiply(Parameters.TIME_STEP)); - Vector3D angularDelta = angularVelocity.scalarMultiply(Parameters.TIME_STEP); + angularVelocity = angularVelocity.add(angularAcceleration.scalarMultiply(dt)); + Vector3D angularDelta = angularVelocity.scalarMultiply(dt); robotRotation = robotRotation.compose( new Rotation(RotationOrder.XYZ, RotationConvention.VECTOR_OPERATOR, diff --git a/src/main/java/com/team766/simulator/ui/ArmTrajectory.java b/src/main/java/com/team766/simulator/ui/ArmTrajectory.java new file mode 100644 index 00000000..7ed2d893 --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/ArmTrajectory.java @@ -0,0 +1,103 @@ +package com.team766.simulator.ui; + +import java.awt.BasicStroke; +import java.awt.BorderLayout; +import java.awt.Color; +import java.awt.Graphics; +import java.awt.Graphics2D; +import java.awt.Point; + +import javax.swing.JPanel; + +import de.erichseifert.gral.data.DataSeries; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; +import de.erichseifert.gral.plots.lines.DefaultLineRenderer2D; +import de.erichseifert.gral.plots.lines.LineRenderer; +import de.erichseifert.gral.ui.InteractivePanel; + +/** + * UI Window that displays the movements that the robot's arm made. + */ +public class ArmTrajectory extends JPanel { + private final XYPlot plot; + private final DataTable data; + // The current playback time. + private double time; + + /** + * @param series The time series data defining the robot's trajectory. + * Each element should be an array with 5 values: + * [0]: Time + * [1]: X Position of the end of the first link + * [2]: Y Position of the end of the first link + * [3]: X Position of the end of the second link + * [4]: Y Position of the end of the second link + * @param playbackTimer The timer (shared between windows) which controls playback time. + */ + public ArmTrajectory(Iterable series, PlaybackTimer playbackTimer) { + // Create an X-Y plot to display the trajectories + data = PlotUtils.makeDataTable(series); + var firstTrajectory = new DataSeries("First link", data, 1, 2); + var secondTrajectory = new DataSeries("Second link", data, 3, 4); + plot = new XYPlot(firstTrajectory, secondTrajectory); + plot.getAxis(XYPlot.AXIS_X).setRange(-2.5, 2.5); + plot.getAxis(XYPlot.AXIS_Y).setRange(-2.5, 2.5); + + // Show the trajectories for the arm's links using different colors. + { + LineRenderer lines = new DefaultLineRenderer2D(); + lines.setColor(new Color(0, 0, 128)); + plot.setLineRenderers(firstTrajectory, lines); + plot.setPointRenderers(firstTrajectory, null); + } + { + LineRenderer lines = new DefaultLineRenderer2D(); + lines.setColor(new Color(128, 0, 0)); + plot.setLineRenderers(secondTrajectory, lines); + plot.setPointRenderers(secondTrajectory, null); + } + + InteractivePanel panel = new InteractivePanel(plot); + setLayout(new BorderLayout()); + add(panel, BorderLayout.CENTER); + + // Add the standard time slider and play/pause button. + add(new PlaybackControls(playbackTimer), BorderLayout.SOUTH); + + // Add the callback that will update this window when playback time progresses. + playbackTimer.addListener(event -> { + this.time = (Double)event.getNewValue(); + this.repaint(); + }); + } + + /** + * Draw overlays on the plot + */ + @Override + public void paint(Graphics g) { + super.paint(g); + + Graphics2D g2d = (Graphics2D)g; + + int index = PlotUtils.findIndex(data.getColumn(0), time); + + double j1_x = (Double)data.get(1, index); + double j1_y = (Double)data.get(2, index); + double j2_x = (Double)data.get(3, index); + double j2_y = (Double)data.get(4, index); + + // Show the current position of the arm by drawing a line for each of the links. + + Point j0_p = PlotUtils.getPixelCoords(plot, 0.0, 0.0); + Point j1_p = PlotUtils.getPixelCoords(plot, j1_x, j1_y); + Point j2_p = PlotUtils.getPixelCoords(plot, j2_x, j2_y); + + g2d.setStroke(new BasicStroke(10)); + g2d.setColor(new Color(128, 128, 255)); + g2d.drawLine(j0_p.x, j0_p.y, j1_p.x, j1_p.y); + g2d.setColor(Color.red); + g2d.drawLine(j1_p.x, j1_p.y, j2_p.x, j2_p.y); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ui/Metrics.java b/src/main/java/com/team766/simulator/ui/Metrics.java deleted file mode 100644 index 2615c6ea..00000000 --- a/src/main/java/com/team766/simulator/ui/Metrics.java +++ /dev/null @@ -1,160 +0,0 @@ -package com.team766.simulator.ui; - -import java.awt.BorderLayout; -import java.awt.Color; -import java.awt.event.ActionEvent; -import java.awt.event.ActionListener; -import java.awt.event.KeyEvent; -import java.awt.event.KeyListener; -import java.awt.event.MouseAdapter; -import java.awt.event.MouseEvent; -import java.util.Arrays; -import java.util.Collection; - -import javax.swing.JFrame; -import javax.swing.JPanel; -import javax.swing.JSlider; -import javax.swing.Timer; - -import com.team766.simulator.Parameters; - -import de.erichseifert.gral.data.DataSeries; -import de.erichseifert.gral.data.DataSource; -import de.erichseifert.gral.data.DataTable; -import de.erichseifert.gral.plots.XYPlot; -import de.erichseifert.gral.plots.lines.DefaultLineRenderer2D; -import de.erichseifert.gral.plots.lines.LineRenderer; -import de.erichseifert.gral.ui.InteractivePanel; - -@SuppressWarnings("serial") -public class Metrics extends JPanel { - // Color palette from http://www.mulinblog.com/a-color-palette-optimized-for-data-visualization/ - private static final String[] COLORS = { - "#4D4D4D", // gray - "#5DA5DA", // blue - "#FAA43A", // orange - "#60BD68", // green - "#F17CB0", // pink - "#B2912F", // brown - "#B276B2", // purple - "#DECF3F", // yellow - "#F15854", // red - }; - - private static class Inspector extends MouseAdapter implements KeyListener { - private int sourceIndex = 0; - private double selectedTime = Double.NaN; - private XYPlot plot; - - public Inspector(XYPlot plot) { - this.plot = plot; - } - - void update() { - if (!Double.isNaN(selectedTime)) { - DataSource source = plot.getData().get(sourceIndex); - int index = Arrays.binarySearch(source.getColumn(0).toArray(null), selectedTime); - if (index < 0) { - index = -index - 1; - } - System.out.println(String.format("(%s, %f): %f", source.getName(), selectedTime, source.get(1, index))); - } - } - - @Override - public void mouseClicked(MouseEvent e) { - double x = e.getX() - plot.getPlotArea().getX(); - selectedTime = plot.getAxisRenderer(XYPlot.AXIS_X).viewToWorld(plot.getAxis(XYPlot.AXIS_X), x, false).doubleValue(); - - update(); - } - - @Override - public void keyTyped(KeyEvent e) { - if (e.getKeyChar() >= '1' && e.getKeyChar() <= '9') { - int index = e.getKeyChar() - '1'; - if (index < plot.getData().size()) { - sourceIndex = index; - System.out.println("Selected " + plot.getData().get(sourceIndex).getName()); - update(); - } - } - } - - @Override - public void keyReleased(KeyEvent e) {} - - @Override - public void keyPressed(KeyEvent e) {} - } - - public static JFrame makePlotFrame(Collection series, String[] labels) { - JFrame frame = new JFrame(); - frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); - frame.setSize(800, 600); - frame.setContentPane(new Metrics(series, labels)); - frame.setVisible(true); - return frame; - } - - XYPlot plot; - JSlider slider; - DataTable data; - JPanel plotPanel; - Timer playbackTimer; - - public Metrics(Collection series, String[] labels) { - Double[] first = series.iterator().next(); - @SuppressWarnings("unchecked") - Class[] types = new Class[first.length]; - Arrays.fill(types, Double.class); - data = new DataTable(types); - for (Double[] values : series) { - if (first.length != values.length) { - throw new IllegalArgumentException("Data values must be the same length"); - } - data.add(values); - } - if (first.length - 1 != labels.length) { - throw new IllegalArgumentException("Number of labels does not match the size of data values"); - } - DataSource[] sources = new DataSource[labels.length]; - for (int i = 0; i < labels.length; ++i) { - sources[i] = new DataSeries(labels[i], data, 0, i + 1); - } - plot = new XYPlot(sources); - int colorIndex = 0; - for (DataSource source : sources) { - LineRenderer lines = new DefaultLineRenderer2D(); - plot.setLineRenderers(source, lines); - Color color = Color.decode(COLORS[colorIndex++ % COLORS.length]); - plot.getPointRenderers(source).get(0).setColor(color); - plot.getLineRenderers(source).get(0).setColor(color); - } - plot.setLegendVisible(true); - - InteractivePanel panel = new InteractivePanel(plot); - plotPanel = panel; - setLayout(new BorderLayout()); - add(panel, BorderLayout.CENTER); - - final int TIMER_PERIOD_MS = 50; - playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { - @Override - public void actionPerformed(ActionEvent e) { - double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; - int newValue = slider.getValue() + (int)deltaSteps; - if (newValue > slider.getMaximum()) { - newValue = slider.getMaximum(); - playbackTimer.stop(); - } - slider.setValue(newValue); - } - }); - playbackTimer.setRepeats(true); - - Inspector inspector = new Inspector(plot); - addKeyListener(inspector); - panel.addMouseListener(inspector); - } -} \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ui/MetricsPlot.java b/src/main/java/com/team766/simulator/ui/MetricsPlot.java new file mode 100644 index 00000000..9e7e324b --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/MetricsPlot.java @@ -0,0 +1,182 @@ +package com.team766.simulator.ui; + +import java.awt.BasicStroke; +import java.awt.BorderLayout; +import java.awt.Color; +import java.awt.Graphics; +import java.awt.Graphics2D; +import java.awt.event.MouseAdapter; +import java.awt.event.MouseEvent; +import java.awt.event.MouseWheelListener; +import java.util.Arrays; +import java.util.List; +import javax.swing.JPanel; +import javax.swing.SwingUtilities; +import com.team766.simulator.Metrics; +import de.erichseifert.gral.data.DataSeries; +import de.erichseifert.gral.data.DataSource; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; +import de.erichseifert.gral.plots.lines.DefaultLineRenderer2D; +import de.erichseifert.gral.plots.lines.LineRenderer; +import de.erichseifert.gral.ui.InteractivePanel; + +/** + * UI Window that displays plots of time-series data. + */ +public class MetricsPlot extends JPanel { + // Color palette from http://www.mulinblog.com/a-color-palette-optimized-for-data-visualization/ + private static final String[] COLORS = { + "#4D4D4D", // gray + "#5DA5DA", // blue + "#FAA43A", // orange + "#60BD68", // green + "#F17CB0", // pink + "#B2912F", // brown + "#B276B2", // purple + "#DECF3F", // yellow + "#F15854", // red + }; + + private static class DataSeriesWithMutableName extends DataSeries { + public DataSeriesWithMutableName(String name, DataSource data, int... cols) { + super(name, data, cols); + } + + // Override to make this public + @Override + public void setName(String name) { + super.setName(name); + } + } + + private final XYPlot plot; + // The data store. Column 0 is time, the other columns are the metrics values. + private final DataTable data; + // A view into data for each of the series. + private final DataSeriesWithMutableName[] sources; + // A name for each of the series. + private final List labels; + // The current playback time. + private double time; + + /** + * @param metrics The time series data to display + * @param playbackTimer The timer (shared between windows) which controls playback time. + */ + public MetricsPlot(Metrics metrics, PlaybackTimer playbackTimer) { + // Create the plot + data = PlotUtils.makeDataTable(metrics.getMetrics()); + labels = metrics.getLabels(); + sources = new DataSeriesWithMutableName[labels.size()]; + for (int i = 0; i < labels.size(); ++i) { + sources[i] = new DataSeriesWithMutableName(labels.get(i), data, 0, i + 1); + } + plot = new XYPlot(sources); + + // Add a little margin on all sides of the plot for better readability. Also make sure + // that the axes are visible so we can see the scale of the data. + var xAxis = plot.getAxis(XYPlot.AXIS_X); + xAxis.setMin(-0.05 * xAxis.getRange()); + xAxis.setMax(xAxis.getMax().doubleValue() + 0.05 * xAxis.getRange()); + var yAxis = plot.getAxis(XYPlot.AXIS_Y); + yAxis.setMin(Math.min(yAxis.getMin().doubleValue() - 0.05 * yAxis.getRange(), -0.05 * yAxis.getRange())); + yAxis.setMax(Math.max(yAxis.getMax().doubleValue() + 0.05 * yAxis.getRange(), 0.05 * yAxis.getRange())); + + // Assign a different color to each data series. + int colorIndex = 0; + for (DataSource source : sources) { + LineRenderer lines = new DefaultLineRenderer2D(); + Color color = Color.decode(COLORS[colorIndex++ % COLORS.length]); + lines.setColor(color); + plot.setLineRenderers(source, lines); + plot.setPointRenderers(source, null); + } + + // Setup the legend so it's visible and placed on the top-right + updateLegend(); + plot.getLegend().setAlignmentX(1.0); + plot.getLegend().setAlignmentY(0.1); + plot.setLegendVisible(true); + + InteractivePanel panel = new InteractivePanel(plot); + setLayout(new BorderLayout()); + add(panel, BorderLayout.CENTER); + + // Remove listener installed by InteractivePanel that conflicts with our MouseListener. + for (var l : panel.getMouseListeners()) { + // We're looking to remove "MouseZoomListener", which is a private inner class, and Java + // doesn't seem to have its proper name stored in reflection (the stored name is "a"). + // We instead find it because it's the only one of the listeners which directly + // implements MouseWheelListener (note that other of the listeners extend MouseAdapter, + // meaning they indirectly implement MouseWheelListener, so we can't just use instanceof). + if (Arrays.asList(l.getClass().getInterfaces()).contains(MouseWheelListener.class)) { + panel.removeMouseListener(l); + } + } + // Add a mouse listener that will set playback time if the plot is double-clicked. + panel.addMouseListener(new MouseAdapter() { + @Override + public void mouseClicked(MouseEvent e) { + if (!SwingUtilities.isLeftMouseButton(e) || e.getClickCount() < 2) { + return; + } + + double x = e.getX() - plot.getPlotArea().getX(); + double selectedTime = plot.getAxisRenderer(XYPlot.AXIS_X).viewToWorld(plot.getAxis(XYPlot.AXIS_X), x, false).doubleValue(); + + playbackTimer.setTime(selectedTime); + + // final int index = PlotUtils.findIndex(data.getColumn(0), time); + // System.out.println("At time=" + selectedTime + ":"); + // for (int i = 0; i < labels.size(); ++i) { + // System.out.println(" " + labels.get(i) + ": " + data.get(i + 1, index)); + // } + // System.out.println(); + + e.consume(); + } + }); + + // Add the standard time slider and play/pause button. + add(new PlaybackControls(playbackTimer), BorderLayout.SOUTH); + + // Add the callback that will update this window when playback time progresses. + playbackTimer.addListener(event -> { + this.time = (Double)event.getNewValue(); + updateLegend(); + this.repaint(); + }); + } + + /** + * Update the legend so that it displays the current value for each of the series. + */ + private void updateLegend() { + final int index = PlotUtils.findIndex(data.getColumn(0), time); + final var legend = plot.getLegend(); + legend.clear(); + for (int i = 0; i < sources.length; ++i) { + sources[i].setName(String.format("%s: %.4f", labels.get(i), data.get(i + 1, index))); + legend.add(sources[i]); + } + } + + /** + * Draw overlays on the plot + */ + @Override + public void paint(Graphics g) { + super.paint(g); + + Graphics2D g2d = (Graphics2D)g; + + // Draw a dashed vertical line to trace the current time on the plot. + final int lineX = PlotUtils.getPixelCoords(plot, time, 0.0).x; + final double plotAreaTop = plot.getPlotArea().getY(); + final double plotAreaBottom = plotAreaTop + plot.getPlotArea().getHeight(); + g2d.setStroke(new BasicStroke(2, BasicStroke.CAP_SQUARE, BasicStroke.JOIN_MITER, 10.f, new float[]{10.0f}, 0.f)); + g2d.setColor(Color.black); + g2d.drawLine(lineX, (int)plotAreaTop, lineX, (int)plotAreaBottom); + } +} \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ui/PlaybackControls.java b/src/main/java/com/team766/simulator/ui/PlaybackControls.java new file mode 100644 index 00000000..2c032c81 --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/PlaybackControls.java @@ -0,0 +1,70 @@ +package com.team766.simulator.ui; + +import java.awt.event.ActionEvent; +import java.awt.event.ActionListener; +import java.beans.PropertyChangeEvent; +import javax.swing.BoxLayout; +import javax.swing.JButton; +import javax.swing.JPanel; +import javax.swing.JSlider; +import javax.swing.event.ChangeEvent; +import javax.swing.event.ChangeListener; + +/** + * A panel included at the bottom of all of the UI windows that allows for controlling time during + * playback. + */ +public class PlaybackControls extends JPanel { + // How large one step of the slider is, in seconds. + private static final double SLIDER_RESOLUTION = 0.020; + + // There's a circular dependency between the PlaybackTimer and the slider: both have the ability + // to change time, and both are updated when the other changes time, triggering callbacks to + // listeners. + // This flag is set to true during the callback that is executed when the PlaybackTimer updates + // its time, so that when it updates the position of the slider, the slider's callback will not + // try to update timer, which would lead to an infinite loop of callbacks. + private boolean inTimerTick = false; + + /** + * @param playbackTimer The timer (shared between windows) which controls playback time. + */ + public PlaybackControls(PlaybackTimer playbackTimer) { + setLayout(new BoxLayout(this, BoxLayout.LINE_AXIS)); + + // Add a slider that shows the progression of time and also allows for seeking to a + // different time. + var slider = new JSlider(0, (int)Math.ceil(playbackTimer.endTime() / SLIDER_RESOLUTION)); + slider.setValue(0); + slider.addChangeListener(new ChangeListener() { + public void stateChanged(ChangeEvent e) { + if (inTimerTick) { + return; + } + playbackTimer.setTime(slider.getValue() * SLIDER_RESOLUTION); + } + }); + add(slider); + + // Add a button that can start and stop playback. + JButton playButton = new JButton(">"); + playButton.addActionListener(new ActionListener() { + @Override + public void actionPerformed(ActionEvent e) { + if (playbackTimer.isRunning()) { + playbackTimer.stop(); + } else { + playbackTimer.start(); + } + } + }); + add(playButton); + + // Add the callback that will update this panel when playback time progresses. + playbackTimer.addListener((PropertyChangeEvent event) -> { + inTimerTick = true; + slider.setValue((int)Math.ceil((Double)event.getNewValue() / SLIDER_RESOLUTION)); + inTimerTick = false; + }); + } +} diff --git a/src/main/java/com/team766/simulator/ui/PlaybackTimer.java b/src/main/java/com/team766/simulator/ui/PlaybackTimer.java new file mode 100644 index 00000000..5f800dbf --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/PlaybackTimer.java @@ -0,0 +1,138 @@ +package com.team766.simulator.ui; + +import java.awt.event.ActionEvent; +import java.beans.PropertyChangeListener; +import java.beans.PropertyChangeSupport; +import javax.swing.Timer; + +/** + * This provides a centralized tracking of playback time. + * + * Supports starting realtime playback, stopping playback, and seeking to a particular time. + */ +public class PlaybackTimer { + // Minimum period between notifications to listeners when playback is running (in milliseconds). + // Actual notification period may be longer than this, depending on how long it takes listeners + // to run their callbacks. + private static final int TIMER_PERIOD_MS = 50; + + // The property name used in the PropertyChangeEvents that this sends to listeners. + public static final String PROPERTY_NAME = "playbackTime"; + + private final Timer timer; + + private final PropertyChangeSupport listeners = new PropertyChangeSupport(this); + + // The wall-clock time corresponding to t=0 of playback time. + // Only valid when playback is running. + private double startTime; + // The playback time, when it was most recently updated. + private double playTime = 0.0; + // The playback time of the previous update. + private double prevTime = 0.0; + // The playback time at which playback should automatically stop. + private final double endTime; + // Monitor that synchronizes access to these *Time variables. + private final Object timeLock = new Object(); + + /** + * @param endTime The playback time at which playback should automatically stop. + */ + public PlaybackTimer(double endTime) { + this.endTime = endTime; + timer = new Timer(TIMER_PERIOD_MS, null) { + @Override + protected void fireActionPerformed(ActionEvent event) { + synchronized (timeLock) { + playTime = System.currentTimeMillis() * 0.001 - startTime; + if (playTime >= endTime) { + playTime = endTime; + timer.stop(); + } + super.fireActionPerformed(event); + listeners.firePropertyChange(PROPERTY_NAME, prevTime, playTime); + prevTime = playTime; + } + } + }; + timer.setRepeats(true); + timer.setCoalesce(true); + } + + /** + * Register the given listener to receive callbacks when playback time updates. + */ + public void addListener(PropertyChangeListener listener) { + listeners.addPropertyChangeListener(listener); + } + + /** + * Returns whether playback is currently running. + */ + public boolean isRunning() { + return timer.isRunning(); + } + + /** + * Returns the current playback time, as of the most recent update. + */ + public double currentTime() { + return playTime; + } + + /** + * Returns the playback time at which playback will automatically stop. + */ + public double endTime() { + return endTime; + } + + /** + * Start playback, if it is not already running. + * + * If playback had previously reached endTime, which will automatically start again from the + * beginning. + */ + public void start() { + if (isRunning()) { + return; + } + synchronized(timeLock) { + if (playTime >= endTime) { + setTime(0.0); + } + startTime = System.currentTimeMillis() * 0.001 - playTime; + } + timer.restart(); + } + + /** + * Seek to the given playback time. + */ + public void setTime(double t) { + if (t < 0.) { + t = 0.; + } + synchronized(timeLock) { + playTime = t; + startTime = System.currentTimeMillis() * 0.001 - t; + if (!isRunning()) { + listeners.firePropertyChange(PROPERTY_NAME, prevTime, playTime); + } + prevTime = t; + } + } + + /** + * Stop playback. + */ + public void stop() { + if (!isRunning()) { + return; + } + timer.stop(); + synchronized(timeLock) { + playTime = System.currentTimeMillis() * 0.001 - startTime; + } + } +} diff --git a/src/main/java/com/team766/simulator/ui/PlotUtils.java b/src/main/java/com/team766/simulator/ui/PlotUtils.java new file mode 100644 index 00000000..d27195be --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/PlotUtils.java @@ -0,0 +1,72 @@ +package com.team766.simulator.ui; + +import java.awt.Point; +import java.util.Arrays; +import de.erichseifert.gral.data.Column; +import de.erichseifert.gral.data.DataTable; +import de.erichseifert.gral.plots.XYPlot; + +/** + * Various utility methods for dealing with the Gral plotting library. + */ +class PlotUtils { + /** + * Return a DataTable containing the data in the given series of multivariate data. + * + * @throws IllegalArgumentException if all elements of `series` are not of the same length. + */ + public static DataTable makeDataTable(Iterable series) { + Double[] first = series.iterator().next(); + @SuppressWarnings("unchecked") + Class[] types = new Class[first.length]; + Arrays.fill(types, Double.class); + DataTable data = new DataTable(types); + for (Double[] values : series) { + if (first.length != values.length) { + throw new IllegalArgumentException("Data values must be the same length"); + } + data.add(values); + } + return data; + } + + /** + * Return the index of the first element which is greater than or equal to `value`. + * If no such element is found, returns the index of the last element. + */ + public static int findIndex(Column column, Comparable value) { + // TODO: We use this to search sorted data, so we ought to be able to use a binary search, + // but Column is not compatible with either Arrays.binarySearch or Collections.binarySearch. + // NOTE: Calling column.toArray() and then Arrays.binarySearch would be more expensive than + // this linear scan. + int index = 0; + for (Object v : column) { + @SuppressWarnings("unchecked") + var t_v = (T)v; + if (value.compareTo(t_v) < 0) { + return index; + } + ++index; + } + return index - 1; + } + + /** + * Convert a (x, y) coordinate pair from data values to UI coordinates. + * + * This is useful for drawing overlays onto plots. + */ + public static Point getPixelCoords(XYPlot plot, double x, double y) { + double pixelX = plot.getAxisRenderer(XYPlot.AXIS_X).worldToView(plot.getAxis(XYPlot.AXIS_X), x, false); + double pixelY = plot.getAxisRenderer(XYPlot.AXIS_Y).worldToView(plot.getAxis(XYPlot.AXIS_Y), y, false); + + double plotAreaHeight = plot.getPlotArea().getHeight(); + double plotAreaX = plot.getPlotArea().getX(); + double plotAreaY = plot.getPlotArea().getY(); + + pixelX = plotAreaX + pixelX; + pixelY = plotAreaY + plotAreaHeight - pixelY; + + return new Point((int)pixelX, (int)pixelY); + } +} diff --git a/src/main/java/com/team766/simulator/ui/Trajectory.java b/src/main/java/com/team766/simulator/ui/Trajectory.java index bc97b9fe..6a2dcbd3 100644 --- a/src/main/java/com/team766/simulator/ui/Trajectory.java +++ b/src/main/java/com/team766/simulator/ui/Trajectory.java @@ -4,140 +4,88 @@ import java.awt.Color; import java.awt.Graphics; import java.awt.Graphics2D; -import java.awt.event.ActionEvent; -import java.awt.event.ActionListener; +import java.awt.Point; import java.awt.geom.AffineTransform; -import java.util.Arrays; -import java.util.Collection; -import javax.swing.BoxLayout; -import javax.swing.JButton; -import javax.swing.JFrame; import javax.swing.JPanel; -import javax.swing.JSlider; -import javax.swing.Timer; -import javax.swing.event.ChangeEvent; -import javax.swing.event.ChangeListener; - -import com.team766.simulator.Parameters; import de.erichseifert.gral.data.DataSeries; import de.erichseifert.gral.data.DataTable; import de.erichseifert.gral.plots.XYPlot; import de.erichseifert.gral.ui.InteractivePanel; -@SuppressWarnings("serial") +/** + * UI Window that displays the path that the robot drove. + */ public class Trajectory extends JPanel { - public static JFrame makePlotFrame(Collection series) { - JFrame frame = new JFrame(); - frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); - frame.setSize(800, 600); - frame.setContentPane(new Trajectory(series)); - frame.setVisible(true); - return frame; - } - - XYPlot plot; - JSlider slider; - DataTable data; - JPanel plotPanel; - Timer playbackTimer; - - public Trajectory(Collection series) { - Double[] first = series.iterator().next(); - @SuppressWarnings("unchecked") - Class[] types = new Class[first.length]; - Arrays.fill(types, Double.class); - data = new DataTable(types); - for (Double[] values : series) { - if (first.length != values.length) { - throw new IllegalArgumentException("Data values must be the same length"); - } - data.add(values); - } - plot = new XYPlot(new DataSeries("Trajectory", data, 0, 1)); + private final XYPlot plot; + private final DataTable data; + // The current playback time. + private double time; + + /** + * @param series The time series data defining the robot's trajectory. + * Each element should be an array with 6 values: + * [0]: Time + * [1]: X Position + * [2]: Y Position + * [3]: Orientation + * [4]: X Velocity + * [5]: Y Velocity + * @param playbackTimer The timer (shared between windows) which controls playback time. + */ + public Trajectory(Iterable series, PlaybackTimer playbackTimer) { + // Create an X-Y plot to display the trajectory + data = PlotUtils.makeDataTable(series); + var source = new DataSeries("Trajectory", data, 1, 2); + plot = new XYPlot(source); plot.getAxis(XYPlot.AXIS_X).setRange(-10.0, 10.0); plot.getAxis(XYPlot.AXIS_Y).setRange(-10.0, 10.0); + plot.setPointRenderers(source, null); InteractivePanel panel = new InteractivePanel(plot); - plotPanel = panel; setLayout(new BorderLayout()); add(panel, BorderLayout.CENTER); - - final int TIMER_PERIOD_MS = 50; - playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { - @Override - public void actionPerformed(ActionEvent e) { - double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; - int newValue = slider.getValue() + (int)deltaSteps; - if (newValue > slider.getMaximum()) { - newValue = slider.getMaximum(); - playbackTimer.stop(); - } - slider.setValue(newValue); - } - }); - playbackTimer.setRepeats(true); - - JPanel controlsPanel = new JPanel(); - controlsPanel.setLayout(new BoxLayout(controlsPanel, BoxLayout.LINE_AXIS)); - slider = new JSlider(0, data.getRowCount() - 1); - slider.setValue(0); - slider.addChangeListener(new ChangeListener() { - public void stateChanged(ChangeEvent e) { - Trajectory.this.repaint(); - } - }); - controlsPanel.add(slider); - JButton playButton = new JButton(">"); - playButton.addActionListener(new ActionListener() { - @Override - public void actionPerformed(ActionEvent e) { - if (playbackTimer.isRunning()) { - playbackTimer.stop(); - } else { - playbackTimer.start(); - if (slider.getValue() == slider.getMaximum()) { - slider.setValue(slider.getMinimum()); - } - } - } + + // Add the standard time slider and play/pause button. + add(new PlaybackControls(playbackTimer), BorderLayout.SOUTH); + + // Add the callback that will update this window when playback time progresses. + playbackTimer.addListener(event -> { + this.time = (Double)event.getNewValue(); + this.repaint(); }); - controlsPanel.add(playButton); - add(controlsPanel, BorderLayout.SOUTH); } - + + /** + * Draw overlays on the plot + */ @Override public void paint(Graphics g) { super.paint(g); - - int slider_value = slider.getValue(); - double x = (Double)data.get(0, slider_value); - double y = (Double)data.get(1, slider_value); - double orientation = (Double)data.get(2, slider_value); - double vel_x = (Double)data.get(3, slider_value); - double vel_y = (Double)data.get(4, slider_value); - - double pixelX = plot.getAxisRenderer(XYPlot.AXIS_X).worldToView(plot.getAxis(XYPlot.AXIS_X), x, false); - double pixelY = plot.getAxisRenderer(XYPlot.AXIS_Y).worldToView(plot.getAxis(XYPlot.AXIS_Y), y, false); - double plotAreaHeight = plot.getPlotArea().getHeight(); - double plotAreaX = plot.getPlotArea().getX(); - double plotAreaY = plot.getPlotArea().getY(); - - pixelX = plotAreaX + pixelX; - pixelY = plotAreaY + plotAreaHeight - pixelY; - Graphics2D g2d = (Graphics2D)g; + int index = PlotUtils.findIndex(data.getColumn(0), time); + + double x = (Double)data.get(1, index); + double y = (Double)data.get(2, index); + double orientation = (Double)data.get(3, index); + double vel_x = (Double)data.get(4, index); + double vel_y = (Double)data.get(5, index); + + // Show the robot's current pose by drawing a rectangle. + Point pixelPos = PlotUtils.getPixelCoords(plot, x, y); final int SIZE_X = 30; final int SIZE_Y = 20; g2d.setColor(new Color(128, 128, 255)); AffineTransform saveXf = g2d.getTransform(); - g2d.rotate(-orientation, pixelX, pixelY); - g2d.fillRect((int)pixelX - SIZE_X / 2, (int)pixelY - SIZE_Y / 2, SIZE_X, SIZE_Y); + g2d.rotate(-orientation, pixelPos.x, pixelPos.y); + g2d.fillRect((int)pixelPos.x - SIZE_X / 2, (int)pixelPos.y - SIZE_Y / 2, SIZE_X, SIZE_Y); g2d.setTransform(saveXf); + + // Show the robot's current velocity by drawing a line extending from the robot's position. //g2d.setColor(Color.red); - //g2d.drawLine((int)pixelX, (int)pixelY, (int)(pixelX + vel_x * 20), (int)(pixelY - vel_y * 20)); + //g2d.drawLine((int)pixelPos.x, (int)pixelPos.y, (int)(pixelPos.x + vel_x * 20), (int)(pixelPos.y - vel_y * 20)); } } \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ui/UIFrame.java b/src/main/java/com/team766/simulator/ui/UIFrame.java new file mode 100644 index 00000000..10afff93 --- /dev/null +++ b/src/main/java/com/team766/simulator/ui/UIFrame.java @@ -0,0 +1,71 @@ +package com.team766.simulator.ui; + +import java.awt.Container; +import java.awt.Dimension; +import java.awt.Point; +import java.awt.event.ComponentAdapter; +import java.awt.event.ComponentEvent; +import java.util.prefs.Preferences; +import javax.swing.JFrame; + +/** + * A subclass of JFrame that adds automatic saving/restoring of the window's position and size. + * + * We open several windows to display plots and trajectories, and it's preferable to not have to + * rearrange them everytime the simulation is restarted. + */ +public class UIFrame extends JFrame { + private Preferences prefs; + + public UIFrame(String frameUniqueId, Container content) { + super.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); + super.setSize(800, 600); + super.setContentPane(content); + super.setTitle(frameUniqueId); + super.setVisible(true); + + prefs = Preferences.userNodeForPackage(UIFrame.class).node(frameUniqueId); + + restoreFrameLocation(); + restoreFrameSize(); + + super.addComponentListener(new ComponentAdapter() { + @Override + public void componentResized(ComponentEvent e) { + updatePref(); + } + + @Override + public void componentMoved(ComponentEvent e) { + updatePref(); + } + }); + } + + private void updatePref() { + Point location = super.getLocation(); + prefs.putInt("x", location.x); + prefs.putInt("y", location.y); + Dimension size = super.getSize(); + prefs.putInt("w", size.width); + prefs.putInt("h", size.height); + } + + private void restoreFrameSize() { + int w = prefs.getInt("w", -1); + int h = prefs.getInt("h", -1); + if (w < 0 || h < 0) { + return; + } + super.setSize(new Dimension(w, h)); + } + + private void restoreFrameLocation() { + int x = prefs.getInt("x", -1); + int y = prefs.getInt("y", -1); + if (x < 0 || y < 0) { + return; + } + super.setLocation(new Point(x, y)); + } +} diff --git a/src/test/java/com/team766/simulator/MetricsTest.java b/src/test/java/com/team766/simulator/MetricsTest.java new file mode 100644 index 00000000..844cd31c --- /dev/null +++ b/src/test/java/com/team766/simulator/MetricsTest.java @@ -0,0 +1,20 @@ +package com.team766.simulator; + +import java.util.List; +import org.junit.jupiter.api.Assertions; +import org.junit.jupiter.api.Test; + +public class MetricsTest { + @Test + public void test() { + var metrics = new Metrics(); + var series1 = metrics.addSeries("Series1"); + var series2 = metrics.addSeries("Series2"); + + metrics.add(0).set(series1, 42).set(series2, 24); + metrics.add(1).set(series1, 83).set(series2, 38); + + Assertions.assertIterableEquals(metrics.getLabels(), List.of("Series1", "Series2")); + Assertions.assertArrayEquals(metrics.getMetrics().toArray(), new Double[][]{new Double[]{0., 42., 24.}, new Double[]{1., 83., 38.}}); + } +} \ No newline at end of file From cb96d5c487bce3df8bff86ba6539a2ee633abe93 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Sat, 11 Feb 2023 13:53:28 -0800 Subject: [PATCH 040/103] Added FollowPoints read-from-file ability --- src/main/deploy/FollowPoints.txt | 32 +++++++++++++++++++ .../robot/procedures/FollowPoints.java | 24 ++++++++++++-- 2 files changed, 53 insertions(+), 3 deletions(-) create mode 100644 src/main/deploy/FollowPoints.txt diff --git a/src/main/deploy/FollowPoints.txt b/src/main/deploy/FollowPoints.txt new file mode 100644 index 00000000..1cc6a5ab --- /dev/null +++ b/src/main/deploy/FollowPoints.txt @@ -0,0 +1,32 @@ +{ + "points": [ + { + "coordinates": [5.4, 5.34, 15], + "critical": true + }, + { + "coordinates": [3.76, 4.38, 0], + "critical": false + }, + { + "coordinates": [6.32, 4.38, 0], + "critical": true + }, + { + "coordinates": [7.06, 3.45, 15], + "critical": false + }, + { + "coordinates": [7.57, 1.63, 30], + "critical": false + }, + { + "coordinates": [6.13, 0.53, 0], + "critical": true + }, + { + "coordinates": [2.53, 0.42, 0], + "critical": false + } + ] +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 4b172196..7c9b27c8 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -11,22 +11,23 @@ import com.team766.odometry.PointDir; import com.team766.hal.PositionReader; import java.io.File; +import java.io.IOException; +import java.nio.file.Files; import java.nio.file.Path; import java.util.ArrayList; import java.util.List; import com.team766.config.ConfigFileReader; import com.team766.logging.Category; +import com.team766.logging.Severity; import com.team766.controllers.PIDController; import edu.wpi.first.wpilibj.Filesystem; +import org.json.*; public class FollowPoints extends Procedure { //Steps combine possible data types into one object for flexibility and ease-of-use purposes public static class Step { - - //Path path = Filesystem.getDeployDirectory().toPath().resolve("BLABLABLA.JSON"); - //File file = path.toFile(); public PointDir wayPoint; public boolean criticalPoint; @@ -67,6 +68,23 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole loggerCategory = Category.AUTONOMOUS; }*/ + public FollowPoints(String file) throws IOException { + String str; + Path path = Filesystem.getDeployDirectory().toPath().resolve(file); + try { + str = Files.readString(path); + } catch (IOException e) { + e.printStackTrace(); + log(Severity.ERROR, "Could not load " + file); + return; + } + + JSONArray points = new JSONObject(str).getJSONArray("points"); + for (int i = 0; i < points.length(); i++) { + addStep(new PointDir(points.getJSONObject(0).getJSONArray("coordinates").getDouble(0), points.getJSONObject(0).getJSONArray("coordinates").getDouble(1), points.getJSONObject(0).getJSONArray("coordinates").getDouble(2)), points.getJSONObject(0).getBoolean("critical"), null, false); + } + } + //Creates a new Step object from its constituents private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { steps.add(new Step(wayPoint, criticalPoint, procedure, stopRobot)); From 77a9b44abb34e52785b1b5d1f7843e521f45e030 Mon Sep 17 00:00:00 2001 From: qntmcube <68516760+TTVMixmix00@users.noreply.github.com> Date: Sat, 11 Feb 2023 13:57:14 -0800 Subject: [PATCH 041/103] Fixed --- src/main/java/com/team766/controllers/PIDController.java | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/java/com/team766/controllers/PIDController.java b/src/main/java/com/team766/controllers/PIDController.java index 93fd4e86..c5a77ed4 100755 --- a/src/main/java/com/team766/controllers/PIDController.java +++ b/src/main/java/com/team766/controllers/PIDController.java @@ -290,6 +290,7 @@ public void reset() { prev_error = 0; error_rate = 0; total_error = 0; + lastTime = timeProvider.get(); needsUpdate = true; } From 79fd82ad164a5043182648dacdabe936f12b9f56 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Sat, 11 Feb 2023 14:47:54 -0800 Subject: [PATCH 042/103] Added javadocs to Odometry and FollowPoints --- .../java/com/team766/odometry/Odometry.java | 25 +++++ src/main/java/com/team766/odometry/Point.java | 3 + .../java/com/team766/odometry/PointDir.java | 2 + .../robot/procedures/FollowPoints.java | 94 ++++++++++++------- 4 files changed, 91 insertions(+), 33 deletions(-) diff --git a/src/main/java/com/team766/odometry/Odometry.java b/src/main/java/com/team766/odometry/Odometry.java index 9bcd9fcd..62f14ca1 100644 --- a/src/main/java/com/team766/odometry/Odometry.java +++ b/src/main/java/com/team766/odometry/Odometry.java @@ -7,6 +7,9 @@ import com.team766.logging.Category; import com.team766.robot.*; +/** + * Method which calculates the position of the robot based on wheel positions. + */ public class Odometry extends LoggingBase { private RateLimiter odometryLimiter; @@ -32,6 +35,16 @@ public class Odometry extends LoggingBase { //In the same order as motorList, relative to the center of the robot private Point[] wheelPositions; + /** + * Constructor for Odometry, taking in several defines for the robot. + * @param motors A list of every wheel-controlling motor on the robot. + * @param CANCoders A list of the CANCoders corresponding to each wheel, in the same order as motors. + * @param wheelLocations A list of the locations of each wheel, in the same order as motors. + * @param wheelCircumference The circumfrence of the wheels, including treads. + * @param gearRatio The gear ratio of the wheels. + * @param encoderToRevolutionConstant The encoder to revolution constant of the wheels. + * @param rateLimiterTime How often odometry should run. + */ public Odometry(MotorController[] motors, CANCoder[] CANCoders, Point[] wheelLocations, double wheelCircumference, double gearRatio, int encoderToRevolutionConstant, double rateLimiterTime) { loggerCategory = Category.ODOMETRY; @@ -63,6 +76,9 @@ public String getName() { return "Odometry"; } + /** + * Sets the current position of the robot to (0, 0). + */ public void resetCurrentPosition() { currentPosition.set(0, 0); for (int i = 0; i < motorCount; i++) { @@ -71,6 +87,9 @@ public void resetCurrentPosition() { } } + /** + * Updates the odometry encoder values to the robot encoder values. + */ private void setCurrentEncoderValues() { for (int i = 0; i < motorCount; i++) { prevEncoderValues[i] = currEncoderValues[i]; @@ -78,6 +97,9 @@ private void setCurrentEncoderValues() { } } + /** + * Updates the position of each wheel of the robot by assuming each wheel moved in an arc. + */ private void updateCurrentPositions() { double angleChange; double radius; @@ -105,6 +127,9 @@ private void updateCurrentPositions() { } } + /** + * Calculates the position of the robot by finding the average of the wheel positions. + */ private void findRobotPosition() { double sumX = 0; double sumY = 0; diff --git a/src/main/java/com/team766/odometry/Point.java b/src/main/java/com/team766/odometry/Point.java index d28d0454..ac6e4a89 100644 --- a/src/main/java/com/team766/odometry/Point.java +++ b/src/main/java/com/team766/odometry/Point.java @@ -3,6 +3,9 @@ import com.team766.framework.LoggingBase; import java.lang.Math; +/** + * Class of two-coordinate objects, an x-coordinate and a y-coordinate. + */ public class Point extends LoggingBase { private double x; private double y; diff --git a/src/main/java/com/team766/odometry/PointDir.java b/src/main/java/com/team766/odometry/PointDir.java index 30d2a433..2f00c413 100644 --- a/src/main/java/com/team766/odometry/PointDir.java +++ b/src/main/java/com/team766/odometry/PointDir.java @@ -70,10 +70,12 @@ public double getAngleDifference(Point a) { return diff / 180; } + @Override public String toString() { return super.toString() + " Heading: " + getHeading(); } + @Override public PointDir clone() { return new PointDir(getX(), getY(), getHeading()); } diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 7c9b27c8..735434d2 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -24,6 +24,10 @@ import edu.wpi.first.wpilibj.Filesystem; import org.json.*; +/** + * {@link Procedure} to follow a set of waypoints. Waypoint files can be passed in via + * the {@link #FollowPoints(String)} constructor. + */ public class FollowPoints extends Procedure { //Steps combine possible data types into one object for flexibility and ease-of-use purposes @@ -68,6 +72,11 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole loggerCategory = Category.AUTONOMOUS; }*/ + /** + * Constructor to create a new FollowPoints instance. + * @param file filename for the waypoints file to load and use. + * @throws IOException Thrown if file is not found. + */ public FollowPoints(String file) throws IOException { String str; Path path = Filesystem.getDeployDirectory().toPath().resolve(file); @@ -85,12 +94,20 @@ public FollowPoints(String file) throws IOException { } } - //Creates a new Step object from its constituents + /** + * Method which creates a new Step object from its constituents. + * @param wayPoint PointDir consisting of the x- and y- coordinates of the point, as well as the target header for the robot at that point. + * @param criticalPoint Boolean determining whether the robot should travel to the point (true) or if it should use the FollowPoints circle method (false). + * @param procedure Procedure for the robot to run when reaching the point. If null is inputted, it is interpreted as "doNothing()". + * @param stopRobot Boolean determining whether the robot should wait for the procedure to finish before continuing on its path. + */ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { steps.add(new Step(wayPoint, criticalPoint, procedure, stopRobot)); } - //Default FollowPoints Constructor, Steps must be added here + /** + * Default FollowPoints Constructor. Steps must be added in-code. + */ public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); addStep(new PointDir(4,0, 90), true, null /* don't execute procedure */, false); @@ -98,7 +115,9 @@ public FollowPoints() { addWaypoints(); } - //When using steps, this sets up the arrays to be used by the FollowPoints method + /** + * When using steps (in the default constructor), this sets up the arrays to be used by the FollowPoints method. + */ private void addWaypoints() { pointList = new PointDir[steps.size()]; proceduresAtPoints = new Procedure[steps.size()]; @@ -123,16 +142,11 @@ private void addWaypoints() { } } - //Takes an array of procedures and uses points from the config file - public FollowPoints(Procedure[] procedureList) { - parsePointList(); - proceduresAtPoints = procedureList; - criticalPointList = new boolean[pointList.length]; - stopRobotList = new boolean[pointList.length]; - loggerCategory = Category.AUTONOMOUS; - } - //Takes an array of points + /** + * Constructor which takes an array of points. + * @param points Array of PointDir objects for the robot to follow, consisting of x- and y- coordinates, as well as a target header for the robot. + */ public FollowPoints(PointDir[] points) { pointList = points; proceduresAtPoints = new Procedure[pointList.length]; @@ -144,17 +158,8 @@ public FollowPoints(PointDir[] points) { loggerCategory = Category.AUTONOMOUS; } - //Takes an array of points and an array of procedures to do at each point - public FollowPoints(PointDir[] points, Procedure[] procedureList) { - pointList = points; - proceduresAtPoints = procedureList; - criticalPointList = new boolean[pointList.length]; - stopRobotList = new boolean[pointList.length]; - loggerCategory = Category.AUTONOMOUS; - } - //Takes pairs of points from pointDoubles (set in the config file) and converts them to Points, which are placed in pointList. - private void parsePointList() { + /*private void parsePointList() { Double[] pointDoubles = ConfigFileReader.getInstance().getDoubles("trajectory.points").get(); pointList = new PointDir[pointDoubles.length / 2]; double pointX = 0; @@ -167,7 +172,7 @@ private void parsePointList() { pointList[i / 2] = new PointDir(pointX, pointY); } } - } + }*/ public void run(Context context) { speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); @@ -192,7 +197,7 @@ public void run(Context context) { currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point //Otherwise, it uses the checkIntersection() method to follow the circle - if (criticalPointList[targetNum]? passedPoint(pointList[targetNum]) : checkIntersection(targetNum, currentPos, pointList, radius)) { + if (criticalPointList[targetNum]? passedPoint(pointList[targetNum]) : checkIntersection(pointList)) { if (proceduresAtPoints.length < targetNum) { if (stopRobotList[targetNum]) { context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); @@ -203,7 +208,7 @@ public void run(Context context) { targetNum++; log("Going to Next Point!"); } - targetPoint = selectTargetPoint(targetNum, currentPos, pointList, radius); + targetPoint = selectTargetPoint(targetNum, pointList); //double diff = currentPos.getAngleDifference(targetPoint); //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); @@ -226,14 +231,21 @@ public void run(Context context) { } } + /** + * Method which keeps updating how much the robot should turn between rateLimiter calls. + */ public void updateRotation() { Robot.drive.setGyro(Robot.gyro.getGyroYaw()); driveSettings.setHeading(rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); Robot.drive.swerveDrive(driveSettings); } - //Returns whether the circle around the robot intersects the line connecting the two next points. - public static boolean checkIntersection(int targetNum, PointDir currentPos, Point[] pointList, double radius) { + /** + * Method which returns whether the circle around the robot intersects the line connecting the two next points. + * @param pointList The list of points the robot is following. + * @return Boolean: whether or not the circle with given radius centered at currentPos intersects with the line between the next two points. + */ + private boolean checkIntersection(Point[] pointList) { double a; double b; double c; @@ -250,8 +262,13 @@ public static boolean checkIntersection(int targetNum, PointDir currentPos, Poin return false; } - //If the circle around the robot intersects the line connecting the previous and next points, returns whichever intersection point is closest to the next point. Otherwise, returns the next point. - public static Point selectTargetPoint(int targetNum, PointDir currentPos, Point[] pointList, double radius) { + /** + * Method returning which point the robot should move towards. + * @param targetNum The id value of the next point in pointList. + * @param currentPos The current position of the robot. + * @return If the circle around the robot intersects the line connecting the previous and next points, returns whichever intersection point is closest to the next point. Otherwise, returns the next point. + */ + private static Point selectTargetPoint(int targetNum, Point[] pointList) { double a; double b; double c; @@ -288,13 +305,23 @@ public static Point selectTargetPoint(int targetNum, PointDir currentPos, Point[ } //Returns if the robot has passed a certain point - public boolean passedPoint(Point P) { + /** + * Method returning whether the robot has passed a given point. + * @param P Point which this method determines has been passed. + * @return If the robot is within a certain distance of P, and the distance to P is increasing, returns true. Otherwise, returns false. + */ + private boolean passedPoint(Point P) { log(currentPos + " " + P + " " + currentPos.distance(P) + " " + ((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2) ? " true" : " false")); return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2); } - //Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point - public double rotationSpeed(double currentRot, double targetRot) { + /** + * Method which returns how much the robot should turn to reach its target heading. + * @param currentRot The current heading of the robot. + * @param targetRot The target heading of the robot. + * @return Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point. + */ + private double rotationSpeed(double currentRot, double targetRot) { double maxSpeed = 0.2; double angleDistanceForMaxSpeed = 90; currentRot = mod(currentRot, 360); @@ -311,7 +338,8 @@ public double rotationSpeed(double currentRot, double targetRot) { return maxSpeed * -Math.signum(currentRot - targetRot); } - public static double mod(double d1, double d2) { + //Returns mod(d1, d2), to use to circumvent java's weird % function + private static double mod(double d1, double d2) { return d1 % d2 + (d1 < 0 ? d2 : 0); } } \ No newline at end of file From 436062821881acd8b2d8d4161fa540f785fc49f4 Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Sun, 12 Feb 2023 05:25:05 +0000 Subject: [PATCH 043/103] add javadoc target to build NOTE: compiling javadocs emits many warnings due to missing @param's, @return's, etc. we'll fix those separately from this PR. --- build.gradle | 4 ++++ src/main/java/com/team766/controllers/PIDController.java | 1 - 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 324a7c69..9a64f1ad 100644 --- a/build.gradle +++ b/build.gradle @@ -102,6 +102,10 @@ dependencies { implementation files('deps/json-20190722.jar') } +javadoc { + source = sourceSets.main.allJava +} + test { useJUnitPlatform() systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' diff --git a/src/main/java/com/team766/controllers/PIDController.java b/src/main/java/com/team766/controllers/PIDController.java index 93fd4e86..8da8aa95 100755 --- a/src/main/java/com/team766/controllers/PIDController.java +++ b/src/main/java/com/team766/controllers/PIDController.java @@ -209,7 +209,6 @@ public void setFF(double FF) { /** Same as calculate() except that it prints debugging information * * @param cur_input The current input to be plugged into the PID controller - * @param smart True if you want the output to be dynamically adjusted to the motor controller */ public void calculateDebug(double cur_input) { print = true; From 0e1603a901c703558b37bde2e053d900d1981f9a Mon Sep 17 00:00:00 2001 From: dejabot <104333734+dejabot@users.noreply.github.com> Date: Sun, 12 Feb 2023 05:30:50 +0000 Subject: [PATCH 044/103] add directories for sample documents, in markdown format. --- docs/sample.md | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) create mode 100644 docs/sample.md diff --git a/docs/sample.md b/docs/sample.md new file mode 100644 index 00000000..e04c21cd --- /dev/null +++ b/docs/sample.md @@ -0,0 +1,29 @@ +# Sample Markdown Syntax +## Styles +**BOLD** + +*Italics* + +* Point 1 +* Point 2 +* Point 3 + +> Multiple +> +> Line +> Blockquote + +## Advanced +`code` in paragraph + +Block of Code: + + public class Mechanism { + // ... + } + +### Image +![Image](https://imgs.xkcd.com/comics/compiling.png) + +### Link +[Useful Reference](https://www.youtube.com/watch?v=oHg5SJYRHA0) From 199b955890a14ec4ee7277116a5743a6ea492b7e Mon Sep 17 00:00:00 2001 From: Blaise Gassend Date: Sat, 11 Feb 2023 14:03:37 -0800 Subject: [PATCH 045/103] Print useful message when reading motor config fails. Previously any error would just tell you that the motor was not present in the config file. Now it prints the exception and stack trace so you can figure out what is actually wrong with your config. --- src/main/java/com/team766/hal/RobotProvider.java | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java index 10a81c29..529d891c 100755 --- a/src/main/java/com/team766/hal/RobotProvider.java +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -2,6 +2,8 @@ import java.util.Arrays; import java.util.HashMap; +import java.io.StringWriter; +import java.io.PrintWriter; import com.team766.config.ConfigFileReader; import com.team766.controllers.TimeProviderI; @@ -116,7 +118,11 @@ public MotorController getMotor(String configName) { } return motor; } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s not found in config file, using mock motor instead", configName); + StringWriter exsw = new StringWriter(); + ex.printStackTrace(new PrintWriter(exsw)); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Error getting configuration for motor %s from config file, using mock motor instead.\nDetailed error: %s", + configName, exsw.toString()); return new LocalMotorController(configName, new MockMotorController(0), sensor); } } From 52230c78a32c681756037b8f810caad07f612357 Mon Sep 17 00:00:00 2001 From: Blaise Gassend Date: Sat, 11 Feb 2023 13:46:15 -0800 Subject: [PATCH 046/103] Added a mode to view all log messages in the web UI. --- src/main/java/com/team766/web/LogViewer.java | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/team766/web/LogViewer.java b/src/main/java/com/team766/web/LogViewer.java index 8738594c..08a8be09 100644 --- a/src/main/java/com/team766/web/LogViewer.java +++ b/src/main/java/com/team766/web/LogViewer.java @@ -14,6 +14,7 @@ public class LogViewer implements WebServer.Handler { private static final String ENDPOINT = "/logs"; private static final String ALL_ERRORS_NAME = "All Errors"; + private static final String ALL_MESSAGES_NAME = "All Messages"; private static final SimpleDateFormat timeFormat = new SimpleDateFormat("yyyy-MM-dd HH:mm:ss"); @@ -37,7 +38,9 @@ private static String makePage(String categoryName, Iterable entries) categoryName, Stream.concat( Stream.of(ALL_ERRORS_NAME), - Arrays.stream(Category.values()).map(Category::name) + Stream.concat( + Stream.of(ALL_MESSAGES_NAME), + Arrays.stream(Category.values()).map(Category::name)) ).toArray(String[]::new)), "", "

", @@ -86,6 +89,14 @@ static String makeAllErrorsPage() { ::iterator); } + static String makeAllMessagesPage() { + return makePage( + ALL_MESSAGES_NAME, + Arrays.stream(Category.values()) + .flatMap(category -> Logger.get(category).recentEntries().stream()) + ::iterator); + } + @Override public String endpoint() { return ENDPOINT; @@ -96,6 +107,8 @@ public String handle(Map params) { String categoryName = (String)params.get("category"); if (categoryName == null || categoryName.equals(ALL_ERRORS_NAME)) { return makeAllErrorsPage(); + } else if (categoryName.equals(ALL_MESSAGES_NAME)) { + return makeAllMessagesPage(); } else { Category category = Enum.valueOf(Category.class, categoryName); return makePage(category.name(), Logger.get(category).recentEntries()); From a1f5888e7b42ee3d601d064e7d65c1e82de52c4e Mon Sep 17 00:00:00 2001 From: Blaise Gassend Date: Sun, 12 Feb 2023 11:18:45 -0800 Subject: [PATCH 047/103] Simplify how streams are concatenated. --- src/main/java/com/team766/web/LogViewer.java | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/java/com/team766/web/LogViewer.java b/src/main/java/com/team766/web/LogViewer.java index 08a8be09..c886a9ad 100644 --- a/src/main/java/com/team766/web/LogViewer.java +++ b/src/main/java/com/team766/web/LogViewer.java @@ -37,10 +37,8 @@ private static String makePage(String categoryName, Iterable entries) "category", categoryName, Stream.concat( - Stream.of(ALL_ERRORS_NAME), - Stream.concat( - Stream.of(ALL_MESSAGES_NAME), - Arrays.stream(Category.values()).map(Category::name)) + Stream.of(ALL_ERRORS_NAME, ALL_MESSAGES_NAME), + Arrays.stream(Category.values()).map(Category::name) ).toArray(String[]::new)), "", "

", From 7af4c3c3b9f71372670c435e460ea0a607d71216 Mon Sep 17 00:00:00 2001 From: Blaise Gassend Date: Sun, 12 Feb 2023 18:37:27 -0800 Subject: [PATCH 048/103] Use LoggerExceptionUtils.exceptionToString() rather than rolling my own. --- src/main/java/com/team766/hal/RobotProvider.java | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java index 529d891c..4698eeb4 100755 --- a/src/main/java/com/team766/hal/RobotProvider.java +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -16,6 +16,7 @@ import com.team766.library.ValueProvider; import com.team766.logging.Category; import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; import com.team766.logging.Severity; public abstract class RobotProvider { @@ -118,11 +119,9 @@ public MotorController getMotor(String configName) { } return motor; } catch (IllegalArgumentException ex) { - StringWriter exsw = new StringWriter(); - ex.printStackTrace(new PrintWriter(exsw)); Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Error getting configuration for motor %s from config file, using mock motor instead.\nDetailed error: %s", - configName, exsw.toString()); + configName, LoggerExceptionUtils.exceptionToString(ex)); return new LocalMotorController(configName, new MockMotorController(0), sensor); } } From ab75155f824174c78a05bd285530a522136a3611 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Mon, 13 Feb 2023 18:38:00 -0800 Subject: [PATCH 049/103] Changed resetCurrentPosition to setCurrentPosition --- src/main/java/com/team766/odometry/Odometry.java | 10 ++++++---- src/main/java/com/team766/robot/mechanisms/Drive.java | 2 +- .../com/team766/robot/procedures/FollowPoints.java | 1 + 3 files changed, 8 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/team766/odometry/Odometry.java b/src/main/java/com/team766/odometry/Odometry.java index 62f14ca1..7a4cbcd7 100644 --- a/src/main/java/com/team766/odometry/Odometry.java +++ b/src/main/java/com/team766/odometry/Odometry.java @@ -77,15 +77,17 @@ public String getName() { } /** - * Sets the current position of the robot to (0, 0). + * Sets the current position of the robot to Point P + * @param P The point to set the current robot position to */ - public void resetCurrentPosition() { - currentPosition.set(0, 0); + public void setCurrentPosition(Point P) { + currentPosition.set(P); for (int i = 0; i < motorCount; i++) { prevPositions[i].set(currentPosition.add(wheelPositions[i])); - currPositions[i].set(0,0); + currPositions[i].set(currentPosition.add(wheelPositions[i])); } } + /** * Updates the odometry encoder values to the robot encoder values. diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 3e71b66a..bf3fe558 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -390,7 +390,7 @@ public PointDir getCurrentPosition() { } public void resetCurrentPosition() { - swerveOdometry.resetCurrentPosition(); + swerveOdometry.setCurrentPosition(new Point(0, 0)); } public void setCross() { checkContextOwnership(); diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 735434d2..96854d2d 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -122,6 +122,7 @@ private void addWaypoints() { pointList = new PointDir[steps.size()]; proceduresAtPoints = new Procedure[steps.size()]; stopRobotList = new boolean[pointList.length]; + //TODO: Fix all critical points being read as false criticalPointList = new boolean[pointList.length]; for (int i = 0; i < steps.size(); i++) { if (steps.get(i).wayPoint == null) continue; From 123c103305ac37e5aad2c6a2cfa8dfcdbb420069 Mon Sep 17 00:00:00 2001 From: SauquetAlex <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 15 Feb 2023 16:50:15 -0800 Subject: [PATCH 050/103] Added Swerve comments using javadocs --- .../com/team766/robot/mechanisms/Drive.java | 599 +++++++++++------- 1 file changed, 387 insertions(+), 212 deletions(-) diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index bf3fe558..bfd3c426 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -1,9 +1,9 @@ package com.team766.robot.mechanisms; + import com.team766.framework.Mechanism; import com.team766.hal.EncoderReader; import com.team766.hal.RobotProvider; import com.team766.hal.MotorController; -import com.team766.hal.MotorControllerCommandFailedException; import com.team766.hal.MotorController.ControlMode; import com.team766.hal.simulator.Encoder; import com.team766.hal.MotorController; @@ -23,14 +23,14 @@ public class Drive extends Mechanism { - + private MotorController m_DriveFrontRight; - private MotorController m_DriveFrontLeft; + private MotorController m_DriveFrontLeft; private MotorController m_DriveBackRight; private MotorController m_DriveBackLeft; - private MotorController m_SteerFrontRight; - private MotorController m_SteerFrontLeft; + private MotorController m_SteerFrontRight; + private MotorController m_SteerFrontLeft; private MotorController m_SteerBackRight; private MotorController m_SteerBackLeft; @@ -38,7 +38,7 @@ public class Drive extends Mechanism { private CANCoder e_FrontLeft; private CANCoder e_BackRight; private CANCoder e_BackLeft; - + private ValueProvider drivePower; private double gyroValue; @@ -51,43 +51,45 @@ public class Drive extends Mechanism { private Odometry swerveOdometry; public static final double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; - + public Drive() { - + loggerCategory = Category.DRIVE; - // Initializations of motors - //Initialize the drive motors - m_DriveFrontRight = RobotProvider.instance.getMotor("drive.DriveFrontRight"); - m_DriveFrontLeft = RobotProvider.instance.getMotor("drive.DriveFrontLeft"); - m_DriveBackRight = RobotProvider.instance.getMotor("drive.DriveBackRight"); - m_DriveBackLeft = RobotProvider.instance.getMotor("drive.DriveBackLeft"); - //Initialize the steering motors - m_SteerFrontRight = RobotProvider.instance.getMotor("drive.SteerFrontRight"); - m_SteerFrontLeft = RobotProvider.instance.getMotor("drive.SteerFrontLeft"); - m_SteerBackRight = RobotProvider.instance.getMotor("drive.SteerBackRight"); + // Initializations of motors + // Initialize the drive motors + m_DriveFrontRight = RobotProvider.instance.getMotor("drive.DriveFrontRight"); + m_DriveFrontLeft = RobotProvider.instance.getMotor("drive.DriveFrontLeft"); + m_DriveBackRight = RobotProvider.instance.getMotor("drive.DriveBackRight"); + m_DriveBackLeft = RobotProvider.instance.getMotor("drive.DriveBackLeft"); + // Initialize the steering motors + m_SteerFrontRight = RobotProvider.instance.getMotor("drive.SteerFrontRight"); + m_SteerFrontLeft = RobotProvider.instance.getMotor("drive.SteerFrontLeft"); + m_SteerBackRight = RobotProvider.instance.getMotor("drive.SteerBackRight"); m_SteerBackLeft = RobotProvider.instance.getMotor("drive.SteerBackLeft"); - - //Setting up the "config" + + // Setting up the "config" CANCoderConfiguration config = new CANCoderConfiguration(); config.absoluteSensorRange = AbsoluteSensorRange.Signed_PlusMinus180; - //The encoders output "encoder" values, so we need to convert that to degrees (because that is what the cool kids are using) + // The encoders output "encoder" values, so we need to convert that to degrees (because that + // is what the cool kids are using) config.sensorCoefficient = 360.0 / 4096.0; - //The offset is going to be changed in ctre, but we can change it here too. - //config.magnetOffsetDegrees = Math.toDegrees(configuration.getOffset()); + // The offset is going to be changed in ctre, but we can change it here too. + // config.magnetOffsetDegrees = Math.toDegrees(configuration.getOffset()); config.sensorDirection = true; - //initialize the encoders - e_FrontRight = new CANCoder(1, "Swerve"); - //e_FrontRight.configAllSettings(config, 250); - e_FrontLeft = new CANCoder(2, "Swerve"); - //e_FrontLeft.configAllSettings(config, 250); - e_BackRight = new CANCoder(4, "Swerve"); - //e_BackRight.configAllSettings(config, 250); - e_BackLeft = new CANCoder(3, "Swerve"); - //e_BackLeft.configAllSettings(config, 250); - - - //Current limit for motors to avoid breaker problems (mostly to avoid getting electrical people to yell at us) + // initialize the encoders + e_FrontRight = new CANCoder(1); + // e_FrontRight.configAllSettings(config, 250); + e_FrontLeft = new CANCoder(2); + // e_FrontLeft.configAllSettings(config, 250); + e_BackRight = new CANCoder(4); + // e_BackRight.configAllSettings(config, 250); + e_BackLeft = new CANCoder(3); + // e_BackLeft.configAllSettings(config, 250); + + + // Current limit for motors to avoid breaker problems (mostly to avoid getting electrical + // people to yell at us) m_DriveFrontRight.setCurrentLimit(35); m_DriveFrontLeft.setCurrentLimit(35); m_DriveBackRight.setCurrentLimit(35); @@ -99,111 +101,215 @@ public Drive() { m_SteerBackRight.setCurrentLimit(30); m_SteerBackLeft.setCurrentLimit(30); - //Setting up the connection between steering motors and cancoders - //m_SteerFrontRight.setRemoteFeedbackSensor(e_FrontRight, 0); - //m_SteerFrontLeft.setRemoteFeedbackSensor(e_FrontLeft, 0); - //m_SteerBackRight.setRemoteFeedbackSensor(e_BackRight, 0); - //m_SteerBackLeft.setRemoteFeedbackSensor(e_BackLeft, 0); + // Setting up the connection between steering motors and cancoders + // m_SteerFrontRight.setRemoteFeedbackSensor(e_FrontRight, 0); + // m_SteerFrontLeft.setRemoteFeedbackSensor(e_FrontLeft, 0); + // m_SteerBackRight.setRemoteFeedbackSensor(e_BackRight, 0); + // m_SteerBackLeft.setRemoteFeedbackSensor(e_BackLeft, 0); m_SteerFrontRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); m_SteerFrontLeft.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); - m_SteerBackRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); + m_SteerBackRight.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); m_SteerBackLeft.setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); configPID(); + // Sets up odometry currentPosition = new PointDir(0, 0, 0); - motorList = new MotorController[]{m_DriveFrontRight, m_DriveFrontLeft, m_DriveBackLeft, m_DriveBackRight}; - CANCoderList = new CANCoder[]{e_FrontRight, e_FrontLeft, e_BackLeft, e_BackRight}; - wheelPositions = new Point[]{new Point(DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2), new Point(DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), new Point(-DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), new Point(-DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2)}; + motorList = new MotorController[] {m_DriveFrontRight, m_DriveFrontLeft, m_DriveBackLeft, + m_DriveBackRight}; + CANCoderList = new CANCoder[] {e_FrontRight, e_FrontLeft, e_BackLeft, e_BackRight}; + wheelPositions = + new Point[] {new Point(DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2), + new Point(DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), + new Point(-DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), + new Point(-DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2)}; log("MotorList Length: " + motorList.length); log("CANCoderList Length: " + CANCoderList.length); - //The wheelCircumference is somewhere between 30.4cm and 30.6cm - swerveOdometry = new Odometry(motorList, CANCoderList, wheelPositions, 30.5 / 100, 6.75, 2048, 0.05); - } - //If you want me to repeat code, then no. + // The wheelCircumference is somewhere between 30.4cm and 30.6cm + swerveOdometry = + new Odometry(motorList, CANCoderList, wheelPositions, 30.5 / 100, 6.75, 2048, 0.05); + } + + // A set of simple functions for the sake of adding vectors + /** + * Returns the pythagorean theorem of two numbers + * + * @param x First number + * @param y Second number + * @return + */ public double pythagorean(double x, double y) { return Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2)); } - public double getAngle(double LR, double FB){ - return Math.toDegrees(Math.atan2(LR ,-FB)); - } + + /** + * Returns the angle of a vector, used by joystick inputs + * + * @param LR The x value of the vector + * @param FB The y value of the vector + * @return The angle of the vector + */ + public double getAngle(double LR, double FB) { + return Math.toDegrees(Math.atan2(LR, -FB)); + } + + /** + * Rounds a number based on its value and places + * + * @param value The number to be rounded + * @param places The number of places to round to + * @return The rounded number + */ public double round(double value, int places) { double scale = Math.pow(10, places); return Math.round(value * scale) / scale; } - public double NewAng(double FirstMag, double FirstAng, double SecondMag, double SecondAng){ - double FinalX = FirstMag*Math.cos(Math.toRadians(FirstAng)) + SecondMag*Math.cos(Math.toRadians(SecondAng)); - double FinalY = FirstMag*Math.sin(Math.toRadians(FirstAng)) + SecondMag*Math.sin(Math.toRadians(SecondAng)); - return round(Math.toDegrees(Math.atan2(FinalY,FinalX)),5); - } - public double NewMag(double FirstMag, double FirstAng, double SecondMag, double SecondAng){ - double FinalX = FirstMag*Math.cos(Math.toRadians(FirstAng)) + SecondMag*Math.cos(Math.toRadians(SecondAng)); - double FinalY = FirstMag*Math.sin(Math.toRadians(FirstAng)) + SecondMag*Math.sin(Math.toRadians(SecondAng)); - return round(Math.sqrt(Math.pow(FinalX,2) + Math.pow(FinalY,2)),5); - } - - public static double correctedJoysticks(double Joystick){ - if(Joystick >= 0) - return(3.0*Math.pow(Joystick,2)-2.0*Math.pow(Joystick,3)); - else - return(-1*3.0*Math.pow(-1*Joystick,2)+2.0*Math.pow(-1*Joystick,3)); - } - - public static double fieldAngle(double angle, double gyro){ + /** + * Adds two vectors together + * + * @param FirstMag The magnitude of the first vector + * @param FirstAng The angle of the first vector + * @param SecondMag The magnitude of the second vector + * @param SecondAng The angle of the second vector + * @return New angle of the vector + */ + public double NewAng(double FirstMag, double FirstAng, double SecondMag, double SecondAng) { + double FinalX = FirstMag * Math.cos(Math.toRadians(FirstAng)) + + SecondMag * Math.cos(Math.toRadians(SecondAng)); + double FinalY = FirstMag * Math.sin(Math.toRadians(FirstAng)) + + SecondMag * Math.sin(Math.toRadians(SecondAng)); + return round(Math.toDegrees(Math.atan2(FinalY, FinalX)), 5); + } + + /** + * Adds two vectors together + * + * @param FirstMag The magnitude of the first vector + * @param FirstAng The angle of the first vector + * @param SecondMag The magnitude of the second vector + * @param SecondAng The angle of the second vector + * @return New magnitude of the vector + */ + public double NewMag(double FirstMag, double FirstAng, double SecondMag, double SecondAng) { + double FinalX = FirstMag * Math.cos(Math.toRadians(FirstAng)) + + SecondMag * Math.cos(Math.toRadians(SecondAng)); + double FinalY = FirstMag * Math.sin(Math.toRadians(FirstAng)) + + SecondMag * Math.sin(Math.toRadians(SecondAng)); + return round(Math.sqrt(Math.pow(FinalX, 2) + Math.pow(FinalY, 2)), 5); + } + + /** + * Corrects the joystick inputs to make them more accurate, currently unused + * + * @param Joystick The joystick value to be corrected + * @returnThe corrected joystick value + */ + public static double correctedJoysticks(double Joystick) { + if (Joystick >= 0) + return (3.0 * Math.pow(Joystick, 2) - 2.0 * Math.pow(Joystick, 3)); + else + return (-1 * 3.0 * Math.pow(-1 * Joystick, 2) + 2.0 * Math.pow(-1 * Joystick, 3)); + } + + /** + * Converts the angle of the joystick to the angle of the robot compared to the field by using + * the gyro + * + * @param angle The angle of the joystick + * @param gyro The angle of the gyro + * @return The angle of the robot compared to the field + */ + public static double fieldAngle(double angle, double gyro) { double newAngle; newAngle = angle - gyro; - if(newAngle < 0){ + if (newAngle < 0) { newAngle = newAngle + 360; } - if(newAngle >= 180){ - newAngle = newAngle -360; + if (newAngle >= 180) { + newAngle = newAngle - 360; } return newAngle; } - public static double newAngle(double newAngle, double lastAngle){ - while(newAngle<0) newAngle += 360; - while(newAngle < (lastAngle - 180)) newAngle+=360; - while(newAngle > (lastAngle + 180)) newAngle-=360; + + /** + * Method to correct angles for the falcon encoders + * + * @param newAngle The given angle value + * @param lastAngle The last angle value + * @return The corrected angle value + */ + public static double newAngle(double newAngle, double lastAngle) { + while (newAngle < 0) + newAngle += 360; + while (newAngle < (lastAngle - 180)) + newAngle += 360; + while (newAngle > (lastAngle + 180)) + newAngle -= 360; return newAngle; } - //Not the actual gyro, but I am passing it through the OI.java to get it here - public void setGyro(double value){ + + /** + * Sets the gyro value, used to switch between field and robot orientation + * + * @param value The value to set the gyro to + */ + public void setGyro(double value) { gyroValue = value; } - //This is the method that is called to drive the robot in the 2D plane - public void drive2D(double JoystickX, double JoystickY) { + + /** + * This method is used to drive the robot in 2D without turning, using the joystick values. + * + * @param JoystickX The x value of the joystick + * @param JoystickY The y value of the joystick + */ + public void drive2D(double JoystickX, double JoystickY) { checkContextOwnership(); - //logs(); - //double power = pythagorean((JoystickX), correctedJoysticks(JoystickY))/Math.sqrt(2); - double power = Math.max(Math.abs(JoystickX),Math.abs(JoystickY)); - double angle = fieldAngle(getAngle(JoystickX, JoystickY),gyroValue); - log("Given angle: " + getAngle(JoystickX,JoystickY) + " || Gyro: " + gyroValue + " || New angle: " + angle); - //Temporary Drive code, kinda sucks + // double power = pythagorean((JoystickX), correctedJoysticks(JoystickY))/Math.sqrt(2); + double power = Math.max(Math.abs(JoystickX), Math.abs(JoystickY)); + double angle = fieldAngle(getAngle(JoystickX, JoystickY), gyroValue); + log("Given angle: " + getAngle(JoystickX, JoystickY) + " || Gyro: " + gyroValue + + " || New angle: " + angle); + // Temporary Drive code, kinda sucks m_DriveFrontRight.set(power); m_DriveFrontLeft.set(power); m_DriveBackRight.set(power); m_DriveBackLeft.set(power); - //Steer code - setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); - setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontLeft))); - setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerBackRight))); - setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerBackLeft))); - } - + // Steer code + setFrontRightAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackLeft.getSensorPosition())); + } + + /** + * This method is used to drive the robot in 2D without turning, using a point. + * + * @param joystick The point to use for the joystick values + */ public void drive2D(Point joystick) { drive2D(joystick.getX(), joystick.getY()); } - - - public void stopDriveMotors() { + /** + * This method stops all of the drive motors + */ + public void stopDriveMotors() { checkContextOwnership(); m_DriveFrontRight.stopMotor(); m_DriveFrontLeft.stopMotor(); m_DriveBackRight.stopMotor(); m_DriveBackLeft.stopMotor(); } + + /** + * This method stops all of the steer motors + */ public void stopSteerMotors() { checkContextOwnership(); m_SteerFrontRight.stopMotor(); @@ -212,11 +318,17 @@ public void stopSteerMotors() { m_SteerBackLeft.stopMotor(); } - - public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta){ + /** + * This method is the main method for driving the robot, using the joystick values. + * + * @param JoystickX The x value of the joystick + * @param JoystickY The y value of the joystick + * @param JoystickTheta The theta value of the joystick (for turning) + */ + public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta) { checkContextOwnership(); - double power = Math.max(Math.abs(JoystickX),Math.abs(JoystickY)); - double angle = fieldAngle(getAngle(JoystickX, JoystickY),gyroValue); + double power = Math.max(Math.abs(JoystickX), Math.abs(JoystickY)); + double angle = fieldAngle(getAngle(JoystickX, JoystickY), gyroValue); double frPower; double flPower; double brPower; @@ -225,63 +337,85 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta double flAngle; double brAngle; double blAngle; - if(JoystickTheta >= 0){ + if (JoystickTheta >= 0) { frPower = NewMag(power, angle, JoystickTheta, 135); flPower = NewMag(power, angle, JoystickTheta, 45); brPower = NewMag(power, angle, JoystickTheta, -135); blPower = NewMag(power, angle, JoystickTheta, -45); - frAngle = NewAng(power, angle, JoystickTheta, 45); - flAngle = NewAng(power, angle, JoystickTheta, -45); - brAngle = NewAng(power, angle, JoystickTheta, 135); - blAngle = NewAng(power, angle, JoystickTheta, -135); - } - else{ + frAngle = NewAng(power, angle, JoystickTheta, 135); + flAngle = NewAng(power, angle, JoystickTheta, 45); + brAngle = NewAng(power, angle, JoystickTheta, -135); + blAngle = NewAng(power, angle, JoystickTheta, -45); + } else { frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); flPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); - frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); - flAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); - brAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); - blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); + frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + flAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); + brAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); + blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); } - if(Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)) > 1){ - frPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); - flPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); - brPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); - blPower /= Math.max(Math.max(frPower,flPower), Math.max(brPower,blPower)); + if (Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)) > 1) { + frPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); + flPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); + brPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); + blPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); } m_DriveFrontRight.set(frPower); m_DriveFrontLeft.set(flPower); m_DriveBackRight.set(brPower); m_DriveBackLeft.set(blPower); - //Steer code - setFrontRightAngle(newAngle(frAngle, getCurrentAngle(m_SteerFrontRight))); - setFrontLeftAngle(newAngle(flAngle, getCurrentAngle(m_SteerFrontLeft))); - setBackRightAngle(newAngle(brAngle, getCurrentAngle(m_SteerBackRight))); - setBackLeftAngle(newAngle(blAngle, getCurrentAngle(m_SteerBackLeft))); - } + // Steer code + setFrontRightAngle(newAngle(frAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(flAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(brAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(blAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackLeft.getSensorPosition())); + } + + /** + * This method is used to drive the robot with swerve using a PointDir + * + * @param joystick The PointDir to use for the joystick values + */ public void swerveDrive(PointDir joystick) { swerveDrive(joystick.getY(), -1 * joystick.getX(), joystick.getHeading()); } - - public void turning(double Joystick){ + + /** + * This method is used to simply turn the robot without moving it + * + * @param Joystick The joystick value to use for turning + */ + public void turning(double Joystick) { checkContextOwnership(); - if(Joystick > 0){ - setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); - setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); - setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); - setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); + if (Joystick > 0) { + setFrontRightAngle(newAngle(135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(-135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(-45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackLeft.getSensorPosition())); m_DriveFrontRight.set(Math.abs(Joystick)); m_DriveFrontLeft.set(Math.abs(Joystick)); m_DriveBackRight.set(Math.abs(Joystick)); m_DriveBackLeft.set(Math.abs(Joystick)); } - if(Joystick < 0){ - setFrontRightAngle(newAngle(-45, getCurrentAngle(m_SteerFrontRight))); - setFrontLeftAngle(newAngle(-135, getCurrentAngle(m_SteerFrontLeft))); - setBackRightAngle(newAngle(45, getCurrentAngle(m_SteerBackRight))); - setBackLeftAngle(newAngle(135, getCurrentAngle(m_SteerBackLeft))); + if (Joystick < 0) { + setFrontRightAngle(newAngle(-45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontRight.getSensorPosition())); + setFrontLeftAngle(newAngle(-135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerFrontLeft.getSensorPosition())); + setBackRightAngle(newAngle(45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackRight.getSensorPosition())); + setBackLeftAngle(newAngle(135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) + * m_SteerBackLeft.getSensorPosition())); m_DriveFrontRight.set(Math.abs(Joystick)); m_DriveFrontLeft.set(Math.abs(Joystick)); m_DriveBackRight.set(Math.abs(Joystick)); @@ -289,59 +423,100 @@ public void turning(double Joystick){ } } - private double getCurrentAngle(MotorController motor) { - return Math.pow((2048.0/360.0 * (150.0/7.0)), -1) * motor.getSensorPosition(); - } - - //Logging the encoder values (also I love Github Copilot <3) - public void logs(){ - log("Front Right Encoder: " + getFrontRight() + " Front Left Encoder: " + getFrontLeft() + " Back Right Encoder: " + getBackRight() + " Back Left Encoder: " + getBackLeft()); - } - public void setFrontRightEncoders(){ - m_SteerFrontRight.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontRight.getAbsolutePosition())); - } - public void setFrontLeftEncoders(){ - m_SteerFrontLeft.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontLeft.getAbsolutePosition())); - //log("New encoder value: " + (int)Math.round(2048.0/360.0 * (150.0/7.0) * e_FrontLeft.getAbsolutePosition()) + " || Motor value: " + m_SteerFrontLeft.getSensorPosition()); - } - public void setBackRightEncoders(){ - m_SteerBackRight.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_BackRight.getAbsolutePosition())); - } - public void setBackLeftEncoders(){ - m_SteerBackLeft.setSensorPosition((int)Math.round(2048.0/360.0 * (150.0/7.0) * e_BackLeft.getAbsolutePosition())); - } - //To control each steering individually with a PID - public void setFrontRightAngle(double angle){ - //log("Angle: " + getFrontRight() + " || Motor angle: " + 360.0/ 2048.0 * m_SteerFrontRight.getSensorPosition()); - m_SteerFrontRight.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); - } - public void setFrontLeftAngle(double angle){ - //log("Angle: " + getFrontLeft() + " || Motor angle: " + Math.pow((2048.0/360.0 * (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); - //log("Angle: %f Motor angle: %f", getFrontLeft(), Math.pow((2048.0/360.0 * (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); - m_SteerFrontLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); - } - public void setBackRightAngle(double angle){ - //log("Angle: " + getBackRight() + " || Motor angle: " + m_SteerBackRight.getSensorPosition()); - m_SteerBackRight.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); - } - public void setBackLeftAngle(double angle){ - //log("Angle: " + getBackLeft() + " || Motor angle: " + m_SteerBackLeft.getSensorPosition()); - m_SteerBackLeft.set(ControlMode.Position, 2048.0/360.0 * (150.0/7.0) * angle); - } - public void setSFR(double angle){ - setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); + /** + * Simple encoder logging method + */ + public void logs() { + log("Front Right Encoder: " + getFrontRight() + " Front Left Encoder: " + getFrontLeft() + + " Back Right Encoder: " + getBackRight() + " Back Left Encoder: " + + getBackLeft()); } - public void setSFL(double angle){ - setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); - } - public void setSBR(double angle){ - setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); - } - public void setSBL(double angle){ - setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); - } - public void configPID(){ - //PID for turning the various steering motors. Here is a good link to a tuning website: https://www.robotsforroboticists.com/pid-control/ + + /** + * This method is used to set the front right encoder to the true position + */ + public void setFrontRightEncoders() { + m_SteerFrontRight.setSensorPosition((int) Math + .round(2048.0 / 360.0 * (150.0 / 7.0) * e_FrontRight.getAbsolutePosition())); + } + + /** + * This method is used to set the front left encoder to the true position + */ + public void setFrontLeftEncoders() { + m_SteerFrontLeft.setSensorPosition((int) Math + .round(2048.0 / 360.0 * (150.0 / 7.0) * e_FrontLeft.getAbsolutePosition())); + + } + + /** + * This method is used to set the back right encoder to the true position + */ + public void setBackRightEncoders() { + m_SteerBackRight.setSensorPosition((int) Math + .round(2048.0 / 360.0 * (150.0 / 7.0) * e_BackRight.getAbsolutePosition())); + } + + /** + * This method is used to set the back left encoder to the true position + */ + public void setBackLeftEncoders() { + m_SteerBackLeft.setSensorPosition((int) Math + .round(2048.0 / 360.0 * (150.0 / 7.0) * e_BackLeft.getAbsolutePosition())); + } + + // To control each steering individually with a PID + + /** + * This method is used to set the front right steering motor to a certain angle. This uses a PID controller. + * + * @param angle The angle to set the front right wheel to + */ + public void setFrontRightAngle(double angle) { + // log("Angle: " + getFrontRight() + " || Motor angle: " + 360.0/ 2048.0 * + // m_SteerFrontRight.getSensorPosition()); + m_SteerFrontRight.set(ControlMode.Position, 2048.0 / 360.0 * (150.0 / 7.0) * angle); + } + + /** + * This method is used to set the front left steering motor to a certain angle. This uses a PID controller. + * + * @param angle The angle to set the front left wheel to + */ + public void setFrontLeftAngle(double angle) { + // log("Angle: " + getFrontLeft() + " || Motor angle: " + Math.pow((2048.0/360.0 * + // (150.0/7.0)),-1) * m_SteerFrontLeft.getSensorPosition()); + m_SteerFrontLeft.set(ControlMode.Position, 2048.0 / 360.0 * (150.0 / 7.0) * angle); + } + + /** + * This method is used to set the back right steering motor to a certain angle. This uses a PID controller. + * + * @param angle The angle to set the back right wheel to + */ + public void setBackRightAngle(double angle) { + // log("Angle: " + getBackRight() + " || Motor angle: " + + // m_SteerBackRight.getSensorPosition()); + m_SteerBackRight.set(ControlMode.Position, 2048.0 / 360.0 * (150.0 / 7.0) * angle); + } + + /** + * This method is used to set the back left steering motor to a certain angle. This uses a PID controller. + * + * @param angle The angle to set the back left wheel to + */ + public void setBackLeftAngle(double angle) { + // log("Angle: " + getBackLeft() + " || Motor angle: " + + // m_SteerBackLeft.getSensorPosition()); + m_SteerBackLeft.set(ControlMode.Position, 2048.0 / 360.0 * (150.0 / 7.0) * angle); + } + + /** + * Method to configure PID values. The values were pre-tuned and are not expected to change. + */ + public void configPID() { + // PID for turning the various steering motors. Here is a good link to a tuning website: + // https://www.robotsforroboticists.com/pid-control/ m_SteerFrontRight.setP(0.2); m_SteerFrontRight.setI(0); m_SteerFrontRight.setD(0.1); @@ -351,7 +526,7 @@ public void configPID(){ m_SteerFrontLeft.setI(0); m_SteerFrontLeft.setD(0.1); m_SteerFrontLeft.setFF(0); - + m_SteerBackRight.setP(0.2); m_SteerBackRight.setI(0); m_SteerBackRight.setD(0.1); @@ -362,26 +537,30 @@ public void configPID(){ m_SteerBackLeft.setD(0.1); m_SteerBackLeft.setFF(0); - //pid values from sds for Flacons 500: P = 0.2 I = 0.0 D = 0.1 FF = 0.0 + // pid values from sds for Flacons 500: P = 0.2 I = 0.0 D = 0.1 FF = 0.0 - //IDK what those do tbh, but I like to keep them here. - //m_SteerFrontRight.setSensorInverted(false); - //m_SteerFrontLeft.setSensorInverted(false); - //m_SteerBackRight.setSensorInverted(false); - //m_SteerBackLeft.setSensorInverted(false); + // Code to invert sensors if needed. Recommended to do this in phoenix tuner. + // m_SteerFrontRight.setSensorInverted(false); + // m_SteerFrontLeft.setSensorInverted(false); + // m_SteerBackRight.setSensorInverted(false); + // m_SteerBackLeft.setSensorInverted(false); } - //Method to get the encoder values, the encoders are in degrees from -180 to 180. To change that, we need to change the syntax and use getPosition() - public double getFrontRight(){ + // Methods to get the encoder values, the encoders are in degrees from -180 to 180. To change + // that, we need to change the syntax and use getPosition() + public double getFrontRight() { return e_FrontRight.getAbsolutePosition(); } - public double getFrontLeft(){ + + public double getFrontLeft() { return e_FrontLeft.getAbsolutePosition(); } - public double getBackRight(){ + + public double getBackRight() { return e_BackRight.getAbsolutePosition(); } - public double getBackLeft(){ + + public double getBackLeft() { return e_BackLeft.getAbsolutePosition(); } @@ -389,18 +568,14 @@ public PointDir getCurrentPosition() { return currentPosition; } + //TODO: find why resetCurrentPosition() is not a thing public void resetCurrentPosition() { - swerveOdometry.setCurrentPosition(new Point(0, 0)); - } - public void setCross() { - checkContextOwnership(); - setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); - setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); - setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); - setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); + swerveOdometry.resetCurrentPosition(); } - - + + /** + * This method is used to reset the drive encoders. + */ public void resetDriveEncoders() { m_DriveBackLeft.setSensorPosition(0); m_DriveBackRight.setSensorPosition(0); @@ -408,12 +583,12 @@ public void resetDriveEncoders() { m_DriveFrontRight.setSensorPosition(0); } - //Odometry + // Odometry @Override public void run() { currentPosition = swerveOdometry.run(); - log (currentPosition.toString()); + log(currentPosition.toString()); } } -//AS \ No newline at end of file +// AS From 637036ff96b9bd87a0d6db587db7736569e5ea81 Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Wed, 15 Feb 2023 18:33:15 -0800 Subject: [PATCH 051/103] Reverted resetCurretPosition and setCross --- src/main/java/com/team766/robot/mechanisms/Drive.java | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index bfd3c426..362a47fb 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -568,9 +568,16 @@ public PointDir getCurrentPosition() { return currentPosition; } - //TODO: find why resetCurrentPosition() is not a thing public void resetCurrentPosition() { - swerveOdometry.resetCurrentPosition(); + swerveOdometry.setCurrentPosition(new Point(0, 0)); + } + + public void setCross() { + checkContextOwnership(); + setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); + setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); + setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); + setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); } /** From 417a0bb6b2cc94acf24431e2f27e5fcd0d43d92a Mon Sep 17 00:00:00 2001 From: Prem Netsuwan Date: Wed, 15 Feb 2023 18:34:17 -0800 Subject: [PATCH 052/103] Deleted setCross --- src/main/java/com/team766/robot/mechanisms/Drive.java | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 362a47fb..bba3bd22 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -572,14 +572,6 @@ public void resetCurrentPosition() { swerveOdometry.setCurrentPosition(new Point(0, 0)); } - public void setCross() { - checkContextOwnership(); - setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); - setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); - setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); - setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); - } - /** * This method is used to reset the drive encoders. */ From fd5f482d80ecf39f241dc4688ea90831db14ca73 Mon Sep 17 00:00:00 2001 From: SauquetAlex <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 15 Feb 2023 23:20:24 -0800 Subject: [PATCH 053/103] Fixed weird bug --- .../com/team766/robot/mechanisms/Drive.java | 102 +++++++++--------- 1 file changed, 51 insertions(+), 51 deletions(-) diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index bba3bd22..09fa3086 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -20,7 +20,7 @@ import com.team766.odometry.Odometry; import com.team766.odometry.Point; import com.team766.odometry.PointDir; - +import com.team766.hal.MotorControllerCommandFailedException; public class Drive extends Mechanism { @@ -78,13 +78,13 @@ public Drive() { config.sensorDirection = true; // initialize the encoders - e_FrontRight = new CANCoder(1); + e_FrontRight = new CANCoder(1, "Swerve"); // e_FrontRight.configAllSettings(config, 250); - e_FrontLeft = new CANCoder(2); + e_FrontLeft = new CANCoder(2, "Swerve"); // e_FrontLeft.configAllSettings(config, 250); - e_BackRight = new CANCoder(4); + e_BackRight = new CANCoder(4, "Swerve"); // e_BackRight.configAllSettings(config, 250); - e_BackLeft = new CANCoder(3); + e_BackLeft = new CANCoder(3, "Swerve"); // e_BackLeft.configAllSettings(config, 250); @@ -277,14 +277,10 @@ public void drive2D(double JoystickX, double JoystickY) { m_DriveBackRight.set(power); m_DriveBackLeft.set(power); // Steer code - setFrontRightAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(angle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackLeft.getSensorPosition())); + setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerBackLeft))); } /** @@ -342,19 +338,19 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta flPower = NewMag(power, angle, JoystickTheta, 45); brPower = NewMag(power, angle, JoystickTheta, -135); blPower = NewMag(power, angle, JoystickTheta, -45); - frAngle = NewAng(power, angle, JoystickTheta, 135); - flAngle = NewAng(power, angle, JoystickTheta, 45); - brAngle = NewAng(power, angle, JoystickTheta, -135); - blAngle = NewAng(power, angle, JoystickTheta, -45); + frAngle = NewAng(power, angle, JoystickTheta, 45); + flAngle = NewAng(power, angle, JoystickTheta, -45); + brAngle = NewAng(power, angle, JoystickTheta, 135); + blAngle = NewAng(power, angle, JoystickTheta, -135); } else { frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); flPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); - frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); - flAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); - brAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); - blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); + frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); + flAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); + brAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); } if (Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)) > 1) { frPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); @@ -367,14 +363,10 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta m_DriveBackRight.set(brPower); m_DriveBackLeft.set(blPower); // Steer code - setFrontRightAngle(newAngle(frAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(flAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(brAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(blAngle, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackLeft.getSensorPosition())); + setFrontRightAngle(newAngle(frAngle, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(flAngle, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(brAngle, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(blAngle, getCurrentAngle(m_SteerBackLeft))); } /** @@ -394,28 +386,20 @@ public void swerveDrive(PointDir joystick) { public void turning(double Joystick) { checkContextOwnership(); if (Joystick > 0) { - setFrontRightAngle(newAngle(135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(-135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(-45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackLeft.getSensorPosition())); + setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); m_DriveFrontRight.set(Math.abs(Joystick)); m_DriveFrontLeft.set(Math.abs(Joystick)); m_DriveBackRight.set(Math.abs(Joystick)); m_DriveBackLeft.set(Math.abs(Joystick)); } if (Joystick < 0) { - setFrontRightAngle(newAngle(-45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontRight.getSensorPosition())); - setFrontLeftAngle(newAngle(-135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerFrontLeft.getSensorPosition())); - setBackRightAngle(newAngle(45, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackRight.getSensorPosition())); - setBackLeftAngle(newAngle(135, Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) - * m_SteerBackLeft.getSensorPosition())); + setFrontRightAngle(newAngle(-45, getCurrentAngle(m_SteerFrontRight))); + setFrontLeftAngle(newAngle(-135, getCurrentAngle(m_SteerFrontLeft))); + setBackRightAngle(newAngle(45, getCurrentAngle(m_SteerBackRight))); + setBackLeftAngle(newAngle(135, getCurrentAngle(m_SteerBackLeft))); m_DriveFrontRight.set(Math.abs(Joystick)); m_DriveFrontLeft.set(Math.abs(Joystick)); m_DriveBackRight.set(Math.abs(Joystick)); @@ -423,6 +407,10 @@ public void turning(double Joystick) { } } + private double getCurrentAngle(MotorController motor) { + return Math.pow((2048.0 / 360.0 * (150.0 / 7.0)), -1) * motor.getSensorPosition(); + } + /** * Simple encoder logging method */ @@ -431,7 +419,7 @@ public void logs() { + " Back Right Encoder: " + getBackRight() + " Back Left Encoder: " + getBackLeft()); } - + /** * This method is used to set the front right encoder to the true position */ @@ -468,7 +456,8 @@ public void setBackLeftEncoders() { // To control each steering individually with a PID /** - * This method is used to set the front right steering motor to a certain angle. This uses a PID controller. + * This method is used to set the front right steering motor to a certain angle. This uses a PID + * controller. * * @param angle The angle to set the front right wheel to */ @@ -479,7 +468,8 @@ public void setFrontRightAngle(double angle) { } /** - * This method is used to set the front left steering motor to a certain angle. This uses a PID controller. + * This method is used to set the front left steering motor to a certain angle. This uses a PID + * controller. * * @param angle The angle to set the front left wheel to */ @@ -490,7 +480,8 @@ public void setFrontLeftAngle(double angle) { } /** - * This method is used to set the back right steering motor to a certain angle. This uses a PID controller. + * This method is used to set the back right steering motor to a certain angle. This uses a PID + * controller. * * @param angle The angle to set the back right wheel to */ @@ -501,7 +492,8 @@ public void setBackRightAngle(double angle) { } /** - * This method is used to set the back left steering motor to a certain angle. This uses a PID controller. + * This method is used to set the back left steering motor to a certain angle. This uses a PID + * controller. * * @param angle The angle to set the back left wheel to */ @@ -568,10 +560,18 @@ public PointDir getCurrentPosition() { return currentPosition; } + public void setCross() { + checkContextOwnership(); + setBackLeftAngle(newAngle(-45, getCurrentAngle(m_SteerBackLeft))); + setFrontLeftAngle(newAngle(45, getCurrentAngle(m_SteerFrontLeft))); + setFrontRightAngle(newAngle(135, getCurrentAngle(m_SteerFrontRight))); + setBackRightAngle(newAngle(-135, getCurrentAngle(m_SteerBackRight))); + } + public void resetCurrentPosition() { swerveOdometry.setCurrentPosition(new Point(0, 0)); } - + /** * This method is used to reset the drive encoders. */ From f549517fba185f568503036d80064de7c8768db2 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Fri, 17 Feb 2023 19:29:45 -0800 Subject: [PATCH 054/103] Fixed critical points not parsing --- .../java/com/team766/robot/procedures/FollowPoints.java | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 96854d2d..b6808e5e 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -42,6 +42,8 @@ public static class Step { public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { this.wayPoint = wayPoint; this.procedure = procedure; + this.criticalPoint = criticalPoint; + this.stopRobot = stopRobot; } } @@ -103,6 +105,7 @@ public FollowPoints(String file) throws IOException { */ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { steps.add(new Step(wayPoint, criticalPoint, procedure, stopRobot)); + log(criticalPoint? "true" : "false"); } /** @@ -110,7 +113,9 @@ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedu */ public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); - addStep(new PointDir(4,0, 90), true, null /* don't execute procedure */, false); + addStep(new PointDir(4,0, 90), false, null /* don't execute procedure */, false); + addStep(new PointDir(4,4, 0), false, new DoNothing(), false); + addStep(new PointDir(0,4, 90), false, null /* don't execute procedure */, false); addStep(new PointDir(0,0, 0), false, new DoNothing(), false); addWaypoints(); } @@ -313,7 +318,7 @@ private static Point selectTargetPoint(int targetNum, Point[] pointList) { */ private boolean passedPoint(Point P) { log(currentPos + " " + P + " " + currentPos.distance(P) + " " + ((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2) ? " true" : " false")); - return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2); + return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.4); } /** From 656fc6bd156aa6fbc74f86ec593c09c61bd6f0a0 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 18 Feb 2023 14:33:13 -0800 Subject: [PATCH 055/103] added image displayer (with interlacing) --- src/main/deploy/cone-2.png | Bin 0 -> 6078 bytes src/main/deploy/cone.png | Bin 0 -> 5719 bytes src/main/deploy/cube-2.png | Bin 0 -> 270 bytes src/main/deploy/cube-old.png | Bin 0 -> 1330 bytes src/main/deploy/cube.png | Bin 0 -> 5753 bytes src/main/deploy/progamer.png | Bin 0 -> 1586 bytes src/main/deploy/shulker_box.png | Bin 0 -> 6238 bytes src/main/java/com/team766/robot/OI.java | 13 +++ src/main/java/com/team766/robot/Robot.java | 4 +- .../team766/robot/mechanisms/CANdleMech.java | 61 +++++++++++ .../robot/procedures/DisplayImage.java | 101 ++++++++++++++++++ 11 files changed, 177 insertions(+), 2 deletions(-) create mode 100644 src/main/deploy/cone-2.png create mode 100644 src/main/deploy/cone.png create mode 100644 src/main/deploy/cube-2.png create mode 100644 src/main/deploy/cube-old.png create mode 100644 src/main/deploy/cube.png create mode 100644 src/main/deploy/progamer.png create mode 100644 src/main/deploy/shulker_box.png create mode 100644 src/main/java/com/team766/robot/mechanisms/CANdleMech.java create mode 100644 src/main/java/com/team766/robot/procedures/DisplayImage.java diff --git a/src/main/deploy/cone-2.png b/src/main/deploy/cone-2.png new file mode 100644 index 0000000000000000000000000000000000000000..d42301846adb624481c417dca1089fd879d6d837 GIT binary patch literal 6078 zcmeHLd011&9u13vEQ+A0EE)qpOQd4HAR0!?*GgbCtQ7E3 zDCM2UD}?DSR(ieHtpBTh>ta|s<8|i4$?M+6XC9~w2)Y+aZ>aY6obHT%|a4XW9j$9~g0-4A)3Zkp=R&9*!{?fSmGk3`)$*lGpTvH0=fp3)|fQ$py~ z4a%jds{@KHehT$=EWn&KMZYj!2*>Co>nCV#zWi))Yw8^J=ZpL{U}V7^w%(T-&u!Vb z`gRW?R5!!t9{p_D-1u`fj1^aYR)mEtOLKU$b7@@du7<+2U#hbHXsnynm)U4I>&!#C zC&?kZ;b~!#c69UaH{0skT_ub#9&1~~l(NFFmtTo^$euj2qGA0j)0GE(t<0UR*!$fQ z-xOxq`0CxIZYHkCzCdE;S8P?Fs6Tloe#H}Typt=RTWU8&?<*0lz7j-SbXR+aFWWQc zyvS)oVSG`<_Rki(-xr-q2z5L?hwt0+(8wQ^bTQYfQhj}CPgJvw3wuS5{#4_d$2R1H z7G?aom(^FIi}tR&;UAfzo}?Z1>Gt_*>P|bXJf5dfr_WEHyk2LR^U~Kd^r(S>c14jl4;=bz$dTowBsXxDTwN(T7~o~|>Uv3SLFKEvS6q(h&w>6-wa_hr%lNC4XbR$0kCwkVeqpm}#dTPD2^yE#%*~(u_5#Ov}A? z3+FLsdAsJ}8}54A$$rI&qFdGT73Z&RdFoaEEG>Wc^$gN9Fno&-7J$Cil@>k8q zZm0Fa+0}dBqOTu2nbjS$KDV;d@AU~AliiPgH!bP;^3lbz_W$-p1g1>u&-0knwuExz zL1swK=lRJF^_vUleSczuozv?MZJWvRy9hN9XHU#_X^D|%x+FUWAs{n;3=Wnm7do<~M5?p;*UkJPM_@MZjRNnGD8Ix&TQc zKmJR)_YW?!lba6tc-SPw8mzg*-cy{qRld{4_`I9o(=+X1(zbba0&o8ivq`@tBsy;k z(wY?>Y92Dl^{Lj6zg%G6@bGzSYkem5S^6Jy@Aur_Rn>{ww+uRR+kQ$>9(cU!r zU1r)?)=ulws#zCheCY7q17Ui9ZaDQgV;TCSu3blIZ+vv)RiktLdLaVg#u7DmXXc5r zlBd(J*XW0Yl-aMHR(@A4xj=q7)9munB~~*wb&=j2GQ%r%UmmZBkJ|IcOSMbv6WQWT ziHxvf@7o=7JD;>YYOJw8*4K;b43ge{aDAH=$m_8JkiUajzBH~_XbbVg9N1PVlz{w> zLOD7sB@j0XmZLdvxIje5bXL`1&;lMEv%;Q*XGs`vgupva3J1jb1#;t}xKtj-*-6Jy zNdp2xSPr3;!f26hTIO(7r zr93{(-`#Ui0zA<%5pubNhQlco3R?xqRxAz25vWuu4o}1piCBQZ%GQeHkP<7BSs)Sv z8t$-+D-}rO0` z7KjW6^j?N65PS{d{9&0mM#_afVquZoVzdO0JIt5FNTXHL;c;#oE~uVJwG8=3^-&A_PGM5+83z93{mR$>flT3nNlM z+*SZ|$UF*(OW@mKd3YiLYsaM!u~a_zfH`D7flq*`c!)YmVyRRBb|n-&Ix0kp2c#f- z5{F14^00WANW$8Y@GzFjgQ!?O#hy7@{qHq=g*~$@zc)&VWF~6DwpRU4a5293Y1fKM7<9vV*-HoAJe1sN0z^Hk#kt${9X1SATFLH-!rutV*F_iP3SjsqVeIZ&`< zBE-Ymkzp#9!sYO=RI(k_fk%SK;67GeCg#f(kQ8Ct^n|qhfG_lf@w!V`#RHxWD+}r~-^iF@QJF22vNugt*~UIOrFWbpFLMxDNl~ z2tfMdAQSTUqg@~Enveq%0)O0HAMKiu0}}#&++F`SyL3igreG2H1*8D4O09V_Pk`5~ zDH89`WGIxb5pt=a^73bcMlCs$<)PK8Za5QVblX^X6#Ua>%5--Pq)b;c(Cq9{1CV}j z{o|tkkC}tSaRvJ7T~Nq1UKv*aA*#Kq8;_6rpup&n`)iSZFW+B2D1gBKZgd1Qt^fk~ zyYlY{AoG7W{15r?-U!|$k2j6?3XDg1x9=|k9|{#A-alpXE*~{~7KYaSec?B?8;l_~ zx2vOE;1*Sz=IEZ$vhs@d~*|1#O}N&RHi&<)2VQ^{$idEVDrBhtLL96Npbai0BAzu=3s8yC8o zo2M=9%-EZmpXDBDH+QXhVt}!3q zdZwx6YA+sr_B21ldEDy8ruK>VSKBl`Sl?YxprKW_XR(ius9E0oG@*RnNc9Py-40(s ziK`)Rw34Yi;hvf>HqfE-pDvOiSEq|v!3%>X{aiYO6Mo~^plZ)|D)OuEvJ-C%%9!cy z8aI4B6@p|%<9x2%Gal6EmPpGyd!|Z~zS@o4*rmy{|D@6JotP8Ru;BKXPQ%t1kIG9? z%Tsn2Ou6pbrnH?FQ&GQZNXTAI@uQ&5Qm-u)W#XXbxp#bW0^1Ml+a!8+?H^G3>=`}Z zBn&g`*la6LFBcv8Mr>2EYRUB@c6OQPD76&%5Pa4|j$2&Ewn4>$I+7+^df9V2HLJ8` zaAW#Mu`2n|gbQ|>992eZe&~~6b;j2Ax_3HKJ8L#a_>-OJ4_(BLy^-f;6&2k=GFbCw zur}v$bl-pZ`S`QaoR-=ipW;nZw|&aFf37os7lep^`t}^Ozu}_SO~KXto3Sqb$44v> zXC4oqTpeDw=5f&~&$7Dc?xPN3?8CJSj=Flxugw`LF8ATpFL9vp6G~g(tCC$R>ss-_ zfzk<*Qh(N+uebW1$aT0=pV^TY#2j-{?w2&w=5{RylwHU>V!sZ>Fmeq63640rnVQ)T+{x;L&e;w z53(9R+txf}mB!XDuiWjxL!Yem(v3%ogtp}OkJz>DFD%^S>?Lx}Y@eQeOFC)Z_Rre* zjQEaIAIy*8vQM0K>N<3;rkm8ZtW&eB$GyszRGVtQg&fv=;gD_dM(!co>_a)D$)ODL z4PoG;adziv2MfH()0^#1XxkhbSj%eOYTHk0Yus_!w}}8|kpd2n8Etc>auCGs{=wQ0nGnd{+Af6iV(q(@~BH66OBoet)B6+@#!S2mZ zT`vmzA@J>0&D+C6Ca*|x`S6syU`NIp{L{(q-;1#+mH&z}w2kIsVUe+3gX>qM1+0CS z?4f?oJ9cnTC;3?2acNCR_!GKMWyalgzl>^n+_Z6j2Wjgp`0EDV(2_i~xP`^qJb#4k zP8Vh%XU)*e&lgb-Zd(4^!+oo>I+EWiY<=&+Z?~elCfF{a-u1fZwAPenO1fAp>=?d! zjx;jkeCA1~eU!Un>(PzP0uOI@lj_u|;+vV0V~SmAt;1B~CF2Xn44d-xwEu`Np)0%H z)m4#5`Qk2*A>CKP^KMs8b2;hi8YWKv*z-)u5pjCbCvL-ipsbXKtG$=z#Imc;#Qi!a zaKz+sC!L>?4=+w|-~QFL;yA}!AMN^g)-1|54&2+{^`<6X{c-q_XO6L$W@(j8aDa5@ zo~q8bE*y4>jorgbao&5)W>q16I@{}X#PmsS%N}qZZTDiD9C|9MQxgh)>9IK_-?>4z zEKL%(Bdp=}sE#{r?N<-;%AfXKvJzBGDO83YX5MGif0vEQw9^x2O0S zlqx7Pcv>F?=!vNDIIf2njO65GdNPNuGpHFXp-{+RvKeeP4S3LuDOwyh(X_^~1ciko z7&RgWOpjwaErsBO6}pAEh)Mb2&SucbPmCEE+ z1R;SM)9B48AodHMIHu|s>xJBi5py{M69I55?+f0~Yd1RsFPRJq)*%at^rXQeDiI%2 z>JUr`nIBb3CCe8Tz%;Is&82a9Di%%1frT`lFM{&f2#?9wMHD)A}B!x$mtm1 zQTcM&d^QK6A+V4|<1z&*nt;bbX+l0%$YUcy1&7TaKoMcUz^a532WCZ3DFGFq!}sO! z5Fw2z{d9aOXih0gWkum;?NEN=%jV-@J+KL-DgrdKhK|@l(tu%btotKeY5L-9*g1 znJ5(Vwt!&7Qi2gqLY3w`0heV6iHEgn6r3M@3--Akd&OcG7Jqr8u0=fR3t#2Ow&JYyJn;@^H z?;E+^$n{zZyq5Eu)%8ZM*HYlMoZqaj|CwC&{V!9f7W@a43|^Iv54($i*Q}xXu(?JO z$zeG0u_5KR94>Wsuj7@P7z+Ss`o1e^&QjtKpS8zGUo+0IcAOTKRH@f9&_C^k?3{ zZlSY)ZLA#D2<3~dw!WAa%R~iX?+1X671NI(k$|_w)na@BV8MVpNW&Uupf?zL8DPbL chnHM|1+=;m6P)~8%GJcPG-PIQg*a}-?;h!W1^@s6 literal 0 HcmV?d00001 diff --git a/src/main/deploy/cube-2.png b/src/main/deploy/cube-2.png new file mode 100644 index 0000000000000000000000000000000000000000..bd5037baa11d5e73a644eea2b29007da40c96559 GIT binary patch literal 270 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`jKx9jP7LeL$-D$|Tv8)E(|mmy zw18|52FCVG1{RPKAeI7R1_tH@j10^`nh_+nfC(-uuz(rC1}QWNE&K$eDm+~rLo5W7 z6C^%02;OAhyy)M5_K)^9%)uvuG~R4t_9>|K(J*q!a0~BGVo;oY(X{!823ta~gGUeR zd?w%Y9pRGe-XE3Ivxs%*Nt^K0BDUf5vH9_W>kefz?7HqCRbS&Ie)KWZjG&a>_woN4 lI1gv8iBnj@xvsjxfZ^*(jnX~RT_6uKc)I$ztaD0e0svXpN}vD$ literal 0 HcmV?d00001 diff --git a/src/main/deploy/cube-old.png b/src/main/deploy/cube-old.png new file mode 100644 index 0000000000000000000000000000000000000000..d08c8b8ec6ae6de3918e21b5329150827010e796 GIT binary patch literal 1330 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61SBU+%rIkMU~J8Fb`J1#c2+1T%1_J8No8Qr zm{>c}*5j~)MBDvkUaneAWdemK0_Lvi=qj0_C3es$Q+vy+grb-7CYc^VF*2;zo0{#r zL)pdCV`XDl9Y3%ixq8&|qN~>*JXFyEr>%Rw?bB(fItwuJ-=-<%08`#(sbPBKVUUbB)qRnajN070nf8moHhq z7jBR64C*-Fd7O8b!bj!nsnhRUh|7vqq@6giIbYS>Xf!d15ki>$ftx z*n6(uzV(CPh5fuSG22Zm`FGr5Y@1hda)QiBe{T(uhVRC|mdO}YaDQ31vo?F~<1dUS z0@hE21sKW7pWwic=P&29n;NtU=qlsM<-=BDPAFgO>bCYGe8D3oWGWGJ|M`UZqI z@`*DrFiU&7IEHA5G72!i{{z%RW59@Jez4+3G!Zy=?R|eBn+47XGJvXgJ;_EEfw0|V zrosh52^RwJs75vgY6HY2$R@$eVL(<56ht@)O#-3;(+Gr<;6~zSAZ&oB`}FHEgu%xq zi&ZDO23+dkn$a~-#|EI+A+ZLuhp?xSRRc9ZlLo;Q0rvy#88;>>FD}y9T?n$t)78&q Iol`;+0E@Z=S^xk5 literal 0 HcmV?d00001 diff --git a/src/main/deploy/cube.png b/src/main/deploy/cube.png new file mode 100644 index 0000000000000000000000000000000000000000..313f02c31c01acb2aa041460103bf058ca59d46c GIT binary patch literal 5753 zcmeHLX;f3!8VynbK?Y?I5i|zWfK75U4}uI~3JM~iLPhIMas#(yz$An)35eo6fKn|A z*7X$8qJk}2w5@e2Xe%m85wuPe1t%&}Z9%l>CKv+R*XLTV|I7;EobT+t&-d*!z|E@2 zh!AT_7fT!tXDtW~i~_&yupf(I;B#X^A`6Ezy^$UhtB!(G@ySYs1eGFqby_llN3^H} zhtsy~kDY($KfIAIn!F?;UygUT+WU)aoL9`N-fQi) zHU-eerlEv9O7bdPvsk$ulIQ*jgNQ)f_%7?qvI(9)8KRx38&1EE`V`E?9tTgx#*l zh$^ea?qS^x!8uMF>5FW}N`37kPF0Y%T3(LKAC++X^spM2X{8)hEAQIL;dUi4g)8$z zN0pS6%`S9!)KjxWxv5+*g-MK)H1F)lUw-cpN@UEV$CNtnJQ@0f_SY`Kya|c>DZ}rc zU>(Srv1^mH^MaZsLCy}h4;S7~SgN?!dMRZNv3=T)S*twkrjb2^FFY^tOW5g{J6;o) z=emb!LJUA{p^8Y{zN&N^@4$k(kp$~uh~JnLT7b#3g_Cm}_PBg*J$H0iYeAi=T${V? zR;|Qr(l=)7E>1@CW9!p?+R;8zMa=lUK4U^=_uWkw{PV1)FSFy{bWmMsC-yiC*E&W2 zRCf2L`IU*1v&zCybM6;=@8<9Qd2?~ncgvl&RbS~UYw>z;InAHB zaL%T(bDwKU2ifa+#kGP@qO+}w;;IlwO_ceW`~2+c4?pew z@$uP)xLWD9aq0XYEG-c9+ULmms~?sZP1;)jW&D@jhrZd}_{Hv?^V9Mh=jRt6+Y(W= za9QA(o!dX+ok=(OBqZQtejMprOYIo1KEl=L`kS9O%po2V`wA`mr)+)ahQ0!-sC0dlDy8wT(g-w>@q&sy0E^v&%(y6^2)AG;&-NH*ay~{-=kbrG;htb@YS6;o_({{tUEWQ zvo?DD^f;;QILigud2Xl5Za%x+1a(roPptX9`YB_` zsghTxZcWIzqnIl4$W6lGOqQd3ex!iUe|^%y`QDyY;1hbv&pH2QSy+(QQjOi>y2z4> zm8;d8y_`-2pi{rPzew3Jfq{lb#k&q~TAJs(W{&xogavN#!~K6VKizmna49J41=;hf zl~2~Uj=#}+W6QBl+|JqXzGmi#@?vDy9V&I(d`HuRc90)^^@vrUr4zp0ntSh$qboLa zrj9CYTk!l|dvw=i(@eq>*UQ#xw0T<19zCr-@h6ekIJ&EO#*!d2ai<$HtOPW>-hL1%rx7tubbqTs?Tn8 zJv(a#(IMwKy{F6-(pq&NsL4tyY3(+ti#+(LA}5c(s3Nra!T8R{9S^S^XYPO5hwGf9 zY;L=_#vEM98Wdc;vEeg$B87|$ixonItd%8$s~Ly$_SGiCq9jC(7a|F$+=tM4>^K3B zihT(4nBh=(G9O7qL(`Q=bb3ULC_PEU6%%}?TY77GKtP75VZ2r*m8*DKAA(Mo2ijPe zLcr@F>LedRYSP{;lA4-I zPNkC-$^;6P%jHra8iht90R%~vCRf8+l3eAEN$52K5tT@ZCaY0}9FJ+jLPd(&hd==1 z_}BT#lEcFd@^V$b3&0PG7EY#6$q+>*qZl((>L3je=}+jb3{?#H3r2}TREiX(2no_4 za<#j$gji(YC#NW-x^l!K3L-^h0ICABQU^^LA_$K(Ffa=eP+78$1gk>ZpkgL?NT!dg!K%9&M9S#c;GGPWnVoDfn5(D8vKnxL) zU@nctW(heg7~vX8%u=FYSHe=`tS~7tkP^cjp;#znl3*bXWFuzNNE|N0A|Yathzg6j zEIOB?lM;(~!3w1e2Fr=c-~@z{EKkr4V21PjBLzML8W|dhL`q?`1Q5U(K;>dZs%l^; z29+VvY8dmA3i4$$Sxh#S!=f|j>;ceRM5zLM5mTi?WI9bZf-MXWlmo1Vv7HJ8ba7A( zkFP{vwL%%AP)L0USWS*-8ryHZqlnDBVrvEacXeF-X9gNSu`0xkWJ zC=r$?AmIM!->|Ra=vy{}gd^s#xhydWhPc>%;xI@;h(jY$sT?5#f*`Jh&K#_+Qb^RP zuoCf406qe*zy{TMg(vnemFHl5Y9fNI1F(z)0o?)12$cR}DcFtix>|3_8-94}07h2~ z;OS%F>H;?*#c&n&`-NRP|Kh8E9sb1`fb{!G-pSwhcD=Xjog8>4@cZ5M-mZ6Y;GMwl zch~>TF3W+3DMSwb14;#tO3VJl+k(fe5y_!(Djd$r9{VxD6>oP2L36brJjndsu+ffQ z^mX>RGr*T*;{<{JF+@ibJJZe=*yGuoujq+Y;QeMCL_Qc2)#Hx-3ZBVv`u6^tvy3q& zhK@1R5Cn~2*COy~pkai+gT9r9egCI_0VTcI>%gG6K1mSjuffpQbM#%~wn1fR(ftVEI%sPc7iXXuBn?nw*w8kh>6t?Za5yA=hU1O#2m7!QK~O~Cfq+Fz F{{lXst_%PG literal 0 HcmV?d00001 diff --git a/src/main/deploy/progamer.png b/src/main/deploy/progamer.png new file mode 100644 index 0000000000000000000000000000000000000000..94842224b5e3894c43eb481f2258222b0eaaca25 GIT binary patch literal 1586 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4(FKU~J8Fb`J1#c2+1T%1_J8No8Qr zm{>c}*5j~)MBDvkUaneAWdemK0_Lvi=qj0_C3es$Q+vy+grb-7CYc^VF*2;zo0{#r zL)pdCV`XDl9Y3%ixq8&|qN~>*JXFyEr>%Rw?bB(fItwuJ-=-<%08`#(sbPBKVUUbB)qRnajN070nf8moHhq z7jBR64C*-Fd7O8b!bj!nsnhRUh|7vqq@6giIbYS>Xf!d15ki>$ftx z*n6(uzV(CPh5fuSG22Zm`FGr5Y@1hda)QiBe{T(uhVRC|mdO}YaDQ31vo?F~<1dUS z0@hE21sKW7pWHD+^I@TLGLBw6AbQR1ARo125-%B255jbsBRvUNf=4g&*Nu!X_VZ9Cw?R!_Hr*~g^4 z8LYiL;Nma_Rs%qqa*un1)hvh7kuV)-G~57*-E$f4A9xRy&P7uO;eM~~VNi4s1an@v zCWC3X0U!a+R*1r*+km#Ofv{mD$W@G~lNlIX85ls8!2ns&2(ukz2;2oQ6G1e{HY=zA sDDXhw7z2>T5{RQonSp_mdKI;Vst0MQ}|bN~PV literal 0 HcmV?d00001 diff --git a/src/main/deploy/shulker_box.png b/src/main/deploy/shulker_box.png new file mode 100644 index 0000000000000000000000000000000000000000..4828587d7a0521822a05f3583f40099295b2faa3 GIT binary patch literal 6238 zcmeHLc~n!^`b`3ad7hk&K`kgDGb9m|S+Ft`P_c@V;RaF?5|aQyi**1Iv`)2BQ7jI1 zD2hX&2q@}P1gF-jsGxv?Oa=*~36PNAxd9Q^@2&NgYrXfMcah|r@9e$L_w94;NiJF8 zp^ME;rkEfQ2=m||{|NAD1;30?;C;{Dcy|QC;O6?MXlVp91tSs*xja6Ek*10u3?$=m z5eQk`Zz}|snw`zmf4jUl3To=3O%l~K#O}Ukj#|@n<=nv%+ZARvqKnGr_$<}7DPE{E zEF)RX-!Gk&8QZh27IJH!UGOVO!KuG;er9q?!|eyD*C*K&9a|I`-KV70dVC%Aun)g2 zBF3^%X;_OJ?qF^&-n%)z{{?A(&Man{_dV}#O8C_-6=k9%!Hf5^JD%-4^tIx`qK%6$ zJo9{N-Rd^mA;o$*f>gmeaX<7%b9xqKcnzt`l{Z;$R%4HJ;pFXI$eOeT9U(tIKCY;G z5Q(cw$o34fIHgH`x#tJZJ%3nSE9`vqwrBXV|5W>bwrYB=Dh_mYkgqtqZF+m*a9!d3 z8LctVEZ01VpMlnwOW`TaC;Q%|0D{sxwp-d$g4QXU+W@o8^h=XO zrt(j-O<31=$Zh&2-c*~g&3w)-e++jbJy z;C){&%&?1GLjU>x%5X}W1-*5@#LXbVA=*t=9_#DkxK>Q;-X%M=pt0rjpB&BQjrmh> zHL`isxwnr`31q*V8^7On5oK%a^8lmls#!=>ZYI}#uf%iz)ZE&gyWv8v&vK5*{VvyWbE<-V@jBaH z#CF_ytB{)q@eiy&qnJ*unM=)x;a%-3I8g9a+a1ip>*bew<{!K8he8q{Wj==HHg#{ofSdb7D6KkK{tr!3yxDE1SFh(k5El>z&% zKG|6^5D|CL=j8l~K5jym>5dn2Z14V7)?*Xmg;d|k$Ws55(tWRT-xZToO@aDeUb}q{yMZ>4615fNz31N&#j}LO?4OuBU%cE|E0wJp!cim$WuAm zVn&W53sFxS{I-)N_{}Kx4QFNKs*GIn`HKXL^6%cZcuh;Dh6MGl2LfuzQH|tx@*DL6z_oQu&Czk}w+mdXxt~xyL?DlNw{&@~Je0lSW-o}bMW>R=T5v!*eJlnE$ z(T-(?j&U*5R~z_r8{Vp^4E`rziQ3JjXnW7D<{1sc4LRis#L;hWYPv=4>nux?h ztL*j8TM@j;*~VE1*JH2#vbjxFmbqJzVtu3~M%mUL**jP7du-3N$L2d^TV=_QAJG-I znbE-!+yBn0GB3mQI6Z@M8flKx9c0|<>JzP5ez#Z`x3*Yt=lIPzGRtEA?}3B9Poa!H zhq&Sh_PGtcj_AI+CAspVK&vVnn;_rxom1|fzV4fz{G*+%3uAYxDs%b|`&N@m@5a7~ z_O_olyUKFJ@Y;q1hm)sXo`^MT-+1xe?r$&`Oeyj|HEH}84{Wb%%~taSKNKVV7X_a$ zDeks@c+GtE>Jni;iZAYYc_Ds7I_O-L!CM9|3qDd1>l4^?4tCK( z6Hgff2nZl46C)Gw6D16p7gnds0Btyo$6|C4X@VCvIwTz9Clo^%iW|j^fD4fEl1bQw zCKyjKhs%iY4;+&KJuhs$R4QWN@hK@OZYg9pp*Rjtq|@nm0trtd;Q#_BNllb8Ww=C% z6D%>R;SWjJVxCCK6DDF{O(sj2B=y2#!8qnaegaWQ$hdr>WXuKN2VTY$;fZbpyg-1T z$dE__l7YxrLjRT_i2^@U@DY$im?UOH0m)FJ)M=swhds_0C5idEayV=}#D@d`Dgm<+ zKbdlIa7g$#1GXTJClKja!0bwbd%P`eHcP$3}w zPA}Ns3k%QB;0W0~4nx=EvRO1X5n|)mbhaun8kvZrP-q@FCKrNmR2s{J%OSJLbPwtTi7+t_>`Eqo zVpgye2S`ykToRWHad93*4;GLjP;o4>2NOr2bEzBxokF9th&m|_n-M4!3z%Rzc>-n} zgcl{o=>}lK89w2`URaVF;bSD6&y;cj0o((;M2;{;@^L7NCx9ZQOxRDNyNA06l}vXB z8IuVl`bW@mNGt(+5mqG<+{h%|2)r;1P!6z`3GY-Opo@cQ7=B`iDHV#NghIX-7ETHS zGslNRzzxM=N}2vlDFj3bBr=0QVi0LjL=uBaXOL((0*yhKfERLj+|>VshHoE?=jfsb z@g!jWR9$HFo{EIljrK;ne4g%R!eDf_1%t^REkVLe9$RssH9EwOXC}r$;QScdupi>Q zf3q1lEFwg6r$9I&m&?Ras5A-=Y%q5ml?;)Ay(}h`%+|Rut}YRBr727?ZEDBmFK_Eors!M=p*(r@L<64jKE03=y8yb@ckML$X+{P{TCG;4 zR<*us&A*aAs2&`LjSY;ai@7}z7bM)#_7-42?rW{tvyXE?N`u3Lg zFhqw#Xu&K9FvE~$sIk3qKs5kH#w3-4%E6&QEmAu?GHhmOW^Q7R)FQjzclWFMU%!2= z98#k7(Q1u)jG!ISTA5e@8PMo`-#aik(DS|r`17{+ZC76xZ~}OMLZZO?7y*SsX|x)& z9vaMtR3kyg^7nGU0g@I*7GMGwhf+grENlSOz`y{Q+cVH( zf;ItOfh4 RobotProvider.instance.hasNewDriverStationData()); @@ -33,6 +41,11 @@ public void run(Context context) { // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. + if (joystick0.getButtonPressed(1)) { + imageDisplayed = (++imageDisplayed) % imageList.length; + + context.startAsync(new DisplayImage(imageList[imageDisplayed], true)); + } } } } diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java index b2b3c2a7..81cc79b5 100644 --- a/src/main/java/com/team766/robot/Robot.java +++ b/src/main/java/com/team766/robot/Robot.java @@ -4,10 +4,10 @@ public class Robot { // Declare mechanisms here - + public static CANdleMech candle; public static void robotInit() { // Initialize mechanisms here - + candle = new CANdleMech(8, 16, 16); } } diff --git a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java new file mode 100644 index 00000000..2f29298d --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java @@ -0,0 +1,61 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.RobotProvider; +import com.team766.logging.Severity; + +import edu.wpi.first.wpilibj.Filesystem; +import edu.wpi.first.wpilibj.util.Color8Bit; + +import com.team766.hal.MotorController; + +import java.io.*; +import java.nio.file.Path; +import java.nio.file.Paths; +import java.util.*; + +import javax.imageio.ImageIO; + +import com.ctre.phoenix.led.*; +import com.ctre.phoenix.led.CANdle.LEDStripType; +import com.ctre.phoenix.led.CANdle.VBatOutputMode; +import com.ctre.phoenix.led.ColorFlowAnimation.Direction; +import com.ctre.phoenix.led.LarsonAnimation.BounceMode; +import com.ctre.phoenix.led.TwinkleAnimation.TwinklePercent; +import com.ctre.phoenix.led.TwinkleOffAnimation.TwinkleOffPercent; +import java.io.File; +import java.io.IOException; +import java.nio.file.Files; +import java.awt.image.BufferedImage; +import java.awt.image.Raster; + +public class CANdleMech extends Mechanism { + + + + private final CANdle m_candle = new CANdle(5); + private int matrixStart; + public int w; + public int h; + + public CANdleMech(int matrixStart, int w, int h) { + this.matrixStart = matrixStart; + this.w = w; + this.h = h; + } + + public void setColor(short r, short g, short b, int index, int count) { + checkContextOwnership(); + m_candle.setLEDs(r / 3, g / 3, b / 3, 0, index, count); + } + + public int getMatrixID(int x, int y) { + if (y % 2 == 0) { + return h * y + x + matrixStart; + } else { + return h * y + w - 1 - x + matrixStart; + } + } + + +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/DisplayImage.java b/src/main/java/com/team766/robot/procedures/DisplayImage.java new file mode 100644 index 00000000..22177d45 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/DisplayImage.java @@ -0,0 +1,101 @@ +package com.team766.robot.procedures; + +import java.io.File; +import java.io.IOException; +import java.nio.file.Path; + +import javax.imageio.ImageIO; + +import com.team766.framework.Context; +import com.team766.framework.Procedure; +import com.team766.logging.Severity; +import com.team766.robot.Robot; + +import edu.wpi.first.wpilibj.Filesystem; +import java.awt.image.BufferedImage; + +public class DisplayImage extends Procedure { + + final int h = Robot.candle.h; + final int w = Robot.candle.w; + String file; + boolean interlacing; + public DisplayImage(String file, boolean interlacing) { + this.file = file; + this.interlacing = interlacing; + } + + public void run(Context context) { + File fileObj; + Path path = Filesystem.getDeployDirectory().toPath().resolve(file); + fileObj = path.toFile(); + BufferedImage image; + Color[][] colors = new Color[h][w]; + + try { + image = ImageIO.read(fileObj); + } catch (IOException e) { + e.printStackTrace(); + log(Severity.ERROR, "Could not load " + file); + return; + } + + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + } + } + + display(colors, context, interlacing); + } + + public void display(Color[][] colors, Context context, boolean interlacing) { + if (interlacing) { + for (int i = 0; i < h; i+= 2) { + for (int j = 0; j < w; j++) { + log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); + context.takeOwnership(Robot.candle); + Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, Robot.candle.getMatrixID(i, j), 1); + context.releaseOwnership(Robot.candle); + } + context.waitForSeconds(0.01); + } + for (int i = 1; i < h; i+= 2) { + for (int j = 0; j < w; j++) { + log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); + context.takeOwnership(Robot.candle); + Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, Robot.candle.getMatrixID(i, j), 1); + context.releaseOwnership(Robot.candle); + } + context.waitForSeconds(0.01); + } + } else { + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); + context.takeOwnership(Robot.candle); + Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, Robot.candle.getMatrixID(i, j), 1); + context.releaseOwnership(Robot.candle); + } + context.waitForSeconds(0.01); + } + } + } + + public class Color { + public short r; + public short g; + public short b; + public Color(short r, short g, short b) { + this.r = r; + this.g = g; + this.b = b; + } + + public Color(double[] color) { + r = (short) color[0]; + g = (short) color[1]; + b = (short) color[2]; + } + } +} \ No newline at end of file From 00e50fd6952ac1ec15e63406aee0c4f96eb8917f Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 18 Feb 2023 17:12:05 -0800 Subject: [PATCH 056/103] Reversed Y-Direction and stopped robot travelling infinitely --- src/main/deploy/FollowPoints.txt | 18 +++++----- .../java/com/team766/odometry/Odometry.java | 4 +-- .../com/team766/robot/AutonomousModes.java | 1 + src/main/java/com/team766/robot/OI.java | 1 + .../com/team766/robot/mechanisms/Drive.java | 2 +- .../com/team766/robot/mechanisms/Gyro.java | 2 +- .../robot/procedures/FollowPoints.java | 34 +++++++++---------- 7 files changed, 31 insertions(+), 31 deletions(-) diff --git a/src/main/deploy/FollowPoints.txt b/src/main/deploy/FollowPoints.txt index 1cc6a5ab..b09ad4c8 100644 --- a/src/main/deploy/FollowPoints.txt +++ b/src/main/deploy/FollowPoints.txt @@ -1,32 +1,32 @@ { "points": [ { - "coordinates": [5.4, 5.34, 15], + "coordinates": [1.88, 0.04, 15], "critical": true }, { - "coordinates": [3.76, 4.38, 0], + "coordinates": [2.63, 0.25, 0], "critical": false }, { - "coordinates": [6.32, 4.38, 0], + "coordinates": [2.95, 1.12, 0], "critical": true }, { - "coordinates": [7.06, 3.45, 15], - "critical": false + "coordinates": [2.37, 1.49, 15], + "critical": true }, { - "coordinates": [7.57, 1.63, 30], + "coordinates": [1.57, 1.49, 30], "critical": false }, { - "coordinates": [6.13, 0.53, 0], + "coordinates": [0.83, 0.92, 360], "critical": true }, { - "coordinates": [2.53, 0.42, 0], - "critical": false + "coordinates": [0.33, 0.54, 0], + "critical": true } ] } \ No newline at end of file diff --git a/src/main/java/com/team766/odometry/Odometry.java b/src/main/java/com/team766/odometry/Odometry.java index 7a4cbcd7..f056f1a2 100644 --- a/src/main/java/com/team766/odometry/Odometry.java +++ b/src/main/java/com/team766/odometry/Odometry.java @@ -107,13 +107,13 @@ private void updateCurrentPositions() { double radius; double deltaX; double deltaY; - gyroPosition = Robot.gyro.getGyroYaw(); + gyroPosition = -Robot.gyro.getGyroYaw(); Point slopeFactor = new Point(Math.sqrt(Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroPitch()) * Math.cos(Robot.gyro.getGyroPitch()) + Math.sin(Robot.gyro.getGyroYaw()) * Math.sin(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroRoll()) * Math.cos(Robot.gyro.getGyroRoll())), Math.sqrt(Math.sin(Robot.gyro.getGyroYaw()) * Math.sin(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroPitch()) * Math.cos(Robot.gyro.getGyroPitch()) + Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroYaw()) * Math.cos(Robot.gyro.getGyroRoll()) * Math.cos(Robot.gyro.getGyroRoll()))); for (int i = 0; i < motorCount; i++) { //prevPositions[i] = new PointDir(currentPosition.getX() + 0.5 * DISTANCE_BETWEEN_WHEELS / Math.sin(Math.PI / motorCount) * Math.cos(currentPosition.getHeading() + ((Math.PI + 2 * Math.PI * i) / motorCount)), currentPosition.getY() + 0.5 * DISTANCE_BETWEEN_WHEELS / Math.sin(Math.PI / motorCount) * Math.sin(currentPosition.getHeading() + ((Math.PI + 2 * Math.PI * i) / motorCount)), currPositions[i].getHeading()); prevPositions[i].set(currentPosition.add(wheelPositions[i]), currPositions[i].getHeading()); - currPositions[i].setHeading(CANCoderList[i].getAbsolutePosition() + gyroPosition); + currPositions[i].setHeading(-CANCoderList[i].getAbsolutePosition() + gyroPosition); angleChange = currPositions[i].getHeading() - prevPositions[i].getHeading(); if (angleChange != 0) { diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java index b2e69393..0814e006 100644 --- a/src/main/java/com/team766/robot/AutonomousModes.java +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -17,6 +17,7 @@ public class AutonomousModes { // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), new AutonomousMode("FollowPoints", () -> new FollowPoints()), + new AutonomousMode("FollowPointsFile", () -> new FollowPoints("FollowPoints.txt")), //new AutonomousMode("FollowPointsH", () -> new FollowPoints(new PointDir[]{new PointDir(0, 0), new PointDir(2, 0), new PointDir(1, 0), new PointDir(1, 1), new PointDir(2, 1), new PointDir(0, 1)})), new AutonomousMode("DoNothing", () -> new DoNothing()), }; diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 462d31f4..ee61abfc 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -139,6 +139,7 @@ public void run(Context context) { (LeftJoystick_X), (LeftJoystick_Y), (RightJoystick_X)); + log("FRONT RIGHT: "+Robot.drive.getFrontRight()); } else { Robot.drive.stopDriveMotors(); Robot.drive.stopSteerMotors(); diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 09fa3086..cc88880f 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -375,7 +375,7 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta * @param joystick The PointDir to use for the joystick values */ public void swerveDrive(PointDir joystick) { - swerveDrive(joystick.getY(), -1 * joystick.getX(), joystick.getHeading()); + swerveDrive(-1 * joystick.getY(), -1 * joystick.getX(), joystick.getHeading()); } /** diff --git a/src/main/java/com/team766/robot/mechanisms/Gyro.java b/src/main/java/com/team766/robot/mechanisms/Gyro.java index e08dffcd..5286331f 100644 --- a/src/main/java/com/team766/robot/mechanisms/Gyro.java +++ b/src/main/java/com/team766/robot/mechanisms/Gyro.java @@ -23,7 +23,7 @@ public Gyro() { loggerCategory = Category.GYRO; } public void resetGyro(){ - g_gyro.setYaw(0); + g_gyro.setYaw(-90); } public double getGyroPitch() { double angle = g_gyro.getPitch(); diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index b6808e5e..16176ca5 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -79,7 +79,7 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole * @param file filename for the waypoints file to load and use. * @throws IOException Thrown if file is not found. */ - public FollowPoints(String file) throws IOException { + public FollowPoints(String file) { String str; Path path = Filesystem.getDeployDirectory().toPath().resolve(file); try { @@ -92,8 +92,9 @@ public FollowPoints(String file) throws IOException { JSONArray points = new JSONObject(str).getJSONArray("points"); for (int i = 0; i < points.length(); i++) { - addStep(new PointDir(points.getJSONObject(0).getJSONArray("coordinates").getDouble(0), points.getJSONObject(0).getJSONArray("coordinates").getDouble(1), points.getJSONObject(0).getJSONArray("coordinates").getDouble(2)), points.getJSONObject(0).getBoolean("critical"), null, false); + addStep(new PointDir(points.getJSONObject(i).getJSONArray("coordinates").getDouble(0), points.getJSONObject(i).getJSONArray("coordinates").getDouble(1), points.getJSONObject(i).getJSONArray("coordinates").getDouble(2)), points.getJSONObject(i).getBoolean("critical"), null, false); } + addWaypoints(); } /** @@ -105,7 +106,6 @@ public FollowPoints(String file) throws IOException { */ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boolean stopRobot) { steps.add(new Step(wayPoint, criticalPoint, procedure, stopRobot)); - log(criticalPoint? "true" : "false"); } /** @@ -113,10 +113,10 @@ private void addStep(PointDir wayPoint, boolean criticalPoint, Procedure procedu */ public FollowPoints() { addStep(new PointDir(0,0, 0), false, new DoNothing(), false); - addStep(new PointDir(4,0, 90), false, null /* don't execute procedure */, false); - addStep(new PointDir(4,4, 0), false, new DoNothing(), false); - addStep(new PointDir(0,4, 90), false, null /* don't execute procedure */, false); - addStep(new PointDir(0,0, 0), false, new DoNothing(), false); + addStep(new PointDir(2,0, 90), false, null /* don't execute procedure */, false); + addStep(new PointDir(2,2, 0), false, new DoNothing(), false); + addStep(new PointDir(0,2, 90), false, null /* don't execute procedure */, false); + addStep(new PointDir(0,0, 0), true, new DoNothing(), false); addWaypoints(); } @@ -127,7 +127,6 @@ private void addWaypoints() { pointList = new PointDir[steps.size()]; proceduresAtPoints = new Procedure[steps.size()]; stopRobotList = new boolean[pointList.length]; - //TODO: Fix all critical points being read as false criticalPointList = new boolean[pointList.length]; for (int i = 0; i < steps.size(); i++) { if (steps.get(i).wayPoint == null) continue; @@ -142,7 +141,6 @@ private void addWaypoints() { proceduresAtPoints[i] = new DoNothing(); } criticalPointList[i] = steps.get(i).criticalPoint; - log(Boolean.toString(steps.get(i).criticalPoint)); stopRobotList[i] = steps.get(i).stopRobot; } @@ -188,22 +186,21 @@ public void run(Context context) { //This resetCurrentPosition() call makes FollowPoints() robot-oriented instead of field-oriented //If we need to make this method field-oriented, just remove this line Robot.drive.resetCurrentPosition(); - Robot.gyro.resetGyro(); targetNum = 0; for (int i = 0; i < pointList.length; i++) { - log(Boolean.toString(criticalPointList[i])); + log(pointList[i].toString()); } if (pointList.length > 0) { Point targetPoint = new Point(0.0, 0.0); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); - while (targetNum != pointList.length - 1 || !passedPoint(pointList[pointList.length - 1])) { + while (targetNum < pointList.length - 1 || !passedPoint(pointList[pointList.length - 1])) { if (followLimiter.next()) { lastPos = currentPos.clone(); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point //Otherwise, it uses the checkIntersection() method to follow the circle - if (criticalPointList[targetNum]? passedPoint(pointList[targetNum]) : checkIntersection(pointList)) { + if (criticalPointList[targetNum]? (targetNum < pointList.length - 1 && passedPoint(pointList[targetNum])) : checkIntersection(pointList)) { if (proceduresAtPoints.length < targetNum) { if (stopRobotList[targetNum]) { context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); @@ -212,7 +209,7 @@ public void run(Context context) { } } targetNum++; - log("Going to Next Point!"); + log("Going to Next Point! " + pointList[targetNum]); } targetPoint = selectTargetPoint(targetNum, pointList); //double diff = currentPos.getAngleDifference(targetPoint); @@ -221,9 +218,9 @@ public void run(Context context) { Robot.drive.setGyro(Robot.gyro.getGyroYaw()); driveSettings.set(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); Robot.drive.swerveDrive(driveSettings); - log("Current Position: " + currentPos.toString()); - log("Target Point: " + targetPoint.toString()); - log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())).toString()); + //log("Current Position: " + currentPos.toString()); + //log("Target Point: " + targetPoint.toString()); + //log("Unit Vector: " + new PointDir(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())).toString()); context.yield(); } else { @@ -317,7 +314,8 @@ private static Point selectTargetPoint(int targetNum, Point[] pointList) { * @return If the robot is within a certain distance of P, and the distance to P is increasing, returns true. Otherwise, returns false. */ private boolean passedPoint(Point P) { - log(currentPos + " " + P + " " + currentPos.distance(P) + " " + ((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2) ? " true" : " false")); + //log(currentPos + " " + P + " " + currentPos.distance(P) + " " + ((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2) ? " true" : " false")); + //log(((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.4)) ? "true " : "false " + targetNum); return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.4); } From 2b3c0b19a47e8e11d4b7dc4afaf3471a520ae8fe Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 18 Feb 2023 20:37:13 -0800 Subject: [PATCH 057/103] Added tnt & torchflower --- src/main/deploy/tnt.png | Bin 0 -> 6275 bytes src/main/deploy/torchflower.png | Bin 0 -> 5756 bytes src/main/java/com/team766/robot/OI.java | 2 +- 3 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 src/main/deploy/tnt.png create mode 100644 src/main/deploy/torchflower.png diff --git a/src/main/deploy/tnt.png b/src/main/deploy/tnt.png new file mode 100644 index 0000000000000000000000000000000000000000..c9d5b78ed5e8249041bbc3084becbe4e79ce089a GIT binary patch literal 6275 zcmeHLc~leE8Xst$%A#n2KtUx01O>AVNk}3Alz<=vQx-u%Ws*!Fl8r17K?D^M7u;J^ zz=C>EM6GKTY3o`=twOOZ(t=h|kb-Q*4Ujhz2;zA?=aqL}Pyg|9X6}63?|%1pzk4Uc zMqcpziN-d@002x3@aKde{bcl-Fb=uf^$bD)fT>Lmi&Td|NjQa4E)q*%oO-1K#=%;# z2mrM8?GcMlKcSoUH_uXH3?C&=-4qxu+y3NmY1TLW9{0+7Y>W4E62#O>T+88BuQc~w zD=BUL6>axc68*M%dW_nr5%gLY)l;#$%F1y;+ym!= z?X{N^re%qK+hB#;PkO#3xomd9h4hSOfRIjYs3MLVY`gk-b6MX0j5mkhUdwQ8w|hAK zCs%A@Myc_}8=)D_2G7$DIA;4@RXlo--?`=BO%fT?v^4Lf<&`6vqtDt8ZFVX1?dYp6 zS&~_6vC`=DFCFIxHnrVJm(1yxJjkei9G{j@ztE5LQ%BnIFDf%DI`N-v;FUf7`T6ZQ zsL{Z@LCq_up-fZGeALj9H3wJX7E;)9%;St^eKh3vpFpnB-nL^#;cBjSk zF;khD=vegd=Q^Kjc!MR+?8~M!M#t^RW|csM%S!to*w7lf)gINbv~tNqV-Bk=a*dVB zj2@?c`qun@!Gv>`VRH;uHGUmY8(vV*{`re2NBqf~8I0L%mo=t^|1u{us?2thOaS|} zViVAj2OQlIsXW9!<2(=d31&gTR^<=lEpYLr>5jHj#!FA`im?gw$S#(A)?hp^Q^dQv z$=pnO@(%7x3iiztuJ@!Ft~HVI`MvbIxLxM4d767GYd7<|A7^*h%;`w&{OK_63dT0N z(>}vGq-o~Nee{bhf-FiACfBIksKngqkh;@;1M?W`*Wb1&t~EgM0NLkB|k9g+>GD1^<}O&8}_6y?5mdZ zD_VNrWfUw6meiWAJq2QZNX-F^?k;tkR&M>`w&t#y^TzxRPFyBhf056t4CDXO@^f%k z*jd+C^DoYl6EAk1zgLJ!D)`yU8`dbhn@DXuXv1QY}iMqm)XTBqg2cJ#-TNa&uY@9auBam4+t>5pepVwg3Vm36zxUU>X*=argu z1M|CE$MtP%s-F1L?pBFyo7c_=_qsI4uVp6({g|^owYWk}s@RdHxuFDev2LUlv7CUbMHu*a^=n=jBntWjUMLV^mK$Ik#uJR|dYjRuwzFtmFv0eSn{vGc7&0 zxY+x;pqd!8*rWQ{ve#jcvoDaYBy*kwoh_OUZM-xA9QblqtGMn~P|}Sx>q8SR7XE&% z%Hf-BoKO4ZU{lB5ke;+R-5c*r4Zk#fHO3GVu{%C7mZw;xo^#8>El^sO694X2AC`At zDsMWNpAuJNL)&~exCxA%&L}^BwgP@)x;Dtlb+t7kbzEQRss=xgSL@!sb1YjF+B*=C zc)X~!Z&%xbWvOX92L>G;=M)a^*wj#@`&!CUqpd znl#zQvS{C$1n=tE4*6M|OZzujuUel@Hng61{(2C5@8a^Ss#OiwZq}ArS9E*6YHkTN zcKT!$zH9dViJP_g+T{CH%ntMUk&8pJDmLCUy@=~_sD*PLGIFM3wW90gMa@|b*ZIZk zo=y_MJ~Q^?x4Inldo%AIyuJq;doDz9Jf+(z)3{!l`8##Pj?4I+{&O?7*wA@v)>|L9 zndMY<*6vlO8S9-zsZc3R-yxVDeq{Spuh(|{FKT872VV#%WK{O@f3b7$R#?T=Nc;Ng zzR7h?AN=e>RsFjapX_<#_+4Yof%)EpbVWi#O%wZ(a=f*+YKD)}(TiIciD|58$?f)j zjcr+~Nr`WN@`pirNJOCfz0N~-JRX~DxSdHVuv0@n;-%)l6j}r^o_y`)8%vJcnabo{u zB^;U@941JP7chl*FHd6+EeipV!fFVol}cnPmX?jz;j)ltR87L;bS~<6Ha?Qe!}-XS zFpf&363GN#tvC_Hdm7_BltK|JgyT01fkKqFfnEqA;0E5*Z|c zAOZ0ps8-6L05v0R2jF(JNOqh{mrh#jZTPpaT@N8n|uVHOZR zNLoliq7ca>sgyK2LZ$XiL_mfU`qKzi81m*Og}^GgMk#=O6JeR!VKjtLFcPoOC?&e- z2n8fq0!tBB6*4O2gCXY!aCsvUC9JxS)rWe3r@{&BUK4WMrVaW2@xnakV%92Od)|u6}l0qG#Zt_pzs9*s)#OvXmocW?9S9d2?Z=a zxl#%t%PE#Zu`o#?i`5xW!dY{90c<=-B)`}2B#>H!1R#4rEECF;RPRk;VksP|hEP5! zba%QtgUqCZG&cs7L3{7C2v(|)T0~JPWTM;9e9(nqA=5#qh0sbx0CW+^Y*;=@7*flX zVRE^IjYpHhp^+nIF0!G7kQ(AZY8U|}gKjJ`$f7X9Kr#ztvJf)K3>JBmzg#F5t^9A^ z==Q;R3@y69ScQzgQl}c)Q=xFekTfJp#JbId!|ApK3la=XK?NnkLS3E+){sdM2gzb# zwr*3AcKSv%0LiL8lEf(Ju&pN^&tHRA09e~QAZ3C zH>5+3F61O6jU0u;e4&TV-`IxN;cpxPf&MtinE3rj*GIa>#K4%GKUUXAy2ix7n4CXW z*Z++!!M8g|-2lxnYbc29q%zeFm*Q)`N%}(A8!L)I6IAFo|8L z_?Kl28i+PD_>pxh;L>I^CV41Y7xKT|{&@g{L8MhwQ~+isCb~Iv_4ev|y^IQfrbG33 zCno?v0U91WKv!bq(#!Ym-5W$N)TY)j~f!`j~1Be2#0lHp4A_#&y9eP7` z2#8Kbdo)8d7K5gN8ucmbd(;zkbZ~ao1)(=RFxq!EJq7HXodDe`ph2UJ`Uq5~&rGjF zd(?mOR9hVf2H&4PqpQTx4r6&XIA!Uq13;?~ZMYV!uK%kt#>J*b7XUoN4wdp4<$t~s eG3YKF-Nq_c)6bnba-yUT#R%{X=A4)pv-aObaip#Q literal 0 HcmV?d00001 diff --git a/src/main/deploy/torchflower.png b/src/main/deploy/torchflower.png new file mode 100644 index 0000000000000000000000000000000000000000..7022e26a78d9427d7e7ebdbcfebe70d8573d5f4b GIT binary patch literal 5756 zcmeHKc~leG(hrO5AP%c5F(?Wc(h1oiY)M!Kf@~^_TPNLt0NDeCO;I+*869O57f?`f z91zhD#F1qb7=_Uh6&*n~QO5^^3JMA$jJyuGp6{LW9nbmRep5P zT*eL>b^CSp$@^~}vv)_#GGrZFe;(7F(_E%jV|M)9DeIEwBj3m(V8$BElgKNL*A|XO z90Kd+0kdgs&8=IO?T$c2O*RJ{+?xSPOPwD4K9cC5t2KVrzpdEqj&{gY@y+k|mhvwS zQp#f!&$Ih4H@~pE_>@AfHMmLIm3;W#wbK`pFSgd}-`er2seH^X_4M3QZ2on>404_sOxe`Tw!U1xRg`XNxsI_M<=y?#|z1~ z-^u^U*ePySSJ?2Qs&2gPs&CGO+B`elm3g^E@M<}~#b*D7@NIN`*t|R?<8>d2U#YX8duHI z_dQvSG64rrz`jeU&oz((4@!T*xRaSh%?AQDp9$aB~`c8^ImMm(mEH+y61gah?YHC?mJ*qfcB}lDt-FRJew+o8a8NNI( z>A*^}_~W?%RRe5M>R(9=KxN0LS1?bFi2w@K$#netts2b$wKN{k(n_sxP$bJDySNHq ztX%2%R9t)EKHOq3-~tU6oG%Y8<;}OtJ!_WPcv5@u8=z+i&4*W!Y=6C6O9bD*UysJ| zxcAwQqT85szsX>>>+)CS3Aof^tqd-^8wGU+JnE&FJy|9*$<1Z^HB33N=@H^oBBp0=@bCqs{64P8rXi-6Ns`cV0<0etwlk z^rDm74R6+u-455QdezoC8Qq(`)a`LD>G-Y_Z?){So}?Qx7JS!58dxOAZ5R;cl)1L_ z04+Hc#3tXSUB3R_vS6`?`k52b{nn=rlVov;6q7Xz$Wi)UIx$#_Dva##P0* zSPV-AoA4VC#YPGKa=%+$ubCDYsx;h}v*cf^(vRe{cV4Nw{Hte$WO3r{e1%~$_AxP} z{cwS_SWa((+b;fHw4`B>$W$$C(!Nm{pt11B7K%^ z_sR9$P6kOY85+TzxW;2rf^*=+8JkmT$qgoSdHUaPxRoq(C9}Ouy@nWO)3AD(u4jQE z#uj@cfn(QN!StjDr!^&x=nk83JMI}y1Q+j#x98?gxJ2GJmo?6}C@VrexD>gs#&;co z>NcU?x4}cQ@h8sM!QN4-#}o5AI~(igVmCr>c3VR(9hKnVOR3Sx_+@0vt8dye&lN1P zj=BI5(_qxN-XI_Lh*Qxrxc@{bDik#`g>&$j>~+5 zT)!3Ctb33;cp_t0Va>&J)hDdNS55`yR}XBm@I_neiyCa*2mJLi#HZ@$DI{J0)rab` z@AZ5;vW~y=TH&DW*%Sd;e!er8R^A3BmS7yGm<^V<3b{G=4 zPP^$JWx|kj%*c42*@=T&q;7w%urAoP$E1 z#-7inzcsx8$%JXUd5cz^{9%FXYpcn@yDR+tfAJ}z-h9RFw6b=S zSVY|wPE52{9a@$)HTRd+j}9P{kaOSR^pHNKQf^^1YSh))km$h?Oz{Qk7urr(UU`AQcpq43Qxo9_z@ZQm{mjM#geME{KIGJOY>I zNG3V*DAQ07kM1d!2|*;C0wEX)<0PWU=>ZktboT%s28Q4Oe3S&lf(kxjfUE(52ofjA zKMsWmgmAC|RPl)?Q^*u5KqV3#9SLNB{84E&ER!R(s6xd94vsVNs1id*!a=A7Rh5bW zOj{t)(3vtARET9EVsR`3qjCzZviva2K^7DQDnJ&ffDurD;7A7ubUZbL0MH2(I>8YO zQ0c%Y`eI1HPyD~MRm%tMJd<>9fgG7XaauI9rh;MV%+t(ctYCUEq0!UJf)4U#LXd;; zFf{Eaf;BV5ivmTFFw#HX73_Pt;6D@ti9*H`Ax9FH0`ZXylKFTnmF!5x@@N!@OyUu# z5ZUo_bh((XNC0K9dnCdm!WB}W(_EpKze|UxU0=k& z7b$hv$VLrUM$p<>RVX%Q!XOW zm3W8AQ7C;A)uo0ym~V*)wG}=bwsxPoiROGukCI!5kh3)M_Us-)y;iX2qOS*Nnq}qN z5OWM;v^Aiy_>PB{Ku@uKpZToaHU8Up)XXu>>YdH1 zGmOV=?>Q9L8__b}GEz50vr6MCwEo-%rmCe|hFDLUSEu=})-2qxXG;5IpQqdwKmXRm z(gR7N43qI8RNoc#S6w}!}$YH3yS)T5=BUe@ij^|m?UIog>R zJG*`J+dI(@qP{^T+$wp@AEYec*rj16o`w7W_%LVr<-HlW;>UlKKqR}vMtK%Z&RBEf zV(NIYnUc!-@!_L9ef0w=NgW;yc}E}q9q=MvZMjwc!<<>P4ui$7HmF7AtyenL+&;3! z-u#ZM%CELV_!4#EVBA#wikqkSX}Hao&OEzeqwA040OiB>XPx%g Gxb@#eV8m(w literal 0 HcmV?d00001 diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 879c9f6f..6d5b5d43 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -32,7 +32,7 @@ public void run(Context context) { context.startAsync(new DisplayImage("cone.png", true)); int imageDisplayed = 0; - String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png"}; + String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png"}; while (true) { // wait for driver station data (and refresh it using the WPILib APIs) From ba8201e451077193cf156ad8113fae347d62851c Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sun, 19 Feb 2023 11:47:01 -0800 Subject: [PATCH 058/103] Allows robot to move backwards in swerveDrive() --- .../com/team766/robot/mechanisms/Drive.java | 114 +++++++++++++++--- 1 file changed, 94 insertions(+), 20 deletions(-) diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index cc88880f..ebcd5940 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -153,6 +153,31 @@ public double getAngle(double LR, double FB) { return Math.toDegrees(Math.atan2(LR, -FB)); } + /** + * Returns whether two angles are within 90 degrees of each other, used to see if the wheels + * should move backwards or not + * + * @param angle1 The first angle + * @param angle2 The second angle + * @return If they are within 90 degrees of each other + */ + public boolean withinHalfACircle(double angle1, double angle2) { + angle1 = mod(angle1, 360); + angle2 = mod(angle2, 360); + if (Math.abs(angle2 - angle1) > Math.abs(angle2 + 360 - angle1)) { + angle2 += 360; + } + if (Math.abs(angle2 - angle1) > Math.abs(angle2 - 360 - angle1)) { + angle2 -= 360; + } + return Math.abs(angle2 - angle1) <= 90; + } + + // Returns mod(d1, d2), to use to circumvent java's weird % function + private static double mod(double d1, double d2) { + return d1 % d2 + (d1 < 0 ? d2 : 0); + } + /** * Rounds a number based on its value and places * @@ -271,16 +296,38 @@ public void drive2D(double JoystickX, double JoystickY) { double angle = fieldAngle(getAngle(JoystickX, JoystickY), gyroValue); log("Given angle: " + getAngle(JoystickX, JoystickY) + " || Gyro: " + gyroValue + " || New angle: " + angle); - // Temporary Drive code, kinda sucks - m_DriveFrontRight.set(power); - m_DriveFrontLeft.set(power); - m_DriveBackRight.set(power); - m_DriveBackLeft.set(power); - // Steer code - setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); - setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontLeft))); - setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerBackRight))); - setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerBackLeft))); + + if (withinHalfACircle(angle, getCurrentAngle(m_SteerFrontRight))) { + m_DriveFrontRight.set(power); + setFrontRightAngle(newAngle(angle, getCurrentAngle(m_SteerFrontRight))); + } else { + m_DriveFrontRight.set(-power); + setFrontRightAngle(newAngle(180 + angle, getCurrentAngle(m_SteerFrontRight))); + } + + if (withinHalfACircle(angle, getCurrentAngle(m_SteerFrontLeft))) { + m_DriveFrontLeft.set(power); + setFrontLeftAngle(newAngle(angle, getCurrentAngle(m_SteerFrontLeft))); + } else { + m_DriveFrontLeft.set(-power); + setFrontLeftAngle(newAngle(180 + angle, getCurrentAngle(m_SteerFrontLeft))); + } + + if (withinHalfACircle(angle, getCurrentAngle(m_SteerBackRight))) { + m_DriveBackRight.set(power); + setBackRightAngle(newAngle(angle, getCurrentAngle(m_SteerBackRight))); + } else { + m_DriveBackRight.set(-power); + setBackRightAngle(newAngle(180 + angle, getCurrentAngle(m_SteerBackRight))); + } + + if (withinHalfACircle(angle, getCurrentAngle(m_SteerBackLeft))) { + m_DriveBackLeft.set(power); + setBackLeftAngle(newAngle(angle, getCurrentAngle(m_SteerBackLeft))); + } else { + m_DriveBackLeft.set(-power); + setBackLeftAngle(newAngle(180 + angle, getCurrentAngle(m_SteerBackLeft))); + } } /** @@ -358,15 +405,42 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta brPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); blPower /= Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)); } - m_DriveFrontRight.set(frPower); - m_DriveFrontLeft.set(flPower); - m_DriveBackRight.set(brPower); - m_DriveBackLeft.set(blPower); - // Steer code - setFrontRightAngle(newAngle(frAngle, getCurrentAngle(m_SteerFrontRight))); - setFrontLeftAngle(newAngle(flAngle, getCurrentAngle(m_SteerFrontLeft))); - setBackRightAngle(newAngle(brAngle, getCurrentAngle(m_SteerBackRight))); - setBackLeftAngle(newAngle(blAngle, getCurrentAngle(m_SteerBackLeft))); + + if (withinHalfACircle(frAngle, getCurrentAngle(m_SteerFrontRight))) { + m_DriveFrontRight.set(frPower); + setFrontRightAngle(newAngle(frAngle, getCurrentAngle(m_SteerFrontRight))); + log(frAngle + " " + getCurrentAngle(m_SteerFrontRight) + " Positive " + + newAngle(frAngle, getCurrentAngle(m_SteerFrontRight))); + } else { + m_DriveFrontRight.set(-frPower); + setFrontRightAngle(newAngle(180 + frAngle, getCurrentAngle(m_SteerFrontRight))); + log(frAngle + " " + getCurrentAngle(m_SteerFrontRight) + " Negative " + + newAngle(-frAngle, getCurrentAngle(m_SteerFrontRight))); + } + + if (withinHalfACircle(flAngle, getCurrentAngle(m_SteerFrontLeft))) { + m_DriveFrontLeft.set(flPower); + setFrontLeftAngle(newAngle(flAngle, getCurrentAngle(m_SteerFrontLeft))); + } else { + m_DriveFrontLeft.set(-flPower); + setFrontLeftAngle(newAngle(180 + flAngle, getCurrentAngle(m_SteerFrontLeft))); + } + + if (withinHalfACircle(brAngle, getCurrentAngle(m_SteerBackRight))) { + m_DriveBackRight.set(brPower); + setBackRightAngle(newAngle(brAngle, getCurrentAngle(m_SteerBackRight))); + } else { + m_DriveBackRight.set(-brPower); + setBackRightAngle(newAngle(180 + brAngle, getCurrentAngle(m_SteerBackRight))); + } + + if (withinHalfACircle(blAngle, getCurrentAngle(m_SteerBackLeft))) { + m_DriveBackLeft.set(blPower); + setBackLeftAngle(newAngle(blAngle, getCurrentAngle(m_SteerBackLeft))); + } else { + m_DriveBackLeft.set(-blPower); + setBackLeftAngle(newAngle(180 + blAngle, getCurrentAngle(m_SteerBackLeft))); + } } /** @@ -586,7 +660,7 @@ public void resetDriveEncoders() { @Override public void run() { currentPosition = swerveOdometry.run(); - log(currentPosition.toString()); + // log(currentPosition.toString()); } } From d96ef7da770f703bb875c9288d3bb66c79fd4970 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sun, 19 Feb 2023 12:25:53 -0800 Subject: [PATCH 059/103] Reverted attempted gyro-off-by-90 fix --- src/main/deploy/FollowPoints.txt | 16 ++++++++-------- .../java/com/team766/robot/AutonomousModes.java | 2 +- .../java/com/team766/robot/mechanisms/Gyro.java | 2 +- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/main/deploy/FollowPoints.txt b/src/main/deploy/FollowPoints.txt index b09ad4c8..4d403b0c 100644 --- a/src/main/deploy/FollowPoints.txt +++ b/src/main/deploy/FollowPoints.txt @@ -1,31 +1,31 @@ { "points": [ { - "coordinates": [1.88, 0.04, 15], + "coordinates": [0.08, 1.85, 15], "critical": true }, { - "coordinates": [2.63, 0.25, 0], + "coordinates": [1.1, 1.64, 0], "critical": false }, { - "coordinates": [2.95, 1.12, 0], + "coordinates": [1.05, -0.94, 0], "critical": true }, { - "coordinates": [2.37, 1.49, 15], - "critical": true + "coordinates": [0.02, 0.03, 15], + "critical": false }, { - "coordinates": [1.57, 1.49, 30], + "coordinates": [2.01, 1.87, 30], "critical": false }, { - "coordinates": [0.83, 0.92, 360], + "coordinates": [2.03, 0.05, 360], "critical": true }, { - "coordinates": [0.33, 0.54, 0], + "coordinates": [0, 0.03, 0], "critical": true } ] diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java index 0814e006..f186a180 100644 --- a/src/main/java/com/team766/robot/AutonomousModes.java +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -16,7 +16,7 @@ public class AutonomousModes { // define one or more different autonomous modes with it like this: // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), - new AutonomousMode("FollowPoints", () -> new FollowPoints()), + //new AutonomousMode("FollowPoints", () -> new FollowPoints()), new AutonomousMode("FollowPointsFile", () -> new FollowPoints("FollowPoints.txt")), //new AutonomousMode("FollowPointsH", () -> new FollowPoints(new PointDir[]{new PointDir(0, 0), new PointDir(2, 0), new PointDir(1, 0), new PointDir(1, 1), new PointDir(2, 1), new PointDir(0, 1)})), new AutonomousMode("DoNothing", () -> new DoNothing()), diff --git a/src/main/java/com/team766/robot/mechanisms/Gyro.java b/src/main/java/com/team766/robot/mechanisms/Gyro.java index 5286331f..e08dffcd 100644 --- a/src/main/java/com/team766/robot/mechanisms/Gyro.java +++ b/src/main/java/com/team766/robot/mechanisms/Gyro.java @@ -23,7 +23,7 @@ public Gyro() { loggerCategory = Category.GYRO; } public void resetGyro(){ - g_gyro.setYaw(-90); + g_gyro.setYaw(0); } public double getGyroPitch() { double angle = g_gyro.getPitch(); From 04cc3505fc592fe077cc9f081e5a31a276e369ef Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sun, 19 Feb 2023 16:10:24 -0800 Subject: [PATCH 060/103] Improved accuracy of FollowPoints --- src/main/deploy/FollowPoints.txt | 78 +++++++++++++++++-- src/main/java/com/team766/robot/OI.java | 2 +- .../com/team766/robot/mechanisms/Drive.java | 2 +- .../robot/procedures/FollowPoints.java | 18 +++-- 4 files changed, 84 insertions(+), 16 deletions(-) diff --git a/src/main/deploy/FollowPoints.txt b/src/main/deploy/FollowPoints.txt index 4d403b0c..ff4feab0 100644 --- a/src/main/deploy/FollowPoints.txt +++ b/src/main/deploy/FollowPoints.txt @@ -1,31 +1,95 @@ { "points": [ { - "coordinates": [0.08, 1.85, 15], + "coordinates": [-0.96, -0.01, 0], + "critical": false + }, + { + "coordinates": [-1, -2, 0], + "critical": false + }, + { + "coordinates": [0, -2, 0], + "critical": true + }, + { + "coordinates": [0.5, 0, 0], + "critical": true + }, + { + "coordinates": [0.75, -1, 0], + "critical": true + }, + { + "coordinates": [0.25, -1, 0], + "critical": true + }, + { + "coordinates": [0.75, -1, 0], + "critical": true + }, + { + "coordinates": [1, -2, 0], + "critical": true + }, + { + "coordinates": [1.02, -0.01, 0], "critical": true }, { - "coordinates": [1.1, 1.64, 0], + "coordinates": [2, -1, 0], "critical": false }, { - "coordinates": [1.05, -0.94, 0], + "coordinates": [1, -2, 0], "critical": true }, { - "coordinates": [0.02, 0.03, 15], + "coordinates": [4, -2, 0], "critical": false }, { - "coordinates": [2.01, 1.87, 30], + "coordinates": [3.92, -1, 0], "critical": false }, { - "coordinates": [2.03, 0.05, 360], + "coordinates": [3, -1, 0], + "critical": false + }, + { + "coordinates": [3.08, 0, 0], + "critical": false + }, + { + "coordinates": [4, 0, 0], + "critical": true + }, + { + "coordinates": [4.125, -2, 0], + "critical": false + }, + { + "coordinates": [4.875, -2, 0], + "critical": false + }, + { + "coordinates": [5, 0, 0], + "critical": true + }, + { + "coordinates": [6, -2, 0], + "critical": true + }, + { + "coordinates": [5.5, -1, 0], + "critical": true + }, + { + "coordinates": [5, -2, 0], "critical": true }, { - "coordinates": [0, 0.03, 0], + "coordinates": [6, 0, 0], "critical": true } ] diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index ee61abfc..a6ebf35c 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -139,7 +139,7 @@ public void run(Context context) { (LeftJoystick_X), (LeftJoystick_Y), (RightJoystick_X)); - log("FRONT RIGHT: "+Robot.drive.getFrontRight()); + log("FRONT RIGHT: " + Robot.drive.getFrontRight()); } else { Robot.drive.stopDriveMotors(); Robot.drive.stopSteerMotors(); diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index ebcd5940..5194484a 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -660,7 +660,7 @@ public void resetDriveEncoders() { @Override public void run() { currentPosition = swerveOdometry.run(); - // log(currentPosition.toString()); + log(currentPosition.toString()); } } diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 16176ca5..7a4642c1 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -51,6 +51,7 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private static PointDir currentPos = new PointDir(0.0, 0.0, 0.0); private static PointDir lastPos = new PointDir(0.0, 0.0, 0.0); + private static PointDir lastPos2 = new PointDir(0.0, 0.0, 0.0); private PointDir[] pointList; private Procedure[] proceduresAtPoints; @@ -58,7 +59,7 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private boolean[] stopRobotList; private int targetNum = 0; - private RateLimiter followLimiter = new RateLimiter(0.05); + private RateLimiter followLimiter = new RateLimiter(0.001); //Radius defines the radius of the circle around the robot private static double radius = ConfigFileReader.getInstance().getDouble("trajectory.radius").get(); @@ -66,7 +67,7 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private static PointDir driveSettings = new PointDir(0, 0, 0); /*public FollowPoints() { - parsePointList(); + parsePointL$ist(); proceduresAtPoints = new Procedure[pointList.length]; for (int i = 0; i < proceduresAtPoints.length; i++) { proceduresAtPoints[i] = new DoNothing(); @@ -196,6 +197,7 @@ public void run(Context context) { currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); while (targetNum < pointList.length - 1 || !passedPoint(pointList[pointList.length - 1])) { if (followLimiter.next()) { + lastPos2 = lastPos.clone(); lastPos = currentPos.clone(); currentPos.set(Robot.drive.getCurrentPosition().getX(), Robot.drive.getCurrentPosition().getY(), Robot.drive.getCurrentPosition().getHeading()); //If the next point is a critical point, the robot will wait until it has passed that point for it to move to the next point @@ -203,6 +205,7 @@ public void run(Context context) { if (criticalPointList[targetNum]? (targetNum < pointList.length - 1 && passedPoint(pointList[targetNum])) : checkIntersection(pointList)) { if (proceduresAtPoints.length < targetNum) { if (stopRobotList[targetNum]) { + Robot.drive.setCross(); context.waitFor(context.startAsync(proceduresAtPoints[targetNum])); } else { context.startAsync(proceduresAtPoints[targetNum]); @@ -216,7 +219,7 @@ public void run(Context context) { //Robot.drive.setDrivePower(straightVelocity + Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity), straightVelocity - Math.signum(diff) * Math.min(Math.abs(diff) * theBrettConstant, 1 - straightVelocity)); Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - driveSettings.set(currentPos.scaleVector(targetPoint, speed), rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); + driveSettings.set(currentPos.scaleVector(targetPoint, speed), rotationSpeed(-Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); Robot.drive.swerveDrive(driveSettings); //log("Current Position: " + currentPos.toString()); //log("Target Point: " + targetPoint.toString()); @@ -228,6 +231,7 @@ public void run(Context context) { } } Robot.drive.drive2D(0, 0); + Robot.drive.setCross(); log("Finished method!"); } else { log("No points!"); @@ -239,7 +243,7 @@ public void run(Context context) { */ public void updateRotation() { Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - driveSettings.setHeading(rotationSpeed(Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); + driveSettings.setHeading(rotationSpeed(-Robot.gyro.getGyroYaw(), pointList[targetNum].getHeading())); Robot.drive.swerveDrive(driveSettings); } @@ -316,7 +320,7 @@ private static Point selectTargetPoint(int targetNum, Point[] pointList) { private boolean passedPoint(Point P) { //log(currentPos + " " + P + " " + currentPos.distance(P) + " " + ((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.2) ? " true" : " false")); //log(((currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.4)) ? "true " : "false " + targetNum); - return (currentPos.distance(P) > lastPos.distance(P) && currentPos.distance(P) <= 0.4); + return (currentPos.distance(P) <= 0.03 || (currentPos.distance(P) <= 0.15 && currentPos.distance(P) > lastPos.distance(P) && lastPos.distance(P) > lastPos2.distance(P))); } /** @@ -337,9 +341,9 @@ private double rotationSpeed(double currentRot, double targetRot) { targetRot -= 360; } if (Math.abs(targetRot - currentRot) <= angleDistanceForMaxSpeed) { - return -(currentRot - targetRot) / angleDistanceForMaxSpeed * maxSpeed; + return (currentRot - targetRot) / angleDistanceForMaxSpeed * maxSpeed; } - return maxSpeed * -Math.signum(currentRot - targetRot); + return maxSpeed * Math.signum(currentRot - targetRot); } //Returns mod(d1, d2), to use to circumvent java's weird % function From 7f48b5d75cb2bf43a72436e34272a13220c40826 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Sun, 19 Feb 2023 16:32:14 -0800 Subject: [PATCH 061/103] Updated build.gradle and dependencies. --- build.gradle | 2 +- vendordeps/Phoenix.json | 62 ++++++++++++++++++++--------------------- vendordeps/REVLib.json | 10 +++---- 3 files changed, 37 insertions(+), 37 deletions(-) diff --git a/build.gradle b/build.gradle index 9711dfbe..8d64237f 100644 --- a/build.gradle +++ b/build.gradle @@ -2,7 +2,7 @@ plugins { id "java" id 'java-library' id 'maven-publish' - id "edu.wpi.first.GradleRIO" version "2023.3.2" + id "edu.wpi.first.GradleRIO" version "2023.4.1" id 'com.google.protobuf' version '0.8.19' } diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix.json index 72371c03..27ee06ea 100644 --- a/vendordeps/Phoenix.json +++ b/vendordeps/Phoenix.json @@ -1,7 +1,7 @@ { "fileName": "Phoenix.json", "name": "CTRE-Phoenix (v5)", - "version": "5.30.3", + "version": "5.30.4+23.0.8", "frcYear": 2023, "uuid": "ab676553-b602-441f-a38d-f1296eff6537", "mavenUrls": [ @@ -12,19 +12,19 @@ { "groupId": "com.ctre.phoenix", "artifactId": "api-java", - "version": "5.30.3" + "version": "5.30.4" }, { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-java", - "version": "5.30.3" + "version": "5.30.4" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.30.3", + "version": "5.30.4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -37,7 +37,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.30.3", + "version": "5.30.4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -50,7 +50,7 @@ { "groupId": "com.ctre.phoenixpro", "artifactId": "tools", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -63,7 +63,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "tools-sim", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -76,7 +76,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -89,7 +89,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -102,7 +102,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -115,7 +115,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -128,7 +128,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -141,7 +141,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProTalonFX", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -154,7 +154,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProCANcoder", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -167,7 +167,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProPigeon2", - "version": "23.0.2", + "version": "23.0.8", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -182,7 +182,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-cpp", - "version": "5.30.3", + "version": "5.30.4", "libName": "CTRE_Phoenix_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -197,7 +197,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "api-cpp", - "version": "5.30.3", + "version": "5.30.4", "libName": "CTRE_Phoenix", "headerClassifier": "headers", "sharedLibrary": true, @@ -212,7 +212,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.30.3", + "version": "5.30.4", "libName": "CTRE_PhoenixCCI", "headerClassifier": "headers", "sharedLibrary": true, @@ -227,7 +227,7 @@ { "groupId": "com.ctre.phoenixpro", "artifactId": "tools", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -242,7 +242,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.30.3", + "version": "5.30.4", "libName": "CTRE_Phoenix_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -257,7 +257,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "api-cpp-sim", - "version": "5.30.3", + "version": "5.30.4", "libName": "CTRE_PhoenixSim", "headerClassifier": "headers", "sharedLibrary": true, @@ -272,7 +272,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.30.3", + "version": "5.30.4", "libName": "CTRE_PhoenixCCISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -287,7 +287,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "tools-sim", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -302,7 +302,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -317,7 +317,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -332,7 +332,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -347,7 +347,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -362,7 +362,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -377,7 +377,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProTalonFX", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -392,7 +392,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProCANcoder", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -407,7 +407,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProPigeon2", - "version": "23.0.2", + "version": "23.0.8", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index cdbbe6ed..f2d0b7df 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2023.1.2", + "version": "2023.1.3", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" @@ -11,14 +11,14 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2023.1.2" + "version": "2023.1.3" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.2", + "version": "2023.1.3", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -36,7 +36,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2023.1.2", + "version": "2023.1.3", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -54,7 +54,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.2", + "version": "2023.1.3", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, From 421941f72b4c3878d70502dcb792d147bd35f7ce Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Sun, 19 Feb 2023 16:55:41 -0800 Subject: [PATCH 062/103] Added directories --- CONTRIBUTORS.md | 9 -- simConfig.txt | 110 ------------------ src/main/deploy/example.txt | 3 +- .../com/team766/robot/Constants/simConfig.txt | 3 + .../team766/robot/Documentation/Template.md | 0 5 files changed, 4 insertions(+), 121 deletions(-) delete mode 100644 simConfig.txt create mode 100644 src/main/java/com/team766/robot/Constants/simConfig.txt create mode 100644 src/main/java/com/team766/robot/Documentation/Template.md diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index 56850b77..278fe2a4 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -1,15 +1,6 @@ -Brett Levenson Ryan Cahoon -Margaret Chan -Zhanning Zhu -Maya Khodabakchian -Alexander Youngblood -Yarden Goraly -Aiden Tai -Samir Rashid Alexandre Sauquet Nicholas Chang Adrian Deutscher-Bishop -Jason Lee Rajit Ghosh Debajit Ghosh \ No newline at end of file diff --git a/simConfig.txt b/simConfig.txt deleted file mode 100644 index 90952046..00000000 --- a/simConfig.txt +++ /dev/null @@ -1,110 +0,0 @@ -{ - "logFilePath": "sim_robot_logs", - "drive": { - "leftMotor": { - "deviceId": 6, - "sensorScale": 0.0524 - }, - "rightMotor": { - "deviceId": 4, - "sensorScale": 0.0524 - }, - "leftEncoder": { - "ports": [0, 1], - "distancePerPulse": 0.0524 - }, - "rightEncoder": { - "ports": [2, 3], - "distancePerPulse": 0.0524 - }, - "gyro": { - "port": 12 - }, - "frontLeftDriveMotor": { - "deviceId": 84, - "sensorScale": 0.0008866, - "sensorScaledUnits": "meter" - }, - "backLeftDriveMotor": { - "deviceId": 85, - "sensorScale": 0.0008866, - "sensorScaledUnits": "meter" - }, - "frontRightDriveMotor": { - "deviceId": 86, - "sensorScale": 0.0008866, - "sensorScaledUnits": "meter" - }, - "backRightDriveMotor": { - "deviceId": 87, - "sensorScale": 0.0008866, - "sensorScaledUnits": "meter" - }, - "frontLeftSteerMotor": { - "deviceId": 88, - "inverted": true, - "sensorScaledUnits": "degree" - }, - "backLeftSteerMotor": { - "deviceId": 89, - "inverted": true, - "sensorScaledUnits": "degree" - }, - "frontRightSteerMotor": { - "deviceId": 90, - "inverted": true, - "sensorScaledUnits": "degree" - }, - "backRightSteerMotor": { - "deviceId": 91, - "inverted": true, - "sensorScaledUnits": "degree" - } - }, - "intakeWheels": { - "deviceId": 10 - }, - "intakeArm": { - "port": 0 - }, - "launch": { - "port": 1 - }, - "climber": { - "elevator": { - "deviceId": 10 - }, - "arms": {"port": 0} - }, - "lineSensorLeft": { - "port": 4 - }, - "lineSensorCenter": { - "port": 5 - }, - "lineSensorRight": { - "port": 6 - }, - - "intake": { - "extend": {"port": 0}, - "frontWheels": {"deviceId": 10}, - "topWheels": {"deviceId": 12} - }, - "shooter": { - "motor": {"deviceId": 14} - }, - "storage": { - "proximitySensor": {"port": 2}, - "left": {"deviceId": 6}, - "right": {"deviceId": 4} - }, - "arm": { - "j1Motor": { - "deviceId": 98 - }, - "j2Motor": { - "deviceId": 99 - } - } -} \ No newline at end of file diff --git a/src/main/deploy/example.txt b/src/main/deploy/example.txt index 70c79b6b..ea89fa92 100644 --- a/src/main/deploy/example.txt +++ b/src/main/deploy/example.txt @@ -1,3 +1,2 @@ Files placed in this directory will be deployed to the RoboRIO into the -'deploy' directory in the home folder. Use the 'FileUtilities.getFilePath' wpilib function -to get a proper path relative to the deploy directory. \ No newline at end of file +'deploy' directory in the home folder. Use "Filesystem.getDeployDirectory().toPath().resolve("FileName.type")" diff --git a/src/main/java/com/team766/robot/Constants/simConfig.txt b/src/main/java/com/team766/robot/Constants/simConfig.txt new file mode 100644 index 00000000..4eb7c3f9 --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/simConfig.txt @@ -0,0 +1,3 @@ +{ + +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/Documentation/Template.md b/src/main/java/com/team766/robot/Documentation/Template.md new file mode 100644 index 00000000..e69de29b From 52255033a2309dd19da2267f3b9113d4b421f4db Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Sun, 19 Feb 2023 16:57:49 -0800 Subject: [PATCH 063/103] Removed superflous docs --- src/main/java/com/team766/robot/Documentation/Template.md | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 src/main/java/com/team766/robot/Documentation/Template.md diff --git a/src/main/java/com/team766/robot/Documentation/Template.md b/src/main/java/com/team766/robot/Documentation/Template.md deleted file mode 100644 index e69de29b..00000000 From ea0d9f683fea9d6a8c35ef65ed5e43c6b8922926 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Sun, 19 Feb 2023 17:18:02 -0800 Subject: [PATCH 064/103] Example of constants added. Ready for use! --- .../Constants/ExampleInputConstants.java | 40 +++++++++++++++++++ 1 file changed, 40 insertions(+) create mode 100644 src/main/java/com/team766/robot/Constants/ExampleInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java new file mode 100644 index 00000000..3dd6c518 --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java @@ -0,0 +1,40 @@ +package com.team766.robot.Constants; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + */ +public final class ExampleInputConstants { + + // "joysticks" + public static final int LEFT_JOYSTICK = 0; + public static final int RIGHT_JOYSTICK = 1; + public static final int CONTROL_PANEL = 2; + + // navigation + public static final int AXIS_LEFT_RIGHT = 0; + public static final int AXIS_FORWARD_BACKWARD = 1; + + + public static final int AXIS_SHOOTER_DIAL = 3; + + public static final int CONTROL_PANEL_SHOOTER_SWITCH = 1; + public static final int CONTROL_PANEL_INTAKE_BUTTON = 2; + + public static final int CONTROL_PANEL_BELTS_BUTTON = 3; + + public static final int CONTROL_PANEL_SPITBALL_BUTTON = 14; + + public static final int CONTROL_PANEL_AUTOCLIMB_BUTTON = 9; + public static final int CONTROL_PANEL_ARMS_SWITCH = 13; + public static final int CONTROL_PANEL_ELEVATOR_UP_BUTTON = 7; + public static final int CONTROL_PANEL_ELEVATOR_DOWN_BUTTON = 8; + public static final int CONTROL_PANEL_ELEVATOR_TOP_BUTTON = 5; + public static final int CONTROL_PANEL_ELEVATOR_BOTTOM_BUTTON = 6; + public static final int CONTROL_PANEL_AUTO_SHOOT = 10; + public static final int JOYSTICK_TRIGGER = 1; + public static final int E_STOP = 11; + public static final int JOYSTICK_ELEVATOR_RESET_BUTTON = 2; + public static final int JOYSTICK_CLIMB_RUNG_BUTTON = 4; + public static final int JOYSTICK_CLIMB_FIRST_RUNG_BUTTON = 5; +} From edb5cf22977ae55076524651f66af5c809d1c3b7 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sun, 19 Feb 2023 20:58:08 -0800 Subject: [PATCH 065/103] Added Odometry documentation --- docs/Odometry.md | 45 ++++++++++++++++++ docs/images/odometry_wheel.png | Bin 0 -> 39688 bytes .../robot/procedures/FollowPoints.java | 2 +- 3 files changed, 46 insertions(+), 1 deletion(-) create mode 100644 docs/Odometry.md create mode 100644 docs/images/odometry_wheel.png diff --git a/docs/Odometry.md b/docs/Odometry.md new file mode 100644 index 00000000..4959ae30 --- /dev/null +++ b/docs/Odometry.md @@ -0,0 +1,45 @@ +# Odometry + +## What is Odometry? + +Odometry is a method to calculate the position of the robot based on how far each of the wheels has traveled. + +## How does Odometry work? + +On a swerve drive-bot, each wheel can both spin and rotate. We use this to estimate where each robot has traveled. Each wheel keeps track of how far it has traveled, as well as its heading, and we use this to calculate the position of each wheel. + +![Image](images/odometry_wheel.png) + +Given a wheel's starting position, distance traveled, and angle change, an arc is used to estimate the new x- and y-positions of that wheel. Once positions for all four wheels are calculated, they are averaged to find the new position of the robot. + +## Benefits of Odometry + +* **It does not require any external hardware.** Odometry is entirely based on the wheels, and does not require any cameras or lights, and so will rarely break. This leaves it as a robust backup in case another position-finding system fails. +* **It works fast.** Odometry can easily run at 100 or even 1000 times per second, meaning it can be used in the times between updates from another position-finding system. + +## Limitations of Odometry + +* **It is highly dependent on how accurately the circumference of the wheel can be measured.** Even a small error can lead to odometry thinking the robot is meters away from where it actually is. +* **Error compounds over time.** Unlike other forms of position-finding, odometry error only gets worse the longer the robot is driven. This puts odometry as best used in-combination with another form of position-finding. +* **Wheel slippage leads to huge amounts of error.** Odometry assumes there is no wheel slippage, and that if a wheel spins once, it has traveled the length of its circumference. If the robot runs into an object but the wheels keep spinning, the position will be thrown off. + +## How to use Odometry + +Odometry should be run in the Drive.java mechanism, which allows it to work even when Tele-Op is turned off. + +### Initialization + +To initialize Odometry, use the constructor +`swerveOdometry(MotorController[] motors, CANCoder[] CANCoders, Point[] wheelLocations, double wheelCircumference, double gearRatio, int encoderToRevolutionConstant, double rateLimiterTime)`. + +* motorList, CANCoderList, and wheelLocations should contain arrays with an element corresponding to each wheel in the same order. +* gearRatio and encoderToRevolutionConstant are dependent on the swerve module. +* rateLimiterTime is how often odometry should run. The faster it runs, the more accurate it will be, but the more memory it takes up. + +### Running Odometry + +To use odometry, set a PointDir object equal to the `odometry.run()` method within `Robot.drive.run()`. + +### Integrating Odometry with other Position-Finding Methods + +Use the `setCurrentPosition(Point P)` method to set the odometry current position to a position found from another source. \ No newline at end of file diff --git a/docs/images/odometry_wheel.png b/docs/images/odometry_wheel.png new file mode 100644 index 0000000000000000000000000000000000000000..dbfd45d6e341312fb3b3d32b3103cf9d1b5477f6 GIT binary patch literal 39688 zcmeEvc|6o>`+ucUA(bKtB}-*3WT%BA5v63`qL3I_8fIcn*^&@qlwD*C$v$SxK@qZV z*=Dlu#y-}W@BPs^&v~B8^#AYm`{TSubLKPmeP7#sE${0ZziXPROnZ*(*|KE|liFov z?JZlj3vAi4&2ZOF@J{;<3NLus>ZGlDaZ6_1(NXY^?N%4AUf8lFJBVS;dvH(gC8ac<5!F0VJ+%x9sBY7d8kPo+?N|@k;bPI7hG*B*`*Wxg zyj{L~QSLwrMy3*aYy>8h!oi@sUh7b{O+tw^1;eiSo)~<-wN@q&Jaz$PaiK@Aa17?d z!Wy@n4c>NmvL3iS&A#pd^w>P~QwvqUs zKZ`b`@Y#?Qcsu^PjGw0QS(7&N$KPsIJTckd?r{Djl_D#}MQP7^y_hx?%vz$|)vF;h zpYQvyoZD3NPoWA5)Tf;M2M40zVo~q6Zl(kx%f;4n{Gt(N(&oE2Rp1$TYhz-d*^^!` zzD;*kN^}`^xwH9M%|+pOYxx&9RxG2~MGu6xwH;iMSjqbE)$P2fOCi&8&{U@;rHP zJ(k1MubCW(9;)60PWbd3&=~2F9jlL?Bj1)b-?14z4^$BYK79%~ z>oFl*`mw6_QqtIX)*8N!+aB;f0&#?9{=X)&Bt zW_7^GLM*so;t(pU?l&LDwuiHO`n@Z1!hS2;PQzfI`AQL4xAp~ejC91qQ&n|oeXr*z zX)II#`$^=Dr{BxsN;M0$Y&@Es1~G5HU+Z}hE1F#K9LpEcVCd5}Xt|1XVWPF4!<3R+ zH+fS-1qcT;taXmcj*wavXqfI#=U0nIXYZ&*yJnqHd$Bz6v(8(NmLDt!d_bk;t% zV5bU<)^6^vLIPih$F>~S7>Sm-m-Asw0ZC7TJmy_Qwp&6{^eiWQ)E25(C?+^x8n@p2 zQBp#N;qy|jTZ6r#Yq*u2w7$89h-RLU@;P9@$8Aq0kIB(Eqc;<3eDDaO!{<~)Vd297 zye^d%4f`fx#^1ErFcLdhFk)|W3s#Yf%rs<%Cx&8QsCVoXJmAbu7KC8qV%sfLJ*Aw6 zI(@7m2JrEP$j+DmssmOvwS65Sv2!2Z+!672T`DeGc^2jNO%Xgo`6gkLnlVFu&Q0UY zDya3I&W2;`IaWtJ{aRM}FFWak;jJFg;_gcShSti#GJ$%rE8WUGbZ8k_LCg3gWKry4 zwxQj_tiW0gG@eKlk*Xv%@1?aZ({*?APmWGvXKqIrU6mOm-JwO>1W}4eC${P^&@3)W z8L>u$);Gh}jq~9JXI?g(?kFlJ)+o~a?3%HQgqr4F?t6^^8st7qC<6iFyxVx}q z(M0H;Aj!O^wWFTp9|R&Ji%dT1N=t?^*M1g=;cv9;e#BY^`d(DDRQq9##OK_C?a!XA zDbUm67f&Yk8$U$Hhuz~11k zZqs7!qv`2Oj!SG*dq#febw6bq$9r&c)e_C75mDy%L^6FHcYuY46^UDG#+mFg-y?89 zA>!KRT$Ee8dGsrBzp}C~%d%kjDw6Nq=2FgSk2Sl!bj?D#cL&SlBqhd=#y#eXt`=p6 z@8Rbu_rvO%KH#UhhbU{YVENm6$!0ve1QcUjvvLdamXVmPn=`{VC@m}Si05u$CjMI) zMx&%r8Ww_6Buy)3Nm|Y}0wGy%K%D0t9`tNkH zD6NtGG2$c_y>`43qRJ#?QXQOQ9iLl}yM)Ay(})xwMyA_XVfON~ejy#yI7u@u>`6K& zs2-vkB({^qYPdFRap*3pK9Xh_`jCZ*Uo(KS^^RC0bjx(G(+p{+uA@Vn?}!CUlCwoT zcYmT4!4?<-DL8BIj4o9k&$Fe(+@%?47hiHGECU*TQRSXG6LF39XD?hT-J!;=RCidz zQeHycV0?T{p}3OPUf_NGJ6OowtuA8M4aZ3x;xuW<5^1Y~#xU|XaYqr-%`QHm6=_Eo zT8lkEl=T?zWD(ZQT0vF>(n>Z=eN4>GO{_8FvFm)PxP#>x?a#j9S1{HVAanuFJW8r2 z=8$RfQBx>QD>`K0dU$Cs-~MIXwDIWXE!96cSx&wgolhWHJB^&2YGC$#wqzkO|a z&|F65Q3|;Hqvh3()YPmgtoqVCLuoRwS{2tW3a*#hG&wJSz*|vil2f7ZrTd2(U}oXRc_BCObTLs#W0xoN5hohs5WG79CE3LK3lyUC0U3gIEmY>k50NXNe67}MK~ ze7W=Y_b8;7ouetAlW$7BGEbQA;mZ{%!POC)6={DOIFBc-h84`gw?8YeTOc1jOp`)g zmtZ?yFMlnsxYjo?9j{FpH9^%sE~lkj1)P9WycTVYz&DY<9dXmc?JLpAj3%EsQLod} zc*nWKbTnp%%kzQUIFdKte zdLHh{4^gC#w6BBqTq!B_x}5sMU=4p*)*RWHwj|v($TSH9SJOEVO@1;ww~EBjOe#+q z+6ak!7gnIsXPMC=gHJ!wQX#n2n4=@_oi%BTlaLC%^uX2-o3GM5HgTXjI}1u^0Tn`c z8OgYn5u1%^KN06#>FekS96qsNN3wLP5{f`tjtsd~|U*U_~k-(Tdp{rFzS%f3Y_R9_O;5iOhl{X7h~>HZHHC7&?`DD0RL;}rGCVNwnT)5p zi~hMZs)agT8N`idrOxN2rJZ)`^=6Z;OVs;dsaBaEWARK5YM?m1fxzICkcWS$ zK0Hn+cI|2lJjNp%CGAdHYUntEtBV&-ONW!sXzy<*8O^?>Ry|CDD`^jxHLO@p87i-U|%+vxHfFST0+1v~ohwlc?u zUbDD+t_K3q`=|2aFE(Zmtb9uqO8^k--eL|jCD?a@r|`$wOI3aOG9hhydvT(p>Fd`K z*eKVJV&!!eeiiXL@i~VbBOhSdA>X}-)p!rW_e=QN)$=`5@mX?uVspMqYw-ia!>fh} zpC1b}=1r45r=2&9?!Ac=&4N8D>saHBGF05_KQTQ#0s^WYE6uTpQm+`92eSieDE0ed zKa_xYgfRXE_aS?f%0deBc~W=eI&=(o!|BHzDJuS~Zg)Cahpt??GFzQ1{6(c_XwuU- zEG(?4vvbUlvh#@YcC@21Jqu>1im`F@K~~lyv7#x*FZnpXv_XFLUxz}RUxYf2CgkP0 z5RAix%8Uzd#s>!cLeQ@fHT~DVulpkHYf9rARV1|Tp4X-Stg3H{TF;Y^kXXtt5BO$I zp6Z#+fVrplYX^SbA?C9B$)D{`O}KEyu>U*aax`)DWb@*Cw$&c2!aHwJ?dk@v(ALd` zSGvHTgCC}(h_06w1383!Q8T29COg}3y!|7gvEj)yJglq4z4&WdRj9!C9T1E_Fvtc1 zJ?2|UiHV={Y}?nqUPw$zQZYeJN-kGOm4KMH+=nSt9WAnK2;0tb=gu9+Z+~s=pHpc^ zEsIisw+=|CwnKGb$l6z1hMeaeP+3l(j zK9iI23tugQ)UI9)z~{jnYJaFA8nqb5#tNj8uZm@g#_Qy|h2pK+vfC4I;%zxU-b2zIN9a_2Ur1gez+C7b%#|0YOrOwWp^ z&EUP+W9rD1`447MC1KoNNHlbwJ{j@?#K~GAKK?r>glx|Z3WF@kdC9FV0$fKVBDOu9 zde*Ca|2+|^vHnwf4gQR=J=?@LIQ0OEJ;wbilalgb3`KALo2q(0Y1DNWG^sI4a- zkPMb#Sdk6i9Y?<~_i!Tw{PW&6P<{PTm;K%v($O<{l129yrla1Tz#>nu&}3|<6&)Y9Ysrnp7v zkC#GeQx6C)Hi8%4T#$Eo0rGAX!pv`I<{4j{nsD*#-Fk@9K=NOJWGD(I_dinq6Mt^U zxwPMj4THRM@RYt2SJ=?lJroT2o2QPs=pL0n_BU7EvPyU+g@r*xc7Y}VKb;?e($-H3 z+78q0&KTHVo;dJ^lR}`Q`)}n6*zqGE;QqLMMtbPP@*LzaRTnmDJMp&?k>6-D%lm3i z`!f->&X=p;J_@&QcHc=yTYkPa8M~kEkP|F}#G&IL;?^fK+FWAbz^E&A_GWyK88Z#X zGcKKppiMTO7))1Wb*Wg{hdBg-0nRQdGu51USbb~R)i6X1-@Z@j* zqq9Ftkn2ch)n#-u%M^5%fnvm!8!Fy-`0YPw%N=D*WZ9wk%!^%PYfWs48QF~>e@mOp zDyA+4ZS87Pecl!4%hEwr6G%IS;73oJqbmu;Q%0FlMW_&&mxU&$;6b73r;^ujEG)EH zG=B@eOi&1szgGy70M&@KGd7v;=E<5ywDo*{y1lVf-}PWs$-9Zr4qdIoCBnm&k;T6ea7R*5+y?-R`Xd)@`H{65XWJD!(K5(JF0DAES9TB;Mgs%qe zqMt7?gz71?q6%XbkAJlCGOLPV{T8Yl*)ryCfrVu^3ZeHgF=`;%Lj?rL-~7?o`^L6)8dSw7)iWHEhj+$q1|fs%qS10eGSxobPh= z(ah)&`PsUS7~wOb?}1GbqLnDuO>1*OZ9Y4z-0dGEU*kC`8g+PuqiCM+2aI#iL0Su` zK-tj7md+LI%J1z=2<7RPe|4k?_ zV`Mz3RK|EO_RZLL_vKeuF?ipN$XCY!HsJ`}Zeg6eb;nfDID{M@( z>&wX=VF0+0@IBBj2t=Et9aQqWXQW4NhhtKbPQBQ5np~tp=!JZVTD z1l*m!?KNM}VSbQMQU@t4>Qjm*ZBi&qTYtSa+xt+BOR^jIbW|e8t^_^h{(GN9 z)<1wjp=*AytQQb9!) zbfsZiZpug^-ySXQZ#TX*)@Q}1Bv84uL}C3`f)3WgzDI_T7kCo_Le_Sb8*D()67aQM zb~hI@qa7d3?}Fs^_Ls{r?q-XAoxis>_hB!?c9_T!puD2v|AS`C4BOW`*}oYY3U-_jP)lGu5`05hdLni-_r*|o0v^*4O(+6(Sf$5C7Wfm2EY zIB6?i*qg42y;tz1O?i;778D$qz!pJ@>~Gt?gk%=_jchzf#2HtUr-E;QTLbuzEq>(7 zS3B9MTj`kpCFn0z@{zTW=p1XF1h~%z6$|tX?%i8cW!(Fl)z+ca9-^8iI}TtbXRTJ( z=ov+R^N4#gs6|!g@qq-ngF9ZEy5IA6J0sZupZJ5;!>ZIXCm>VnR$~(0hLNRS_uKlL zGm#o{_&y9N-eo-Tq)A0I>ut;;cd*`X3|gg6jPP~L_#3YJ@Xw~%Mh4?7?+5ML`6c}p% zLQ&_)?A*F)AwBJr72xwf`gRp78Qva<)&?nsP%CxiCp1MIgXa)2nV7ln_uTic+NBH9 z2s)YuQx7#fs8;b>3M|pLk{>eJg%uYp+qS+r*82Q>L5y&){N&aRX9#HCP?Tz7cH&o* zvMYdLZ(1L_4B$g{VF2@m73YzN5c6h929=zqAhuOusFHD#qZ1sKHG6t>V9be{@%k@BZ;8}(Km)~~|= z{r}L#y`r*o|RRos^c=t3(Ul-xaRmsR z=xB0{!H|-vCU=58hg-sDe{dLiOt8suA&r{y*ps%5VAp%}w1tLa4DU1Y@Ce$i989hK zGR-YHO`94|(Rf2!+rd6e9*FrgfpoQuA}iH92ntPvwjm`)2imM_GzD^!e+7gG8%b3$ zo|DFmIS%V`8}Y28gE>u6Y2-%f#>$_v5q}Fb?z1epZ>~wtU`*-sncu9*hLSSEp6r+# zX7_yhx!Tn=yu~tcHRy^EZAQ#j5QQZr9nD+!sBxY7a`=z!VF=>(RO$DoiMSq=WnZZx zs2~-j&;7c$hKCiLGxzdnATuAZ{1sw6DK{+sxY9U8-f#*m`^soOogjeH<-8h_dx{JM zHSmby&Dn6A5V%h$Zw_!T%77LjH|DQ~w{hkaP~D+-ZyO90mT3aKF&f4fLRS9dkYnS!kAfu`h^YuR4%j51w$!X|Gm)~Ex@kM7SPzzDegY08f;8YEIq8BqgygSZ;^p9e0$ z%NdI#=XTX5LQ|j8*+;Y&RRu*1?c7h;uXmiKA3T_hgs>D!XR-f0R3g0e*Zr0R75|L@ zi;s_QqujOu3v7FF{E}>SuENA8kM9jPLr0-k5QG)`hoPpTEKBC{qYg_M0IZ>{1?Ngo ztXtSwcwm&A$Co8}bD_l|5UVl#Euh{B%TR#zca?n)D0~)z|Lc#b?TSvr%2##H$3%hZ zHi-B2kyA?nLZ|`rxjC=GufyM)fxykQNh{CZW`YP1lb5+RH)M@5=4rX3H5EU7rg^8tijAvLimeh^L(`f2vU6|30Y3b(9t`*>JcxeYQp zAn#Pr{n(RM8(RTK%kc0^>Y%_ zcv4<|8!C~V_H$~@gEfx50quMc3c)gL+aI3Bbk7(GHpCn`zzK%9TID&V%&hl%ED zT>!RtQ6$qnr?MDkJ<7)gGP6kZqpzEGJf=8d)6$-~@Ab0lLHO6N9jXa9uI!xjoLeAC zPH~>KGM5RTyh$5oi%gxvHU>k?0&6T3#exdY22t!TiP|CBivvc^my$+*(S%7xXQba4 zC^hF^EdHQfy=IlG3UgK+Tj>j(19%5s$JO)LMM^`vOeTgdAiKo^?k=Q$mxRuM#e_d` z(rF?Prj$aBUmr2FT)2kFDY>T+%Za~lsP=u6?eU3ioV14N(EK@OEjVkoeV)J8hyUs8x*dRS8|Y9!Odb>PpNhI>!$l#Oa& zx!4rQR)h5`#>Kv}jz!6@PaarrH4c6F$A{P$E5_pqV=8!iE2`WxB#7yYrT z>RR+Oe#$Us@u-obnj@unpDjI&O-(~P=+e=TT4$s)Y6Z0uGg=9JTy&h8$`pBF9~Qq0 zrY?~C@G3~*K3GPbR01Uhw(5_Zy|oEZo*dCER5l%Ug_ZmL*%p4T12g1YX>o$i^YO>F zClQPS2SQCo?O|vDIKNVHA_t;KH0YWcFW5dQxE2HT?*0I=L!usx9xF*qR300(*F)#|fp7VIZsJ#q~(I*2rEa{@mA*27~GAYy*QbzSzp~xskci z(p*J6B`U^Q#Xd+;I&Y?vZay#e%ITMAZYAEJ=N+R8L5f5jMyYM6W;=|Qt}^A_XZ6cRI5=?U zPn*Q5UUhjR?)qNdUQ^H?l0t9+d|) z=NIP8q=UaIkJ%SfI?x_ibpYG8fOKMl#VK*6YduL6agFV0 zV#gkVCrzHMO=WfTD8!;m=S-g_ebL+Y>$=U(>oco&I$=uFi;Z+Gf`^zWZ5+801=Yjc zcj2%G~PLNC%!2$|J7Edh{+RLAHd< z$jiUgM07O{4B|3}gbZHAvvIlRc1JeGOaT$3%hR4LeW}5r&6f=%T=)m7o>zGEPV?<}y1NovxNW=TrA2AB- z3PX2-#EAGA9^xClGCx4qEAw+_q7J)`&CLz035u!#ze?_jFAy$p+wzj~ z?l@*J!{0sF>Y)YAV)!8gh{FT2m>bw03;8U$H-Y(NdiD6=tJGDjSznc3>}9vA3^cQH z0!pFXWd{c7j@vD;GS|6~R~P%p!kw-)&H!|R~ zWNOzD6U0OuTgtrG)SK0v^%+|)o*!7{RF`gyt-s{wq3FXxR~g1qIXHn8u-|>^sVPo$pN=5DfAx@=esz2IIoQva}5#Z{Ma<*SHCHezC4Y2 zDlbOTl5QlnbGaSMg5w*C&E~yIV!q`uSxV2exFao>n^gxs6XZ#OhmGUW9@~S?7@sr0 zNN#lZtmJclJq#N)2G4>WK2ijC;zOtaR}(u40i;~^a3u)t0(Ih`7f zjzQqB_9~;4nE7Uxa}$)PrTjwpc7TVTY>k$Zh`8)NWJ7vzc@y>U?%iJQM<{bB6Un5S z*a`^;KWRwldl!u;Qq%I*>%~$*!p^QYRgOc2UM> zQuYPa$j-}b13P2aEL5?(>jU@Ky0OLlw8ERdrecnyqO@uxHXXCdu=&^Wuzh@Vf31!y zR=rV9);ZZWuFNmQUvhTfV-F!;kL{!U{7kK3JpXO!M)Zy|wwV&uA+J_(mC9KhjjgM- z4m>kZAp{_uLS%;bTYz~}SbrYhg>|^yo9nKve^-(2LJ)E< zNs;*Al!`89=jo_x5*oWb+8Bb4z8HJ96IGLucof$%nkR5uI-WEG%noOLPbh!S+tux> zFq2>&y9_DjYsC=tdASg~E0O}nH_|0r%5DOnV5rZNm<8Ss_K};&#HTQai}fe!_*w^T?LYUE>rwp0&xSiPV!n}PGi|HqSnWQD`G3}I^YCj(< zNugh=PQnV#ereH?^LQI$KHYbMe!w#?b(X-9jHM%*8Co(ul#V|*qzgy5=csxNcpvO) zj~<=x)M>s!?&%i2UcQ^}L{Z|6hy%-R)}z!wd4_@PV#P%f($lx;u145wz2X9QkK6$@^7*n~t2-MS+=kbLg)yC@ zqBCy|R@d4;46nZnq-uIOT&$`|8*$FR;A~@-4Yv(H`ZcU;2IhBE^W?IX;9yaQ6f0&T z)0w-cU0Ig|x3GAVo13e*ET2%G5a)cRsr2r9R92oTs$OvK1p0Xg^AWmTHwJ}_j_GPu zdKl`ncxE8qZ|2q7_IibzY?5N+b7?sBy$PnpJ}h~81tw=3S?Km_p3D%oBOsT6`#MmyTWU%p zA&F{8y{aU*u7ODaG`uSvZ}d4Mk|>^+arAJZ-KA^ z9Mf^AW!Y+k+cOFI{?}?7yi0SASuPlTloyy`Zx%_(==S#W=Ov|7dh8E8emoB!Um%?B z$-B|?R!h={`Rx@jw&9>%507x(%%oZi(e{_}BzM5u+uJdZjbVas8-k;SDJ$kBU(O=Z zUo0H$jM}NJ?vxJCf4q|gV{&Qnm7{1>;UmyEM-Mt;C$57cV~f-Y+)|wFMI)nvTiO*t;`IA`WI_8o08d;wqOQJX zmCZahT>DE&KGBemkp4m-Nn6&G392p;M z7E2DQK4E%gv000~+&8nj_|OPJ;en|Z4=VuP{nF3i+>Lf=H?n)lRHOMY>O!N==))c@ zGIOEpOagYH&5(lX{Y#Og0Ftaw5j9cswHYI~Mi>Al4d5whEitvTv3DE*>Tvm2!8x4Q zs67L1Ju-Q*pv299Rg?PeL`s9>{T{(HoYptw}GPN z#z5(~#QWq*0;k-8tu6JDzjQkOo>G-PW}lG}77{IoeNlQ)G2%362a=&yt80e_PbsPQ z0SsmH=A)$iW1QOu=PBpnthfrbt|)aL7vB9y&;%?O%m0;JyP=3}u`5~o0d>y%!O0Z2EW13hzBK)vtfeIkEtt1fofVF&G{ zjigZ~byG{%>J%3e&pZ;-0p8?bH$%M}g9XMR+zUz#>Y;8(9sCvOOFldGWJahHJ31*f zyOoMAY1A{|;gid+sq!O#&X)7AgFO9(lHJ<5F8*+a>+SLQY{1miUk~?+ah>Q0;j=Ye zG62cfu42yn*Fy$WsI^H@K=Dq^ zDl~jXAZ}C_#J!<;Vt{%-dC}jeg87xsT-s5wFClr>8V1E@RRB!^R1nAK`t;pra2JO( z?CY-HXtin0vOBJ4=T^STEt6LwZ!61Ft1r==*pqQ zJ3z89oFF2BS_WMNRHvdBu_UVHQIIwSD!j?eG-i=xyvSLfeZi6zBM)Cu(#dzm@UW3x zygcKhC{z_ddEQZ4e|huKgUg+-Ut?o8pgx<6sbb+ocLXS1=f0&P{54jC0?rN++t@Gp z#l1Dj%JN|%?c#;*Ur;PL4BPq)f>hA@Dy$;4rta}an9>UyysOsRwRt;>eT_PkTxWFl zw7m<*Oyp3+BR4>En`fE1jkq|AYYGFEg(L?BU~XuH#%k-TqnTbX~LNHY3<#FhHA2*hgfSsl^U265rc_Qi$D03`toglLiaXVk&s z`|u51+poqV*rz+tD;Mw08w81pIo4)UkCsJ%opveO5^7kw~`&Ww(L4EUuzb)}4fKWZeg!;4@ zQdjp|9F89}&Y$7tz{$BNXR7Zv4(iEMH!$p4%2gY3tuYU2BB#-H^x|0%WyQh3@&xKvt>1)^b#EEoT)-C z94bQa>j3^YAC{lLiOjcL&f-1yn=K)=0NnOeCsqx3Bxii~Dzp|2qc0Bzmp36MUsIp= zMX#If;l`vBjOzAp0FM5Vo}a7yTpR&>pMY$nZL5RC)cf^h+fu3fjPA{3erOFQd=hK!d{R7O{YE-@O`IZVZg=d^cQtRp>1@9Cq%{*a3gX+w$9b+&v zGC-n|BNJ5usygTitC(;Wi$AJ2?jGMU;T)17fYMN_fYz1L zF&)PtidyuOolN|{^f^5Zd_jUa@NzKEPRid2Pc>)bHu_w z-#!>jFQUEz5cbViw`UtJBpiA(TT>oFp4A4^J@Rji?6b82BLyb6LgIX6kAor{+;f|_ zaR7<)Wd`7CPZ1U$Th>NfFml{Z1;uSOFk=wg_Cx(+K)vrJSzW+3-=`BGN;K_s2lW!z~wsq9QMH$fZyotMa%|)Q;DD1Q-8XzPW3M1}l zg#pol`vyRrYvRQ3XrWEQffNkAQy>JexQf6Sb-p)gvZ^SFxZ@lh<4`alin*XFvP^6MDgN`tB*QYlktUTCkxb(gU@YXi z@5jCWv)5u#C#;B+>XnE0(NRDjA$TZJ_;v;~Z4rziRBLTFb+a;NJh*|enENL&Jaq=_ zcHLjKt-CVOp&voY{Ss4h5^A>ow_m~HRX>9D5&+#ePJJ5QK+=$yv)fX$-|)g`E}mL< zMN1fAN2p$peK!z5|B>_p02IBu_GF*>sD+ElMA-sN9ZbqA=uYql{qg^Hkl4NMhXNH) ztA!)$pzdZO^KIdEuEy*s9Rvo>ewpV78gvv~7ftaliAsyqoVlSZ zGx-_X=+H^(!GaAt0S4;==BZeh`(5sgj7;L6e0~sz*M|ZSxS?n>IwbD)vi2MDse04w z?$z5ZH%+FfyaoTx7FE`B1}cq!H#h7Ms26p=pe^8nlCgT%>jk&Ua58rRN1fOEnJ-GSLsItWouwdsAlAyqyskgC7v_44a{Cv<9g zx?;VSd3|=##FwQp$=`WM7^x4Uxhw7jH)=BPxqpe~paQpekj-{@gr}W7X9e$i$5J}j z-8~ciDEAV`@2|zOnry(b?n*!2P|vbIOOB7Dg@T*LP4CW^41(E*MT7oYFm>u!=)%W- z?LrD?s{HJoi!sLkj!yMcZq2ZjeL1!A+0a3|{;pVUZAlBH8mpsjAKZsLKg@J^Q?$ze z`w)x*jLP^^5I_M%!4_KL1}QDs9Rb7d6()mKQ-=1L#C~4z}3oCLd>T#q3#X za?i7LQ~MQ$4Qc+z{pXr@;Cb!i&z5wb#8riKvk6LnN`4yx+-Z0AV$f~3VSEo7jV#q% z!~QF10R0ef=Z-cQSGY$ilgt{S$`uL#=GM8X?B>ldB}p`>J8N=di~uRA3P?3^q>NP4+m+A1ow{vGZ55Bf&nk@WtnpaZJq z?p;?wpIFeUL{g6!tQR`=iqW2b4?5bYNRW1!?D21Jy z+zQLSiW|S|GOK2jmNJd{!2U00`eQ z(X*-W{9CCh=^+eZY<%ews+4aesvcz;iR#n2cO7FHW{K=NJ$5=N)#V#&9H-D%lAiK- zTh3T!j9M53w9i?Bf(>cG6~j?+D_5s?k4Rjwt)q`CekQo@xu~aa2gh_$72UK&a0S;t z#ClY(j)#u=o1s9~dIntv>sAbG6Y!(XTdTUEbRnhyd#vn_Zy8}T4MJ6>l-F>2L0rvE zLyI@mJv*52*@Y4d1h|orzUA z`kq*>cF8>crn^gv+=+{#!!;n#SVH3PNeuF)ddog=cp8{CNlg~u%Je826@?NM|B2k0 z0M?`#z@?+#jvI?&m-L}IoBinOnA2^d*;a2g7BkgFI@e+fUUcLosJGd}WcPvXNT19& zCGNx6c*s_IzdnNX4?Qz{u{u)SpG|YzKm~IxiO|6VCSpO29!tdr=~2H?2Jq5_3m}yLq{&{xUs+&)lhx9cCqe@1Lq>L@6Gs@QCX%i zU;MOv*Xa7*SjE;QWI^(?K{BG+*kWMfh8DtKT=&s~&kW~{1Q?yLqM-XAZtNcok}CI8 zjBDT89#b0v<~Jby_#}Qw!=(gJsVK33fNLjw%gBdqiEHM#mIO zKR_7A%%8i$qG@e&zOkYE8-5Sj z49_f&7&SK5%r{bePn46pfFeOyAZW(j4A}yE1-AS3?8p9)5=U<~#_`GY>*pi;xBjrB zvTcq0DK%9^Gj~>^U8JTCp7n^DVR#<^L2=-xa|lVwS@1S-#n$0rWO|$ z!R$YSbx;SCh_kkLaf;ViELNCz!~m}u4B#NwX*7r*lsG1~9_VkCq#1J(I8LtkbeC+) zb@$ZAPoJ!~{rn>Vx6fPvkt>*%%a;VYnV_Lr_Q%_MZr`8D1ejMo0AYv9?SyS{2m?oV zj~I~YU(R|@j(bhK(}SUSo|1T))VE*LI*H9{C96XCE6H6IHu)~zZZKFB!gGZHaIdA3 zLcJVA*<#0CM7Vb*XQDrsDTq=|@8y~{QP+ZBySR@1`8N^P&ph6_9rNO~iBtxvR6W{~ zn&sV?goM=$EH;N*!}PP=t?HhB-u_;F0-Fa;GRB8ZM@l0Nl-qL*V!2H`jc1`P|e2SNUEK+`#GZ;EF(}qe}n|%*o3?rCdCfy8{bqiU~;pRE* zHV_>``Q|JGK<-e=2K@Z<4Pr0&txL4|K+NpuMja;PbpTYq5U}cp z@gKV~%_NZul7`IM63UHT|MkX#&hfPQ=K$v=j5zkeSqFy=`e{VGjR3@#n7Lma5$JuVAy1(6>SR%9jA~oQIPy$8J;+_;@@6(qrMM-k*M{qtNUL z2&o|us)^W(tYnM&NI@{M-%eidXCU+8%DB;!{)hs*O zJw^w04<7b>Ob8Ef=vy0nMAhL}^jj<%H`o)vCpG05k3P5IeNJCjNVGbebT#q-dV#C2 z*9lka2wL|E9fvXe-ZA>EdIo)hY8pm!ZrE=>@9qARHXk33^bu~#MUbAKh`#6!rs|y$ z{=#1Gz|$t{PI9e^kSs4&u_Y|D8vwt6v_gg|xn*p|440U{&S!nfcbJ@`$Wjx}93HXj z0H}^S?m5#tec~@-krw)|+G`NH(I0xakqkp)(GNeceId6Q9{#*wb$iAQphXFG&+7qp z)Q~af5iyzY>Ig{1m++7sYKLc@{Pepa`|bi>zjU<{8>uFL>dLPM7#G)Mv+=DVCccUd zy~;54`p=(1=T?<|?zLGoo*&BWgFeaW`4K)b%(OM=HOe}7&S(W|%V8T3e;zjeN?iR(e-32=fFN=$V*{ZOPO#u|a!g|!D8LC{xk@kRXMnhtl3W&x?3Dpi89atN z^IHvhr$KBKg0oE?ctm;CGC1VgUNOGa8k$vG9HMv7LgH8^zD1V4OK`j{J-X$hyJ_b4je z<`#HEYVSWj(?;tX9yx!|1xNR%NQEwTlCJ1IA_>m#X%Yhs<)1lrDmcBkx%);%P$-y{ zG^_cb-9=$uh()2HnNAN!Fd@mt`BO$sqZg*=5RDSN--anCi;YJFsz|B;g;9cK|mk4vaW&h;EP zznpZzldx65r4JXa*fpg{Ru*O2v+(dE0J1N#Ch4q$;rnQiIKy^1;bVYrs>gZpI8hyLi{!SaRrnmV{?c+fe~(4c(mX>OR|ac+_x zU+jd@iDGzGr~EyB|Ao6Pq9^1p%k}8!MVp>jbP&q@lSVL z%R*;zCycWme5XHY)94@o(12C?Vy2*xc_=zM4({4OXV2uRL5dH!@(~Q(=u?1x^n|1- zz4D3;)-i!YA^1a0J|tQ#%(GEE%74(o0{6K{;z7d&IsBa5Mzg*TBYR(%jbVhXm@{>d zL@inC=cYVf>xx~=W?WxHp^=m|x!G@U>Xn$aVtgXJL@e1r3!hkeFurL(QS1U)~l3}2Y| z%FP}t7{2m#y0iS6VHUZqOKI(~5S2ome&Ul%nSu?(lPG!JRIt^43fO8Oj0#`w0909< z<6iGwFjZ?sAv1U|N-kUvtV*^;n-&3X5H< z;;vCz@8$js$1e~Ev^+@U=L$o&XULIIN6(Lw?!FJb0~10d1%&>x#k?QUgsWez4cNgx zH-}R>pA{v4JWO>jQSa%@8&0S|12v!&gg=4%(i^Lq*S!G_hy;wu8*1%pXC1N4h@2O6 z8!stot!JYeQSieaZP$Y@C=cLmM@!xgKh4v~!WATudO%|i5+2oH*fS<OWIhE;?Ys10x#-mg zn?}ZtT!*y#h=;GAqwG`G#{H>{*QvHM_?{FMD!-E3%;GrpVa}AXtag6M+2M*g+)Cl2 z=}s2H9LfQgFA_Vvj7Y z=YEg=^2Z71?0wc*Ywfkx`@YR|)$Onn!|juurJvffp_rEzv}oZaWQijde=2jfIU%jK zz~yun{aSnu2UM94owf9#m@hHBME8ZTzGa;J7P%2(g6@b=ib7HDXLauyXq~v7F)(0E zWsM3%wFsJ|);=D`er!bi)34{`ofMY>(_=XS=-SN=ArOJk)-tFsH6Re}q^pCI z?f2<8sN~5{6c-kNpoYooGNLqpMoqtvN|~QZ9vKDUTSUAg`In*t3@7&s4S`ENhTl0h zzr{n;OAWZYyT8&wqG$_!$7fxzU)&ZVPr()7TCOPRpFX$<}QwY#BZ$cyl+p&)z9tf4>S`~ngG!D8K2QglMb zo9gukq&JNFxK-dxq*HS>rB=q<+nb#>w6ub)15r^? z&sgb!bPLU_%g!oNr_)Om1hE@S4yCXE5YfDc{ZgMjoTl`NFBi-I~4k~q$bUA=s_ z)uH^NvtQWd=`7yiYa2m9{tBA5$fi%>)N3i^T^t;iW#>Dd=<*v9`L98l8{uwhryL#S zFE&Nf@WI8T9Bo$K=;-Kt%m(QtyCHUSMF=Zj?jLUA%4<2spF|67vRKlt3HBw} zLDj{_Ww|=ojV=95c?3jsw00RJ#;nta$d&C1;EV9Ey7 zPEp5?INVsAmE*()aV2FBhqqJhSthe1;+$Tb%S3w?{-RK9RR|<9m83*e3AC0KG4KhNyr{t9jv$JG_8pQ#i8PVl0nmBlAtK z6!)M(5#({#<3;U0hi^9r@FfRr*9>b*QgMqXxFH}z2y}zVjT>cOMy0i9{0j#sOo<2Y z7OQ8t7-~^lkMmR`EbZ%gSodZdA?D2jfuFg2NqIR(A3gz`#|yJ>6)+spQs=rglqg`- zi!~i58a9B9k{}ls7sqED4~3=qO=Kl}fn(wd3uPAyuuPeSR1Sj^Yr6P+2UiG@WTF-e zJK*5Dv!M(rwkR5@NS<~@$Q*5Ob8};H>YofPbyE)wz$}z*4C_$}c^ru66h z*G%G2Epw&ow}@C)owVQHc;8?!rN7^vgS~E#I~>6DqP!nTgbW3tAp!vo9I82I)YlAt z!#gBUxJ^L{J@_hWXV$!H-mW8@%7e}u@>Pc#6A019rz&w+*{A2RfWgAf#mBQ+_pxyC zQWd?uXlMlRFl&mFk1C5Ok@|Z$m(>KXgJ&R$@9t_)cKJZ<4!05w;Pg~Y5v+4;N6 zUa|4(Z3BiIc_@_p|67TRrNEAHEXo84lh^)_u1bh!dFiAX8ue<1OFwD%VPuq`P$SFZ(!jH6dRCo^p z?h_q_msQqh_g~dd6sRGKN+Pjbh#~>g?_cA_o^}qfvD9=Q__QX*00GhL zX@t6*IG2~|2Q?&%-EV0y5NE6%=C!&;_mu#?>Jo>|!q;>wOH+9xPV6vq))^SutCZ5( zUcSrwwjsn@pf%TiWgZ+eB#}RlX_@A zfIP82nT7KbhkRU%8VsyP4N}p1%DIS1h7D{SNRK5I4oz4bS?s|7**gd8nK7`+1t&!y>Ugrji)~ zfqJCu+v*($U`xzIr`($TCdF8BSfBal-bC?tv^6C@LPdT^Z2`N0{;m02y%92p7d2ut zraxy4cF>A6MQvT*I;Fg~QpiW31{AlaU~0<*4tTf0`v9UlM6AEpe`% z$KlFx&gp_h|3%zjd=OB+x>?CC27N|g&rCFcZ?r8fBm*Va<;``Et0aMrZ5#Qx8qJz2 z86>Oi?lRFmy|HE9P8|~ODRHW_kAeYT$Dt}1qp>@>$<>Kin8%o%>pDEO2;+AELndS;|)=l14P&)sp| zGbTk2R>a+_rVPJr4s)eBkS1;-Z>RuuT`E?KpR2)hld2e)Q0s>hIQd&=6=B zHtR=f4+Ybs=;oh&Fa>Wb@yY?in&_iVPZqPSRR5fNT0cUY`E8hh-{XoF%cl% zqpcLkULXL3_xy)#$fmU(H8ThT4FoY`Z|_R1R9Tpvn&68yxmTr}_X7D*AqPe{M7oBH zpA}N+$C$P=Yw6~C@af}CKBWtq0qTxJjV?Ca>ilT08*h_d*}_c*^E|FUFubkNHB*yK zBCS%WipxujJNTuDM|6=Jr4&H#NZ4DXb|%R#DT;d{R@;t)WuxRT`*6lXYY43-7MDHX zr$LqxYp8Xfr9!WGr8|0?H5eh*U!sZDoqiFB6t`dVG-*7b##+hb!>cW8uYP(8qa9@S z!kq$h`q{5Gn782HvGAgMB~%!PEyI2TTLUm`;x&wYYfPCo2KZunv_1y9jMnR|VWllR4!7;xv?eNpxxZIMerAqELnorG$09y{FYO$Z}VJ z^dmkR9w{GClFs>3X~$nLnO9iwFh|R=ed30Q*_CyiqCNU%3k&@3gSMLKr5~9YZHoLY zFYEOn?9sh^6Qz-$BchAmXC-?~A3ybN!Vu1O8pgse5lz)jSvp9_)cO}l?pBJUry?|C z@3!fLKvITK^}Yy@`>k4bFjZ|7YMqolcK)Tp=={tG9=csF6$fh)8;B>u?}UNSDDG2A zbS&ID?sR7*5!ds6bzj&(!S(9H{G4DK!Y2eG=Pvhb^3xkLZhM$2KSsvTiBg5+&JsC9 z98O|fPr=XBbfC1xS;^g23#v5I>Y?mW_f&o{S_#fP;8`P%@sd@t=%RIhy0@5{s1Q)w z@5hSO6SE*WjZy6VVi;K3;Rj5On7~7W>Yp`j9<&$q0Lbhyilg9K30P}Ef*Qbtw?y+B zQ_T*jZtj4te~!pFsjR!nRVT)aB)8T4utn^Lz?`i<+GOT&Ju*DLcX$B6)8 zW=h@mRCn{X$D~%qnL%;QThg=2-5ktVXDEL0DfeeI(Nd>ysIiL1@Y6LaEvdEI#E_@K z&bMbLroyfhlV)x*+uz&Wp*@dTj9{~ec`3Xr-|b3Jl)kC!c4or%^pPV+0K>D9eSNs| zjVSzjIzjJ(0N&0r)vRjz&Og?A`FR_d=K$A(I&D)(@ZUhBO-1 zoQ1Ax;Ni{P$wm9@R)X2bVU}=64(&xWpsdngE#+h7)*>Zz!(sEI{$=H1s73?Wk4)NR zNSb^>tFj0c%~IA+)WqMk3?D<9ao&hcmU~hn2edpq$!GYa*^G!-yzu5&AUudh=$gCS zX`B`D+iB+IZ4i9gC#%^``#58fMmmVP5?0e`An*a(Y&whTNAJE&?c2b$)hzcgUnG@x zr)I}KpOp9soXZMI^D>Eu&NQF!e}En3kkOl4fE$bW+`S?poe; zK$iEyNLKUMF!!+)mxC@(?J#Q1-V&%69qC_ocMHHIlc) z+t(Zv!9?nh)(L3h`olW`dSoXKX_Lp07+* ze`tK#4e9NLS)^Fqs8fHMSx|aRA-PpW27MH_2hZ&dGKWl5GDv^uUW&V3urj9Rip3xF zEZV)(W4~+e$>nZ~b=ylEu#`AR^K(6g=${#nQg&Rgobse{is!(Kk4K(Z9LnXHe$#fw z6SA45bxo_RsAWjce05x{6SH=r7T`{~ItR&M63*B-qO+UM;kPON`fwnhKUZWswp9dp zCose+krHOm@}QN=#6e(>^_9~mTpRfmuQ?Qy+zoQ9MQTf0A37NCd925^l_m?50AEK( zo#!Y$jeWWVJmm>Kn9*HFTO_BLa^u`pLdc_&EU~wB-m-eGVOi9Z2?y-NX5`TXkSpV>1JOBqS<)Vv%W$zsX1LZ zZ_lhwAC+m!x-OYQY?;%8EYvXjh%Q?;F>Thybf`ZDJRo8IaMQ+Fw!W5l1J5Fo?U-|2 z_B*N@ZuJz4Ob>D40G@k7Z*^1IFC8fTNYo-PT_r9pBLju#47!bgsD_VyI=W3lg-Y5s!FAEp++?t<6y}qT5Y(sQw z*WZ#LYA+?8Lz$B&w+4OO?Y{xkdTih??RHsm0u&XQd08Sk*YW>=C&4%UoyzZ~e zK2VMN@a7-`%p3wg{7ki?qO$p(rh=DWYj=mPgQr`ob2^BY7iu*2?w%adqo!(Hu-SZu z>%KGJgCz{}v)z|R3AwcMZ<=_e@93~FW&_q>$OMcaeuLC%l1vHXU+?&lV~_wHP`oi= zT!xYl);f2bpHDq=Vgfl`@Z}MHOa#qJBXc9hDz}2nUcXBUpCx*pPx>(m8(4A?muc=a zdknb>6Lsb6**K1qYFNLvU_*FqzpJysr%=qFq`1 z2#8gvB5`T_2)~bFrsmu&Z7u>=20*R}?TH}JVMp+xz)MXzjQBI+FicjR-kFZ~$}kuV>j#5NhD)V{Wf@-k*LPjyt?}mP!h{cCGwx1*!n(No9jnz~#O0jjr~@CBg(N+E zH}7oL)H0E8P@KGfu^c<;!?Clqt)U%W10Hll)U2^x^6>Xl2Ft^k(NHx(B)m-f$*sof zO`-Df!ouf>PWNe_rsB9{q{>GNXJ$7+U^@BmtF;&3N4-_8pq7lPL{+lIhKp{^*mUpl z2)NtKqE7QOZKx$~oJ31{@D#Y%5~ofyAl5^| zvDsWZ`hKmx8({mR*_t+q@B=0jMM+sCGv&uto;;-IqYcHl=NB^s*YcBVVI>#& z5CBZ+Q7!z!IlK6H25OR5GWQ>zc)G>GBSSbvGb1Zf(RK4oeQi&TUAXIJL0_Dy!{)j9 zkTdM34cz%HKWyYI5dsD;-s(|*bj=KppZKuZwhblJ)ozE*-jcl#!z=v{_q{vwg6u9w zdlt=&hc{OjxotKh%Bj)lnXu${pSBg8U*APY8Ci19|2BFc4i0nRET_#Nt~+=NKx6;* zp_~J!!Cd~|80_W0Xgqz}SpqNOuUa~}KgQoK5p?PPIV-vC&!O(Me@eW4+i(Nk{;vW| z{~mml|Dvq+JsHgkjP~1Y`5*B=f<`a<@Cp^ApY_{i43fnmEa?AkT3P++4ALK5k$=7R z@9Fbj{db=C$K=TX4+St3D{6Uv4tW1f^Y8!LEBd))U`bYB$QJ%M)ya<&!CGC+yj>h$S{R@v_7 Date: Sun, 19 Feb 2023 22:23:00 -0800 Subject: [PATCH 066/103] Added FollowPoints documentation --- docs/FollowPoints.md | 53 ++++++++++++++++++ docs/images/desmosFieldModel.png | Bin 0 -> 281729 bytes docs/images/followPoints1.png | Bin 0 -> 78582 bytes docs/images/followPoints2.png | Bin 0 -> 82185 bytes .../{FollowPoints.txt => FollowPoints.json} | 0 .../com/team766/robot/AutonomousModes.java | 2 +- 6 files changed, 54 insertions(+), 1 deletion(-) create mode 100644 docs/FollowPoints.md create mode 100644 docs/images/desmosFieldModel.png create mode 100644 docs/images/followPoints1.png create mode 100644 docs/images/followPoints2.png rename src/main/deploy/{FollowPoints.txt => FollowPoints.json} (100%) diff --git a/docs/FollowPoints.md b/docs/FollowPoints.md new file mode 100644 index 00000000..723a359b --- /dev/null +++ b/docs/FollowPoints.md @@ -0,0 +1,53 @@ +# The FollowPoints() Procedure + +## What is FollowPoints? + +FollowPoints is a procdure in which the robot follows a path of points. It does not find the robot's position, but utilizes another position-finding system (such as odometry). + +## How does FollowPoints work? + +FollowPoints utilizes the "Pure Pursuit" method. This method involves a circle drawn around the robot. + +![Image](images/followPoints1.png) + +At the start of the method, the robot moves towards the first point. In th above image, the robot would move towards Point 1. + +![Image](images/followPoints2.png) + +Once the circle around the robot intersects the line between Points 1 and 2, the robot starts to move toward the point where this line intersects the circle. In the image above, this is the purple point (the orange point is also a place where the circle and line intersect, but the robot will move towards the intersection point closest to Point 2). The robot will continue moving towards this point, moving closer to the line, until it reaches the line between Points 2 and 3, when it will start to follow that line. This procedure ensures the robot travels along a smooth curve. + +## FollowPoints Customization Options + +### Critical Points + +Though it allows for a smooth curve, Pure Pursuit means that the robot won't actually reach any of the points, and will instead curve around them. It also means that if there are three consecutive and near-colinear points, the method will bypass the second point, as the robot will immediately intersect the line between the second and third points. + +To remedy this, the `FollowPoints()` procedure allows for points to be specified as "critical points." The robot must reach a critical point before moving to the next point. The last point in a `FollowPoints()` procedure is always treated as a critical point, no matter if it is actually specified as one. + +### Headers + +All points are inputted as `PointDir` objects, which contain a header as an argument. The robot will rotate so it is facing the header of the point it is moving towards. + +### Procedures + +Optionally, an array of procedures may be provided as an input. If given, once the robot reaches a given point (or starts moving towards the next point in the case the point is not a critical point), it will run that procedure. The boolean `stopRobot` determines whether the robot will stop and wait for the procedure to finish before continuing. + +## Desmos Integration + +For the 2023 season, FollowPoints has been integrated with [the Desmos model of the field](https://www.desmos.com/calculator/qgjgrwb7tx). + +![Image](images/desmosFieldModel.png) + +To use this model, drag the points across the field. To make a point a critical point, click the red/gray dots at the bottom of the field (the first dot corresponds to the first point, the second to the second point, etc.). To change the heading at each point, click on the purple dot attached to each point to rotate it by 15 degrees. The model currently does not support procedures. + +To add a new point, add its x- and y-coordinate to the table. Add a 0 or 1 to the c_p list corresponding to if the point is critical, and add an angle measure in degrees to the a list for the heading. + +To export the path, open the console (Ctrl+Shift+J), scroll to the bottom of the Desmos equations list and copy-and-paste the code into the console. Copy-and-paste the resulting json format into the deploy folder (C:\Users\admin\Documents\GitHub\2023\src\main\deploy). + +## Running FollowPoints() + +There are several constructors accepted by FollowPoints(): + +* An array of PointDirs will provide a path, but will not allow for the specification of procedures or critical points. +* A string with the name of a json file will run the path generated by a Desmos model. +* A default constructor will run a path with provided "Steps," objects containing a PointDir, a "critical point" boolean, a procedure, and a "stop robot at procedure" boolean. diff --git a/docs/images/desmosFieldModel.png b/docs/images/desmosFieldModel.png new file mode 100644 index 0000000000000000000000000000000000000000..849c504b12d713553abe057b8ee04a1e22bdeb88 GIT binary patch literal 281729 zcmdRWhgTE*)^&LB0Z|Y;gsSog3IZB>Zz?Lig-)oUg9rhsL8XWws0bK(kzPUzy-Af4 zdI&{8L|Q_JfCNImLGOL!Ae_vRNKKtV@ z{?jk}TO>1!{$eV3FBir(b>HxpIMl3oHIALU!^9*isx~4j%80e*xieCIxtPrUSBAAgYL&JuN$Tg9$53cH zSoQ;oehphtX;og6p@BtBZYU6s)PEm=^5W!D(uK!UrXAp0a~k$n(q<_`d5(->%p?ri zEO6ji%YPl}papaq1fp$&Q%8!Prp?ZmS%-46T;-lxfBz$Es`YMWlL2=j8n@K<7qHj= ze!OF03hKT0Hyz-Wm9PQ0DhXviwL_s*q_s zXZ`RVtHtQj7`5!%f9)7N^X1POF*|j|O;JPW|W8 zUgG@oLI2mgp+h>GsfS3ad)fYsKZ^*w@0MG`R_703TXSz3>cU-b+5b6AOX;isbC@e4 z)WGkw+_%KXEnivBwTAK-ITvGk0zdsv$XI6X91I|vjhV5{ zUalsm9Z2?Qvn>*N)P=m$Yjj{_{y(SL*2!O3q|1RA)#+f8_@*uU>-(#$)D$qY+^)6< zvAFtb7pITe772}%Gr`}t!5J6|_RH?{{Ydp+zs=?Q^Swj8f$#Sh^l#LJ8!L^F6jBx< zn(xouwge@Q{|Vz@i+3n3kweOe0!44DnYvFE%F##?CuAfA?sKxnWWDjNg!F6#f4_R_O#) zv~5=5s7>KAi^cP~yl_|Yg#YZ}%!LY2C*cGUCy(GSSzy9Bx!pmX-h#b02EOFMf_)g3 z1nc!?VZ~U!;NiVv10Bu+HAH8>n9D7#prd(imYt=6n5ys$@7jaK zq~7F_qKHHi+T7n6-Z7#ngMD!BTstTaCM(#jOIhF${`?@(+60K`)fSLs*}nkWXi29i zNIgv5Z^*6r{_^ZYIopweN-euTh&?&KU*D;eW~yN_V$3*Osemk-3+tCZT!m6*e|1W{ zky)?F5{0iUUHU>>xe#x9)n_))r_xn-@M4X^(HwKu6312B`zi8)euDEqS0^e=d;f8- z9D11D<&xxDb^DzBukX(m+sFG}B);{)is3mBGfI&2wBPrp+-E(CSCmBDXBxIycyg|Q zK%M6pgD^Kv((}viP>S=G&tu=R~|L6gIhazLJ%tnJJ{`O`1h{{KL>H;886elZ) zPyFQmgFr3sbkI*+sPyuiFNVME`ylsyT$zF=@wT+-=FVrz{2mm!2)7f8F3OZVS*=NK z?+0I$;pHpy+*2;n{C)nQ;GAdQJi2g+j>VS}rL=il<@Uz2e)SkOK?oe=i6Y|)lLfoK zK6*H_Y6LsIQc|xIkK$Ft{=`Qf3}_!4Oqo>(m(;J<71xP5|7hHwk;#nex2vE($M)a3 zL*1+(EEjpagyecqq%KUS7>DyH+o{g->vwA>EQgo&monK}7e#Vj8p9PIZ+;pdP-&IE zFGIQE-Jm1LJ{GHNWWU;Q-OBhvA=Qqmk*x0W{hUtVQ+H?>fkom!simd;hNyVx;w><#J)vng+Zuy|3dkQ$ z48$|TNfm>vc6LC3AI};y1!t5LRIyem$nrwnIa{S$o%KzZ4<;=9*Ti1R?SJz;g`+s5 z8@<(RjH+?XN87zD;oL#bJ;*D$EK{!4=3BJ`fhDqO89PB6{<8vAlTL-@O^;)FfpEZr!fg!-}I&{B#62Wm$D03dt+U{^21oQJ}dSAu(CL02eklKc-Vj@Kb zWGe!q5yOx9;(AlRa_qZP_uO?Z8L!H&ogOHz+r7K@$tLVp?;OWs!k;b?TqQ<ZAm#zdh^t*&W;K*H>JSl$4_{ zcl>MKS*DQGd)IZc5~76t`%Z2pVd$;yh)HL3VJ0l`WJ#>qXgV|@Ehpw^rCH3F>AKg{ ztr(diRMs+xwLjhnlqc52=yf$&PLX+Maj`4Vk;9Gs~nWfjeWRFg=fG#`|RuZ z#>GVEOa=Gw)Uys!mvD{_RSGDA^}6zc_Si)0dRyf{I^fI5VPa&uw#>KkL5Pfp6NwTp%%EFS7c%{j6oPJ+=aQ zwJavN&*1C?c9Pv(QgSBD?BWc1!t>#kk=JQqdSAA?mSjO3D|a8}FcdKG)0 zD=VXIlOIdzYo{i?(W!vMq7g6V#^D{qj6bm0TDR*gF*TO zk$%anfO%G7n`NUPSkSKxg@8&)E3)vL@KnFz=Lfi17UVA#ov9{KS~`5|$slG%3h{Ga z91|;_2oi}-@tN@*^3yZ2c`Mdam;JZ_0J!i8HFTH=8hUmwQBHem{J3t}_dPiyp-PXs zQs<>1@$IQf<&4E(dSd)fG0y2IpNz0LLklSr`!hYaNyaJSzsrl@x%&@u2Su~Dez{gn z@S2GK%@}-l>=ySOiTh|eMO1$fc_hu7R5Yq&!6X;{o|)HM2>n&mdm+y7Av*sJREf#H zs_+%`OWsJ6-}+UV8JV7p!Ed=s!8ne*etlyWUzf_uPmK~XJVORJ=v_10L6ZIY(-=P< zJPhj0z$z$~)%=c`DUf{jSHXMrTkm(ZWs8=6L<$S#%Hx;>Mg6)@)$~gfqY6|cE=&ik z1xz|IToHVb>9>0qlKhv*;s>!-_Au~wFS#x*f0x>-=QZ(FUi=Z95tR{a>*uU&*wtzlAyia7>+`g?YpU+gG%4KK{dU`1D7LH z4>fvs@wZdWx9hE&&my^s=?Q;Gkmd7xuRfx_RgM+~CiJ~fw{K(vVISFb3JMA&>m_hG z_=vni(K)kFE;tmGT;8QnxR2+!pU|RqPlHL7ekw%)XG|Vk+uN}iD%zh`54M`hFM_w# z0AZF%BK1b_r5f$2Rm)d$=&}=QO@RL&gskqqLzY`b28soC1XfU7q)CtAS7$F^E%r(IuD*1JqCI?3K;o(;h(ooY#GLZ?PNH*( zRKd4+Q#a!}Z^18>@xGX-sORvSSVuKv1lM}Pih$XVo8q|7$1htLpFQ!y84L1MB+EOD zYZxw(7bTjdGNUYrOOwJHe92E+^ZZ25W`Ma39)^8+iZpL!zKWQUEFkOkPcy~PwG`;+ zOK=Gqk2vz)C*`Uqjlp}~n|n{(G`Twb1tiHTuCTRYy%pI^iETvRvY@PS_e>m@G#wgt zEcgiBuJ)rO%?cvug$_s?k=>s_vA-)M(A{KxCf&UhUWqc)jx}A&`H}1ms7;32Y`zTm zE0DCzfocp|8GU&-&>V?4I-%z-v?;27Gy6^Zacb||qqkn7KvS5cyE|!c;#uz0#rw$3 z$r5H2&K_5}_P4nAFH`MT8VDkPC^P8Nr30EpY?5J+>fonifQa`}o%fzm?&+_73i?t* zZ=<0=*TU&No-tNlNg1wu94%_~=|F^#`8d7Or5yTFbSIrK$Q=!(NGlJh6d?2+GktZ# z2v13;!JIZZayxdP2KetQ==JBx89)cde^%t%gcT(UWZT_|_l$W#^OS?ZyuJ=q+{gIfLnxYJJN+3)$$w6ryu`ir!A2m z0aVjpp0-hhG4Ny4&0Xh?I#qeFU~Zaoa|dmtgGTpa!CTWqoyXK!N21Uav)Zj2YX% zg}gHm3s_d+Ce(NpbMX^uvGxjw6F)rD4$TaqW*!|s&cc2vZ&g({7XO-Rrc7NB0X^wG zsR4f!!YEF=X4m~RKPwE6`ci)gA7>tw%o1TJb`uTDNWrRGL~_4RlO9LF=9es}_37Hx z@?I0l)x?>iwZ5a=@WQfr8;1o(x#h8)Xf>hQe@u8g0YYFJ=&&U5xi~5MciO+!v{p4W zW?jElB~UdRboj#t(1W%lkUJ7~=bY(UoJ@a*ZA<(2Q9UieX4CQUda&oNi4CF5hWt0} zwJ0&NO2<<;#!dcQVA}fb(X}gbhp&s@t$^huBF)t#TJ74IG{mopTnyiTskt1aFE=JK zOIi0ZmFK)?*YnXq>N<4=9-d3_(~h|*nV0H12BnIH9N*^{)qXn(;oWPa zeMZwkj!j!{-77zoIGs5|y`jk5E2AOh$jx z5BTz$oU8j+TCKVJ>Z7_IL~8|&A(`iJ=B9X?9Bi(lsbqAdMB|D^2c-ATh%)-5D2`ve zhsw9^>dFH$udH2XeN519R!0X5j6-hhormih1}`MP6`^$*Niswl5Y7+ZZZxsWFy-_U zza;X`c&ez0Oc2Mqb%Et$8|bbxgi8YnKdC`7sg9BkR+US&hM`Kt_hgF|exl!#x{pwEm^ zJ!++7O6>IsD=b=S<34_xue5{-&~+;Us+$FocjIN(A<9sU5!dbJy=kA>We>kj+a*ku zOZenCd7QjyzTs!s+X7ClCm){Z$RJQ#H@^9pG!}&v*F-ZQU9RrB%~KmMMx$*&A!X@x zl}>!z;ZQCPwH=rXNqr+^CWYf0Ae&@CNgvU<>)gFFULzXCsLe!02SpqdZL<)vUhG%G z)BJ9GbiIE2Vv5)B;~^WuU}RYG31V_IQ%u+byi|x)>z;gi+A<;*QJZZq;a(MKy<2y9 zlI8W6X~P)9=R6Er9ZlOj2`sSQ*=62LVKJ3aGeZOqVoGY)I~w4X^?xa%o6dB&Jnc${IgW4(w6iqQTZ5$iGG>;U8hV{8S@nKLUN(hHSJh_%oOWB*s>Pmh7BO(jl zbarZuPvPM4uB1wrS|KT||2E~us*2;dAF((K5wd(3fMF(?^zL-Rt54w78-VeyBpRAl zsZaz)V+bn1VT+|>FiNZYOusQ377HM|Q7qL#?Lk@Km&!PYy9aQwFOQBTv+aajJXqZ6sF zxN4H$MD^TmiUm^kQ_@@U$yqgvK&neLB%0HKW+P;2iQ z%^*;gy<+;hfkLtF0+B_BWtj$Bg^xLKlx4`xFVY+Wmtdy_J#4>W^|bKLTCste2UB@lsVUCB&|apJ_1h`gsCnR1!c4`Utg;^CKG#!Wj2NG4hEB8 zke2+x&*-j|#cya4Nm;`u{&*$#Ox$hV!n`%o+#UE#1$+6Vbu(p;Saa$lS#>|&yLo_I z`Wzr^s(4rCA;tTBMQk&lNMG)m(M_DD5+34tD2U@HN+c)msPS5BeIyLw%J#Kf)-7Cq zx3V{B5X9=tXRf+hb6J)ZgjZPXw%$r(3`W2~MQuI)R4oqzLilow+)mOD-0YE~>zqQE z`m1KYh5Zg!W=h@oYDlgshluA)uN`WZa?IS}h;P1Y4SOBW5wzKD*js+DQF^~}D#%#& zuy^)KGd0k-=v&j~@Wz{!{iA}l?aq0c-|~C#T!z!=Ft=*xEFU94ORlg(t_66n@sD(a zZdGLVc{sV77s4-$)?#qZ6thDT%V633Tdeq0k!W-N+rB}#5wd{G+uQr@fJZU7wEr5O@g)5dF zI`Envi%%&%#>iLhtn8opqt~~zE7?Rs5|c!6B`Dwj&E%%(EE%e`e^pLv#MU^6XHVwtRmOJEIQG1l!|p@7 z{@t8(3ID^tMVFe_L@vcl8o6?E8D@{@wjvm)KNPvI+2%yXMP|Sl<#x}x8$k?6&R-dk zzWxW<4EAk>Rk_E)dZ;zS`hvG&BbmuRr3Zj|R_aF>YpN+R$QcR(lUG&Vs~got5S~*I zH9Z|O@APvCWAyxSIQr7fS8?)YyA|?*HR_d&={6*IZW3&{9M4`+qJ+P}cMPaD!%h;e zI5!-7HW(CVx+rbPou{?ypI*f<1vACC8ii{&7AV}w-I;=&dXzv}hoxM#V0Pw}jx(T|zzQ0k35rgHx=WJJ7ukJjYu4AE6^QX_IBxCS7WH<; zH87wxNMG~aq?zh{#xeO=bj^=9NKlRu&m_ma6VRwU$nH_CA)ZV z0LZi35bqW6{UVDjC(uV;@DF|1uW9-FvrJ;nN#HK^1XTHFjb$pt8HLiYLkL3rI|x@~ z)++US2XBtb7Z?^Qw)d#zsyj(H_vhPS&*RUTr8Y(~34|1>xSDue3P??WOe1VPfgNj472+!-S zmIk-><@GO|CQe3|ej(v+IBuW)7U4K|h%1R3%d;j2EDcRszNQ*>N` zf84n*Ny?vjM_P0}Y;Di?G`BhkLh6tPCugFF$E~081@1R<*ry<%!!A*C!tT>BHVUFn zu3-$ZOygCfkPMfCpSc9F?EYoPo%wSnE>hyorI}AQYxOw3sie6 z1u=N9anBh2wI#J$O7(PeZ zR<>yIZHY#pCH|^NOd^f;ttFBb|2KuJ&+mcUf_{t?8-oNbeAk#eRJ0nQW|G8&4)5IK zJAP(yV$3G`vfCB-o_VpU*-HbI9LfDfmPqpfzZ}sebFV4k$h5}Isb^`*BBx4%TILtZ zARLorDexN&PW|YfdE{Ze!eu?QxwPJQP5V1SL0g4*EOL^%`~&|+uf#t?c3;O(9+vpG zSbe&6H#adYU~WKlREFzc_2xNS-49le7jJ@#DsniMDiJ&sK~vdve5V+PMd#r805>Na6PIeuOm*mNIrC|6ak${5fS(16fiC3!$0>o&~iC4Mz*6!r(Fkr6sr?D$5DQ83M*6r?K@Nc%>i?oNn4jvAJ>$Uz&S^hKvDC>^ikpA&3X851l^f<7@Z z1)KE3xF5FJyxkPGE?DCZx;Ex3P00@TdV=nOZZKJKpP?8$dG7M)xrT|5q<5CYF8&tO zofr^3@9o*{c?Kb%exEGXmHAId_TKE6<7|KN4|V{R@! zuhmR@q#oB{Uu3hOxcpxJ_7a47hO$hoV0EgU71$sfc+shV|3YxSp}*QVxqm0T_FrNa z$Je}nXk!_*fYuFljBIfsbHh`hs8re6TTnpMhHS@23V zn)2dVW#KH`@rHobYv!XDiV%?gmAY2XNdzF|p`Y=?a=9=W(GvPGjzf%ZOyV-l<@mFt zi&9AD5>TiJj+hKTu9$DFDs(DM*0snhMl`4g_k@m1wTA=!>T)gh7&tkSY0rpieB2?* zYL#ZdfNcIHG?zWmrBn)ehn=+8_1r*7|f=M->-R!d}LH* zqE)iBSCH!6yAT%ial9tr93k-~;cnle!iBx?JTiN01R~^!9WYRIy@nw2$bw;Cj`(!r zQ{0xg-*KzNo(ZMsCX8?7*!$JS7z}YAO$OGUTbtxHLm4bvSO|)okQ`Pa1;Pu$ZmmUr zBGp=R+6|t;Z*@>Gk|q817DX05e(AY@saA*29lvvPMdQ6w%9z<2cON(i>1nq2c-?Txb)#$1_TeiaEu(Mm zdIl;^BdHYC)xwKGpJLl&lgp(=K^C4^F;`D@37Cd?;WM1w+ctkq7w;DS9tD|Pcu8qm zxNF9@jY_Xy*TXq<7o&Psup-dT(}!7xw3g3Z5i_N&-}0*-IDi<@{&%))L6;%zK(&fJ zvVT}>m>BmNutBr`ovqV*uB(Uf%pW}z+r_8` zG3dUA0r+%flOa$%#=^s6J)ZCif=l~248-I^(U{pN8;C{s&zlu^LLr($va6?yGl~2!_5g?f9B^{#O-;LzL2VX%8rx=41HRPet5OTdE!_*V~!-sbI zFRJT^k_p`w4h&I2{Z!lGTHG$Ojr#?BDvf|fJ29y{a14P33L zzdI!@?aH&cuB(mH7n`?5mzh`fAI=9R8lz1f!WA@jt?Z;VqB6@9zqU6GctJqk?6GbV zGbqmnIoWVtBZmFZyfqhS#kl&*+INOLxKom=iwZ+n5Nos#(MM7K)xSD##<}aw3s#Wb z_xCpD$l_v&H(U3a_pH@k_}Ro6KyPEU;?Li!NL=2_F}itYc0EBMjL{qbbKrzyShd?S z`ciAQp$v9+EMilmSx7n;{$M03xJ+6mgC6TgJM2s9bs^ihawm3;E;=1PMG6P9G(FxE zc?GNC7%^f6wK>1n)DRG?u;=Ro8Hp)`N&F;)zu<>k67|E?-OF~umu2A}&Y}feBHaQ< z8Bpt@Q?H^*$so6-i@2n~>W0$^o?~)?-&lB#T1>@EO%6M}qOQy^1{+lFqT|>OO*sId%}l zih{s-UderyiE^4~nfi`1r_S3~K*EloEikxm#R1x8z(S3UiYB#^X zlx)c8dg{F{wWJ8gW|6VRc4Q8PajgPP28sc6FaSwxM-)KSsGX zJNmPX?~R5L6yg$So&vUsxA9j1-PyFPn>Q(npg?TXLXtK)gWb{o(H5Q4dXMkXXr9_h8{Bz0 zsAzz_$-Z&*#7b6%W)Y=B&cBtoS`7%?c_`{Gqw;`pYnm9t0SHJjYImq@5piTIZ2^YG z8-2~vv4$PvfKj2Rs;KHgoc9cS$_R8|ReVTalg=6xGBeoL`qbp{&G?IVpjA!{x{$6O zaAVWK3T->!t-wLVs8NLN&p@HletLG7L~~u#A3DSsa^gIgpew5@Sf*Kf z%$K4+!)Vu1$;^Gv+BF~Vt*4!2I54FK3z5k8mUyqZO#9vuM_T6P768;3HDufcXO+em zlWz-BbV|5enO!o*+@!4Ns+`uteTM|BV4-+}ee{EmcoR0$NiP=(zCco&697$nfubFm zOJjy&l(034TQ-$Gw3e@gE> zJ?bTdolsM_cvL|0M4iU0qJNax2k8mXyBvz{SSnoi%);IK7gu$VhkyRituqRv6_(X0dsBqJJ&dfzu$98II`%1@g@$lHrN zX~+TVc$#j^!V?MFbkV|Z(!`=mg1H+DJ+!3i$*O3;>V(>?^Ws8DRs&|7<=SY#B2^v* z24!m<6n&{OI*?vQy*WPZG5q;)$9AtU%!%PpIOmUzCM@=;?^m~qz0lsnPN?*%IIsCl zj>zI@y)c`iY3SzJUMTUNZr2nsS;dPThSgBuZHcfxzLatBSih^%bvsk~V3OIy+DHn2 z+rHrv8^Zs3JoUEPnMmo>Q(F3H!+~wT!)Rq_n*4Lb98rTO&DZrJN(MUpJxo({H^TNItwKmgM-=UkMYkX1(mSJlx$Rv zXtLi^Gra=N2fQy64mtOSlMJTv6Z}<$5^X`Ewx^D|lVNcp z%eR5b-pP6PL}-%|uH;qhiv;UkLN7r$%imDoq_Z}=EA`MVSUL zZ2RO4*=S)3H-ZH@_>G3A?B)gPKdcj4St)%n%EMMwX={d81}M)RMYG;JU#VVoml&c63;-I$Q6v?yu`(BIr{ zn0_`cGIw#VG2N!}iISw=viFp$A=^`%h5C%yx$)uo)FDhbvc(rL2VI>dk5y;d$y}Hb zuvun~i*v`#dkLkC^mM@8I0f#4q^-AqcJl;n{d`hVp;=q2iijQc$}fY2<;de;ba?@} z%ph{%>dHuNb)WB()%h3&d4Frdbu_q#5O6L3V$+J@tR#7%Ph`Nwyt>M79?DK+Qg-iy z>#pu8Wln_`Tgbl-SsRU^xhop9Cxgv*$mMAm8)Y__qkriZXwn7x^nqoXeAgDxra88F zi>PX8aHc`_N;tH#JfrD1e%?c9(}VWgR$}-HXf}@@ps%8j7nv7a0%g)_B~5aA;`M@{ zved%aI9_RNPwvFQt|zwLzOyC4f)eOhI<<6^#^TIX>CnCfACClsLgB};5!xa&P7f6+ zeerb13uskh19=^vK*B*H$7vNEA5{5_Axm$6+ z#HX=v9B8emrl{rIO>)$JD40?)qFemxMpJU@OTR`^?#xnR8Q^^ z!74rnymYEDE8($P^0hc*j&RN&??YHPp}eV4m$PEkPF8PxyO1BonY$_)W}K}zVK%>p zAbAzq7v2ZpVzqU5&O zPu*CVxjP^0=t(x>Oneh(bOIC1o;{vWEt_vOHU)~d3hRZ=zZiqhy%wwx*hx`;Ubbyu zd$-(nJqjr*Uvz;VLDt4HIS8CxYRqPH^VL*@1NDm49NIOj0>38=NWOymKx1m zkdr@tbR@u#f;^U(qgsjPaR^uReo;{4Z__*|ed3eSZBfwV{@e4|P4rFoLop|YIJ}2+ z0(LBCL9cKL04gI~I*rj0&^m{OnX$zv#aLB0B( z{RK^N-G70^d?NW@Ai1+*`&aVoKOo7FUPRv`1VO`BAAS-p+Yx^|_z21}&8;ap7qac6 z=s==rT(_rFOz|g-=Igl5Fl;a=?>`cJ%q1`tJ!o&`RiC@U;jM5rMV8kFXl&3gYd|A1 zPYnvc=dy4Lf88G+o7ru+g0e=u`cBEcM($GmUIFujIj z*1d!SJzwl&iJWa-FBZTCB&GfGsxQQr0iB!U#u|( zo4|j4;e$yqI7xkvbUUsVsfU&B&gYO;Hq%*B;}hjowA^65$cpyRI>lOKRTR) zI9&6LhA&&l;Qkwah)6aYXw3{RKHB#Zw*xG5>@KBW@}9l=`I;x%0gUsaDDy%bM;W~# zG))VF?zib(Ru5rk2(L~wIoX)W-ac1AToc%s291|cNAZ*BfI&pTF+r;Sf|D+L;F>cm zGF44P4`>wGg&w1gX~bf))Po_hrb>p`+ow}CFZz4wG&!dT^dh}{ZPbHe9KbGvDE@7DoK!q78fQH3TE9lKD6 zPW)&q{gGkdqHgox+_MbCyS>5FV=D=_yqftB4pC%CL&Q?e3*xI+I3K{-KYG0IcKQ*? zL;-(19$pPBK$Rjhq$iTo<=bvCa(l1iBgsaJR zB`@~S1l}qSwBq(6j(F2mmAYoP?&mHXyxKkQTxjTCd5+;f>X9qTEwf^wq zSqCpyU=92BnsS|-(gd8m$9u&x80OVbM+3 zXGeM+70m(D+>G=wYSbOZ(3z5{+D2}Y-t z?^E2zh!fwWNWr(q09ehSMqA%L%;F$2(Kr8$1th)&mnhSI2fXlOrK z2dO)I_#S|kr%LGeG6cr3ECJIjpPtV6F2x~@DG^!$nWAq{IvR_Tu67?|SNhb0-2;iH zkrK@Z*ae?zz=eK=FU3o@(&9o8cg%H>jDEhX#1z$8VH>+fcF+_l?YKp_n&v6sC3>Bz z#;Yj;3hV3{JoW3h7pbtBTv)DPXzGf2hI?x?%fM7R4cK9aJQ?H?N{Ow129NGG=qHeh zqNfozM9)FH$Ze=rQSouN@{FggtU8>zj9oJ_;Pw0U<#R^vgy;U|a?_oL^e=cl${1{T z%MY|dX6P~$$|K`?H9iSj_k6rP^i1PNFzq=94PI!t(Q$Y)H)2R?fqI(g$W}KSHZVd) z{Ugwq@78-g{8BSRO8rQ|dmwMMc>E*!bA`#cdt{xdls&`WV10W~`(|Zw>5Qe|#P7i! zGsxo!dRpAjMv`t#U+G0z@xOE8!RG*Hu*5+dOp>Ai&0%Sk-~s=%9W06;qUROFT{_6P_CdjH9gF5&_o*wP&mn~#aZ=XvEIQQfS$#8T(?#+rwt-jMg*r}HL$dKD4Q z>)2z)#kMCSo? z1~GPJA#_lUWaR^wFn!XF%*W+eGtQG?$wY&PFz|=oKX->Z_ zpMJf7{B@|40AQwIel$pa$#r8)SXjMCLR!Q^VrSN z3}W#Pdv|X7suQmaf!^FJnuxEWi0s4L>@rA%8~MFvf;o0)KZ?Tf%UGbWsd`YvQmx&z~Zj*Z=&L0zrRdekrxo4mktfM4pu z(uGSCpj+NjM3nWAXR{;tNIEpiYh>d9cX}snd~Ua6;bOy@GJ?o4aB!CeKl+(=H|tHntLL~k&2ztEuGiN`WNB& zthALx^+HAfHq}T|wr;Nm#uqqGl#=#j^Jb`URGpB`iJ^}u_A0Tdt+U5h3{)WJ;w^XB zWMWrXTt)DQKaOKUYfz~xT1Ymz7{=UTYkZC;Ktq?t2Cz>HjwC>mhO zY-(AG)D?(ph%o=%S_X--ycL`B34RKmmCkdi32;Y<7Z4^OlKZ|edz!2Vw8J}0Z%=mW0%!{>)rdJk!ShSfJkQ3 z{FHJ{B~ku-sC41-tJiR=*cCN2&fBT2l#5dCoYO%lgZQjypc9yH%x!2FHTpl8w7su? zh+p%G)AQxTufX$G-pU9%+W@09(3k-`pjklUG?+gn=G5GiAMiXt81QD#-3{x{nz-yU z>6klwDlg5kd)3JwIvWzw_X!dgwxoCHb;zkF)GNz6=I-U(T-Fjxqy6==&vN#_6;J9? z-0&lNk;U7)NbFai6ZtkNWiV*v8x!(KUrOY=8v3ZojyGVf8hMM$e^H|2gow&^?d1vz zSp*y)vSwasHBF91@u{T6gVq739ro4LIFYMQ3Re=&flqJ1cAcbnELUr`K)-!8iaQKU z`VfWg-OuzjxQ!bpwp?QG;OA$`T`RIcdEikQq$39Eao`n+Z!+xYK?6fo*+ZIkUdd7R zfS%B|c{6MB3q7}4KcNbs2=Ry5Bfi*As2|D&ypWNi`O#EJiopO&zbM}&6rBcuF>hUS zxVp1_&5jF5KhVjP5{f7)YML)t_g-2JSt&C~pr#&NmhS;r)xa-=eMHwWG$m{m%GV9z3deg!g5^%qy>=KAcr!kDSISe7BZJJitWxlx=j-Uc?ihq$LU4tKw+0{m(TYJE;`4AlarpMKVo&X({tGgqD_Ba74(mJ`o4;#(kZG)a0P;5ADWx~GQ3{rCe?0d zG}`hw*Y0KEavg$JUm+Y}GV2V(x!60T#chn`BA8ryR8aTYjz^(rlIL0sCq5Fe9;As0 zgmUc8ZKS1iktJ6T$9HE4EKK*8zvW0Qj>|)gwlo+K9o5E zH1$riss2z)=SdS%hqu6}F)U8U7o1@WC+@1kfwkQ>`x#`$QJ@VM#_q-{h~BUsz7re2 z+uLx{%Z0BfnNW=)?6NFcO`jOBdm$+$_@EqdeXz)f6;@QY^^%xMT2yeNf#&Rd+YTGV z>`4-8XcD~Mzy>mSNX8+7EM-zzH26v%qbA&`8^?fFqjfK<3x(qiqaSJEqU=ehiEX9S z`xt5nLAU>_DE}qPRp!%iS_UIlBt|t{&ZE_2FF%` zud$ZAYARM4VzYq@G^mTi-upK^B!AL_D;czFc{kdggG)OvPK%rfXv>HtMLHG1D_k-@ zBkv_{ihF!K5=b0(0eVCcTztEXj|=Zjepcfzv{B}cdUvo9a!HdF|E=x!l>UE4LKS!J z&Byi`Ld3g^ZdT~lXW!pt!SnOQencfsf|Fd*2!_7kJkeX{3-Nbp)BCUQ#8p8|9IG%- z9kb74D|xfx2niEUmWD}Qt?Cxi55pS9hs%I+Nt0+I10GqGUNgZyg6j{sF2zk~(m^N} zOiACAML-2nC@i3(ezd?8mL5AxL}vZk%~dc@HC(fCHJ3x?sXWT6T;>oLKr*iATNDbn zk!=uf+<=sywZm_Sx&IUp(7*7T``7RNkqkf%Y$pS-2aMTM1>X5z$Fn0ootQx~M5$ne zA;aq5nCY7dX2TxV8CHtE*Lgf}HGDwm8xoB_9&hgLq)`Kik`&lL3oyTJ?JAsA$cUah z=zIlq-o%{a;I#$ft^?5YkZF$!rPs0OLtFDs~#x8?x%e@EhxOp zP2J+ozVM_gG_3f%h>o!ocK2$b@IRse9&c(u_PcLYf1zW)A9H~(^|>{X6;-Kj$hZbL zJaDhZZtLaTC(8bK&Eo_HJs?f0STEsg?J`I11d|2k#}5?tYX{=!%5&I2IB#W2F8J4O zuo!gaWM0gKlDo4UaIc67Ck#0kR$-^F!`%~LB=#eMfWfqpvD%!&4r>QMQFKF^wzZot z%`DXrK49ek*KZtxM6aOGfKA>#u0kaG?+h#F8>Kj?=@o!t_U3`t{2qu*G1WVkzky4Q z@_)*A<`mNAoBCX?pj8R0V~PCfC|I5%8|&D!KD^JI&kPNsqM%YL-7zql>du&+}t3z;q2IzS_L>4)T?d<30r#AkPxk2#OBM zU-}Id_C|h($&n2QleCe1fu#$)r|Zl1do8q5Xr1ZcriLreZ-fb@pD@A4^*f#kX11+az^YO%OLt7l^XsC?dV zXyPS`XfS&W1SaFwLs!x)^7lO6P|@kw>WrzF%7OaaOI%`kYcNsPQ#KNOGT*Ge1YtDXk`Q>~4f?G{o_>gmb zR%sa;`|T@ePzp)^UhL{AlTik3v~r0#ZE10zre*vhSL)QwO#yt=s>)(jh;=Q91V}V> zuoCARMFj?z3JUXkFGNm7(wA<2c~q{q>Ee~%d@6P0uu{%En|YLjoMn92oRHL&cQM}= z1Q9Gydz99-_4xT|9Eyl$W&IcB+t0t{*F&@sC=KTA>BXE-uk;AXE0;UQIs{NIghP|~ zXwa&ACt@KdiH|<_purut9Z1_w9dpmd1bonrNB9UIK8L*9`T!&u?Lq!I5|>)j9Yvg? z8+?j2ux}$th?=z3;U`3AKAd`;R_f|>(P+%r+%qV~VTKiNL<-?L_AWiqe=ppv$CPnk zUuTwH2HV-nABGd;e(3)8d3WL6-trzAdfcF@Q_!jCtEuO3rem^$XKnhW-CX%*_g1Pc zLQujvzWvFZyP~jUm~VK}wo_u&3>wP(o8wuVsf3hsH^_wzyri*wdRrILmx(ZOr;%Ul z`3m)Vri(T5Z_Jt^YL7c0=#RnUS`}OGq!GA$mh!LF&-t;11cm4ztB-9N z>KwT6xAx3wS%xS9{Oaa>tR1=5dAFtDP(NA^A9KKcdZu)$wDWi;P%$3dv)@?kp3w;% z_FKr)y;GzU8j|DMp0Bk<4sb&Is#AsUIWyAu={TG(SY8SyZ>4&rbhqVz0Epbgd1F+V zB}<`Ov++qbA0;72PnN_tNg!b6eb>41{aC4ZiL{W)Hk~Jx8Ki{j0XV>h%PC#>9XG<^ zG4`YyB^7;YwDWede6GrIY9wnYL^4x-De3X$V`wwyVs6W=$Wu(@AP-#q+l54;DSwoN z%lPg2LfO$?Xa)s>K21)Cag9*p`Q(Xq@z>$<@TsI-ack7ejxV*tvG0 zwg&n^JHj4IxjU-VZ%dm5nvmAjFArjQ*DlmZM!$TpBG8dtcP#Dn#FRfuQvBNDe_Son zH1UV}V&7q)u((*zS&g{HH zgHY{5d=(_E1{4DxxvBW5Nq~d2Uo~3dO2Z4YQPBg@dDGB(t_JJ+i|{R%PY`n+Q9^53 z`Z=rPX@%jO8qv5~vb&Tfu#&(*R}#0Ba<0sG!C z{u_tln6+1mYfixfk!VT6R(^XHc8$Muq0NHJ2cE1n6RLXm{xD*3 z?0>V&1`T3nen-iJrn?^$ox=#=XWuRy9Ezs5`F)ifq>USS8+C~Iu)#pWfSb=2D%Fo@ z6yH>sjU0`}lVWg6xGQAt&g9}#s!s@S_H)a|J?T!$NL3)^wTN|n?mtG9ljt2oYc^f7`sNlM?Lz96x+%IAkh_+Iw9j?zb{Wqp z?(ICFMDoqG{%Im-Ya%jLJkg`!r<5f%!)L+irLSFcz16g%bw?kPn|t};*EMH3rA0NR zMO~EsxMH%wY@)-Pe2O-H*e>N&(>HVtEWw5Es#yOP;E9qVa7>YkN;qXpS5b1gY4QEv zl`y>6XAN(XVVQBK$)8n5c*&*CCB`GtodWY!f`6+wzmEEPyRkb+@v?2%ElcNP-;t%c>2-j+WSk4ipx89Q{(|To&T6&XS=ezThlCCrS)wN%|q$6#k8()slR z$A9W0*l2okSQi$L{@OXe*yoc}?Yz*&g1#r^PxLnzG-TK%oXt@{iYdqW2j!YylngA zvK`;%BArv9&%ieB?LL#%i|#$kJ`L9_E~7tR(L(e~zFZZ;@Hx>&^mTFZUdb{R6PKUy zH>+=liJFY2w9PoEmvkO5aq0YBLzBbAB>=V~=ZoCr{vU6KYnkNv>2anH z%*#O{L9g!GtMt^4Ta&gZTfus+;n%K^cXNVeRjbc9a)$oeNyl%Ftlp8QK+#w58YH5j zUR;eo!pR@+GPVm1zy*(6h#O&PL`#leX1y_zP!={9YUcCTZ~FGLHQWCR)qlJg{g+|; zH!{}0e-9MoX#XZNhyFmziGRs;{o4x&d;Wj$tKBQPWVin9p?`dNBKP*@f6#M8q~`nH zZx(zVnDN%kHmeWk(=D*+c@AGpWnZ=f8l%b5WKT7?Y*i^><5cewD7nC^{rssLAph<_ z-y+cs^iKlcuaAgkd_k3a0#TJSKF4a5rt;8@VPz_P?*Zg!m%cng?C(`@6q>sXVh-;IFmXjx7YW_rOnfDL_TmQG@mz89?X>E?IgEn3; z&8*5teJ)Ie)U`6HS2u?8EY8b#{sV76=1N~{GCn(&5E^c=zxKe?LUm>$Q>mQz_hVWi zm;msNPt}2e=CNJ{U#kVYFRnwrQH5yjoLLn_Ms_X?@8sN{d`5M(=cV!&L0FN``mxJW zd2zAruU{VDH63W#`p|nR^MO)y({W>$G$2qgVaK3+{RM`aF6f|cK{ zTK805y%*W1hs04CLizKPE|YAjYFRQ}as$_~-{cgH#*8r)9@N;Ea5xq(Z?`Nkvwcb> zO0ks-H5jpMHZZv?sAmb3EM+UDPIVsrZXGIGZqQ^KxOMx}2&%*hsLXy4`=1=ZlQPM- zu6Qx`v$V$_-I&xr>>hErWMUz+*^^TzNL|v8$p2dLGU;mW+QC6enoJf&9<{OlOYKY*qphi zyqemrDvaqB3kz1y$8W3o*Vg4=5h28NHxn?hn5?OHwm;W=ByfGazyp(Ms>Tjn-(C3TyPHC*-4;g2iULmSX3+ zd5sKy-Ev(HwSlLJ5}!8LW(0D&2gj0{Gix)O>90N6D=5NlB+6tYPa7xfD*3K?^IbE; zQm)LB(~XVE(2ag0nKhz}=)Zk?FB<|%fFP!7!!)=E?JK6SdL}6`<-b|G|K_l@G+Tbu zkKM6c{ddbI-Y2x*9C$Ik*sW8!?*j$Ov`S`Q@8TmA;IB;g|FZG^K=i_`?s)56O4p`> ze7g(=YBImox*+lbh}a?+B6?ruz>1zKc=IFmUjDKjt&EO?%;z22EGmUL42HIn& z*lP9q%6uT&WKL-n9@lYcR6k(Ux!q!_`||pC5;j6F&5BIGg=0nLx37NL&KUCdYxm!* z#Q)jFoXK>}o7)#$2!JG_AY0(hMjy81dvi+MF9M8Kt^G6gZQ}|qJif_YG5%Fu%+G8N zBfjHXz~V>N&LxEzA(Q*5v2ndZ`wd~^2qY%>OJn})P-tP0{VrzSBPdSFQEIfuJeDuU zXLIGrX~3X$o@&I%FhHcpJ{YtqS5!X*p@f!YfGXfx=h=JagY^cdnx`3y?Ltb!h&O<_ovwh{lJtU%*$EBzWtx&C8`et1i1 zn=B!u3!LCT?x{P#;%WfEyT*#ZoFIhNUA?lozLJ5RG4Xp5aJ%t#O2M-b;xmRmHY5Z2 z5s6VkvfUF)0GX&pv<^_gbzkahtx+d5nP5&l&i-9wjUwkO_adM{mQniG=p7eqQws7N z((QQz5BXBgKGmG}z1|R!Op_6r;FlKbXNCmXLfs+GteYd>+QkyiU3fV5D$eTq<2O=s zRZM1mDZw2YR=Jmn+QUDB`pO^@@+&JM=}!eCVI|r7;yfJg(+q6>t!|1gEAOiVS>%=M znXtiT&ul%kF%gG+DPi;X_*rs6Hyp`ip@M06Hf1q%45V22w$dEP09DB$ya<30Qv_X^ z6s2@8bXDxJ9}3XgFM7d@{it@qU`ZrtKiog0a0jqNPt5ECu^&FHXso4VbdbJ*{1Btp zREn^k<`Km*;k*WyM$pVAJ~DWXXgx>;&I}-c^FJS86k4;-t9AayL~L)Sc^ee}MczX6sJB*m9n z8=4UOEJ8?$$j^$bB>*VZHt>6x$qm+pDj~>u$=-;cF%`}pB8b&t%C=PqIzdGoPKpQ||*t?^?* zOwp+EivT5h2Poc$8}gf&rHT{8+X-}r58IKSZ>SFO1m;hm*HVvpl@O(U z_~!!^xq3!N9@-hstp{RnX8q zoVk@l#O%aV&*FsvRZ}=KaZWDSb1J)XcQweJmYM)0hM%IzIm%{zhvU%$SQ54h>tEWF zl-Pw+EG)EfKv9?6jr=BB+-jAS;5l8C`~rmItbfNx(H|-nuN}Af1E(ytvCv)(Z6&VK z5mq>q<~c^MuDAILDcaH?L;lleJ_fnaab2}{4=vbOjVl8(aq!nkR-F5nKRei?l!lQd*W);G-gV| zh}H8zES{97=ri@sws7DMWM})DrI+>cV)ieXA!^r>Y$UOWu+uIDB-gComACLz4b6as zndxI`Pgg@-^6#c{IT8~w@7p!}b~d^lp*0X|glE{gY`p-LHH(Cm!RGY_?^8h_us8xip+L?phgvpa#`9=)5ZZn5u)V;zjD_1Fm5CeZ>-W5{|M+@L$STl&q`D%gS(JvQwmPQ_@d?I3NO;?+o-gQTTh;tMUZ3Nkm=xr;epa+ij5 zK0e=!IkB(BS4*{kO)-79AR7)zHJ<3G4Cm_$co}w0NpuACq%zzsk*LSi~9yS zjH`YM`uciS0iS2Hg%7})KG%baybu5KR^p0c=!N&%?p{bh7!iv7vv!MXGh{f3J}fzP%30(?3e&KVEVG zJtt>~ysvBY37CW&Rwc~S9Bgnas9&A01krs~;SEZkAJxWp%zuOSFU;24w}dwd8Y42s zQ^X-{5J_?i&(H0Rf-<$yYhwVy+MOot7F^K55E`3U!l!m%>7ALpp)X%Ax}Cgp5fi8F zzW^*Q21zM7QJc_ZAHskpV??aTclYcWAKY+tj&p9Nli9m#QiQLULn)^3kPdBaZ<2BLP@&n9NIw3hd{ zE!!Ke;@+QgO1IgU|E%|v?Jorv1tN~NjjQUuE!i7>FKN7p#^_Vrnr*VoFK??s5KDJv zU!`y6Fbb_OUrjSeYw(#GtaUb&0m!5rM*^93(d>Y05FLRw&S>X{CI~JRkWsXO5*~8y zAF7m6B4Q=&ZCVdbSvm$nEl^=IHOTq#$oL#FAU`zN{Ml47KTZEZXdIk42I&^P8Oi1W zvADQ=x1*kQc=#Dvg4Sn=#Z`8qkeaySBi#B7g%K2* zoUv6)?>o4lY5c9AEhDl9OcL4pvo+p>0T9s^5>Bf%w`Uz6sHoP`FTZ%DJSafO$)$X; z{@^o_zY?4unMEU!Fm|fI z!m}jkhDhI-o1Wp>kd3JZpU9q>&&jbNoXN}FWZJZ;1P?-BM)Z|Et596;or)EA;>J|4 zQ7Z;*15Q{Ci}1y>096iq^;Fok|F^Logmw2FVHzlE`l?A_5zjLU9Cc#9NHXTh<9CkB z%G!vOdmCX+_yz<7=>od$Dj+lc&&Y7yk;rX-#^1?=uf|4h(^H7Af79Q1a|By@OZ*YUCpvukO!7Ar=42l{U=8Bx>sz*BKoi_KQhCSWQa+m#h9(fgv|Q&CiQ%^u>~ z+7olyI7~@RAVdaPHfJ0Ez;RBN%r{kcY8no(eWmpcc*Ue5wO9Dw;&sx`9Sl+$G99C2 z^O&R4kQ!OAFJE6JXviS+hjq9&(9t#KlYw3}X^t?F)bvlqJ$%*Srl9d!-rRpyoyJEVq)i>TV99?q>Fq!I{Y89{gy@F#Ac(j!}A{Sy3dKIZbo z7^yzocE0c#rlQDcG$djpz_wSzPHTRoF|fczpP5fbZS5*#S+<)R3M*YJQOOxWwyXCq zB^%i0H)J)2XeN7OKa6)w7^eyB`uIy(K|c1EK90i)1$Anns`|zLg_2Eu;fH*wR)aXN z3d(I<)`i=%ziuv<8|tAGg@U}$jOlXeVwdBv;8fxB(gs#7|1x^tp;xbO?NXSJ#_XwO zC%c=l(HM!H6GG}zNF=&9{)5?sdA0P$iIzO<3*o4R5Xc4z zu208NnRd5W+L8?Z`00W9 zfS{{61v41*TAu;Z6{>)7c&MOmJVHxfDAEM6S?*bbaDVLUVA4byXF~bS`$B>mgVZYr z_D0+R%_IGJL;XDZ>`Xq_Oz+RYC9J&l`8!!3&4pm1sA_rzZ`g3ur559m|U4ek_ckXat(RaRBFUA_a zyv|0&Qp}tU(qOwOiQ>>bT=YAg5?gXQMgZ%y3@I9BSDmxtYTtoK!-QqR#9~#SJV!;b*;^=>IBc|;|;ar0Z*Ri zK*uSiABD7L)bhY6z<`1Q*f|3!mC8N>NV;xhS0~;2I=P&5CX)WOX#CdAWGN zPzE&-6toe@pz#a~S2vMQ8A37LBe+(h-qNaNwoO5R@6q1&$v+}n&&XK&vt>(sg>nbp zMQic}s}2dLR~!VjD<&d4#A?kVdY22DR^GV|jyH}2NGNS!Gbdy5T=aYnr2k?CxI}4~ zra8>(yqa(yI3Itku3Xp;AZtD+-DD48*?gE%wgxD|Qc*M2^;SRmR%F z;Jj*(YSQ7=%8ny!?hKZNC8K1D_gO2~CLrDSsfrr{sn+h*EmVeWH^zV1DK-`$K`!%# zeTq&nsnfbh*u$N#Qrm^QLT{D3&H4$5!P#YHbtZ2_p+C1cTT%v2Fc75ttvW_!J^6^S zW$Ag625SxLERqJmMV<<=YqKu(fqcd#gS@+PqLXWQEY$h+7uS;TJ%dn>lgn?0!Gh{d zcXjz@rWS)m2XE74%Tb{N{WK5C_K@k-$tIn<TNjQREzr|k zutDhQY9lLlu;>YzR0y5MoDe=WDTW{i%%1h^!FD?*1V_^rClsi%4|=anwJt%vr!uz7 zH=q%Mn~Remsn^#B1CQ2xJ>9>6Y`-N2>($nMaFV>@#iZX|)CYpg(_OL-IqOI;D;IcgQdUhPn0K$za zW<=daYqP)jGkzCI`Zp&sde&0AkKKr!&dDJ_enO6JLM*ol}4^=-daCGq^#G0T_Ywx$bJO1q6Z8stVIAIDl zvf`%kbbryXqH|8OAF&$djWTt%nT|BaatYILLSj@MeH1=d2vVnr*n=vSip70aX^(YA`L}l>e`6bO%~j+pBJzt9zo-+kJ7WR zPJTT(UH;LJ9iHkZDxgcy9%i1^uf?UhqZz1)v&E}`=@De=T~w~g~ukk@Ncx~euu0#V(6 zN(S6Nj9_wWGCpni2dbSDZ%YqzMToU9VpO&oLLl*RR+TA`VxeZPiQ~jnpx6nRM8Ttj zkqMq}1kPpuGQho9P);oo9#Q~yOTdvi=) z=9tozsSx%KYNnNSZos(ae40~+lFZB&*3jHCgx#tSq$9`bk#`57Vxj^a$me^%Z(!A# z*u9I|LQB|7Q4onH8VkBko<5B!f>7RFP10qxBxC6%0BYqMqK+(_Ij=xd8-hJZ%}lYT z5=oJ82>}oiGtf*m>t|Woew~kH^`QOGK*r0{AMr!yQnnJ|=phJy(VzFn%+Cse?SmFI zdHi|Z>Lq8Wqnxg1Tm8im;H-s;zP$#}pB`=|4%6+VVx$O1>%@~{L-*mZPfz?g+03@t z++R_F_@_gWL+Mnza12Zcu6}y%fzFM4Y+6!F?}+u=gE%NnYe8u2UCeFoF+VpI$boNd zWqAs{!z?|FcJ9~eI6@B55 zs5#VN&3}brC=ng2*JjrRI{{~iwJGR-$GS5PS=%n&8iu0(k!dL6FvGa#+1teNuG$Gw zY4}Pg7I{exlo*QRsB>dOZjlj}!MjNjTc;s=p_~iq!LYu)Cp%IN{coKi8653+Nsgnz zIULeUkNq30QIT4(MhZBG5mSLe3oh&s{;lROKneNBWtPxKzYMrOeAjU+2qRM&I>T)ld?`x+XfvwCmGrgf^tDI4+Sh5aF@Sut z_4@(Kg4t+PDT!JE=<^Od?6e7{0su-_S|g=Yz!#!zF`~9z%SpC%lOO&VbD!x zyHFYa-bLM;xd&1+UJv_phKq!BcA(UOHPwl>#v4f$DkwJtz{ zap2HuV5&TqS01Iq|Bhu)?Q+p@INCO+YCk<6C|&!4^DP?A5Cy=6+KV$2M?}~Y_Db-J z6yWz>)YW>aR-4n|H&v7K@02P|3hbG7^-IN#A;J$z-w)m%kTie_2#mgj@2n}h?=(Qn zMwH(bFU)fF-(K>xfGAb~2Iy9e2`AL(K7sDneq(zkv``x|qj<0b)5X~(f{uSLbVwJq z7(YQ-P+#MbUh6DAV=6U_#i5a|@!HH+cr*TxjWB0|0~ruO&-4bDU?iX&c@P>szY5nV zZFipP+HJ*@AKd$>VmQQ&1 zfdhR!StXZB*1yybvj*2#onne36?+1rt8OleVp4{%a?ZBJ(09%hCv5e64f}qD`~cTO zSyaIVDwVL_bcTqO#m|MO?z}+6J=u97cR(7&rvWQS7l;Uc6dKM?jXpVZY4-H>+bDGe zgqoBf`dY09#De>T?$7TOeGB$y*Vvj~*9EN8O+ngmHgr6g{!6|!_Qx)2a6Ir{JSRSqVf(fdXN=;t42om~Mk5Z{xXEkVAdZ4X!Y z2sDv<1qrl2>mCWL70z)1JmLV}h-txBr7s6VO6fZjogSQ)6&709`HFDY?bf*Vc@UKE}E(>}ei1Fy(~5r5@2j zL=1J{AVT3&THP>!jE?uze1A3;sWkIB^By8GzaNnpm8udosT`F;EPErjfJcTMGN~zw zc-6!n4FvSJnW6;5kGsO^WqzRJUzsQM?v)8I@D%NGuu}~mNHvA_T{8Gubp~gF@^wcF zV;4N)+e1?e=R6lZQn@SaMNU|AS!ZQ45Wh`Br6S3ca^2PEV?h*jNY`TZfwpplyE0L{ zhL%z4!Y>pu_^qT9cueo&d0?xI`;ZP*}%T#*#PxgIf{8$6>eiVQJF1E3%a;-DD?kQj9oKSp}j? znvkJU<#T~?3aSQnI6~j(qdxQ=I^p`L&;SbBwH6;RKGU6I-6^aY>l=^5Cm!x22mc`D+_cdEu-XWM9CkxuYbK%pRgspwLZV+cLGgnV{x#tF|r-q9^WT))WI#hX$=u6h|dXcK`a!utn_Na zH-gFUKdf{)R*3lR|A(6FM2+#24ujVs`eI@yJ>@N_e z_UeBp_8N(;#nzAra(JK3^^_Hc7=gYdi4gVZ9fCI2)IN=rDgm20$_6wvHArjPT&|#H zJl$wFd$mWTQyb~@vr=HM{kirzwY~P!f`s6-h!vF~el{OqUK{+Cp#wKJuHYj3GvJ2~ z)cn8s7&kE$uJv1h#tQ9CdSvD+^sO{OHQ^7+qpLCa7OZF0n4yNe?SmgpwlrEO%h!HE zpDhU>%0V>4N1=7q&~wz-4+<&OAm$thV&@s}pc$!vPN`p0lQVM(V(9%ANI26{=h~jN zm1ozqG)MHFo1U9{y$fK)lh^Y@d(YdB0G*Xal%eG4GqYK=GrD@JHgz|9Rbcckij_Zs zn$x01Xx%zhx5{(rr$hUyntgEA?-vRh!T>%ls#7w%SrOvh1oAcicY;3ujl>0|0{MSp z`@X;;D7Oo3^_@#9cTG|5%y6n|q9}7AOzhC0{3E&S<#cfxDnmSg+f-kHrk74XU}AiZ z=|gwgDuPAMz`6;esGOer#rso1fL`JuvcO^_$?T2rD^O&(<#E2_4`zP?FR znJO7iO$(PRhuUgU1Yi<-3aq-J#gVX1UV8i6*LTFwjn665*Zygdnjd9dVU#I>N34P{ zv_|IXUN%ywMuRy+2jYgR`zm?-j`F}9fav$=hJ({+6Ca&V3`m7*aDet=lGm|>=Mvl+ znzx%ctSD#IH((d^wC*Xq2lQ`GF`CD$Y zH4RzYb(DcgBx@P{(>g2^U_J0{u~#TP!$4qxid(&rTpddY1e)5JP=%8&snhSo6VF6` z>wqE^RS4y1G{fvA+q{b?S9a@jvVyE_F^JupAp4X5Q5hggmraNmS)(V2EXl)+$zIn6 zdS4Xv)^QW!;x&eikr1KWxTPeZAS zFZee&0b1eo9Lhdh9{m$V$(sj2n|m~V%@aCUrEi|87|IF1eDC>wZLn>U-98)LN9JRnXd^SA@7+7K z_JzxdxTRjEw{DuB^=r4!VtsXRTIM#v%>LQ@Fa?t}1hd2aC(hp(`<$AXAKYPb9Y_=d zB*sg}mXma0RZH#_FOL&pY|7DqsR@6Oq04@;*ri)9qr3`}M0D1_*2;v0r|sH^^7nSR zTr@LR&Gs@%Jw1D>npk(ZuqfqV0i)4{yZ#?`e%UM4QYF35KSzO!ZgH579lKfeU5j}Csz3k0nB);h~>*C`f*^!LLx zHBxV$Wq$A1YYP1Q!9H>}cR7si8oALh!iS{!l8tW{(UGw_o%(6OZCF3{ULTUuoVnU$ zr02ER+3M)>BzC?ft4a8ZI9}pK40{kiykd{k$>Z1QA|w3`->t-d3hVZsPd@x~h>K}> zWl0P24tn2G!3(q>z$l8p);cWJu&#L~GF2i`TI1W$&+uRHTiDg8QuIbSZ0u>mX&rLm zK9MF*dW|CDe2zG8Z7e@Bj3Erg(OaSP$^hrFVlEij&b)L>Gz^dci3basX*b4oA&jW6 zN*;c!Y3Q}s_CeIL?dcZ#wf1$MW}SJ&{;ABjOtJdBUfVusJXrCcq-< zJ*-gOAhXE@t6PC5ZIk-oOI!RL?9PvE&njIy2HPG6`CjQdFZ&m$0G+Aty5-#@Db1G)(VZh+?1;e2$>$f7Bp6bv>pV{Mrh2$Avymd! zB1K=&==KYL=!M?f+AEdg6r>cHi$cl{y&fVlp7IH0x;*+K0nmy-RH^w-0QGQP+b}aY zwzNYAU9T}o;F#APdcxNcid!n3(4RRL{CMh=;dz>9aof31*k> zcZsPlFLkX)#GJweP)qVvE>?GwAc>0p4(!8cR)4!8K*)yYod|=813?iRDi#%oGz$0^ zoH$ooi-xEDnPdBx;_s{2c%GY^%Rv40dVDjFi1o*5{}{r!_GdStpyoolw?13TK9AtW z{gKF#M&x0$Yke13V?ctmsI^6OOcG}y9`@Wq=14VMWW6Em8~ z5buw|5ydcW;LNgU7?84m-C9uDQcEu$Po<#y%;24WW5l`K!j!l^jYK9QwyNN1AJ`zE zSZ(Dn{wz5>*ZqxY(#%h|SX3{e8qm5I9DytnUf<@2YCC9W3%ttl;vAEI530?&1v$5R z)njGL7ZL@+>iKvGJ4#9R9h1HysvqhF%JppWTII~N`PxZOj(3@tjk{;AH~9n$B7+NI z0!7uBP2!rAZ<$m}2-=hS_rK|N%q@^SGfPQh?nFwH%^VS^xXra_X_iv)4>C$Am3FNi~JfCpd$r8h@ z)$Z!FtTG+Y_bfm9C}{%~31#atRl_^pQo1oC>^KGuSmG1c_ofe&)K% zlqthY;_?iV%#{3Ef%Yil1Q^Y2bJgKN>0s3;;-9a+D|`y2xJKpoY8sdas|RXZXBxye z*A09{ZTc^Lqck(C^o>EknXGx7QQ-M3dFl<={XKlTEUV&-8)H&4YJO|srt>=S52^Q@^@7CcWlBuc${N@b5m=^x))cl0lrCHn7fJZOFFA9(`T8zW z^}X7*g8+FUJ#IO17{*d#`TBxUqnZ2g*=|0DeLN4?Ei=YzPi(Ke8UCW>xA8(4$T7BQ z{4qVZ>DXrZ*31^q@ui&5eYxgvf8aj)Iumw%fN=$KtaH6jPKLppASn7T97=xQvvso* z@(HIuTdshl2#cNf{NtDWH0k|qT+U;;X^J-nw$U0LZ+S!)q-ps>8}!3>F;7-CNeCDX zAwCAS^tAk8Ohuxbs0HhHQBe?M1(jBMkQ=4E&gML)38F~RJu^WjZwZMab&W@Lzsw*PAAzCr*t79PzjBY15(I6Mew{c>YwRb*8qr@?(PK zrIo}yHmgx6*Jkt1KU48aMaK+pV@7%HA?{cu5-z7KMZdl0!Ck>Jhw0pcU zR)xIybq2#w`TdkZZV4KRpfLOGbxLn#LAD4b5T1y|oKQMG2jV5nfSkXA4j8Pi+kIaM zG0nCACkXY!G{GeFi$Xe*T+#AVO z)_;)6r@bm3gxn=&A;U}KRyh&}Z zfpiLFZH-FK|JQDMOz6i8gFsk~-EoxJlEcV^;pVX6Zkuzqj5Y;5q+yqG`29Rwb=7sS z7$-PQquNJZ@a-8Z4C}XBuwk& zUf~u-xyc})%lQ332cOJ8fT@^+NE+z!qu$OYh~AwmH~fA`+y2c0{En#rRb58fI2GCt zL0G)bh|CZ=GA5kkAkhjTB*ef7Le10li+6&&QqckQJm~b20!%sDEr0Rh`mQ@5GxQwA zWXMg;?673aI@8SzcVIiPK?*))*m+rt-z|m+P_Eutw%jSw%PCm6>qxl1YtQpc6`$4i z>XURFYW(FKlHB{SKRM4U3h@p)w<}f0ZuG>4c@(}g3ADh%+Psk$;I2Rm7*XOaAshnp zvDw9-z8ccMO7L6*WTy^Vec>C5C1rGRWu=6ATI$mKuADIB6f{Wuukr}Q3sbjg?5~0X z6RcVh7aX)lp9bQL|Ff(@?os#KG=d;1TZxRdgSuG)$g2(JY4x1Mk)XwOU;WXRK9CFY zY_i4z^E!{tq3DpjsFwS&kvlFZoUdN$KGR!?HlI)Y_Vq+kHlz3Kjf`uj<~}m|yg(}) zc~?dAIwBezjJ-a=j4$K7s}J6R57FsPpySHHMQi0*Toey})~hLsYwSv3zk^*k4l&Wb zZbKihg?9!QqCFB`j6_=BLFWgV5juimbH2D}Lujnqo%LCpNC_^uN+XfQo>Q^qU}qL; z=~nyqNM0$|+Caqt%~1u>fBw!GM8NcSsG$X+Cx?VQe8x>^7}nYB76V3Iy~ko=#)G{o z^)wSKlvqya@mU$QM>I8Je=;&K*Yg&@ob#}eOtWz9q=@5Q9(gv07wR1Vl@VT>7Nc_Y z6Vq_RgUEXaHOefnexT(#k~M+OxN!D4+<`&IgW_4-w!Tmg*t2-HW z^qn~9$n9=Mbua(f`}G^9!hjV|`$1h(U-&ie6(}dk*DnT=7F0{Yj@mf;+zy|S2DZU{ z^WQpzZ+1Vm4hpM(B~-g#wJBSJt}&sDEYPGqR|mZ zfy*VM(iswY{m$unOsyV&y6U5<$q8l>zvDB4?xE9KiyBrs4=D!+K{ z3Y=+1&vXVb()kux-;)oXS1r2nzLmb$%9{d%vJ@Nuu>FW@q)BFLo!P?+N(teNcg)!C za4-tqyLV67=QLB~*VQv4G7Q;6z>dS8XP%PoRGJlKL0+u$M=v=LJ%Q z7TMsfCGxACXJ21k@!&#|=$U2OAYl)tF1jZjhcfB%4~nkGqlU0pObPJtyqe-{~ ztx!ewy~^!kU7)Wrie|)8sO~u9!Z6K{`rqVCFr6W+NG*)&Kx2`$)&Ls&qk{}=e*akx z=J9=hD5y~sidhj)W2jd}2J;i@UGSe5uVX$;19i)h8`qhk9cnThr1x!U+JtNBhJmpn z^Ys;Downa33wI5~T6JG=cO!OQ;NIh6pFVADj>_GmaY&@GY0^c*PTO6>UHmU6FQsR{ z{<(S$-0_#Mw&1-|=)-g(HMa#0;sqqo<(9XmxHnAY@P$RU^8XyU{rea%$&dZm}A@J1a~RlE0$zu87K)5Bd!9 z5yJ#)<#at6i#;2tTva1|>RL)d$hg&HeGc%(e=p(IC#LJ|Za`kZ^r9{im1A$Yl_J$R z54VSrj03~iUHOa0;vGqn`1Xb8^cjlrkspj5#}2*#`6@J+=wr zNLjJsW08!-Yr7Bw`6P)(4K}v5aX}b?n>}v~a?3HOPWC?>1)>EKaBF1iQ@MIg!!v|E zS3sd74A0)9cmo9neifjTJzFOf0z>u`wg?iui-IkX4^W_6kh zOz|z9LTNj(=Vj)}&A+0u>f*cNLZ(F8_1jw-$RrO>s0MNHwTIYiluINXFWozAQ`wI> zF(8@F*993JYKU4@yhBIt_cQG%P5x7G3mbvZ$hD{Kw7-B}BNQb_jcas66tPl&fhOD! zUkU7Uw~oNgWI$yK$3Lq(%0=dk!Us52wppv4RNgDoT*EaF-o9#Fvvo zR3)AGIqO_EE6;-)-Y`mVWE)JY%ihC-Zx~C89~MOWG?Rb?OB5O*a;<5t+>+K9%r?V; z3gp)|wOp8{^r+T~`4uV}9cuXp?$&s5l{{$eS&&^*Y%}!78xF!2-K)%g)Q7l%|0rCr z6#t<0?~CPiqHWEpq2aJ8>m!G^n{Q5X|6cn3%}q`o0n@IlP*sqN-enXY->i-6_2VvA z9$UWjo(5GrY6?Kn3SBS+fNQLtwkGXw@KgF!4k08&0L%?o=H&z?+7FjX*a`Ii8MZ2N zh*1bhqUe;r#%1q$(i-i~zLwNs^C6)(q8 zLRuiIZ>hF&m;LgKCsIpb)4Y%_zsZqr)q&iFB_ZK2qZ!JyscrZ85#u`oT86?t+t<$+_*3M-* z{RgXNYg2`Gi-{ynbcBNL2nUR!!jE4D%`r0=Mz(f7nS7)3@Zo6ZOWIw7o)7VLJOhF^x?!z9;bIu;W zpbr5sYGFF^4*4$bdIX_2&Bgp{(OGvCPaY-JduOx9Z3-|2V@o7pS0g*x$|LJkvs_9- zv`J*M=d6uVXo6JGYYL%JK)9vUZfoz*<@^0Y9_~IZHfgwovS?e5!650jTg$dbfb z*3|^x4(+9dm_7KJomgb5QdRPyd|lDIIh>f4&!m`dz^U>P8R8!96Ot@c38O57G~GhK zvy@Im4@EgO1w<}8+M`kSkW!A*s1ZaE4-Ttv8i!Aa^j+e3D2O9ke9-$eHM;sK$teoR zatG=(?*+(m-%Gug%`d_I-A%3vA>#_q>Ly-9?3JH-RF51P3Lxp;zc+#wyitJub8jrS zX>Uu;DN@u)K9?i1L8PtrNfi$-IMpm%>mTS8+5>~^I=`G^G($sBT=Iehq4UkJDT%<+ zCSV(#Q>>ZLU?twH_xJX@4YCrhtn|J(E^?V@*<5fdj%mjLyV;xP?{xP}o)VlKJ?cql*7U3<>ea`ca@$d#cyP>hE@7bX!Yb|kD8w>J z{qNttOI{;S)1KN24STDUwUV(m<;MS(LH%HORgsw|UKWIVeN3OY~uby8Pn_|-WBD0>}va61vlLJ44^?2Xn z@|G3V40R0u2u#Y56mx(6^1Be^1hY5&lfV=nSI46y_w3SP6 z`&%}$A5}mYAJg1D0KS{1pN^3wyVHtX$Cu_QSPlNgcLCT<0-t#Q1NTeZz3y#$eoCfS?9|sthl0*kazAB z&z6>1Y;{xnTQevv5Hpwml&F>b2B!|DM3n65b2gik?wBz?}IVU%y+-zD5DiWwS z)>6Y~BvVZ{hl=5(K2$EIJAxw@O?JhL&^7Q}Awe-7kV&E)zdAcFc*$N#Qk^asjKbWY;3)$WK@HsTXiPH}#B+S&-=? z=M%&)h59;c*egxb zFAXvfKQ+cs4V;dw{g539kcL;63J%O!2d`b4mN2AG3WBev0_-99!3_x+N*ylMdMrFi z9$eRQJOq;IAv>y3y&4WKuoe`ELotMk9I4)0F-$Ixv-Wa7s0V1p;HefpG}r6VBx}vq z;PRf}ty$#QEnnp8*%N*Y2O&;`f?#7re=n^+0xLqgvQO)d3i(yk+pqSjcRNOW)&$y6zBrXj@Q=4%0)xOCZp46tcl`yj9DDRBfArb5p~bZEbS#gpF%N3OA**eiaZ+|f z7RdE8igBqx*H_OBi=9}XuULx% zXAXr?NEkO}W7o@pjUI`sH;TB;Bc5j~({Xm2dOt6mA6-GdYjrOgF>5@;>^^ z)T?ez^|?z3jRMHAB1VNvG-(mWM9o6B58$ZChPf#hYV072yDlwDzUI&=Kqpk(*%8^x zVQgC$%-eH+f}IJL)(PHwv{bcw(;9eXu_o`^&?Dc6i#_bFJ`z>rG2$woMuly9RZ);V z>+HJoOR`)5s{NMu1eR8jAv1-r$H~r%Pnh!`N6dNqOZb2{)*n}7$AJb=o)JQkZ=v`z zm^q|WqZgZm;Y~M&aof*!6Yg=Yg*Mx1m#R*lL_VZT&@{tMA#o>0CCdOh^~pktUGTkK za$rDs59`qL(~uEAFOZGo!A%~Mbg~1zIjaJ&cdKI}QOzfO!KhJtB7=%3@5KkEcQ2Y) zbf}J=2DzmnOURUTjgkOkx?)=jWK!veq~oZy8nbd5Zg#*YbhprL(QL`F@S}27HFAroj~yZ}y9OpZ1h$ zzy^xSPESn==ayzI@gh`>wLF%Jni)~;=9d~5;_x)J3&5H;({d*EXhE=~oVFF`iUktw zsL&u7Kr;m>&u>WukI69UpoJ0T zO7{EjvQy#Nuqlk+wGN0s>Ps@RY`??4B zgv#{HTZ%#Z*ge-xNq^7ZW3SBPF2#dx!JdQoV1=1N3K9b&F;n9kuO`VKwE;MCx36Zz z9P^e&ZnM}q&ar1BO@^&Xt=TLby^T@~qPJeTUe904vFcH7fEaTtasAj?WaiHMoV{@< z=l$+1&md0K)Mi0^#zX-0xM-{k&A&TZ;J6R99v26MN)Xk3)4);FoEysfj3qd(l3eg`q4 zKEMqzc4~i7Tc{PZj-%1wlq|?Ds^9bWQwJ#V{MPG@4Z;HNmsU|9OiLOGsx>thpSMl= z&>bx=o1TsgZrg7e1eNh|8$P^0xAlO)Eh*0W%GKDY%b)sNE7y>%W+bN*`MP%yJ7$b- z4<(^g2AwcLO8XVYrqXeVT4JLU7gm=0#1l3O4+r{@B zu-Tk}Mh`d3BJHboTJ8ldCNjRia@jT)u2JIe0w9}@mt2fpfhMcM*v> z{nd%w=Ij`0HRG_4YzEQ=JCqUBK^Mvm{3Bt{pDePbkAsRGEK^C_QgdH?OtB?m7a#Mq zc|^l*QL~&Jv_qOQ*HCbAb}drc291;MO0rH0rILXGVui&GDxy0ZzpHYaB!?y_{KAj> zv8R%y70x2T1)JgadAZZ31aq^P6atT`@J$rwFe&fZPsFKZfsm2Of}Yzyk!`e&V^WVJ z&~18cEqGVXNbLCfz=RM{Fk7e(Mv`SjF0kW|iF-)0u`RT`RnZET)Zlm2r^>wIeil2Um<^))0{=1@2Dl{o8f^I_=)W4w=M=~zV z+F!nmKKc^>^oT*-Ay{+oqm#M=c=`a_IGBTzRw~!x8l7g*RWo%e3Obhw@ao-VWIH_~ z@MaNz7FCXl_XE&JnCXESzc8xZ0kM=W*C3$%RC08|9a;3d^t7=gva0fD6Tq^J$32k_ zEpIX?o_Ck2iH1a*tJ3#g)2B4X8ocd^H_)1X0X5nG5fg)Ff(^TR>y@s6(jNB@jShR= zk;vzaQ#mka$d_W{bg_Z=#pnXg*q9HQ^MGX_5l;9)G4`pd zG4HS}AS1Az^oV5}bilcrrmivn`f zQ|YwNgt$Dj<#O3j^&Ur1lo+f>XS5R4vIjZ39zmu|F&Fqa$KFY?9Z}fJBbZbU+%(B@ zz)Z$($yIkbA(_znF)l$CyM>MBA6pWm6;r<5f>K_=Bqu1Y(>R2d8te8S!gr>vxeU=n2 zMFar^7E#ptXu?P&yY+FVUM(`DX!{WAFsWE}n;E}iipNE$q|060QZqT*EysmqtqsOZ z$+_C^=-o1~C?6)*cInGkArQO+Y*Y4JPC$3fu6yr1FT2)IJVI6)s}oci=Ecs)ser3{LbFkRh#lVF)7!KO~z1FR-gk4@pwmtJ--m zWovBoaow{^p$2QY&Sge#8P;a8SYJwQ0VU(Qsd8e zeW)Hg#JVeUWGnyzdY(b?*%BKr^AqhDrQIn3JCL)Kt zFuK7D949ES?M7}kt*a|nW$R7(E-ZP$@es4B6d#(=&WCE+r=Q1rr0a38@$PspZ*95_ z`(Zq?X~g;rg9kLaB+`W_EDce@D6Xi}zcn82WGn11w{Q^V*vnih&Rs@^K6Cj!u;DW-?a25*>A)=Rd$H>-TvJ%Pis}MRK?l{9xT5twj z0|j&Fd4B@!)>h!^=+z?C1NDon8l7lWR9?0j@12OGh#*`>GI$y&D(t$#I_`nKjVXmF z*Ex42;jKPWcU9dPbk#g6E9oh6?-+UGZPe+EtVXQH%njk(-UcI|@B*WOfN%<&_3QG^ znwa4MJ^E=Zjd;Ty2RG=Gq6!P}V@Q-H)8Iln5GM)6RB`bxSY6oUYLR`ufH+24UDoDq z#Pycu=<%D#l}NvVAqCilthn7!<^!SVFtD`1`23ua_bd3*iy~8gEy1c2prB@K1w^IK zUf+mdU;v9m{FU>d$zBTSIVGXT-H;@GlCZ1Ll8imHfD{> zCicn+ISMW3NC$;3#UYvXiAOt$kwsMOq6}EW1to@-tWBp-P1V^ZS^?y)6~khXF4VGp z4XkqHvYxBa*IWi+t|4K2_R>(xu_SeM)lU1r0Yg75({avaj8u^o6}09 zDK4R^Guah^*ZK}w*3J$Cre*40Y~b!ZverhHT3^XfxVS>>_Zi97byF!g08wntX0rx~ z_z#isVI&cQ<%%P@1UIxNRgJCP@!K(THJu?-(%&c&Fh!<>+%--s=THy2umX3?x^8~# ztgD#*co>`wYv%@(fhMh9-pj;UyK3sk;z$uhVr?>^amJtg!U<2G9kFc_XtDu(0(~)(!9J?9;|b(sw7T%d2sa5p<(sIs1^M?a%2gTCGB!&FZKz>VviLP z(^o8VezTms6@h#ZgY$rb9o8F70S1TY!7S%*a~A&K-PPh)um_6GENko|+d)VjWP1F5 zi2waU1GSnDx1qCw7Fv2OXqi4dJqM@B1p&w436em`d35>a%loPn27sdStbdU>aa+t9 zI1TZpM~nsdpryAOrO+gMmqMk5Xd7UVl3S>9cIgW7+Hx_RS#b+Ct6v)Pt_cGoK6oAV z_kFhF7P{H70o$Cmt_pd9_8dtmKQ)!;0bc>2o_G-PB^ZC@G?~PtBE^0+ zDDp|cI}H~-(qZ~7xaF<9bEl5BgN`&KW=i8SRGuf)+#Sgs5uG2gjIacrku(GehlzR>x|U)7yscyEc(|xOK0V zNssmi4SPmOL!yP^xZ?JudK1C5=v99E_8Vo|Ox)^ZfW``SAMdsJ4M;q|kkH9M*BrpD zXY?!l&U1_bE4+nY-vSo&#RV*Z;Z3uiWbmlyKn6Qgj@AwfpoFh(^K#^SVbmhAp}gpk zJ4Qzyn}_@|*-Y|V4Ljo_`T6%8dv4tl*njcro@2?d!IQ*n=dc;^k}CZY_c zQzX_Rh6&QfA%-%O*S!ttL)oH?9i9MR5u=Im0X0bC&k}+}TIo6BF{$ z(B4_%UP*X7r8QU7%}qh5IA6tM7`L_(C)GWdGnKW~Wr>Lt6X23#qTIgobcg^YNua$A z|71b)audI6kL_S)VKKZ`O1skx>$00WlsC`gKSISHU;?J^b)##1vaWCQiB9-xSdz&db+#0k7$YN^ql1TOYTN` zTE(K#Z4Gu$?l8jct8C>bhwg+hQuDW8FOx@^Hu34dSGkxpNDpf+qU;>DHEKK0nIlgf zvntmX)$EZ+ZF&0Y%{{kVQ9h}qi&cs1_V1mz0@VnF#-7i0_?Y$?1aUvlJrxA9Z|><* zX<-*3!naSm?nRyiaC50dp$vO5*!43M&Q|2Xf-}Xa}h=79@|IOm`{<;5hGo!bIS<{O{r+L z;&T&c3*N0*a-6`yp|l&M(`OHKQxK0gP+oQ>v&WZ+_fvLkQJpgG<~fapSoyT_X-&&~ zo~F%Yg*%5$@fGwwlV&y|8^{_zbmxZtczr-?ILrs{%;dhKfz3#vK|>s~`*i6$&kLd( zf)xv2l?3vDU{~1awmczIg7qTQx6B;->}@mi{ZZRw(po{Ul?xu&n__-HbwNEL%5CEZ z5c1A>!V^wHXM$NwuYA{+C=-sfEraKJoOP^gm#Q-Kde5T?ga6_QVZp9Yygh;NCtB(D zy=Je~q-slftRkEqr3aR?q!aS@uC3tlllYmGD3{7?sq1(H>G z#$W{-g8VQlEJMEkj@SIL=c}ka4^k-L(Iztj2QTogac&n$E&1p`^^k|x$v-CdR)u$Y|?xHwzkOn$8 zIo6M$D6Ml4QZvB$(P}Z$a8CQLCv@&f>-peL_T$bRkk6B~09%$_nu)Z>g0)}j+`A5e zKZILN1Xq%0q67;hUTSZ=9m zEXN*N+{+t^WMr-&z^S6@O{V;A;+3Z*u@KSdC`mw6Q>rc^kcDtX((CWWayy|VcqHgG zyaU`x(Ru=0%jYE2LQ_SJCX9t>47No{dUy{#_hY4V(WVKJxIm&FPT3(kgc$NRdV2Hv zH82zve0jMVALaJ`-;Q)MR!D?-<3e37*{W!P&wr(U;9fCdCsA&*e@TNf$8AlFk58y(e|j!-QRd|HULqU0G&0#h5qboh!)X zU9uVEP5a~N1v_Y$mjsH18dL)*mMZ@#(G{U2-I?pn>we{UPjalOtu2FuS-l-tZ?RBQ z=ECe$cN_5XQ#pMd2baEHY;B@2BzGwUC_ypiZa?gEI8w6*1*R&ygVF_4AJrrTe#tNt zx^OTPb#|K~em~ZGBZN-%eZe=hLd85jS)t6pE`-I@g8mwsQD5wA7IrPox~`&Q9IG`B))kBj5Q1IbvW*(AM$pd zZLK%)J_2>f%)vQG1d_wRLYxky5|9ZG4=>iQ!$gj34>)7B zxUlIl&&))n5JC)s9iH?8Jw?hhLD7Sy9+{E~`E{KCfUMC46VYKOAJ<;yfYl;ZI5g!9S1A$p#RRdXQ>Qwf zETVI6O&n^ou@a{9t9YEb?NxDlEX;%`^l&J5MumJf^6uP~Ti=~5$Vh%kpI@TiXBUQ! z7r}u72kRU}Px|A8%%9aZ-ma($7%D|ons`dVg0o0Dw{#@@lb_wf=!h$IH`C4;(WYQk zo~*fwP`9I&i1qeQUxm{a3x#5>>6*RVO{CH2)vx$&Qy}90s`Efa6Gn;<{CEug93*+p z>t5Wscl(G@x(%ZcP552H)4C1!&gQ_BmEx-&+~L(ckBtRK`v@1iNp^3P%Z$cF?smLj z5jCr;eX7di;MVPWd4^kaud@E5!1;akMxH`^0pWijxSssFOc$sq3Kn<-(grwipoloY`d0k~;~PPZL8V zJq8kYUp@QqDwMv1PgJrCXk%-hoqftJx?b#v_!z5(7l^mJ5uN&sUx`vN8-{M z&@2E6&05xa3#>SM>tuHK5L^SLzXHGNyPN-S62E_?n>kM5i#kW_Kmnf!jMtmKVsZ$G z6+VLznDQ*%ryZD$nRvBW^vX?Y?e)pqQ%r7y5&`zQdb=*oz4p^wzfmEX-{n{v6r<>- zsBTV6EZI4Q_Eru>ke2M?U3UG%qdmIFH9$n3ku6yD27Z+S_T1%tl2XHPC_PWv*yTB0 z;WfR50+O8&{ZDsMP3@OHsVZxVxu%QxOF}bqY|MT77~k{!-{6<}8Fkgja63*o`6e0G zMAx{`(XS<#&b&wLuQg&J1}p3`N(8)bNWXf(dC)JY{S-LR(gj843Nmh@Pm9>ZCF5ff zK(zJtQP}@&@C5la^zAte2%N2+jI%y#bPt!Ie(KAd%4 zL93-4c5SbBh&S87xz`zzp_dxcpqJdQ=+J(`J%DX(N3b}p>*THeSG0S==YTINwrIdvnksaG9*}O@m&~3HVbv*V1d@rPN|~*L=E4 zl?_S~xhT>K8Z2~tqD6kA?~ip-6R|c5+qmqMhHiOaWSd>77Zd^$B^pZ& zYR`_;ea2-upweG-&(uqZvMX^WIsEWAv~HZ1An_6}HhFTm_Uy^}MwI2;6_wxURxOAN zvN1RNWZ;FG!<)~7+pjSr6n1Tk#;aY;)chn(TT|OQhxDqX*5Ezfq=(w9yYEuAXIKK4 zuT4FJ7gx?H4R9KAE+kx0-gCA%?=E0G$lHACH@b+Nw>gc(B_VqJlL8&=bWpzgbfof| z(aq;a`1{d#FTOlg58Tg)I?~k1n6(K=0aAKFS|#`#zcWrTt(fnByz;t$Z3Mm+ z5DdMX{)7omcW01w$?=QOH64$v{F9ojkQIFFd?fUdp6(#L#Kp6>rqj37enw#l;G%~Q|i-vNW^LI;;ekGe%8la6no9AKA*PkxyK=*oX!rEK1NrRME zQiD4DC8^V$6-&CS;g`-q5~1>QS3>^*vp#PI3s!ve4O9{?1z^q(h(h$LuSO4Xy_wf5 zP1VhLDk5kK?LH17KpGLMQ!PiCIHwp&byvD6!9!thw=k3Hs_LLnJW#g&VtfwYe>5q= zJqOhX{U|kovVEY-yH6H`t|&wi0yWWEq2_*sAF&pr+zwKA&sxB#o9UVI=?o(qX|Hy; zlr4E`b}xev1o50+eT;vgxDf3`N!q>M&fV#F3hUuHM za?1{B2mhESjG|9lVmyg<9r;u2j^>*tPPa|~;r{^0d~%5kPT&-G-r^@coXi5Jv_ij0 zwQZY43@bZW6=ZU%uzk5t1`bZCdsd{0&#tT5Csu&CVeZwjROfp2z5kKasFw4*yX1po zfj&G(REMIQ{wY-OB!q-%zg0vaD&FFhVIF>Gps|#ouK`oN1mC`{jg0Jds9PNswL+0) zPQjBxoe%4U4mnHi3NXqX+Hy?x0P|H=C3xSrsc@~c&!9A~PVW3af{&Pq>;|G73l;4; zoi}==Tpfe^pA?mM#e7vP|*T;NsLK11STBA9*U#z%whBKv!J`wi=E){y0NFY~NB zQb%1gD1eUsf0SmblUn>6OGI=yYgK0WVU)9CXFSiiiLeJv*08U*oO48>IGM|p2 zO@TMMH7;+sEvM{gfm)99HlzI`?)fijS^GD&v^Z6e-4KKqx)}28h2%Aty_RdHYJ*pc zGkflt_OG=m@5~k45RVL0?P1u@hBFU1rYW=$be}*p2S=`&xh4Yi$s)6~fDGx7UgC2+ z_y-(PCmjS=kZfX5D(L5%DRyw(r2Rh>Hpl6iAzxW$BulCN(&sA`mWtrk?VPN!!ttAj zT#%`RJ*7*)KXEV`D8b!>QhvGz2PJ8Y68)=NdMJg9;}q?!xH~`mDsppaR1uSaD(!pg zt7^OpT^)+c{1{S12Q2)O56*3S=Ye5A#{#Qe?xJje@rU_=1p{k+5$DlqG z$LFZ9SLFN9xm1)%z~oZDl;f86+@!fcCeWfyNx%-vu>;!O2_}?PHLprK>|43|rhI#)8Q^qUibG3)c zZxSp4V0XtLlBIjft6G0mZ!WT4sSDqa5~j4`v`pmhS)qd z!bGvX)kwuusz6uuD+T#psf{LjLk@0?i^S*2dnqm(hVI3x$BJO@s>$Gd*wr&E?et(RV+KmXdu`Ak}i z_uTY{htv{;WQhB&rM>0k`p6q%{NGLg%OfW)=Q{&*wN5CvK`Gk0S2jna zhhov8PkNa=W+VqDqZjl~;fLT{_s>BxqyMYCcxZLAm|>*29Zy{7-x5Jv{uGp(U>ZLl zCDER-;{-wu9#p8`R_F_gMUJ^EE&o7P37V6jSW5k_cfR^C)~;n~>OUdy@|D?C%H$X3 zqEB9g)Cs7hTa?OI%Ju}e zHo8u6y!9ecmM0oL;|(`9+F$F_=w-hIDBaV#k|i?fQ7VI(#Z8t+qA9WqY(ywtvP8u~{FIqAj%4ah zhG(X~Ew-Bitcli0tPQW%5}LKL=n+R2Qi#7Kf^nn;^`sPjh(Q;J)I8MPjs$7q^(8`2 zbkT-((R;0(Ah@2nMc=vEs8Z6VNDA)cpXk`!Ll?GxRxKS$Z#E%t#-EZeLU3=MW5IP0 zAoo9M&)$bD2yd~SwI-K@K_Wczkv?mSA7*Qd5_Fualr=S9+DdE;0k_i4nhcaZhj zQO0`nbSPoclzi@ByR>Ie`ZexqOVBADIf2MfOiX`DD`^hIk=b{+-lbUbw@a@2YB{Y-esnz6hLLP#2M{Es2)Q;6sQIF6o4cmP^tnAv%a1Z4`9?hU~&^_RH z>X63w0`&O=qR|uXfN&yt9VQLhbQT9aFv*}a^No?&MDf&2m!YUk=7av}YbB$M6?-io z%h1%<=XezMhQwCf&W57>I+dqR46ty7RCAbPR|-|I5F1EZ4^Zc%3V|gs&{DjbfY&XK z*X_k+_qT7HpQ*P9bg6 z3HlQ9Qa@aFKk)|6{--*h5{Ap5ndUFQ9cl@KQ~w4x@Xhuq=x>W!V!kJr*wtF6AgN^3gYpH%3 zC}XXS#FQQPwu8@GN3&N3_Xbhtxa0j0%*=Gz?P+qC=@u<*Sg>NZ zm$RcJRft=_@>n5fuY4>acez7QNX==V2EDe|psaHuM-M$HIK-A;@1Pn7rbLbGz`HO* z*;`7h)HtrC$_05NqTu^Wg+f?A>UiY$e|NCGGCmMW`ZSFRmd#4w``+UTcuW~HG2BhF z*3U;_UKV5cuEd)}bWrIVri?Nqx`_Zjg&n>sco&j&@^VI5*b;$Al!{27UNi)4k9QirWIj zcDe8TBFCuzBkx&(d!Fi>emS#tHeAdlbitEyt z(dk3}Z`QMr-w;SScQ#YI+{S3RV>*)=g4=K6-Ws|kE_nh&hYZR|m+L$M_dV$>d;1TS zSiDv`O1|44TX+vUw{&BU;>cm-#LW2PUkm~!26OkPmud38^pTh5qrD%WB83Fj!D`?$I)fkY zXTT+H?X;=F4Uoy!)I*TFL{DodD--f6si~=vxN-6>>OiAdxh-oXv1VJ3MHYOwR5iI> z!qgXK!xlo%STQr*>IR)>q{H-sgTyPffv>q8B!@W)U8ZX8a^?)p-yhblsMX^$`1;_C&2S63&`rkxgo^HcIU_~TRZis6v4 z;0}{&Qg+8&wLG1tTN%}gd3cEt_B;V+eP<7I#*riAu3|Mqo%hOk@eMupQ?IPhFa3~3 z6WqNbsN;i2a~oeorw;0q;)d12f`He{Q=bZY*wb@7~dufkhX@99Z(umonhkdJw zCy*7t5H%>3Rw@#A-|)I_T1=e_=T+u&Uj5R3Jx2FCb`~o|J;|v@x{4KGV<;_AjPE=4JwUQXc@UFcSPa2$cmTjsONOm zKfX@v5+^)Yck2oTrDE!5l@*!l6PJpjD^;3-)ZIL)tIzEzY z)m3V0M14kzET8-{O&wT z6_=&At(&T^0U66pEGjK8DDyjo>@SMr81fVn+MTAIiu4HFO$o-{QS?G$c8P#_y6-f+ z1V)*ZI}H7;4S10huB(2(td>ig=G^o9o&0&-k(biTV3R9ns@$mET~>JA4~;0}tL(y`OtGfF z`9vE(YTdKq>iDlUO9<&cWe`(siHe$sDo0yM^8NB(g#{>NNMTKPq_)0h7F6Q$ICL|C z)1*?x@>r+PLihw%Ug!z!4)^8-LQWi4d=eM4dU1rX*{w7ms87pATn?q@F2G#*fMlA2 zD|Q+#sJOQj9L8~wr7=ymFlmM^{LcM>C9%gE{Q`XbeD;a`N|0%#U88-Fw*bm7FnsbTJ8Uz7`cQNtYE2cOa=|JavH9=?JfxZIbutKOdHh~cq{ zqlK8#$w-tJ%8SAIVpvV`wjBayW8zLKX0so}>gb@O?;KkP9y%Q|;)=Emh>d`&S-D7d5n`{?vF`!yo3?dlgSlech|=ArI-*`7dgi^yflpwX zs80}DP_Q>>z1aOh{7J{2;XCoQH$zvJ0x!Q74s~5V$~wlpI7E*LfMJl+%y^L5z;s7) z4rJx(no0}xqL?`H&>o3vaKhVLmjEzy0r?+E_pAW<^$>>@?!ql)30sDi zl%qjwL6GHzMA^MhoZQdlG{&D^LRw3UtufzEcqu*c`1IlME4DO0jc+=0y)@s*1lqIE(Hw%S4<0yU^PEe01nxHyutigwPBRDCb`Q`4tWj^=zfQL`VIN! zF1#L82QSAvqxMtwM6@fkBTnh7*hyoS(}bj*IVQ?~#f<%1Hn3nyEC8w*WxbOC7`4bT z4#RPNZ~%;B{|qSp26=VLMe1gcs=qKY#+==#Xk4Ay(UydU_C^S2ui4RUP;vX$Dl)RU81;0iGM~fmt>E~$Z$nwVUE78 z-%pPhW$cC89OaH;vK1_s@vI;_-R^}q;5GNG{CpNC)gG(+ZiApK1)S|a2iz}KA>mL} z$dRfh=aF@8M6D9GMAaYL>%s1U?#6t3!rVORo^6izuRc~JDtYKs4M6r2KHeL7AJ-|fvWGj$Oa7~yG!6kppQ7N-Td=`%F_ZPeiTJoF^!>yA^7EiC9|_Qi$gr?S z_&2~?=gky*n#!QK4me{b2Ct@t6sQE_SlnC&2%#F>eHDiNv^ODasU;zafm*a1t3+TZ z=vyeVuTcej+?Ny=))V7D`ymSOVhh~!$%L;w|LS$GJV)K_e?95)2x24y&4(p2wl*-C zgPaz7VV!Uul0ZG4B?H4EzPWWzi`2VV!}|4#1fBzkT6o)o}jkFMM~ z`tc!3%<1Vuhat@cTM{ri2ijdorR+PnK?3zOR`<+Z?Nr%WD_*5ewW6qWTi_e$lVUiD zJAX_v2cHPI!}D^g^Uw!zKt9_O2h(S1$f>Vri#QYDMt{U4c4QiO^E9tHKOV(Z8oAvw zH@KgikWftdq#|3=#-ZQ$I#hM7Uwrpqhk1SG*_>VeCiCvTO*}B)xBntMlc?+jNtdC$ zM@dj-oGmvM$Qf2zR!gF!9zvDKMChS18~;k zt46$q`c>-Ng|8PchMLZ$VXwD7S}A5;UaCm+Mf*8w`9kj*_PrIfrk0gUE28nTp6J~U%4hK2SH?^6xpKBEjQ}M%FTnmz@9kt|zW-6X6&R2Bmt8DnZ zPEGp+kbX*Jjs11@;b#Orp3!V!`BUA1r+?P+N&_{Y-pNkFjb~!Xp=*_h(L^C;ke@V) z)qwtK2UyJ_f|+v){L&u(_C;V}5(W){&)ys!P{QudkG-~Y8x^c@UIB?RT-o*p^PVBm z&u;uGny`3(MN4<3&b|(cP}e;{%h4UHk8^1_SQuZY(7-3C&OhD^ItfkC00zSW4VVx- zp5BtX+RA}e3tE*wrvCm+F8(>kxEA6MZ~_kj>(7rIbm(MIR6oZqJV#`F`!ZlGY`aml zhQp+_9RRX#=xU|HpzYr2j&#$cIoAKL~GbEI25) zLw>?b6AixzT~N)^+wF-&1PSg+?QuL!6GbtEDKbns!)k;)B#=OGBiwu*Kz^Vr(g{#w zQOttwnw$o>hL*G*`efilO+}GOrtvsN-gKxL0Jp&C9@2>v?DdmEB*asBDX;hQ6m?yR41I-M}-vYkx=+4A1nl;UwODiq~Awq2@aBMqqn|3Rw^3vK|}$HSk59m}kd&wYfM zxR{g@3pz0E<+f9Cdh4{Q)wpy3cpP;N$1(xv%gh&kR%A59IOdPNBHVuCI`P(e*Kp^C z%T}49G5{B^Lvn;*67)DNk7R)bHzq!hTAbF*CV@yC?X~4ZGcNTC_M!d9+D?p;6o32; zw4h4oHTs^O9xpWEjo}k0x80oFx;3-dR17lel>(lf1`UUcG(Xz5h9(y8J!v|JsS5)L4D9+O0okzd>0KS0Ro&**#t=>{2Ft zgzh9%M|n~5NB4QZtGTdTb!$pxC53BXiXP`bP6M%F?Fz_T0Ei=d*_nhC z>TxC`g$nd)K&o?{23?rT;Sx04Y6LFyQ%^Lk;;4y>@cm1eU{Va!De|Q^dBp+2vkgb9Kvf| zU`p|k%4D?&h@6^=noIq!vP@v4SOD0?fahbYuzknF{hcth5<|LL;IMi0Xl`Jm)h7M^SB8K#*_Cf^!mMHx&ygnzmQh>3o)P`QH-$lBxMhyE^pAd1A3<#9mUQhy@b;_jM zkp&A;sBDm0&$xP%6irz4Pawazt|QbD;Je=-t%|}A-+#GgL=*mpyKWk(ay2_TJg{3H zyUy#jeSaD!Y}bD_qTva6gy4p}d;qN=`@VZ^*sWI%NLGxnO^v)|LJ$#j&3@^0$YVNX zL8l}nZU;PC(Wuif5@d;*y6;fz5uZ&3uhmBms#~17%4sLUN(wfrTen-vhUL>vbt>|O z0nhj@o>KOrNAt}E+cO4V=humzv%z)0kHdW(?yR45$<5DqP{@C&tfAL;V3BegSxWsS zblK*7ny_;$DCy4aD)Ak7@{vc`-B=4el2?>yi#qMVvGlK*JzYkU~&6M*aaX{VH z6>V_wsn4Gy5f7sD@%K||-Oi-;)n08?nQK>O-I_rkHExZ=El`4?=79@vZPEc+22(Ep zPX~)t^=r|MChZs&l>vY1DC=Z}^a%DuvhMorRRn8bN5ivyU0`KT;gHC84k9wenuA9J zGGyo!OR8%{b06r5-&^xD+o%W_m}>Z?IDrYi0xgJmWoVf!Qr7by*{1L{FO^+~`~zJ5 zyQ8uSRSc#DgV14D(4CTLzVeM8lV#=Pbd6wWHhRpah2rf55zkef0uM->|fd@W=fd-4{U(n?Cnz|?H*WsI-WqA%YieT{6XyVPFy zac)QdExP&ZK$4zc$KNAHh|8c-q|M3Z52I*4eQ$}dUp@2ki@*FA=Uh#222kVva}Uho+giQ5%k<@)-!4%y3uS&jyVLHv8S@hO?fjiJ8b1cjzn(q>%KZ4k zolKyY@9^>i>e+I{$VjF9o*Txm`wK!yZF}emZ(qu7>~?pO+Pi)EJP%_P;HZ&tz;B$I zoAp>+(_{jJV`4uMQZZ0&JEeIP1pipmaf}La!h&b6I-EZoT3|Wt^Uo&q+kQQ_)j$_U z$3a|zt>z)LP`(Vpa@MZOJOuq2LxuN>lC8*woV(w&w~7A8mGpPRxr>tYWRD+57BR~& zmxh+v+9mb`@dWfF`9|x=?X9N9UVGwOWylh(?3N4p?ON>f41Z2M?I*Rv`qcJs2d}A| z{+c9uJ_qIF4_^0Ip9&|0NOVeYKRFUkZ}qBWIO-6h!s)J zb=f!5>`G@C0TEkkWQccHFG*oxkRG$s{_QI5N8YLosahxAwU$L(LdjmzmT^*9jnzRh zBy7Ko%Cx;%zSuzbR7&XZ=01gl-=-}^;s4WQSf^NS= zMcEum9`v5S*Ewagoap`f_Jt?EB+`%^q$;?{rlGwbE!&nsxN!+bz=j#M7QvPh{7W6u zwCX~n2SdwKU)ow$6KN=R6an+#r#j;C+y6Na%z-j9a|c9OaRXUlOw#vTUu+CanGj)* zM`9s)a{qoQ^DPUMWx+u(E!wi2ARX#8qies^DvU)c0&E=!=hU`LHwZFK6|Ix?mUByB? zY0+WM5-;#VvR87q__IHjs_eNHJiQ7p{52f~2@?xcfzIQllhAY(ru6A>9wL}s8@=Oc*4`v+co@^*2pXh;>{dMNJHB(AOHG)>TW`s zP?GlCaP&F?(XSm=PgF0k;@CVT8s3=en?YJfU;Zs(>0EfW>z66tQ?TJO)Jd>o$tEb7 z<=;B%RS+AM4d~kq;u!#cE#0}ytJu!oSkUuZ=lB;?j|3W?(x#aZs$NYb8Xf9P44F7} zsV&Qvrx}ylZEOrKN94P1EBoLQ#_E*GamFD=2hh>~+vBk6pbHBY@*NwBGct7>>Ng|Y zpwh^84*(NQ`^U5JzXS$tIg^&{XSBWp{;ztLy2-<8=9tp86Nd~$XL;@3KRD7k9k8L2 zDDF;QhC3Yr4Qrr$v6c}-0o#lIlzaTZDgLJr)XxHCd*~IJ@dJ^(ES_^^qfWq&pE ztbM1~ugV%wIzO%IU0Mn967nLN?B2Q}5kJV|w4CHQI1?gP314h`!=5DKKB-A_I}L4` zN(D6K=^y`WS02tCjn2BYOKq6?NbLE~)xOPj$Z#O&W*SK8U-7Y~VcTkW3ozW0q82)y z{Rh2+f3F<^Ruwor93M1p^% zYj$Hd))_PNdku9?=bZQZ^FHVNzW;aAHP>~$Uf1*Wd_11_$5g?<)LZGlwbbBXTWHKx zSWP6ODO%y|DDS^uT5J=&z9soo5w^q1`sX_X_|>>=&DYymaNDU^BC0e21eHqjd}LRG zC4oH5`J|T8yWhzzkZz|0^;2~GRoAX|-kNMFsJq_+eMga9ryXul?t0}<*ZzOjC!*je znRyrMg4}7WV(g0{<`E4Ft|c86Q;#X zxR9;&4l*1crhU<3Rq90fZ49j#{D%`1m^M5Pd8CHjp#I5-f$a2HC*A`o55F$ylWnq{ zN2VB~6j!|HXM)={iu%`gSrFXifef_oNgMv(7&muHIG_WJibyE|CE zM6i5Gy=3}OFDocdjzo!{Pn}LThLjRrLdNPWX?!gk2!TBwt%Rq zlOUeD7(m3KiXF^yb8}tlWPt9t!-v~x>pp<=NY6itvjsl;TNawOHZ%4+*6Dxo?bm>_ z4;Qn8Ap!D{7(tVy#mhn^GZfNyPl+p%9yBoG{O*GNt^Tz7kiy!XsvO+zS&3m++YY^` zplFXedFvY^)h_gFx1$R%OJdgFWwBS|Hcj^URon$#XW4(Xv>P(U`e)QZ`*r~%Kw3ct zLJ-R`kAvV*U!)GSpSuDvx*X%E8I6#_OJF#9+L>C zEKn)W0-+5KCT+$_Kv&=95JdRb8EoLcI{8DII)4QyYB%zRLBBcK3@=bq@cK0m*czla z=KH(pDL4bRoo^|!0u7x+R{MFA8~(Ji1YRI7;>=aCn_~a?U>9vJQ<)4O2cHe_wRaT* z_u7>lv=Ba#n3|}b(w18!ZRs~D0(5bHwihwG7oMKNT1CL)ETA`^_27n(bTpuPVUOyMA)X4ZJ{>ApIArY2?RK zTK?P*`(sU7uUgfjhznaNo#L262P8^4(JI=5xfarx=5C_|cy+vPT=b(_8iHeTyxRJ* zr!@Xe!S{@&9?@}h2T=G&yUQUktM@}k<$M?f6iG>Jjx%Alif|j-LfqENOJVxK{UtRN z0Zh-8PxOkGj+`iIj4&&T=HpB5f3tOJh#VW%z2yRWAyeik&r`sQ(eVP3T?aZ`)W1uS zq*2fxO7-q$&V~m`U~>b64S@XjsJj~O3C!*w@5Q2d3}kt3mlz#UTYAve@U(dBp4fbkA?KB~W8kHW)xFYCCgL z+qA+leSPcMQ^giAgH^r5&b{%!om-@%%71)wqYfjsH|U5Z<<}8RYlasQwhX7gPE+lt(A$dHAm@KAfch544<+asB~GyShwOi4yi2d6-kca^=IAC0FrRYz&Ccp+cBu6EZg-o+B{5_KfSpr z+ZFg4!8d|&(J$8b4e%%Kr#MG({^{qH&y0Exb+LJ(W#Ao;(yw~Dj_wSFVLMV}anz4L z_OjcNj{uE0Cp-I#jF%kncqK?XbAkBN_)P8i3qUE(0D%r)t@;Y>td>|T4S(RYpK2vhH$|Skxo5_s6bzN%>=5)K#zTDJG zRdMA2yDW+%**cXkKLRRlcbE{X9-Z4uIA{jo1AN!L#1Xj3s9SO|f$n<^ztaF^tOZL-BJR3bfc;gy{ey%0EvmWU` z@$9^ip&@UQ2e-{SNST-x|NFxMxw~DzJshCM=ucUqWRAFts3u421J?L({Lb@9uM_Cn z656<;3`E17eJ5P)39}FpKPgp3r5JL2fBT`e01gan6a-92uFds!(BFSL7cNeAcX6nq zFn|b?1>F=^O4+pujlsTIaClh-*~~KFgz(JX-aaYM_w+9U`0*H6ivN1NYlC+)x-&0X zX^gn;L{tS6wC)^+ChLZnSCwY(AldL&D=S|`<&^T^tY3i6>bg!7wfG^Y38QZU89-Is zo|a7eg#^Ekxd%*V1bWlnQp0uUpug`s=Ap3u_*1c!vNB>dBnYcy&jhFzBaF|G4)GT( zN=G6h-Z{~{fghH38n zH9p=vwv`kjTc0+95kVgdlVx!o|3W`C5GJd}4V*wMLYJm^52J^<5qT|XmE31?tB|KJ zjJNbY`~wN&7$|g?uB(7A+x4kh7U+Q|3SeetKk1Pfq_9|eohXdl>@0vys4J_lt0h3Z z*5|HHX}Y03{nj?Yz~@X}L8XiCq(6SGdle)yw{jAe_Nf^dwzJ+41d?jcbXH{;0i#6x zfVpMSbpB0A0eCK~Jy(j$R}27?M4^gqK3?|fF`;ANr$F#?)h4kWyDJ3^Pqy9Qrt89N z793j-V`IePPB8m1=z(?O7ehZ-tZjhIybo)uxF`rY(?XY&|?~$@n>CJ8G^pH-AC(rv| zHQxYm;=FpVGAw5eifP@ej7v!=C4ya!d0n>nkC^`8-&&pV5m>F@T8^M+g5c3eKiGSa zdY%(Tz@&5lNWcTLr*|T;xbxp*SIQp_r~E9VP$`R`r_;WL8LA2hxFzqdZ*tuzZ3IeO zgUY#fT>0a7@!Ns?ec!-9g*FCGW4j~Q_&oXJYy3ZLXF#ioHkYnUZaxQj&JW4Wn+`uF zb4Gi?FuNWlxpr0);zn~nq|zUE0gOBDD#!5=$T^{}3Z!u7C4KO5cY&{NNCjY|nhD>7 zm9|q|eT{iM|NOaM6BH5gAbbO7)!{5q2~u)8JjSMB>)4#6l`tqnJsC{fUw)YV++ID) zi@U`vwR_o!NV-;G%LeryH_^Z4{VR3xle4%7IjIIQ@;qq};IuK*!LL2%nqEBLk7(KI z1t+~=2SXFc&GV-%ejf;kZ>|exQwAevR#v26`E)6d2owa-&6Cdre<=}2HF+^M=N z`IspJ=^@$G+^1}gGn9zU(oIe?f%ZjDWGGwP_O=0J%+epBB3yl1+@P& zRcM7sNvC{Nr7ki`u?0-F{1eIJ=kd{cf1u{H?^Lp9Hn13-NG-V4@-nsRYiAW^ELqMo zGv5r+{)|`aLgcCA5bTki|eFwkRaGe@n!&yr)#1?5iKzqY915g;B39BKyh9?m?z+XfsRS zKdvtF**^#v+>QXM+C#-E91w%deuo<}{&Y;~$D>Ldd*0rA2`oBln})diAX_{6 z5iPqW>EOJS#qg(tbNqQJ7>!AVa@DkD8n76$>}{g+{Z~(^JHn}-7DTP=G9`|lwR!l& zXKIaw)Ss8}S?0&^kxid?B5y#21l)lOn^1)&>AI2+-yKvFroH<4KBhyt68nolc;> zb(?5pl66NPKFFykzgmLzTzk=%xo~|IWO)TC=#i1N*6*GYZ^{BM%Agb{cqG$@-a6FQ z*4mXZfXtyCEa8_%(D|AH5tXhtgF*4Kk8_O=jYr`KBm0!@3f-hw2JS0*iniJcr|i5u z8pV)tga6UMw|R84-l?WhXB7hvEd<{A##V3eyZ-G;c_l?YGSiV|R~L5FDs2cPW+Xdk z9!NT4t=Ut2@razq8*WH$_oV`+()`R!zBdmJ9*67<1YFcbJ((nB$h%$)2FJ9$oNJP3 z|4y7T`NeWDJ4tcgt)`L;z()+eVW?pN|4GmT9m%t=&%j6x|K1vs%3lhcCZ@=~q4IzG zuDyT(Ct0MRkkEk!Z}jB~Qbx{@iH6TkYR1O1RHxxeUFe!A`lC6z$U9M%(`R*B-yzHB zC&KBdzFdS7?t_vmPcV2|`#77lQMf#grx5xA@`ioq4_Ul*I`_XG%iic^wyWjO5^4QneL^($ylL zzKs(=OL#5}Xpjtv;QJX=5$8i^@!QXN`t26j_g2*cR@EX#TEP(VNP2uYIu&~kJfHnM zoIjt>A6j*Pv{*lYyf~^|?}U%FSiQTr(|19(`1M^bHN$OR{O8|%l8q9$s_;AQcv}$7 zChj(UNtR?uh5gZXF``>o9dK=-D{&D2B;lS+S=)t>Z#F)4#yg_J>O5 z+U;#wX5ow!H`7egV*&~t<0MI;qkrA<0bnEk?x569Eg4i`Rgi2;sKv5g>JTPcPcil0 zo_+Qzij1f&y|q5H!t?#vLwXemxMA*(T20+%ESAj_;mGc1q-w;ukh!27aeRjQZ$Fef z5yRU|P8}^}A|#|%9wnxz#o@pV$hP|D>MZc#fMTWF`h;FGack~Fi!EqwnLcTuSW5uy zxEzf46>_7+{MqMVf7+pjJS)xC@_}uX4IgYcxYL)6qVEhY8wBx=HEQ&qVaKwi1|-)*2pT*^BS1gZg&N?y6nK92#6oPYVL#{yHNuO)i8Qzo^JqFTfP+4`8C zJ1NC5JHRAz1{SNYlx1mF5sZELW$_l{558H0d0(*u8w1-*uhAzX>F?8goa+JIhk{e( zP}#ll2h)aXw>;x6)i^n&muG2C-&xY%CWtxWTBjMKbekk|REuxot!v1K6tn zdFi>kx?0%)?io~MtY8|jl&7;L+(&!kLzs`wS|4(wkaBkoeQ)kMPZLD{gzeiyW#Ba>?JRCuctUE2#u6x$cuj8 znEFpP8&F>>%ho#$PHK{BlwJMbV=lK#aX5SxWY+y-I}@oqB~*kB8Q4EO_Q zn#xVI{q1af4_|xcXM53hSMASNNE=_sH@~1elul{noEvLjuop3P2?SA>wn}d=1uGp; z6gW#<5hXI9W$oHukEF}Ia6)I>_`^^s;p?|qU%$;(Qu1y(6~OrVUEMS0hN+8U5_FZ5 z!gNJh4T9^2It~_h(;Ke}cne7DkvVdfDQ$Y4zPANeFg{NiIY}9i$s3bI>!{ow_hI7s zut-XXs(U)K<2}IAxL#^{UZrLkY}DH89pkt}Lkt8#**!?yRp>a_uIbAvUxPy!dj;^gM!V7U;xlri$)anqkpUpw9t?kLz|oY1Rbr(soSlKhNJ3a1Bt87n6QRSeCibHR&al&=DYRnL`gfaz7DViOV)a>1f% zE#FCIRyK~&BX15Ds!>qaWpFj|k&NR?I#=T$)3Dc^mSU075S*&$F}FzY{MgE9gFY^2 zT1}G2mS@IjQtBH$kp5A|mteE1bvHfFf7%4vs(jY0(-s^K*-Ty(=YnwA0o3AOzYh#E zo;E~9EEZc7b{ErUOv38=txZ^ys3M>n)`Fv4-+~4>H+-MW@QEm}Wb#PU4PIq@cIW^r z$^NUi9w|zu2*kL2^D16+DXHA5(th*F!OWvAHzUz*Xw|*YvGa0Y=?%pC)WB{+;JY7_ z&@I|?EYW1Y5DmPWGr8TCzse$CmAHKR-nf?NHZO=XuYi3b^`hen%t`QK&>?-^<214U zNsO}iOMM2=e0C<@e&ra@3mPkL7RQ}GFdn*;mwIZ{+(B^PN~2&wNnIKhXm5ys`|Ytf z#NOoznlClNrSbTng8`Chj%>437Fs~+-AdWa(2-#n5UZ%m$y zy0naM%GtcQq(r|s%G?7yQnjT>=#3li5!LRzP_WPPpM>zaQJ&+O|4&~aH7-0HS~8+; zI7~tC^J;3ktx5a!n=ileV2t38IVsBxoa|{Za0UB*_w15qAOobOD&X|o#bnwUex4IY zE}r%3(?sTVT;FlLbZ`M(o@Y*Gr@$5M{vJk^XRE$JiNbV_o}~7TYrQ|}GLJdD8^QUL zAkpy^e_dc_lG})Mjjk-m#{7^A3IV#wkC^`9 zzu)jwJv>u^Be88hm2vSDv}VrjXi;ORS3cihHdpZCV=R6#KuMfg2|uIvAhHo8{9=+X zP2GCw&9`YQqS|n+Jc5n>>L++*=R?!j3(ydz*=H^Hxa=k5hL~`<*~i~PM>pT@;{jvBQIi?jXNrH^3t8i0~F7R zOYOnY205}lt>;9UUjCTMKo>*dHN)WVJnGf+M3%i>PyNE_Rzu5o(F?QsV7@gz3o|8S za?nUgl(ZpZuCv1}-UaP-OUPp)avhC=Y8uPsrCaXViR1f?JL2;WD*o$By|q%52&hV1 zSREv`vzyjksw$OD=9`JT6i9OotSaGnp~efER%G=IJzSh|K6!_Ae4ThAZ^qqDSHifHBzNrSUh z{@a4_!{p7v^5nzl_s9}Pr1pTLR79bsi6$w2D z`F0?lqe@CmIP;fMzc#e%F{zi)UO{Uj1XB~lO4LO-7+V$mHgdR2iRh?+ic|iwD;(Y7 zoO}RtGBbO?$S?`V(&|fgsUi-`;kmhFMUs(XJF@iD6!a7_aaV(Ugx3<#McgSr>&**s z2}he|3pPC)h3Uk(8f*>Drc+8Z%&Ic62%H>tFUl_#bTKB<#2r1{NLW+e?(6sX=s4T| z_zUYZxBKHJd!>%+djq8-Sq%HNYWwR5_e>Mv9bE9)1)*rrdDEvV%Ye~R1)}Z!UQ(Js z4l@C|0R5>+Z^|mAT?fWa;i;BOKGM4fr|^9Y?MX`Tb-t+;^kZptPM<( zLZw;*+(~oc-NA=LUrw1@2A6pn-=3(vc%+daQxB$6Q|^A*D# zFS)bwKVT}NNysrT-)`KGjfDXVJ_btQ>0Bfs>Eh`jvuJeEMr1AMQm4Pn;^@E&rCSC zNlr|}L1`nD6&hF8l=*a%j&%8c{}=@J)#s)HPTi;XE*DIjXjwb3!iqJb*NtA54c$)n z2GQTi&e*H~Y!@YEmR#5zJMSTH-TAmVjlJ8a4U- zaL7pkwAPagyRd*i-QpYvGllP;5K<(_QJT*T!;jBb0q#6_84c?62GJW0gizpabPed1 zDO^s@2h%DE;3jv}<)a$?pPX?WMYsNqo1C_y+*deN;@)+c!-Z52d~}y1JycK+oE-$G zT@W8%$VkFb_=rLTM4**(1U>I@XPvy$b?HDKH^_n^3K_t(J>i{%u3QJtX}$bg<=yRg&&wb)3R_7?mU+L zYNfrw2$e1@QMDn7RMAL$XJDet>)=RLJ|&EDxsEUAVdUK|^^FAjObKtWfyw#73pZNj z3BopdhYe}Ey(FSxG`)LNP(lSvF-g<}ME#Z$af&ECwmQa1l-^WlW#m)g<(I@sxf}Ve z?>EjDO>MyU8-B$lwmIZ$U0(>jEf|{JNr%bSu*CR0ku%g#fox~SM!ZSUo=>sYMZ6P= z^JJ3<$W_p>gmz5NPtEF@=r=sQ-0Vu@v5(UzN8y6Ca-YEmvsox6Hq#;JT5S~1dWO53 zhbI+Np&f@$IJVnP*TMI&;Z~b;6TIt^w-rsCI%nwq2GIz}mEnw|gQIuKf)a{Oy?UR1 zG->uo>0%`=i2$_y+e`FvIVn@s!^t|G!=d&ER;G)6XQv7!z1GGaf(mF&0y{TiV=77I;;gzx3-nj{Xs`g%*Zy@8Id4a^%)qjEajW>%Px&Y0P1(XN`5^JyQ+EnmNwV%jGB zI1;eckp26bSOFTdeev&2h7bY}X9UTdRw8TT9cinEwSzKbjl zRVS$-J=|~E5kneKgcGqfXe+X}9)_^Zm<@ArHiOO*iYsiJzDxQ=k}KINR+OD@c|EL@ zV%#1h=?zsaLM%e5>ypzXIzSv`Ae`a$yIrL|O6q*q2nrT+aM&dSV0_j}Od0@%!UTKM#T zDoNmhl>c zmI)dbmM?TIER%FC`oFajj(u<*^q5)$Sl3_hN*zVeLdw6QWuj(4)^7!XQ|^2^L7@b4 zV0TDn-}MKZxjSFL> zpd`6X+h;j6)U3lOgW5v~`DZM!S^-b6Yn?YFlwP!MepHTID1&cM$yZr_9bx{ksR4Pz z+J4+q2Jxk90!=S)nOw-zHbIYx<$nL`VCxf+ywy~Ud=Kjc@g}hcs={5rd263Cpgd;+ z7JU#-(}kWZ?*oz6w`DqISzH77i4n<87n-m}6hwjxFS^B=%s5Cpzq&jet*Vk9aBK~yL8q7%n!g&38A zGfLVJJuGvzgi+UI?Edrb9ZCjlePV|4aCR$(IZ%hLWMH8dMa|}9y`)yOe}-)-uoTs^ zAj2e%e1d293+1`L2H;+@CAs0Y{ektvnY~)EZ6QI7Il~=#9RThRc!w5~3+aM2oK!6= zt8EdTg?2bGUAXEM}Prqw;-BpFaH$+*2;v9E5$Ywu%R-L2Dgqo#8 zPgb}C*arc+ApL4+HyC=806WYr9ZL(*|XjzClUeEbAm-!dm4B zDO*4amhhS|z<9r|YYm3z@RF0vSJM_NcJ0bvEW5>S?%$8PGF6~0XHxJr_bo70)?Q*J--Uj!*o$_)lfxJ)qomS`#JqWQ;4@kW&`!C%%3bVaOfGbkRRjbv;VI{|_7A8AuR-kQhA~Gn$ zCPL_WbL4xHc-Q0oJ~PSxSc}O@0PTBT_e5k+9e(|trllcfC~QSANO<5OMfD>IHt4hw zB5SJDWGR1PkZN0jxsQXmUMYcL+$x(eKo0{%FGW!&fG`!n;UmmzakQ3Krj8BDe=o%tzza<=B?Q+0&4%AE?&S5YhP$uQ?$e4wbvc_8 zR5+QKYR7xV8{FK62B?j2+9Rh3 zVxg0ccZZaBm+=D2E4_G#%7_&2nx_8*v(*EZ2BE{*#gjd zzx7(ixCD|a&A}kgTpm1ASAZRmF zaLp*7zZD$T1vbx}wpzJ1kjFWp+U`nOeeS-AU~a&mw26danl?8gE{v%t`mSe7z98fg zwBd|F1XXk+Ybp7Sk5r7FJa=h|j+t3ce8>^>4QH2=oLeK#wGhG-aY7N+H+a9l&x{%$ z$CVUFcZVemvh^s{m-E{1jRvG9zH|HU|XFx^al4 z;V(=p?MK|%mH<%i5puhY6Hm`BeeEu%RSZvEjmFXxV<}MeAzReoD>)ColJ%cfYJ&@P zEXeM5@b#6t^0UjY`(j7?q;Bd_eO>rlo2S@-tKF6)vT6#cui=M zIKTV$(z;12+A**Xl<4Cu<9VXoOF)N2?X%#^!UWJUvsI~3M;3((Lp<&%G?k*Eh&Y?N z7~)~3#W^=w5JyGgvf)&AK&%~;APnfQh*H%|aMoPi3(C8lIE>%1ln+M-MvYv{D&I0r zB?t;73#4B5_D1E38yrzz=qfBdw6;$`oP+F*hMSd%X&AHEZ2Ba(sP#K;1IzMRc-eh3 zm*Y`mY+JXkd9peR3hF?<-PRq9?K%QI;n@1>Jjj@UzXuS<@e#e(Vpa%e-4TInS2;HF zO%q$bBrP#XQ32v{N;)qSXRbSKCcif7ez6eb5nd)DK+YTy$ih2XHW~!!;n{1 zkJ&P~M|qC0$W6oCTIo65S?S65xQKSR_mT#UO>D>Xz0jQQ+deX)9GY{pJ=lDo?~A2~ zYz(F&+br=Y3O}*=F(vVY0!aHQTl<)~y7rg^+Jx>lk{sZl+yeiK`MXIPesKbq$ls2e zNFxm+XD=E6*k6_y+0zyh8;t=t-Xge}#_cHXA*s=I{LSf(@g*rC36iPu`2!{@l-}Fr zLZuS9L4J$A!!+Ryh${U2NP1>3r(~C`-Nan`WjC$aBZwUB0p!Sapz{;Y65pN+RkKV~A+Ov+3T`6^zdU-z$hXOT4@r z+Xk4|l8bO%>2=dSd)%2&YU8X@bB7tSg?CtFTW3MS z+gWElnieSPg?j}db<7ZBLLxj_K{Ys+jeYXc_b>92y_Gjzm*2Tx!Ad;6h93qtd2 zj$IrtiJYPq%rI44voLj%Hs6w+Z?X5d0p#X$+ap_q_`vS(pru!Mvqm*R{JPA+X>mQl zabD%NSGD4>9s>|spkUcX)V}e?tVjZ7i1oP$sF(wyyU<_BZY$a9zrqgB{GqAxJL5A= z@w`T=TF@jl^t;Pdgw8gjyOG4}qY`$e=ZukOhpZ48MJH@-s-YYLl({ZI)`Gvue@A3H zyhy)>GG=vhU>a)-d}58qu31&cxlJD$xE{;RxaanlHDqzA_4Ayb!=OmLl4jK75Lgrt zvHgryz^*AJ<7g4oYNPS4V?(gMNpFJK4b>(7_LwClZf`sKByj3|aGU)Ke`Fv0ah@-4 zTs7Z<-&dg~vDjKN?C zW_-*D>v!9qmtwh9SS)~B4 z-uEXpTJ{1yw+f#VRk^RHM84_e^Y}8IG>!tDE^4oaOFdZ+ZFH~b2*%#YY-BG}UOZcQ zEq;B9?S|Dd_HAW*_s-E3wre^5JWS#O8~!9+c2NalBsq0xYT1TJn$PF)7~dbFo8gSf z`xyn(Z4U|I-jeWP=MWPOlcKSaxu_@-6o=CR{JUsK zBy@IrX4P#me$_1{e)Ur1)@neRXb|MZ#n&5O!IU2;0K!1T6^GOAu=IBxuh5Q@&fhdj zq&wahT1s6qQTckiJ&f98)|hf*o;Okcb(y`X<78?uhy9T_2npbJH}q;QR;rw@Mc>~( zdo#5M^W2tM#2oZOfvuxP*d|I8f-G2IQ9JEop_8u>?P&DfaL-+0&xqf6(W|sQGh2r= zlP($1wM31I5=KR*L5HO#MP2!$+u;Prwnm3x^~&j&kS0h#It7QjNGmsyO+?Jfy2)eRFR=G@GKeChpgi*C?+ zDmhhT7~6%I2D3&r`8mAi5bbOEWjhKX4~()}#C4-BW@IdUlFr>Ne_h@p5Yl6d+Wf;b zDR=2GTFNrZYHLgUE%7+IJ7B;1SrfRqdkG9Ln44Gj{jL3)tl*ogMX_BX7CN&w`K|AZ zOTLj5ymsF-sB~GEV>)uyowi#Pn#zXu0^yK_VD9imozMEqlBAzPc&{^klkkxOrqw%# z^dLsZR_}&M!3T9+v-0z*@|`Xf&Tfwy1*?-4i0$=E)-w#fENyad;JtU&I{wA|mo!BM z^r5HH8`CV6|G2?y;sA6PfQf!k#Wf-2s}m+}c>58Y+mf7mZ&Hz+)z+K@sc-&t=xjeW z|H|7(U2ja4Z|?!SRo@E>Ie{5fi{wv5U;qLgBj~oev`?I;N=cnj`N4r{r5CcRfI>?` z#m9Xm9|1W{IlA*|_W`-i5nvS*<#z_3Nj$*pI)m_26xD~LD$_6JRMpzeMUOg`exu)W z-$dMAj61f=M7efDN1O*fm2n29qJs2LB23W>5!s~`*nH94Y z+k&=znu9~+_Cx9Sb1$S7-#dJ@EG2})A?9UXIUk^g_9q6z_(V@5!Y%LTE4rIeXTLh* za^f{G!#mfN+nL!9XUa&pK2%cS81!(`vRBG|n9JZM_rU^UL}FnS*|u?^rn;*L?sv89 zbK)0SKUBY%alQ zp$PI`f`70uU1QW9Rnfh84?L?oJ^cl#lK$i9v#$bu=#K4`KgSP&U->X3a3jvBBfGW= zBh1Y*4}|(XD<^xmt)|gzag}e=k#+c*nW$iSAPFe$HQZB;Z=W~(VHu&^A3$6*0Z*g&#lGnM=qc{DqkS0 z?bW1?=DHA62x?o4c z!C!ZGFTyBMm+G6``wgziPk;d;F^HVQSi_Jb$UE(xC) z`GCAZhMRjS6)E|~Tw_*PzsTPgkeX-_usgb$&ysc$SJ9s-W`vFI0BXW%M%@00SIhmvQ+lBZ?v57K16IlDGG=Qk>%ul<*+2BYt3F zE#EvF8>keIP#>xMXb?>som1k@F;NuZ`c<9z$uY;Qv^_QT(Gf^l11hGX+Zs)YLk#Gr z8=odo9_oHpX_ofmv{4s_o=I;@)}Qb(YF!+BuX3hPkUv@Ps5cD?95(kNUepQ)jWcyY zDf2Q5nIt$3I;WX37&MSRT6#S(LSsXHhzJ2}2_b27L9)6=&_8pzF#uV@TU}mWK9XL{ z2xGeyFr3zV0kj`$D&}*xFKoijoYKc7%H}E*rGSod#$(eN*y%no;v(R9Nw?FTQ(x#7t9tB1cSO~HFY_frb?WgZ+X6^Q z<^Z)2MAsCVs49$QhrGPBqFVy-T3#_(CA8@k^3M&ZE1jSMq{Jud<`s_I3QD%H7u%kT zc^}xfB4;*i`2`kRl?7)qG`Yw}hT77LlB2B$`wog1cu|H63T520n6%|BQy--Y4Dz3p z8?~I-?kt4iRp)*AKCSTHw(CNjVdb2b%D(Mib$3_C} zJb2ekAhf89LX}DrQD2(jDckYp>L-U+9bBHEwy~)_T`;Y3Xg&!A*(8M+9 z&Uep=UOik9o}kqEGUW2}j`8|V%-NF=7k)x1qzOdGMqP=!j>~-1C`-|0o_Hqwb@E=a zrE~NWG}~cY^G{}@0RTr6Oy^!mCK37l#A8l=?^xSn?eD%?3EsJSIlKOMqSI9mi1|&# z&@zcEZXL*H;XuG(tjfY2mLosD^vDfL_ExC+O9swv^E%O>#5Uyt$=vo5-#@Hyo@73*1jvl65==U^8R8! zLafomDMQAvyEU6Ev=GtZa9~3?kj6*kRXpS6ju76&9G7~>d7L%%%J<{=D_NSzl?JN%?!<>2z(whZ-tI7ZgWT!xq}fP8UbRae4Iexv0$ z(d4&7uLc-fCdGn}pf5LNvB_KwY}TGT1QZ#bk{r3v8Hy5f)o`lFNLE1-s1*DIr0dmP z&{CSEsr|Tsf6UgC6ls%ol=4CTzUWvEI7jNJB-%b8{EL50|DnA8ty&fz)`tM0fyx4Q5W430W8^~Qa`x_CqYOd(v z(40vC)48WG09tQ0FHL?V>>o)jalp)_`nTE-BM>14(t90SYehj)xDP2o&0yy0)uLca ze}8k3|7~;SD+mv)xtsqc?f_`!hwSMuw!@}czFF!qQpf36(YmHRth{-o)lOu> zGybA7R_B#)qNn|^9`*luo~ZPmdB#l!bDhvshscXLUoe$cv;r?8DJ|<;F-$E}H#HqgsXAFJ^)9=CuN*i$_c9oEuJhZ`2Wv<=h;u^tbXi z*$cD!N*Uj7j4xD`Jy6F`v1FLM&#oweDWxiq6isEn zZiHrGnTo|$q2${%L7MD%8%~x!1f^{r&rBb;(E!q$J57pTgY5K$XW>ZnwTmAM6caf; z7oHCs;q$8HX&x4(Hwm39KGl5W;ge;t^(~XHITf>OhY{iqx=o98Sq_n00<0M)Gv5p2 zX6}@yD(P!C4Hj$|>5s@v7@c{|JIE~a@`>Al%-n!aw-W~V~9 z*crV5RzIH3>^!KXxkKSgvuu^f>$&?i(4psoh-0BJGJowyp^yxLVz%`b$aHk ztzV4`_VlKGlHsh6ggM#WW<@O5W{Dh{IuK|_sh%FNb5oV=p)lfNl{3xAmA}~W1_xaa z;tRi0`@Ehqx9`pC`Q8hwT{W+|I_f2<)G8bZ_zVm)CcYDb!FkZZSF^yZWs~0*f9CAv zh1Yh1hhxNjwidIm_2R_+KkXBD!nBqX-ANUM9;fIEmA>SZ?Poj}A zRSCwB(#3Ar5(E`Ky{=OCk#CRba+}VGS!3WmO1AW++*{wm^G;rxHE-f{zL=n`dL*T3 zl&HQ>m11b!K?_ZqTlrbx6aC5E!T)C@haCB}Kqt63uy>>0^V)s)nz;aKT#a(2vL3Jo zK@guPgBp>E)dhy(BQmsw1-Rx-cS!~|dxS3Ugf8lhI$;Xra zYu3TQWcl`$0~@JWUfPT)_P)nl(c1TYzMdmB7ql;5=e^_hkWY}>PXHzgBx8vyErm;HGNMY+h_M5->df!am3)fL{Skon&8J) z6C83XGnS=X!U=D@#roy8LVT_+?<)p#V2~LR#o6g0nT-^^-2WiC3*}h`QUJU zr=e10xb}_9JaZwAA(>l7sm|f)U3VNOH%p?y#PX zysEKKZW#P(ic7xv72j*`XD`=~t(fXN_c$yuMmmsP(x^cfp<-N{fC$N7{MzgSo~t2! z5-*r7xg>XwHF9T_z%~P*SsH9~9dYy+U(7ejgiUlusvyK;UiRLQj7JPt-1))9S;}gi zM9H@1WZ#+3^(h@O$b#8`9KxsWRrf)6EZ@>s$+Sppvht6#oSzIfaMoB%?ryDew`3cQ zs+m|tKWrNHvN9?q8QOr4c&qPV@a=o}K@+J;=PQ?-#jWe!$X=xUO56T+V$sm*DN_t* zd!|Bt`V}+pFQl&mP51ooChp=5V22Sme>(g6EUEW?HkC9Wp$J2N@-p|L;knd`OAIZPU%A z`Eb&4Kid-d`S<1FYSY%B!I;fg-9R;VOgARBHD}_h!RTC<@M0?%!jZXT`E2V(&R`;ysM(IxX`OsB4YIozagBng!^EvY9@&KlZdSpVp z*2mk=UzoJyr7|!xB}lr2T6kV?fifcf?}Xh7f`?_{%D6kJt&%`}*Kv%Y$}nAKo1Vfb^s z=r(nz&*;$Jt1O|QGW4Fwh)d!C#=ro2zt0z%FJE$wEJkey*9^;%-{>jVA&X(BjzFAk zLA0hj0rE?v1w7zeGA7aX(zTSe>Ga69Z)~;P5_4u zh({s0wg8hZTC?SbQw0;>Ap23V1U{vHVQp;aYhrwAmh)_DpEVhg{PLJG60H6g)8}6!4KrEEU(q+LKY(QK`Wz2@bmgBuwoLc}q}|MI*xTTl%)J#xyzHj8RR4r3MAJ zgH~Di&bG+rq62)>O^zMVU{Gprcv584r4(_9nHwE)eyt**6*#{FC^%!{`yI=KQN|Vr z51qd=1stFrUENT^1avRw`R%B2%Ibkoh5@IXs`(`;_vRWx-v_m9do4=il9P!R0c<1N z9>O`j`D?iT5|hEEr~}8OTaVJXODOV4{WqEYC;!W4FW4S<`Z2%@VM?X<4tWELUK6Z< zWKR?BnwYj0Ct^NGJlNOK%VPN|w2B~M;WbKyoh#~2v(!svgwP%2&^5N$*Y=3Tx9wTI zY+E_Bm`)6rstdvdnelSpQZ=|^JDyRp*?pZ%?rS+l_diEQNw$rsJHWQ#1D^d(_*FOM zxwT}?c||tOjh{dcwx5cBJOXURgWu&aL0wN8bT_3RTL@8j# z{hp8j?&xmtz)ykhy#ifKOi+VY6c|=#mZvAiR`WI9W8&z+-$1H_7!nk>Bbq50q}pP{}}=s z<>Q+`G(~|3uifAxE)ZN)%H$5O1!(mGaxdW}&({nCpoAEEy1L%LpJEH3u;=_eIQB{K z*@K#*7Ku&4$;W~rRSM8j{o-bCgV>)u;8e!-1UJ3+eZU(A9&}2-L$qbV{=q&mgKE+s znWKY>b-0Eg+zeT4iZ<9kYoBAIMOO4B)Jy(Jp+mnUiui>8<$gs0(p@GEVgs1MJ2rJi z81U?R<*>A_AtIc_W9}(2dQ(0bW>C`V$TJb0V{-xd^uK31k<0|Yp*w(=;KfZ}j^wla z+O44~%UTLWE5l_08&0be2*T&@bt&6+&ndDmnNSR*K+pB}ZDhUAlI_^uH`E#edv|2H zpWf;t)GCD`LBU!$->fKR$lo(^-4)E_{;yb2l9xff7|5Ioz^u9xqY_H~>Z33qT^eiN z9Ls}%2#Z06k>#;^5K-FEyp;q})@`jz@0|0OTszu%%Q&T1n7F(pScy$xJuBg{+-wCz zQ4k9g@+}h>Z3>j$4Zqg#70_!WYK@oP%6a3CZy9GoN`&BzP=!aC=5$9Aw0&vrBlsg~ z=Z)NsZ+_621X9E5;37b)y*Hu# zR_Qj|bvFb0_cw>n;|-?Y_0+5hhZ+Okn5h#4tLBN1#+4?q2qF&;!5_~*oXU2ONDx@s ztdld7Ju^Ij8@~Ja`S$4Y<=NELt`|&&*Bj(^_FvZ?Qo73j85@^CQn`8hf$ThtyEH#sGQ&e55{n!OrttxrKS3LHDuMDfq1J&zJbDcMp=S$8NmZKm(s)Zh(?q zvPhK_4VtpHlJ#5&^H+}8_iOCTU%qDAE&je6_9|6g+5aDHZypZy{=bh8DTydTQB=0F z7b1HJ*-0VW6cx%=_H9NaC)*@TWgFQgq3qjG;gsxawy}?~@5_vt`96p0UGKAX-oMZ9 zT<5yZADwfZdA(lG=VQ4a_v5}zC=nz(w@>g~CNtuQLMS5ywb_YmjjB?}q1GMd)L-f% z4gc;9KvP-{?}$#ht_Xe^`ouMAhVJF~ z-F5L^Ju`swo`UwrSHdD-GYLlQ0bvXjTzqO8`jNAGc?f7ltx-DX7B1 zPT4P+7@p&~V=)=1b`xxkFIUX@G8$w~_{+E54h7?oq2Vz0{;v=N1NY zz|W7Hv5RCi?G3$KudjSL`~fYJ)?+Nn@cfAX=&g0y&~0znAC*EtF#EaYYHPayk@X}I zoM#Y~%7&FIB%3h>UT5Yi1tL=q?y}cQ>#pF{<(V9x1|vXfR@t7s{KrqXxjOrJF7)jcIr zv;9shQx;u(^_d}P$4ut6i%TgEnMM-aC)jGsJ|)Uf^Xj)mf7to{_v!9De?G~m&6 z&VLus71-8KAu5%BzLQhIviWw;$2uqo&le}P=hEMN*=Q$bj<-*D;#_7QgS{3MO2{SF zOa-r#PIOZ}lMZ_5Zpl&iANBINu29Uo@inG@E_`ogvs5ic&-`tZ7|$KUaJ!KV5m}(a z*|rCesyX<~m0e(`jodbXKwIW^C!oxIx}hn37%Hb-<0f}uuOYDwN-;mlNjllT8KIEs z0AzwnpFhROlB%li(}(A-A82|08Q`udd1pTN=3wM zQF@H<%&S-F_f+NZYb~k%)cRnsg(IJ4z>orV4a4&2qzFhqu)3g|P>FBSLw5kz5j8Gz z)bC9r(Zs%C=$l34w;IgW)Nl!}w_hR+(m5lXcq?r8W7X_&N#Uh7fpOe%&HgdZN`!J=7rDwb!l@FKk*Yx}G7aHd`(E&avErB$?@M29Ng?ks>QMX5Fx{bKZ4B!T32hb3SH@ z`H8-go>?s9Z)<^9Ob}GbU9R+!jSfTbf3A{;>smJ45!p@aod&ioIJY+MP^N&3)d!4l z7A`36)VOQkUJ^G_hmgsYWj681ey-#@gz<4Y(0#9C`D?5pd$wJoO(cXw< zESs4nzDqRi&i8!@wwN?UT}&4J4cTn9Yxw*aYCnCs_X#D5u;+~GzCyR3iiY9!;#ij= zSL{+t|=M)6?=Bo+CX$NLqTBQ*7xqAAmOn;G5~r zGri~+v2bG%!YN52E+;cBvC1R+GF25rv{0MtKP9jt$T~HT`APc$P1<8a8gI221tF7L zqO!dGb2t~Pejlfm+q+fwcmO-=!+fwx|6uLD&1IpD;V*P3)ch)5QVMS59Z7qo zecYL{q|K#j1&7Dpn~|lo%#m}ZCnXR)B66{#R}A*2EXWd;+x`$U!eN1M_$h9R9z_~M zB>bu>D<$d1Yg3e3S7p%n{3z$C9Ur!y0mGZ+9;+gR1XNQZxzNC zmrRt#-j?b0dO6UVdx%tJH)L$+&tzug`-PeACYrv>eDS1i1bRi3KV2h(2j%ug_VQtO zRjPBBXuy$2Uf%ntdkyRU@&RMk@m}nt(`!U4mt)IelI4sKz*&gJbNx2n$!Am{9 zv#NqmxH-4R>%De6_A%@{Be?ZXW;TeWE_(0!U%XJVnbps>uJRYLNmWS0C(C7$n0#!U zvR0RC;@tv*;c$GBGxk1p#;xw$+%9cpNMDgxQK6T#@87~WoFZ(>P#;f#>@(-u11*W7vka|-l%;fsy!(?&$hW&vwcc!kc&C>M15_yBP<~X)g zE*7;qz<~qe&|&6l`ct7@=Ewm2MD;lb{n)(NpWaO7sC1ES(PHXTn|Tovy)_oIqz4L; za-362Z=sx;swyG$Uc}7%JFxA8)z=XvY6cM5Gd`t-Zl!oD^^G+*&Y8XHLcNq2-0oSbF3uBW=zcGt18l9!^*{ z!qUhdTksH|koj7b;fkATxc#6z75l9oslNH~r2*+En(ddiIsg6-FO7*X`w^<6Fk2W6 zYxOzO|0OxWT&%G9nX*jML0P8?@Ey3#IZxMbW5_L2FmlofMWq;6 z$C1{Lke$f2njFo~z1hB-Jm!gX#*S{s>SwknH>i6dY({PqG6S231p>Zam%7y%kkNO2 zUHG}SS={vT!$^CkKKVO~&OE)nopyEtdCat>DJY4JEb67_F?gT)JpN&6Y3X3{MPYD# z|6@)1haS8z!GqTtF;GEd^>0vwpB>kcDDMTInf z8*8>V{u_QmFaSKTQry&a1K_J+Afs-()IQe40MY0Gpig-5GHf9j`e1c05H8!&@%!BLh;C@+xXFa+3Q_|mW1}4o1Dh|F3${FHKK1& zRlUD?6C{7CzfJyM{o{Ya0m#+UL^_~10%Xb;$oZa*XAv?6iFhA3KY1`~jh=6mnFFF% z_dw6{H`vhy&q@g=db#Bu(b8n4M_iA=5_R2wRV;=59}xlY<$l6hfjVw{B2s>f@j-chAJs?azM>6p5@F3B zaeViasYBAv*4AiI>*mCNJhI7CnJ~nJtfL^Ii`~JdMq#{Bxc($5fb!*G(enahUykkv zgW2Jl>x7E`gU=5(qU1YREr0}a)LEx-a8MO+Er=~O&A)|ZZ#3yKrL~Flgm&zKe+Da{ z$;dThHT`;i@;aci#pi?B&#e4`@EXGolv9}kqU#?aR{*qz{DioY0Ybv^RxD)Qw{`i4 zgGC;4bMkB+-R+lQJ5YW$-$D1Vth;FO&X4~wF#k3V1VP{rm#fbShP~wZ>b*7j#2Vl% zXD17v>^k6(1TB-In!Sw?yEW3b?9M!R{1u;Cei^etXA`m(La@-krZwIm--lITPF-rlAUaF#_CHwwNTlK##8ESI!_N3Ub z5bkPOrtuJB!v-_9JmJfn@2(WJ>e6?(yQHmzADZ&Y%1;}zd2PXB25&|Ae{jh@)z>Te zA%@ztTr1+tVJ1EUaxf|iQ+g^) ztPUNODzfxKP!8Vd=YuQ|gwFHx)RMN%l~!qgUmSd0S^jD0MJ_LKSkM!mOA$E=^tUxt zKQfXn0$3Qm$t?UnzoWa)H(nvdoUvo;Q9W^N9;ChM?2Bjq8uR21LoZ&Ln!wI7O@z_& z7-JD7Z>RQ5E*YG?VldNEseODp=T!<950Bn?=$jK84(R3=&Ka*X@$%2fUg3WW7z2Hi zTYsA;xNm?%a;yXcTqDEGth62XNcM!qiA6j*pdOB4N> zE-os?l0VqU|4NeMzAz(#A`#{SM-#}xv_&9;!wr9*#0tAQe9RJL$BpQk2B`1ZuNy{FlveBxInepw$E zWS}ocAqmeE5S8nLqW#70;r6hN)C9ol$^vVD-W|fyvanYmO?;gS{CAEbpZ24SfMtBS zXjdN!u5d)w{V_eKye6mj{Cy`2vd83)HZ4FhNB`J5-uGmg>kL^9$#)diP?`hSzMRu2 zY3{dbNgcUYK!1^ER7y~i_QJAtm}hG|3x>j!*;hN8?~F*^hKjLdE{ly}d^*np^_;NT z73Vlzjwe-p%LztXDvxJ2^uMYrRm`S$vgcIXs_1O#ujss#H8l2u$urOB&5cLoJ{V~7 zPlDd(zH=D5r{E4Y6{e3R$L;Op*zVeWe9N`U<-nF$9(L++^*7%t14Ba@Qu5?=~ru5!v>$8fW|B6a5@;}_-Nf4`|1>g zKx#u?C7f3CDi>!0l+!~20Rd#Z2e@m6XMzz9(*tTcvJV;f`|$^G*0sWCI#ZN zPAVduHk(9{3f*v!oZ~$K6X1n3Lrl=2q3;N zK&Rl{&2Vt*AcC{_2sqFHUU?mGQ2ydcJNU(cGwm(Zl(v6ht!jwDX0-cJJN)8x&0VZv zNk_`o9ws=Aw@SpkSxsDBap7)jVkzF4y9P8YbMQkfRnMze*BeaAgE*#7D+z3tl%&^P ziYd2_Se0FW5B#3Mum>; z03#uCx0D0U*;pDb&#aT6$wkdT-@95CFQe2X2QARRbC8>eEtT<~tMWfSqLft|HCf?P zbx>vjuVd3*tahy0;a&S7=fw!IW7Rq@h$eE43Syp{H*o8pF^z>f@~Gk60i|n?sD4bj z)wSy@2jvi7OLk!L(ZpbO9*EiJ=d>LBm(R+_(wNQ;HN8hwIWmXhEL}uCffzG^9lVf>hdrGl=^3|r)?57{#CKa3pFL#U5V(U+FAYmA4Q8j`_{-0bMh&j~;A zFQ1PS5Ew%>R-T|2189{j(C>yVN@1DibRidL;Od)}dX8(I*^MJENcd|Xa-Jl6iT^il zK@K}VxIw=GMvsOw`ilb#`staD%TlV7?50vdtB0iyFcRCFY~|3}5g4=qH8| zrXw7F4Ve)7#)cs&c+F8Bxe_(*^R`oRNvlb-cS*aceCbvi`Z)*2X~3qp(%S2OMn8XH zVNySTfBu=EAa{RXQ%dfAvs9yu&5o!CGBjO|3`ZFig(*JJC;Fbb)|!3d=x+Yo&N#EF zjoZi@tXI-qwd3_MnNA5WH%WI0(NA7VZ*+Z;QN1^b85nx}X~U!f#w2(7vFT=+5d36l z!rK9Nx}1xgTlO0BzA#zGM%68S2YsB&{*llA%dl3=3tsj*07o6)2O$g(qHv{8$fV(wR?J)lE1{=!tUme8wVNI#D-t}6F_qL*iV1_n zLX;w8lm_=46rVh;e4x`NmkL|{x9b;473c4vY?&Z+!U~EQ`Hj{mYv%oVGTIX|BrI!Z z7h1vX5$~DoNl8OH*3GLUuGL;>sSEE_LJLx=4>_?k2V#URc2@24g-jq40hNl5S_A_O zQ6466oI=`9>)9V5iUZz_njGJ&iymcArq;SGI|SK8PKLOpuXax`vky{BM=Oxa9vL5N z?>>Y)1AcpO_nD`80+0ldsw&nJ3dZL0A2Hd~){C@l=%)*2&IL2bC%zANnpbI2EOi{s z&VUqqG{j^;j83`PM?lu|7QDz0JL`Z4N9A(5HWk2qB1N@(il}427dg zN38S0rI8@m5{pRa9$)ocm!V6a7W7&3D6drk8C2C~Fj;@--@CLnyu9a=&-E92>usiJ zr=2bb-$a^w*dZ4V!XC>vwgMZZK?;KVU>sr}WbAlF`tsEA+UL|@v#m)<>r9v!Rn-Mx zW%T|IO4E!&*RDUSrc&xSoFx6$N;1A@agWc!5OqsVR`z|?#u#R12-FNUfRiqSXgfH< zd!a`mi&TWqKuenu%e4Dz7Ul-?QSTIz`LPmcA&qY=dOewEHeQ}YqZK3H`-IfKilRo8 zM;u+_8R<)hww7_i{Fos-c2OoO_>l#@4nK)UDc5(k^lvPMzJm%Dt(j=QeVXoYI0dm~ zf#9yFz#)bC+JX^Ef4e(=4y?s5=|+T(fEH~3ZeQYjj|kV!ssP%Fh$6IoB!ml&zSO&J zOe%N0Ur8K|s6Ty;4(~dhnD;)=WD)%V7$V9qdakU9$Zs~U%aI>ut%$Ib@~BR8)8XB| z!r}7ww+oA{OJ1vrn`3^0zZnZD#!Li8m#@_^G`0rwh?sy?=5*X!9IkB6=i*qsVN1qc zrtG?hA>J)Li-ta03U$M+hR%ZwR;D?`bYIBt01<>!k)=PR#NCKz?7pbz(4Q3h1k20E zR)p-*z8W>}Y5#8?mT70zxD=r$ObR=K4@?>N5@!yUc^-F`L!K zBYEZv zm2RQvIx4Ul3yu)i1gOW}S348;@Cv4}dquJbD1`RRu3=j=Yz!Nw?&fH*{+k=7MLC$x zr(-Mt;ean`u_@fU;amo77+n~_HgrKzf;1{Xw92y-f4#)T}}tbImOZM(2@? zc=H752$su&h)-}X^TRrA_2X@ui#I#ZR4WD7UEon%iR)lLqsmj|rUO6EC9ukldJ0Ut zWxroJrRj}WDJvdA`I>3+JZn8+$J6FFdwZF}qO||bw_`Vicw4T`Qf=rgEIvDR+3d>A zY`P4dDiL6JR%E5EBgOK|!7(b=iWL&op01mOPRo{=7-^~u*#iq=XfjLrvc#$i9;dX6 zq4K6&ngPYDZerMi*O&W09>feMNw1-MxCUPjl`kUEy^BvhIQf8PnfQpQ@j_5I>aDtI8|%dCH^ z@zEY1R$(9IGK9Bcn`F6KosNV&bOA4kP=@Nux>6pI(R1)2WaE}<=WbF{9%TTzbU#_= zwEFbD$xEfF7>nfj^pZ-<9$dp9PrgT;`N%213pgoDjz!b_UyZ0QO|1%6SkBIH!4SOzi_QB|FK z|FC6XrZ+nWzOvvUE$wpeSDz0A!mUVQqw~>AeYlNsuqV_cDG6PuG^dJGa6h-#$C2nX zHI?27(`4e)DN4vOpzFie9-ErFeWkj4uI2DPh{yM|{IEu#vrUe`!WMusnw>;FxFzz` z$vhPyHhzrZpcVY$T>8*Ir7l}W$V_|KVSBr|teaILBBqIpXPuI=ATQxXqgB6;I5frV zUo!?5xSC)G2S=Z2Sq!WMXr$->Jaj9-%9idf6WxU=o48my(5FBZwm z>AJlHdAZv(GcP^*-9vK2vXB!|+Te-#3G_xQ4gmETnJDv*#6 zf14l48^)offoVdh`?4aAgubTCAZ{$Y@NcO*1EistAs8*BHWI0TV1~3E>_e{t>W%C< z1*fBs(hE2$FuL11nU4Tm$B9K5UYvbuM>!Z=Z=U{^6_x*?LN2GPwR!kdbhD)EFt_Jg zMeWRe<~ri?scf{NRrYK;iUse@L&<+k*M|@~Vik(6r~e^CZ*;%8NgH}djF+Ei!{L)e z+aG7h!c4NCHd8AhbhZlZoU*~Dv5n-V9Q{{eb9#^OB**M*|5oWS?saz23zHeamz;zS zC>qEI>YJqYERvb5PY>g+0!Z=oG4-h_s9CY1YPxn9xn=b5!}k&?!SS820zdWXMWo{P zsoeq$N4N-Udp;800N^cdbDl|~4?mbpyWARi=x!DSws|%Au(hh3q$?hMGpkcV-W4lg ztiSYn0pI;Yj!T5E&Y^XH5Wdbnk_EQ8q^zJnhmq8N)?g7iJo_T{gFPt=6w3eN9DD3k zvAphN33W%%khK(RBwT6Tt?PWzxl&}7(=x0S@PFJjA`8cf5#+~FL6NTL>0HTv`^ z(Tx?jrfF?!8cDv|*L+&;P6RF$%26OggiJ)qN(BSE8aq zdvRyvUhBdQpj}P+8QH!oBdlQ@YU{uH1@$0tMjKw9q`uUQ!6MK1w={@ten>{jsCh}0 z_wyAUq1}^pg>wU}J~J=e6p}dF3fWPJAM38P+J}4Dtv~#>Uu8%n8mN-DjyJ?6=Xl+F zmqkOFcs^8ldLb1YS`(b?DCNjB1C}8Ek8Ru|%E2;?r_F|(lIp-kdwG9U({mrf2)%HfyQP&0okCFUh&lwKm&J&1)rXM0HW2JZOy|>X4u8tW zhG6)$bZN3vG2jWrt;u-GX3ZBlG11}-ZE9(uOED66GE!0=fPEBYpy&j& zK+n_wv6~d+*E%(jMqoMr5lM!&q2E1DA2Fo(wTF$}si>tkHiunNh-%nelERFQwMcZCDgljo(zB|)l6{ImXi%(DzW<^Ee5;fdHSNrS z>HrZMh#4T^(S#Z~TcM!(km7En=$p7^1oc=kK+OnepF2%M45?18iKa5W$m(C#5OCYB7v zt-Sm;(@VT2c#TUlYu9m!-;kE;H9^eI^+HA5ziIQfFZI3t@G)R{X}f}bpPZlHF102> zb`cY5M+NfKNFO7Vo&X(4%39byO$)h?-}}SvT6`R>|WT>2>Qg4{fh^YQ38gwG+OpF_e`z{@ z?!?XIJ%gER*6pFib}55D;sU_Ye}jHtiw@|V{7Ui$FBP0X0OAsNmm;Ys=2yC)=@njU z#^>X4>Bje)mSsiU3D=5Vz6=Tq4i0?-6?`AaV6{JZ8l#iF?AG9}%|##do;h#|C2gBl=} zTa_st#|rvHn`x0H&SRrS1a@8a)fhgA=GK;?77+p-5*R7x8BmKK;bPXr zILvhVELZ*BK(h!HjOVMoEhn<-g8k4WMSXu6hTTU;uMC5QT{dX#T^es$IH^BzL+w$x z+pVUwWR0h-FB)P)>mDgjdU&r71;#SR^vwe^6m~>Ca30Lq>YV&jOG{&3myENG$QHHr zHP!o4>0tWxrh_I6fGW+FiU}v_8>Jp|& z@)PW%ZjOGATiML(SO!;CK_f-5a3{J49z*uR3^^nglC!4dgwe5E!H+&LWcr{W<3DcC zaKq$U&d6c$R{UL>T_|)BV&LVglo9=OwwtIF&1Z_L_4U}n)tTB64OxUbv19nsOUgux zh8T(35vSwe9u zw{7DJsSGmg?k`!{CJV__IBZO^6pb8a0nfR6m#V>QaSfl7_iU>vr4MeDU7KEe?9QQ~ zp^-fNgp(qddoe+)4s!uSKF80hVA=MX2XO-vy3~8YNkIfnm~{)Sqi1XMct#KK+&|3< zV8rl0gc0lkNXH28eMB(O=sk$adAD3WTWHrSc<6U-e9a{zql;Mv*+E`HlJ<>A);@6R%{{U6^>Gs;Bcn@!v^ciZ|_6IK~q zt(p?Fn&k1XKoR0R(-Q@K@lrejXh!Y|wy~ECY-`fcC51Zq zIdP=z_&<%LoJA1#!72(6X`btKYOqe?Gw0ZQmEgHq90Dg!fQy!wftmgCp0AOID~dt0 z!<`4zK}#UUh+EIPqI-9ww~Ad%S<_G!l`=NBk6dZ3S-`eoI|}a9#McFK!ld|xHugi{ zOR?yKh^9v%l&Ia5KSK>pUkPq93!J_OZB6x`q69+g7#RQW4__bUwdO^niVwP*19+B4 zK7DExNw5Iy)e~2)T&bxzv-{FU)#VotDu zjUfiO_5WcIfePXvqyVK?+&r0Xu1s52&(6X&f zmd%7>D#e1J1hr4Jj0G`hz;&~tfvFS4Xna9Ym1fhHR#Wj*^dflf@n;4l^>24)=nCw3 zY3GN@z5|=GY)rr^dMXt8RmZYRvekh12im-BMe9k{UAI%;+<9G6t7olVi-2!h0%FV4 zpT24a!+9;IK5~RaZH|fjQ-nOX$2WEluI3Gc!bpL{oAy0j>cDjnm+e|0v|5}hi1-!RmntCy*!6uw)b;e1Rp`5dx z2oqabZQwCZ$AQJ1nt&aq9DH-LKE%Sj^tr6Z>6O`j8302`1Eq032+M&3M!h?F(Mr!! z7Vl@8w69j)w&mnlQuiCh>?|;IYzYY!&-8vv@=w-?=HBgbj!6K* zuPOKbyd5S!2-2McRTx=lC1;MI1Loujsm<%&Q-t!!-MEtRzq#G44o}@^{&#? zYjQ5$dHlHh=1wQDI(hfTK1~E>oO^;q>M$s5ipl|IwMx6X+7TI7P=4|r!Uu-R!_(?6 z0qNAxeCGw@m!_5X&)E0b`q+KxX%J7cW$KsAziV4@&xz#10zAx5l}26;e?n;`)O+KI z%ql+coOB}>-|d|;0oYT@E0Z018^W5dYcqFVkjn22$XcRvbuH%5Bm!EsChbN>wzgK? zU5ocPt$Yitr*Ym5IlI0=J9`b#yxv%9p#=)ZMMTvXMgV2D^nPuUf>fm;+yZGCP&-NX zacgWVZyE7Rmo8tvA!}gtCw1JM#~@J!<{{G2w?<1VR z=J*-d@=$F_*DL_Ki>I*ZNq*0v=C@Ud>~c49!M{`UaG)Zjjy9+RL2M+y)|X}SR@WIJ zYdZ0^ z1`t6u`G*N?^-f{OzFm40<>0HUZ$tddOLdRGXVQ_q9!a#owr4Vd#h}mKW|W!U*KS)> zPhYugTI{=PG)fPhZdG%t7-PyN>3k~NyyV3~iGZX&@+5mE;o{oqYp)>I!;Rg_*tGPmAocef{KnLN3TFPrIh>D8Q=Iq=|0m_P@C=1 zcK->w?8Kyli(Fri{R7&ebkG)BejRhG!)^xZ+m_gN=-J@C0W%!Ih{CVYFseg zQQY-X$S3{EY?8d#OYHsdSf)Z!hjmNSveD^wmUsQU4yk&yZp|N3Wo*8Tv)%C;?&g3E zNg=Qog0s@#G_5uUB&BM^?u7SS%kKHnK%Tig)s?-b|w%J6FnSw53lh{K0 z{+I+Hch4qvi_Q*R*}v||^j4#b4Q{R}_^hPbosQg&-Hkz*R|EC0btf808BBUu4 zF_^dlB}KuAOGuL^o4@Vn3dsqFU}QDPeXGir0`WFa1CTDLOdxnb)Nr<=D9=np=}j-4 zzp59$(0$HV$akv=_ap!FuO~mCqjmEPHMtRqD;KpMl^V&b03Z453*HZ56*9gNxl*1a z?|Vf6zXIR`9Hw3bb=XHUThs{5M^GCL4k7Q5<6x;Qb?AMdDm0x+am7mCjb@#o*u{O4 z$MR+k%ShgVJ4Lf^$KOXVnWvUL6mQ%Sz)8_e!*ir|k6)0-)T(U9@@{Ss)|?zMOW!}%-$9DX^EF*5B3bj8tow? z6er6SA(6q$32{rn=jqQzo*GXf#TJS$^d^_ie|&tb){>gyS4*}5EXiVc6_xo|@^1FR zx;e1%*{)zfT@Pjlh&^tZy2i%0?K<#nNTT@tI!<_B&!Rq|je8R~b50zaM5EyE@}eL{ zpzxX&rcmIV5EkyWJ`mZL>xBVx+nE!`nvIX;+SFewt71I>O4b_2oy?%&)p@+LBl`XA zJCPvx3oHHG6!(4f z1gc&cWiE}7^GHKraxTh&rriheSH*eIl|q4iFDPNM8MJ4H<4x4n)h7Te;}jU6_1&W_ zuxWdE&&df31k@#i;6Xr_ytsqXQV&p>0rn%g$`E^5p?QT%w@= z!RBuZ_ZkT7?73MXDw?gEVaOVy9PH0l!IO8SK;jMI@OrhHsFeIobw5W;bSWSnE^%&F zoggW1l%bLtN?j!?2eh3i2ahqBOr}L#hMP~Hpm4pIvr&uOE1A(1!)^Q;hJC2-ejjpz z6)Sgk3t0X$ZkI5{eCjd(Q1G}03@5}n6#9R)d!9HF@%iZPRMEylC= z6geP|68k-;vZI&X+O#B<^`LKq;X3jg+@Wj|pWIDDSs)$oB~8M6-VO%mI(l=90}qp&%<#`X5JZP+WNvwgb zd#EeJk&)+?mbE4p1AIlm#)UWygv#{#e-EdzK*o<#RY`W`NQQYer{I<>tQsR-YLPS| z8J69M`VNtP$30+#OlFEXFYNhKu3ssYBKb)*sOd%j&FhJOrx!tft)7vu#Q*CQftv6Y z`3;$!-bHut@ln#)_<&}%!>80(d)o-bvNE^^%4hH_&J6#0d75eGYxh@548cUX+P24) zZ68i0T4e@c^TrRxDTI2u2FS1nM%AXBq`P^06N&RXbg$?XHt>t*}(_>>F1mGzDMh zipq@#B$a!#<3B!E!}i{c)+6di(wW6L%0&uWTW@t~_WK^c?JT^1R!R2ay@~wNh z2hWZ`+W&IxtqnRcl^0C{O{n~j?%pEbYj2?u`{e&i`D-5}v{gezxi{T^kLoUtZ(MlJxX>k#H%6-D}i3m2`p7r!(8AGE*cshMZVF$4y2AdkAmqr)b zNb@=QgR`=#Aa=&Lue^r;c_YIQo2zluwHreoGq!P}zU5d=LAYK|Xc+i*=V z`QG}0KX4zsFGbPJO{iIXYchNKlaKvG>-7}9wE7F+MSVGelTaNDLQ88H*EKDWCZ1tX3)w=TjP$ir1;(2@kPxYX6TQ!On?N)lWZ0N=egR8RE#U#p7To-vw7)nw?EJx>nQ5NL2-Eny2xV zDV%v!#-YwCF8(c1oirb5ux1DKLByd0zk06IwCC;yhk~Q4S*Okn@E|UN?5=*1 zD-@0!i{C;37_uOkAj}|J3xIfQJNl?DA(_LBR(8R?4kPrC?x2ncJ(53cNLl16h@44o z7@PK`yH=iZr{X>34sBS8g|MCeF}6ndF2go9Hdt13nuJfj&}x!<%Gk^46;g?dMX3!2 zqi_#vtj?TutZ`Y>AM#heywP{Q8rvnWPY-!>>!~}#i5gyks4_SPI z-*#n;Q-0sdYRLVIK_DHHVRRNmfq9LGSfg`fKFO~fnM4ILptU2Ik4;%YW@mCb8)66y zs{ZrBz<6ORW;X5BkzKgpM`fJ^Hlk{~_>zHXDht@|I=x-Y_;|G6OO6~3*n6jt9btF8 zBjMb!3g}zEY9hh;O$ztT#(ua0VIxRjczrR46eCZ9lc2cG93nqIsbU57Ithm2PrQ%f zxbU8XLz7xHRE%S8u=xe~&0M__)h$O=Tj4FqSF#vO%|C$D4 zSpatfz*_6aZnZQuemz1z*a*bx)Iz&Kb`sSJgUut!t5V{?cxVWbgM%RJI8brX-*BT?@%VjN6qd>>MG z8|;9EZpOE?%UMg+c{pD$`BwOQA6OUbxK- zIHP^mY97JY&~Oyb-1CGvmK7WrC9{=jR5ekTX1=yKBkJ&a!CiYDdx)wPf0kyK>QiB@ zeY55FO7;10i(cqpbzc&p!J&2IcLg_69lUwa3z;{npf#kV98Fc6)RpmIM4S&2;~5BM zq4;p?jyqa)k)S327Fhqf14yK*GAd+QPG%P+xA9Js=-B`%8sMoJM0j6UTQR^5 z;V^mg0kqx4b!V9$b>^?+fCaqvZ*?jkxm*6zr1)+hgxUC-m>e&~Pta|86pn`lvi(;p z1y$AhAZr`Y*?kNaeZG>sLCXh54JsSjl~gPVc2Itux8!BdAkSP}g*mhzvB zXQ{RyCuJ|7vQ~?vWdb(we+IK)lEVyU(JB-ow!0XBP%@Q&zsy=|U*=S%^YR|HFAm{6 zf_o=VA!-j?X>Pw86_yoUazD$e^znem^J|XWi%U!b{deD#TdHbM9)`KqNm1mYbM^?* zIF5_GPi`up^@Tq>3pBd~TO}I3)}|4go3Gx&U@EN9ZN9Ia1XUPLq@T3xCv9#|T$Bm& zJ1BH{TfOdqiLCFR)xCclyPH7D{*)3){nH2A<16DfE5675x|r*<(e7PzWR?i@boJmG zepNYD#(v`zu#!E3e=8_mZw?fs;`40!;f{2!PZoPk?I z?d0EBchRy4CKB*#N}|`!lQF2i#`g-J6XK7~-CZ!A8|dWswS*CM;~*KjS&(R1`N&n) zy}*RKmM>d@WTLls&ZDO|CLFR@M~(S9e|u2InXpE>wTwzExEj|x>uy~ zq7!^YfUT?W$ckN;j5ekBWZr@^CUI~6O$^L3C%0O5^!`%m_OijRUyZtR5Lqq0RlCH+ z))qjr-gjL*s?kivgrUO0-F}tp&(_|4qB8Y?9}XB|DrzET8FN;1kZRv8^DK><9F+yG z*?NN`gQ4gAtuOT!isN3>>ut=nsMfaXm>X%6iOgJ zrE!UknB8kr#SxVg`yHu-y3HKiwOoJv?baZwE^8U>_H88l9sCe=QflAPq6H|BF zOsRM80_!FqCcRvmcN~>_P9;z8x;&{Yf`-ZLEnPcw8;#}BAhu;7Nl9mWL*w63fz6x7 zspEf-=z%daQ0@D1uPYhij$64Yo|NdT-i1<5x8#%|u-Kir!Z@hevta+Z%LMYner1T+ z2U=PmCKk#>C$i+_4-_)czA}TtHtA-4^r0F#RL025k=V){N-khf# z9Kwi%8o119n{mP-joqMNhBwe%)>^vjvq@21_enuf29LpV;q8@xzl3Z5K)*S)+jp+5 zGC+M%Al-+voAXZOj*d^hPOe3-vVBv3*w`rhjgOOBTv5R#}Xu9jHP&H?pvRC~jTfNT4x$NBJ+lO-d>ny~+;i3c&5Bqa5tbcku+< zwUz#pOdP@U<3RG}`yeFfKcAzuf37>va(RT4^vt;6HtJ*k)vge2}&)kIi{{Q1FZ z{h|}UM1Mrui0t^{2)@ep{-el63SB3_T;E za*2;TN-=OLHz8=;Rae}%EY|B+xOhJm{m_zt*BOn znreT(eNoKOP5~}*&x-633ohrjQu;qErhP5>gjR@W06s(ByS*y}fjL`H3mw!`+{wk# zJnOmS^ybhHi@3GI!vO)6G_(}WXR(t-mUZ;FSvQmhnOrNkF&eQCq6BDf-xtn?juJL) z$Vov&pUNNTD22n8ZkU4vU!3R0(=X@DWcQ^6y*F7GYp0K!8%@OK?t{cfguy1`(7;(I8j^9LYCo3>fG)`# z%`umr@xT^BeM*XtBg>mT;m|V1BkZ^k%$HRHS?$=*9ygLtZrgu|t zk*B6VY)u2dO?%D79uR1OeBjq302X4;;WpZ~0zWU!F2LYU1$3X*nSNfri@uVo#MgS_ zR%HtX=X}XU-7lVi8R8kYuP0z1M5nE~BbB_r#C6Ldtw<*}q3z!Hcl&tyGZ<27f+=Ob z{ZS4%&-N!vt^0XO;?Fwq;wst$&GzoytA$A8_)jEtTr+ulYp>be8s_#FO4L(vS>XKx zA-O+$|4ejbrZz&pB>rkYMzX^T+~ zsxEipR5o&)Hz;08%BSBv_Ps>-!pcKB0tjHUyu-Z?sD|U?H7YdrfV~&`2_6HKqD?H~ zklo7Vxy^H66~svj4_FQ%!0X?{Vsqu zQwcLmLpiu2XV~1YB-sL}>x|~e?N#i5T(bNYIa&!b&g4ECtdA!{j8I+_p}LD`T+u}S z&_eWY-&gT&7-}ve$3Hw`>NKb@ePnjCISd^InIYeSH6Va+)|Ak$9t8;RZ!e%gzN(2= z0vd?m{cKaGfBNB>e&=j#PWG>TZl_@~?mRC-B3!_uk_!P|PR$ z=ij<;zW|4xXw4LNDSaN5gW@EW3aWlzOMAno9wdEl^tT1xq=y=m&QD0fZj1)ATnQ$0&Fh5}Vs2vS~Nv@eFb*)^ry6b~1V9^OPJug=$tgRUAl2*sP&}%*d zz)v+r@@N$qSwE3}2fuCft$P`b00PxfPA8GF$NcH>vj~~*|j!CniWm1g3t(LA(Ah8_>WD6A&B!=!c1fI8>GVI;vaa%D5(=#;~YS7N*{)f^uOM?%J)u~PamB!7aq9I871FDbZBkv(IwX6pQ|*1tC0E)XOR8+~ z_bj;K!}#mx1l-BR?^SkCX8Uetf>sg4njG&`oEQqadP)}b5#zp^#1|W98+knXU ztCB}EG1(?6DDQXiGn7#O_a_JZN2l#KG;1+@E&DnvjfOS!1KHCRN}-{qI-YKJpej^C z9QSB}>S}3tZ7iigAcL8)oAsv8Q-lzu0GBvk6k5Eu19PtXi)cHO$B?MMz8&i<)9bJv zM;YV2{z(0rJXO|ZlWgcm`mddW*2_o2n~CU=1y+J|UGC$hfqC1*tq`6O`sIMZ{Tu^= zz5E5(rTtp>hO}pSs^-lAipA)UStL_ZyP{6h>dgZLudO0`Vkj-W zr#Y!@Gne*Up0SX1*mGSUnUz(fx&Czudw9Fhtet-UGcN3`W6LyecJ$S_mocupN|Abt zfXvoiUF4lNSZf95Pwt2Eg5YNCe!(f-+WVX9C1CWdWFw$$ zNIEDA768ESGp>3Et<`8KN7ZilOKerYzq#Xn+5^9-@doLFx+y-ig-Ue`1w z053p9_)zR`BIN~eK0e^Ykc9K!qx26k9r5W|*Smq@9KLQPXf041O#Vw`o5!LOYQaN9 z=qK=PuhGZ4r)u(E5hbocGqs~Hikk_MJj4-tjG@b0aB+1qs`G4JRPcr#v-hu4A_h< zU#*U!G~N27G(oV?M^dnJQZyW!3;0@^sdTTPvtRn9$s=bKuD9HWHbbij>fQQHE|xrV zTG@;;)HUZ;CI}CCtkw6NhCQk8_Oz|viIYi^OfB=)Kiav4!vulFztrcdzVNLrmz?}c z9hm1Q!^6s`4L|y=*hLO21A-HVz>?}E^J*LncN-=v4?+Wj_;$ajO<;H>L6v%)k=s#6q7cZ)Z(>k!7xiK;Q3<E;+Rnec$n-f4b(Vn?>IyTu8(UG=+eH; zNFM$WWw`TBVrL0e6s%mk(f?uP+$))5K6$mF8|z5x)5kyDuAEA?bD%$bl3q!0GJ^4r zj}1PzAlD?l=Mm7y*pDf{7kG;CVqlPX;AceGX_CS(r?nH0qa?S`;HMsW+b)qp*urR8 zd}}{(0$iD5*oHwXeaaO|NHJiaxC$Kp`K|`fluI?BX9_)T{~*ZJ zN5@4r(iFy=b1K8}!yAJ7-dkn;2&mI;tN_Ik3Gg3*j0GL&?5}-DtK0aoZMKq8l+aO? zA?eiGbV{-Sijm|Ddd1*RBGO4v`QSr2E6oSv8~LrezuwZvGavEsPdL?oy~@%+u(pkB zPax+{8YSg8GvFk)Vd8l~59!_mp-?6A@<0e+B0}v*NCH->q^Hln`YEROD@p=i_NMDheev3B%uA4**{agpq|GN$w_=0tdmYK%-La!cO zD4^y){s@QS^pUM?Iw3DgVk6icDt$hKwy|p0<*D4s1`r@25iW@H<`HDLr=Rnug8NZd z`xTg1x!EbqLT|kD8kgZiD6cG37xqD!lqUz<$gF%5rT~q2z(Wy|6uYwkW&_ZR!U%{n zCE5UXPWJ=Nr-nCf+>iq(dJ}|6rb%?I7J#w-6nJ_ac?N8A(k)-T7H_$;-y?t7=c9lA zen)(^0elrGTwUAy674B&%KMioXIV>aF}Wu&Z}HhLaptG6ZI2X4&Tu@i2~$cZb?(du zowm2s`^N?vH-!#^mLYgC!~%{mAPJ@{E!i6a+5o}?X_B>Ij2{L}m7iJ&cUt`LBe)?K za>;6?gNy{|6~_UbYN4*tj@Lz)2td&O$~uAGhu|>*-p=nY=sR|#+S6~H;Dj`pz^fD7 z`y_zHJZBij_SeS^jQ51!G4;xR1Ru@F5*#9k#sYreZ8z`>pgvY70KZFm4fa>|T$xWh zuv&v&=X3gY{nrDdqlxxa_F}AaZ1HB>Ym&IXgiX;lf$RN~0}7o_aM8h#>(DdD4ymwa z*TGs(QSo7uyMWqmF8YXWzuBO^N2&eOL-M^M_z+D^eD9U0*TB(M`>DGE;tnumg2bTk z@4_gF9)VgHbd4hcDp*BI>P1P!0;s5RY`&mNP4MRcn!N{YGA%q^G0mTDQlDJwVhsd~ zerYYHj!SvM#$|}rdGtia_v2H+0+6{|{(W;7s1p4CAY{fj0%iXW@peiY#yV^ulBbr5 z;;&CKSW$Z(#r&|BAllTSf3ik@e^2v|`dG3LcXq0#yv?{vj0J)R9y#a?gRJ0hR}LUg z4h|5@|8^b%$-2=5A(P6E+1sc0PeMTN`U#@^%{xF#?U$(u(1-B4022Z7FXvJNIH@Hk zf&FU5-g}F9?BY_140FC zSFiFNb%hx0fYVEDICuR)aDj&HOhm(O%sKM0`MOVeOCl8zzOe~Wb z8ytf+0#F;rDo6dQ6T>tIYN1R zKVh5%f#eNzJbxx{@Sq2Ml{U~`IfP3NcsVAv#zq|n6tCdy+KK={&0E{R@&9-?J&yUz zbm#E;yHHS2I8J;yKW5eW1aC0y9$kqDPVafVzZXqwgP!X{kzbdAMP3NJYOeGlZlKJz zi(N-kVe%3s$L)*n=){B5xr5UfrFUir+HZjXiW_!cNIT5n@p`^`SxFu?3#M>g?1jt* zH+<0mRXS~gT4`iulurZ7hy|aU>pN7M_8D}(>T6a zus7+z_y=m&g1f1l3Jt=bHWDLIesM9MQnnfb^*K78h6x!~lQ9iBtn)SrEUlZ>k-J1_w834tB;e}vRnQOtB%(^7k zxt6ei@@p<@J$(xa!Z>w;2{Rp8;$CS11p5E3wD_ueaBm!sdqV$^^vC;eRzZ0dzya@S z4t7+SCI~<(iS9zTWXulOmO+sF|GM~%pqvJ+Ad+{v$;lr!^kfmiYs1quZ{r7O_l8W1 z!Zl^Fa+ReSgIUz3?=*9AQwLAFsuv<7Id>~?vWgYuoFPly`qp^zOZ@MT_)ulSP0o+I zz~!|j`C8**vodWaJ=g}Eqp73g)6_%@=ptyX@y~u-r)>!);R(*LLU`!Wm)JU(u59V| zrHhXTWu^8zD7JS9Ye~6^BQHq`FNK{TPNdpYmW3B|M&lFNu9AL*#w=dm;KKb)E;9$( zB=>|f(c^or=cFR7$1(b-dhr9m0 z+5tl+(JUek6M>5rZ|>4*^z_dEvShC#YU;zgR&I!&(noae-tZQfyicd0 z*qpNFqDLnlA}nbxuaA#V!T335op4g$eZ8|S_)((*y_U-vE?M@*QdzKuwjws5gfHz@ zO0m7EFB#HpYt+CwBUJvnT2wFRxtljb}B1`(9-0R+sye_BdPkZ?7Y-%QTt2S z%f9_NHf&dYrzEVu zD`MJR4-+pZAe|eAZyaeq;fSAOW5d0cpOaDVEND2!f(d-J?P?sidKT9~Y}AvhA5;70 z-sWsk`&6qSmTy=gczopjvu>=X;)iH_esc~9Vs|*}wovf?eFVGr`)T(dVx>Nam2twp zKL;AURd2fCLuMX9bkIf_j=$lM&Q$)U2~(dPG%yjX1)8-0bNC$g8MF`ny}YOGAs#6( zX&faHsRwE@LG2N*rY#rphQn|bOdy~{RNk|R`Q*c%so%q@?wTLWX<+GgcYMd*5_{!j zv89v#C{iPeQ+25HzGa41&GcO*j(V;v-6%*nLm>Hiq8xH;leW5#53Qx5LNl-)tbZ@_ zB9F9t3kw%M_D!ugN$s#nAbt*;HFvnyc^HMZA<`4zr4Yzj}#M zKB5R@pFdwD;1H*>pGN+iVjTSYV&{lY(AgRx)*CSOZTk_jvE@0?oR;08Y(vVu-o%UZ z#w;a7D{?tTD~Z#`QEpBipI+Vg@_e$s&|>H0*dqTvq6oz5)OE+Me=VfTDPb)wEo0v+ z!0VkRf%!Z}cugF!{=h9Bguqu*d=W0@+h1#EZHg+BONE2Hj1traXOS9IT22M=UA4)k zQ{GM#bU73Rd#`)9$K7WTH@w?&9#q+=A>;#DCRifu#^+ekrMN9t5l+FtXNpD+XCrkK zs1cP3IyH)Me2LN)>gm*juUro8{WuMNt#focx?lyRZ zz^WN;%S~?x0D1ub_Frq4V0NOro_930wa+oP&ka@eYz#Wut#0c;X{u)bDWUb?x|2)?U)BR2RUO2fan$un){CZFJ z{3F~sML++OISBpA7YXGN)G-W)IV=U<2(w>H<4`oQh&!c~r6ujfbcpZhGwCL>Gf{xt zc4EMv(>7t=(I!y(*fU{uk3^jO`PU6r2TAG_l-(M*rJveh;+wIy_`+Msl7ew;ybnu8 zAf3(K4HG~>f4z9f{;I)uNzm{~#DC37y6Du^wHMi;QtEFayASN~J1{Bw+A2=P2-+BH zEE)deS%G;S2zZQuO>&Qcd#gwr;Kx}2RG7MkhN-6~D9wwldN{|do?ZVSmaS72H=(2t zY|tSEXeKxDj%rxB(Zr##^^X5B1<1h$OKo&xg#_V)LSxIF?<*W8vt#Ih3=NP5671Ss zo(yVt2$-hdGJy7?9oh@`09KdSkChrHFzRQEY)p44eNWjbhpP-!HFu&q^`|QCXy`i( z=1fyn>F6oZYos}}w;!mFGQE<4`8<02y=FLXrK#fTc4)N z!?Njew1NXi;N$iEx0V?lDu_Juq!z zn|Cu70pwfpZ<}({x+pJkXf`AgVrptC3vAXaobo(?m>y}PJeBd6j~p@1ouk5`gvb+y z(g)l1Dc8|RFQ&fs+X-z&qp2wEe4uO(#@PQuh}R-cjP@z$jKxcyQfwcSZt|KYz|mMO zS)XZw)zvS$=<*A$7ZEKX3!J>3`@5FnwMw z&zf+mEU`6x3hPbZ@}L%VwvOG%=$P!-bt(fo0xyA}sqO4Xpu&J17T>a1UCQAbOT+Lb zV=twonkBcZ9U}Tsfa`WfiHjU8@a+>j_bmYa!^2dSD8IB+K}%)HR*dhYbw)8f<(bwp~DrLz6Y9 zVj)fF=MZtf%mez)e^=&pN>M3(owRFS>X~X779joc?!2R!?_~DYfb$dO1eq<6x8~mg zgdNS+#*3M4jhrDRhm715ZYc_B*7g%1RHwwpJ-nOOXr`Lb#>iNZ-Q{^J;-CEP z$ksO2Yv^-I3f>ecV{8jVtIEc-Oy2q?{rx5nGk|pB^eD#1Kefl{X|X4oYOc87;t|DB zH}?BgbeQOVcT8Qvryni?QZlnZOs7kW=Q0zwGO2a!&FJ7aBeU3+yzPwppu=-%ZTkky zTH^0}SxkY;y^HlH96j49f|jsqX^uN4DN`?lKjNOOp^~^w8a_3-wejQN$XU<%aI*`F%ZZTuM3d|`qHd&G!8^@_F8)c(-7s4RPZ4C;yg-j|IbmQ z-01yNp?h%f5(bM)4h9+i6zrpJEC6JHaepNq>=u$fSq~gIgc;#hXe)U{DQ@OGxqO>l z5p`$}T4kJ9OD(vcc;lTtQr>x^mtvx`(8l_J#=4b=7s=$D6ja%@wA)~$H_Fp(j*oTa zm%X)L6}Gq}eo5;9P&*E^6o~8!fA5Ok&DE>yzadavp7mU0_kyp^c(LM^@DXOJOr(`k ze_BN`sZS_c!!c0r*!@YRlTO)pLL~YhE%MO~=t_-;`LpER(rw;(^32>R_obXy&*L~t z(SGbEW+CYE2`Vntq4$J%*NR~yUVa#9lYg-0)_oz z>3_Lyot>RR_vV3c4>%DtN~Cvde0xn0>*j6-S38;SE?3-%h~x5po4|XCx6Cgm2E*y- z%I54;%bC@g-*0e>pF&FOVpXu*NdeEH*Of20RWtgLi`O4d*4sR#z7_U)Tr1YU-GXi5 zwEK3;+fwpeUGo_St$WVR%FN9Ox~+;}WfAb+x=UlMOO%6&K${9LnAel`6};8l&IYex zJ9cus?t2Y}Mwd0pMo0gP8E>O^xW3f0H3zuDOLMiUKRGESd@R0V+$Oa<{OE87$QIh9DA?z(~AD8%Vdom;Dd|p#pP@G#p38tO}8^-P$y8%(bln>Bu08qDp zb+6HE_|eulRE_(ZF8fj|=n7J-8$LKYKd8E~P3s02OFDX`p#pi{9N*mEOS2zCp5sp7PQ{by zQVO-IiB!X9uObwVD^YsVVmBSSBrjJy&cB+Tp@!07Q;{Sn(%DO!O)B3w-6LFTXU&uz zq3$3O(ZLNqd3(akE_MD36FNgBY)ghZ4x?q&3wI(|=ii?qx>miHngp@?4K+sC?vEE3 zN5x_L%JeO{00uFAX-T(-!9rf=aB0xgI3K^0-zbMSUZ+?IGsv21sGR|w%Aa6Z2-*(R z^}&qfgHQ+%VoZ)oZ%dA;3jeC89OxGY^Ip5d;P&JF;Y>hKjm*wyPthM;Zi(d34IHW_ zbKgaF!!umFx;x4*$_FOLQ9+!qSk@Wyxn@gbUk%r{t;!^~7EY@GW2fo~P{^>%53E-% zuD0$swD)Z$9{uU{{aKpmQBRGF%4+*U;+)Iy!-DCxg!H)P0eA`YMIt1t>Y+jH%4SwI ze^e=Uk+{6g^rbK?NsH&iOzgR$%$Lb9>|j)<4l@OSuaK{bswyL8C_C&Z_L#ibxj;A z3V)H38{x<;U06_hd`MGzbKT&)XIliF9705j^inp7;7g`Zc75H-hFo)s%hy?-%pgnE ztLH9tBq*z`majRQQfr2jM}WtTgZmHL_XW^XLo*&MP6uJZFnFmJ2io)h+^eP*;1(;lg z8;xU@!^yWKS%sQAs4^d_(w78m({5~51yaHQ`J#V?;tJyTCkB<^sDE8cvg%c?S8i-B zuJrhWYgljinVoC4tR!`iTI*q;t_wmi8Q|DL;+RtXT)>Dgk4~xc)8Qz25G=pGx_k1_cjdVA`uAToz+CWna?= z;AuH!gtHH>mZ@Ue;pwfR1Ht)*ZkQ{sBpb<7TRyNM3T z5q2kaXRR(Fsq#WaUCXTlRdtj}id1aTy0Rq;X1Pu02hT-oImr8dreNP>#q<^>=j9k!d-V2H}UR#q<1Z=76;#NXR%DL ze~9bdOwfBB96Rv2-K!y2dWHvA-IiuWJI5{SQ*pU`(sb5)%Rd@>vywIPnpHpNfGK!h zKK?_j#xAVbtHZXvdeSb0xxz#19k@98i})%mhVZ$7(g}jbyI7f=q<20#bLN|RFTfmg4A7ZaAs@e>anV? zQIN34UECCfx`fMRo4)d{jUAysS*-l&X%GY)*r)~A4GGDnPm-qQE42{`E_S z-z4(14_+^^#0H+{9gR<5n-*#XhYb|vX90bl{hL!-S{f*-%{&yZ7UVS<5aqx0Hz|E> zZ5V3YQh%PD%V~TtRC(MsP3wR))FR7VSZyIgj`tIH#J{CDq+8OQf_z)1F3Ra_TK6SN z=m6cv#M`;O8rkz~DgB>gEus!RVOJw#J~>{Tw(W0nby?sV*sbD&wlQGuP={FVse6Z% zsyipX^q=RD`?xNfBIKO^sZv^}ks;6LgPO;mjX0(1~Bq)Lf z{XGmw>I$Akece7kWAQP1uGluO%*JKs10>T8&4Yk6_g|n(fQQYRwL=&qOjD}&M^Vg; zmq}@oisKwM2%e?&qpZJKtoS+|8{su;`~m6S`^EruQD3!T9}7{M)OJN|ug!IGO~HO$+M=Us)wFNj zbiSU8zRk(Ne&-!|mA?k(_;9E)#v+yruF899V&~|E$zV=(*W^q+e^PZ=;P)lX+^C9R z&x6IEXWwB2+_nb=Y*@YJ-OwsK;=RjW!X>sM&RJfVlan%}dRiiI@-H#7)or-3gXCRu z$XM@$S2da?X*?NL&)>)lY=p@G@&(l%q-;WTZ?wB^+e3J|o1+h^kn_QB2)i={s(5Uf z*ioWukS6j^U<-iW0vHN8+I0{hNLA|828V2t8Ht8hKJ|k0UL=FpCLTF(O6w5MuB*{fa9Tuz-Mou?H2PDK@su2jH>k zps}aRzLDndRwELO+mIUu9JhOV%&nl~hy$SZhMxN5;ajsaXm>twE=nBv=Wy-J+c|O# z%v!QxY`LjxW1aaCvuQePo2E+ri(hkF`}ZgFd9lmya@?_E zHZaI6n9D9k1jb)dgjE;b@>`hmc}5A-n0{DNR6}L3*(8^p-RhPT9O89q)^Dhx_eO4s z*U8Hvhu6D8<9dWWtLyApd1?jxM40>JLg>l1Tp}j&T0m@GaH=iS==nLrc}lVm2K;5` zPQ+(KP6q}{P+f~4gE9(0wXqF*_vN<=^|{b&rB^4#@z7T zgpI?;j`-jJn*pLWL8DP%bQr)Ho!B-8-nBu*@ySLjd;m8P4g)@Kbz1|H)_~r(z3nk( zwX?MJDN|j*Car{SA(4JL@KOSK0r5y(wW~UQ6mSBJcr|SMOvO$azyH_ES6VZ#gKtD_ zQSSWk-c_!|B~asBdfK~`7DVA?P(?I3Pz>R*0XDRMXU1i!!PYwlj`y|gBH$YYrx!-JLR_PVn1ElaIatgEl4|1j|{rU>O z-QTvnEyspbYH4dw#4^t<8D1$^Qs8C3048Slp0JLU5lzs1?Duo!G|fJQJWpE`VgEd~ z*up-=sMeviP; z9@*p~D`AU_WQdON9xWwm%a~r7JxzUGsPPA%hVxQB^?)CbC6&1E84-;o_yIkJW#09> zud`yC0*=di#J$~wEMH{Cyl8^bPDrLt1qATizVW^<;+ zJLJzH`0t=-(HGiMDi^HZEZ+CiKbWsLX$Kqv7u=`HRET~66~QFPBxB|4tyA~Jc2>H& zIR(5}1(xlAbrI99o z#Ue4f!-kdl!lp8#vlD8fOd}9`sJuesO{%Zc@tg?q8tX=C6kB?iX4-HHNrqmtU$6?j zhUpqlQ06%3#qq~I8>H8mCA$Kg^pXSnsijIDl9kDsku=OHYoMnsD}x6pvyy_uYl?K<0W^d?bQb8&XHMfP-RT zeAAX5u&$t{-A$~AR#pVMyIUvgDTA>6^I&>$OV50l?F~B-*QM0@s)bs4CnqO$Lqi5B zg2YG^cosl331C=Huy>jP(5HS;djDqYH|3L|lMv|zu$TzjLs?gee$aR?D^`v!)Y>dM zetV8c{XhD|SK=E@Rx@y&RE8Z?Ck)j-Y7uM-w!T)W$SPdQD#bv=k-BYu(LH9=>~h({ z+$j#CA4NxWV1woBaZ`uasGYDX#)QhVsp~Yt_Nm}X$&%R7W5kbf>=FE#8k)nZ5y2 zO(ze8buKr_cFcL0u+Hj8kNI+>3wLRCPDf~vE+|6MGHs1O{X&fx$edG)^f1D zeo;RNZwDfTVb?J~lAypgQi5&w+Bg70zy1wxLaVLx!8#c@ii7QKS^zx?p9aMcu`|Ml zj{@}c*GYhZjtrtU{V7Ns(vczq{V0-#J_h4edEmr!s`0*Q1*C$T5XFh+Ld!>S2F)bO zO6?zH+Wmu^kpJaX|FEj}9fl{y1Jz$0GNYF`3Rt52OHUm@G@d8&wi%zpQW9xl4iqWm|98wB|Qz2ogM^ zk<8;NTLM}FwGxw-mIK221G*XPax9jyDHR8hU4(UqF?H; z)m~0Ox@2w+KHi>?GV<=&=?aa0kKgX~V#0KzY(y$`Fh53hBh&{gIP{0Egc?AQ94%V; zF1b7lIT#^l^n7CjVeRp|mIB>Xx2;XtH@z4&8wW$1ofw);>K^ZfVpwm9RZn`}g&Xx( z#$Es&SeL&C`+;yY2EAQKY9^-0Hf=%jpb(Uhc$w>6{z|8;sRXDmftl_oNu923MFjn} z#^Gs^x)-MU+IBo!b5)smgteG7)#_V;*mNXO1)9y*c09{bCTA&q!d?W_9N)-bRx<1= z9RXrGx1DBfP;w|km%(4T;Rph|Q%iODFNugv)4p|Rz1l`Px+ktMro1mP^weYW72 zf&AGRZBkbD(n}@ZeQ2k(LnV?vke$$jZ|RCIiU_z~h0E7JxG4o%&-^)oX;X!4&khNk zFhOY1wwxca=l|poftE^`iM_=1ghzTr)sNzyh(?1gx1OPV$z=4dc(e{%MM?#xBU;n9 zT7ZYEUeqTji+v*1HAah`=ttp^et2$6X+bh)%IgO&r{q$pB(ajJ}OlNqNJ!0c} zSAwESJ1()*zBMT;!A_@w4Y*cnqP>iHEIyT>EesM`( z5l)wlOhjJtwkX=Q_Dz3~Lu6F=NVurbns7nQeJzXZl%-rLKZn`tc4Nq3t&)twvY1-R zu!e|f9hHvUbgtqb`2Yf$#nMila6~wiTMqBw?P_IGQmDH~dFY_sP{}Ktu&{-JIgiJt9O4=M^rE?BAzA1S+Tvnpry5Rsv>Op8K*iJ#6;1$XQ*MCO+frRxRqUP_;GiF+$OUF2cK<(VgTzB5ZE&E#&8 z>buW50p*Z9Leq)JvxqBojow38mYr3%+P5z$BEGheXHcUS0NpR>x06u!1Bc0?8UoOD zM~sG6hve>jg=C^iXnoZpE!P2UFUZw);!f>vgdfoyx|e*$94!PFVv^pz0}SGnXZ zRtzFeO+pe0;QdkX;JV~e!Zhs`J=$G$p>;)16pWepxEVTiANLODNlobSQL@Tu*I7#n?P%y*GE zx8J4g-?!WTjyl0KG-(GMrKG>L`DFw!2_E%1CDv0+Ji@UO7Gsa=x5^6&Bg}4pXYT1T zncLF-V7Q*~QcVR_z~}Yl0ca>kE^d7SI1B)-|7Ze{VgSTWCQVZGr#&BPV>F<_08tA_aOua2yLWFmaUt3Y7H-rqcP%Rb=+DaJAra5~*riz>T_qVd(Z}2z z45?-w;o)QVb_0xZ?xH3_*v(EKdlWp9^Wfftp7c8n!+ z`qCKN#%)2CrFH+x8dF8~Wa)+smx`3DR`q4Dx5GJ~3jW+K|GROs?7HhpB`CYoGK;_i zCEa&vidk@ocD!=N_L{$U5R32+9ekPhjv%!pJbAHP36S|f5PDP&+*-(V5RB}%FEqN@G!DCl_6P>Kd|At#!wdUeb5h^@ zf(h?p^UdAWC)HpsGmMrEI~x`zqtP^2L`g<~;VZ@Y1fi~}>B6`pw1lr~6MMOr_dF}^*(R;wdCcP=xha+g179OF`) zQEfM_zFd1ascV_Cj{B)oA;lq2K&t%XK;$2Gco5}{QYn{j7<-ZCIG48tWHu!$3KZ2> z0wQ*EtCVaGdeH4m$w(%9@AP=53E1?X3&DK?She4W{}B-6Eo0F=v`j=`P|CnZ&wD)e z7hl!?gyv4X|NiMgJK`aPO3Kuicf1XgayOmS^-Zd>*6+K)9l$kzg+|P=7dV+VNXsfV zJ#XievJsAL;ZQSutX&F&zn9gZRnt{rrhvsfa2(Fjok3Kq0U$`ef;@7JMYtp-LTJW$ zU`@Y&*QavhYJ7A*0-~yO!71{k->V{jLDU{$3#CQ3CofkM0Y!Y zi~E>e3?ydKFy92ZxIm3AqaWWVCK_ZtTY={d1<=wFq!%>*Ulv1|7{U;aT@e8$W-s>G z2Xi$TcW&`AVE}EvZ61EM>#62MOC>E!daM^F@Mc&5!bY$xlOs7VbuG;D+0O6>h>W62 z(HI^ZfvR_9Vlyt`80*eCF=?4uEyD>7hBPc9Kk#t$F~it8x{R|N8_a*gMsGab*G&7j za`N<~UDF#zXNgA_oy>&0xsz4&}0;pO*IoDN|fieXwZM-BlfkXroG*OYFj<4m-S4u;-G|;x z`^}$!F0RNwx$0E`HN{G+V4?$uw284AJy?qz;*FHUTVI{ZhRGvfc{TG(YbbvLK93;x zngHyq)&=RYpMvQ`1BZSst?P_HL8bNdYY%NJsgI?TLRY~v>0j)6{~KY64NdSfjhaRq zK2U5wL5^t}R&x>*7d#KG5O2v?u6(6Egl->w-v>xieo*_u7G7zijXzI(V9>C#~(!@lRpPPKS#B@lYA29v@ z<9p=vq{>eF6cac=@ov+Zh)*u9&o(1T5F2(?W>ftG49N^bujPC6926Z}u-^C#@8ktg zN_O;^gF5noSS_iVt>AA5X&!j%k|gB`M+4z?;1AX?cKClOFv8xz9?$l21HNq_`OKjc z)VIMHNI*jJxH=VvwKQcqyD}y|;W(gpoq6k^5#E#j+%jhO)dTI5k$2&fpmn%Y02(gv zl-mihb()QD=)tLa<1eHs${kgiZ8@KDVMn(t-e5S?UVTBpOY7X1_y+;7&ows1F@UAY zwFkj&b@^v@=Z&~VfIO$J7bTxI@QvKqMtS>%5ze{{yJjqI zI0L}2>Fn$wNbwjNs2pl>L2c=$d^P(Z3%kn2B}gxM=YNPnvEe`%77%O3zKgsdn@1a( zE4H5^!@TDtu&SGNEe~A)GGd*eiT=!i)t0U_@5>joimR_4n{e++IuhjstDWhQBi759hvv7Q)ic$D>6wOm~=1=nCLDGGa z`@b)a4A%e*>rL2E@mr|U(vQ0U+nxGmykd*BrDKNeE=v*|Vz)EyvS+*twl&)V7PoDH z7W*?m=OeIviZ>HTnTZ~aHv={Ge?Bv@#3QqzmvMK$ySdJPJca8z#voH}^nG;GVI^ZM z6ibNY%IFxXqz*}g1hamd-m8L!7mXlX;q~lU%d7)k%g?TR+Nv>QFe@HqP&Ug(*qq3l z)u9-kwtE%AcenMGUUM9a(Od&yY?R8bRVdv|cnyVdF+USaE3AOdQ=7zo**RSEXDbI8 z^w;`;67{8)3*RLp4k71zdaE?D#E>7PFattzcRVS^v7xte?9rMXC)CT>xXx}WA7ua2 z5ch8<2w^xAk+^Y>0NO|ogdBj^3aOTqes+BX@i zqP>oujQr~4Mz4dwC_ak`0u2LclneCgFCCe3Fs2^Ue(?R0hEq_SXb#I{6r*}fIza-N z;JM{$K2VxdLe}u?l!UpBA5a&K{XNVGOv*j>N8^7IksxuU$7ohDk+!$x8-GkDOCW>g zRZlbs5#3#G$JVd`9ASG91q^aT6Z5*NTL$NMb_#$T7$M!wXKDHQUs+b(f%FMHx%bRS z@1Qs#?S7p25YSQi6F_=I3#Pu5ptH*5T#w>q@VGvsnU_vF*3j|e;w|&3#2b_;(t(M> zMGsZxo*Zyo+}@m8mh>0%-Ym9g7`p`oAm(kifCML`M5;)t6*<= za;Y6g0qXP~iI<1tgt}-h$9QoiXscMkt-7e$g8g~xLnTXQrzl`yc0Kwo{QGOJ@L1^< zha&Eg>GzV*ihie~8VPW`h|F+aDyLRSax8;mQZqh1ug~6^8wBryJq&awUwv8 zZiJNQX-g`6bc!%=DbKPIasK)*`;e_u{g%^XMMZsLpw@{!h*sb#+YWzYIFQKAtChf4 zhRFnf-7pX*4+i!uzw_DvJ*T6L-!cieTCRLkj2C+cgz~LC;uz4}m;yztn$x%NQ+rCj zJRBLB)z2c;qeHipv{Yp{3XKk4zd}<~Cd6jR&%BNaZu65k%nrMB=i$DR=}+X%-?jp# zmdjn2AEpGFO};aW_alepRpN%h^eTGog&nbxl9G}-fVw8d1k`{ObUi6JOeuWG7~s%7n-pb-;d+swoe!l%j}4U4hG2!|P5 z1#niFd_!=WO9(@mf&1dNaKE-n{10)6oV{MQvoEzsD*$#6O6Ea&j}>pm-ybZuD+X<1 z5&DXaXoH1At2$1{ovwDR-$k562H;jR0pRW8kvA5?iV<<)=h|LfPd!k1OHSK149Lh zFu9a0LXFeZ>yrAs$St%c%97oPGx6OCK-0oPg#6zk zt1$(Pe^1)NwSeVGUUKqNU`H+u!C(L&M#O#1dgXV*E=rxiJbIy*QxBxBBTpX~aOSq8 za25sg7wyrYR%+y?eK~-ckP^ zN%Xf#D8FqCdR*R*j|2HUA&OKb+RF+>=Lh~pa*fcV^l6}7wc%^k$>--SX8U;ts6R(misph&h;{_wQ>=DmB@ zpxXNBg?DccA>+{T_M&IiHitzj5sGyH!Yp2?Kh|uHx|$w6@tuXF=_TM6@7ByAT2k3W zobiPx-4~67$4gX}3^~U&_?Vk79eG3g-$K}oSnV!;CKrHEPcpcEKO+y@4q+HP%S_0$ z@xe$EHmkJmEn!2vRxVF>=fo@uMFT}=nypm-U&7bNTdi2ovK3Uq2S^?BfwE)vsk@4e zN67!>x>RFU_GN6YBrJ?SAx!ognKb;RuxC?Ob>g-P@?!koo)NgZI-iYop)#N zMGLsvtDhUx1B}g`*-W)RA4FMzuT;@pjEss>Gd50A8C-rQk}e{!?u>${+$1-61Wznz zsog_yqSp>9vhS8uzOfhm-Vq+;^qfvPlrmJ(FtuNUF}&wuRBo}?A#`b-O=in0d!+Et z3N84*0{^MdHjZyRaQNg`NCP}MUOJ%>1T>wjcRSz9q*lgcUdkM-V-OdM&9&L0sRX1- z9O!QpKX?!1yJ$j6pm*&l$zQLq2inpHsOsjIHq|aQv*Sdunpr*_$@LoIk#GI|Q>C?xCXJn$k~>Xg__k_-L_`o?Mm}%NKkT&$Vp(M)B2X%WHdO*xhXR@SHQ~_^~-Af&h_K3RHnR0 z>KZ6ulIgclgc`=(AbR1>{@wLiUk06<*xk=qJCg)&^LF4bEab9geZ+_8(64bmwhox? zpbx`KN=mv3eh9c+xHRW5aJA=Su~*T2ns9Tc3LovJATA@WRU_@KO~to&Dfg5z@9Zn| z|4Vx#D13PXbh^)%k#tXT<0mtVz>u0oB&hUCoxAtWV|CbUPoCk*rd4-#5_q`NpqL?F z*_Xd)c>k2;{|kr=6myo}9IbquYo}`{YAK36IMyhYQ039jC;vk&#B*bJYh~#2QM})$?nyY$HxW( zP)uzQD*7&a0+~fMWpOEp^Ppeld>(a}`9FReE}};`GWnIN$GfziWEJpfZ-b4g%lO3F z;D^U)EX9>=4tOAQIoS@+BXZNf-Fm4FDk}aTaVau6c?8@k?>igx0Eqo`YhV}h6q_;w znp#nNnPtxd`V#kly0oh8W8j5q0sJiZJn@b*Vhu-qfZ3ST!8(DsMqQxAMdz#Ldy;M{ zRE9oDDNdvVWVgV^@jaU(C|&#`iU1^6IFOp&3Kh;BM?p15>9OuC0tb{$`Eo8je$dH{+2=DAfY-ilQ z&Pal6L{C4lnru}R0!lscBfF(2D7oR^fd}Vr`k7Dv+ig)y4|Yg6k6Gy=(x3#QL15v5 z7CVTTK=PjZ8$a$k5NqE{&;PjIfUm0A7Hwg3ik6+A7$YXkMgWy@pfhSsXJzr%k{A*- z{|&wixnA!nAnnN=lbQUN&RkgLShb^?qB`u$Tv<2h%>uRcdNLUBa)^hNfWhecj~eTL z6|``tVP!c6QVa>=G!a|FS$P>vz|uK_@bc98n|WZK?YW(DN+NN*EB$=P!Tozr@p^Sck?{k0e^}4U?{Cmcng096XNZw%J zLxA-)LP6}p#a{#4QC}R-FW2=7w;;+#H7 zyN0ANPVYP7S|_I4^TnJxU&YNzn7#btt)T`h=EO~R=be_@xz+y{%%QX+&$x>chcroH zZEZN;DTTUJuppkdZh572?3OugTh0=Ri$hF%E!`jy_mqYX?ZckKpROxxWP;*g#dG zrDL?{b7%FuQu#wXCbnGlj}TOxgBQu{k(19^b`c$F*q)e|L0mDUyQqE4FT*dzpXx7U z02i%JzRSjCg$;@o8m{}1N<+CrI4aqT*PB-?W0d@|0@ z9Kee};@A|~3K7$$XOFlzkONLB&dW_6WkbdmyTwvS`~n=(4WK0q9qE|At>XNrST5YL zHh0+&=!?MG$@Lsk)}}&KUCXeGeO|ZWz%fKq5Gk<#aFut!>M|Qr%l=pA9wlr4O0oLq z&3P5#r7>0m4NsO0sbaJg8FuF{8v;EN@04Lr(AW9>CLl@z8wGG5ZS_(;v1cWIE(r+@pEaGy39D6gGX( zMkI)~AH-7Gkv3gx)8m=a?RhOF{{16rW)r5nEp8LvontL#D46{uC5Vf*WHLV0GBJJ~ ze)IT3VPJ}#Q6nvI_SW5|`YizcOsym?1b@e3i;g;Ek4mudxNOJ>C%a$PiL|w#Sai;H z0JA?~n#bexE*cx3#T{4f9mYVh{$-hjkbNZs1{BUI`K$agYf3|JT>^gWyAJ1HIH5e* z04g;hIF>-VXNYwz{qSXMxXxWwx%4NGP({Bk6R`tU3Bb|fwoac~^6uRo2ktb6t@42X<$#UEr8QYO zb!S>=H@!P!y8uEock6l+XyoGk`56Ed{Pz?daJsv6PXHnR?%{^l+;1Eazy(QDmg(Ersz%`oSkD#a2PJT4$lA79F`)BPGd{(fQV zok+N(st=Cu?-Fq_V{(5mUSQ<=#+{x%{JW{!nGV#(TS)q>YzP~dlzptbJN^IBalu9F zf&GI;XV%icn^G?*T4rBv~gS-SiNA=B~?U`isZ5!DBlML11MCgzTM#qg|B}DE0ck z@Iqfn?f)T){t+2wKv%V4#5!)WGrh8>CcuzCyi?9&dSZ;z@ZpNcVx18}9Y=ak-;`%V zBY+hz{l)WiyImb|6h0r{6OnH*NH=xPSYNH zoC+Edrv#<-w#2t#+^(5n!&7UcHXsds*em;exX+hjMSULZw&a@GOWMT~Jmb5{f|7q^ z`x0p5eNWL}-jN7vhT!pG&f9`?ef-D~7PfdkiSqQjY9FzonJQS$UE-o}xG1i_dp2 z7?Y+d_qPo1F%BtvRZ5VDF-3X8zCeoz@s~GX9IcVYvLrh^N={ zu$y#>d%LT9>*n0l)qd~vG^*rZ0PG{|6KyIiT`d$dnm*L!?;Efe`a=^qd@rbJtjA$-U=P}un%Jdp2u3`T0JT^rfVN*+gP5? zL!m>k@%%T|a+JR$6F2(8$lxI;uY&aTOelx)0>-6Vx_|Q#@@u1&9v&f%?!nVt@h%xxwx)k~%iMCmHg)FRn_W((HJU0EjSH@} zdYVgR9Emcjx@jew{XBqo>O1Z+Qzq1H6~tGf<81QEI$N2Ef%R6%|*rF+2o{ecDuwJ>k>SMJmgl zq*UP#(xZfALCSW?CjaV0{#60gOXT%S=!`ZzqRKs!L!Ysb2^MkdB z0XoRse+L$QJGTh8pPp`|XoK$S<>5(#txRqh!(dgOP#`68oe~d`#opmlf56d3$+}cN z9k<%y2_^9e-x5$Z{?6;vvJ^Xl7L(2S_t)Uihr3zz;}Q~HPp-+D>j}iUh5;Eo>tE}1 z-gfBoPm6%Pf+Hm?$OiEo`hR5ZUC0XW4HkWe;6+Fn$Qo3I4b^hzia z!lmj*(k?{vQn!2((K*B}Kl6OrsqH$u*M`7_KYMVKjAa)=C&dcHBp4m4!WD|Ua_5y+ z+b``Q5H^z>qq_r5ethiT&bq?wM@AN{@sLZI9msYq?r?s#384)8vRD_yOvp*@2_+7z*3{o?@;qeP^Cl*B>-~*|q@2%!&v15CVtj%0z=`H&@-ny$oQ$qs^I?j3d zo04#LgRP4(1{{-<9mO57sN(itL^r>$6RM;uNo!B8oX)GlzB}0gTXpQnpt-$#2>#D0 zj@gm(3C&bS@73bPEC|29+Cz<4`Ny4joQR8>aj&7oturjB{MWZ?K*FZMgKHk&NgmAJ zphoW!r-B7R(fHvhi}|$es<=>Z3E$$>fm4@n zpNll{<9RS6&0YS;(=(37HZueU&j4^i&K>;|-YkJDe_}>!y5x2w^nji$%#m|LIaPRh zdBKoS72|&#jM*=RJYkKl=9!fL94cR6wfLIW+OYTzTvPry2ZMJor?;HdIpYQ6WCs9^fkZ1Sg@~I&gYB6$S#QL&H z7m4{aB)dZu934T3fo%cfY8(d?uJfMwo+Oeuw>E8_^5*YB?R(D zZw~qDyD$i-5A#D+;!MO$i?}2A@iF{(2ksU-YM1xgs63kn&sqJ@+WzfhW6xpn(s>yU z=iccFi6yQFH#_Bc4m&7(+aDJbMMAM*%L{V6&ie2uFfcG^4xQfOmqJkDSK|zAq5mp` z_9MgsOX|};<2xJF5kKHE682mK36->}VL>Li;-b;2hyGnu{EqH7*-M~tW=H0T+|9@I z<9pT6rT{k3#fGX8M6zo8n$x{eMVNWCM<5A}Rd;{awXZt8ay5<>GzS0nReX+vK)d-{ znT#W|oU+y&NzG3J8-zj*M*96Bd77?2St5_G>^Dtqs!XW%Zp>mv4i9(oW z%EaD8#Gy>xGID}|C9oimcH-BxQS2*b6&o7xK(jtx%;QBLxalX?hSS8h%{&Az1sfu} zQoKO7>#U3G_W8K3L*5Z4p)u<{81}zc-!bXIe(q#!iB}3U&}0A2gOzMX8t^-7?@~YI zY4J>q;e0NH*Su;}N|ZamQ{zZi3n=k{DHY~0-pNn>13i5K_TRAd{S8{BlFN>1G6)@9P@3`+^p>0Jg zHO@c(Hrw6yhudK7Wj2j?Qjwp{(8d{~u_s1ObZjdxglByy2qpgxi*bsSo`UEYQkA48 zh82U3?-YgRbv*)C@qMl6xtbcT{g)51{3HSMp;aHC)pCOsSZU5~PCAiYGwH%VpAXup zumlwV{nmBg&q6GGaLa3ypJ z_@*T6CTk;b-hN+f_)AuRv{NKn>M^-x**^%baX2`yAvOpZ!7TkN6%OcT$S24jc+lk& zon&`uI>4pj~OC$=r`3;$LCEerMgPcLWXW)Vd1ZlI#otVa# zK)GdrS>j!3zh^#Cl3UMp)4?IyeVecF4HmkVDEo9#gegAg{w^3BbG%g(+BV7^bvDC*KqXjf#5W6-qz|b zY_-2y3V2dy6`EzioB@3;estOvyx(W7sf(-ieB8hnTFbAd=fH|=bkWSMdAr6@a1f7_}cnG?y(Li3aCd~4`U6Lb+jP>n?L!!~uwf2Ye z$!UMYPWb5wB5G|0VM989GsR|hUMfI9HxGOoZn4CdZ}?QSpUJ|cGSvGuHVBqM^-c$e z(a>RoOuy&sP~q+}^~(iHeKg3II~t3b)@pP@)saU8 zr82&i`?w$M&84m!9b4u06-sqR`_M?(CzxI~Xyu={sc&56L-6~oLj?Vd-$*RP@Zv`O zLuTS_DMU2eN#90{wRDpkcBFER-2Im+U@7~&VgHR15uJPyWl(V>xN8K-mu0;AFRtJ>Nh87&j4ijzZOi0 zfrE16;Oqf?Nhr8la?~O~RGl--Qt4kf^{@OQ8|)PpSvu^V|IneyH$ytXhb&DxztJ@VT4u(MS;nzY19*`3X4?%w z9|M}C^Mh0TZUB71Za?M~X(0C|kLCmDn>gK})>-eOt##uie!q;nx=Z35+EJlZUFe|G z^et@2b(L)RFTwAdLEYW_BS&>HnEc_NsJQ>bmx3X6Y{S&e7Gz>GnkESSFMOn7ZSFmCn9xkGT{SS`Qyq>e$sd8kQA9$jqG%Bqk(hJqooL zn8}d~sLCMej}_GV)bl*5+n(X0t8E^c`EfkZ;%ipCX{O^Cy{0|AjPrQn`Kdwj1VKU| zH=Y*OOHd7W^r*x@RA9$kSuqM%?u*9x>Mnu0F01l!Png0uB`rAztQURLYXGxkbV+Ux z;_C^7i1O^)D$f46L2!u3sjjsJTROm43ybp)x%;y&dod1 zl3>B)l55xhxU&GHu66OV=-!N`fq@04=hZ|1c-y)hGtP{px7XhWyp4UE<-|OYuS#3o zqoKap)$7>ROMG};9YYoq?FZ}$7>O?m?wGtU`+3&85wQid)L-mx8tGT8C_ydO0iZI6 z%i?*N{0Mcyd?=$CO=-h=MaKok?16_fXQK!IKf=567bim&Ud4O#+$9-qZA7Q}OJl z5d|(If^;!@6b%~I49D>~Gd#C^?r%ar^b;URzUX*wtuU;`5U;^1W{R*FBDK(o*oMLnveJIlk@^eqs7|@|0obw;*b38z9Hq6K{BF zOrP?E6nixvc<+zf4_RN))mFJ|#$#q^7G_2u%GNo@PiPL7+m3jCO&CwO95LKIbqDcV z8lX0%j&iyy_HEmXB+@jEet8K}j;F?WCHJOoQbQ8!GjGSJJ}6F3K}*Dc{}J{x>>k@} zU~4azI~hCBY7#&(z>;k}UtDKaIzm<8Qt8{CU!c#ZIg{z>mT;w~cB-ieGh25ZTkwo4f9-Wvg3PN z@;L*9rhpi&t_@B#3g=b4}K5be!mGX2sN{tfG=aW}lEu0?4fq#=G<7h3Sb( z3m#2qaRC>_&EBBJU#p`_!^MvluJ-++AJw!T(c(ejWq>aZ=b$yx!X5u6Q14|eQ@LF4 z4usL_OAA3zGC36gl^C8ArYWMAu2#W_PKqrZ2zsUUs?eOy5ezd(sPNS|D^pLr zlzi~xt_FG*AVD1-cmQ<5st#4*aF%pKAZQ!K<%drsDp82Jlp;A|04r6px^me#`Q@le!4jv} z<`&FZN&N(ns2gv{k0n(qdZlx;{;;YaG*=4+(MtI8h2+Ue7Novy?8$5_H$E2&47_C} zHaD<#eKX!{bjKFeE85nugcGFcl+mqR6m$5hC_wY0yy~BGTGN;}|8%};odX6p>EGSs zx}Msr{P|o5k$-ot>L9i*(5p!4*i>Lt;!_>35gTFn9HTR(lG=`+PIpoj*65A1&BnYe zP}&aKyM^;ZvYh$k3Mu*9JmrlhMSi2##8R)z{A1~bysi*b{X2wn>Q3GEHg#9{O zDnG|*ZA^gQ(IkL}7zxiO-*Gb%^h zU{An_h^OvExtgGnF2Cx)lnsI$l^gE5zUbJ=Ft@cgc%Z|MA_ow5NKSWf}&rqpJwswd0ijT+Wa%xCW%m_knc9e0|Ts zgNUYmeM`1=>{wYZ@L-&PG@#uxzsxWp4ikrIp5U2jPh$xu#^oebBuHmf0%_B3c1(ek znxc7c4R1hQbi5sqHBLf#Y+W*g}t5IHc8m2xh%a{W^l7( z3*?=LDwM`#A?EKAGAs!GR2gPTK0fUT`N^-?Nq@+!pf{x%p?~~1M}KpANd{a#0_0T3 z?Xa$gXP(Hfk<7fJPp=tr%szuVOP(KelRTwM;)ie|EcvHr+N+db3U zh|$8rGbfsTZ`EvAzX83Xm$tnGW%~h_q)j`=ctxH(`*u!Q6TgoQ{C_E##^i~Wz@wT(oz5H<)yFb zOrbK{tvSa0NyoDTl^e}tL!=*tMn&Cr<&GZft$Mhi&9+hB=A)nXe(WmO@$|4G`A%cq zJ+Wb#n~q!Lrrv>b`^6spkLL!aW$16-l3DH)oSbv79oYX9Mc4VAv!5J#ALqa>*cmUn zA{!I9FJGz8naG`Rj~FABkerZCO!iUWT9TDQ1eYuFDfl>PQ~lFUmK?j?9LFN5$K#s< zl^O+@29xQfxE;$6wKBPB%WMyQU8%TJfz~V-UM)HjHmxtArK@46>A_3)RxvNNssw!g z@3PsztrZik*6P6|Z7$`7o#S^FvwCJiGHCnuO~i)}AD)gu;|d&0_c25$I4$TJNhqpy z=Z^T^B@9+eyJfByFEuz+=AXzS&&*5G%f1xNOR*X?w3_-Dpf@{UkKZ9u6tsJ~>vYVl zjLP7TR9!!0VZdfKNqm%|YhR^-f07_gjK@Ec?mNa$1t|aBHg&1PgKS?eBvFa(kN6E3Ry_u(F?xXR{+^lVlZ*KKLHd2rP@XW_r$Bk_qiy!dY zR$~}4UH3$V&Ts9tsq1K@I6&NmrR3Ra_cnRHT1$jR7%cO%HPi(hv*6u5=A6Rv{?JR5 zFH~;l=c+h-7i1W7<1S~$5G8(40hm~L2YL=*tKRwamXKw5qr&aQ@1Yzb7 z-)12@=ct@kAWF-0?yn;cABqfE?EiS?w%b)JEqijuCl?`Iqz;RxQf8Vl9v-C1qC-=T z{y$-e{V}4Sr#mdW=K_#BHE@w$mz6auQHvKlD6~#hs@d9uven8|nq_%P@ma{Pg%c|Z zvKG|UF12gy)Nt$+kM+gnWSWtS70;-ZK4L*QE2LScq-jy~M)v*NRGT_>Ed>=fT1VUp zRMlveILNl4-wzPjRWcA;FC(j$0=CY(bF>L~3l}~tU1lb2fi*C_ox2IB>^GQbwo1V| zH6-RXg2+e&k9t>EtgcXCmdGi2mOq?>>z%Ew+m=s^M!Zz82s^coY`smxH8lDsTI@gG zGhIZJz74jYlMHpBKpu3Mz(eRwoB4x&tlf@o>$r$pLar2}tq@V%f`|6vfr|zDS+ZLU z%2>4b7#8IOziOM()wsEB!JqW&Xm8w8TEc_9aEMYnHBu(p11-lsS5y`~X^@}x{@ecH z{p&_0&%U{D=D{Zs*Pl&xI#rcu3mtdiq+)dII-(aP1h_X^?TtugofH?GK6V|3aba1O zNz(<2ET?dzV0+~i*3$Llyf-1z0d1C52dF3B_=cJMjLYbU1nDUYB0u?Vfx10a+Id_k zH*DSEL9Q0XiAMt>Zp5ai$4OH%8rfiaU5raM1EgMp%0AWar zMQ^%ZFw1*UDh1UX?oe&=Kp4-y=hm%Tul(C-V+I~59lKDj`(LCc2V`){skzg{M_e8; zXX5&e6!SGVe+}2guQlhaK$9xmxd~J@3$`c>sq9ZgBv0)-(mHc+-5V<{!>gC9gCldo z0-Oi3ueaI%+atj7$g6=U_Y?a;gWe_kXWFQzJ#sZ-)xaWH>epx9Bd&I4-)*~;s8hEs z-l${zl+yIVoXyq=x7X}HBiA^hFVM1S*_U(JUwV!>p*`@yN{Be2J0@QkwIR;&4x%0` zd5Xy@e$FMV`UjWbz#XglU=>>ctbMVW$+uGSFRBDMOsQAL3^sLN0)9H^bnvkv*T+J` z)=lzm1o>1FSPj%fFOkOYN|foWi8jwC0g%vsbx)O9E=24%VU~*fu zd~G-o8B`0V=5CrVOn$bJD{kv{a8DXkC(`aVmh(rifQOjxuyfnanNX{#XKMHVF+* zg7{X`bqFo0pWdmg+##~IwhMS%0zwFD)#ODVNLZeo;MoLyq#Yl-jytK(qmgltVK;AWPYE?alw+&| zI|lZ{u$#%ATKlq{;qXMAJ)LGrxR0VdW0Uuj&9?M@%OK-z*9s#V9*a~q^Q^Kl^`h8E zT-9xya%$!kABmHByxFnh$ibFL%!BCt#*HhBvdy!r$x)k-%qIu$Zs9jTWajc`FOGY! zw>d?LdlUXp_>&gP?T?%eohJL`IwWpgPwm+}tjgrtI&-ewu`9%vP(}+!sO@cQ8-(25 zH!MtDg5Y9JvWI=ve1DW1lFY1YP$9f<_s=W$jl(htC4Oe6r8wl=hqTxo+I*PQ28FIAt%z|GB$zEN}`*ToP@_)Iq_}EGqL>I1#;!O7VL-;N&ogx!6}wc zlGKp^{FyF^>$R0Cr%tWUrLKcy>HZe^%AYYEqfMx9dH^unE&w{2>Jlot-{y2x#C}5F zgR()DK0)PzM4Ps)_S~84aBa-OfjZ~9h{Xb?oGV&HOb>X(ZV+wxC||VEqtig~o*)t$ z*tj((3@97byPj=XL3i;q6Pp-Cwti4&w=sVO1`|-Uq$D27kX{Q9Z84Fkj`%j2Md)$g z_7sAGy3Yt?zb6KA2iN%3BshzDOzZEe2Sb=^W}+j%nCW8H%cjCS_E_D&%z0IX4wv7gP!QYU*kX-%{m6qr zxE3Qtmuk|>!8FLpcgiPy+H#SFD||+h(tNWhevq^0X37LOcrW|0*b*wYw4GO*+#yYV zHKYzlr&SW=qY4L!0YTzFtE~iFwvHITHD~a{K6>M^{dMlxK>>%cwbk!mW1E!<&Yj=- zLN{pm4j*E0G*a$k@*_&9`^Oi(x`TQznnD(>K*L4p_{GzqEKP?Nn@TCWr{e<*zcjw4 zt{^&?Lt`5Dx{V_QApAMiW_&bELp(*we&B+z221#~dqw%KYsfDWe319CXv3%>MimPQ>tZN$4KYx5AZ%r_4j#(ML!;!C zISgNzRtjd;hb1h;FBa%+a~rWE&Q$r;PU@XM?5#H%*SDuLdMR!bU22>a`M$Njs(|vA ztZPn#Ykbp1N^|DA6L&T<9VRmi5|=j+kL0;}$i%vgH=Edyx{vgVTp`+G&}@h6uDTGqj3Ey!!l2*3cO}tN%wlHik&x5UZy9#m9wIi?ZM)P` z0?llU@C$vFshJxUN#|76D=K`X$;a4t(TC6Yj``$G=-2|FrxT(VD| zH?bk{c)4dD1Zg1%Hy}NqI{E<3SWtzB zf0?m>ERWy1Sl(UybceAw`Iu0yU45kPQlxu}+^S~Q?zMhTylxmnBO9~H%`xl zSQ!daq#I-1H{M~V-9UxMlC;dU2&K^7R;?alVylgZ7@$KXAJebHhLL;Jv5#HlwQwLg z4c+sfwh{Id9WMZLXJnP{(hS)wf@XH~=<|hisW04^KG2eOm{S9MW@AsW#w{FDi^wGad`1qh{V!3B($#Eu^R+%h~w#u^Z>d0m?qxZk4Vbnp=rtRjb z%1~Ka>h@Gx?Fu zp>3D4$C81Yk($ibb6x!G43vSnt9H4BruHz2imNJ&Yfv{fsJo7^w$g0{p!?6tI2Ufq zr|+*p2+82el9w0b(Dg;QdwA*6DPYgBUwF{aU#4N#nh!6Kr?Wtc(v2*t}mkMZY49cgs3*O2=59*uA? zZDzR4>q9?eW+6M%&s9exlpxkE2cCDjXcBleHC+_K3?_r+rY3iI>HzkoCwq(kWaIn5 zQr}u%e6Jytx0?1VI@@<#*fbk#(_M8rWHhabp>SppAJ(R=1LxyQ`8gHb4+Sr1D+v9G zlrh%bIAAOuSDZ9;MoUmyiPwCLQme4cEJv(J`hC$Wn=MRk3tn#!jS0OKGFA8P^=piN zv)d)Dr+??D0ojEX{w#gzKk}Q+? z#&zMvT^|iuSG*R<_8+m++Gila_Kg0d*PE_s3n%`9_TmgN9rKFA)wO9QclSn@s>y$@ zb3`7~5*(U0<-g%-w$`jM*_^C4`)VUj$LKw55dGXJRAanGZ>-qZ{r);n%%c=&iaI15 zPv;XitGn^(P2dX)%eym|*f;&*rrznrf}x1Hc6B6&IG-D@VT9hHW!qG;c~>KQLw!NgW})wJ>l>l2?((K@EhC2dPVk45e|UK`!DA;mx_KDvj~j#*cprTL#pz7Q(}_0_W_a(Ke<1ycs$**;>gecRfBPuXJYv-N*iOV+)_PJ1*-Rvc$hB znXc-a=8dsLBNs+St2Qo2vB)!p$NBW$yMp5zc_W?n-_`<`CrzUU;I z$FRW4kadV9C0W<>nee^cF=Ns*#hm^~+~i2@l2uAO&Ak?%IkheF*b?*+m8T~%;N1$( zS)KJGdU|Atrc@FT01u6b!7y6lSQ z`)NBV4jG43^zW@U!CtKwg$ko!rN-S>xSV&_A;rpWfU7#4g&K(#C4Gt8Ur{=2>+zfU z3-r$mWH-&?Uu!0o-CT>8ewcD$cc)dczH;fy7kB;K9Q!W@;COu47)5h(#pgx?X|zxU zy|In;Bcr29x!XWK@mjGDmkPi}W0_d_ssNQ~S`&3}6^J4E?4^b|x>i#!R|?;ABe((# zEvC^B+m>@L!e`oAL4i)+uGzR@@HsIJZ;2<{oiVMyG)6c_9N5_^Cob-)C#ZnTV)7YD z0W+a1l=2zX(Nh2t7#<3Vo#bul>RB+Aq|(zum`X0XQtq^WFoNB4Rqs>dyXTtD-hktv zXQ?!rde2H4o~rDAZo)=#EDBg9Iw-k1-!o+2lanRF_X?w?&I>&?X8B`g)*L%_#vOTj zv8}y3Bv4GZE)_4r&_mYEFf)el2V$F?V{gj=(-?N41*fmgV(_VB=wW2MeT5`(sCA!z zwWCT$Cmx)iFOb|kA1D*PfBo$3zvk5;&AI&WA|-D#s&hx9?=7oc0)O;wRm28(M9>RO zBG2@cRmx{g&fdcb8*DM)&R<}tlQ&t%ie8Cx3U~BS)|X`Jm>(%$1+PjVk7xDh5hkw{ zGWJ1isMG5?JC}b> z3;;rGszNSWf|hN^1S}o%@BuPn`_gx)BPkU@5(bE?>(b(kj+Vsu+<{E@4*k3MJ!a=h zE&ZMdJ@l-iJ~{-EEV4pj+3U9Zhk9yz4OASZLmFiZHe4q*KD}yoqTctG+CGEMOHpoX zPSo699MVv|>tV?w#*c|R9`el92(Os=J3KD0Lj2C`1ZFE0%?Hxw_EKGTe9^#|2Xl5g2*LUu-*(}RdSN{{CHXI$8s(l)WgI;IkLvqZ~ zE_S{nCB^kS?1r|h%+B{ZR@Yk4hVt_Eg2Y7~tq)2W5RnZ~d zJ4|%o7CbBx2iLJZi4cEfQBN2f+bXs$`83JHk8k0nhs`!!U$E zxmG|8QR#6GFi<8?K1m33$7wtWA~-7PR&PMh1=pBlG-o}*h-93;^thAh>NBHb{p%ow z^!UcJ47@q4rFB+T;5?N=CP5wW7&Ny)+QevL1tau>vLLPGx+1mebKN*|Lootzuu$yn zW;adJJ`p?}c1wy`yw365iO$Um3AqdjV`iJ~@d`o(zQ5iv!y)HJ#lBU%G48JyHAbVu zT88UfQ3XqkeYIoFu;NSGFmuhfO{~vL9ZrQa6rwnLYOZ3w>-*;n=wd*Rr)WVqI^}6- z>-P1H;Xe3?Tkp{}wmVd#BZm%+Ym9{D^m9mp6+su!IbZL(AU=tqzc-p>YBWY+f zr05}!a~U}6)nr$@BFjW21lwCv)=emwSm2pS=C64*rN>%@^Ze+4aL*DuxS7y8vJ7+Ciecb4CGdt$TENC#@)~Y<1-v za~Qe#B!b5ne#mWAA2`gaE}Zkip%23y8?_I-s4TL66yP5v+2oSAgEch#x?8iAB9fg%URTSV1v1DfSY z_E_}cHkT8*mzH>Q=iT=spXO*ckz*4T$;doH*s>e(z4S-#auLAgxeR|= z>o=aPE-sSozGk^-bcgQanFMzq%S4tTv(_M$=s_g|b(TgP(lAAoWXm|la{A1n)x=EU zsK)hF+KS+%J1FMOqkvXn@=eE&irW%3d+kr!cHy5t-?Opn&tE0L&m^6Vo&{}B2uT-G zqdaOcTQdd~mA>KP@u{b_8XT%z>A`R`JuSn$K@!%gtp$McK+)mzMR{29BHZ$>GSjQ! zL1f1MXlu$v%&OJazZY>!v!`mr`AiRB(HS9m($Mxot6U#|JPsVI;M($VSeWx@+bgb# zI{hgW)l!@yH!#~|xOZ22`t6Z5jj@DY=|2pP2dv3_6B~hHAKVy3>&9e1rA^7ccJ8p) zx&8}}E2&xuWoT}Q{1AL`G!%-xfYo$EL_MCExAt-(K0#RLCh(`1w@#BM<*}-S*@kFR zN`S%s0L{7q*$Vo$yZ;{Y>=yQ-s@bXti`nlR~iMn4(&Vw)=LWae5`_<19*^ zx`*aD)3fAH&IAvnd*c_#ZHF>4`|b+!IT$%Vah|Xc5EaGAG2YKz68-^JaQj@{cjwz* zU~f|=kk!9foYYPWdAqN`;f0@xQ|E3_w}e?;+$*YAM=1E6{h7&f@>BV%5Ij2@Ld6o0 zz+(JtuYEVCU&mxpnaFkI{@J|0d&|!_Cg(|p{6vWJ~=ppEPaY+{!G~1 z@ZHI~WzqGoXwh|ZOwDtaf=7G2?RmQdr*^&HkIYsN5*3g)^uEX>71MQT`Yf;cwEAgY zSXBkw?UxZaV-JdSRM5q@%p|8REY#)l1P1dLl^KwAK+W{HcNVze`3a+SielZ*%c$*2H+zA%a&vy z4$~x4b$dFO-lVK1aun-WXd0JI3UPoE>vOY(`4{h43Q-U9;s&z1Y$CBS>Y>xY{+K`V z3HBmc=fp3p7rY5bZkP-0_zaPzK^2$Yoo2IaGA_m5%F(|CoNAH#y@lvffxe;7?o^s> znOcyXs|WAImMJKWQ?*+H#Y}XW`kV6u+He3928upbK!N@!dhu!}U263)Z0bT_q-_d+ zI?G8&h1zJH#&l5xLt%iD&kgi#pBD6sLgxcuhp@EDMqKU$BjpCsBrtaCJTURj(tCZb zHJ6=InkE`Brw1vq0EvT)mXJ->{N>A2X5!!b%Z!T#7;r}u2iM)J8Zq<^n$XCK=RAIJ zDGjgsWugxz4PW|po#pB3%s9lsXyTavti4g$K_Imwr$Ox(TBRm~#Mg!-xuEc}~x_v?ymDAd>yb zEx=W$Oh2o;VL{*v=8bXkjZ@D)l8RfK?+8Y{U(|@|%Ak049(7Q(dJLUnb3mD(K?XLn z5!mp1mGi>DmgVH1_VkGZ71*DGndX+6zK{TT4$|P5gk}2LRicBviUEe0MVN`#POIc6 z`J8M7=F0R>i1-ZXDlvK5s zxq1P!%*kpz7AvrMbDTdom7`Wx+sxbZ0x`_^m7*fi?=hdC*=0v}vD3}tiP;pN9Zx9$ zCqavSJ?c`v9~66EU`6a@XI6U0jhW<7<*8RJl7>43T*qslSeL0|PeWc?SS}w=OY7yZ zS+kQ$Hf1*Zp{5+ANes9Yb< zj9vkBzkQ!`k=+dpDTRi$G?TT!s(syA_~WxC0Il7Brxgg7sBNbh^xIAu`#MhtR4p;u zd84EGJ@4mchkt85sVmq|GksJbr$B}6Pox$mBH!P!wsw2f`Zj8gNG#{uH{rcuoN8GT zF8%`mLjpqZ7*$TK*^bRZLSl9odbKR0hhNe0ZR`LhIB-0+4Z-YGF)mK^@PfADnhLJmX0n3~k)DjZJv)1&KO{B2oYC3p$_e zUYyYA;-U#-)LM)eFSTf~+pXDI7cG)X@yN%r=80q<2GOKw%C7X|??wHYHr_hd^sc)2 zQ{;3q91tu@{5(|t6^OqAwE^BBpcX8t(2`{t+m>suXJ4-o(FQHzHGT*)kK9`RkIf#k z9!@SPEYqZbi)r?YG_hJK@y2FcGm)<1X@d{jHOjCFp2Vn}c%Otv#I?>#|AL=?=RSbs z^~d2J8bc0rXT>?F22aLv>^!?zcJ$2-XjWudwCOynTn0RjI631uDXo>}Q7bU)sgDhX zru=$WipJ-phyN$|v@u9+b-r5h_Q;f{S>nRg&iuP`7skEYRG^tUD4|8EwWrjAK6_lw zrIL56zV5jwZ2H?M=68!mCMMwPRVurDRBlr(EX7~5j9-HFu7!nsszIA>U<~f>F!8bN zZ*Mn#QPz@}J7ongLzXU&nG#L9+0uXxWTgLP4bh>3))2#HFr40=Ye|q(DTLAQVcmVZ zXIxJg$&ZB+^HHche4mYtZA-qcHGI*>pf$cXp&K>7+SaL0w`h}6d6gSI^$Ny|9d1kw zj{yM=&4*inl?R<*gCi{A1*|8V$J@lLYm|xAW{iTfil$n-YfIQ`Gm~!G|0%YM=Ra%? zKnPE>r`N<+3D6C~dRVm*z4T4D#cCu^j}|_yS&g`fql2aa)Y;Dq5UvdLN$j2<$7b6p#0F9l-jej)A*sZnDW&uB?Czpcm zB_&D4i6pQ#inBdm1G-VP;9J`H*PQ3KFBJT$J>NM=dT0xix-79#geqH$Iiy*mVbmI- z=m}p9Gc#Uod-T-HDyzCQW9|$mCrL;yuYIbBH1^z?TC&0ueI?w#eWm+IoFr!Y3GaJ9 zKR?AmMjZnKHE@QwTW)DM#)j?T*Y1(UoG|G2+bU{ZLA^8j#p2ub0K@jwXHLFu4y`(; zHuKNlEck$xRT}U6WA+pH%aMFain8LxFoaNp?yJLxo83|dtEHV-YyuAG9*@rQ+>#cpfHn%V&n&U?dcy1LMgqiR`NO_*z4 zivFwyyvu{$PWFHAAG#dsGHir9tn8`hn}&OHsar^rEeyMhVD{e8V0-#?XMA1k%pXpa zn+5*8Ua|6tjf;E5 zG9tD7{_Sk0w8KHd1i!1zATAp_1 zfAMAaPqpHOjoUoeFqz=vz~bB@ST%$GiJ-uO1VdN9H?f1uKW|>@PHW6meF%G-)l)*g z^si#C0ub~*lf-)GWF}wDyLm6RTDV+^?-h2O_O0v(+hrAy3jkkvKAqOd%&Eksx9qeB zUPo7AK*>mHRcc7v>HqMJ04-3y2((R0K&@$@GuF5;MA}|=PuN)iR#?3h(daenQSaZ| zuhM_dImPA&cBg;7JG0_|67;{{n8Smez_aroQoTJ%lEiUI?*yDT2;Q?cXnS$V-psLI z^ZK=GT3iX;ME@O2S#BNk*n&mxoN}N2htGqmoI$o{Jkg&;h}j6bpb#?>rOBqHmY|bc zuvmCe0%Q-U<(ZfD?`ZokpGWo7sZ$yDROcAy4{g+yPQmqIJWk!~b7lr|<6X(qHXYs) zHOnMgPv-mIySEn_?9p2^VvZ0(r|SAj+Y^V_RkD`v6*{tYJRd&fi*dUvrJ(DMD!v5; zU++QYw?6yu54XS@KW`2E1~Kbp%|^uLY2R&Q)i2)k3cGk<0J~VWf>=pR#=-~;v(~n^ zA^L$u&P~dAV@pquQp;mV5c(f5N3Gaf!k33TT^*r#!CnIPAOA!?!X{p+aH`cR@its)h$%~YeXw?PsdoKRnpp$OG`psqR^i$jgV?CL zaxDRj;~b?0N21x7`a0iF)fCW zutG)gQxL6=B%S>WW;=pF6ehZ@ zP4A{raWZt<{l6Z+Oe59~Qk28?44wOAyw`M;a61bLAPw;v*OT!D%CohgkaFw#ps7VE zR{!m?nCgxEsWVAFpqTfVeD73<$;;L{;Wq)c;)5CTnl_wOWrPC%DI0q zM8@={TdainnJjO#kMKW!5o|2O`Pbdov@}>d@%%Ynr+D*p>QnHhRVXD6SATFwc=I6L%9 zV14;#Jk>M=)NfXM%8TSGcHNVxQI%C@89)p_Q!7yEyYg^WC-p&Wno*F9K2h#^0>^KD&ygbGgFjF~rSMcYt!kQ$4KlzZ7XrNJ6CuOFev5b}!2J-wh zsrk*`%854}GHK@?@KTS1c7uD|Y-4KVOv$JnvF;`XpzSWg)FNfKJJNIl3Wo{2hpS`N zdEgs0<=6^33zcsD$EEixOmst?34Wv^B_72h{H@o7d}S5ob1w@oTaEB6EF5z0MdcsS z&1_h%p~*jP*rwbmC~vTWjhq*ed2D7kn!#_f{@ZBb*HIzJ(>B;sqAvp4!Z#PYNo0nZ zgGNL(UR3S=>(};aheD+Mbh9i}frC=M4Ymnx(x2o7B2!OR>PpyrTAuuCmVX^ zYgqW@f;N1$$?<911|zKBr2WZ>fvdR`@3mq#u8j>c(`|kElkfIgng^rU!i+6e#>9t@ zM~~m6ZQp(R+tBDY&X>JI(o(QxFOJz6G!fw&RqScRQMk69UMNc@)shMqFzWyh0R(Hv zbjiuspu9X8yD*FQJ|)Zk+2w9skGPVE3aG2?DZjF)V_;h1iJ`o%jLGtRm;&g0_{Aq$ z-z7+?bn+7A9}e8zub01Q&e~Y#XKh{`t!Ay)B&RAP^tQ>?%1%XMfh@-SCU%W5k{~b0 z1mW;)B9J(+G(ig!UgY?bb1R%>EaqithY56BLEA#cNi07NKQcTRlkYLIEat7I5RhVWJHBosp}Ab*nbwWKQRgcivM!s;1^M_UfcXn1N3E*=5d$=KU%| zuO6k;yg7KUdu-%VuT`P)$Q5Ms#=qM0Uj(yGee$+1IHQ)d3#eM8<>Vhx2^#Bk|vX{~BMb?D=i^XoRx_i8L^Ro((w)m29Ip~8YqTzm0qvHah zLd=z$`sfD((hfl!&Kf$tb;KCOqbLl^{&p0P1k?O0$o(}?$e!GTxSapEIA^Fqk5qmB zdUq|58c=7&HcTrZOaC?|`T89;c}Y{7pM@akJMFXkg*jcMUpG|J#pc(Q&SJq4CnIm@ z!a%nbiSiT)@;ns`J2;c6|Btrsj;Ff)|35?}O_CzCq!JQEW-5fN$jm5ZWM|JKQrRIR zJA3cFjtCjqLL6ir^Vm+#anAW&=Sb^zf5!d!{_a2Pq1*MouIqKZ#&d+Iu5;L+6N{~Y z31w`D2Edo8Ov!cN|6p0BfEwHlrrhwmSD7w1B<;8k@)>1LyI9G)vXjt%#@RmhRvD=HMOuMLWlW)7v7= zoE{{!Iqy6$fPcX1!@wUL1;yDZp*#1|aet&*1{JxxVBkfS>=W;{`+awj9DEMk1x&%e z`zI@ED@S#0UiZZ7h?WD!1hJ9hPrG?gFrZD7QeGah|2Xe;VDB3XRD?dEAI=kmJqSvX z#{uof7my)YWFlV0;vK3u_^oFNldkJeVWp8FEW2H7*4TXkG}88I+fyQraS|26n0Apw zPCm_oX0Gndt!+V(47+?g-CHYTD5Iew2;sDBIcTu=N)(gUw`StBrgf-3+F682Gx-Lk zi$zb6I4ry8;{D>bYFz2zcoaRaSq$Nf^$E3Ph-W3zmuB3FaYjmB&@8z601Mzvs(z~# zfcmV;2%7GVt*w5ZckJx!j-cnKwEJ=&QwUaoVi-AC(NFL{vjdM+pA|e{Zu!!=Uj&zu zK4$>_a%&_ejFNV;Nmf{zKN`B^LHK`aDMlS2T%fmb*$U@pni_@N7hb#9dMmLJ(0S*k zhI+uS4?u8*!mCGv;7+@Ot`rLbQE-P!3B^lNvnuzJ*z01g`!Zp;^vE7|KsF*K zLr3!wbIu8HR)HMULC8r+sW@?Zd0iN&RIs=j{OD_?F`PIqA;>E1`YTdH4y6CAK% zV}AnpAnucJ~dWWrs%Fd%W$im2~+OKJN!1AWxUD>d(7H+d(JmgknRMgBn`5hy?~ zues`LvG_v6(qZU|c}KJucJGHw;6Zu!35Y!r8%cH}9xOyeJ`h67bB(&;$5qsPz+$5L z9cTg7S*>oCVQQYw;+?IyB0|R)yXs{xn7)}_6 z|C|JWH}yR8Dgvv5gyXqWPZQIhr$hn4O-#ej6jgKmv_c)A-!|XWI|12A$RGlZM`zFA zt-|ip6=kAbJ*e^Apl4y&llhoj(1%gaL^bu?x~$-l^Mz?ze+}`3`E}n}O>&)6|{TJ<>o(4_t11-PePqCi3U3Feq^Sz`^ zfE)wy^_5SFL1_*hLSe>UQRL~rPla1<+;|iO`A?SvoC{56kWa>80EFU~S!CG54n!Dq z5`;ei;Bw{Qe5qA>GU#?Rvq`zHFC!FGRaI9iq<_@ZzxQ9SE?&@&M|A=m#LFIMpgK%w zSp1efP|ZS|L|KYjVh{OqJel(jEpV4{KBh_|LfQ!GqMYi;TZ+nrmVZg|^0>s8%Z6l_ zvPU#=Dc{<}{ewE`x63gW8=2l-Zs~A%$jG;Y6Vc_r-HQqUcW zP9F9Edt#4>w7DMqbePFh;lY%I&fZYGaF=x>1?8%qNu;8@Mu`r=%cbKPn&CEHom zz@Ksj-SKLJN0(%d7k9{sX5DEityQM;eK+|bifos{@<80sxj7(uHu*>D`+@bxP2AF) z%Y6_5zFk|2yn4{Q~&UW4| z!^B(HyMy?5g0-K3ClC2_&EI}E(Y!y*2wTY;qPc!)N$tK+tee`w`>SUYFkjby(gytp zwkG2vLBc>>Cjs?A;D=7*TcH-2&HUJpTxn(>lTbtujvD~)WqNI_lEqh!(9){=QG6b4 z_Hb&D8_|+O4F1#o&nDq3NSH=KPfJemV&IF)mX0^OX$u3JWW+ToSzhDW*+0)NaX>D- zZ)L~zah@be%^ct)Y_mv=v-lpaq^7ehL6}ND^wVxWr=qrokA_p8Kj}C>r;@hges_)m zK@H9WTbd=(XZ50fJjE3^tWHKKx z0U#2%Ug=*l>HjP&xze5B(dtbVCsUtkc6JYSAlpf`Dw=|AGIy4nE84tfkQXPX*)fn{f~12k10 zBRob9zbhFlW%}CbV(*70YZG$|l(5fG8RWmbPu+ZH8#XxOt_L zRgv#vK+-KYh^T2(xKK_Gv-tOrwv^i~>w^Kn5lPZ~=+wU412Xx`H~P=BsPy^W%xIdc zq5OVW&C!;n1$<2F(`Ss|9$t@@DNKST{fFl?(FdGU4(M7F!Lth#7(mlY04caZFdf@^ zC4W;eEc8$oIb9LGlQc%Se62~0WZ~m%NHT!Zr`KaIeC1e+p0+B8=w}C{VBOyvP-I-! z4?>>Z=WS@AJP09yKE+w9P=D~5HFP){I)1NapERD(4K{#L8=-zFavx-K%Ez8~Q#@suvMWDB*s z7)kbmSWqlJaoPp^s_J^}yJt`zNxwXuPWw1B<@29@VQ)etsCj)XeI@A_=q;5&VSg*^ z`rCV!D-YoY+4~Yf18COqm;MJ3-- z?@%SVqJ93U+!LYOVGOppnzx1hBykSs=4VRiq$(PR+!&3yUW51q7&=Kl^gOwkD}O5{ z`tLJ8@YS;>zm;AfG5b8kfNWf93H}IImz;VumT)Py^0+&h?P9hu3`!#Rj!YOS<1&4P zdMWyb)wnM>=#bky(>AA9`2#`~BjVZe#1tE#rzbjmx!&945mf2^Y$pBntou7Mc7t~4 zhRw~QAoG#vSQ*5)<MS7>?oN8JvpD3S{b8Z6OoFs zFC6g+NVU?1-FPopo`Fv0knRpi20U(E*zR3@@1H@-KQ&sX#6E%*D#)mWQi1%O)rN3C zuJg&kcBBlse-KPw^*)?vL^+XEfWc7TM-miH{NoF|{6dVZD_dqB&%c z61TzQux4Z(J#`%|(6w#j*oZpIRm@%(Xe&W&=XR021|7&h=0MN(wWWN7W5tY8CXmir zL(FDR`=&k`?he3h%;OJ%#{TO=$(e*o`KdgM7>=GZZ3)$=9gU{{-U}hnFg7b^fQ~v6 zXw!j)U3EGCIg`WjMaqX()b@X@q2FPq*|seYypK?>@s*pMTU_{ zWY9a6b@KLgLQS$~t0oy6X%Sy(97r8v!N~OAV1ap;AHVzO4gqf$nIW_1gSZ7Q^qEuZ zeI7Ir9W4j!2i350M_ShP=Oo)Lk{{f?vWoez$$>7?82d5Pj6(O7+oM<0H+sNW<4c(h zM_H@oDIj$C?;n+IqsNI|lhyB-@7a*ds$XZ`C95DhW}-`@r}=J#^Pbj(ugdCK5sMqH zEnt50Fo9np*_XJfoQSxkl6y;9LnZl`$UUjaW@q8}38EC_FPH96B7|3OnUl`~X~XoUidS=nk`58R@0qHe0wf9nJIM6uvem|54u_drY%~`Ke)g(+Y7N+Iel!=$L1= z;|Hd&+`ra2bP|YmcDw=5&Rgn{z_Fe?r;VZ|+f*pqMnL-CKT6gvm4s*Vl-9u6hk|u% zWBes2XiY)I?@cp*CZ?1?lKEI08JPc=49|b2m6Y$B#G_8`KgS>9Dx}&;#~h}5%V>eE za8A+&WFG_Pg$q~%^uFUpV7e7w)y-iVBP*2gYLLPV^Nc!ulA8Nq*2c+-Xt7@_?9<}{ zG8exDpTKvgZ3rTO_R#ThSP-jnE{1Z?rtsKbCDwDL%lFWMF9e7tUkgC|AWh)B4Mu*Wuisx3Lmp7!;V)_4y(^c z>HN*MQ6S_SpgADGnuI(AqAfYhc)^YPGh~ZdV2Glqq*RCGxE)Va4ErZ(9zj+8_Uk@} z6$_;*O6qP3V$;g*&ur%qusuY4!~{cZXS-DCEN7BIT0Lg4^0{9x)-}4cY3L=B zRt)e&R9lKx(`#!xWI5dSz;K-ql-6fZdAYK$ua_^q1U-!3YLQ-qd6#Pj;q9<)xs0|b z6IBFa&w`7VI)EP|AF;t>K61-i>%obCd^@QKAhXSmGB9EKqoe#Yik50M(MlzMN`Bns z*vw}w7hQ zeEa7fwmE+gn0~|KZ@>4bNCoDAXNOMP(P@EvmoL5-9~Lcp0hItmg)AG1S^H9VSKRyw zDM-Y%vP&0m75K%Zd@H=U{qmSY@K};&zfvJ^kd%qIdwm|d;!$Aqsf9y`h1_q;+eNd| znBebZ-}$=IDfZ4J+)Ed+7T*mo%jqZdlK;p?3Dhf!)28Li%&cSN9@8#_>FcY3KN2>a zzF=x-DZb=aqlj`Ge-59jx(uRWE;QJH_j9cG-au?un(d?@ z_j9au6v3?2_{D0n7Bl92&U}SMbVtc@wD>%v*cw}x4B<`CPAp(YLMHcbbE01(%;BHm z=1W69aAi@Z^(Men0&|Q9jC567J&-N+1~5Y&`>mx41O4|}!P2}~t;@wuI;nnov+Np8peWvz;Gq{Gkf>mR8g2aXGgVRs_H9j$s_ zlU~0u4fu|S%tAc|ZXmC=me5Jec&r5B>YgnxFs~_?*DSiYj>^-^w^ESZ~(2RXTt zfnFDAwB9DP*|(Z|uDpJPu|XjIA-JH$0H(&fZrYpupxrpZFAs#XZ5=*-OWixpLsIM4 zpFWLN|7AdL5O4J zs6a5h2&|d+Nv+`u5;&ie$mQ5!WatDg3SU^?$_$VjJW%;VPG(5QmHp4eWt^%!g+z9M z<}T>s$N$>Un*xdhUWKBFwJNhzeNF@?^KC+o{~H@2v?n163i@_e1mI4I^ZD1!UccAmlaVqv^>XhyS0B9T$Ml-AS6Vr)97dG|s0tTvB4 z+E_mbyQYHVj+cA=B%#xsRnwd>3j{~(RNlk~_%S&+x!L=Xgq3!dXf@JdP|(C^WJNxD z9DQP&tTxOtqMjf;-Cew|ef?h2@>24*q~xAbmni!}14SH|!kz#+ey%^r#KWo^-&eTWOdkk&jcSLOFF?ghGHU{O*XMy54uF~IMLPut zb7-|7S&sY{>*QFQ`UK3*RR`nv%kY+e=?xL{$IX@gNn%=&={c#O@~)LNLo7oZ9BUrH zjHGZ$=ts%5I=iuvT!OCf+9TkoxRIg7PNw!;wwLO$JFEY5tW$Xv4QRx(0lsj|{vKASw^yhPgl{QS4a2j6bj2%A+?|GO9XO>1%}GN%;PaCaBueJ7{A`4PaDnt= zXc8lKrvj?dP5B9ZIkgG^1HzD*`=j4n#(#|n^MUqjz zS1ZJI#d*iB{rLbGbt-82TSq{FrOnX2&jTfuogKW3vgQ^|IV&GJeNyD(#0b(_jZho{ z+JS=MvB|w}ytS~?%0LIeeN#vmuz8HJem8Q;0c~Wq)CBlJFt0d#b*JsU#^i-o^}yPd zfV168^mX{LJ?iRLlNeA#Hy@*hq#xT1J;*81LnSu{%IM}lA+X7BN#H99pE4%;SbS@} z5j|o~R#0j6ZRhY>GNgEJ{jB`^W{w)nitc#j`=Bh=;>VsP8fDoSO3%l#f`lKxZZHnx zIvfEhcBtkh=q&-mXq30 zxDzGt7BI^hoxgqEGL!h(U3L=}Bn=Oru`Z6LW#0c3vv&v3f&pDS(Er*Lc>k?ikf08^ z4^P>_`t2Hpi-P@%Hj3s9NMKw5<&dRV`pD?gv?uZOML{KC73c zfxBVtAly7;-%JIeVf}0p5BeYqL$A7$kPE26mrUZIU=XdU7~iEo`AYtC9F#^OsWlh5 zH~I55ERKcSdU5}nf3(Om@htR@p1|;-s`n?b@*#8_#GcP*M|l8U_J?_bh+hCuN|jCy zgn4w?fg*q*Ig9j9ToaExd(*geu7`WGL;2yfiyH!{mFpr(B7rpXL`!57l84|DAPGz+ z2%;u6r(FW$+?fF+t*v#hEm=000!krHyIgs!!Qa_D5Cs;cCyFuwIwd=|2P^%}^LOlv zpUQQH<+JiV&vee&44X-Po4ICo#)@9RpYK4pOolj3UjKT6%~#eH;dza0vMMen&6p{R zBX?o1dXtXw+8*@@=XIZG(Yn>C_X*&B4#(AbCsDHuc}TiCXbRUh3W<~;ww7j#fLHT-S-& z+(2|S!df#Noo*Io0tFI4@%(*m_AhcHZt1=u+!*4je_@vGI${T*`lU8(huNz}z<4sN@ zI$Tm%&%?~P$~5Gjv%M$*f=EFAdCL{5&rWe^XtYMNaH3%~G8pg;SJi0SMq95Gjlte> z>E&V;8o`;09l4uI8gparWj{<}t6O?WrPOA=WmD_>&B3NQqU*%gc>;*wh~EY|wDFLm zUPpRCy#1HY2sP_hcaKd~DB>&=w1J1+Zt`>>d4`fur>KTmfXJraAm+7FhN?J+Z=^Py zTu#cRW=Sg_xzl!XAzXe@cJV7qbbDB&X?Cn^+ij|>r9G0#<}D{mOWwz=)Q9o3L9s~K zl(;a48QYJ7-o~$0Fex_qLDwkJY{QbQph`tlSbEhwoEVN!@oqGQuTpy0JnS@(JtCMP{4;0=GF1U)NVaf9ft!DVfim*96b4R9!1{wJiByGLlXo zYD#^Zb_NVUZu~T1?T)PX5beLXo&`pg6eH0ig%dUDWw?Ee0=>m5hgk)_3&)4w+8XS+ zjf2Ne5Ezq0IBN!9RINq|-~J`y{N;pfJL>xv!U4XQ$g9F4({4rV@3iUsKEsnehak3&W2gED@)r&+AR@Eli^&VzZwAG(dewOd`8%yX;ey*D7^$qRn)gR`KWbf;mp`DgVxSA(#B6Z>~@#IrZ)jvKO=8LWce4u{MlDDeZ$5k zkBHK41A^6kbDg39q`v7ORe}u@`w@MTfGf!CrojLZAMYg^4E#u@4?+S1f2(!=+Z#!c z*GsHT6EnuB`60&1%2aS=YiwPG_*>RYIiY-hpGtjV?280%58)r|E0n#sYU1GX^hL`f zlnx6K-TdSIZ34MU*OP&rshxJ$x{YAGA{%MI*q8B1hll;jq{z(Y3>}oeNoMJE>ZZv6 z46yLG_K)j9HJNp0|5s;CMq9w!BzmFAgVp~~Rr<9p^|z>OVl#PrwFS5Hix+H~Z=_;+ zFe>k4mTTznB1Hqs#fBv^56}W@bVaYguj%h>VZ~OcbJ4G0vITiMmZOP32);HdEg#K^j3EpSf1}SHU(IB{?>2_{u z;#ei|(pDYB*SvIb+*A0K0@I3@aHUO%-S=nhR{P_&*-wgKNV5wGst10pk8u$Z$APXi zO_|ftNpo;vu3#7apmz>N9lm1tIUcy3=k+Ji|9IX)04SgX*tW|m-!~VnZmkCLtuO`9 zd&%ICEitYU8$mq0_;TKzH&Chk6b}O0t z?U6fEY6NJX8Fj|V;J_7pInv=KUDmPiwI&5H^5Ehsz4dnMOXCCwETBUd18RZ05)u*v zXc5AuY>qHOg`q+~g#9()?s4fhXEQ?C)&(Td_s0ms=52dK+wuvv7q0xl)_I+3+dW!q zmwqnk8$9}nf?qobV&zn0cC%MZI5iZCgdFa8GGSMQsS6v3Al1zn_&#tl*MX-Zb~t!F z9>9<70h!X$DJda+L%FD%+x}b0XGJ-=DifxwK8?Tk9|B@^~m^N)@m#?-H z$9bXnAuZw^mx_ptxm8AZukl^x$z@*07O~Pr-Elo*&-Isv^W7gD6!=LPIG7i&AwHuoU28i-` z!NvvvAUnH8RVBdfCb77OC_~A8?La5V57X`c`CYc9$qKV%toAhbG@QZu!0Qe?h^*&l zGHzsy8%Zo<^vw(*qEk1o&dv16T+?M;dt;m<-`#Z^nQu~cUtLN0CKu(4+;mM7`65H| zKt|j`yL66&qt!m1z3!S7m=}f~&e{~9{lOOc%WU^AfjL^L3;KZ+;O~eKyzFhjgqk1H zka2sal3>LFK_i*41d=izt!e>3zsj~CL8V%^R;%pKzn&Zs33loid*9VqOl05Hx^Vm$ zPfIE536ygfVeGS*yxJ|aRHW2@!#>+UIgHmlwm=AUdp5Z|n?xLtr~R0)we2ru+(3ISFT-TU0>hLC<1qUS%E_rC*YeH2R!?3976Y3+kxiifuY!!f zHFo||O@W3AJ21KY-p;!9@K3NDXo9<`FHTpAWvEghgB=+4dU)KQFMk`hnCsKQuV*=n z&+U?KePtdj#I*U^Rg~viuvBnbBr@X@q##`%gpSw(5BAcM{>wl#Y@p-G@zq&)^i`wY zgFUpPvjk`v08VX%=ASx<|MQDYznE&*>Yollr3v4!$uy-pk64`8>6e2To}Mvn_~qAi zn(fbZA3QER7_bab6Es=u>S7hTMzLS6bvHq6DqoB1)OkPP*NMOaq!M%rkY;P<(%F3@18WtYjnm-1E6&@G8DdrsuG#vAsbl&q~K=~g(V$4~coz*V(hkIFVw4XX*EZ+mm`VV} zw%y6oac4R#8t>tujlnKDw|@0~}$f)H&M2?%?z#V58MpZuky7@%}v zDePP^fhYGjDzA^L`u-agr&Q{!)H2LaV1@%rx}ocXJRZ5|MXwa>Fy~5jj0hO9H8{gB z05ydoZoP|T&b_yzfgTm$X6gIhq@>NwjjE1^sC=>5z3P}v&x$)=%A+q$ z8RZzJNzeVt*Y~&tbf_$3uF0Qmv|I-R_*+l8jE71CHKN!7%jX}QRiNf=`)!=_9zm7m zqXChj3u>tk(%ZZwJ6JRc@_~B%`@Pj$Id&u-R;VYTPPQ97s5GV!e+u&C%blaraILVL zH}`1i4hT7UABu*W*fStAjT2*UT_b=eO-R1_1l}&Vu#xU>}GoB?wkS~Ai&i9 zZ(n!dVa4;gBh+NaWJ16_Fd-PGcuvG<{G9#$=tUAjCGVmqIJ%&&Hy+?~p1PtdR6x)B zB5Yz+Z(Pua2@oofJ43m2=vJc@n%5R;Kqm{x^?81^Sig4Y?2p^{wR>cQcdEr#i)3N- z-D&+taZ!M3Bj>mA35GcTr9DBax)2}A?J?KvpE8>M0j4sQ#aFjaBOp6N;va6PDgcRJ z%Ao7?+1WfOnl$)jKZ)GJ-$FHrPG{DOsmlwh=9j}0&67mT`x7K_@SnIy& zPm&Hf-+-I*C$asxXR0bKf^#G9KK>Trvyvu^y9TuU2#pTs&>v^`1@ul-#EHS$5haKt zD^G}wFkT?iU?5bcz|^#&und1`8f9h!k_k)WHeX$#wY?R5X4=&_ZVZp{Lx+A~3xAsR>O*O{=-gRxWAV5uvmX~$@U@uX#~D*M^YZ4hO5==H3` zg=Lnc#7dE5=loicKytHs|h_FB`Cd#}2>^*zH zko|Jt_>3A(Ar#E_K4~3)vSD78fswugQYkD;ICLzVDZUk`eu5dxO6#)%L$J&vz%vBC z2-v9Sg)nP2lYyq1PjbdR!zh-9hIh7he3psqb^2nbgSIRzi@ZaJ0OHDz$AyZL=jJdd zuYb0a3#7wkSxR7)?=|`2w15zf{l6~mR2C&A46Xg8+e_z*pU;(d*i=(Z^JYy@RWy%P9{JPCFj zHZOp32(5APa$V`458e z%R`W%IAt&KyG10F2J`%!SvUXPw%$y)T{WtIMsX^O}JE zqAv}oQ~J~UjFhvIIV(|9g%pVN37?|8nV0S>fa*$UyyEPfS|Z5$kW4i%+GpH$b-pVX z;N#VXuo-l{IwH7!X71Cc1PyqZf@)7@euae|A22+0vYSd+sV#yTFRmBmFC>vw*$Ux$ zn)IuN)Y{T_g>}B5wYS%um^>9GRN3plc=`yzSSbeM)1rPWl1^4yQYJ73aKltfEKl<% zrkuheZV>?P-%IVE8sh)DC;r+| zS0rwUD1IqWynFXXZEbBn(5z4cnpU5pg`>gXS}ITXQ|we{QfF6+f&p;)<2D)Km6B{| zZA}7-CG9aHZu-Mj&$<9RsS)e|kX%#2RPof5=LOWCEW{f z8cCV?NF1uV>V3L*h_@wpX{`h6RjGzw*@gEGnzWB@fNC+^3`u80_rZjEXQ~b?B`sxs z%!*rI?0lI_D5#6-@*%~5-VUVuXpM&|BY|4q4WN`551`%cz-ZH8yfG->as8;{nQ=>p;^QdKkUaWAdl zS6EnH0!PQ|#$WQ^1+%H&?M#%O>eGuZu$_3TNBVeSu88H8lQl1JwcN*ZYYb-Ev2N-d zo?5mXJ<{1Y9<9ud$C#RGj|=gvI9Xq0eP0`J9$0dtdHb^XO1Z=9kg{-z*WvXkBWs8= zM*kr50kAC(K|_N%x)+Z*+HW)Cq*YZ`QGzTZg-t&#YR+I{$6#0ts$N4t$njhDAx@5~ zl4ksX>8Ob7EGLNcA4O~ewmC&0mOqsf)ynBESv_{GO8m%r?m>}-RMDZlWUPyM`f~(9 zBQp_6np|HpXnf#IL>WJ$NwW#{nVY)CvHRVWR*`-Pcz5{1|vOPf3(d{Y@@rt^>S<>IOb`QjJi~AnWVeB@%kYjT!e-tI- zLR7X`Oy)^6XvWTyu;OY9_`aiPhVfuA4*^?D%71kAxn zha)Sz;x31ui8`JSB*ciWObPWDfH;2F^nKAXPGP3Lr4>#0(S|+l zEB#_RlLtN_+DxMv#qm~94s;fOfBW+K#$w64o^J_Vxrp0OIvlhW$Cex8DxQL$b~fNd ziay~tpz4RS*+}E~ju4|C z!Qbwx9=snd!}d-{LFsOmL~WPFjUb~QN83Xcm(pK_?N_}ey^|vrv2;XkR5EHx>$V>% zOu}z9LgoMvYIm?d+yRFp?z)*+Ol4+TOt!Fds18JN0UR-R;IvJID34`?_$uGwyYMv& z*7Nava}#&x3N2Fgx%eBe%!QPW!1_7zaPUK3_Sn|BBP1c*4(CGb2l@mgkqoU0`2J|` z%af)D+GE1!bB}7mNGfcXKOJ$ytzD|XnhJZqf_i{Uj2H6q#~)7U84%4gF$|&-jAo#x znM{pS2y7r=-6p~8i(~-zR${jDFgdkn>{CyQu1GeTfy)xf;%WfnrYY|?poEW;yEvUW zH9&;faS;Sde)f@#jr$_32cQRn;7}f*<@K_5A_^XNS(fi@dn(arkQs|1xO}=e>%JCZ z$}^5A5?)p5){}ATk0Tu}M1-3UMuIZ7qzOd%Hl~ZmmME1v+G7&$Ez|7O&0cwJ- zC|HM|$d+=JA&p7w%pRYu^j63|YoAo66sIKDj`-K}bWFQ7@HLm7#$CJLX}* zcGHuBZH6b|(Pb{kxogqLsl@`9q_MKH(w0Q^rxWcykw;Vp+RTNzXXKcNYWLXo zqGO;#UOv6RN>U0ApQMX|U#&EAgg5O@v{di^4 zl^be;%zcIHusaEVqu?IA(8aKjIiLM1b1s|PQ{#!(xa^!K2r?%e0H$V+w%%OhCA0h! ztBbkC0NZ-5z#_O-9&kg>S(P1D?@HT1rB47_W*puzw(rdJx*Ugi>EIB&8fQN!7&%!Z z1rtZ$SNV_7R$3i%T8wO(OlzXDoB#T9O5fSJ@dFO2#-LV5kQPMsmss$u&Txl2rDv&k ztpRWXCf*a&I`2=reD91ik{A&U*S5hXfBFZjIGrRVC>W3O^##w*2n zPOX1!nreU6#I}z7>MR=Ug3@MU9=b)JZl?lfNa08NMo*iD;tYeEshEXNih2+Zyg^qaB#7+W!t26W z=UD;H6CsSqemBPH&Pcj7q>K+xY1I?+ODK#}mY<52ut3 z)i&Djj4KM-D^b|OoGcGwdv;Vz6}3vg6E45he*><{*$1D$Q!U{%NTEqu9!g%-TXyCG zZopji_?4iT{+v*p;`+R=u+_OlL;lR{;ska7D;)GnE$uJgoKw4|)qVUP6l&DA$KK?d zn7y=yl+&Ki@~~s{$@u2Gjo}qZ8KCrhOx}#D28KCw)#2OQl zr-6^F-PIH>Mb_%?J)LrRDO@~7efZkzc?Mpez&YV&v^w7=MH9GxuZ5OZVLR}{BS<-!81VX=zkr%1w_hgU1k8ft`)D1Sl*INih^wm+brgdh=zKb zip?v&)2R-I`H18uXwUh+R?2HTrb>|<9R&=uIhP}7GoM_8Ee%v0uD@a&k~@>QOJ>Q!wO^ch zE;ujuK3{UD346D(*6o7+mduUi-XMPp^3K{f)?>R^|i2ODa1+=hbtA{8WSCQNb}Ynnf) zvQ*>jUO@C;xB>Z!kw{(9z_UkkvMPiuZw(A})(R)ydBAV+XquNJ0(+Si)Av@;>Rxr> zS$}8T|2mF+J?j(D0gTMvYu+hTh$K7uVk3z-@L&R8`McQ6K}bcMuL$b1K2Y4ob#_gc zpL*cr{^dXsUIp!~6_E?E)ms)%BdZb+TN^$4^d;cY4^?n-tY2$4aAAhvN=9#JzF2lC z-4UY!*-!{)o-Lhv7Pw*iq(DQ=inXlUP~k)NbCW57Xyi2COFGMNYL?;JK`e6W8D+}U z>)I}(Nh+yIL!pOnnTJ!v&!?3QS%s_I*r8W`$BwI~{dFI`e(!(}cexoCzn0qGPyhrD zgaFjy^Fh;jO}@+a+~6JICAoA?Q==qczWH^-=*H8ABVpW6&yQP$)3adrO$vn9-E$7U zsF587Z}~qtx$wnPB#eUgUFfHhEI`(TD0(6!2HL4x(u4L0|C1cz4u;3ctBz|DF}O@# z6eQU)Od&Q9@7*p1rB_Fpg;_e-AxD_gmDA?#ruLWet!KV6G0F?YeR=ZWR0geRNz%AL zX;Jrv?S&yca$=c{?rONy0b${K|9Z8S1Qs=#vkP}#uFr-hQWLwl-1YC6rNH|Nggk6N z#N7`BBP6F88R7^jZG)vqK;!=;z}BacB_qjf*Jf3FmWD9%FjGZq1tLMz4wBxCrxq+haM&X`0ZkK5*28q=#Yzt?G3`jWET49+zuPT?Bl-psB%XiUG z{5-xLw$a3s@_w|2&}@h^tByR+nDv|*t8$?}wEt!7PII9*Ss$Z*SbIV*7s(JD&X9rQ~7}RaalwqHgaASub4l}#rh!J za_Lc;-HM7=H5sF^P*3die9Nhah_7kAoYE|t^T}X0X6E!)v@amvK$>MF&T^>*2YfF6 zK?j$>K>FeRRbm@kY0GCld(^?aj}>U70io;8Q}~n*lC}?G{b+wZGgFrz>*N=SQMy2% z9WSE6%Ife+9Tt9*!c)vjd6gJ_SLUZ-4?NvndGzGB!?nPNC;$RUqvTiejoi30Uz9VjVnHm)oGH=}T0%{hSY}&BM-8VKj^^n8BK}ee47|=Bav(`&i(s!oKF@&~!#>28=^8XXe z)@v^wP4JJ73DXdim2>L%lVqc}K%ojrL+M#eVNKRHUW|x-I-&3rkk8l|r`f9_?Rq18_N6tBQb-Fb zNVt{Ojhcxw&~ytv5I2Bs$;y%>^Gig_zFQE1Y-hp#_muxDSc;5#b=-_FU=eZKxzePC z3t%r9qXL8rg-7QB@+08lG?#*tHEx6!79-|ErwSWOZB-%@*%$}7eanSmk+p|h^`H@Ps#LU?-mHTKO-n&T8A)v3v-#m;3Ji>I@(kL>F=uWx!8W{@ zNs)bdEV+ll{Whmx?Mo55*{zp?zEd$CtUd{xM*S0ZyW09FughA1dCB!N*NN)e#QkPXZR_ZyAV$~Bcv(l7Piv5B z6ULZL>2HnnIKXFVXvMPv*a4uT{20VNgB;x}`Se(Lv}_ieN|mHzN(>{1W7PuZ{|fyJ z7<>~Hq#EEkA})+Rl%ZB|A(zndl(;gTr|6V8-P!}pcSM6v>>jzA0w823zArZPx5cU~ zPETOyJ7M_5t4^>w8hMYo9_8*ky>+Z5aR^l^?M@M_>akW2FwFWSe!y!0oArEdhWtuh zt2Nzm7MuZE_PlNp#f~lLjN3^iOS{MQ`}q_VZ<+cswR$==@B+)8Ii7`Lt?zKIe*)EI z+EliGy)w~1gezoD+Q6Y;Nx&RbOj8s9OE<)v62WL%f{(y=vpy6x|3 zy$oP{m5q3z{P~(Qo423ye}IcmHI4cSGtwy3`7+Skt&VsJ?P_>^IFkwZ8+{dXDx8k4 zcbKo>S-RkQLPoyh3s7h1^=e81?l7ha(xgPiMn9Tg9&TMQSAOwn@VfA~c3J92g)gJ$ zBeElvciuT)c&2J%$4j8sWfgh^(l0}22*;X!*pN1o%~}b|_I5^lu~N76Eo;2Y`DHx+ z{)C2Q`zE0Bhr0UT3T*uag#BY@$AFKdujF|^cyM23UaX~aVl=5-*A+kGK11szbe2q{ z+6QfPFFFUUch_m{)b6`Z9hWdP#d4Ielfc3Fa5T7uFdFWw?x(~fU1C)RU!z5HwXJFbM4^;>t9lO7+L)#Zh zHp+KX{y5koM9)wH-10w=`q&1sO-!|?8i15{>qKt^zbkwV3ojWYYh@eGyF`+|1VqdWZjB zMC&gg%kO@59f1;oXGPuLfFZP)W(99t>&>go^nMf~m#<87DdF#=wrY}zP>q7FNPv2J zeqv?v9;xq(0qXX@EvBN5%@-^N>M%T2Jh##2FmR*ChLrmxr0{sS7Bl|S6@EsBozewk z!ex+N0{aVl$$twIPH;z{+XRdLL!n#1ehrBFFzEjT$e;TwbF@q@zm{&O)4B2bjt|{a&Kysh=d9vpr z>cO6fvHo|#lT}0K8B;xa)JnFZd`>1b`>R3FI1|3_{dW+@k9i*zfJy9iCvCa;Tf)E^ z*y4ft?b@&#+OWBVqP7S~0%gO+RP9iN(5uEf&28LNb(JDF$(|3Qpo{Gn0XCLD{AI%* zu*BfMh6MqtbAiXE>ivtm`VDgO$wKTCzGs{Gx#Qop=gq$>qbK@ADSKW4OHE4Y&1p9$ zSdO0>VlsOkShrp2Kka-tLt1_&RSt5bUizeDnsJIwVazM)RLnNQDO<`%MaUN-^?(=m z)n9&VB0=K*1+!Wgu5CJbZjQ8f)v;A94QUJ~Ux{T(sfQ9%1UiD9pM3dvaV2hPuwu=s zA9ci8S@=zFA#@m6Cw)~VQedKpI!@CfGaRHuwM-!8vd&?Mi6RnwEY0g2S52gwV#SBN;vv?gR#M&(>q#sf~%)8Cf!%0E>vi7#66b2HyXMNxenS2}CIeo$wcnEWU-iHr9-@H}FVQ{u_?lmRy( zZQoQr%l`&q({RbP)2Mb*ILgk-tXI#*f>&`^BXVHNL3xuX^W!mfxRPw=lML%%G{(iE zF7C{4HLZbJl^S}(hV;z&J*crqpN`tQJK8&U9>$4yV;|;hz1(!hDZK2g_awloCYZLX z--A5(Mb6-qX28NB|JkG4_VJUn{g3QB-WamVXW-*n!v}`@mVgpqIp_~wi^+hPxA-w# zI(83e=y?irRUQ`0c?lmBH=B6pFvj8qXI4FV(RS@Bwrbs;duAbLK4fy=tZfS%2OUlf zcL@zBp#^aev@V{Qv%4xZgS6t@TQsq$&Vvg5#nw&VZAHJjUm)D%^nx9hl*vcc zQ84;}N1<4cw4(9Yc2Yx7!KaXsWQ@$Oklm+;!`XM&P2L?m&-sMWxUui88abeK^Pu^| zrJ0Hcf2akh1V{Q<_S!=*^Y>k@f}nHqNZL~`Dd}rpf1MUw&^wC8s|my7fB2eD6w9tI zhyM=0Zyx_~TdZ=JN3a=3j0^tA3E! z*(1l+-c=o~^=-#y4p9@Fi@w^XyX&~bHE&aM7*i9YG<}}X47nOmzZyZlWhNx_^YIlA zH`Ci>^nny7hPP@cPwbFGE%@=N|s&>8bzJ^&kj zY`NLayx9a6UAlTWM|uD2B)OD(&G|V4kE%bbFIt>WYE#uu=tiISxxP8yO#e}b4JGg0*+P*ET@Y=V zP0nrUU!{zRJTO*z)!Kt%Vq%jHL14Kf06I!UwPg82t9~yS{|n>r^?_9fcerWQtnuu% z`$Ch8GEd#5%11~qaJ+%KJ02H$x%iv1UOV-F$0%=K4|bz%SPt+1=gFo2Zs3EyX^R}B zTKm1)eEEZ@`ExxbX%Q;0!gh|Y*-L8+IX@W9N~Q*>@}QEsuSET!t=QS_;mxG?@hpdk zgwayZU-h#z4Q(dMo($W`?yk2N7|$v53)<)fmoBrXw;|`x7?ge?nFY!n-Rzs&y(@i% z;gOuHTcQkfa9JZsHYM-YDAeO5ux|6J6$oatED-2iM z_P_p_Ap) z{j?PGb0~G4;z~{HPsqo(`yTt+%I-%#-X?#4pZ~{vn~w5TPMp|}BNLjsui@VY_Gaei zH#HVNBSL95HUp**t&*3h_SYRlR#F#f8JZ?G6KaZCBTrkSx?&Kh^kXsRxg8su9)7JY zaK}tbjdADS9I+q2N%IH5p;c>D4OVEm5B&su6SCh{JmOc<0bC$sha@ORmDTrWTBJX& zi23_rv`dI+H+gtwIrrv@udaEOVfPyR;(DuBZEhMg_SSwc#Rh|B;*OP2hGqj*d_d1PLf z&lomuGy1kGW!FzZKiyvVS8(u|-SFNoGuG$s2$HI4I$IufUgvCP_*SqVZktpBGims` zdqmWbKQ#INHKF-lNw6WnA$I-&=_fSxYwD_F`0z^OeQBf<1t+OFX&F!T#>~QQ>!iJM zztSA})Bz>m6&NU6W+-*gXs~x5_otxYXX(-}rp}!X>FcF#uIt_AtDtDm6go+N`o4}> zdirrjx7%xyaw?4_pNackPQObk=L_#hru^!3 zY5H2)=)hb?f7_NxrMoc&LW_1~;s-3cs{I3g3Q8Brym*--(d3ajUfP*PqbL`AB@9K^ z9SL~WFfnhJQebRw3;2T%!vA67`v{obB^U!B{bgZ?d=+;ANlfutDU%N}7~3iNfsrHI1r_%@SO8ay>0IG;@Ohqshdy4;py)c zH;g_qbT;FD8+Lk{S)gPCshDdq+=E}JFHJQjMqicFrw&>+p7P!(5KQWKJ z5Pl%%EH3z*<9y5OhQXc=rh-T zrG>$<70(xQEU5zPUm(9^;{P^+TOFVYf3=()7Yr?m8dT&rn`T%uH%%VN{CUo|VTVSr zU{(sFb1PF72pIY=<$}yD8Q0#5on-==@Z}W3&Te9!@7e-XW>ZIf+u+%i%}s5|N)CG! z2ivY1=%TOf6nFak{MJ02$QgzLBGulMdn3=-K5p^u>8F?LA52T0z9iKiZz9ww%;FM~c+!Y z%i(NPLElqu%6>?i;j`k+PaqjOF75sqf}BgiKh7-|5ba&K4+>b8{D{PXY1#PJ&s{q^ zrz(CP^1asQv6l<_d<$xl->{}@Hvip3jK3o9kg1mzUF0~lshpEO;~OK_QM*FOtbTv7 zbNi!;fjxR68R%>L9+6R>%V%UxGB@rXPR`>lYNg(+l+c#RUvc5_^XLf3s3)>iL{7Tr zNnVB><&j>s1?%po`n>B%67uD=99k zj;Ab@J$@f|cXP!BLS4sR^Af{+!MfOsbJ{mUd`ySAJFeP!GmfV^yhtC}5b<@J0 zD}qh2W8P9}JJ(XEWrFLm~cHAQyGS<+mQH%ds9RA;e4NP491nZL8#QegZiBLzFSL z7{EOt+y>Bpe5L28E0KRguAC0A4K)ZS%GA8VYcj^PyUUB*D}eM~t7Mxj??ndVMxib2 z;}DfCbAzBxzOO~r?5llc(Rr^Ik7+joBShfZdY(Q3XLVc-?TIWZoGG|m8<8;+5gEC~ zS9Sj5BaKHAPS38kZ0gnIs+$Ox1O{TqO^wL`8>VC58%YSieWR(GMmy~SEFUPkK3dFa zrzYzJZ(3CwwxsV?^oL_OgZsf2P->2$($S?Cd~g84Aw3dpfvCf`hb$vC$9 z@Js;G}-y!8xG_xF#OCRL7H=P5?YsF1aNc95+%lBu6qvmfM^VO8kindS>B^Ix4 zf1?^+r$tVk7-%q7>)k4L#%rou%vZJjteI2H1FbE;=7vugo$#a<$)0O5m>5KY1c~s9 zUsk<+v&^PkopI&u$Dd68^uxmGL+l{P`KoYdolkWh@rD?h?PAr`)ELpW5ebGOA+$SV zD!m;gUuTaXFf$&D?Oa0Vl+aJ>ehPv>@W&vlAPeB@A-}Bu1#(3c0HXE~06t2Y!|!7A z50%%``owYA2~Iw{*NUWr#1*QK=^&-o>EYq(w@-JS%S4r&%n>ONlk*JL{dj(B@VUni zVp~?EUBjHrc|<&vU^8kamV7C6_vWonkE4a39J}(DQqlyWR7$N#*w zb>WDz2U!`%RQ4t0O;iS1D@S(Zu(e5-bA9R73-eMUL8^KL$U?x{%Q=TsX-T?cZStip zWKVTUqDQsiekg`j-{U&}*?PKG8LB`?4z&0+mTlB(eN`fsa^S3S)3re3#>2tF$KWg8 z2n)ZxN{e&BoYM&rdLG~xH57nzBpL+h0jA`OGi?Q$5Y=G4A`PO}1>wtS%XRK9?0SN=|la>&t$bJ%vpD?{(wK4ldR zJ${!TBXqA@Yxd)ov1r>H`s=nG+z!PJeNZDdnj-c0liKP`L}J+uEl-EPG|biSB{g-l zsVG}R=6(~J@!b!RU^O%%@myb)QIl&uQU&r%p8~Cq-z5*Z(eqkCo6+gePM)Rr&{?!L z3)9qe99jcROePwTblBJYrb{U;cno)94iAnsxaIC5|9r|MGZ)9(O_+lcy9!TNKU337 z^tisrWn!{NeY@1jIcXi&TjTbSq>T6-@+Q;PSrb@3Jr!?CWT%U#@i~3?d5+x~kA?Tp z6h2#&uf^r_K2Yc8Mia>#82kyE(oUUZ`Nqa2jP7ch_x-@KN_VV}o>G%$ch+Q$p%UI_ zu$vjGa0QUE8?VUeb@MsGQZl@~IH?#LY$F15zpMc1gxA<#FsdWw(D=oCX?4 zoN;XtHPKM&_5A9B3`7S^;?A~C9Jv=a^=o*cCd{d~gC!S4cy!swm)@!-)q(apyAn%g z%%(yEGbK=+h2d$O{g5xa#vq}21|dDV4}Hb)M)D*?>}s`Q*I*kvpKo`^V7wasQTS0- zBbn3a$(gN5cSX|^rkFFo3BB4TY28$~;OD<~BJSe3%CzbikfR%g-;ODV2){Mb@u%-d zBwb>A(03$}oFV(er+33GP6)k{8b{yXwa6ZW;k@+yx-@kX`e?J#pPFhh>|STT-n2u; zYy#6mEhU79*1K_)UY=gRnu>2W$^QQ5yyT8d3>Ve8yPkx1&z&kB$z zQe54|w*9>r1gAPYd$%dxy42kfJjY@?if9NW6al_Ju)&`ZT83*h8k(iR_`cn*E}kgk zGJ5>`bfPYjl#-`2(TW9>*vu*K52CG~DLM%^>>0DxN%%_S8Nv6&?}WK8{bf7n(kbn5 z4|h_`LE{oEz0Y&vrFUaDXQ<(>;JzWGSvG!Y(l0Y-aV?urY@b7__kEf>dbD12vhy0919QzQs#|7Fnxrs15yU>xGX&+&~!n*2;V+dtyN_BQQy zZkxx|rB_%@c^Pib$eGsP=wQY?%d{Z9c!v#C8P*eeHL@SfzaH?Ny8W?2g?iOgXkYBp zD5vHMuZx#uuJpYx+C6jIiWNgtW^R7l)AFcQgL?qN7+@VNN$U{nzP*+kKV5!M(s5c@ z37R;~^g`C&&=7tb*DyY}E-2}4k&_t2KdMuvoFFSHd<=Od-2>;n4T79D2vzV|djaBh zLAWCA{)!9QZCs5Iz3-H|rgf3oisPvS_OFya4fSgdVbo%h)JLBO3k2SqHyX~%@Y7co zO`WvvwctK_a-TwSHJP!t6V_Gs2S;D3&} z_r6kwe-=BF^7#TuC!UrJIq%`Qvd!1AbWcl*Et0X%BK_n=;kPDDz|73TD8o>UFFRM~ z9u!k~J{DQqIJHycT?H~M5Fc?g8H((dnRAIyfOu`IH_7E{D|_Awd`xk?F8kpOWODyR zV|mJmcHtN+d@Kncc9`rW?;Op#*Rq+t9jP?UI!vx8nhRs>l)boMz>eLaC`P&@bO=|< zKn@pfht#E)Kj>%!+Kmb0K3Omq-%)V|M-4_RZxMdmY6{a1 zq-c_zY+3sqN#Mw)y9z1W+y4B{GuS&4Lv#eJBdh-Sc&|mTsrLQV{*2~l(g4%7XXo?s znAANv&t?~gAByus2QBe_?LKRVkubJ3J9ndocYFLE#i-JA4hjwa)twZc^^<7VtHi+7 zakF^+JJ%7gVs0^3pbE*IF=3bBQ@g)1~>A!)sDAHKW6biT=H}XM9RM`dXaCPr4`>3cn5b(v6EGU4X>y^c0_smjHI#j5%>| z_kj=CKyU_Q?TgG_Dq4*&pX+K&r;x}L|Cj!|*9D2&xgB4uf})#`Ja{1xgDlw11}tFt zWrqJZhkr4RbW>bhqT$e?)hN^N(xhjB-U@LEa}LtL%azO|?3pV0Z54T;TCJMe1Ex-v zkjF3X%{`iI|GbuNPOeuKMU-Yx#iXqeejn+WFDI2<(Ka*jcb&%CPdN1yPKhQ$*s*b! zaPoUAuXxqvD05Y7UtRRI`OLGK5Ua;RI~3jo$f$h-YA4N-@*4K~3Ya;&duX7@`L=5k z#p6v%UzBK#p}$aSd$Xm}&H2*REf1}}EIz_Q4`R!+P~i=~6rP1NAal9uto5sdN{@SQ z!e_pKoEJqAn|_NpyrdSI=eBqyCnt{q(1$UCGa%kt-Z!7;*>*;6imrVajKreydDL`( zGA0@!*xem1V3KAVuXW(SU&B_(JDxYu8eSGf@DN9dbWNf~FA?hBRp0G;)16rm2$y*c zuSH@`-GIk$L)Z^G;Cz1BfIWieQj%h$@seHXdsWJ=qa?JD@6O*EySuLSk&e}UWlG#d zps5?_%=&Bgk~gmqW%gl-7#Fd{YP_>rtJS4B0N!8``syxi5nt5UQTB#Q_>4cO29M5R z7KanBxt?|^PHsD&{aH-~-ewoTef))gB^MG)>gFJa3dJEK8+&yt((WxQCPRZ|#dL3A zil~TS#^7e(Bh>yP)wOqJ+iXkZN@T9l9Dksec<`ZO@_Izz_(FZa#`U|} znQ~~t_ENOI#(cz!ZY#D#rF+3`b4AJGkTdw$g{(UcmC9$Mdnm&gO7V0gqX!wggB$;G zJ8R^9KE9;d@NPJfsvn%m59tm|YsaZ8Nq+Ss2b-21%tgQCj&v`G1hEY6*2CjrUT_=t z!OP@Lj7mKtnl_UYr4dfJ)Z*{V2{f%J<7=yOlB%4JD^3t*I*W41I9KvIdbAPTxriA! z)}qqJ4Af-IEjl_~t@C#V;(kotp7Ia0-w&w{BHt474?EuLarNr{sXjtE7vcAcvfZFm zy8R+ar;TfHOS|UzwEnwamSk3BwNk(M%0IDltFI1ehE%WH5mI@A>nihR=KZ>CHj~Wj z!StXFS0#_#lHYdDG0_=A-cVg|z5h+IIjN0CA+CieK;Z3Z&^V-zA>OEc0>x_`o zkJ>5~99GDxtY*w9Fhf(KkfDLFIgGV8yE0CV#d5_?#d+6mWwgC4Gat2kXX&X>Cj}z_Lb;0s|8L234r8Y^NqJKcAYrDOx6%63d8|G;5O|8 z+dn>^&Yac*q~%=tS9bNgA54ItD$Wia+?KXc1&o$I4EK9@WvKF9(Zc+ia11Zl)Fytl zYrqBainhXJr^~<&3@C@RJVYKe%yynz#Y`PBywk_wbf`DCGbb6RPwCxj%`yy|db4|= za~FzNr=pdV{ml4j+(LXxmrATjqpwd@%Ub*jwE*49OG6c&&Pg$`SaYFQQB`5gTs2hF z>t+?t*)zG!sX?s*IfYs){sbN6?O-*oH9oL5?=@@E%?68yAEmabbW&0a<;&IuR~wktTaELizow*nlbAPa9!PnB%?u9SB}S%6(=m|?~_|@M{Y~qXO(k0yTpiYV>>9EtLx;53%Qfadt=`_(ODF5 zf*opqvQIP{I#w}2-s>@)wWGAUXNK}~|aVHmNJX36Z!`{Mb$U%acUQKn3hEcw9|*1k$SB&q4g~f+dInl z=5{xu{S_t+lIShBJyy4lOAa#6N|gE^QqU=j`X;VuRNwKXJpCTA^3@^_>phz3G;6(1 zCa|`@$idRaoV!Cd%~5S*dNZ=e6?5rm?xIg6$rdi26VGwJCuZTlw%-nt=zW!%G?$o6 zN%wsRe1jkFM6ZY(X{r;qdd-^F2{^NC&XzcD+pf+BQLBamqOzjwde%}^nnP@1mpjOmLI^aTt@~!Xp$~5;Xuh?_n$q{K_l@&$=&Ak=HEEJ+nB8 zge6E}II|4@vA4kgSe##Ek8IN0^;C!UG(4p-L9K*rxCVUYHU%K~TI3O|IxNf|Upf+B z1maKzCiE#i)+3G{=dnoTbBU(uNnSRKV7{}~1Sb44NhxC?kljPhYa&h`KCW2mNimyM z0wL6kffyW8b1WsY#RXVoEJidDAZX?sBm_@E5^*GuOvu3QoIW`QemU%TmFr6!iA8-V z*sRsVSG_j?esMDS08Efc(LUCC$#d^@Tg_+Z;DOdQ?q42`WvuJg&3?M3n5Qr+ZOj1p(0nw@DX?Pj^262Cc7Dvn$-+ z5q$lGlN(2?0au8Uks=&YAo%USUTEI8wN|)XACyk^I4$_cr0U8_&T|a!5oa+!nG4mO}{y)AVs|W<+NWvEk6b${sbvX$yf@~@`iXg=tgb&9zD)H66q zli>8?5aY-SE$33^hmYU}*Ur^iy`5x7d|h*hp&hquB%){HcL7KH0c|4Sy#mbIYa+Mg z9P>I>;Pecd<_Uc5T!xvrNRU#$nkv|50OO_f;yAUq6o3i{f!Sxv?agFU0xA{w1Vdp!`bH=}kPhVyK(lg& z-@g^?>zZp&CY{B2li%EQ&=`JZk<~+kHcY=63}fi2iUP%}Ptx{hOw#>>;V^$qQe~5} zGVD~H)#ZBi#_-_EnY+-lRx27x?9r^@7vb9McLHL&HpZ*6w_1UF3D;S?$|e^{w+eJF zdzjLy!^jU0r64tgkKF~grG8IFdx8_tNAUM%lU2ZPQMSi35+*5hFnTGQ47>bn`GZT! zdR!=8M>M6LcSu@CFLhsxqJ9W|Qt{D-)O}MQ#*Q7#shF^*W>qq@ssuLNxttQ?*?WY> z;R&qWxN8_e#kumOHTq%e8W~^f&zGq8bp$ulR$KK|cuQp)<5pOp>By2>bndN-AIK`~ zsiWT8c_RbM0U2xb{3;u@B-4UnesI3xR*1t}ybg=akHm2-Z64KGzK~Yl*KK zsgcS!+^9tm@RlayFz`UmptLmK-xK6nTTk>_)I#}5PO}45mVJF7xH)IVnUdj8k|-C^ zxJ(Xc(*ZHGDiOz)i&-IV#_g}Zu|;BuQV+>^inzgGk_hs z>c}gzkn_Ugc4h^|l>I&XRSa7u<=cH}6AY&YV@Duc5f|GT zwh4Cy*TDi!32zpOZ|Ts3H0yY}o{*bghQAzZ_%}e<^E~T-p6eyWY&v`y%j2-xQDUWU&b@ee&S0d_)K(l=-0SmCRjN<7Ll#g3XcVW8Prf=UOaPW&u zHe@Z4Q(>wIwXNO9r;~V-q$~{X_q)0HT04D_-enfJq{`mA%E54Ss?7Rffx7!1JNpHt zHRc-Dzz4khUKY9Qv9GfaJ&PXcvGo}55Up5ofpXkl;)Hk!qMMl$<&?rbBAVJK%8d;{ zY`I#v*pl4x-t|;~UX$^p|6v>fa>#pBaX?jdD`aBRw-^{tl-DnsrOXA34X+bXm>Xqd zY2$%mTC`6^7f%rC2hEr7fFHsciZso`&NRkN?Iq6Lf@%-m+%Jw#j>z0 ziZ!q56wlF`m)cb&j<6fXKSV^&2ZPHQLJ|XF4Q?Tpv=a$!?bV=EGf6irYC<&eKEOC9 z=5@f!Bu^t7UZ-;t8-;`IR6bDiJl~V#}Va zm4lu2vTvl?)82Vrnqb_zwWp<^yvJ2D=;(Z#MK)X3)H(;GMm0txQNz`TsrPvTF}PDp z8Iz9&=%0(b|HUOxDR!Uzn?vAj^kGaWu%V%R+!NOD#_?l9hd|WuiSn@77bTttIWI^& zj>cim1p<4VM~g-%%JaWE(_$RCz%FMj49D!OgK9o2jK;h>CrDw&BPwk|xP(_7^^U{D zi5~vfMng!4UM~rpIAES8NSCrXEyYcwzJPNhO!cXvR>3N{Zr5I1?IY!8ps26(K#_x! zg(MR)pU2Fm9GbkoMQr^f=3JJcML1Aq;WC^`-aOt4*$?L9^|;1ycCkm)h@~WltHn!- zzl)LBL_!L9Sp8lXBVn9G38=C^!CJbOKj^8H7)_LkQ3x{z1nsYWoo$-4@!72ysn}F8 zf8%*A-F%SQG4qASx|LX@eqvwTJTlO+>ZO*_v*^l!jFknawZ(oX=BpL(RzZq?6PlHp zOY_Cn2bK=0ZSoam@ozLxd$=b*o$TDQ+xMCJ&kU_dkh}7_`y$|!9k6JY(R9O4LopF& z1S)-$1$L^Imvx`w`FrquqhCNqfl{x6QX1jr^5QFL>aqAQ5g`hU0$a?S9_E=2@DL5* zl25eRX7qZDD}PiEW;3kFCn)pZEAW3i$hYe&L%E>#6$jWV7HZABT{#u*EVbm>UWWP8 z2kYo07?H}}?uDAGl{%pdtg6|}gw-LRxn{i{{t$)1ns0-^WuK11za*5xHIP(sU zk2A7AMO7#C&83Y`kSsP2RyFz>wwkf8!za<7Fk@qC26MED#LeF891qh7j!s>T6?4?f zoy^NR{z4a~f6v74dGA^v8yJcdsgA%r5Y!dcZ}mRyD1+;$JPuou-4iYQL)01ggE--d_|WbaW0nd7Zo8tH2`zEVTdtMek;@lcFN z)6v1lV8CJ;!{6ntfFOyJNLRFNr2^3uO-2vNzoameA#b4LSP?W=%8G((FTHGbUuMbP z$)O{)#oJi4kw<_vJ=Tk0BZp55SS{@Mk8a@lB?t0v8ui2Id`Nci-~&T{M33v-$iA@$ z0dID_g<7-jsa0I$1S#BqT13lXh~D$CN~Q1(ranyHuRZk;jwY;zsQj}nlNLUP4Vrm5 z-J#DY;(KreHM6s|0=628!|Pn&GntlF_QfQUtVobfo3%iQav_?NMvp zrRY&2G_iG)fdcm-4eZn_ftC3JuR)i1U&=4TuQWHYDzS9hw>=vkCD;-ihA6fY5^$6( zs1)e+T7Z)dj$;PZ4V+DG`FFp4pTQ&nrM>G-#@BaORpu6h4w{@b#MPY({4v-6P-n@-_V> z)vZbivOhSWy4yG5?{Xv$W|ASFw)_ll<38qKZc+F)uNMLa@G|j zmT=Y;PRHzixh!sYdW@ql%}{KZsELZi4@KZdBgjaw=4Ptoh^W9?clZ`(abTPK(CjHo zDY`ERCUEpP%)@9(A&z^ElygLo=6VN$lLk;A>!&C{RFH<&)h-1Ie%IBSQI#4*ZoI`B+6}plTF#aRV&>ba@Jp9^MI;h(!1bS z5Zu4h#s>-oiF6I4)vHHREue^`Q{CFcX5;LZmO)DDEpcqDVtFv56UXhsS>C^a73@lK zC0a%`tGF|1p5qltH4Gm(YsEwV%aT6Lak0-O-wb6c}-2Y>&BSeK z?T=?f;c-;TJs0}P0x=ENIP8ii~uXi*$N#WnLWjgl=!WdV-A^NYx zucvr-b(^O2Ws{!0zR}xVX(_st`Jl8Hq#y1zJ**}Wm?~H1bnjTBE7~IpZ|4lW-C?3t zAYU-b7YhfKTn#mTl@r{?&xLLLIWk~hL_q9_I(Ua{#O9TdV+UE+8j(3kB`Ev~VTj}J zwb0!h8h=v)pVS$UhQM&=r%I+to_X%a1s+wJiOx=)#pduZe&Fy4>BT1vhBhXveh{I7 z7=D;1k43R!39?&H8PmPC1Z}=Dr6{r%z4q%W0WA?fKM<=3Ei=H3PJoBlBCOC{*0B+VXvDqCQ#1$3Z-nwX#f2W%BL06VH=486i$W+!L? zB-Ux*??f{b_&n#JTgs2-4$NOz;zJF$)}`qnn-$F59_2h zGnL(?L0IenDtuKu=uv|8Dok~vU3UcX=* z+JtyEEbll(EFVhD25Mq|l|^p+C4BkhJE;&nOJ`E4pJ4c;w6$EMhT~uJuwc>V2Ntp=1N7=*^ zeQqB%wD*+Nh8s^g_C`YyeL&LQe|LsDfiK{*E$X|0-=v!$^slEGX=iQ5HzZEab*X<9}oW4p1OR3*d_YEkq|@NCSdI-<(N z!P5Opw2EBPR`bVD`rDo zjlhyUS29hDMV$!_4z}D#Cri4PPrYU+G%nF#l3CbcutGgML>!ve2PLkb`Shuh__S7? zFrJm2)#GvIkoaokN`W*Zh_{a;6@RDHRtRz%3U=aMAtG#29sb?y3k=;9^3`%I`g=ap z;^KTwc*e$vE%?4K=ygWbcg5l7dy&2yHAbJ$fueAUfU%5X0-{Hh+nYK9zJUCF^7s6` z9!NY49E9D9CNb^i>WSArea~)<0l&u))niLu{NgN%TGHwBzQCz%#c=Wb;<|}uJ?SJK z3&$_5b0gLYTL}X-k?La(nR_vvITC|tp$V#cFkWE*cX7U*oaD}M&nLr;9bO{RRD}iB zKL*n`^8Rd7_s%}hnAU2n78;XBBhN#D=9x{Di?UyG{kUj`S2RMS(68=5dP?X{wR7Q0 z^ug!QfN$#t)d?J0{RwG*h9D~Kx1xxg7#D;xqGBMws~l2>d(qzo)l0IPwFvmbOseyB z-kS+>jNd^X8EZ16lAVU8hsWB+hcRnffcL{CX1;Q6&zf`PH4-zY%lRw}57$~s!6w`w zav6+V2*fNVz-vTV1((V)YDBu|I0#+1ap^l`V>g$^FZOBCm$gI&;?+S?E{%g+&U#sMe~i4nr}&4fM&}P6-JKVwNYq)~aqH zo46?dD8u4dFUf2Mun-fpA>*YiBv>(}=k|`OvM`U58oy^)(ZVZFELo`~b2cMDCzLV! z{CoKA3BSu4dw4$#dTqbJJyhDiFwbUvWo_o}_bF)*qwqU1 zr7r}z9Vg)TwfeQ(7HFsT8thSQUBd{pei3Nf{Z)mv-;)dDCBF2LIf0rX42a<~Xfb%B zC-wZLn3ZUo3BWlSi^IfL3enb!7pN?rORIMR@rXT}<8Hj|2=#@U;@^P$Sg2SA!AoDVgwu1Yn&XKnO@XjBVils+A`j^E@(_(pB zlt5(-qtD(4yu*|iRB6g&bz_!*PBf35`vj$#KZCaEW>vG-MO~=40Qf8 z^r;QxmUN{BFoeim)q*N-I`%~HUv!>7ec3;U+4u!5-Objq?^(VV(|SvJr2dBv|MAQI z8xYv{V)Z;^X))sdmOmhRpsccfq3Z3HntujF{hOElcL=-X!tJ=w(#A-$6oI(`{r|vT zpU$?zn*inHYEyW{xQx$Zx0azMS^%rH28-&PZ>$d8**Y`h24*$2E_4nGQNOy^D=YyV z+qeRAHamtY2LKdu2D{77y>{QyPdYssG61|U_RKPl4|w$eZn=T-()By2YsWHxseAcj z0N9kaj0gPT1IEk9rrwK7Bsass9V=u2;DvAoWGVpcxN5!WF7`iv>MwarwMY;sD`VQY zK5P3yF6LHD*zA7{+WR-0`+IrpXTfQLcK;2%BS4TK)@$9I{Ercl|10(J|HNz=Yx)0; zm@T0tmrxlYw`9ZqSt0)$o$%+t(6*JU1kCjO^dC?<;A#orML;nA2`BjPbiz3LPf)iR zYkm?u;n>sPz4v9i3SEso%J_c*@jtl)|7b`5Z|%;p1iM3ZRmp3l0}kcdmmkpviSPA$ z)YWn7>FRj(68Jy(3xBo1KQ~m|H7{qQWVAMtKJgDwqraS~V7O;(u9pe*TchDFN%vi##YzSV#GLXRwJq0yL^+Si1kdxBq2HxcYRRuGf4K z$NM3CSnl3|i|%Vb7bJRUTmH8%_pUvc`r^LSxOLX0*a#WQQHrmImC)pW*UJgoCaSY= z!7|nl^q=@|%i5lnQmfwN+f<5``)}XyC9sIz@}e^dtF67xa=k^%&@PG=#m+S9zka#( z=DvPWncLGo<{SO@pLQJdj=2buD)TjB|0TtJ_5VF%xmDvo@cRCLL@T$Ajo7KNrgx$# zgB!KA?F&n5rchUW_S?@tRc^hh*Jyfwm-}g#jixobFjva1y6wN-*E+~$8`o1Rqj083 z;&7~|&wS}deR{ZtViGL|XWEh5)yH;N0i65w>F;JV+ol$xJwU*5O^esl%>y zc{M4fz3qcuH9x%PSfStic#->X-5h9wQYY}aR8s*cbpCQ{aR)r%h9J}H@AON;2R7Ao z%mraMmMm>N)=M?{KxF!lQEGNYwvf5@&b?1FQRiQi&#bIs-vq{BY$Uxsqk>}ALjGE3j*&rEZ^w`39 zQpQ0HIK&4c470h{U-w{n9CV8Q~s@s@+R9oj-q|b@HJEH278OU$fHnhupK zqo%`!k0po(j-Hqbza|yOzImHU!3w|Cf(BfyeCEmyPB?Mke%!-KoNV3TBQbgK#Rr|4 z4r=4*du6i1!An`o{o6l+48^~1$Xm|r0sY!<7Y8KVwKBucntWoT`ab*O7d2D%9+dQ& zylp<8q|tJ{rQ|8ejpBWsDBJKZ^mUE$#X?biB*w*`%8aZ2LAW!Uxgo9zXg~ntJy9P( zqY?vpsR;Rgz!FPb%x1`5-5AAIBA&d8Pc)7`5!LdWtRHvQt|Y2r3@3qnD3 zIzr0hUc#wibOSWMdqQX23eu2lJ|0!;fTy;9F**+^a@rop#_JNP6twSIA1CKjcE0%k z_RwQu5GtE?b5Po&aiovhsy+zq>B&CyW}>Vp#eOt_pWkQo(^v0%ExJ=oyyf;B^}k8a zD;)%n7URzw&?H^1%I4%7?~eQsj`rl!bZd-kDx4RFPl!#|$l?MDkkvG!=nq;VP-(fR zH6hUHr2H>N@gF$(8+PC17k{!Ik5WpgrNtJ0-7CTz1hr8AJ~dweZyGt{-P7Dw&nU ztrwS6cA6bu80^92?ASV814Yk(i)8ptoc7Jz`}sVfV~F zU2HOIGRHseGK#KA9F{rrMjFN)Gi6q|(%KF{q{tdu)BwbQcdhaB0{3Vwlb!-NKLBRB z$knozVo6Ib0%T-{zxkmDf+o{&kUKT{A1=+0SuXsiUY+0y2H2_gl@PxoPY@j zRcmlq6&^?8#}nQJ0Ejux-4f%Z0ZZO4<6obCa1C%Ezt;`Vw5;$OeZi1T3i2+~KEqW0&zq!{^3FlqS`{JFo!HlSf^zR0U3i?PX zjNKxaSf)5N9)O$jPRnkB{VIw6^lhxcWqj-V*fA35HJ7yNU$-CP1t5C>LciQD4S?W- zkCmH7S?gRAGyrp}$N#qbK8ESdj!`U2J2&fmHG{hriA$r_lGNi3mx20q+`5)bMSHyYUEo2vmYoD1nzON+3SKqL#oM zlvS`b`jt2rF$fDi9hcjb8CkQE#r8c69CMT@=(-bhRi8QZK!~{ge=3MPuPPE*Qt)9M zuIJZ$B5tH)9m2PX_k}?rBd09K8us9b3bcLjIJk1sihi@QPYmVI75$v>4O1RHBkx*k zTob^`ojK3O5ja(OK2BcvtpJsj3nyp@Y>yK__m6?1q3OhzT*HYDys01rR%NAD-MfDu z>@iNLu8|V;p@4xInP4b|Nbd(2&LC!7CQm#GwzGAP`{q*BBP{b_qo7|1eDxP~ zfpsU5V79G8-18JRD~`{_;K92lePDV}1G?I32XAq>T3w(P0E%qcP87iij8_zp)(6?I zKdS;PxA}KUt_Jx=v-_YaUvs1qx=Rh-F9A)u{zfhdogr4@G}Ddrl1T<9Gy-q13Xvi$K9cGJB6mL%t3qa-gafHBPb6aFiD_DAU%Gt*JvK2!Lp{U?jn{`D)D@5*A@4Beva85 z<3mcwvIFsz(z0xH9((g!L7PPnE`NsvLE0q%X8R7`ah<)MObSdlkrExEQffiXu}$0e z;kzZ@!3X>a3Ml`6y1{Z1+Xgi3dZ(Fkzn#A|VJV2CdJA>z=NW@75z^;bE*@ngQ}kAj z11##E7YcK5i)JALGPExUd1YyY1*nf{16Pm9;5Y(B`_gb((E|5||6aGFO%5*kRya7I ziBY$#VrVhMuisUS_Uk`YF}0PriER)ffRZc`=r2<*ce5dHuJ~%?$+)}|Mf?*gqgaZhXpYz`Q z)+;zXt-gDH@yD}M(cb))rL${;4x%khI>0NiMkci@BYek)4v{vfef@3`efoR}h3!}y z^#)w>uUp+?mD}WPla#HcJfag$enU?(xpqLm(i_!EV7AICXqX9&YnLr>BuLj#O_zO# z*rl-lh0FBb0usP``Mn31vr78G-di_JvbbI|1KYH23VZapyA31^ZLqF4w^F? z?oY|qE(YD;9x8W!+vsu6J=)K);Yxwl$U(J-@41~+cBzTb6Dnm}WB{x~4npHap$M^1lopZR5)=_JK!6CL2c?7np(P}wkbFC+=gge){^z_Onf3qcKP=ZQ z*I-umv-kbnZD03w1rcj}iGw{R1yP7aeiGc=5#u$mpGD2-js1xrbo{PdnB;R(O*`4R zE|Ap~_eOayj$NH~GF!S0g5?A;6|+ink=}0~rb7TKhf~w~t3gc;z|3%w9t*Dt$1iCN zC*(9+*g-WK?Q6Fh)XXG{XuvV(v+AMn{L@he7$+m*+c|%iBqs7oQ~xiL#2qa8?yRB4 zdqJq7m>%mx8dJ^OuF#Z z-}Qm4Zh@)UA_j~kT;@1YrE}}VLe=eUBy2+>u`=C3-D|}|;kXo7L&=yVyCg_=5yFcJN`I(ey;jt`428yqLG^Mwb0YkgTIkc1_q_E8*t$udVV*H@B1eXMppu0k`b zh4foP9HoUbGCFwc{XPp_6?~}<5t^~-ZX*UN4xla|J@HgvB;750%@UB zGpdRGI89rROo#V}_U%CGA>neM*r9<3ezS~DSyJC4M7@#ko@-Jse(Zj?SYl_vneNbx z;=5g9yF!W|N2+}OHz`zr64p#3*3_1>r`Lvgynu(+aMwe|DVE<(=O&1oYRl-zaJ^K| zE)y=1y}9rWeQKGa%JdmfO9)N;hYq&)Rs1y73^0~Eo||SJ1=sz%jeUyxqB&r8&0B=) zF1xNp=hp?djdmK{GbojaABX`vLh7At#Q0z-`LP6w^Mu(#VG;b(^-;#EfC$r3I22x~ z`HP^7*EZT=B>m@3bV?^m^hT9fkM>nwI$CA*zu6p6Jbejvi-zy?;8KO5M3r47Qii53 zM~{IGgjK>qHo?3klxQ9Hj(qV;?~7~H1D`b1+K!<1aBpY7>K5e?EJ2ILr1N)Pg35?R zCLXS+s9>g=PJ2w=7&FrE3^*U2SgAr9w&YV1IjFr zV@{$wiu{p*irLZ`hqU?oq!>*qkh4itM^Am?hMif5G9Bqk03e_gPQqvsKGE-pE}x!W z(AR$XXsyd8q!to})CQoSoyc9t6Ut4(1|nXnXq9`W0igW*KIDQ{9q0Xqs9d_4QnfG} z7#yQg6;3VQz*hLsk?TdeKPSzgCID^9*w$|WT(I%~W=}!R?irohlXj1`j(J(LS!!_6 z$cW-W(k<4nAK)L=h?^47XT*iOsJhZFXd;XD$iTK`$bM+A!yXkiuD}y`r+!zoE*xgK<*P4Q4d!%010* z1PVqG1qg7X7V*K8A@q6f5uU01z7RyWjCe`F8Ym9wHAFVNCK7}Kr zY)$kyg=MuODV#{xdM1#>agpFBWjAk&9=0NQ(5=H_k5ulO1( z2d7Oeigp=2$P&DdWfnf`FCbrvOm*$@3la?I2B)xWKc^dp<);d5(IyGg(XNf3qGO-k zHb*9sj5-USIBGw-AZsh~13EAz`2_3WtkSI!ViCB0K_ZSjKJ*bf(g54uQ^&=I6PI&) z?Z;tC*P3tz-OgDCah%zau2`Oh%QPM#n=$Li(Mi^srM|<1eqqh2>0OBgqhJfc zM@L5uvbL@i5--Dxp3}BUSk_8G%P3s2+_fwBN5`BeLtKqp;FbY%6Q}B)qW`xBoOA|s zma%)-6TJsPft~NP1OEi8vnL!z_TwbR!nSFIIG7UQ3YUaU z?)NxzkmkK$*A-d&0+2v(eG?qZM5D}0@w_r`3OAtV;O)bat3yMJ&ze=WuXO)?b5bTA zAWX5`ky*@UlO^i+tft=I@`w;_#0Gn>ID*H}J~8jWF>4)j@`bJ|+<)H)mdQ#y70Zo5 zFf>y+94Y#Ao_X07V_HjrDTconafDTgv0AHEABpF2rdC}2!^MNNx|?Nuo?VTd+*tpO zv_^WmNd$7VedVSzzboElfb8Awo(_dDQV}+exJSpgl4vEMf?ES-h3CJN;Gej*FCt`dbMmi$er= z&@~Qf|NV}C0ptJuY|Gvod7d;|w-*jtgElDuqUR3a3O0%US*b^44F1gx8GAi9{mn<9 z-P)CNv{HMcW!?EY|GLQ&G9H1zE-(7^fzomQs7l#Tb9;^9yPQ7*gBj_lcn-h<9ze0{H&a%76So%FJwO z)rhtfln*_(mVS-vjD`T{!-IhpY3wntn))yH{~J~Ge`n7AXX5ey4#WHh6!iZchWY=+ z5ayibOncmlt1e&uxSy8Q_e9agqH2|1KZd=BVBsisC@M*Nxn zh=D}kB*T1;xUgu?AI6wx|A8Mvg&U`bKd>87su=xD7D{+QU*_K!f)MziU(hu%(fORx z>2fvMZttWPdJWViqgIYxrhih|oALB?FzMT?FuMAyHDq8NXqgKoqjQg|#=)0wB8Mbiz?_3`m7| zlk!ZZY#+09q2>Dl^swVGapHqokkdFdH<`xr5BPed{x}CK^8P#ri+GPjRDUc7@V442 z7JmONMc6mhCp17bjV>dE?6)fk@)l+abHE^Jz|^Nm`2N?Td#?i@ONrQKDZnpT4r#RO zy*3wt{_+R>F(8-+eqvle<05v1C>%*U0Ys;G@V?U6wYZLaUob9$?DK0L7&s$rW>UYB zOStMyODAR0-d8PykQ%df6~=`@CPBf116os#qRs#W&pWe~oAWxrX^3krc4naqYWuz( zbB(bde>5>{WF?HyR}DXLV@rSFJtZGNdp!`sr?>-}BAXp`W-~1T!Zmqkj5`_j)gaR) zed&rO6Yn>$>;=-^_H3;@)In}6JAhZ9WyMGcJ}-#Gd$sZMEln*Y=gw=*6`KiK`)?O$ zKwqoM7<})aa(v%C5>HrA=4K^2<4*+Oi`KfH=#zw^>qi5+= zvuLRVo;l=8f<^GC3>&zhq}Lo_P8W*j7c@$c`vQ_ zFbaT2r~T3qFvGCS%>#^w6bqrUvT`z@A}rl10X?Jh$Hh6bI6FvxtGL%4|F@l6Q$Ccj^qcyV%*GKeeA`S!2AU8o3AkvRu z(5|>Y&NGewPM>(!HsfSAC7c~kU$8O^OP317aqNLcT_|uAsSenhzUt1BV7S|n4Vc?f zhui}bwmXW+u^13lgoP2(-=)%6TaPy;E(5H?{f=N*U`F6>Mn$k!+x@Gm8lVRP z0}d5M1My#F)ed~o($X7l1rt7ck8TiW#FPH;0qP8au$kOU<=}oFOrPxR#7L%vOUF0G zy@-ZVe-XC>a+q9%Sf84HllHcS#=d49zJ9xX{fJ_~&mGX>7yi1VDEO(-73O{3XEoN zimN_?J^quVk9X@ad?n#pHo?0+-(4T*CmQZ5&MD+}@JD}=Be+(WJ z$IfD0`l16e<3Cofut@$cgksDC+Ejf{odfu=FAMTao>`DojdQES(oH-gF4XXar*@Xo zBdIFhmvW}Ne4T2Oo=-=i^)=t(`(z9thQ#0f>k*lQBXS~zBZ%yT(cx1QLjWCwRGqDa z0t_gu28p&#^^U65$Cai2M19f5@>ng2+m~=#3&QO)S#XHy%mX@~5Y~Mx8uDN1vx$s} zm2z89`MSrUM=NA8ng00j76|Z)=^WI`@CHO-_|u4l*jryWIRM?c6xw`1I;=3;*W+gv z&&Psot=-wQxZCTYWT!L~r?5T2B*6|@P+si4e^i=hpNR&lE=hQah#`C+64Zi@Vfw{( zuNf})Ves88U?6Aqz09{At~x=+=&2ZU>N6fdB{NAI*j?FLQH&4B$Mue2za%>DfJ=CW zgl*PJnXm6^++}IdEg$aLE@`a^nD9j zYpftmw|kI%#qMnrYNWgQB5TR<&{ncj^zv;d?^v1edjr6vSQ1&QWLqa7hi$3?@A`vs z@BlM9z^BQ{`GA({B|{iMvG`_{w`69OhmR|kgA6%Us#~|+p-{W5cO&eu{oFZ?8!}s) z<5-!fT-~U^8X#ulWQnHN84SOyNTb{}g^M2nPjTHMS%fq9Nl4DyWd7BjO=M=zzve4p zc^&@Ng8E34TZUuy%GMju?Q?{)=<)PuiFf5fZHM`AZ}v zkt0o-@lTxyQodIzP!S7T-kkD_d<|x_cK?@#!>tH!nQd^j*D?qXQacWjS4Jp4jX;i5 z=0}9hnbWu=6ZJ|r%$|LMChYPXS6SgX)|Y7OJ2)9Kf@bv zYHFAC;!>ivN>);g*cMVI4+@29T(m8QPXAqtK}JihmhT>@KN>pq+lI#I3m0-Tb<3_} zZ2QR@Nyv7#LlkqHcrxzVb!^dhg?W?QVen>Y+YfgX<%Av<)cwVY5PO7Ai8%sNJLTYj zfZXZ3$7l4HTWA1aAS1t6b3*PMMU@mI?$bwaFgDV@qwZOo)y&x{ZtcBCCm8l4O8P-p zxWjjkDG@GLe*~+NXM!&5n;^@h*8GNcqgE$NjRHxb;jXyH)9GGvm zS?9B7=DJI02RbCO@viq`!ANj%_r+Y4^Kcr*&@QJ$*E%-^K2G@%-g$*I0(Lv_c7(bn z#N8@y(kPe;U-srx^RQPDFp-)ciykzeDj(8KoWLI|_^uE=El6AO`_71LQnkYYa_1OD z3|n|ddm=d~lkeu4=v8~hGjy56%dZ+X89TzGQ2G4g8<+&RT#c60N_6Ax*dgRa0ELqB zzOq!*SOVImb=S5?Ru)Y~E1}E8tK+5Wf^8VvFE8O0nZ1P9wn6=xlE7#QH`m?QGtsA( zU`I`#LQ>N?G=t7jI{51qk`X@{<2~{4`<&xwgU{g`%N^uCQ-t=jBXaG5p zLm=JOJOK_scV>op!8t97H=Ssl`#`S&{}2gA<*8^s-Qvr`fUdBNJj%7L5PEtDK_`fK zCp;59YI8DCS-PDYiFMgH0n0{Art*ol;vD(z5ay`z=pk|zab0J=yK7rve}3)+8FSxi z&+yB^K}^wiF`ID^`ynJr)+KH0o}0TEls`k98(|ujrX}NuMwV&UBX!gO?g1eB71XE4 z;FP@XUeVcr>n@gT^Zi;M?HL96;}RKJ+djE5Y0s6^*tM^Z1jg9wVu5JqDRJ0zvgu)a zypK}g1gANdmvJe*5uvqtgzZ;O8drO0XkkU1Kxj!iiw6;D^4%xrjjcO^g`oR)%&{PU zd5-St#eJS!J|V~s9_`|EUsAD!uk3i`X8s=EBugISGxvUz@0PYGmq8jDD-MyoEYYn9 zP04hzZjlHlX+707q#lMhDm#KL`+(uTBEe7;We?Bx(s{9MN1EMCrMXXK)DPtzqJ*CANL3EpJRCxoxlF97WCnpwTSa!qFS zmGa?4(wu=?4<%Q9S|0c~K4kC#1&q8i`X^`UQTgL!$!@s!e#m?*cu~{m2k-|m{IlWK zAkk@P?p=@2nhvx=+aponNzT_h>9t(PCIA*q`Nx28@?{0_o_a{u_K#6_ZESwtp$f6d zOGnRIYRS3tM7q5MMJ}TuGwj_5jE&qmiS$vrS^C~qJn`_STwXOI&lHf}_s^FlRU~%P z_)>_@Bl2t%iyhvQuNY~L1umEP-G!01t14s;RtVt%_ZSFPIl*ID=dkO0>+w1X+M75Gt&Nh%&ZT|MKwgOP;I3&vw*;)T1bvxAM zPcarcOoP<37$MM?glSFm{RN@LJ>>zz)R;T@`Pp$ksU)jJbgyAfW=iT{Rq=#6oH;6J zwcjlQ(fO%^v_D>+t{LVBH@2Yv@2W7{~Y(}CLrK>Qbcn|$q zW;Lv#ecJEM5>*I+6QfyFmbK0fNhteXZrLO%!#Rd9r^WF|4T5^1E{7s6E`Eg&BlQyi zN6->Sxv>{zq$4Fk!`>2AQ0vS@pC`~sK*=nN(mv%l)B%KCZDPo-eI$pP9Ncj2eeua)s{O4(tEPS;FT5S}=mO=jKVThv9${V&xYlOU} zL}XQ3uJDR0d_~Rvw+>>m6My3kL-J+R1TE zT?DzA)3U)jS1R3-EK|(ynS0Eo5TSJ9L)tbPY7#sxIhj-k{M0)ZPnQ zDNIjSP1>Hxt92_AEiNlc!ri!RD{hy}$3`Zrl7djhp1m(P=}sHV*YJ`M>ZV5>r(t0M z#L{zGszK57*bFkF{lXy|afzpWF~9g0xPOaH6{%aUC0C46+PD|O8tj#(6tX(h zP0j&7D$~ohW)_}4Y!}dYjM)v}W@%cgU17w*tisAW_-99mAi@LKyXy77vD7EQ}P;}w4g-d zX~)Sj@l;O<_5Bj-@1_Bd%$yF81fc5H{MXN^Hi^ zwx#_9@1T{I8`{+mnbFlOaE>pxBurhuM7;+0^`tjfE-~|9Hn8nZA!2O3&XTrc9mFLh zN3oC@Sg{T;so`A%JxA2r;)1-wUP*Oq9?Sr@Wwnu^K%i;if}{&s27`@FtoB{cJSLN? zQcww_{^Li5de6xxl(2l&;j%0-E)_1PjW`d(jpi@hX06tae+CPSOncL9mYJOn^*1I? zue5E+(c}V6#Cx2INUp6S*5SJqD_0&a@j)ay`42p?G0-Mii`gu8FGzL7eL%@h7;d|z zW)x3)*Lr&D!xCO~h%Vt&;??$o(TYrSJO-a*n{t;MZ+rp>>J=p8!!fQlP{t9g>58oW z=plP{#U~w3g{8;9RZC{G4eDK%7`d^$9b=>y-0?9EZ}ecK#-AM>K&w@`^$_v}T_= zY+lx*IZJjn$#(-yIUN_dF@(M0E8uKtU{{EPPFmf@Ckmjc;r`rbli~_#*Cl*exx@Mz zj1{A0nQ)CRoZGexB3^C-p%L#{vApKu1X&n_q!NFeWsv&Fdo92b0;(WIS9>4`Fq_2Iux5yPR<*I7`@ zF=!YlBijHXpZQoDxtF@GisjirPPK&BkO6Vz{-T1zppFYCb9l0@uw z-cJ&@s^Pm4864#8PQ`MOnD5G_wR~?shk9*$>LYgAK->L>+`*1#f~DW3*40&UQ|z*A4p+;x?NXhiwaZSj_u3*8{687-w_=9>9KRnp8 zGGth2D5sT+2h3+18>Cn2C*|(oppmFz4Vc_&X^Xva$E+#8T-dGp0IOur_p57$u(D=W#-Evg9~ctWt$kTl%>STdhWV78_nXawYv z>4*UajvX;Lcho#8*F+1{y7*QD{zf!xsv&AGx+!(IbDNlmtY2$c_s8C7zBoIy|P>aLV zGv{Mb`QG4C+zo*)^3>^kh?rjp^x_KRCp4hF)dA6CajSt4pOhhH_Fz?C3bV)R8|bG# zg76wMM?a7Ly-$iABt?7hii({QzN9Lj4LS8@)Efv9++!fSfs@V{R%Mf{NNtlnxhy4G z5=&*&q9k~9WXeqpqYgA7ZQv?3S4a_z<4msOvnH5`4U$)cz!X)L3M?%a5zMEoW(R-@ zh?ejC`XU!@*q&i!&d5{3!WS0Mo2$>+q2IjN6)genlP4NJY1hNboU#gXpcn#FScZ_h z1Gc05(PLTG61uJV>l5~9+upY0Bn%AU*AxPmH1!Hs=G6#-LVF+I#xwD3?MSmxTbx5j z*!T^}j?PX2u?8*(1Kj@hY#39Z)Sqf-UqIlKF;-!T;eH}j@IH|_Z*flWhjXjuUxsD% z>q>gE261BR+ayVIKu=^9i09LLI*Z8|lmNJOTFZj=#_q$eD>Vv3o=@j9RuV;T0|uMQ zu3tFcySTfvz$Xy6L&|$9^FmWQm1=!VtN?9EkYzdY(G_F_Ro9Q9v|3236{)Uifc&7P zsR$Scv$LUD^h!6XU=wEeiAKp!-eI4w<$|7mHexWU<1TRuFeWmI%`9F)|7(9DK5-RH zVw?c_UevC#sH75c72-rCNkW(;vKbPTpp8;RB(aw%uo$8rb#f+2JJ8b(qfhrqGy5TeL>II}0H>nKH%O%{dfd-n zr@YP`GuEW0nMbYAJXjWR%C3_*FB~+I>$9L3C2W`-h!8ZiXW`b#K14G-r!UfD{7GcW zWM;dDSM9rIqi}v1lZj09z)3(>M!I`kS| z(r3l;gv{#7VptaXl|V5f5t)eEWPF~Xnug#=DCJTcCyta$oOs#M+D;r7|ur=vG-mSt8BWa5%v=dmO$kqtVpJhmu1g`eKD8?#!m zd^+Z=+}Oags4Pb)JVn1gl3K4PSOfv=~vm{+Sn zy02d3?z*bA%#hVGzAv=cw_q6V(W6gU1@=kZT232t%QBmFHtfYv@=vLOQ-ii*LI(Q{ zY1jQphmjK2yV|e$I!G|1H>*PJ(v-a;E?zHHINBDCp5*wmqU0fL(O+a)Iqq3$bt$#h zoPFCV?&^U9)UhTds)#zL9sU=xm-(g5x0XS3yK;8g(Dt?K#4Jbb)Zvb=?fw7l6SL@i`xa)xgwCaA8Wvgz$ zncRI6Ro%bLoLawx)!w!ML3|t`e9e4LTmA6%9@okw#TVlgbGdV-(m)P`0tCw;{}&@g z%>hKwXjXIYFLW1-;e#M!q1PmtpN*&|SkuoS@?hZYYr8Ko2B0d0U5-!pMkbErCHWN5 zdf!Jl<+2WBg}Qq0GR^Hn4d|@(UU2bdx2vxb&9Mdc^TysW%(1-A!+aIUS?e3x+Dryu zf{Rx9$qyOZ4zcGfw5m!pj8Px3LASlyx!okxX;nE4vND3~v3xA8g0yGKNBU0f2(klrj$UBQ$hVPNyy=!@CwEYZ9St@JqbC%@2 zwZ^$Q*qEr_Dej5fB9Vhu@0F#SabEry+Pw}Ke;2?h09fe=DE&FJuK<-PA$y0PEh8Z=n!rLI8;Ywr*X%!U>~_5R5nku`_kE@iRsk!^#G^(YfT?~> z1JsXLplI6cIv&rpEA8? zT0lGR2DFyVy-le&S-Rm%LgCK^J6fl1p{hQGbG* zP<;=L3Gy*y47ZU~RF6Xlf~Th3m@m9pD#N|BXUr!A(cwLytVpNi1FTz=S8KAtW8j`E^-Vf} zy)HO47sBrSHk~31_CIZBu@{#Yad3o2q+6L$f+7h`1!EP|Q(`h+A8|_h9tqoksnK?B zUONOqKgd*8(_QY!u_d1Yhn0PSk7z5l=#bPGAU!9VMC$4%A0@8xAi0`?eV;ZP>S0&) zX-@QMvisg3w1xt$2(J(fDHJDw#37Vroa5$!bc^6-wYOOgT6;&fap%F)O>d7wHQVg- zy-L4}xq(3eT+oJ0Q03%KJ4KunT7xUZs9N|!P~U_Hnv@9ejzutQ!f8Zj_5^}qE*bH$ zZsSBny!=gokEg|E{@liRK%JXk(}B$Z zKqr|dv@z>^9OLHrEjs%Y^ufJ7NkbPbz5q8~%*Wc>^E|Zx7%Lqz@%!M$jCF!3ia5=j z`{oG5L&-z{Nkn)k@d{lg9JD~AoHZrJO>qu7H8A~0Inp zMPRpSB=Kafhx6mDa{Zb^;OaoDwGS22{afzPz1IQlako5r;@TUP;V|>jkcyUv5+^|; zE@i{*-KX*ClKtRTlMk~F=EF+7>m<{auzVIkXgyYyWf6hh1Ry}}K~Cp>wvq2>Tm^u@ zw;fp&0M!Ft!coj#4rPjPo53s+NSvQE51%apH>Gnuj2hi0VR;#Vg_ZZpGNXawek_J!n56)- zEC<|dPbNUswVpgh$r95}$qzqrawFA&|I?RE!AojHNTf=ZXf9~O=*o7lb}j)H2LmH! zxlDcZv#p({=DnnuOYB@=2)UOCFha(EDwsHtqCsJ(YV$^y$TiXGK4r!w5IDb&vg}!b zi4=?F(5(cGslAi;%8TxRo6|+-as!3bOjL?-(GM*K(?>8;jH(#8`cv(|oS+n$63sn6 z?EVajLG>qwH3B6MV%h^*`uBxM=e5QSahvUP3XH7-Es(8*5)LhW3Ma_`b4+=X0I;Z- zg|c-Av6=FZ&ja{gl9czNGy}Q6e2s#F2huYr&pk=Eq@7LX21HM1j3KG~q6tPFMyg#i zB~ua+ooX*t=#~`wo}N{_6=2_AZXNMnv*M6SfxEqDenEdjvr+SovJYrIzP|&gHJTV; zSOvRVwie!aLhj{#k-0FHDD2dkpkWe%L`-~&w^V5H6J5;8?bFBXGUkA|Q%iQ@z6y}y zfdN+Xrv(2x1LiBTmbsLqeliroNT{kW`+f_*eA;d;nz{1@_qk( zlz)%j=gVZ#pL!~qP}ljYH6D|LP0X&aQA?>#2ak@y*cJFVN+lWo-@#+Z{W9iku}|iV zg)JJ=n;1xY(aiMpG6*%VTl`!&zPMaEj0;=S^X!3f`oBfS21bbgM=46|rZ2Dgk_H(f zkK=vMhbfx@uF({P1SP1G%aMu z(MnSUL`>(96V6E@purjC<5e1X@epR3&{TBp4bXcvou-;*)?EXwNrUND{Pd|npVGeV zzK1bl2F592LnF0r|!ronpcwU&oCZESqsP{5qWTR zs63hNydPx_mdEfk!NZB!dL;*-|K^VZUmgH4NN# z&R~9I)v2ui(RRK9Fy;Z-5VOYL1(Qt)hKvp==WSdaLVo9QwV0Bb!Bgxt*<^(&j?l2p zy?C;j+&TBTAFj@DAIK<#>4P$m;O9U>0b~HEv}4aWpbz*>(aO6Mfw zL`pxqPgIk161)Z<$URvwGdeA+Xda=2oxYBl{tzK0)_J4`E-(=DcT(fg8(*XM@2&q9 z0A!M`=)1_Bdpdy#W>V(+fvJ1C?*xq2{~-fGBF2es{Oo=fxG&1EerIy|$a-f6%zgvr z)BIfu(!q5o<~NzNvIt1ImpcWwx&s=nre4ItoyX$=R52o@WW~vX@4qjW z>8r-ogsi|A(PsqVDIGA^I7p|*868Gr1W?8JyGv=I z&+Zw8rF7i{Ka`Qqk}Ax+c%=(VmdTZvV|R^{;lEw_;=(RZcM_Phj-}Oi0^Sl#f;l7k zgpw&97)vHP!M980!HrVdxKf9gyc*SJ)uwQYV2U|g1~41x5u(@FB4#jH8xP7OfyL3 zfaq*N8ED=Q6CURI82}mSmF~s&bABy)g;N;e{ZhVb{Km<#pJ(`&Hp!+%3)nncP?M(M z#(1uJh_mR3cY;Qhc2{-mhgMLXbfQVWvA~H~h}JI;m+6VTQ^F>Ic_JxL7u?cI`T*#4 zo6io5kD|}2qyZGblS4J6n|X-0LE@dub-sBTnI!eBom)LFHx}^4K~JiXqz|K zj^3KSo0ffU*q;@?=0-9B@*(H|xd^rZsySU0^KdiC8tHMv<>@9Q*)KngH!_IJPJk&` z$Q=btnjkuBFOo@qMhEKbk?Nsaqy#dhF-@mhPR9&nKe~1EW)h%VkqSJurvOGy zXZz02oph%bgnO`eZ(*)*#62=x!K3^06Rv&eIo_*)x8MM13;yA`aKv-Ts!pVEKtTS|N$HWy@=_LJ_=!8J8I1HyzhqF(} z@;*S*vQ|<_z|CaM7w?h!t60E;kQ!mTBcJ!q{GZ_P)^?I$G`{aTqgHx0$T2hPTAf%<=Gs;@klM`(;Tx4Y5!fw??&!n~-B;X%p9nIalK zxV?O~$H#DTsJ*S=fim#HZ~Ht4J~MK5=_zqZY2EKX*9WWPCV-x&Jojm|((Xj{$(kB1RNoR+zbvS-zY+<}{~bwplAD&R1Sxs)OHy_Z*h zmOHoeG+Q^6?#684G5|#XF4rE9?CmEvzIn!&VTPS2lhu-*&d0X)3F#7a@$f5h<3^mr zFCQJy{66MYHJ?L(qUtDxaBF3J|9ot0mS$e9VG~^5BAxmQ*G~xqQ%1Zqc7fGm*jytx zaMqFU!&2znPH&}Z%ZcEKf}kEJXV z+c4$JI|uPQ7$&rwL-2`h2x4h5AuOVH?nI4~+_^2=%aSOQ4T)zu#n-bhHkX&b@Tkn^ zwx`w{wfiOFcBMzt>Je8kW9Ht^&SMQOsWK5Kz0RdX`mVA_O)S}ZOuFc0(na5128|Z> z+?MJK2aE!7VrjLC;W_+$i+ys%8NfZ$QCNYaDoaLSC8=w2OeLVVNw0UlImZ* z5jXQ27s`%jBZn8d{u^AW|B_tQl3%R~(Xt%l>r5r0@y{J_lAvi&HKgbV+s59%v@e4@ z><|Y!1T^e#f~kJl6Tsm-;^xuNG;I&>QB1#p@?frE>08}x7{Y;Ur%k-NAfLW_?h~k` za$B!wui=e%CSqN(VV0J`qdD{(9cAMNu{B7`e^S6y7-^U!LIc90P`4lr##tE*~_ck&CtLuIWfxkDgbt~i}6uj_oB5CHj`8c*| zok@t9Q;~>+mJyU`+;OHS|^m>YVaGSywb$`-SO-?TGW0`^w zFjMpVKhMDRlk-!N{wyjz$#pHc9xgYE~fGZ@hZX74FH zn?w=0QbRIT1%jWxS4%xRLZug60e9Ccf?Q-W0dCcfAJ@#aoIsZWfIf2D5zXLSabU$n z?pjP@MAk>WxC3}^$Bk*e6-C*2+aR2fm7#0X&!jm4*z_);(_or#XGj`M_~ zfrF-PsnC0KXw)eE0^B zzOaQ>bMe{hm7{#jH7STYR@230-+2xB*OKw%ERJ5>RV_!oRHu}O^3I#Z;mMYojc-&J zCZP`UPzLnvmzZzUpq39!ZOsfr)oQG z*|qwq0Nm~`;;Nv>E(yc8n+jVg+@fjl4-o=B1!IB^6YqB+wX^XLB^D*dlsuY~A-V*l z0@X;6H@Dj+9Z&!K@#Nv57IWK_xj{yVH>)~x0RR>4G?agd`i8(uJCSKcb~>Zs3nT4$ z5Pcg{cOl@T3H-F0WqKV2PnhJgajAU_ts}V3&SxAO?WK_6IY#=!mr)uW;;9R{oMx_C ziFB&9KyvdEf}XksTvpd>%OoG7KiUETR%%2iBSPw+a)VfHU?;Yvb`&(=~%S+*Ul2a~otPs`)0oA=T7n@om13%m97&+O>$hEa*%! z6_uLu+92j9(DgNxO`!LG3We0_(uUb4MGgfn6<5dG4Q~YNCE%;VzCNf>A6!0-|Mgif zgX~`KH3+CK7jZuTRL2ibWniRY2`fTEaBPa`6V5%_gh;DWZQuQ5d%t0?QlWQTcK~`F z_3-t#DrTFh`<~zbLDNQ4>A-hx2cBl#KdQ3jMf`zdtMYQK8h<>o==!l6pSL7`+_FDr z?Va-r@@-brJnjna+?_m;*BF~qXD~#h7@F|-ZDFL~X0(&JU0WE2iyX}v>D15|DG5G5 zdQ#AQMeYapk{GH!ZBjX0L)cQ4hI0z_7&KZzU~{O}gxyh|tx!y)9uz%K4Wg+lS+laZ zq6kUJCS@RCWTw(^S$~r^^hkM7;04tv43QN`=O11DrS6nt>X5d|$H26q;{>xej7M_< zBQB5L@YvG#s41{`A$zZ5YO%@Wo*%>OJdV;1P7!1N$w#hcb260_)^d!;-!5qi2K2mF zO{ZR~#Hnz0M^%k?j-rEiO3Fqfd|N|}ns-Zp5`!K^jxqjdt)92IR-c|Bop-M`%H6w! zaaawaSgJwf%gR{KYn6lb@Zb}MiMyL`&8%Nd=Ib|odE@O|)FV^>{u&geB1CVch`EpKgJNKwc^~QG?j!f{Ak9 z)u~S&_}kK$dukK{69xqzhwh9Sr2g!v@kw}k)e!?^U_w@f(NWrqEbFp`^YH$wK29zo z!czXpM_jf=484KgtFR8O;4WXjd=op>8gJsMPH)rqR(~6L;n6`%GRi?I>>dA%_K)6> zk-j&yZHXR~rM}R_&tF$xpLX6euaho90Az5H6&NuXcxdVo^>J3zSi}zHri#!0CF$O5c2l&3m=h{`SgCbZD%{n#Hg4=) zlI&LF30-dW0r}k$F&J9#2%PAxt`@N=rU*cHkB_gxFwGHX)ioIyApZad1gY7p=|tnOv}XsStokE&r^t|Z3stL{F9GV0B@8j zHzoyAyb9FrSYzP#>rM%f8j@u2;fRR9L8GZ>8q;U``Ri`GK)w2s{RxlL=GD(B-|3?8 zct)>{`h#VNYvY{q*2h_tIpsz#iAG~;RsWIG`PY7Gg*hF}QKNRnBKBW2rTmq^E!KT1>$8Y13wt@oUw^QgNoU>Pr}ysR|9PcnrYU;c9yr*in*1 zTrHBSF$})Fw&Xrv>eyRF8lu-4C#2E-SM+b59*_}^A9Z4vTpM(9lNY2T)ueM>^>m)E zMH{qR?c*fy{d1dfbJ0D!|D#v-U%%z9O#6a4d(pqCUQ^-i#`M?3vJ)d$dN=deWj&NT zXUo=j@vHow`zAzO>iYcoG+R!C;j+!%LtW!LE(18hvd@Curf>7KArpy+-K3ym^m5oB z{>s)(d%r}I8GS$t1t;oH!2V=sZU+*LP_IIP%0e7|y0#hzSTImsSF;S>Ht9i5&%v>2 z|B1&|vSk6*+IaHgD`UU&!1Xl^5lAK>wd=A{4}J=xh{Gx{{7L<@YyR+e!n` zPD_J%mo}Vr9%xJ7|9e9=lWB^f3NlQM!A}Y%CUp)*5rP2rlTY=!kumMiZ#kjE*;UcT zrUuu_C{^7tmwq2-=Byffmm;$e4h}2?IG=unvJM9ahm5XpcI|7=g*yu5?r5AmaQw8^ zXN6-%zJ>4V^WZoBuqat(IVLED?k8rEX>@)9J$3~H4V?MH{>-;mu3X76fofi}cStT^ z*!r0JP0(*ul`5L>OD$@&6~)}M4Zjb8^%!O2Y5fz&5QjS}IIEvTs88MM z`HvEqf1UH(Ot$UTs^;bAcKC*bm?>{!YPiiyxG5WFH+&7ydx zHxCUsX^hM)Q7_Zwk(wk9jpDc{J zfnU<6bON#XCZUXLR{;`VtqtNZd395C_)5OU&p${y*C8;|lWs=mKkqXW@qSuts%kBD zlXe4YBbijje*KT*bGbYHB%+*loMeoyC9QmwA~tl**lVV$qzv=UiN#@S963D=Tvr1SbE`Hoju)V_(YEOQno&di=JjbccsRx7SJKh>$u{ zfIQX#WrUnY=)gKP=-|~^E)+nnn*2|{{e7kig^>ze)4Q=qJoL`rQ=xlmmJbCOW6IKh z8rF*@BN&GC7g|NV_Xe{{M$RVsm(M95cbVO47_8Y4ypP>iE{qhg>Ns`={)H^OzH);|6$Rfi?9i?2O@Tqfwz3=Z1f+n(O z2xp+7-}iA(Rh0F6)0SWODv~i3<;eb}D<(ne`gD(fzeVu990kfa=u^kxC6yG2mwiv} z2LfAl`SQBP{o)SFbjM{g_SS98N6TJhMRnwP!YiH_C<-32kIwYjn!fbe8X1oc1V$u* zKHIjheKzpxnLb-YoyQ5;!5-M7}<-#+p#o6`!NIr7IOLjUuv{i`6bO36#<-N+>1 zV6v6!9i_v~Tt&_SJ@2{RFZ6!VV+DZ~UqCU@x;zaDY^{thZ_NA4SL@~HE zC^!UKNhiN{pMLj|-O>N}@(2!;W*<`Mp1Gr=h=(bw{M9Vn5yCcFns0cIS`%Wr31I^| z5(TTI#ebGMMl|jw8X}2@w)JY9HuIly;0Z>kiP8mF#)sGgj}*t>srjD3NOkX` z^~R8(;ktQs9NgtFBjZqDL~oU;c>F5(9LInG76w{i|IWJq^`p8nbL8qDfN1%*)aHrr zTeTZH&}ZK@qRt9hyl>fL^C^P9gl#JEZylctY_iwi5{--+sAJ+A)1asNW$>c04XIz~9M&Uo6?l;%i{1<5oG28Bd zya4N4I(}6d+yC4M2Wp3RZP0T?HRz9>va5OZAT#)Lg3vR$A22)+?r+NEI}xtXcixcB zvfb%&=X6bO>T0dlgZ{3t^?U+aZ?o<3i9aiJOY8dnOFLFUQ5vQ`3Xh96{hF|S+cq7I z_iv!W!ori&LXxCJ8T;lRvXP@SIeYzUS14ma+dNK-GNLCB5o2?UbI6B`j~+Pm;l zW=?lS&G44jM6eN2^8$Ip#K6Q$hKho~d9B&!cg|U7|Nh#o<>C((Yx#ZN=lOg-&+UER zf+B2{PKCjLzfOAz9pg3ID9a4*FLs>0fRe2iY3ooRO`nJQRQyy=F^6#_z&0lDg4Mn1 z@39mJGS;1X<#+fR{x|p*T=DX5-T^KPzWT))-g<_Y*R^jyaJb1m9#ICDZO*qAUMc#D z_Q0}_cevj)dS+E6 zK1FewGB!mG%-K9pyeH8=F~lx(RL#Q1?1O>Nyud##2g;H9mJCWDc1-dj!Cw_}_R-KE z0!xiU-uMGEHlm&OZR5a|Gd-1is{Ir94cCmVvYVz`>&X(l=-hnclzLn$OR9=`n0m?og-G(E>4)vpm}8CsvlpkATI+v` z;7*)^oEe^Pd^iyGiTx@$(EZ}u5F$hCX$D$QfI~80g0i*m&)vk|K9M?F2iLUO8h(L+ zmIPQo(ZpcbKj~Zo-udzgB93=aJj$X@c z>G^y0m*7vEKK70dw2D&!5BppO-V#FfvE^xpD>)~`>TPMv=_a(iIRD0m8; zgiBu<-=jFaxqA*!0H7j=ZuGj)fCAKM1-7ZON#|00NTL-*YvY^w?@zm$&g*$rXf4+f z90XcD)zbS_w);fK+nOkb#P*)|_j@1Z1^7IAS_}#IpN|j@@Yr8$ko6UVMuQ`RK;b7FuHiS0@k^Jxa zJ9|rfU}B^@^<7Ol8xkgVs3_%ADvs&3oDzvn#b}o-2V8k4hJuWe(9G&M?*YvY%KA8^K~-JVd83izl|dV6kxjIS(+ zjSwyg7e_y|n}lA37FiSRC%n#V6IH*2gqJMPkxkxm(KH#fS$BLnT47S{@6wb|5qLLL zmYX@?@9rAfHEK*vHOa=(W6BfUP3$XmE(HUK1)lf*xLQ_?l)AKXHFneIJc#;L(=x2U7Id#0uLTs2x!BdW z8j@c90r?=R;tLG_@99+FH?X^P{0?lGc$l#&Z|VJGZOF>UPHTsm^lOoPZ-#p1K=Zh* z80nD~tcHX^&bZ*yD~7b*4pe|)SXeT1NZHY9bxFsusb*;5lA^B}XtT)vpr07?6pe8{o8>6(XpD=XzfPQ)nOp!=Vwd7i|O7%y_OvP?zvKlRPt26xoAEJWD>IS zU3@o?QLW9oJR$8>e`P~fDiq6ur-cB=uFLEZKyq>qnt@j9|6YDr@On*u1=43L{P&O4 zT{=OIIbYkD>8LKW95K@s=t7Y0BiAH$#Ds~qfsRNeOgY$G*_Gb%(r6e~)lYlK7q!Gs z7q~pR-3>0S()lpa`m!n7g%7+L;{XXODh)`BjbMGF;){Z3x7+GiozX{*pZc3ONw5CzpJEjRzzI(a}9|}pK7Ui-w8Nrlm3(2jWQ-WLeFQ-+tvZH>ZgH+UZi6aBIF&dLz3-0oLG zmuvd#8G(bk9fJN7FTG`B-u)A&>FIIf57WPffvk7_sMk_gkElOl1y_BnuC|xPG83A6 zHfFSE4)FcJYm3&OmtFqL5j*6_P&%_+_Wc(!0w|tZo4&5V1K`nlSc%`ZFV_~d?0ZpS zQ&NXFD|wHf(iIFSd%h99PW&$*?5PhxnqY3G#75YOpjG@#8QUO$2=0T-tUV)DU;USxhOt{`Bgp&=*9^<$5{plmYtbLQK?1p9mCS zzv4^Vd*|IoGmr@cC^3r4CCvJgA@$5SyPLOLACA` z73D)TBKkcHWTNnQxkj9Cnr`@yKj&|L2wj>0f)WpMHTk>;#CZwSJL~6n&=@ve2=@I# z$9KW&nme6a4(fI#uO+o9Re!f}@#WmKq;B;udav83TbMC`_)4bl;Fk^39wN%;ymL!G z7+&^`vDa%U8@O|;e%#=5p9s2nJx2z*zu$41SxLduUna=#b1^leA&n$i^&e(WH!o_A z7LBCIRQXUxTO_duLv`gic00a;cCZ?}N5sD+HYYyw)0#oKP8_kT;_z^@p0cowacCbu z(?i?YY=0G1M0yUzhT6>eY@g!Bn@jGHl~H}RzJ0b`IX|auXA6!lu(pO+S01L87c<%f zKP=dN!#&5-7suCvQBC~Gv_dbJA4j1P1~KP&S0`O169^K=QQ0x;v4?s9A~#nijSh9o zLh0%ip+jQBHr38E@>yY3tb^#x{MMv*W%Fg?4if$VS!Eql!2bQvkth>|aB(j5_Do;1 z9*00%aO@@#n#`5HCz6`BNaZh+3iVeDxoOM27^)OZRr%iOu15+o7&%VoJWMRFCN=Et zAbGM;NG!DqDXlfZpiPEr?Ii@bwC5LIcuss+8Ul5p)BP%;KLe`3f)(K~@$c4D`p!R* z?c;Hso_h&$37j5pPT>(g)@rUdf?7f!(GXv=MW;Qw=b7^8CUv!Pwe%{Ph^%GtpQ<9S z>+k0{3fdhz(3c|JCEx3QoUp?bo->#X46&H2e1ChX?nf0Hm-fK|S*{tzlSwmt zfXd(ab@RI z{d6^i6coQ^A<*B4wy$H)=B6AVaS&sMFOmECmYCKXDXB2@xUWJAO7jdkkrAB=BZ z|H-OApoUG8WEu`^TFoq1G*&Xj`Tl7C`BQY$wzY5KwI7{n3A!I~v4>*aygQ-7?!(6> zhPsvt9OLdj9;K`XzyO$w_$=ITkZX2mIxai=;SNLq4p$yr?^W z3SVE`Bnt7D4v?OA=$c{+Wf=H5t9AZ;q?5d0_B#w(M>?m4_k*U1t!cL?P^B+od0ry4 zPo*SJR-I4xx|QiJwb{M(#hO`UrsgJ0CcR$SSv~HAo-S!mYKu=IM~{xWVhiaqPhNZB zUgqH(=yJQ#KI`ToICa5La4=}t2QEi(990Bb>JCnPWiAej;1a-=ui(`I`mqffbr&PG z@_Z3{<=Io0?eTy=f~M6y%@6pGuM#d|3#qH)SvZ;OZ>}6Gb-NPY_AhAs$^%V2>H@Xy6OL$500ufJHAMn9atJ-HexzICKY-e z+fT6^%z!Z;7jaW~jlySs7%J=HRxz3P*8P*=VGUrx4tuTq5%>P8BPC&~{&V~ry-Mb_ zyD6!J#p}cAC!i4siB_Q{{aUZ>)0QVUsgen^=(TG)mhR|r3dP*xk8D>ZoCuE5>VhSi zQ<-YWPO+Kf&`tykMZ@jqyFSl82@7JkBw6xNbdEc}lD;aGqS25aHXkwE#UT_ixGO!B zi3d^nz@IE{U1U!z*li1J;$sR?&(kb9f>Ua{G(*maCPjkU!_P?T`mNA$Zr*3VcMOV8 zZa`!cJRBrM9&Q=yMOehTN-8%#zG6v?0$q%gL4kG*$lJ)gE5YV{@t>j^N>;%Qz{57c zsnv3VA#vx{hi|OsGC!ZNchRIP-JBQPfx8pI8vyRg!Ip_#b(dEQE4rPYqahRc&5~kz z@-OL$m)s?W?a797osG$59pu<_x&}T0WE0i>Lq%Q&B-ivQA`iWIlpk)re@-VZolm4C zquWqJnm|s^P9$lrFSHG3Q`3AWnRk^KwwCzQzp%u2Z8YAMQPA@+k46Fv+OxZanJe>L z+}f5_<>MfM4>h%3T{TyZpAM2qnL!kLX84I+6DMKf+TEO70`owp-7FoFM!q=|4`4(X%_x$3(sn-dRYbxR$B2R2a>s=P?*YkpZgc-rRF2x@!fp02-W2by9 zf_c~zg@C{^m3OwrP1H6cUqN#-|3~=kAB3(=Lyu%41DB&VoGTJP2)=MHFnW)yK6x?x zY;e$m=h1|3m zq7_sB@y1{Ewq-Tf`tb_b_`scAfn~`uH^U%eFsaPB=1)r2oshYYZqdG7^~%6egw6Qj z8wgco$zyB&jx5bL4r|}_Nf~uhHwtmNWXtQBQt~gEZn$rOrp#>J^X~8)`rCuSoJcXz z+scjNc%%NNnOD%T_W^TWnk|RbZG9hY4u40~74wO}S*nldSfXgFi#BddZPU5#O*@9lr=!=oQm&34ZnL*t3Y&w~)9j5S z()VI+r6H~!PVL3qaoWWt5kt}qbK`ik> zZnuDwIU2;+RK%0=-wUM-%Oe(u;acz^B#K9bgiw-i#XQD6?9|WmJB1WF?Bv+-t{!SY z&BR**U^Gn4Jz0+1id+2AiJD=v_4SCp94YZ!gkeJ&IOXl55KC1=!BU`i6;jFAQ{rS3 z7YM)LkS`7^l)+|qs_LdPsS4>9t|PxP=6FIlWZj|n{RQ3F(a#=j3pqEUJEtg!tHqXSz`aznWU-e+<)jAtkKAO^UJn`KN%&jZ!2Ib63c?nV@_uQXbPhn*J(4 z7*cXR)sR_Cp#54$lcVr|=F4hS)!rU7)r@pmG1a|;MkvG{D^u5T{(MFePRrq-p4-}YacR@)DM|oORA6x z9WiBlq1ZLB^l*;47E=CAc`F&6W2_<~B^B?+rfy^}IGdMme1?>&QWq82eN5zU5rxRV z6}gj!*2_a*V(^Xf)DMB#<&Tx+xjkImBMq*5CB=ZvC}%0l>#~&6-`*}w#8>J8sq$L{ zPn^PTeFShgvG(RUgtC7taf>VzImxi>7^&@kPM-X}aCeIYHE78x+fhN@-n_KT=`it4 zHs{P(=ual)FVMx2V`BG)GYxtwf@L5X8`jUhnJTXnJK55!VBBUuAzeOY!6D3W1JE9S zM-n~xL@+8OM=-BAN);orm$)bgPGx8Vm?->Mu(0zioe<2+N!?k43d@o$A+3oAC6#pa zpuJSMr*4l#7^nVTi*{-VX|S@xQsHy0u1p^|H6K7U1$R_Z?6)1IU#VFN-!@Sj<#GdU zYt%0M-XreMG$_^2=0h*&iX$`kCg)LPz%=ZBEd<(i;`8+#cCC&@hU^U~K`B~o1*Y$X zFAKeiNTTorH6uIz&^|M5E#jg9e&lHZo|;IYkCAT#1b8rzarv(NL}D&YQr|iwkP+!u z&q5YrnI3npRa$}N$gYge<39y&mWTF1*2aD2%DO?)EP2$hWO%??Y{V&SbI^p-cK-)E z>dDT$&HL%nu|a?J{N6$jpi(M*8W75xS9JfQ&5X**wu?l0gB4*2fd$yxm#3fC#@Z$C zc}QdE>cXI1FLbvnSr}lov*4?! zpGr<{wxkA@y)mRi=!QeXu96eHSi7J;!AB>4NqgXPAzk$$aKUVb%ZiNJm6I=w!!I6X zCvCqb*zkrfSGy@ys6i&4W$?}~&e_8Fc;Go)PqbmgRA0ZqY(`ivNMz^N>I*E&@%>mT zA%9620S;nld*~xn>D|~*CbAtg!C>7T%s0GIca(xvDi}u%5CL-|NOs+)9k}jq7+<>> z1>5$uOLr{~7eXW4F+Cy8-gR}%oCh(ADBsjsIYQCG;CMM2Jy?PzWZCDB?u<&wJW1Q_$d39gvkpwi|2VX!ME&?rUm7OZF7Dvt z+Hn;~!M%3P2*v4Qor7{0rU9Id*F6O8AQu+R=#-#+$*Ry@7;_$e#@bV~4YGr4v4CX(h_1iNOXI9G{5a0PlY8^R&&u!uM zxTLcB`)BDS=qhG2phW?l@M>FavENR6lxE-}FF79EMT(5l;Cxehz9P*gb#zev$tryT z`eL{NVXE)AVEzWQ@9!o8E`gUzm@z4DgIC*Vi;-9H3tlimdqeG>IFw1b3Cqs=nU%>! zgLB0Yu_+L^UFUo6>S2x>Z4b)tUnj_nvxce94#ROk)9zmp%|Y6mpLn^d<1!y``_{Ix zg*wkdx{kzyy((mg925lCb?`O4fml-GZB%yN&+8!;fw<~6xew8tsc(5KMwOe<13m?d zt3cp}05k*s;&vPcms6^5tl|KjZkeI?|$=65l2>LL%xVB-vcQ~+;XYjavYI(M}$@&T6IoX&)YSclxo z|Gx<(GvIR|PQD%1wm@Oi4tg!G^f$fLr8v@%m+o~#c24Mj!+WRyO^25Ol4ets${x|U zF91(Nf^s1N6DilQHstXQJByq>nQzC;2k*X%Kgc}nQ9VQS9l52hHBQ}m3(MyM&lZSW zuc{>NFC#&0nRyfET#n%Q0&APxle1F)vs{gyYlZVsw}_QUxspITIFpOAJJd+!LW7zR zv!S{%4c_T~A$ypA5(n}LmQck6BiYOHXjN!Q9jwIT98l=%F65@$j-r}TqNO;M>X5E^ zAoU=x-IbRC&s5`g9&(Srj5gAqxJ$^TBiY3ELgBM+yAHAZH$Yb1u6LrOViwegD&?Vq z%%-5abvIMFq=}{8I1z&jf38;BaLlN6`ihOk6zpW2#~_k(aqIkimm|@JE2}(j6=!n+ z(Gf6``sZ7zHWVW79eRe_KrX~yQ$F4?ecqKLn!;LB#dmmz4GtkNJ?yl(twg|vzHb7lC9OXv+rB?69y#k>p8{`w zYi*_yYCQ!Howgi`t@0nGTdD&3pz}$$g%Di$pqCZ5u!yngmDO_VBh~?>U24nU1WPa? z!Z2lN=+&5c+)502$<>f#GvhmWIljor7bbCx9qboJg4ys*ZX^q&vg{;8nk$b9Vh4GJ zl0-A_4(JmDU_trs0uC(9nC9rcuun|BeTi-#5mjWL_;?OeG$UoZZb`)+H#})AMsaRx z5lVq4th{&Ts5o$Y$=6o-qesk!g*%PA;&R`YIb0a~ez=G(8WW^pLmvKV?iHHtIl05z z0wJmO;myt;K)sJALNggT$qZd5y;a}zT^}FoPUc5`#0{F$a6h8@cN2HdS~d@DQFCSn z-&H<%^Drvc+m4)yFpM#uum$7^nvS@It+wq!0c}nNO~sa#U?H{}+Y#UzMLd#m&dd+UlK+ z)3-q@H4I5pakYnNjrzfI7Aj&0@|n|aE?&l_xo6idxG`!NKu0e&y(n_|+nn_#D#Z!F zO#bGBlU)3Y*lfVmZ5d@PVczJ1$><*Mq+G$yyO#k*a`_?tl0+)LgGnljkNme zINJE!Eik`AC|D z>5FY1bXc5lB4yp@&B;ImMHWtVACg2QwwWys$HyEy5C(_jtyNeH-O1GJ!_xtu^8DV9_dh?|8O5i|v-ziPzu|(t+E{DezpftqMiE zxey6zz#LPfLv%C0VV>2#c#1v7ahb}#vNhy}C#j<9H5BTzJ9PtDdiIzYkp?#2=T!|$3<`1cEzZdr~12N$?8 zIeE{s?6+jO)1r=hd6-FrJ5N-d^(b;;lw74*60c{X05zEy``>=-_xnsx#&n1pX#aD5 vC*%FhcO#^tu~8@}ue;GPRvuff@pwJ|HYofuoeVr=4RrMIi9^h9!+!ctyj}0| literal 0 HcmV?d00001 diff --git a/docs/images/followPoints1.png b/docs/images/followPoints1.png new file mode 100644 index 0000000000000000000000000000000000000000..067267c23c6dbca61fd2652ce4886e92dd52f037 GIT binary patch literal 78582 zcmb3hc|6nozdNN;sT3hOOYA8j#|Wj6+~i!LJW-S*=e7<~gxp0YMb3B-F>FtV7_!Kf zYaQ+}IcCi^`+dHyp5ODN@<*>;^?L2|eShBf{kg4w^4R*dyla;%S+ZX1_z}Y;OI9Q; zS+d-SV-@(HD~cORz+X$<43DWV$*$em5B{;jK}}a}$&%bKPUe}F;NNR59XEGdvV=bn z`m;2wd*tkrCF~TfBWlK8HiN9yQ3+<=!(sWSik-SU3tY|DNNQ8c@X=jiT2YsRHHvsS z?mAsxvHe8;k=sj^BGQ-I?O6U~yLoor1$$w>;*dMOJ9u``a!s-n2g*FnA9u}y-E4K4-|$zkm#sWM0JcOvCog%LHxk*>y;YzVhla!#<#Y%x|)2Wo^opW>r8Q# z;x?ls`t?VFxRxxNG9M4qrjeGl`7?`F2BjjcS&h0Ggzsb>6L3OkkzqKf<4*7_6**cKBCJr`;j(^yf1d~(i_gz^Ydw0W4{qU%RQq#ZvzgW@$B z5&(DleL8j@K3qOXf3EZ-Sv?KLg}h0|sijqj{fWCo`t>KhZ0>!)tW8oGkK~C=WKQmv z-)*Dc6FUPj1NAG~@bFo&zP1~4czl9Yh^!97xC?(?aTc|w!H)YNqGHuQT#+)obqhjWal87_ zWpS`+M%}LdVFe^egF+7QtvB@z^-h`(Yrb9{0bBOFzr5f|SPvv&Ao!KI=uin)$)?Ld z(0=>J2L>sD5nSwps{RqYBlQR5cW-#-_qz-ltZV<4P5DdQ2v8ajyj_Cvkp9~o7GD|1 zZewVQ-#{tBx2m)Hk`$bykc;`YdxuK`UUaLvR@oo<9U;%w$H9J^RJZXI1f%PvF$dMf z^Mvk|D?6+CpRZfo?_oZ^E`U#XsgqUhm#Y_Z?=9I3+OzDcb&s|=w~#d<_Lx>b?XJ~;h(oAXhQ(5CHYbZ$>ZZGS3-i3kx&CH(dy&kelOzG zfj-mo#+XA?R37$x?ILchmFvMC2<&~Lo^}m?QD=hyykE0r*8Vi_WV5zRx)7A#T zg!tDb?OytpXWE>tOS*9Vkp{5fdptT2Wz@r?>3kKb*V7RAqMDG(p055#LS1A5{S-Ig84t2rBy=DE4a@2ZH{Jq^sLBXcc?HS_v+5X&~cCPGSOQ za@UD;3h)|!TU#1Zup~uvb@39%J|{wjvzK!5$2YzapK@^bcKi`->AEf2>ZO_VpSa&P zS7IIJv>c?X+Gs90kr1F~k%+f*AFY3R`~C|-PsFG|)G$WtSc6_MUU!LCc|U>I*{nOi>gt?}u9q(@j_JpveQuO8Ct z>*|)K^mY*{!`G8aA`aEn`w%Cbc2Zdw?zIpuee3&y8*x;CJef zBs_T+TS(21Aa|5KFP8_cFdbb&pWO+geK4WkUz2C7YwVgFxt7QwKtPj!M~o`>(Begs3(E1 z`iXsLPIBQOX~4!HP90ITK4~qvO>e_V(+h|pl*PsKM>sqNyGD}Fc5)JQf^9qz=_+j- z29M)d4JHcKKmvcmOAOWpD#lZ=HF5{XdHA935J<&l_9hZ{BF^(GTz*}a=eHJ_e$YQ+ zvQ?M_eYP8AJCx?hQE>WwgjJ;&n)KeSqA15S79Kburb=gdBw&F@;{O{SV!V3+h3JI1 zw__FEgK9(sE-Jc=-q}UC|K&i1nPK(wvw`XXxNkxY55-aUINz&Rc6+)EpVzw?Rw7Af zE=Q1=oq}-mMc2M>Lh>1M4NCr_Y@CI^zRU23dw#V3OeOY)Js?c@9gj~e$ph_FF;TNC z?Jt{qY}3*Hws<481}*{b1Kv*EQC%O-!$jWZs6>_ik*`P#YDFi%Dtqa+Wzx`@Bjo}8 z6&v$l%&M2By-W6D#|h78sD{xuT?K2CP9`cO+%f;Eec>JRI?-|MWzZ5R$`Iq(3Ji^T&K~ z-~N`5kW8d|*JItST)*}u)s7f${^MeMQSMmpH*{>NGd-^KWHBs?SvE>z%M;MCOn$>D;vQ4I8Xq|td^74Si?O9?ip6kK z_5IKkO^DUxs$t!c#1xB}=Xsk`1T05gq}dar)Ew3E4tsLv#e~*8l+C(Eqe<05^_kGo z9O%k`*=TYOvHSh=%q0|`^##A(TS#$OscId)LVK7&bMd&ThjeCYjwZFK#QS|M432mb z&k)s>M=G1KdsS7U9?){ilr++~{3ti>tHO-!dUY#(%La5jHPWOk3q_8F3BdWt;0{yFbxStIr3jgi5Jx) z^FB)HPU3WcZ5x^8!LGdh_{arWY zX+v3DOeR|t&A3hTu!*DHuw3OZ)viwmI)TvbrL0q*b8qmNX32uAzyUsnCME#<={-#_locALw|Z^?=zewD$uQe!b-xuYgn3TzcrB z=iq9hP2@V%6c42rDOJqm!gl$lbPYEp3VD36Bk9Qvx5Y8cUqYrf#v9gU(^fxrNeALN)9OjNnG$uc~d|wrRieClQQug^7tYdvr*9Flv_T#?z@sEGo_cv{&^qF4~ zXo>dZrl^G>!fRX*_txIK!aURd&MeR~G&0`3dVMM99$EkT2)yr5?fT-&LCg+rQ{AD` zO-07J3^*N)kWCCV;{f#gw+{G0dIX{#`aMqSev)1;mR8 zN048enE6S`Q#dv~fyDUcpDKe!<+i$c<@lDLM^vpz68ZasuNRuqGhn9dtJ_P{>R`UP zW%Wn5@QV@l|v9dps#CKj~(*ZWS>=e;7Z|F6zDc+*uaWw%{yVju!MDXUwZ^ z4ev1{6oxXFXnXk*-*l0~{KVxorw~&ml3f=>6eP9K6K-P&_hYq&07&n*;{eF4_FOUg zfCi~1sHEBIv$iflL{{8;}Jnzn9`*9;+jXl*t5eo zc#7P4@FE%A%+F1^jDYK;3r#EJz|$NimcI`csyOzGHObG-;jTzh#Htg;SnA7~UE0g` zDoo*5Q~Q~n2C()-`dDyd=#7$g$&-xFf%?`R+!;HWiI)4i2ruzrQT~TjQf}&Rme#7= za$U&y;v#5fNpqQ|*|3G+(7K3DS~t3eE6G)U4_<=*$a?k($~O|S2kn7!sgCM}Bw>`O zzIQx8Xp2Ug#k=2UUYbB>?2gGTnYlV7ZI!RZZt~mF?C6ya8tWOxivE)tW$3RCiuhC_ z&y>Oryq{qY5oTI(Qot?e(2&kk^)yGTP%|&L%Qy8$7V$+rU@mq{`VS0jYIa|x-D~|3 zE~-av(gSW1n>MLNU{AduM$)FpYyy&)Ln%`k>)n=lA1FaH-xzg-<5qQ#-Zx#SyCT%l z&!(PT`_?6WP7)tS-}xQS{6a@!GfqN=xh5Jd7uCSV4zk7Av{;H}H$|*lR~{`(|GU6U zv=@QY$?l{T7{~7E2nJplZa9sVGC&^Va9KQ*Wyf*gKTRFMJz+|A`P7c;|$4(FmrC5vF{f z?iSSe%tIzp#-X;z%m*UH4)q~;sVY4zCh-A-K5HEyU)oPZf^Tx*Ywcwoc|@G=Pyq1i zeQYP(63_^@HoNp@Ybg*}1pZEB;orm(wTyANc{ruv3peKE&2~?X(GaIqVuGxy3RfXx ze6{om+}BKm2%DKn5@8SDG$>x8O@98x<}Fjfyui766>Tlipif6iLqe?<6_NjNeE9CP z>E?{0Jh=DHPQnsm)gLwr(!-aiYjNthA5*dt;T# z@8sk}o>7LC@>FG3WF(8Rl7M&p${Pf@qK^emie){Bqr(F{#$Okwe%=#+Yf$vxEC-Yp zvm0;iR}up|qZ}_gHOhYLC`> zudgIG8k+aHt)c5+*JXLdc%MN1>nr|rT@_V&l2y_@_;h*22JEKjSHFpoGKV>l1nMUrSYbUO zPNWh7DDo^Sc~wHmX)6$d?aFwj8H$9m+#Qnx!Np(VCoWz_yKP@gPKc7lu$*ww4bX~i z@D%jfy;U7K(fl~_tfgEDKG$hcsmv0PP`e^wUgWKHF3s2(u7bQ^vxJ(*M~DHBsDUCqE@k|3<~@K{dtNI6Nwh5&v>gXF7F| zkbmms`L$)#TuslkD6rGbL-p2nIpOce@Eq1+4d&7*E*v)&lk^+%V2|H_Pw0HbhzRkO z6O}B?sj|+KXAIF3MA>Do6>;tBD`8#&QQFA+yr}PBw z$F5D1=2wvV;MrHi7rv;1Mu7)+FM{fVVVJJPu;v3`!+*OV^Li4Ct{&4d6lys7yfiwC zbopJ#AOb@(y#L<_~O$}z{L0z4rTEyhHCqt zGBhw2_W;G*8C@WeA$(~O8FTRCV0j93V_}5((%#?C-EVHgqKEl158Oy=ZjH%Bth@0D zB$$7rGJ6615a0W81kxaJYm-oyNX8SvXY|K^tA-z}YimVA#Fc^EwDqNnPNVwdW%9dG z?|OCwfdbHPMfF+Jnjsz_%dgGfo|N>(`AGZ2w=!Gcztsm|8+odk^}*>1q?H&Xt8UHL z>sysIew#(SJMd%O-GDv5XjF*mw9$$;ja-)_{{G!(+7qh09qY6pYrbB+0PMr>ZdhErc(Hgd(A*}^Yxopf}yEgWXS!YDToTlR!K{8uuzBX!Rm6eEk_E$0}ci-UF8b-5%{l z%5sa~>@}@ecF*%VAP0{uFmd|#HUD03?=|H^Z|Gkl9d7nU-t z;I)rFS$Q6aR9r<*$)-ZJMO?d*Jf)K_p8_Zy%l_&?UW69l9`|6UhSdVCiD18dWjg_FSDH^ei7e}#Qa4e(MLx?_5}0DVe2CBRnOhTlJeak&T@&5 zTAP&Z>yyNHhHEjuH)>)zJShXNLGl~v_5skbun0PjM|rSo?#mFiK6U{8X)c{I!V0d; zD893ck&pUFNPSEf?gL3ceY7lH3;@qO&@I!xg@ZFn(!6BoD&Lvqi@E*#CRRZkmsn!4 zxBA{&ymIGmFY@=?&8%Z$AfnMXG>RF%1iB6u(0xB@8tA`G#BxKBP6BCd36uctLyO8SsA@~IH zR73~^YGF%&!9d5wqJG>@oe*879FGD?DwuccK&`LTLv$@^iYkrtk?%yXm~n7w`4x`DxZPn z;$VNv{M;D=n+ zr$$4<--Ea_Oz=Kg(|B=m7F%0A<3^B(7d(YC7AGpzUuGSN5;w=Z%rE!&4EPsCGK7Fz zGerxiCt6{)t8m8hS)=lMa$4=sB`FCaxN?_aH{rdj7o{V*^Un^4+y6Zj39we6Cw*zL zzwh{RzwkL|bu}h4rJRqPU7VaSm|tIf0K7J8@ILa!F+J?2js<{UT#rOB8AWrdNfsrn zY%Y8<5Zc>o9|}wTP7Y3}q4eiH0iUr5bJl1$NC9LFd$@>1_GH)WL^vkR1eibxZG&39 z^FalV6YAo(3FVpV_5RfDHQmM!Npj8|58!Cd}ykt}N;zX%R!G~!)I^^pB0)k`Jx%UIIhloRTN+e^)VY6$rWwto(mCw zPaX&MKRasxLd?%kxg#g613PZj&wBM|*uU=S^(UjKrwY%bM@N#rfc8|-{a(B&WpM}? zaAn75LcU5?BTy#whi5{H-~6}-$ToV-Dw9SoqKB~d@IXqq>K? zyU6=gy&UbbuP-?X5u!TndZ9cM!O(017NGX>r!?YZwTx@@1$U!YsJhqIa0I(nfE z>f~-zLnvMn$b-_15mY&(v{ijQuPj`_tIMA+{MYDxlvJI_rYCydJmE88Xk=t$^9Q$viKPEp z6FiEgNX&?k!HYb!z`Cb1c%E(;1fewjr3ZfEgk`P_@E};uObd`X{^dOm5939aR+*St zM>9tR*_TIaJ#jK-=GSyCn1pTIYrMJr{9(}~%!8v%{4HSkXe@w?LT;aWSr2^abiOy@ znT7U=*0+CUsHw+lYr}O2A{)a`AEAU9Z;$(PNn_u}3^aSnB%Kph`d5;Wv1vaty=u*q z`EQ(h&N@B%!Ln0(rGY%Wq$Q+s0rmd9{lzhO1>fdFgb%u|#ivZSN0>COO`06t1aHEB(5RQN9bzF+raI>2<>M;e_zDNmF00nG*;`sU2zgzx>o$V@dbD`_@04 z>I<7nld-SQkIg{l5BcajAw=9G(eX`9P3`#T2Xs-kvw5tdsiCXZC-2^b*b=SMcBZl> z%x|CrRy(i2f;H05z|9u-d8pRW@M6bp(tJ|A5 z{W-22`PXsvQX!3-#_kiwP3xP^3RL>t^)~RLV?20=bP5jFB>}6Zs$sbej3U9>759HA zBH!h^CO?z%5|KCO^BNLzFynBQ@)8QhWX1=?{Em>7=m3 z`^K^|PiI7J%=l{@Ww;I25nLXdJ$(b0bzG&zP^v1|(SdU4SEBXcsPy9qUuM+UiW1xI zz>^*2Y;TU&%EW{BBKVT9RuPd^e z*7ar-=h7XuB5CujCZ)UT6Qbw9;W17E@u2F4Q?%7SfbQo_^S)Ux4_JKxuSHMqYfAmc zbTH6Sd{^z|O`lI}7RSSy{A~A1IKHbM?p>8s!$+zx%*0$X)*BI(gU`N=Q5WgX4xOQcUXBfAzRc$90C-8Wz#73~_nZ<3twzPW1L?R^fn?N| zVshhFU^TBhSw=SX_hMprlq8UV8Vgzchx7yIYVLK7R>SmsXp{tcl8W)>Eyqv4tMnb0 zm?EoRWw}oD(4toujz*QqcY3{IJsUU-h8I2XBNsY+Md2k(&kRTb6pfU>qi5=T`%5fu`Qee(3-d~Dwg%>s z*YElmz=Pg1nL$UoEX4#w2)AimF563I9nT&CC=i$K8+Zurr|^PtlX80{4qp{}pQ6)ca``o!(GTjdYK$$_&Q)nLb@XoC`TOqLE64A}y#e96_C zwmFtMg@8S-edelH=3XdM6yshQXixuZpI}_R$_a<)2mJM|tpliKp)j203VpxaWR2R1 z$W*0CH&Nqyvu0~gYw1eE*^fY0C&lyRi2!|48Ty>-=Z5q0d!_Z6YH<$B7T}wT>l@%D zj~l*f)h-M7?fxeC1k7Ffm2o`$W@`{Qe(k}^QzyM7X(18Ak7073ur86QZ(xv$(L3?s zqvq?CL8^a_-B}><^!_;isL&~ubq>hmwR;uFk25RkEJwP_c@QV2y7Z<*yg%O-Z#S!Y z)f{qlD`IbX-Ufw8{o2sIy#$|F1j?JTxv53%K4LAHxV{x5sM-<(26R;~*ydgC6_Vd8 z04@~out4erquF;?+|xwK&v4(jJU{wq*9}4D>CsTn(i=iiudc%ycWvXZx4W^Lt2X|a zd5T_SgUn;wm0(~O2-|K8u^OB3aehTe|72d1FGvB zqWx}3({5aTj11>u3(_l(xh@4whHeL2V;wiehh|gqp9n=wd1js2QpGd`yl{l7{IzEQ zxTLbk?vwHdHh}xoB`uW48c5PmX^7!fAp~|){PnaS`zatN-A4y9b9!v>tMu0;)z(QM zGIX;Pg8~c!grZC@eE-OxlDl%Td)JJ;>A{9yzWSL9n9&93Wuyb>RoGBX>3VfJx1usu zL)h=bUuQI2Kb(#ASf%Gm|40Y3G8?NNZ^AWPZ}Hf2(*P)fr>9;@fT80{9nWv)^hPVh zLvi7~9ehxs=x0Kcx=j&_T~P@`)?255Q9~ERmEq0=zX7Afs+A`nooz3=OsGu&!v=3Q z4(y{&q?m#!2LU9}x08Ea(le1e8Kz-P%eEkZlO?yOVJyF*7Ze?G?trMM1>F$x*ZLsU zpID^=59P5M8PPz!QIQ-+BNv2-KlXEwWCU=lx>|DW5)gJA(RyXb^sN$#QKC9ABF#3w z7q#G-4w4pN_H_DtGAVdp_lMs-_0kr-;av21**JdX-05u-{JJ0KAX}*3f`mk6y5Yw90f?mMAut+ zQVnzJ-R{Pw$*2B<@ZX&Zy||HWmmK!FBcxeKSV*FrF|$Oz*6a8F9#b`?Lb(NA3HL*C6L zom;c;^mx2hcIjwUO`<`LV-yU8)Ow+Usu<4rpaA`Nxr^Eu)MS6nFl-;2Bn!&sjX)Dv zg9(RIYlSqD>*kNh&a12BUO@rRBg0$tX2nv-X_mF$1t?6T2$ra zl#khCzYiszF0LRzvuZKk=dbA6bv(~|tY-#B`G3HO&FpP;%6UsIQ`O7YmL|NNoO0xe zg8?;cYUcCgEf^&kn9PNebv=!G0?+6!)2d7A-+MP+_|EPJ2_Yv)kQQeC;XT2V5)XnvoG)m( z`X(4^zU*hhQPC_UDAt`7ki~V^VsuLu6z+KipZXdgWX#KnGhV)hUt5-1$xu&JL5}t~ zpJ^P(niW7}_!k}*sQwtHXVI(K@>At|?BG80yyWEk#IAm?80oU=m(w@dMdiG{A*I!) zi$UOVSB@#iYOf5mJ$LC;md?;<{Dh*ej$bYV1Y zE)h_$`-CNDll_8BngWmPQLuY4`9V)*o8K9ZXt4>D0Z^R%ehZ6gk$16RB6fD;6678o5*PsLcw z;llkGQPNEgO7QkRk)I;1{0SQ3F%uILHR2@THY=aAep9}#N_h;fz64reqg_UAm}ia> zAJjw(69k>zn~Wlc7@<&|^e4wg3KTQ5J%>B*3w{&1>I2Mf5@U?g$`IfICxm2m5X zttM67-ZL~41ub|=5hW{f{_u~`q4EL;b|G(}JP-4(+tUyUG#OL>7~;ZbM!+-+Y?1WA zDoSd15<%Ljy$`f!1Ld!k;)99D?FWg8GDXjPPznBtLuX2L_n>!x?9`aF3urkSfon`t zEJzlvadRCZo)O^DXku0zPKQ!{B(cVKGT%JiKpp0+XMre#D-o*K{siVYj3Ep!>5pr9 zOWylkD=aU7BjZ@~2y*+d6sqsq2 z{n8vd@>4VLh7<4bD>a3L3IfkC{RzfS{G=$U%mrF%Q!9wOGT3!qKBMqwP^YA3<}bry znb{k`swa{Wi0nWV@H+WeXY(X&II)?}qRfX{6VA{)# z1NpDS#K_MD-Gv>0!el9(K3z9VKCOm5b(NmwHJ%w>%N+<8|3Z%yVF*P^L1No!RQR}r|!9e?7Yr`UkA8$fbjQPpZ|jPje(2rf$q{)$=n&BK%*sCBZF zkFC{^*yDXkBTH=yP!J8;#JKK_t6~F4X-H8^6+PXceul!QSJf+iXCOytv?DcKIn@C!>$ zdH^QtSeR4eK*VMUy}q;PoxHyB$YpSA`1tXUQCp9^wR~O?k|ywzOFNRoj|Dj(Pe(+E zA8s7z!9q7@&)%GRRG{UdUTyVWZ+yWzhyyf;6Ubw3u^&N+rde5z_=}VK!?|>puUc2h zd?+F+nCwWucNsv6-mq(0C9V7rd+&w>gw0q?ufqi>tbq|fbZHu|UfA~N$c|SAig^2b zHLVs&cZ4s6tw849R^^(tmfU{fGy{AhAQZ{sCbI+5L<8x)8G$`ud{bvQE@lw!-X4;+ z^C!or_+ZyQyt!`2XU(Q<5UA2Kpr)jL+ibb99MFf_@V?O10pg|8gO2i#Tz_JKqWk*y zUd`wYaRb>pCjIJ+V#9RlnCS^TEx#d%g-mXPCGjF25x40`h)ztwu&40el1lq$kcxx=YL&7$6=c8Wz^ELG5yivGu&Y5gohr?{pW}B!>w29 zhkVmjh7c(~he%}jLqw+wOW=Lp=IKL)$CXviTZ3!!J_qecb;zGwyL%va`{6b44xY?! zW6Nix65hxI_-E(rNjp`&73mbD3`pTZb(@_^ms>*ye#W4#t3SW2NKp5iQ=<}>&Km1{|M5Z;Xck@ z=PvK{$M*HCAz+7AcibBNiRO=bRN=Ekbo>ay_U}Z=nWKPTKgBr>RGp7zm}MkzsGmG->DP?S9O>nqB^4X%${4Hfy<~#?my(ZyLgZS%o_F8Y6sBH@G~?$5q|=X+Jk$2 zQ`KeesL?em4S*nDdhEyrxc1b$vDVVrHtA6W&%%C^sE*!+rBUy={cdkUQ)Wad0GE8; z$*G#GiqFOl>;;w^%4uzdtD^l-z`MW1NVc!;6m~vx{wD@tE%i0vus+=DAXW4nfO+T7 zpC^#j@B^D5E&~USH4j5AJzyf^lV;Sag+T<1{QUkPO#W@FaCP%LL_?%4f1%dz~MD%xYwbovoV1>0xLEyplbV?Lp}owAx{=g z)FXk>m1G-C86kw@C-7~O0#PG@d3v{~pq1^CI-V8qDXSUxeJyfNh&~wgr1=1SoSW90 zL3#_YN7@c1zkH#V%OC2@P|rR!Det@x<4?_YPtUx%*}a#1>O??KHMgE}II|JKGO5or z%Q5coAwRuOvde`=555pnv%chRg(AFXeLDTJjtyz0U3#U-4u{D+Om4gt5d> z@7?6eqhYm@d*+nGXgJN=8&C5!)~WS>I{g82B6nmn)Zq%6ld+r5FQ{#aVKP{*rbtYl6C`Zl3WHJHFfBbMi#recL85Hq$DDFp?xR3QzpQ$QJ0f_X>LyPy-ie{wT+II#WdwlkQde*qilsJcH4STEZ; z8K3qzs6KJ_!v^`!`xf%jgyaxiH*WY{t(-hvhexCDfr%pxNSfs5m}0=-?KC>I_W3Ao zNIWiGk_oxeV9dz1r)GzI5X)uj59-Ia-o|ETWA~0N5Ab_;_v+fSV9rM$qSS^Nt396L zQ;B_-s+U;W*|?W>+Z#e`B&NCNB3RsKNIaoLn>1klxSXPX0%zZG%c=@rvAPPh4kSJ7 z8|md=25nISD`Y*=o4Ch-$rX`<u*Dd*jG(%6he$8UhzLb z1mQLi?c%^$vu!IE`;`EzqyG4TzzvW06oT1q|;^_9<^)pa^lgBi1%nzcS=pKFTd*?%E17kvCWl zWElkCpOeYZ0Ai$-<@2Vd1u_Bxj@BHXK-aL{4;uZdaa&5bqKtEWy&l%cfKn?EpbazW z0k8@n<{f+$RfxwNikNDAP~-2wvR!IQo0v$jX_klZ=am;Rx&LhdzkU`G)UjHdLN-_z zHOG`1b4=MP>;R{;vP8)z_e1nP2Y+uy0bV|&*V`v+E`X9X=nMTpwe%DVpmJ;fTEw5(>Y`@ePeI|9+BhL@qA4j2B9i14j5~ClHk_zgNPp-msAI2 zYMma1SjRt)(PMKMOsCXCkx&|vzo8|RF{ChIW2G!>LRo6stk8FE`3-7TWLUi z?6MCEsHNV2uDkui;p?Pu+!kM64Ex|C*LiiNd~_xwfjqCAw}H-*re=GVNf!4#3U0sU z1vLp|U=Yes*2CHlXzVe}E9c~kASwNW9oPq}c<8!rpH?9D#gxm9-@$^K6kl z#}+Mzr8#M^>h~M9K?{#N0IFm^TNK zv*sX}pGno$kf6KCHf3r;pxVQgCIoeHJ{3_wLxOpz?oi8BKb+fEFGKEOzRfcQWu*37 zRiLeG#wt9RLvwC`iWHG6X|MNH&BtmZN7b5T&b@&eXsMsGbfIa;AL6#54H$(_CS(D= zdA#P&;kEFc@AgTM6wGqifBkcCJ@+^hEU^ZRHoaJ$Yp0v=AgGxAU=lwGgL_t3c*VJs z#e2a17N3E_{L#p_2eC0Oe#_%5Rfxt_c<4hGknbHU}eUAR2G z%lSuGZo*ZbT??tT^}bJ~&&>0~PR&`d%e|dNe-+3@EPYmrz@w&@kN0c&fbGnYe#2AH zvSw&jL!;s()1uE{VK*&wunwZ@L~0gkJ8hUm3Q7BJM`shpP=TeH1)6|+$^?%Se40U5 zx03UYg9x8T7`{Yn;E79@0+sKRnGoOg_=gV-q@}>hoi%N$brt9NWd9tW=rTRf{q-r{ z!>cWz*lt>i;ReJiDSm>u%l5>zkDO7c+kACi3&=|q&ziVAxjt8K8>x9sXEl#LeD97E9oC2Db-+<2cACb}&w{H6%y9)N_G`_7w&TIa}c?JaC zN7X(}kn>DixyPKn??#V~UZdMb@Vdmu>DMKORsWC#{Y7{98V@Z1_DdeR)TK{PtTLJ$ z)Yi<)BXLe1<-oSTZXv!Y#`T!){3O8Q1RtBk=L*1F!DY{u@zpJOY;0Ek!>;G$)Ft!0 zF`GLFoL%0;0&Do<;^Nv3e8EEH_f+QSZRlYNXp#T)JR0xvAI`J;J2DIhpT8WX`dpo} zQ3@fmHp({AmW;~HN0SRE(O?k?+?x1uy)RT60t?i^80&%u?#8pE+HXPp#{U#PfB)wB z`>%P*$g8Cfa~YZvZ>odk;SpWWbDq|K3D>8cVBk^k$Ga>V$B$Cz#zkvlGkVMR&yy`@ zo@|>fXu%2V8{6AKcMVwmG@uoczz7pV@b3rvj;vWhm~{dmbnS`2J7YM1w<^`}*( zn12$iZ64r$#}1+*Uxt8QfE2WqymudHABLiK5)m4T1*rLvWpbn&4(>~vn3!}%&4c@V z9$c^o9!5@J3nZC@iNA^gsBCZx6@)9x17KZy8|<5}*+GTJAM57zh@gw5tGNUQH5<6* z-5{4)H;5-bDvwf)?ZxXIH&@~Vds_z-D(=iYpaFlH*?w#C2X+KnIN^$4k^awBx*5E< zb-V{9`WrLNY|22xwpPqO^9Ti8OaR0te^C-l7`-O**>f|cPoSL1a zTM%VOoht2QA~>@z>Ndv9#5#oLn1BwO|14qMxHlrBA$Gsr8++%X9FXU!87YvSz85EO zax0+DqWLwx4IYSP;_NbYon;wWBUEWX3~~Gum{qi2&zs!zjgDWJzdumXoG~qz|KCys z?W@pFhc!vV=askeY!wHYtCbG;e6`2H&zq_Hz_uUELA{e7?s}WsOb_P`{n*3PzYQy= ztZb~W{|s1mo(gW?sgO^x^geZL8`x!|7Z;g&Qk+zR28B=F@wR?K(qr+CwAKam(`H0o z?e&58sbNa3+vgdld7g0$Yq5yI3uz$KDB2VPtrsGk0}ly69nhX%nu|6Sto*S*!E!iK3BFse5`j>Mb%`<-AT)hFof3MH@+K)4P~dgs^$y8yxa2UjQpN*#zvbx<@LRss7p ziX$EP_wzmO6+D^$6!Ed|B3_Gi8Ht6KwCUXgGnHb?(QTlic6u%aJjK$UHUOD{PMYPa ze?6<=?~2@0nAGz)H51hSp`fgHo>KK49;8;7GX!1s`I*;6z^F+Xp8Bc|02SV@Y^4yOg#u9pd`OREX>MBqZ=x zM4(IT96>WdorW8jd%gxJ)K05d^6&SAQYP!cp72&>9YV9zd>~dFHgDv#n~{=a37~^p=uY8r}Kx=zaQq9#Q=?wZ+!*BGib=Ib%6Gx z;WCM!7O$Y;*gN&u`A9cpohMkiSO1MqP_}X17Bz2$|NqQwl&7~KsuOD(p|_Bt+GR2< zz(J7{to_&idyqZ65%@1Elr*V1bdr{Tr#D#bOipFn>^33J5Q(z?b4vGpwJ7DIIlK#< zX@+xmcTbk9HVpB4q_<~IBJr!|a?ckGpL(D{X2*M2)DUE-Yo9)+E&){P7vS^c*M@i$ zP^p`HtOLYSfSm>zcFX_G1lfKBtovcPYSTGS4<$HPc4|qsAmjXX^Fk+w#SJ%~Yy|Oq zS}H?X;VcrW<{~@K$v*;*1=Sk?to{cXX1H;3GpxWs07OShj`QY{wsc-cWfW7Y6$kK% z$7N+@iyuS!bD&=(^<<(JB>cdp0IyFRdbR2?b~W&U&XNTA{;gH~{milM=N%*WnGpHX zVmRmYAY;kA>^54_&hk@9de1B@K?122m|&{$8{nlv&eRP^ZFejO{_9`EVVnN_`jKZwUzKL81I?^oaKyJIM%)O8CS z9RwT{%vMvE;VRH}JdQ+X z{YQz_#M;V>kl6&) z`+vL!R_?dskJE=8?X1G8SL~gSidZv6`7M*Skrr7Db9sr_)z=#~PoKI|*>(30U}b^x zJO4sX^oBTCA7kp&zjdQfH30TRG+(ske8TSkPY&@~0v1m<7{P54r=N#{@An1@T=7rb zu3?7Ve{8`%L>@{8v~D6i8|3Ev-r+U#E0+w{Jf9E4R5 zsG-KeDj8Gv{(X7yYF-v!gpN6Wp@Wg;2o`Odl(&zK6!1iSGKj!|1p5*|`k)vTQ+qfE zaH?1S?G8wci#G8^NY3A$^ZV^xI|M=QsFM+F{ItmiBGn|A(vD-c@f$&_Cj{cYXu5-4 zk70@)1LrbzbGZqe8`&7b$#Lx;@b; zU|J#fbL&89wTJUFPH^eJrOOYIN71PRy0Sg@)SM+lxqR0-VVLVZiPq`Lgce&GDV@u1 zjRt-TiZQ7z|L71PKZUXB@V`vB8gSnBVEo`>^BREfy9S_Q@$UWgrL^r&9dlkm{>#N3 zBcJnt(S32V%=rlLXdVtR4E}o}0lOs!6e^(!p4o~5UiG{5hj}2RuhB>j$sj55Dby5t zAuF};*|6dRzsujCL`<+a*f;h8?8`13KDP8fGS_?EcR8vKTedhohG78GAcRD3!c%M4}!7K<|Oz;?DGHCGl0;--pob@q_;n-5#Kd_8fWt8gu_KUFxv|E?GBGAspiEKNEiD?mUqT^(0Z zn^!dOW>!{e7nGfP91R(;hFDU_jLW^Rvq$p*u$xgx)&DN(uT1d*z4=+OpP@|1G_1&f zz?#j-+rSu>Hv}^S?#Cn{$1WWPjO~e4tSeyQ^du-EXa09N`}Gz2;Al(B zcqLxJA0O_jRmw&QH-d2s&u0f9=9ql1h}MC;2HQ~|`Rky#I{PZ#_lGk%{=9e*B(ob^ zyX4l+VS&s4ySUMS_ms=V2#b=hOurx&@~Ksv2NZCK>wP7?eS4GIFCRo~oM6p8$@u-b zf)(ooln-rHCp6ox0%`#&E3;qin)gBm%0Sj>5Z`;;#4bb=C|llFkDk+@JZKvVJ@Eoa z@vcF}%Krj;mz1~drhel$DJNmzH%&_h`;WPL8{mZ;MxFp;SiumaE-8P~KqTwKTQQ@> zL5K4vKeZMbCr}XoABViDd;3&Sy&Sa%1Dw(69tQTAjo%s9hNh&bINIs9W4+E1jkFe6Irp4AsB+9_|C2Y7amt&B zXi_-uep`Q~RyahhH={3WLZHz0npuwqeKP}xID>Bit=r$jkR7QY-CF!MOHh59F-L%f zoPk*FJH#QUXz}s!W1XJK_N;913}Ra9$jpPJ)BwvjqHeKS;8jua2_*g{DtFC4pG-V( z2OWe52SXK{`GY4yw#?IvHy0#Y2Jypxn&jC$2If4(p=rPxxE;_abvz~x>_^qBVW0%T zPLF>+A{%vv8K2v-ZD z(>zFs{DQsa`5<5s;FEQ$8|ade$8aX9OpckkQC~4q&xM9Pwe6%a%2B!I(5}$&vTZX@ z{H<#~raDs9f-B@IO`!!7605KM5y#XarwUm4M6& zBs+M|d1F;y`9H?KJRZvRfB&?jg;UZZBoq;CQr04SB9WAulO;t6N!IChjPukR3oDa$=z-%%zP_>Hy{s*FywNyZukKv;~jP~XtS8 z=d%d`W+RBw5y-b?b{;6xh8(3bt^pqlK=h}TVs6)EVeo}U838748q$KCv*NRedmDqT zsEcc?qryfDRgl1M>?nvU)=~47C}27I<1K+8S2u$`r3us`zmysl$`p!4LOW}TrccTJHe~sPQM&r6MGH7avwhli zB!cUpYnJDqWXTyuWu1)ob^3t3qZUxB4%~UTyHlrFYxY6&QvzD~`N~(#KI(s07j+jc z(hpv}?VZRL5xCl=8y|lk$__#v0Xo7P0pumnfzw$0zc+9nA9<0K6!oem1xYCW_tSek zFmczr@r(3FkqS0@*z^uC^ML%TX{Q{?IaMkSEy>ocRD0x6@mJShvAUSFN&L@awy_gz8GL!x8-D?cn$x1;}u?P85YzrP9e+5F2==DJDH;GWX# z=U{{e@%;J-xHvHx@yyL1np|D_(;)eL6sjm%~F3@;m6HJh?A0NMK6MBv@$AiMVRrDM2_C+5RTGXE?mR)8W{ zXf1q%9bJs8aiFi(D`flqdsZ1HBVN8)GN}WI5s{k(-FF3lkKOpghij&g5?LzgAIRd| zApNK%#Jkz#rmT3C7DerAIH>HS)5mjxzvryaw$*Oh~p~}J>+#22z6U>%7UM3$zK!7B(h`R4`hkyg@r_-am+OSZXi0UnFznpQOHx1O189g=`^p8^21up za+EYJ@LRMw#zc48n7o8q7zrh~)g|Ow;ecv-QU4kOz?S;QYw9QBef5j+=G_ z!pd1}$|vNGruKyoarCCge_h^2hNvB9X*+u^+58s;-hZ^`12k;?Y0M=i6)P^V?~rLm zi1h-beG_!yZ{~vE*Qg8gz{^6gC>j&-v;*i`5tv#V*l7RKeM*nBKRhQZEco3(ExfxU zj!!8SDzzTEHQe2b=7tp3PEe_7#TtiEYA(n_`2;+mn}?h~OQm~C^Q^I7hT^sXy5XGP zFaDedF)@dQ>k$k>qWwP35*to0@hb@QN%&3r<@tn_=tam+>}YQ^2i(NVm5}(A{QVw> z2Uq`_3wRWf(#_p}sp!Hz)3jvj_McT$vV3L2b0E(M79jA)AO7s~op--94a_%n!U0uqqRLW6%$llQ#JYFsMVrTioeFR+5C~O0Sps`RH-ze z3w)CZ#T>AoY1i+3whtpNs(Jx6IVGKghGQbiB%Ovu{jfs_j_g;f-0+X>ieqoKi6FIg z?`51lVodK5EJNe58iCEuCL?Bsr9?Xwyf$$y$?4rzsWOarVOJJR`OG8!sO*PEJ+dtb#hJDrZ`%;?ONYr!I9&KcVyuc^itg(}dDust1>m6@6yciCYwh}%v zqwV6`;MAp2R7U6J--74#e)6zd ze;Nz*$4OvzfVb)cSwXwq=i9p)PS!@uiL$qT%@0lga$^e&>%|rqS)>z-$A9%uxOwe zQ1E~JGW6r(qM(L|#-EdM4)X(-i5LjUTcINI6!$0vOtt?u9z-DqzNs^V2GJvUvt#|2 zT#xubM(c3@)qlaM@_$;wtpV?xGgm`4Pc+?QV? zaLZfHlwU-{%l0Hd9L|Ff4|D~alwo3U@b-QDSgF&Jqyzh-)MJT zFET2?#B{}`gC7}c*+@0!fx?j{zw0LTHlf}<_liy<joOudknrH|R{)S;4`meJ9WY5C%`$3pGg)Z;EiiWUyfh|qLybp>DthWYf7P>E{e**;|^T?`G26`Pg z5btYM%epww97^-NmL5y<80o3~*tA~CI|rB2ZvM=FkMH>TC)I8Sg?laz93>sdGm6<| zH>FmbeoWcm*(YB?!VBD{r?;v?p`B?X2rYh`jMItAAW!*(1K-xA#oES27d{>9{r6UE4$NAtW{m(ahqZOtO>AfY^F&Q>6Oi-b}Vc8d5w=SdHyF2VAvGmM7%v2{P%uu0d zC)MSpb@46YNbhITrbykyiT3!A#|Z_3)qnFQymI>5b*JSNidr->WlW5^>wex@5q)eQ zIL8!lj$DDTshG3n?N>|NQY-e-w%(e>l+Cz1&+cuvGdL}67Q}bWgraPatRil9O8@83 zM1R&M`>CI&9$V$_z{>@ic+;W-M1RzPS!xX>9dhO|KWc&T^B`?6cROoFh+eDdF-jH& z#d&5S*KZk--JT`dB4W@ z$>yxAI#62s^k^SKM%HF57pybtXCWRj|KaB+M*S2*w7A(ih#%J`bO5a1cHtqzT}P%y zEF$<5|M%i9NmvW=&I4T#jH&q>n+xaB+>Z#DRrbMs4{K^zITbjS~Df2|k z|HJ!>Woyu@Yib9Fo-j;}@Z)crmOnDHnQ z)2=!1r|z45chB#*g`U%th`2s^xCxa@{&lcShC&_we&$b&5zr@>q3p*&D^hj*P*;pg zzC?2ELt3#wx+C#+MyQ1DMgOc;d%bsQrr9l2Q1-p1$745CLcGFkuW#^)FvsL08R8*j zQ7=cdb-Ms*-BvSEzy0{Ps({1#*4x%f7PlYu$RwxaS2|`DMXj0JkYm7`aMEwIL7x2C z>@1J@YChYCMawnG31-WdBpBFqlmvU(rx%UX8ItsxE|f-lo9Oct??@PcGk!MW&im3B(hA;+vNy%-0aytRxM3 zwok$Y`pQBj%8mUg;nie3om9{knz?UDLPi|#=$9J*U1WyLh-mR>@h)lawP_vDWrF}C z-n&HlZ?qSe7SlQOTQ;P4_g%2GQsU4)%sEr!xA(Yr*0srXL+Rd6+e63-a^|!tV#H(Ns`J%%)qO!&Xs=SQ$hIgAgl5f zW6<54Zd;e6e`4VlU<-^Ll#1SOFrFB_u%bqIyRF`KPf}|u!IJMB*SMf^vL( zUoCm`smi}*QgE;TS)pubBu@x$+QdBV_SvgJ92=EYzHQCtl_wa&Kuo5-if85f_>igo z1}sJ`%6tm%@_ileL*87+rcB~cshF{R!9Y&y(y>k-BC`|U+3%(rztn_^h$z7{&HQ23b}yAdK%j_A==pkCf7eXyLH_ znoE6YDXpP9kH0#HlCD)}n_4CWtI`gv&M9+1ATU|Cl5Uh;gctEr{3?Z*d-j;)@_UjQ*dD!(~JwKXrpVAYSP1Z<9- zM{$v1ZUi?YyJza>d;U$OA!43{`ytE+oi(Oz{PIluaVdB6t_*J(ds%qjAXNE;IJmgf zh{y)?2RWIH>^xTbgQd9he4AnG4ay%Z^mvTPGi!FJofHwbIT~E%>FesrjjwT|&pv)j zdyWH7@&xxfR>0t-{kBQ|Po39IC<#{bLv>{Sw#j4FQ$NYZlB1DXzEYmAfMm2Sa`ENK zt$U{?e*`I$N569*>cUBtNd4QhnT>VxbB)#RP^QjS87$rg*z-L_8Q;9 zcRT@cgX}*G|Uw!hi$rd(>~$OpPCqI z^?$owN^Goiy8<&uh4y8!kX+f~=NbfEa(q+yF8F&AMf|7NA2q5`c6a4gekBQp7xaVn>X<8=YEo|+4!k;{?(G}@9xc5 z?e;1-)k z9c_+Q;};|Kpn^udQ6oni9HPn)8&EwY|PiJN&EUfEIG*FmT>d?&Ccyj-{D)6h`O z#m%ZODzFdT8so4>9@GGlLKue8XOZ{TSUy?S*JY^NCRa&rX)tjBMK3iaqe8-3n zAK9l1e>zWf=g5A8TJoa%l%nN7%khIMMY))XU5hgnUhS*3(Juu7V5kC55O(ePQdlrP zZyDe0Va&c(ER*3CW0HoS>c?Ny{me0jLO__eAY&`6hvYxid@;8oeaESISPQltT%KO0 z_FzO*<=8c9X=sXXRlElN%%^V>Vr8Q^BTKPQFS??w9xGnx`BaT3Cr6)j)2;roXi35g zXTddz9a4YYUB9=dFW0WN!SRKlX89MD<#l##D-Kk@t=-%El`wU&oe>rwhq1kVyCGf; zNDw`V1FCf|t`V71|AhUM{L`%<^Jlls7R^*mCNU%1^seiK+SIz`lTC6;SE7aA1xoum zx$U|)(u1tV*gQ*H+VUOsHY*I3K|BqiHzWZwuyLOC><)2#$sLiH$yzbSp>`d!>YdV1 z_eGOxhrcz;mp*%;8E@KWBSt@Zy4fs4ay+cl(Lo$8ZvoN6bwp8l`gtx>}a2)#3U@4l6hy%BafU2yi`QNWG= z21343j##;F0}}seUX5QhT8BXFbNI0U2=>De^9=C?b^H4#)>0wo(Uait{`wDU%}O3hDLv!PH|VX7*6o|-xK2MBRkdOt;NmY7OYNaYAo~7jMUP* zYVvWF#@^8Q?-J4GNSOMt^o4z zQ84lLHoIJF>YZ*yjN5IQU@S8_^4S=<^9I$L=)R`^Ogp1KwWudkQ+i+Z4T@N?f_>nD zm|ayOMjcGw>n5Em4)aLqt(W`R{Uayj$%KB#08iGn%fg)hw@}5)xNy7W3W` z4N@kaCPENdAM}C}Uw?nW?77(oLV&|cz&@cR+T;P_ocwOp+o!k+sO{FlO@Rr2 zC`bGbh`pRJM~QE+|KvXvs6HTxM=1gxjlMPU^!K83oFU*7?;Tc6b|DAq@L#KfV5{1JIA)0 zKROJFj`Q6oFF9Nu1@lb4du`_IR>*#QNx0ec1p>vAv$6ehu4g6Qb62Cl=h1mEL#9aBLQ^ z)U39`oV)tCH0RDKn}z5t<+D9NAsEUF6@CHw9f^o z-vonF|2zY4{7ytfqN6izUq#yC6t`qOlW!V!Mw%Oz@(VJx3g>H1)yUccX=q-|seVF{ zYln^}Q7)nBh@MQ=mM8&(D=Lc0Gn7CcP{Ex zpFJ!Pz^F000w3hOd{q%+Jf^SRhg`K- zVg8=4y($FS!R~v8@_CY$g_m4ObjEY7>KplxkExXEUy4|{9gcG{@#D5V9hLmciFFFK zWJ2H>DCVU-7iYzvZe0yduiF~;IKKw}{kI^&_3Bs!oD>f7(sT$qlEHr{wm?mZv=3tLwXFoAv%~B(ApPDZr_{mc3dG`|Cw$d!!khF<3X=&=_ z^6cGdWb7p%N!b_1RS z{TW`uhh)^HHpv6jZ!#`@!EyuJ1^aT-O*K&*j3Fb6;|#6rP7o zpydV{hW^oBJsh0NmL0^ukyW|1NvSmI{9C3!UUFph9yiLlVD(THhF3DnXl)k2FK8Z0mm`5pzB&V88i$)tiwt>R1I zBb!Sxqw2K$-`+EKvnp9hf1Rbnqv+U}!7UpsQEs<8cE8IPCrxmr=R!kt9}=X*XnZ4ewzwz{>iZlFDHsi!oG-B;R^n4=c3WZ)@-*_ zT^^}2yMXPhh&pW)mlRxCe5a#(cXd@^VWt2>Nic+XZoAsB{uHMAU^w>po|6Oik!yP{ zjFOM99?|2;b^7|MHCyxIU`wRx)ObhUU8C-hN&Mt%-=e2+(xZy9*Rq1e1xJrc2#ILL z9Ro5R`9fFCoYRg|3j1b{o7OK$cpf9G1Ds20=CWN?G0|&y8XjwkLzVjIr%wwP@VX0( zJfdv?-=k;`HD%)RYEw>aMoyV{6A;l6^;I=nE=p8inKfGZpDMT~ykwnTsMU~ZEneTB zg%>rybXn+Pnbg@654WtGwc_};0tRDqioZ=*3k#}k>wQBGM)W|FlDp;c+OyX$ zXH=)Rg!+g#NZhF4OOU)=k-sY3j`Oag&|ko8mn;_8e9~m(Ly}F+e>UY!x(9(oUE>Uh zFkiH=KHg4^o;OQm@J@iQAkTWfb_n5cu1@v!G!Fsu)tdT$Nnu^ip^|e!4Ic5xdQ0vS zQK)JMl7XbSxO{QX);~S30nRUFR}y94j>ViuW;JvEWumJ0AdHYv*qwfwCSL#H<_dQ# z<~C=1d~&iBJgXtAf&y8VC*A?pJ_UFzbsbN#{Y-lQb)wSowGKU@E!a@_qffOJiKGCp}AGoRs# z=o_)?w;w3o4ASKvhI)&%QWu(5hr4lqAwm)8M#2WazTO0q4HXYNC7BA$Ef|H1_)UV` zZ(z8^-H=653O6kSGwy>BIHYtF4C@1^a_mazg~-Vn$XP?r4cM>LJ`s-zncqmn7Pt7VreFC#3L)_vg7mLjHNasjphWeZ3|<_p(VYc9 zk`Gu$!{kB@1k((Ht3zcUJmAEpdrS!_ZICzdJ%oa6ei<&gU4rw)zk){;qT6VI#-JFc z3ZUp4lMBEuxS7_a_8F+RIuoC;dM1C&DPD!b7;lc&&^xcNw|)n-EY_F2%**>Cq6STs ztfy=LX}nM|;Dz={7ROzOrVnJI6uW_U&yYTV1YXCs8<+M{w9$ShYsRpD-lOs5b^i&Z z|A$`NZIM|kxp1!d>5X=6i^j+!(}e=>MO_wna%_=zTS`wP2qrH z1E*2Me0Dqz5s(Uxa`sFd;GEn3cxvSWL^k)j$rZXujERR!}lQm3LvYLKh2&hMHFP%W) z$8tL{lT*y6!wPy+-JW8`4L%B!r~2p_D_N7S%6UbyK$%3h25dLMPL^V0TOMr>xRuxw zR7LTT0lAiI2$p6G2peYruSp!8tZ$k_vJW0zjF>|J5(thlVZ?o>1x78pnU3vLOIh~x z?3~)NUYhvw_Wr|T_h@PuJ5`gm)Zx3M4(r}p`YYIpggis7fi~t`RIUdT5#&M{d9NY@5TqMglNY8tjo145V6=_)N zvE=%PmZdgXpafAYo0IE-H)Styz`LdCX1cn8Dium< zPrrr}u~;qn7#Wt8-L46^?!z%=Or>Pb zx6^sJ-yQ{2JUbq8QLblj0TbB4SM$md^b@c~(ui}F-a%s?ikZ)TNwS#7zAC4H0U<5e z0XRBlo1|esE~8_L9vYEBW#O^sS4C$|FhgHABHaUxwBxNj!kn4bvq9s!rpc;njL|3wXb&tH*pUxu#N*Uz=uAdvFxIJhzYBIyon^-2 z{Skgl1SN`o%h3OUxIkZp&`zrPP`i(hLDO2)%8QQBv45f#9g4&dMT{8PR; z4wZ8N{LA|PcfHYw!@#)JSKgGy;D+B2StB3F+W|h+hAY9f8C5a-=YL1xZ z!#(aB*FbKEXzoee-{tgxo^GV6w3P)CN?RtZ@2rcelwPQ2xtaa*yHb?612+0jn(g4UHX14Z}gssSH{Hg!>FBzuDGx2J^{BJ1uC5!wkJ?#%Bg}^K-f0bSqWY~ITD=E8RNM^OyD9BKNwyCaR!U;#L&%$Xy zkq%-%#4D$JnSh{@T7~g-?ap2*yjFOlC-grF)y-L>DWY;w&Z{ROP+8-xgC&0gShc4S zzUy^=7B7M(Y=pMrVa16nn~S_ak+8EXFXY^6yAEk#J>K-jEDZV1g)ljLJ;yHRcnl9anj4KmT`5xm;v-LW4cQ8*2_f?uCyVw zs3Cz^lY+dvL?1sZ0*x+_u-|KdVZPUx)RMojdB0{4meGW*3Jx_Kww`YnckRMnKs_ax zA1tB|*lWbZfO^~LQw+m_@)}EjoyWW*9)QSQIegxX-xK^LS`K2+Xp%%iSlj|dfVWW_ ze2K3`CWM3CgqGuhGahAPoUoopGfMFlh@|q$-u3*HzbW9stV# z<+$1-!}7&O+S^6y0<9W6lsV?=^UAvCz z!%*unsl`ylPo@{bZOy|?{tVQx8X-sg>OilC8W&Z$DQ+}Xwg_&H1Uglyaz_jXV=S!d_-CPQ*^Hn+(U4+Dp(;kv@kl1sV9yGJ zOHT#|k-m?2AA$M9pKa%LNlH)S8D4u%+VJ*XF4~s2{5Vgf2Oqw*gOz|J`;4blRGiIC zNFkJe9=44g$sTc+8E0GtVPhbwMiM5T1lzVTLSPc{NpC0GvIMyM4E8S$y- z0sV^?>#1P?hD9=+g0d~DqS(oy>KcaIg5m_Nz}DI~th_N|AD>dDsausw7%V7st@kCD z;-An3JXG+I7hp8yb2lQuv=b7K(PsEbJHQS-G_DZ_1OK!4 zlKSCjGB{FGyx+5z4BcFIh7o8LC)=MflHUmBUm>Tzq(Jx?iR>4K#-s~5|Kn0LdPEw7 zwtLna@@u71ILAI*C(y+03(&?%nv<@w;2LS$AbP! z`W~b`8+n}JFS358;H8Oc9h10_e9g|J%Mvnh>8rMFs|e9`b3=fC!>;lMs-OvHJ@|Dfcy<)#dF~oWH)>f|hF4&r?L#Q*Yni zc0=>Ny|~Ddge74fnAG8F75)lVOXq0adx3OSjw^%pG&_9wa62q$Mn8K&wF7WIH=iu>?j$X~b|u;C2rr^l*BiRP8ZM{QXm;Fb`oH|X>j4oQOm|p~ zv=_5YO}Nf=lfl73FS15tAwMf|{v@s>9-Z<}?-zcz(YN4m+Gdpg*VN~cqF&SduTJ&pe2}D58!gLi zsf$M5cHO?cokMNdNf9?KDGxNDowwxkCv&Vv@kTJ&pshw}$0pgTp(GC>M%KUqCf1np zO`ic)X9-EB;#4b|GdqmDsq+_yuVoh>asY~M+m`P^!c%qxm{R6Cq6u{6&~4L87-=X~ zDyc|=i+JgumLj_6h4BOhdGgM&GaTz3oLY03lG>1{Yv{8-2WgXLI}&{ftyHuRm#OE` z?Qg=um*4Zy`%B7aUa!ZV#eJj#^1(YIDqVMu1SV{O*4%o8`ZJ@s5ZFkUa?RCa?I5@4 z799BF8nw%NEsMN8wtMuMQ8D^%<3GO>j}s=2kcz$|R*MvOXd4i3p~+?PPn^ke&2qm4 z6WFXX3{zvZ{-&%NwW5s|ie9PKcENi>^=MYC17`F8tQ~O#P!GE4xw#D@TOhST1CF2b zr1SXeU(~3_#H#zXh&&Um+%*Wa)EBHk3ufp`F`}8p3OIndIoBUyksW0)s01?Zfh2fc zgM+cVJ@04umq@Q$wHR>|AfWK_ng;!@H0?$tE~6iN_J&zyj`(9B zf&~V&t1J|9a`t$<2>Q|}yzAU~-D+_gqPod;o$Y^>&$ULaJ!G=Cu^4Fxk7~7%2xru= zXcTZ_g~LiKqpjTZN#4$1^eO^h0ZdbY_CkaHqIKJSYUjDF4F1d0yPl{iy{DrbOAZC+ zouzUNl0Y!?*7e`XgLq10mLxz-4L2T)U7caDlLQ*e>?pHtC>MFEyZ3}F+g80Fr(UZAE-v7RJJX7u&$9udz}X3T zfV5x#^R(jrCMG6Bz*zU&gMme@JdgXR+_e^O$NkY&4B zo*bWig4;;2)up|#^}dN^k-QZCgFi7;*X_I6ZMJE?K15y&@2b8>by+KxIC8G_%{KIj zNoj3;v6g&o%+9l>uSrASusr)YVWZL7m6|{+)>%Z=^PqC>M)QRWqr?Gg^I+-~N70yg zpz6Z*e;^KufO1hEr#p9JUYI}@I$I)ujqK=lZ^s(8FCLLPDrNtLn_g)I?{ zIv%heEanegx(**Z3B4wrBTpx*9BV5Qi(q@g=wsVG2a)bL4>~zI59pE6I_9-{PWGuw zUfdaIGCf);Q-H%GqAAFvcs(;vh}T6rLLo(bwuV-53);&kDnLulgXPl1NB=^qQ{w`g zOJYK4Jtd9&2?AhgXW`?>y>!6G0%2t%`{}0FVOFzj>Tq)7xi%k3THRnc6cEkvF&!W$ z#`4pq{D{SbghTYww|}jQZ^iu}2b!2h#{O`b!=?pzY0OnYIcG}tVD;GR8sbg@Yb6?e zr0Fs>zP>`_C)G5Hyr~K75?485cCMkdr6ma)9sy?_H2NZqIKeA8gaiCnxb1goT<#Yo zgJ*(l=Ue}ji5>qo0Io0+v_nPcA^CqJ^f)Lc0_azA7qV)0f3FX@B)=rV8ZXI@TsZjq zS=nF8^H0cdrfk79KAyb;DJe2qfEx<@vZP0;75SsKMnfLZ;;rv%W&^8KQ(qiUJ@ad1^xh} zB=LU_@9?aOvl3Js6Ewn*-a*GF3IltCYRsH#_zoDG%l#GX$?sO?ZJ&dl)zjA5;h zIbG~uIx9;Qu9aGj%}N{d0j4>0?6uisG5i_Oy#>+`=V0MOoGRJb{e-6Ftcs8Jl}j6< zi7TBi+7xk51zwk1wKmNHB8to1_$EE`;qqMeTAZ!NVb4@PHsfh<0XflPL{8L;9X}@> z^25loVvCi$KW2#kce1ZwT@Nm67kAc(wp8v=OyY4 z(gBE_4xeRES8uV5e+pGl^l-=x(6hYGL9g6I>+_rC*Adg7$!QzBhRfQ>8Jn;w0KM5L zwJhNm(l-U;iqDz5^>%4s-+01c&ieh5H{G;+2Tq&y(H1Qk?E1x5NXgN>^X$iI1|Xs&SJB#=ZuXRlLKBrfYn0{TF+IgA2Cxx7*5(|^)4 zgwT}j8uWMtO^b>JRi$_4$B!C58m`gMa6gyKsm*5$(7WX!ts|5qyGqScH=7*L;DsB zegV;xcB0>TgYxB}UA@N$7JTg61PqkweiKQ%-b?7*KCkP<)nWOC;n5F?v|QMc7U!YJ z+KHgyM7x7{bP%~~y8$%Fta|D*GN(o#dbiWi-QC?mtF^wKc&7!4K~bG3wP{MeWAJ8y zn;>s7%~{sODj7oSV=I*(d+IFQRV>hvY=ACi^z}w=%ukB#cb4b)qK`#4k`Y2v9w+7B1QIoW#mSQf`9X6KW!=j!s2ib6%K5vU7s#%!Usv7akK zO@Nma|1j78svB4=)+L?Gy`hTH`A(7rAt&+dYOo4B0`&oxb+oJ z{Rk&Gc2*pd<7{%Wl5S=;Z}xFtzkEq7O3_2x9-aZ&H5!g&7m~$ZpK%1k;vibk61dATO8EZOs#ux;9_SG$zniJ})CX}O%o?KU@a2Uh5MtVZpz z{0nKqhg8^A03a+-I29fMEU*y)hq=q#PUSr9>h)9rsc1xHu-P*%S*iN8XHWzpDB&>b z;MXRRXIt270W=NFw=quviWXs&nZmYNlGkwxi`aHs(*n2i$53q~E3yaqFwyA&bHUZv zuc=gf+y`17sA;usrd9@*DTwR=8MX4@%8-Yu4~02#$m$8)I?l!=k8e;i*wQLj$#^Ws zo$9Y6BXSG-){k=Dud)Z|nENkKorYa!Pmp%A*VVe0ZpwZ^m5lfi)GD2O{{6Ypg`M0* zoin|tHf_-_ZU{4iSX5PKa6rhz1Zo}#c(q>_MrIIP1*%z*$F@;F8O~iZ7)q{iTw-}N zRt?tFub)&tu<9zJ4H(xvf#b$8o#S=D{axRc2Rwg&qz8}p5Q>PkvvT2#+<{}}^$NqP zE@*nSk&53A;$jF3AAp#esp6ai03#!`;Cq3R?HTuIc}+8U8#MYE_HW{xsy4)$BT+tZ z2C`^Neq09%I6<}SF~4oxAt%B-cGX{=Gq1I_gloxv9nx|WgUT;sX)Me=uWi)V&zga& zG>I5@h=;YbjW~scZ2ti4?O>sGfhFsive=O_E$8ZYsSqW3;%b;;(IZacydH9m46A6Xix!Y1O^g-o2umzA&I@&&W!w!h zgCK6Rb~FjeWmx)|u3V!U0Tdb_=tC~jtf;VLl^?-yeHvqAef)wT3q>EksSdu)@y=K4 zsGQI%VJ&d03mZ5>{r<;~A8)4zM5!KX3k7~(SGXJp&Km`NesAj>f`4s_HdY_#%MvC2xB%QcF>3~B#xfmDBjHfK;AS!}Xk53u>a z9SjfO;uG@b?_IM^b6;Uw#c5cLuY zb6SI+^RoZr%spF-K_t&wZdZOD?sMHGILpvEaDj~jbGDsn?lvmc?9OvZn5C@E-1Lw{sVQuL;0CAX1ZFs$jL5lPiNV0&_fR6sf9qeu-)2 zInHqdGb}_dCAnFO50t>%Bpjy0nVADKK;eT}wCRkcI!KGKtBuBASm8KJc)kg{LlITB zwp%pINsa#WMX8aMHz*RNiI%-NZSe(`lEbum)&hHk3*uo`BQ=rcid&aj7wF`=(NN&pe$lgK~Qrd;H}+t>&O$XV1)8h zRw3GNzmMGaJxDcO+3`K@La(XPV{guOV5hi5!}}X29W(PblKu8NLSY>htwSM*bt|Zh z#L{O-2x+s**+XJ2|15_Z)b=($vy2&oIucS%=42?pi0z?>fOh)j2&)J7jMGHc8v%&l z+@w!20*xi3+Y}*4_ZyDuEe}P=t4cU=_zVwKk0>j*@!_?C4+;jem$RVQ6 z329~jv2*Kb8_?9Px12r|uYqW3`gL{jmbVN-?WTlNu9`XV&#UqlMc}=f)^7dh@}G1W z4d$joCzcR(SB9bMB!Whige{^8iZWlGi_?Aj4xyV1C8r2nlO_v|D%rq;DY?BSoOC{#it#f2Y|2Xk2;(jY^|7 z1GMN32%r}a$YG>zbO;9sxi`aM3-QF9z-dJzE3Vk*zvs?R#x+$Ap~A)=c;V>^&5Ol$3o0E?TC+)<(>R&O6@~!AmH;emP+Z)tAko$ad z-WOT!X_jFh3&W0b?;F zA1F7jJH(FbqDu}9n7Yzh0D}hNy8+0v6Kp39g-IVc;Q$w$iDjg8Xwccpq zD=}uxm}DKlMl}jq@LJ76(6A=uf*yt1lefRyq#j&zp(y1MO@Jo z0?z=@4ArAkFZ8>k1^sNxkm4v{%7Jg%$~Dd59Me3i-M9+>I+sXM6`NiOh3XzxMIS)a_5Gj@*MwKzsS;fGOls+#l|hutLs@+BNmUm`2xk1ZB^quAjzBMCd<*c z12^YKex8IG1B-G8jkRg~!kTb~u69H|w&|@jFTWPIgcP_WH66QI}&!?lbOMqaSaZ z*yjE?5$^t9z#RW`_sj+d}HytyM&ex12 zM_dT>?!`dw{`>R=3uKoROofU5SN!=M5yJOip7+ycq0_a2+yzgAK`t>7=i1$ygHr)3 z@V{q3Qx4Ln=bio{mSXECXY5xyhila=9_S&7qghc_4_4*#NAORdhUn6f$O7a>h$tv{ zN~HgfR|Y^>s6e=a8~#oP|KFx=iI&s0cNyo*<_i`i9iN+;2^#J*=j~1psst36rQ^kd zzau#xJi|16=n86mEirP6t5D?59no9R=gl>KrtvQm>V{yh)T zvHSf%Y=a8GlnG>!)E0=-NGEp>%pVOYb;+QyJ~vh$fCvvPQrCaIvJZ=9-O-5 z_X{h21OrcgF|_}FB#JT4$ltgnf~rf@D00qk1uu;1A6hH&X8P#*pynLZW1w0k<$2Hu z=rp@@JUB9)Gf%}43~`>$5dly+%_34N6+9DvEI>tS+?R4z*zFdK-xzG_vi~H{^v-$4 z^9F&jVXJ7jao(F|p5ZUi89sh`Kt~J^6s64vQC$*^Ce8!NX03K6<77kF=;MMp5pSoD zT%_y!9YL^l#V#QAkw1$&7AR1-X8aL!(xWTD)Qwb*{d znWU%g${2?v9o5fno5k?%{aMWX^c_$YPEJnFW>!cUR`j8TDd#%3CH{KP%6p3EnmMro%nUSZpzEz z_2dhlLS}G6-NDYTIlQT3a63(lN74+U-d zZuj5x$~Jt@^@>3{-ch;i&RJsiM>MzZ*H%F?FGIV${ICE-kWj@u$hpQ5rH}SqrFb7U zj0>l(9?{AEReKZXyq0<2fzstu>Tx!n;2Q6l+Gzj%-pw~7+h0)17UkLZ_lloo7?3T*X?!0Q50W^zcBUe zv){q^O!(76ATcT@vTkH%J@uxl7vSrw_oPHHtH0k#aNi+S-!Shl$qpnT3AY{`ePOH(x9ade>bf3y%{=^{r;~Y1v%w)v@m0}#nM`I z^^J8`d1DkRu-#kzI!On3?S{t}RfexDe!k8g{*{oLT%PAqUzxgu<(ro``<^v2KBsMF zF(kFCu5{@MkkL*wq_hZ6W(q{ce8C~Ng@Qou<3+qbx*xy*`b(im#wQ}qG_~qyDD*Mw0Q2!p^ zKA?U<)iUzhtY4Yu{V6Clvv09-Z%4o!Aq?yhWkJ^E?JvnT8`SPSr#+tZR1c3D_!wcb z>uO1+!4ccpKTcGw3??v#a5UbeZ`?s{b(Xgyt7u9iF zJMjJEKq>07AO&q@GfnNeF$#kXSC8%Y@W7bpi-|3HKK}0U``!xNBcYi~)biZA|G%GN z*avrI5~hAOUa{47KYC|}kjSzi(Wq7xIhJw5)7=Wx=@ z+{B^gw4WXJYqv|)8`T`-*S!;e@W{j2&z0_o;L1Z|3)7;?RvoA-ozL3C{09n95pQ?>8Id;*K3H;8Ob*zj*v^qoGL z&5s9yO`qLGzIhRQwkt8qM3n1K&#`kf`GgC(Ir7iDt{@7=$Ddg;30H|4bS!u99qz4L zY36xnfWtga7G zxyT*v-Iq6CA$a=uw!HXww`IlUe4Ptca<8Xrs7BA{PoGR4L}5ZaAf?7UC@i&J zy9<+^-2EiRnGZnOl@Fm=1Ir7tOl1t5L$L3Eu_LZ`sh7^ZM}Ac7B4&V`!Vod)mQh0p zak_j2bm;0`di-6;0d2Au^|e1T?oG(Pzh=)_*IrljZ1E!pg3d8D@4E~Y|6gU-8PMd_ zh1*)SxTqkahS635*&@mgv?wA=WXKc{St3iB5(sIPp(0Ra$w~xd${r$HK|y9@CkRAj zhE0Hk5XN_3u%9ej;5WJNz2~0uoPF-h^yo)X%Kj&HV3r;M`DJ_( z=lzcPFspQJ367vbqlMM0BhYSR`R2oq*LRp9))XJ@7%w1pFeQ%*tdEk9ziD7{1Z#MMp z6rsm#$~bqm#o@}tqY?IkHEzScGiNG~`X2C+qgNVZ1tz>>qUXaOMT{iQsW!m4BI@t- zoG?12K&xMY%L_*BJky~926}ovkG@{WoPFg7@i2y=QZ_V;IiFr?(RXF*BrYnhvg;Qn zCN)q{p`@j?8``DAmt9g%o4)_s9Iv3tw=*aj$<9c8<5|btS6Wi5lgp(ci=TEgi6{N= z(>k$pjAx^rNdOZn2TC4iWd zHXm4bAzFI&wEvR)g@e|v>zTa1)x_>8f;sNj0}L-p#_SAn$q2j;4WcZ_THuG@RFBGg>zK+wVK9BgT*QG%AntSrq~ zhz0{+LKhFradpKxn3$ksOwRvbnaJ$2yJUdjj3CMcOjGaPc_P8N?ejNvkrV*Tui2ECa7-yXY(+u;d;4eL$uHJ7Dd<=Bz01xAA?nqUskn7jEw7pXlQs}Ij4c_JHy|Pe&yQCSE$|? zAoaqIM)WWdnm<0pSvvs6c3HLcxk98!_(BQ=RW&-holqlTW3*D> zevKTbppZFNk`?K)jdeRf#sNggi|^kRL5YaG4=x3 zK!_Zs%S1j|j!ofYmlyH@Y;{?Gv(XCM0A%Xb^!xr_qEX7;$dXe)N^rXBLT~!l zbMP-je37feyA=X-2`v*~_Z3zBzJi6~>{7P_5rSW@Oh|~o*eE=NJ9@-J&6$v>b8Xt| zkF`ki^Nc2V(FtJxC~QSX{X7F|*VFNn1pATkt4cWchX1RSfCrXT>k1O!0EZ=j{XFhR zkj5X@C@5x4_-L_|YRR=H|+76wv8*Kh9&!OS%q3_UWPn@P;Pn*^p_go(Nt%Hm5$Q#?T&=LF#(7hk1r`|%ZeH|wd2Tgc$e-j4FW#joZC z1vI*{g0F@@CO*9*D&=)7?<~XdHD>yQD*>HboV&FlwIDr%$J?>!u!w* z%^yDe?JiHdHYK-;)~*PVQE`UF;qEG+)PRE#$aKeXr_puKwKN&d6!mn@Hgf9;)t1HU zsF_*tzui@HJA{09h3|4dH0fH%!~xrV)yk}$)%?-!BO_kqj)=G}h~V@q+inU&NYF+S&aC0%=V##w*vS2W?SwUCk#?V$ zjoaSzRPnHET>dZ|JoQZ1X6R-!275cb5A@Yi4_NECD=dwzXrLxt#Le4e4PY~U#TgUz z=N6`lGmd$;VtrdWCU+3Xl-)vlFQHEiIy zQZ(-UYkwm4eM?M6} zF~~uy*(}sRt03XfF=+X=6?Kv1jkXsk9)6UKX#@t~SM3&PKV2kcylm8)jlNk zmH#v-c3@(%sk_1g22}HYRZ-7#@~Rv!hLj+8Y>i`E7L&lw>P(-wYzgHnW5IlJ%>s7i zV&h4Ug~Bfil>_d|y&o9`rX&g)v@koaU;iqrvzDfQ zXa}yD=Ai}==Zh}23}CBq61R|VCp^$Yg>$aG+5ognQSL9mQ>7sp6)Aqnq6T$Lo3fK>9cL2n`-4Flc~owMNN$m-d01#1m4v9p(a@#s1r5$*c2+2KD7`l4#6ZzW+ht`?zHqh4$1 zubDis5_VY{mJzq^K%UT5(+5`U`WvueCHLnl!c#c zZP!V&a?-VNTT7zgp|E^}Dzy9Fg}DxSwUTRPYcTRKJSr}>11yX)L$n|qYM`}O;yLrR z31E6=FekDomnDcM&GhE8Z|o|$^&dPs`-arPViq&xa0j&A_#V(>%Ujfar@-@Jrn|k4zu+oEl#{i^p?@TQ!Z*|$ zSdCWf5yza_#K7xF?wi~nJ*(D*+=0`@WOo)RUqQF<)@;f{SMtrqYuG{+XG`afEYLp$(X zm*NAWVlq1*bC|UA=T+3u{6}3(wT&uiISOnf#vcvFcF#tSf12vz8}LKM7A#d53%wA=9S6~&jkyCiM`4We6EMkvXMNr*rUn_0C&9WDJEs`>PCv(i;pcf z3yNZG0dGdfXUBp&w1N=j5UX?1$J<6@3oX_KF5~F@kxM1lR%?r!L#}3J?NGpCvLm(X zVg0#{{G2E;qT;;l6)NY6IPd8H)joc^S#kuwH85Epx z4Vk@Yb^UkOB$k>#JNKqW!u)7DhGY2y=y>5D^}%-6oMxEnxcCyBM)*$0kg43jFGi=< z!d zB9+7zU=tJy;yYoicFrAfNCB4-G4``JHOCzCTzdER11@GEzF`4jT~sZR4?Y!|N(X00 z|6J1LVhzd{s;Z1<+V|%ZnjV8g0zZWPOMu4|2ja}-ptDSkLO`KjeSXMmPk5bo*6?E8 zQ=#J&s?}K{h8qN{F1X@x(VvM=lmzI&ORlL1H6Ei=08IXgh?!in7&=O-x(l)P^k9De zu;gjdP6r_9t3p)Zl;n5PM{A{jP3cf=wG#Kxn0hH~oFaU2iDe%!YeyT5EB%aaYF7!} z2>pnk{1}EI;h2yQzF$q)muLd;P#hGxT-d@7iHt}*Nl84gksF9SCAeaTk^VYX?&l*W zB;YcmrA!8%c-ZXH@z4H^)!B}-5c{;#ZUl-7^c&}E_ z!W>5I^4AT~KYum_7nL#yg5T?v1aYVY=TxHgozB6(wSNwhY!QfS#MXURbK9K40t59l zav1YaHs0S;f6A53K`+OwSF<$#G)SJGxeC8#AMaVP(1)*j=zn~JT(VK^zn5f;JLVOn zA`dq1AoTO_ZSzGu^34c?B(MMcg>Fk!HER$cOG-(Or<~7f#i>VhrPV-wOMfRZ;t3P$ zCJ;vAU@uIX{`BVFIm%e4!(K14f2g`M_L;pvp(09fhY*Veu`DUKX1HBnc4h>h-CG!S z+vnoGlAs;F2Ue@6+{S;@6UZqnt0xwqo|0LG5o(DWtN#u0vreb?jprOQ+1U(c3#sw^YBINwcL7dn zJPMLht5{pz3jX3HE947Z2folK4ERF9ziz@I>d0g@#azDV_G7$;)+zTV-Bfjj?%6Bo z$h%KIv3z^~Acu`sMOf=i!(;gNrzq#6@x^JKZFJqU$(($MwP6MLbkXS*7wHD%BGEP@ zEz!LwD9ddp-Y>a^TNN-y?pcp8OhA-SuUBwDC|tTls;N@ysHpALCI`3Z-oQn?#4um{ z%XqWyAni}wz;s*Vk|74g-RB)&5%EOev&*Zh?A`4jsi>6;6y-lK{FQO$uDuIlVukpn zfuu2;Y#`g>)?N_pl9~`%#!cV16XeKNQ%(?WGGGVgMFf#061ol28ah8#grPUaREeB9$v{z%egLnxcKDk3n`+(b$B3S&s7759{9 z)$I;s>f20m?Y0obbUso;GWYu>yRc*t@ zTZM0oB!k#lSqv*!d!sEK077~OWtuw*t6pJ#HSMvu631mg#^n^LUXicZlUO5IT13oW z@KBc4dPc=+1=uHD4PpkViPfl9JTqb`bui8Ca}7v@)JzGNJeEw^m%Q(;<~Ig zC4NF&z;*-yNH@e33FtP6Yy@6Fl|;`n0C-^CRbQujxU6=-&{1i%9@8w(-r2V65ip&gx4MBDHy+30% zak#$uI|nlGCTdo^3AU(XFGnTAQ>uU41X=EGeq4aS*4hvP55)om=39L|d*wNqzx(cV zyTbWDG@)E;#^ATEDjB`I%K#*O>kJA7LDF{lgjt4^=|m;oie)N}}u+wcayp zu5-&EHfGqvc$n3Htr!Un>K0A@ZcEoP9_3ZFhkAFu z+26bth6uEzQA7kt_)q=ypxf7#w{Pz+>tY%}95)m9K-_e#UNMxeoL_7q0>5>O`+S7h z<&gohk;vk4+^L(@PfX?Jp<;~HwI;?5$BiU>z!S%wrE@Pz_t=$C%}K%J=uPiv2%kl{ z@dW__E#f(OKSPxPtBXxQCWoqy1W#78EmAQ{;#VCT%g+bXFhx8 zfF1ac4M%D*1ATqnprlWb=`v5Wz)E_5Ev!7af(^?aC`;dk1(}QDf8gOEGsv8;i^29P zIf=QEt!HO@0?OM;$hq-9C~`Ef6ickzn9%SSn++vHZFp!ZSF|a`>b>{F%Jz$Pe9)8v z=BDsf`zj8eXm#jcLCwz^-}!pm)TcrvNR}dV-2$0zmw_^c)fEa}aslqdBOna9pD@>& zr|8uL-dj6X5x~w4{PoW1v%!}KR!UU>a;CoL683+h5ijic+O zCe+`UqZyh|2wp~mfeB{~(1LZFEqH41sKjj>0F=~g&-k6|$m~L|89sz1sn*uku}?68b&Bt_% zp994bUtC>(-y-qp+l=}i@YZ~gds7Oe=qQ&%SyL)W{fLOQj!vluGD-7vyh?-?&)<45 zw~mZPOCURO15c%q2r=;ZC~-J7__CIBF&Ntz)`pEJrACxmg3=We*m8*pFr=Wc;Boj< z;IWee#Q6|cD+BL&dybXDm=@a%Ov3A!Pv0q;>7h##`Imt^iji zE@2q;N(89fM`5|*x__+z%GVlANN;Ycs~Hc&`v%1jpOt5;o)7pFi% zd%afL+fVlDA^ zN}|kmNG9(Stm4Yi%uX-_A<=F9QrpMCBUJl5z7O%!CX%(eR{#Xlkk$D(iCs#ZADCgL zA0FN6eM>aGvalUWF|eAL+dzd2>6i2(QWDv>aa_&hp0u`pkf-1s!yIX~wo}$>-n|V% z^Rx&7ri6l%p9*~gnP&ca$GpLa+1&L5nYY0^D{fd&oMa$VuFtl9iYpkuF*|l#1LP8b z>2tuM9<8L+a(Ej%mq<35&GCc6Z2%Qc@ZJQe;|)gPx0su?_->q)R7>=bMdp0%1mo66a2@29O}H}+{upAyoL z?WDGMn94~f)T0knUSiuTUmD(%;P0bhafvHHbJsSg(b7EG{@e+ot;^CnivO9++G#Y`WxombeiH`5CH&E1thOGu2oP0UWb7#) z+0R?XY!yFn_>zrEd4X=6><})=q>49pStG70A^$gcYH6LM-W_G$ljtTxN0@Dbbq`bM z_kjAP(|Ol!j;G*@1tKLJcwBS&wjoK5-u`Y~hDSeYPUA6o{Jgkzu$sF6*ji!c=0jH?l6cy&b|ce;|iOd5daMBzJV0E8@niHJ-Wd;d6g~CN;2J z2o*d}$FamDBk#{bmvAZ9Loi+Eq(sR|IrujnLV)vn5{K>dL%4l*`7c2Aa2>)!#kKAJ z_0a&c`;3>-58b4ZGxFI^U!s z<5TSXNauT}K^>DL;!6t?H3waSJuqp+xi*i(Y;*GuGE8ZtTjUOWujDE2tsFI0g3OA? z=>J45BE7SKB<5usq27Sdpj%=tr;C8Xvyu8;L#$dOSEHo#XEJNsvOOhk&zT;PwsV}l z){s!8%`?!Uy(DZ)?Y&j^H!Nb|z*K)8`+Sn4aLWD$SMjvyxbPa~h{MMx6Z z9_ycn%S;A#%&>;hO>qUsCBy==j^414BL$bw<61FvJuF?DF85l^6ZIlFKXm4-`eLrNti$DDeSwzFGp8Jjz-XLNALJ zQ-?Ds?@M~YSRhiNA5FyP`yR{z?c(Ws@#Dok#U`9P_1O@nzWAjaAeUNoZ zM6j0sE~!77o&ePi(0k0x6wL(t2VZs;(bUh$^RyqSMd$SweVi`Vx~QTrD(sqr(CHrr z?@QkdzDzDem{)&loB}M>Ht6By6-6DOJj{}1>W=`j3 zyQk72#m&yja-j|rM1u!E3cf4?pj^qL(Vd4s`Vmr|-V;+g6%jw4m+hSFXV!)FOg`Jf z6Yb321+!foaf(Eq?j@zviuzdC#VWj z#EW!h&waxSD?4ER=xUj%>M@rbAlVZi22?$VjcB?}lxYODGLEL;r!U0KA{oq|;eCKr zuN59W;xszb1VEyHdL~=Rf(bv2Gtn+~L=w$=#%p20`CNgIJ}Yz)%}qDN&$v#Nx1rej?F^qvmAgvBdMY~f*M>D7YPj?H)~kiiy`|}syqsJC zpDu6ZGR{|a9j6KRspbot&E(wba}Yhl`^PH7m?2Sf_=5EGR!jFZ= zIhxZdI=e&i+(eN}HBE$zZ27MrM!itP>>04K_K+IUj*}%mcz_M9J}fC&#h#4{h+Oi} zIG78Ff<+3 z6en9zN(m3O+ozP5evu819jk!X*ZliMe`V)Dx)^etD3wWB^UM{9)>}M~@+eDv&*LvWQ2z$O8V~%P z+(b;PG4=zr^o|bAQwzh4RJmqR4N>kT{70lcCLtH-iPT`B3k9CZj-+Y^Ud<8jo)Yuv zvVcH&J&OgjpGxQ$HS9`o$YnCoUJl3M~%^lAkw^QH;**@gV!eDfKTQ)2yulfF# zP?>=hfNFtElW?A=BH{UbX!&?G65R?qD{Lfjz>~DQupl%d76jL?95d;~+|?dK`i)qh zkmRkx&^oCmJOa`2X<=xoCs<(clu>*ZpXa=6**8;nz|5d4LjAKcHy zZxJer_zdQAEXIzshd%;a9ah!g^l2}1-X0)d@ z7lu$=?E7u?J~%pz>iZCm9$=FUl2U&Z^``z8{U4W3o$>dD*> zY)^@e(LZpp;x+wegW;o5e_^B<5mHE}CdZ|lDUNf5fW=aC6H$S@O2Z>diepnbAWuB4 zXgNag)#k679|2ES@F3Mc0-wN#cQ-QqjA+qfO~&wtvBtKKlHf76eQx9t?gcyA`1Dkl z_)tLf)Kyoz^if816`yd$V(>7HjCo zP_6g`w5NF$yHUJVB1D4Gc~2N_R{FE5V5@Xw!N`SDE}Dni0wb5IXF#YsTN56QWw1dRH@HzWg@)SW3p1`CQaOsW+i=>kj=pWkJPOQ61Ir4r?HkH;F`PDsRw&}w_ zs%S)Y!t}oI3579ApI_+Z!ecI6GM3U&S7cemT~BmO8WQ3M*or55dLOqcFrO>-o)_b5 zfB6Um0${I7h3zzx{>-WwPx%vJ)BiE{LX&;UpU2=m<+sRJ7ZcjV!8VR+Nl_h^KIQ6{J&a1l1e?VL8-(-^ zr@qcg&kVZU)LOTXz&anR{=J!85R-Z;GV9vDt(bzqiYJnpfE6zvza(!0WqNk77hwuZ z`gG`K-o;o}sp2G}bY(|n5U1v^&l)hJm;64K&DZS}?yE_wfOmHV>^_s4omHU-E4MW@ zOlKIX!;gy;cYX3UW(vJPB-{(W9N_0B(k}cga#?Ob>m;a6`exKp-VvvgH}w$EBdDdR zjNa%D9AsoB-z#+&y9U~qa>2D^@d=-E9IjJoh^MX)GAL?N)_`dp`K;|^;F)g8+Iu#-u z5A)m7_MCu^C6Tvp=zY;CViQz3QmJ3=(3X&3JozYV+R>TL3>a%?r#;3gbq|A!^2b{A z%idlw5|Qk=(GVjSotc?AJ+2peS@M{Rmwwk+({#A>jtY3ohy~y0USeQ3I)EmMOjkVl zL(WljH!LvU?6Uj-*?1h}s_!NE*BRIeTQtpQ%{0e&o~}nr!a}T#*dQ-A zUbQZpI713hqM(kIURM+Y9%j9_36xX{xY}t9giiZ+gRA0MT8#!b;U-Zqv3^!O`uq`8&TBZ8BXG0d`o1B^J zltReP)P3CC;EL#why4G%;}=5M2=>pYcrbuxLpI}Exdaeu8uf8DuYT@dn|h8=3)-{z zj6#b(@7zXCfyl?|qsjutzwp=a2e(Vw)gEa}ai6QeczfBAX=mma{iszh3_!8ZmZQ1# zt(n6U=u?1!I_#6+Q$8+){e)Mj8?*gLlQL17pH;Z(0MWh(l;i)?mcDEgd?Q)XtXNqR zODliK`oey1{7dthv0URGG`xF`E8#5fGi#4|<#RWroOxWC*r4>_)=~mP(LJ9s&&8?c z=;vFh=)7`LAS!cX`#vXLNZzGI-y&1fNSOaPuK{s&Y#&q7d;uwsv z{-d-2FT;RKptwc`b=zF0&|`-e6ag=g{qHygmlkVzf(@wW5yAS0$#(+*h)VnWzvE92 zbSrJnnS**9-f?#3c)_c|Dfc1%GJp!e|0C|gnC&kZI$j-g*=Sr+Wd1hp5mc1W+eO^7 z1$zPKBqendgeS7XO6*m$e!B!%#?cG1zy3pyj7UJSa)QS#^?1*rsp?2mxyUVkl5H1j zx{6*XXvifjx0T$d-{LXLpY?zuobCiH77&*Jo0Y@4e$vU}5!m9E>3#hteW9lC2n%W5 zu$23IxBA&$rBau}=HPeKVG0-TXVATON&CI;^7M#*6Vp@FEXS!g!2fo!t5wx{yJL%d zU_52^`aVdVRQLDf>w|KT*H7FMczgdlRETreExK;=iv0KikTY+KV`Xn*xdN}uZuL?w z7#Xq_LJ{VDM@u<%y+DWbmblhLg)-*A zgJmUtCd-7N$Hj45X4%PSzyzanU+YR__0(U!Ih=82F%Q6!M> zaj7%h);K3I-M@BknNpzpx8!OGFLXUeiqCB8mrTG+$vu&G|E5m9r0!okxBf{cqt;O= zmXd`}&z0#~Xu;y3TX@SCl)y_R&Gjy)y_W0s#USl1UjNT*kAE{zwMl)mRl?mN1JF<( z@Os`cXBM%Ll(IiTX1wOM)|Yuo|7N{`2{S#+wovpL>z;L5_pk4_eq=eLG1iikdH2Ih zZH=;G7PqnKX)}Dtz3vE#KlpAbtB8!Q8tNZn36ORpj~zRv*hCu6ytK5qu&O%et~i(o zW3^mp1GJjs?0e=~Pyj66cn?eoIJxw+JSO4A9O?ageD^T2(!9SVbFY0{8#Gv|+&+>C zn*USvCDHG%c(N80c|zXus^*vjzUZ`}n$JvD<+%aMpcjrn8?sW;N~>8w>m5)ULoRov z6tD<_c~Z*`R72mLjdi&o10Rf}-l`9&+T*t%ETE&L18(gB6okk4 zY=(Qy8&f&tHBhqkW%vJDQ497yR@0FSRn+()?;66PQm-xjj*ZGtroo;H${Q*K+tDeB z%agOV1P;fIWN{@+Iy!@P%8GH`GXDj*=f4K!+EDe;pAAZ&T;Sf8rKMNNA>~#z zZ%jNtAsBRcLRtPT5-U90cA$GA$_JYM@zDqkI#0Lr>#QPaR|ClVz+WyTFm72y--q&n zOQFk?k~t3i)~Uhf4CGR#>6HPfRI5*n_se{=e+vkZIKW)TWitR$A)w828+VjbUtG=% zI_wTZLlEMbzvNoGLReI9u6gsBA@VYW2{?p1OHa&P$Z zeu0a-&da`QSuq9M_$+q-=u9$GN=&bi{v%y@%Xk6milw1u-@NkTE(y4jlmIh@FfWcgjas zG2MpS+hIwJWsQp&_^^*WC_8jy*~W*1g|1CE0?w-GD+C>N+kp(T6oQkOJ1trP;3PmT z@ZEje`L3{abpbG;gkz$6(y?0?+&KG7krIp^!6A)8kWPS# z=H_p>X2qP|2Av%v-FyVA`D6N1IwMkU$ZSLOCF)81yU$VFDuL}+XoLyf-mjC(l`!d0 z_1bce#|`#vd^oxMuj5?h0cdFWQ5wo#4~LpH%}RD(IdtmqPu)v97<1i=%KCn!eh2;( MNUZwuEfiLT0k> zJ2S#ib|y1f$2R8o8g-Y?_wzx&KdOfw^?IMzIp=lO=Q+MN)uBxL*!S(&v4ctZx{~IO z9lHv5?D#$4k3HaTxF%xyz#lsuHKCVxWVLWkf**F7U%GK=$Bx`U#x>*J;Ae&h*YzC1 zKlP#i+8H=HW42=lEk#-BlJ-NxZ&ZetcSl{v{2g6Gl+PXutZg|`9U28$_6*Whzdy!% z4EnzIi&5vwlALe&zw~KW^(BGMH^92nS9lJw%8xPfi@0a!EFDzw*$w;h^QfxFqH4NMr$taCH?#X9Jt5H_A81LQH0UV_ z^qnk!(#%HmRMVY*33-__Usf@sdYX&X=27JsqaXL&?n8`)XN=nuawhaj&?&1Fx0>q5 znHk)%2mG(I{rY#+Fp_~$Y>b7;hA&?!xc~b9v%&PALEDM+$dFqY?5K;>_Btmcq5}V$ zy@$@j-_gX4+f6Y>6&;j)evkww-JIRbF%S_{6PubyPsNj~J{4n)iRWYqcd~i77>h{m zj>eK_xqkh^XI9QSb#>_G@SU?>#x)IFe!{t{sj=|eV03Aw8`61_LO#L@zdV^^#K?Ib zzQH}+9B&3cX7BdMST~kpRdOsRV_}v%N@r|F^8W|bQ;o1Z9FSL<)cq{qYeuHq-Z!#A z8a4km=A3mz=~Q~gU3``SL0KSnL}7g;IQrQxjgM$I?w7ALEXFbpun zTghCDETPc0?`$BK0=lR9rFdnmGfpq6R*|;cTDqH&^&YqIo}aq7iWr139;(b_>2p!y zJ@X5+FTc~xJ$Xo1`9XJA*GK@DEUP@?@i}YUhivqyaFjT8mD2jexZ0?km0v{WunYV= zsfXOcGjAx;Q(b17V zXJs}L`wf?6z(JL4sbo=nbqv`eJ)Y0g-hJQ)lP33LUc4+3Vzp8Bk1JJRf8>+7`tl{W zS`RvRz4pn~z~#pbs)NEJm?s^^<*XNMFmy>YjAK?wj_{R^$o@djHPa#_d0-;dAhWR zw|_eYS4b}&_SqJhUCzW(`>@VrEX`y7dhL%Fl_IhH-l~(ElKE)Z<-Rt|)4B`hwUdo7Row}D;D6t3bZ1j(1DQv(U?Ew^Dx_6kd&3{Z=J!TEAr9D!#&ITitOR@ z77jmelDCYQsJn$+uI%jJ{d+XQ`gbuWjy>q}S}^;ic)junIMfg$gmR(gZ1x`2JK%Dz zvm_{mK z;nslVHc7B@>BqK53bwM?vE;AyI&{*UR_#{@T{CRkUsd5Vu6`~F)O)ixZ$l+T=-%Xh z?tB?5-N3#|R!&vlPet|;hx{Nd|NU_Hvje>SQ{5SP>X7~t=Zw|%K#wqn{1J=HK6@;I z>%xQMsQHHz=gb1O8t9=z)8X?Ed!L)d}}nd_Hx2jg|hBFl`yB5GXiOYmV9+ZIWmI%@bbn^iKy-18dA4EM`>7_0 zRwwvU1>5_E_`HI2+WH{P4M&!vt<6c0$4dvPS*0T(s%Ob}h@Z{l{Vnw`jA#}S-?Wx+ zNqOKh$vlcy){V~b&2n+s_nFFM7NZMJ0~6CYZ^XJ`fUD`wUnBy9H<{rJV=k@v+Y|_y zmp|T3nv18Q`MYEmy0i$%%AqPHH_-=O{OR8P55)XykvQtgf}__SCPbMV#YNt2(aE6H zr8(Nu^0d6I)TDSCiBMWoG9*W?y~BW_YPHb$uXnm1_Q8UAf~i0tIEN>t$Zn2I8(icqTMQ@`Sn0C<6@v`T`pTOS(Ir~cKUCw-aVLjg{ndoa zbng-Q(lhJK(!Yz$iR3d&?<2+{2P_qxZ>s0cjjN>HCK_er=H`wFjceDLIPG6Gl+G*zZee{D>I`n!5NfODjVi|c78Ln6!W!KbLu0x| zFcy9?p7RFoLX%t8=%M48pgMW+G>U{!)3Ip1eaCu9ss*)%=6${VC40 z`RngY(i0NOV}bXYhH_i#cK7zOmnF@&1w#_8+Zl`QsSAWL)-_Ig6FsPky_M%CIs*g9;cu3^-;qlM*d6b>Loouqxfh@4ABu3)L{69qs9r z_GR-L^z5U#l-jTFElQx7=ZT$!l;e5_<3P;TB7JT-PwY*V`3wxrMw>Icf{J>*vm=xg8G?hexlm6E!zwSneig!7GNP?jY!@B)OSkl(-xBD&uC{DlM^X+jQzlTOa24~p z(TNeCgI7c|Go{u{MS6N?ed4)FhP#@EYa?FNe+)pAW|t|GodS+3<{=uRVRuz;RMZo* zN?UO57dN8Z9+%CO?y)a6uW^STgljU$FQ)O99)ch=Scy=*e25`eMS5SxVHrP&f_Fe~ zuN#pTup6c+YrhO9)s;$J%MN<+#NePxeXt{9mqAE;HBLZbhJiAv;VB~#C?jKg;8?_R z%8yuR+GEpX#8V)0Co4R}X+rR6_aAv{$1}K*$L=li@zkCdxxT+3zi@C~5kwyEi6zBm zMC8@%o1Cb%a*cfIKL#D4|1Voff9eQH0?+DXB*rtdkkQg~9_k z;4e8C3)$^?$T&L!hyPoqVj_l9`t)2zf2nB0N9F_h?|(^QQue=IISI`RLmYUh*b{O_ zRh>(<(_ji=JQ=A!shjVTDocFYp8J3pC&hY=*Xl}wGrXb`aYalzr7#Za@M|iWwEy+; zNoaQ6Es^!{yK2D6xRP)%`y0+LM=JrZx@IOOQs_w-)eM$+pgXn48QUME8lV!k3@5ra zoy8vBNb(8^o8>V^L*yrC|N7$ht*WtI4|QV6L^ZG}BK4QXEuBi*nIMNmce+-v@X1zN(Sw z{88Te1}IOUY-^@0l$_I?2>76kwuK>tYE47+REF!}UsI{d`ipNsiQbhfZ0UkXKt?F>rb9(>?$Xay11^h< zo)(+rm3A-c_iN7krEf&;@9JgyJQLCRR)rxSwJ;Sf9i4Lchd>NvNS@ZWOg^0R>|O-y zdOKPIDLXlb3A1*Xw0xej=hvQwI^XXFvsZu5Gzq*M9J{QN#ru<09l4gZ9?0_76q9lt z+V~i_#Fa9fd-3`!&g$?kVddLapQ?XJpVZFYw1uB~IR#!GZe08A2>X>3?%42MKv#6< zyR>SbS#Ge2z=FHRE0j7w#O$f6=B~bN^NXh|oxLdvZve^0+c2y0A2P-{EF7X|!7SV_ zrxv*{aQeS}5k&M*RaG66BqVz@fM8VYmt4(w@FNxX;0NhpvYZW*w-LGDtSWzgK-_s| z3>c(^k)F}^XAKv1DSS#|i;~sooxi4@opl$BF?B7@X^(V@@vTC805v%i3<<+6cNAaj zhQYCxFJOfpcO(%v-sw)i#`IIvON{5B3n^x1-xRmxhU$|N!$dGpG-K?Tl za=Q8J6!1R4gFVevIRHBbDh2%L4=31fan}(&1b5zv6f?Ms^`K7mCKWtMfrDpfgV{2i zaICv1j@i$n(C7djiyD&S?nIsL7TDh*Ma~9@vU~v7zBPvZlVh?#fl;_R2B8EyD$${il{sB1J{U zD!!u{PW%QulX3eY{n{IlCcoXV@d1T_%+DoK?6=r0?@~g4%j!2$Rn5Ytu)WkcBtlKx zRtm8f_n_hTd0j}QddMF2mh}kK*|Wd&4U8l&)OH?ZxnBg8HG!NZISY)b zj~Si^M0~b31qonAr>g8qkOLu-L-DX<{+m~CUZ7AX8{{%rMNpvPu~py+g=FsMlF4_6 zo`>h~1xlSeceV9X?aJ;$r?{{ji+Z{w%=QfWns(LL3|QU>S)(L+U7d z*{{#NW8YrFAM;N@Ek_5Y&j|LY^m!-kCbFpoIW_4Oivq=z?|FZLyworXSA(qA}vo2R)3`$F)mbmuQmcKi4Hhn4^i1)G?v}V?SER$T#qt} zLLt}@B#JluI@CU)IZtJKg?F*MD7Mm{1Py#gnT~v-FA$GLSdly;SODQ|PBy)+pWMk= zzM#-dX>InscKA(R<|;x4p?RFdR?!Z#n0p6204S<%8MkrCAi^SO9-*MJorM6!nZUSU zL%LdaiJMHN(`|6eUhAX-%abpN9^&}HeeUzDLvk6rwlz5tKF?oW>jE{Bca&%tB0Bhm z>5TVP9}`ShLxG_({u)ceTUb&b_<4Eye1b?1+2Sf9?GJ z{eY=veLEY<;UOy=v|h$kZKDeBInsk0lW*@Wl+MPw6QJ@aM(4P2&}Z4kY(2V?_%bP< zot^zGzJJ#EC#i9lvPD5CV?HQZBWh42%zmI2M;(66Rpu?%+VF_}+&8V|gMc`IV_!9A z3Lm~t<#9C|E7$X7O*b9efnkhe-;(YJ=Q+RSY-w}iIzv#vz~wme(NBq>39v?hfR2BN^f4x90wOhsVNy!G?{l3MnStmh=H6*o+MsfP{2=k30b%j(9*yJYTof5&aylF2BR=)HMPTLskd!A z&a|rhpZo;1SP>36%@uM!{?nu1CBo-*qn~f|N*M3|EVyQy-H4Uxj`diX)FYoLvMXD_ zRgI4c)Ahk33bK$1S5&BuZO`V*XeqV~i#d-}#$A9>WV4p%#!EA@N`z)sl~pmd_wIJg zHKye^<(c^X6zc!14}xkCsD*A+YL{irl>_nV|Cm{-2UcBvL0bwjQdc$3D)i5HXC&B) zC04PA7>lyp?px76>X&_h_u4&7WC$iZd1O_s=9GLCp>NO(v6Wq8lwQ ztpnvhDo~GoJymX$0cKXxD;`-6TFfG#YjLwFa%HY(!pt}Ilsf#qG`lg;Bdw028L!}e z5L=W#OUNxa+#%We{QqR?KMf~()~1&!IF{v8efK!#&%e*ja~nK?UtJdjRwa_|EP6`d zVzct$^VF2?QY86(rR#|sbMKCBt6eX;Ljp*s(`*)YwzmG)B3b+(p!GAyx8J_i5afZ$ zhEX1C_xBf)A_LLzBPBU#3W?CTuCCfANBm=3B~r?GHBYe#8CWgZl#uK}RobuRiPN z5;)&TiN5lny}tYEqNw0UjbSX)wJuFAVVAAzy!YcmIv56;71 z1Z)V|2f1SHL{DI!P^*J*t`RKT8r9+3q9a`#G-t<*=>L$}_$GFhKp~+ZtTwSo!UGs3 zg)?kFjp{?gI21#tR)yrRfBz$ru+8uC`-wcv7mHdjCr!6Jm{ynEG87c=o+!TXQ&t2`&m%fY5a;bU#ek3 z#HSxhS8m*v!Bg`%Gn;UsM${07RmePFhpD5)-@S8Ya`l!9M$r+=du%L zLib=jX%_dWMn4?Sm$pLJ?9~?A;rEY4m&q}Puh;+v!SZ`bn{yGOQuL|oSmm}n$x<<% z9jV`aMYI^B_Qy}%)0LBQFaz$9eX!&Nd$3r?kZOW#O#>y(&?m?&4y4rE#AmhXx-z}e z!ecIr1wTF7iAl|D^F@ zUAtZ}2qSYSI!e49S9;Nt6OyD8SDv;tNjyri2VQ>52wTnhNq>1G4>_`bIVUqyl>Hd< z4<%;gXB%h(b!XswAL0wm>?KcfCAUXj{;C5Ksk2{M8AaSH6R&I;oSF;qa1oYoUd}`f zEa&_*m27Hz1}Gm^hqB*$iKbo3c0cNWeXr%h)%Byt2jhze(+=7w*Yg}YYBb3Ky#JP2 zjh3?0VXOLBOwdpH8=bUXAN}2@8kinSKPhO^cjY|DELRMNon;Omt@%&8+<7Ko__j(Y zW7F=+>?;^S!7ToMXu;=b>po9Q1}GZ7yJ2?}*F7Zn#pkb{94wfH{zkQ105^z}cdOt$ z0%P8m83c!r*~!ygA+l~KewyHNB|P2QF*N zw9!FxpSM0Dcep-O0LnY_Hy?(wSE)~%0l|Z%)`@-ja~H=P?!81?T3M;=FHG)Wx656s zlx*F#rE!RU5^!0xIF#+|5BCNd3C^A*XrBqtv7jP0Gj8b9X0~Ep6U`jH@R|pH)jWl+ z_qPm}wR*3JKKc>RJys@_&@MI(RXwlineB?kk<~>h5p({uWcc0Y!=|^9A@a6Oo=3LJmvf0RW3gM2)ybo}ixxLg+2Xd+&8B z0T;hkA7AD2D!JpZ6~o_`4#80)Q!}4~FcI;{Rl5g0vv7D{5sE^JJ?6#irwAPL7Cdaf zNi^kI)wM|#wEfroof<5m`3c+y7SNEQ;ZjQB3AkodKBk%#2Rbr6lsuh5jC<0p4>?O) zzbh7L|EpIr`;CPC!O3S^=|Mar|1yp`sd}F7ccD;-|HiQ)aiG@zj%(0v!BsLk4)?=14T^hYD@^^!L(8KE>ra z(Ln0-Zu(6Ce%hD0Y8ylOK<+=Uz-mXBulQ)Oi`fQqxFd8!fwp|?N0$;J!gy>_8^pWdGoT)!MOgLsw!796<3lJRp=T- z2Od0Meyj{7uD8=8cpiEL52`xRvgi?ANg+8vVv@j(udLh1yMnjqX)9r8$4w%HHVa9* zHTm@Kdq3Bs)Ovmpr@K>G@Y;9%vmalq8BOO))&~=AP zNf5oFM)&C&dJ}+N?z?u%acRQ1i1vMF5xGsFh}O0fIWiGE5j<5frkX~_9K6T$QA5bI zwrzBkZ@;LhsIRQ7X7M97(1HG`R}Ce!rI%))3T-tt)EreC$R#^g`0evlgstIM1zq{p z8@e*m_RV?{gPHyB8*B%Qc<1_6z$H25-B;%8R}?71^9zUcwidId=RNal0Szj>?ZMdZ zjO(pOjiSuyf%NWBO&pc5%2L|+R1FwNMNgYVSczqE%m*74lV{zxZs>{g9zxU~Fc<~* zEJn?G!xG338@J);%1PwKCN``3mcStz9cxgNcm)8}1f2=?QDuutZ=DG+QlpgIaLb38 zoyfkJZ2qS@DG{90e5sI#eKC;miF!7>dM*bugFkj|qheD&-#*rLK<_y6{7WW9R8^M70|l4wz;uu6S*QhRU%Hqht=*^5a zZ!fCDPuA^*(UqS^2Ju0@D+J{@u!}NX`V^RF9{CkDoin%nh4}kT=2G-g{2Fnu7P!cf zaypRhE(Fup*FT6fOdiQaFAdZ6&ayj~0{ZOJ8Tev*1+=k_JN40=MEI&>nqT}{?&@bo ze2Kstg*&qa;X=mkH7TUWwVpw)EVFT=Wk@A`v^07or*t{?(lOiCR?Y)dN%dUf`o{vE zn%`1o2R!KYHv+YVn424p3-NDEM24v8uk!J9cWJfo$fYxFqfb^)zSLJsrpGo&yrrHq ziZ9|W?vXz`sf_&cy?o+`HT0Pgv4>|}s?;`sLvHbFq6b{Mj{MLA_e>ET!Dg0!o86|q zASD4bnKY*NS|O0Gkl3hz z@3nMu*O8voVWdhViL=}fkV)rTU@j~qeIB!WxVotJMf)3B_y|LRKI;pY@$&{9>v}o| zZEQd1ofE&;ftoKv(t{K-93|+0PAP!2nn&O~>Y<|ZbzBZqvRfvqUog0uXG?F>4ZSS7 z?B~|eq5=R_iMPCG;^|tcnh^jB<5$8j<9mADjRHB!EIyXbPsZmfYE;CF`|&G*wrQDH zX1(y6B4WnX9KK6mIy-&L15llVytkEe&SluDn|vCI-7i_xExm!%W<$Wr61+Gs7qOpjRwfY);P|H3z&}H zT*x|MgI$^PPfD~-ZlgcxstJt0MIxFH(~7}s%FCasW3vGe*$=1XA+4@?)Z#(6As@TR zH%Hoek3I`PkV(3JM%Lr&26lB%67*8J8xFt*J*S>8dPZ{CG~ZpgWRer6UG#BXg zYJ$;u!-9uAANa}u;6-UEahH)QB2G!cDn{E_t%W+u9ptiJ8nSpczV(OPRJ=01IU+vH z@sx_}vk*gQ-D!EjUH1r#kdtyq5Clz}>%6$l>}#!FiwH!oore?S=oFE_x}>b0MU| zGqr3FGv~{+hh?f;^a*J5uk1{%+e}1 ze~UL*MV7(?mfTmXhvH+`FOQAyW#&Bn78>|u#z1g9t?U8?L*?qAl6mTLR4iVK}h}u(%Wpe9?g>H5pNaJ zdJ!&=wl*kAhD^@Yi!RHJ6zs(~BFD~Q=ISVfVXdddv8yiC9;v9;UlZXVJY{g?FNu8f zQD2j=(%?u^#Sg|CNDWM(6j4bW-y1~jzHlImYis30m-;oWQN&d}a%2j*U@9RM0E_ho zY5MOmr~I>%H;k_th~+n_HL5yKy>Ap#?LQVA8g4U3sm(<86F{W-@V_bWK5^2&VWolN!wQX%=X$5657Lmu{^ z@Pjrtbk9m_jVqviWr>)$X+?^v$6zLz8HDlVdO2*Dk!nTy0ue9ZajiHd+r9OrPyZpU zxW*^wS^G?&fXQdlUaoxQ4J_KL5C2$Dw2DQp#em<|V`Lq_Bku;f1>!a0s3~rXWn)$2 zY%pGP|9TV_j7!{x$eYKzyWrSgcW1+~RWqX-acDkB3iCFQ{nZ^5{S91p>dD7H1|w1s zv#|=A4b?-AGjJa|@==E?Jns4F;e}#EWEC*W&_GUTz_Sv!Ca-DJ(ql zxEQiMRIvfICeV!kuuyvbTK0p-0i@>>@iGtl-nvO(p^r~8ba_yFnW6>-uy`ycylYr1 z&bfB|yW&;#)UaHvJGEv}9K2`*vUXxsLeV~M;l1ojM=OJrrFhe{)RQFHe8ri0tV#MZ zwVfnf#Oy?)1UM4d$ZI-oRHFQ#gE?Wa$B<27{R*XK4S5ir)H4f^{wap2dxQx9j>XBm z=Huw;e!Pw44nKjHPs2GEpx5vwf0@Ol+=gO|R0B^5RaG$g`!C=8@-=N4;XZ zj}0kajF1zfd6GXs`{TUaK(okkzUP*d)z_uPHWjN+F-6r`joK zA{9NIhpZ37+~f!KfFVoe)>B+_zNm_eK+udr7`HL8LVzl6Us;~;fkc9*=uaaL+-|Un z@OjU$;yidOlvYM{9dyr+jLGAd%^`fS4qa_`bnmU*A3N*BU)A9Aga;+rjf}>S-*`$2 zqed=(<}u<_gy9w8$nHLT;h^tLkI4R8XCm`=!4mnTl!OXNN1d}*r>Op<{7W-N#CgTF zCYHiv?$}wiA>v^z7{$(SAU6{de%7Mx^}B+Ls_G8ed$#fHg7F|P5g<9u15h9PEroTW z_=b1qmFnr}Aj*%f%cYH6e>ZOKUndi*aWv23@@l(&q#}*6$eFx25qxiCnc{D6{w758#uSY+3G^y%1cwsY+?h=o>@9gmu0HKk) z^mtg+AjZX%PCLiPPE{ZPhJ@7ITybmpHY+Qu=hwnmwh=%>5@;klm|w~A)Aa9DTEpM_ zp;jpX3s!J$$V=*AU{y#`iPNh!qQtZKy8+*>&3A!C_}->(42C= z!qmXxj3skngpGdO(NjmX#^rl6 zjz+6BixEo&zS&x8dO5e;_avwZ*1Y@W9AneKAKguY1imh_c%OVVUVVaLc88UaZ=NMN$ZSowiIB0Vl zAvAOwvi?RsKSX9YZba)K-+V}|J$f~u3NQHPJZXTl%oGMsSH@@!j*gFRmj`#$6*;zN z+{p&`r0?*UABHmaM2~)voxvE^(U_qSH?12_7Zi&IT28n}#^c2DlAtdlI#EsmjT5Hd ze!2%a^v6jsa&vhqm^TkJLEq!{h)O4BaBe3sxdKd9L?CVDe?(0u<-0E&xdqvg9mZiZ z+F4F_R;BXd*M$l_)+-A1zT)oe5r_|2s!UxKP{8)cJXpFoA7JaAb{>)Lh9TO9=j{PS zy{#%TDHmo9KHW*z$9K=pz~g^hw_so46NDJIqUCb_qO71{`>B(zA6iXnxCOZpYK zJIs_-!vZUts6+A|(ZEg%WI22{%}Q~;JY?;p-Ko>^Vqn^#qZhJ#v5hzN<0{chr!`JK z=|FYmHu>_<1icB;qI51hV|19t{KKkso$X-Y z^yh%~=*gXR#Wy1F)uvzCJvWNey8+EZ;5j_~kZU%{!Ru89Z&n@55ZVDy5^&alKBAhme@h}y+o{r2Zcu;u|xo#S1#*Lk-hL^^! zBCiH&$Ah?}Y%hgxk4kt~V_t1Z_F(&A#v+fEk({cTWfgUZyvsM;dG)|hkU;GXi9>rn z2wq6n-A=iWN*C~2jwk4(9v50C|MbF{UZT>MRRg*@@R1=&??Di;5EVbT)?z?P6z~jN zSkj2jb|4~cUl@Mf1@gQ##?Pwtt09!N{-((ON0ob%ZgnSsRPZI%1>^|Y%7ob!VLEx&eQxT$QHx6JaUI-Q!9lstbPU|oG^t3Pt|U`UUQ z)5Oj0`RgCL<%nkZxpq%`8VCfTPK57^({{u-+jfaOL4h8j!)?xoZTP$qnq_gzQGH?b z5J#K0rx#-nrIY7RyJE2R=@6)yR-DlI01`uf1%aYP9vKHIB|f^umE=K-QIF`Y1B1aN zPbzL>GwU@1x#dk{84>$T#AWw~57E?rDkE=?=7=^1L@`4iGHcQAtSzalor;cLwF=)9 zdJARPqtwd0M2!a%s9BZ`ourV|Yzv+~#|dm{u{9{|Y5Q31f>k_T@B>+(%2a}bJ-ukm z0e6>n_y`v+JmtAaXXf##ddl9HCZv$MZ63=#A^GYg&9%Y$AC;SLgwn{%t-$4{p(iZ} zgPuzlO+IN`Qr9NOP0De4MGD^xUrF;jeC%qv&7(vXVuoQ~Pt_M0o|BS-@`h|zkm8g+ zDLfgVg=m15efNa?EGL5D$m(~i94@wM`=f=@#*QT!1U_P^t;kepm5aY%sG{!Qw3q&o zV2&s!P?fSK1Wirw3v9!7U*6OQBc$Wk!x0<{Dl`9l3RJ|um0(TgpuWahe9nYMUV5dW za(E!X-=NggeO^7pcy70z2B!4XB6(1e{eaIl@A`8cfmxLx{dV^{`926MepJa-^eB;b z`rM4Kgwlc;`Ag==o^q@<1}opS^oDz7KIlY$8e=SpqhlH}x%3aB__i};hw215lv9s4 z2y%O?kJGw7^l2LQOh&V8=CX*i=O+uy^{xCea+A8OAO%8_tt z+m8TXn{45g=Al>Eu!R5w0hwRhl zNXdzMWS2vSzs5F31@Q{>N2+2UDY&mF@lN^Cxc@EZBJfng-o+2n)?)&DZl~ZRw65Lv z)`w%hS|Z2(Dk7BGi@orG)#faRfXUjVL!L~*A-u&SHK!G}QGj~Sm1|IBSUTVOs?k3T z6EdKT2KY+oG^_7_rvgmt_r%p%|G;92Y|rXgX`_2?&4#(>R&ID3&+&<(My?60vxA8G z+RQde?brA!F*yIwaj1iLg(uIyoGZXlMcoQZKzT^usSa27kiRP7`Hh(Vs}!|{eFe!L z)cJ1{Qitg*oDAlOTOvM-z-Db30mQYC{9Z)|=g&Zpk^6jUhW~QVDti?g$mQI(Xot)w z%yMCr5@~srbzwN^^E4mLFyFy)Eb+VSq8U%h%G7)z9oSa0$_2Of+xT*l|7eZCy8g*g z9^a-d&4f%T1i_S<%tY(A4hBdJ>Y0BU8WzNLI<|5*EOI|UzLTXvHyGS1f3hAqeO)?Q z_5ZG_{Efwl{TzwLpHMDw(=MACWcjDR@VJoFs#^kv0hG`A-vx^Z=xmw_P70(hD5V8L2NH5GlPfzJ@f-IV1o7ZnsJQzW)1vKJ@?6hGB+DuxLCg5V;bfkxgP3r#=3Su=}nfde&_aQHa%$N zj5st~2yF$ARsYJ;CzrPgtTe7=!jCgNyz~)dba0Qnedyp3x?>@>D`J8pV9Tm%mc+^tOx&lU>lxFhn9oMxni?- zuv`bE?*7khkY@PIBT-jXGG3aZbyZiWO%&09M8HQcUgwVMuy*~Pl$-WsQ8931v4;#tWF zGFAhGA7Jbl^j}Yj64y(4-U0l$CPYnvw41)+V*aft7%mF2zWL_B7I=WzayD8QBQ{8C zh)VexG=LT)fVPuq{jYR$76`KZAAmJ#U#>`osyDYX6$a6IwEo!gz{upJf|0`Ux+QWr z2#tUA-;@DX+rE2|KA*MZ@9l&+Ga1}D=Li5BlH6M{(}xg=!{OffyNJ#+j;{RoyuK3J z7g;|r_F2U5X+ix>jXY2WklUOE-VZ@jfR5_?xtHYs*}+grQtgQSvpo=ZaE;RVBSxZM z*Oo9?viiDoB90D2HfOn!@3Hef7<(X%gle?t+b7>6s2!riWPdDN`F~e>oLLPat3R{+ zkXcLvW0rq+HYKxGvzv86Bc^2nKg4ane4IVl18BF!Bt9FCLnVd3Nh+kH?!Ez4{olJ- zd_G6!b7%4`k)!_QAhE==Ig~!J;#w5w&`05XaV?pn(3M|*tTjGfn%V|;Ozv>X6b10x zqpRMR{*NUQ#tT)8zkcVp|$e%tZ(XLBzrBfpm~ONyurI=;kFRV#lth zOfvg!K9#|e0kIssNg0&-$0~=6InzjZwyMXO64@N1`hA5^-VVk-IW76+^*_U&b}sJT z9Kh_;&h}JGc#YEh*8(FyV2Gt51#k12$Zj7W#AQSMip{1Q;_DEbxh8z5)0785T1o^a zY%ytZW+jAd^1)JCU-dg65C?fl7qdITKJLR=;EDXB^TgPL)qy;+1)8N`TTHebb(bCu z(=y>0w=8uprVSj+@hGnX?`@j6o@?4dA8G^$m#@ET5!St+iMJ-bY~x0!ENyI>^xcwC zi{FmPKWE&0o}zNBG3dmVy8ymLKfc7d_zM=f2cXvJdsTEPgRq}u0%;TLLy+~8hwLmD zKyc_Ff>wy@Hdo8*B$kl)YMFOc(KvCSDUZ)mOjHk`u-fSJ!Z$o;QRV7q4HWalXM z=DHh{0vxGtrdj$x8;I&SVM4zy%Qe=9v6U+_( z6w6B-wG{d>-dQLSSGAi1;5;4y0d#g|!iwIVyS{H(CVUI+^*d+@-84N`dO?!bj7`up(PHSR(Z4eCxi+$w90qPUaL}>MAc-4X~L@ zJu_he3a^9TaYm|H2SVu10yi7!}NLoA`S$*LZ#%%nuxf~7^3=UZhuctK=`KbZzb zt&{?XK5b5GvVo7Gq@gNsz}Ak@Gv~zrITGtk*@>L_q6{o|Z>l+zHwQ!}T$A+%@B)1p zEa||}EeN&52d}c3F%-0bNu`PQ`5|kQPheIDY_kG(tl(G%eH4i3xg;%P1F+&hDh0t| zcRd*yHW$A@v&@=bjWy^o->VC(5$r4 zY^WxpR_WB{*wr{m;&%vpw)1SgfY#E#WG;dQGG;J3nODdn0K8UlzV&%~==|POg2|=K zd7ID7SmI8wTn@udi$Ad)6%q3HUFhAv?Yg>O(?;i8&FVSwPAYbp)UCwOQEaIJ8o&2MtCS#{UWw& zi#z8}U0-2Dn40qXLoi}sZ^Fg^#!IINXV0bNKzg!YCrwN|pbJc+=KMxA!5}20ap&=^ zbm*4PTDY#5VN7YTC|j}FOf|k5tSI<_L~40Y;*oV}`f1Y3fl0^EP5On6Lc|2 zYTHUXyMmqCA4;FQWdsPV`Ipc_5)0bW1NfbqW>doZh0;WzW%(9w z^9HoTSphtHuwo6P@b95D&a`@mM!J5wF@o}51$gi(-Msjsc|5;pv9-zdEy)bRGLPG7 zH^PI#{xr1vkM(xIHG&x~%w3W7y)1OZ*d69rQUI6Vp50GvgH zx#8D{b{dgoy0!lNUCz=F(e$ssaj@nF6ljYcef?atK-Pd}~8DFY?49{=>x4h)vWorp?%#;(g@nC?YKj`DDd6R#CD;$_0S3UAThEi~tRmDk`E1K$4?D6a zegc;c{pZq!Bw5PJi*EXR>Yg+X*mn@n$cGA1hla`WKmBXd>9aV=iPMXcN&xc=7x?{e zJh2Tyv86zx6|5g&BS^H{65P+Q--2(PHyayp^ta8YVme+Y^>qHZ8(cN>pR49N(=L!9 zeH&pk+T1}h5d*}bvT%yPl}jIf&G!Hj*<_9_bPpE-b%j)u_i9h@F7SYK{&_$>C7zGn z26Tgt+SL;d5t;hrGPE_oc+`8Gkl?aj8HgA*S>?Fbpcbq>GUaH|M6fFz6u~U%gY_>P zlZ!?sU|bJp+c%CH5C?+SRnRToMFy$xs}j%D-Pw>j4tL?EPIl{yny z<=K4zOF{8>W1Ndk&4$qW#*`(owjEXeVhLxjl zjM*^9V42?V-5=3)d61wT`4MmXvtD36(h~$M{kbJAZq8e{8*P4nJ*c!N(|uqz|Hpx9 zcYlP`;`j9=6BmJetR|F8id8{TKM_j&eRKNiWK`sT(AV@I`a+AHm8`+i$<-QhyU7v* zKp$|w=?SS|X2ZIyBP1TrxH%7loWmSz`G5j7|3`roqrf(rVn;h}4#pxoS4$7c#6mia zla>}1b^3Y9BP?1Ak2lqD?t5GaWJgRCH@}rslrj$nWxi=M*k>k(ZKtcnr zdRgrP8XCb}OiIDt?{=Fu*<3!ip&bhaBTha6^kbX~gNRo?WyK*WV{$pvn0uP?PH6?ko~kV;&mhHy|auEw|gN5HDXcQl#-fouf% zcH05hNzQPI1|8cu#%VEhN%;tNw>XrvEEm$@^k`?DX=5jUL$I!3-qQivpp4 z9xe-&X}tM}@9W98BP;s90fX!DAA<{*@fy?xxaQ_n3pdF`1fWfH-f6n`oHaEhdQ83}6t;rw40Q6Rq`rAsD2)P{=ub?7-3hoAKCo!?u)IFU zuUr}Qap((vK?IcRjFo$;v3?rVF$$Ut!4{(Zz@;+EA2eAeMut5xDA;0A?Dk=L*hx`c&} zRo`J%LGVdo`Sq2QbIwy;Rk_`#H{OvSech=Zz~5B=+&9cdFKq@n-F5E1o$GJBtk=afKlpP<@vn1ZtrC*Lda<6KiOho1 zLz0uy#iOmkU|C`@0OJ>7uhmIwDtph4A~n=OFv|4%fWxr4mxg9;?G!l{i8IKn1=>aDU3(jW>-~-CZg#WggjX`}s$6`jriboD2TjePqycyX_0N(9dc8_@Yly0F-6tO)CI_6&I#>R9a%^UKZ z^N~~gRkmsc8hRnB6y-AH!N5uDX^>&zBa^W*BBw%p27M?lgsjtLV%hY8*7dk=YII*(enX#TDgv$ z@{Z-P7<<+uaynD01*iFYrY7bJj51`tDL$;CPLx}M3PS3QPC~ol!<)>f=icdesRX|A zAZ8mE7&dO6sc;|WQuh2Bu60P&yPA#WX!M#DGqMLpUq>u~cM#M*D0de%nL^^B&G7Wa z3oJCk*WbV8eInHTh#SE5YwU_gBbwT^!ZBDCFHu2P9nzxt%vA!qs{;rD1ek1Fu zX9wDOxp+@RG)cQ>bvd@mv&l!tt2n>j3p-ddF@9^>C?iR0?$pQLTvH!6>H@w`kvC1E zv+#BX)NCh#xoMn`GwWg|k_loIl@huXe(=sC!?~6IgM_&~JS4xvU zbCVG+#8kM8fqf+Zj4NiB;6b?~Lv0CHNOi%y?O2t)qCFwstMFc+RrQRI7^iSYY!L!= z93B4tweraF1~t_nc}%aZB#Y5E8g@n=M%v2nzN%61Hif%5DHj`{9Pa4)$Yg81w%ef^ z{<|L}+=JNyND3fBJlalm-vS*aU|*_lDd+I1#mW>=ivbF`5LSGa<{T`vkYadvb-DKd ztlMlg&Wp6_B>-wna5-@a_FJ5%QR!DjK@RfgH4^&nR(i6FOPMWz4B~`&3ro75u+sGe ze4UY1f7BIGgNy{pJ{}c0lU0#0FRCG#ibt8Kr^Q?Oh5$s z+N|D@eM^V)$-~z1aiAH6LE_!)I$MUu&PT_oq!n;WFSNlMldT-gl{T+w?!Dy0sTWi_ zBg_^jx|bEc*82F7{*tC8K(T$jys^1lkp`BJtIEaRsE7ws?)Pf0KRn3?om(4|!q%_d zeauXAPWAxnv`cTqoWGj=;5Wsdm4-W*4v+koG}J5&l^+!LWIx^RnFM{oN@Z#e#Kcud zS>xU{EqPE^3Ianv-4N>)Q;htg7C;j6R(UMysxjoFKmmJxo_i}Jl4A_l;O@a~qijoWkL-#NZOy<+x>s*rOY&$!RVIw zcTvBj1KyW9wFC=r06iK1u0Solzo6{T&5IcskQO8e8aR&3I^Q*mVkqr4kFHPOhV>FD((fTS&W+=GY3!_*j* zkSIyh?a$VZPo+K4Cn}dnBt9|d22<*rjc8wL3oiXCe4FHa0pzZVjC-uUs@mn;wxfR8 zt9V_m`9_enM7?FMjE=gwu+vBgPu*IlA~kgNix*2GG$5422DF`=b_E}Y?y5f^A+s1D zORC$KfcXD7d-HfG_xFGNbXw)eNkw6(V@pU26&gxKmdGyKgvw4?GnP3iR5Es=kbTLT zts$hyk`mdHrR+<{GFfNlcilrL&ig&ypYQMA9*=JKyzc9Dt4JU%n3rkejm0{ZSIGffvb-FpdCt%NCHuncxBXuq+I+Y%6puk>$RQ8^yQV+9sOL8 z`9zqka!HlE{W5tW_=5ueZjJY2)%{MU!D>^zRT=Gv(woad_0}t8Y~-s`-l`PjfB1-I zRFFMNjDmifa@W&CmvA&;Ff4mAyxK%-OXGMC3vVV=cd9};Eiznzr<>Fc<~4K0JS`1v zGQVI(QVQvTfmqG{t`txAi(LEs?x17$ zb=^$3_~oI?1z{n=wnwgN-4j*Vnivjjsx!ko*EJ$!j6;=@@tBMakJAMs2#_a{0GY5sS9*--)mv(p z+0h%cFwZ2vbH|fe2?~>u+{KvLvd|4%EBpbjTU=mN+uis&EfM>j zle5uo*892E^?)D%s>sI(x}Mwnu=;ZuKAIz!6&70tSR`F_ar=#2!>m+B6D*jGd zn9UD^30QNB_3lyT%nOpSJM@)P8qX-_wal(HPx~MqNRAL-c`O7BL5p>_A)p1ajoI&n zBepuJykv^a8`r3Nto$i}AuhJhG+;tInGQuB%9Zac=-2RCsZ(!61kWZ0+vvh!j zuSy8Baro4?oVt7|+2OLyoV8n>g5y7ufZ$7;lVUG5hob~ns@@iIE`4S^Sh{)NQ1Pxa zV=gqkZSSmdZ61WoD!yA&|7SE>D3D2mPw-Xw|Zwq}* zSsKhdpX0M`d=h_JnI8@fJ@%lA_LS#Nb3jp`OZ@AmeTFuJ?qB-Z>pK{_3_^0Tl_C8MFmNC-+9kri8^7ARA?}fAK~*; zbn^CN_mx5MF<|AvP6L5oXj>Xc?$Dx{fE!0(d!ZWgvRfffl5r=579i*Gcae|1BP+MB zto+`N&$ssyzPOI*Z?Frfgb-2kqXj6~baUP;lr@VDJnn%Qy$c;!yEr%1VU`pbx<~ly zoke$^nPLa~8&mN!j^DqOrOkwST~@d`Mi^+rXaVp4I>UV!+kqO0KPYtf5huFfBJL=t zkHh2Uw(cuEBYE5{QdN26sYq*}gs8#wvW?*b3g>xPK8@dn@oB!dA)?2?cI*o0y~a-f z8=r0`BB;Su7e4F7z47Oivl|usN~4;L^w)ByFgaDQK6B>Gw5ccyJ5&vl4*mye`3V2TY0Eyfb)~geaBDvKl-beYsQPtsr`nm;BUE?M^3be*7*WM zPKm=~-8^Sy5f2kLmEnX+OkM5)u_F>Jv~yFwc)X6D%Wd$aM-3sTqLz=-Zy_KwkX`BI zHPf`Wqp=>qew~D#JpnkLBkNShHV#0;KY~td@k1)6)IIylUw{B<3Awy)hL~^pDR7s0 zbw$nRwzgPV_H4qBXD?+!1aP6~4!=FGP#kAyrq>e2=Bv%cJ&#AAYou+Xo~E zycjv763+SK2BIXv|BBLW!9n6%AayXh$dyc}vZxL)nslkaTk^YK%LpYh<69R{9q%5dFmW`Xs~R5zh_dbG>^D1Y(Z z!czpcqL5CZd;c5>t0i4erJoJsfq3iZU%j+X{3ZLl+(RBe3c|pi$i08=osE0Y+?-WG zN3;91f9M7t7&wBbeyo#Rw}3Q+tP6({Ye()S;ub4$mN+42MI}CkS2!D;gcrx@ZZ2N0 zD1H6{AJP(VegBNz&|RHPx*oW*kLJ5^cqkZcNF>$uoBp`F5$Ayuc@*qQj@8G12xM0Ga4TpkI6#Ij2=^!Lv`Kf(IU|e>rcmKH7ftd`vXTSeOUA~*W9X$8GHaAvOF7Q}k z#bXWNx~BvDe6YS|jh=$^@cBZ9=Zk4fNHVztNhU?X_;+yEHnjL3I`t|;kNXrBKH-sD zw>Rt;mn`U=D`>Y>=#Tv-M-5R-$9lbl-Kzt{ruyIcL`6O*DUi;DI->I|Wu7<^hvV6N zRn^vBwLwMEGua`Fr;6SG?-wwk*ytAUME(tr=UET-b-YQ}=4JEx1m+%hK|PxGQ91-K z9cv`nW#l0glb6?|4;`WGmKvcwT*gy|WzBT?qhf;x2~Mhj37x+e9$xt|F^Ow9K~|}Y z*dmf5--6{_%l@~Ci3>Ox7qk`?_5HdAT&+yK(}I*_UZ5nM*?IJw^u9TC7{=XsVf#_0 z-H|x*+}N$n9M_@Bx+lX6`7<4pX*-TW8cWN0U$dy^$BZ3GFPQXVm8%NSvfZh|KYk&D zFJ#1LQHk)pP|sA);Eepi%cYmgJWS8tXhc?DJO-5|=dSRU*T;4AQu?~;PEIL$uY2%U z^j9{U7hmUpj6T}6vj#^2t(KT%L0)cXya^p^W#Zl+)WubH>pds`oXy;)+VG=C zlVX`)d8At!;BXEI$=l&{p%Cm=6=8JVELZ3n2$UVFvO*a}FuI_GAA(-aW}Bk1{#~Eimgv1`mH=>)u)G%hwCb7cT~U+(r_;klHX}HXrX0)%TiK$5DFN zpG(X3xT8?3IG*|^-o~8q2DsB%yxz0R^nSVTGcUa@K-iBSML$xaJ~^er*T}U&yl&Ev z7S+{0hhFPJc@2O}G%YIr`Lo+=G~#{}QK5suVjRZDBHXt7;61Y>1M;_a!cmJ0Pk*$9 z_B)5(p)tWx-jB*_`*0QXOrq(2|21J^tov1r%%42M4@lJEA-~c@4Hqkgsgnw?XiSm$ zg7G?$5lCx{0EbGYsVoBttv?JNE~+5B5H8Jare_ONlBCEHnxlC_qf>&k$X|h-Td?)O zgVoPr&%jQT0AV~nbHTCb2kO2|d>D3~+SbgF)4*PU)s3h*TJ)@U8UjF%ihy=YK*HO> zrO^nqo}iv7%FjPmaC5@wIF9Uk+@|wnOIzD8v<|zG0e~2qfVfWwPH#E-WAM4=#$)0_ zWw;s?(4>?Keg9p+N@z@DNWVi~7U|1DDaf@-L~a*oD!8j#r-aN7r4Fg}i)3l3C!`nBzeEkz)dY0h#c0uD@%qs*L-` zK>`%{K5au`w%qlGqPH|;_9G)$)ab9|&q8Z2sj*i2U2FQ1* zpaIEl58Fl{B$(mudJV)k8$ZH|$o)#%P6?o*<;QIMOq1m4VodsKLdKw%WyP3t#h3(g zlX;ilay6cOO8s-wf_l#n9lo+vBlT7_^2a8KFDA$lkW+~QD>#UCK8Yezk$4uWFwOJh zNPmDGPTovw<{o3;YyCxD<2H6AU}VvC)B^MNj&?_(gI%1AukE8_R_2uOjk=X|qIE#@ zv@Jm$4gKE>e}qZHxDq~C;M0MYx>}eD3@~ErtlG1sSZ`e@CQY>DnP=D#n^i1m(eFwR zUHGW8ZcGuJ(E3XHJ~{)Bbr)8&uvKnqO;MKZ729e)ry4RR*xKguwud zY93GdEr`PAwRaJ_ia$;x+LLnFW}B|@_eFNn0Bao0;RI#SlmaPoq2@bcdZ)O#?;1CU z?K!h$#p&+}K%9S3zWyj8A9yh(nDyk%tOZaZ9U;#}Q^f2x*W>2Ga5q>mt~Yoe%CllD ztEal02Oys*?sP_@5$;T>uRLdEx)RKOMAle~4-^=;=i-_VP_>A~e>~T8c2T zN#cS#Aj#`Ftw$Vupq=F~))u@6)ukzyifsaEm41p zBOKwaN~0_#-#yE-6Eyc@dSlyc8UEUb$;vZ)y=exDSYAn~g2g&s0Qqa|$E4~Dis#;M zf?-VEa|~>pU2TCfW{34?g~j0Jz6nxNI{4)@Y3!KmH;tJJ z3yhyeS6L=6UN(89Ib9|Bt;Xx0ki$(N6z2#gpxTU8^(Q1?hjb+}WtN<{r+g*kaYV34 ze&g0YpT~&~P&zCA9U|PSQ;f}XAq4Jn*@RCd4|$ zofBn9ij)*Pf=~*%MoJS&<2Wfbr!F_A?geFCM353SG)MM*H%8y`B0_^Q!|3p~*pCm- zs89S+iD^kClr-teroWy47gf)VK#l{)eoAG|-{M_fn^4|@LP${ABPX)`+-gbQl<%BJ zByylNex6;|+;j5k=X@(iDg-cF4W25n7PG z<)}7So^=`xBRdb!b;c)NcoaHI{-_BaLQ@vY`_AASvU-7lBGL-`Rch;=bdnd}buIeB zGCAqvk37u08+mc=o-t59jwCx=q8P7U#Q4U#q~pwYXB(Z%mDkOgR3x9~CJ$jp-}Dn( zO4Qeb$H>NB88|xBrdiPlkCftx@(9j+55qK|>`-UDo(}T2*vg?d5YFz`Pfb7X%eJtR z^9?Tm3EDHoq`7YK+sPI zqm8y3cz@xK;QJ|cuKh>vtS8{A8NnYvrAWjp*hBfy~@ z#KC^!taqhwFkEg>v|UZln>6GFVhXS#wQ@K%CQKYq0)!ZFJl~ImC!3d0_=cFin799m# z`GGW3xR^7?u3X*xLz&#G+>XrrO)?6a5Kyqro-HNXS-Uoug_*yMJ;SeA*InTQ)EP#@ zu|5aydun;607|WYKyUaTf`L1ozo?$d7H-R}w2Zzz_#Pc8Y%`v5?mR@@qVpZ`*6AZ*Qw z&-Dg%C5n*)6b@<|e{EWik)bhOo1)KiZ?LWJS2kML0 z-i)&2CpsYKkON9nnS(I!Rt;jYx-WAl;s5dnW9(ZuSsSL32zR^?K({?HM6{y1Xc;eV4sHzeXLt*tE}T6@{U0aT?F4``$cXJZIEVVUK7iW)tX6^P7GOmRe>{|KDs&hbq@IO5 z@x_U&8c0oH*B=4otxyF2lYZY`JBtLOlQ)pP+Q-VTERZsypeo|_QY2_c|H5**`icl_$=eUMt(WC%k2c{+dio_GvMm1S9?P_dQHCfY?1L&;sCn-^) z?u$2_;2zd4ELAS4F(#9-7a+w?HR}yDJxhX80%}7)+9}tn%JE**yGO_QHYpL4LqnOV zsE5e!)bHBVVE6fLIt9|b_>y)?N}s>A=bxs5R}`q;b8ots zmwcn=%~e!N!t$SKoT{DOg%m#1FQEKwQ$q@Cp}9+<$w_$ZWt!!cETnx#Yy?DQX0;LN zU=buD67hG-Xguwep1@v6U+P5!nGcIyAG}+%7=r-NDuLD#f?k|TUP2UEJ4@pvEe{)G z-)PPi23=k|L+S#Dd>*mNg2z)er19ZlW6;+giCwPajiI`a8^}N+87%U1_$CVxr)8BS zrdve$>DP#4|7u1gn1DFAbz`#1z0(@mJV_|#h0Y}#)fo&JG4I=?+r@t3eR}JkQhoVt zQ26TTyPsP7q`WukdQM2OEJ1G@b?QJQxucz6*8y48j@M7yStT6PEUc^?V9M=l5Od<^ z-@5etTGGf3QnEIzs41n1{?8^sN(z5|fIv$}>dL+ivC$4P&sxuZXjhEFjNogikZ$N4 zMbx7CIdD=EkVwR(uvDL>ghWA$2hlnDkBB1)D!ZTf48`r|;=2{~+u$ zBe7HfE%AfHHmp;EA4p`N7BD?)1(ywy$|{|f_};-<^NVZREk6FT!ZB9?D$H={n*&q& zJt)i?RqGxdZ9zckEW9maQ%{#Wa_Ldx!?$Q%n7D-KT25L6y=OIZlAZ ze}H^LcWk01*F4jT*r>ut^Op}NS9rnfeswQXk~gpUsLNb4GRGKyL?5@kDZyZ=<~D0G z_&l5tXFxN`Hr9Xm@aN|b>C;Bf5d1LR3dDS6JO`G$Tz+f8H6h_qrI?C~!Z>q>3l|a$ z#D_iC_`S~+m;hT~@@fV0`EZJN6huiAC8=75{0uj&rbsNd@oh8=7}7*9)Oe&XuJL++ z`)Pe+O~p4Z57~YJv^j&YL(XPP(qr=rPvLjR7%ZW56XmMwQqL9JH`3Dz#s1>v+1YQG zTiO3~T@{B@lE!<+p?|0_776>KK+Tf;7`wFR8^L?EOw*nAmoc@r##?>+G2A48%{{p^ z68X7Ji9|~@QPCh5Oi~Vg#8wV4@52d6%weeSDM`Y#ohUMPyBJEHG5uU0qgtYF-DqYm z?;YK^c5f>nEewIyJ=MNHBH1U+m~tM4q~yLG)QTl^^M8J&f+)XZqcUJUkY-6|g zsR^UWSWO=Xp*zBP<+P$lE2Q=S}%d?4qQZE;2EL9v^&$;)nBmQl%J^EQ;POo%Lc znp@xYNleT>Y_9m7?+KwaO{!UC)Tibd^s_luK>ay`E@I!*>OxB_K8m&ABp|+tAJlv- z%=(#X!gLI2#UUN=uGO>An^#^M?)WG+uR6%a2ii}*5$ej4U{w((exL?UqT*8EYywzz z9?ig+yY170CpZ1P~Iq$03BGA~9C%vluh!)O}D5f|d&;`xhYDm%<@h)FQ(%m6*4=ZOE+m=^0Z@D$OpFDeBp+N4Z~h4+@s3 z_vD=VDIA0t{N6!li{>_@rRZuqH2$<1n_65lupX*BTFZX7pTxniFq@$ZcufZD8wtc(Gsfh#~TE???@O&u+}pz^MWHyf;xd8IY(;6~3B=j}h-9zn3Q5Q#N5 zPX~5ToKO(L-^!8BaUQx1G`NE5 z(194NAHLPEkU;B9pA059Z#sm)(O#|$8K)aR&ScL3hBtGpko}B(KE`&yhZ=0jG}2M;2auOKL(CU?i`m8>>#{#Ak;vrwaFl z5~Z$X55f+T53qr2yTZgu>D&g$l$g=`#Zw)0uOs*F)~dr#9ROLB_EH9RHVK{^FQ@Ec zw^ui+`nCV|22&Z|D|0ySx27;#TAurK{XVmsV=~vpoMf(m!(m_LaH_CTky(F1)bf1{ zTrS&xeS#5Jp;JE+*lC5si}qEX-FC-4668HA!sI2_pIs3O>7GU1_Vz0T$$CT#Z1#(K z!T6W2rs~J?8r0H>FSPyL_&3wCZf=xqWqdn>At6VVADKyRT6Jse(Z>DMUXn6im&3Oz zQ4r?hS*`MK)PwiE_6QkB;DGo;!mWv>^~` zZOCi*2)t8iqKfkFngR`96!_PA?%%E{Y_AbhShp%rFkqR}KMj>&NrT$YMZYJ^)!*IG zD6fnbW*3ex3sa@(F<>S;FHK#h^`RmWF0afC;?Mo`w~ zMVJvyBWMU1_sE%?GJ=@XvT|$fupEFhTo?%oy31g7 z-bc8CrYBB3bMVlkA{D(FhkQtih$|Lm-4q+*2huNDAR~eAa(taQA&B9sPoPH!E06m? z9q#tO?)Ns3*EB@fb|Ucd!s3t{WJa&N1%b!VrEZRng01E+++OGwIoR}1=)mf6i6%9B zv^xJt7)2|T!&+g(h$Z;p5tCKNd7%!bFi2?Z$P}(RX+V#LrL=cCrSS;oiL3>pIk$zD zsfxf7potHFwj@@4bzdxuj1c5DEdQsD1pM|EQxwlVm?~;Eo$x2EBJ{5K0m6G`*z|B* zu|nx5$4azp&+dwp8Z3tXC9s}o==(jk9n92MrBaEcqyB$9Qiu59Vc`KJN$ot6lnUwp zWXnN*!b8_|SmphHe7gvu9%;4~;WqnR`J6x>b`BKfVO)2~BCN5uItWe=c3g94%(zcC zs#H_W#bLF%q?y2c6w3Dp?m}bDUynlO3nUAndDcyKBqQ1{m<)To)Z?>Wb$o5a_K6yA zr1wBhg}%w8nYHzMoq~8)Ha2)U;M1b{a!o2@|Lx^6OqvqWW4h~+2|F3lSPlkD1{MLK z6fClB`2YHTbho2S_|jlsbh2yQJ?kK(q*U80h`(R_=tcsthtV=Tb=U}|8s5>BhIi+5 zT@06OM<1gyJN?+?7jyW2&Z0@UXzpipdn0qbk6t;Z<~<=Au}_4<$ZekEM-Zqbe>bNqn zq2x5f;`~F`;x&%0N<1(lr>TC30o-fEiiKcFUPUZ(#;33EzfqJlp(=i>0I6~X)mRM7 z9PB^+Z4N8~v|`r>hhXe!9oR@OUKL%Ap`A)*fe>bSzrRvMRP<`Pma4C>Z+#r`7VQmf zdz4(kpThRyf58PdSZRTDkD?e^gq^yI>?{G3W;^(Y({yXLsk$L@>je1eiiYWE@1_rm z_lg7F_MI)-&lLjU$kkQnIqW zjKC_p(WtYD4o3*~iovPoIM|3B36GaL=>WXK|BG$|aYI%o-=cOPK<1X3mD!zP(^T1g zE5vj%T3F6<1<4hvpDM{Ctg-kF^c@M0@l{}hA**aKZGc?B!sDg;G0gJ)$*8jp@AN^o ziXE*Z1-&d9-bL;4F$SkR|xf@M^?bu6vcg_Brv2b(4ctUFEle6^=`}sgL|((-4`?V3g_19Hm<-( zpjX0uh;(WrjXkB{PTO-^NdoJ^!seM%;^!CMu67w`izKvr|Jj+>)B^-r5N z)27a7NaX4ox{DAJoO};A?H9ooa;kf#+npA^r}+=ZdL;p``8f=#|KMx`m-Fp(dbVMg zMrPX1%B-=zwe{hy#q&haLz&tQe()D1*3xU+5wD(kb|zJr(SZf$pe@*5_`R0zXiO-M zHMV(%Oe7CB4X;5Q1CMWSf4pna6xvilZ&)xOy7&+62ldL#rb!r|ZaQZoi4cC5IKBDM zs-1q0UQ;Gh+hvW<_Y|L@Uv$k=N|os*k{BAT^ssPap1il-Ccz3Y5rdvbIZ3{N>W&?wMLJdTpLecEj4oRWE}r7_nD01dV%IO zzj$-$kJOvuIrc36v^3`dh| zi(<8&GSZGR@t0&9&h;vb_3Z@E=;BJ&zU8+C$7ABDuF7O?rav3fOJ9wd?vwpoiE*wj z{vTGGc4o}uq09EUgZhQfVKo-ipnWp$E%QMl7=xU_xuJ8nKc6{()_Gb?{yy%5J;}yc zfMu6z81Xo|Np|hqR)hxz_A8#Jm@FgR=ZEU!hALXhm)TR1TM<6p%aBjLXj?W5sjfG2 z*$9Syd1o^(u62Wp@Ce`TpXWV<_zBNlfAK6*4}upx?i)V(p3?9|J2`|dpG-7#y5VO6 zH?AOa_t#_N;(r!PlK}ZjqjlJC-c7D25=UQh1G%1a0}R64>M ze}GaPK&*8^h#{BCeX3@=eJ(!RjK2w>{5RWb<~QclveZ6v;LH&ZibD2oGEd`XqzVZ* za*<8ZQF4oNhm$f}FSrrX*sILW{`aM`H(Gisx!U)Tbe;`&n9(y~ax^Ot)BjgL#6##i zm3H;^HUfRD_1_jCb}e*Et6^3ocsM{Fd(!GE$>UN#{WS!x6e*_+0N_=`VFVgS<6Kg85-1L9tZsEQ5<50pD-@*y=@^C&s->m zEhFS=C|rz3#l3Ra)aGy zM9jXxd@2fbp8$j06<%eCu;=xan*2k{j-23bB2adSS`^o(PWzpDNaay#DU+8f;uS z!c3Q&jBXcm%#Mfs!vYSGZifsSP^Jhic`9-9lkI9+72vGroJH3-zmBkYHNirsaSrr- zpA{VCK(cq(@FSP3g~Lz-k414nYCk8gcMC|F!zO22t}zbbzoJ>I7|!r?oxAY}h$*)} zT*>r~yx}qQK%^6N@>72d&3_EFMDllAh75DsKUUe~JI_$E(6j~I<6orl$fJ0vEL3-N zK)zf^sflyC&7=If!dR3x1MQ{&@~|!y-KrM2!oc>pEOU*78AU8Y%1xhtpm>Loq^4D8 z511bk9g9qWH~0XsAOfiJRcxhe*}o~??U^xw__n~n5A@q9=p+BgWk8sH1zXh3fq6W~ zTg_q0Dx)54IG&DZCfL;J?C?c+v}i%`KVEVT_)S4cs*&NQ5YRtQbaAbERY5G|VF8zP z7cW26l(pc8D{Lp_d<6?EVh)s@1uhh5OFPqUXGFd4^?8gP+$^Jmz?rtNFV0l{Lv|0| zjP5pv*a3wWW~o+lGqZa#jrfUlHl)`X7Z)bORkPMPfXg+SkOQrPJed#QyEs?9@*h|* zvCfiw)2t=Pql-1x5R5>4#H-%AzHQQ`e~r$D_#@#97cN|i2?*7*+dxMtMq~-K?e{MM zCjuSOAr9@;jOA+D6n=lv=)iAU&{=p&t>p*+q5fGW3s_nvaNbqGoWH9 ze|AR)(eo6Ebw7CwdkJyC$8l$1GWdUZs72Ex{$fIRsqm`H-jK#O#2Un8>B}y5gjGe# zaa^Jo+a(3sC;AiLMVw}j+$(Np7g;=+Kfm6~&X`S;UP`MQWa5bsfnb)R!u z5L61%h?Cig$cNBqDGa5RREeImJwBPxo7uKycKqH-R}z#vTubbqE$dj2f4)%aZR$7Omfl8x0+~?)h?srV$d7VV%6Bh}>@=#UxjkTk!}PCy;D} z@5}V^36<=mRo3~<**N{2c5h7EX=-C59_)=5srs8=RClJeOfOzRj zL$^XUtx?oNVZJJ-eRF`i0r=r}oYd-veh3|w%2azGZGlIa& zx_xs;m@2I%-C@kLfViAM$3JW{FQ{59cD-BWSqnMD96B))xyT%5`=`CbVz$!{7pl1+ zr))0mI{s<2-31ub7z%|GXtj=vOUe;)$nN*IaK}@0dMMDCT^4ykvI&1;Rf-q6Foq|I zw|~7x-E1?`tor-7g?4HjT&@d0KR1fvuL-z{_tgP_d-c{q4s7ky{jre?5^asb;~#OH)>M57$D@ z%~7S9Jhn;@=|N_eGLL@)j$YaZF&98T#ycw5TVx<7I)PgqXYOLTUre^p3yCF^aD5;- zTTVA1_={_u^QPrDphHe;=Mi3&lki%-VF(3?q`NYW+bA=uqKrqPtkTh7wO$fYI<-|| zE_NXY$)Xp?{E$UMl|z8ZuuNPUMFpAj{TF$a!K<%={17pYAmOLIKM96(8=y z^z`WG;}+>lO1C?C8OXUy2{kgsW`*hBR-~!}Nej@`Fr45C{y98in^H7;VpL zrGLl$($zu|n)6F@WI7=+&l2s1Zsk%#JH*f!*heJWa`~oi>e#PwjT;WzUPzBe-PMT- z9HelpdfSWBy%HA;+%;=B^%}bC+Wqn&$4vQ*5pyqon>)Clnbv@33Uo~)1GS$PanG0D zUg>H9fifw(3+MYGuxKt+I%3iJ$yJ1A+_^qceQ5utH6GV1{Q_L6LVLKsnsll!RiyPO zGin+4xOcF6MmE$4S}Y0?i=SSM{9W{Y>>j`~$BoC6fCYijb$p$Y|gkO*sI;@fLUcMESy7L|E2WU zDlfK=c>a15;vDl%E070Ox0y{3uqf9;G2B&hHTaPj&P?Pl67Ba*;7W4k9@VSj|EuX0 zPJh*xk{%uc;7fDi6OHP^AQ@bu@Fy6CBa%bbSZnOs4^e{BB7yXV2TKTO2a5jnJ zZ-=cF-~E2M^L8y3^hj>_ZP(}6?L+@w^h0_tS1VQJDUm-|Ph7v87|5ZZmQ9sO;?Ic+jm90u>num}!4vW$^6bm$Vi|PY;9OlA~IZ z(gjzg><~>{;yeBBk{dnuPK``=y$DZ#e|UYh0r4^>}Nb{r&R^EuSYbi1zD}z!lPh#Ewv9S9G56NM&v^ z`!O(BZ#bMCwm2PnyS!tr=U-tCl1EnM0jkRA zXYR8je`^A<%e9V_O=dGDi{5NV(Egw@RB|Sk_G88798Yn7Kj5^v9EVzEJplFmz^RDD zDwUAeU+OLhzlZ7>ox$11oROk5%kn$zn<-wE;w>k!54dW8lhljCx~e2^JmYsqhl=}L zpW8cjx9LtE*7E?R==W-a*0ocmaUG_dK9L^-+Y8<{7_ zdI(S?x`gRom~ZrvN{#EvVgx6D+-A>+rgi%cUqzZL%l!&gRZhi1g#FhKe+{LuuYM|( zsD7OPTc2KZ_D=0Z71Wd@RqzK$3y#UYXxd8q(;qv3vkBN|pXdC=vUzL^?&K;**VN24 za<)Wb?+-*^UPD5Aal+wb>$4L87|gw{20}u#Q`JViH16K`{`Ser)rV?DZFkIPv;<1s zZ(Preb45LJ;<(PzNrKvP7}jHeFXeCArmx%E#y|HeUAjeSqHfd)r;Ptl6OW zo-pP2h=VV-^Uy7I!-)J&iyZ@=CJ1SQ`X^~X?190?RtiCU4VV=R@ zg#k-&PeRnzL{O@IlJl2FBr?NbLdT5%{cwYi)SP`<=d%{Kf&2-`n2>#Unai}3+(wp9 zga8Qxp3(Ly)U%zGfmN3iSPu}T!>$n>V&QrtCPDJfh6xY^KxWpyGc9MizSAnp4r7Lu zV?L@NoHKiRC=XWsa$926Od%yQL!(Xt1j4(O_o1jw6^jU%y&c?hvf8T4?hvadZ8yTS ziSYOJlIsF9_)Du^HaLzClN>VsW*_lRMKs?2flUYWHRCy)o#aG*rv>uonBrldvz|Lh zgq`bWq|#M62)~AM$wh_KPN!3f9u?6>_U((^i%UAEGlrjkm~Plc+i`05Drw6}pg9*> zE8AWRt-9~>^=kVY1EtLOzU)>$EFPNC)%U){OcCap8P3)szte;@PVt+H4ERBjD~gP0T*Lij*OZ?Zo;mf6%OOS^ltnEyR!?@9%i0#`C8nCi0}+ zXfwK{CuI-3G<5ppkEGno2>N?6p0ubSpifuESg?4R{)Tt5`pR5eya7SA{}}(?F1@(T zWFl!NYTPyJ7=j%WwRRTyi{?sIKRq+6HLNlvOTf14ivE-8c|TXF5hn-h>b#xX4JVS+ zQKdL*7+{GHgl1b;yy>XFn?*Z!yLtY3$WBYS1krY*WobyH{H#t&x|qzHSW`7i{fUU{}M&){el7Up;;LR**Vr_=#e4L>D zB^0kDoqwI)9?6rE>#4h9Ce5v-9B~E|Dxz)eEk8ND)W11X4t3y^tjSrfSF{j{FrA8( zkj4El!G-4K^lC-C68b5A1!22;M9w9d2YzG*UMndRX#@)^8tn4jLc5;yxHq=f4am?O z5oLCX3+@R#?NlT*Nb?~TPpbF6MkejWl(Ut>(GQ_uFL9~dP+Hmy+Fmch~njW_Z3i-KQ~h*20s_r@HWbC&2QLk zPA5oKPcX=c!`o+p2ivj%4J`s8`qu^%i*Nmb5%r*-xFhYwBzMe@&& z^wrGD>K#aILmM1f?W~%9)o{G2;qccbNwu#|VW2?1mMxVY)z~6t^pbNV>|1bN9tfDc ze)SKN6)Ed{a#Nl~ORH1rCS9}VJFE_8OW8bgZy?((21e#0?XfGne;quh7rsOmbS~sX>$K+++r*=G=Lmw2^NlD1 zNT%*uZ;eVd;x&b#w2Oc$~TQ#|obl2k3s zDE1;)YFhK5sHdt!gZO*Tc4&=D@ILz`f+ATpb2&RE6f}agryJ!f$DD>_JH7#;^$?=Cdo^mu$R6wLUr+u~g);7QIW)AOB0qNG5g=}j>(vBM zQ(9KY5^VuKd6ePOTBm?YllPB2O38z-R*3C59PrDW^Uhf(stg8?#$QBWw}M#nl%6st zWL+Uq^0HaN zyh~Zgf$F~P>*ArL>HDw;Iuf)PGQfRzkDF@TmM+K+V?A{Fl*qGVzkEjNd{s&d)Od=E z3B9J+I0@dGlzX-v;X1#7cckHldM8YQ zb;o^ip+{7k@WunSaTk3)NRySNcN89HRY9+H%8?o7e@WPQjy=?VsOR!H7JZI zVXJU3>hW~DEj66zQ1Kjq2AXNV8m1pQOG<3Y#FUl~^b6!eb0En;Jj3N$ghU)hA+7WA zqG9)}?SGKa{Ays73E~ETKgPT%$N zf~dqDAWY8`t()8m9mgo_&_hX^dkg*V;-E~dibMrvnEj}{y#wg9B@&mi~qOi5B;Nog(u2l5pJSx`8tC~-W8 zL_e%@aKXgPwT`>MYNpIo{pywLZmrvRD%)&~Vtm#RO7q z(96U%{V+XCldurfr)MRu5fhn{R(dew-u>w?*Wz`TGOM1^CbWE%_dsp}U5xRkdHpfK zoC668Df$sINM6e`3<&P5cpS0cX)FJxU#S;MVq9EqeDA{3HW)ZEqhsusHQ-pqO!P%! zPp);dP`Up0_U5s{?8Qy>D%*dhhsuc$<8pf!Qgwb>!kq>P5kC`lP~>!2*v4^BCIr9M zk;XAc7%5%&29ic)aVwHo&Lrg78Qx7NiHBGaV*qAfkV{77IHPtK3Bs=GnsJhKD=IQ# ze^Y@?S2;@I*C9kdX^qRhj}|Hfok;jtAAlbhkOZN6IE9SY8ng>3B!^;Svc2!uezg{e zk3;MS&i;BP=jN~bgewvT8pl)&X%W}!Trr9wnEAP5-<}AK**wi}*X5^z1 zkAI%3_(Gv@7u$YWvpMQ#+9J*Y>X9%t>-6x2X=(PTyQ20q7|(xnj36Lv-nL8ZTyl2y z;gRD0&^s90#*NFjE9m`;vA6Y6=YKske@t@lV4(?uJ3-L=f~;zSv{a&~*S0)Ht+rkl zp$hA0Oi_z7iDv=5?N(RNUUfg*(hxWv-v06N2ptj^Z^!m5DJ82EQk6RNISe$D3ldj-9<&T0md)8b-c(dEw*lq|w-7{X8NfJ}{@*!`Qs}!X+QhW=P zuUq7Q^OdoGKugb>dduw1{^~M23o1R;xEaVx$6DT`FfaXyOU)#sgWEXge?9rZQo;{A zRCoW^V;#-T;8O=->K(dCs|U$Qr04_#XCwridM5)$ixviNj;&h>2fG7yQ& zcfgcvjxPLgAxR+3!8%|oW%)llO7Z^pnG{k1RlWpdFO?BJK_CT? zA7em%&4H$8q*{uh&I~8$Zf(nq|nvwz|qq6$+Euz@I2m zn8i0<`rVqY@FU1ug2AU5f4MscEQpI5pX0XQuq@)-fdp1w(5TBo0Gb<@SlFOBQQo!g z%HC=gy63jzQ4ce($nNR2H^{@LCBAQ9@rxXO>L+)i8 z+ES}Z4SXLQP9AndKrYyU+j%f9Uh~bxt~}X|=@pkq*r2!1(SP~G!$i^+8Zu#urSwe& z8aV*uQ?)~-OH&=!p!g5e$!_=WFB{?Dr9Rtzxh^uiVNJ_qKXUQDaD~BT19|+;6qA<~ zM@n}xqb*DJW-c&Ytj-$`oIhNk1hmq}K}dZte8?LKjIbXAF#&-gBE=5tjo)d>$-sv4 zgwwV?`zynYgbxYxtkXi{w-|hD5yi2z+|hm0;A^S5C=tjZv97A9vU zHy-E~T5E}PpIGzdxsP1T5Vl39lSvCEZXBNSjxQ|sT+gl*h8569!skcaQ*MRglFl5% zC^GVz)$enX26~ZrYxf%l|LeJeM=qua+ZM*?-7IY7dVWRL74&-QbDnN~yQr!?oi*o? zHKxU6%5PcnkONj!dt#hIxxI9IbdR6qg0H!YrX8AHd7@KNwOudaacnDmzSK>6KP@F0 z?vTachnVmZx#6Vt8kT>aZ9FozeyqDJ2uUF$5{u$0@qTLtqk({1<_odww6a;k!%z-; zgzKJeShn?q&JlMD3yXenhl)*aP#bk%(4DwBD0k?l)f*}S8Z>spE3MYLM)$5f2`ve> zWjU83e^8`u*-jcQI>O@ixBy75l}}E?@(IG*ggqn|hsU5r1(+?7HncT#P4YV!;j2SQ z9$KPBU0C-JS{~#<*`s*mA|vLCcM%dpa|G0FcZNN7BdLxx1Z)jPgqq9~{e{OJ8+i0hVfF?6tEtQsLi7 z+bB|Dll1IgEewGY{PWRQWfNMuYn*nnEL)0dx&tQjoYuFBFA2TpGr&y4?7594TU`&M zAI57`wxzr1_l)+yx)x!*0fg*ROG(DJaRI@SI}K2doUnvN73wV#*|TNH=i8IFcr1UC zfn0UH5Wz|P%JNk@aA}68Hqco>b|3G%5m#g=Bqsi}flY9B>09LBzXnMHcdWz#M+efL6HlP}XI7_G1|8pP!X@jL<9(J3No){xisese1e6pJtje;!ZFO z4Q6lJZ&$?p^Wnyo_~lrFc9(cX6_X87q8=@R;Jk{%tj1A5%<8HBEkYRi%CQGN9(kpAy^%}SioM5B&M+k#r?J_lmbod*7SuVT~|6ou;%H(wRQx8 zG@`&fefiZB<1Y$RFwb3_dEu82e{AX2)B0mFd(Ph$ww=DuUZFa;|DaUs zDxCw8n&A1@n@yd=n+Je2)9pL1pr2ViWM~_)8(US;fDjOVwk~={0-EfM{k4H?ymut8 zhQ4F@c$>}#&sQmgG)kx%Pz{ijE?q$S{6h%C`HJfof5cxC!~HOj{{2YG{fbSx?$sT; zytkpYI_n<{b(bsJ7H(pz9@-xNMAnaEY)AC$*~GwpwUWT!6klnJWu&_Zs{S{Hh>fu7Nb9N$=-(iP`r&qhiSxYH9>) zEZi%=I$&f|$UbT68R>&`I|7xo1QVn;>qAuIYI)8ST``XDSB$w#kFK4BXmo!Fvam4v z3{H?ih3y2>f-4=+wi3U*gfIFpZ+->#hhz&vOyPXF6ybe@9^X@d zh2C=?c-nqh;DTW&BbX_K9?O#U6SET#kR3kyOu_Ag9Z9M;VYW2LjD-$m%ei*nOdTTmnOluT&MJ)9c)SQ1V@EKPT+z|4_`EII@!U^> zi>!{p&U8j;A3{bASLGNcmx77T7Dr}A$8TH}VFIT5B^R0YpMDs18Fr^r^6@&G^i|3A z`m8tSVzf+V&i&3acd}PqdCs*rC)M%qzOY%r(xkYL^i~~}<#5;geYz+ul4uDeQZ?Vm zu$tZb3>8{)rR0z7AILrt=pv^(ELLC^ z&-E{m>&V~g+Br$}oLAr7)@j5o`cdjh)zORh7N(>qb~70ATU_;`wKF5ag&jUiz9+F)tW&yE zDDP5Co>QFXj%Lpn<={A6ICPc(IAwyN4j7+hPa?d0Xno^*`KW|837z8HmjlOfbWz-Y zPY#?bmVdQJh|Y^Uc|zefSGvv}Bc`o$Adj?zM4F81%?Svcc^Dtl9KvR#AubDJLcx!> zFIkrK{-AV4l5)zgkJu=Y3i=1@}Wd%FSq&q2z-(Rq>GpA{wxNqOjbQPxhy_bp6A1Z8Fylkg$(e8 zkA&yuaorxi$jrCuvrp`H?SC2WDlh+di76w23yr-W7rNn$`<(18v!(+(r*PgJh6xGl zB41Q~kk!>#57tF>CaTF48&rJ+OwKM5gjjFEdhJpT+WempY8!gxLM`=LDa4R5`R-v7 z1O3_HC7fPM-j(_Cl8Ui`Am{KODFK8B2*{9+fPpRje_0Zxw-wR7NWJ=_&2+;i+K0Eq zCtU%B-p|9gZ=@_RqHajJUN@&MYFvRujTlq)o2^vj*yUHx#{QjOWnZS>@pIO-WF`EG z6xnzB2;UnAs#t_|J5(&IJkN(sy1>qlCku4^Y~OkaK@>z*B_IU&QvV$iVZ*5e?M)}8 z_`tu6!v4iXn?6jbm;T4$;dMwV2@ewd*CTvX6sQ?u)|{$fx|IY1`@0}q>mzdqmhiw* zeN-6#l|mbpG4mn~-HK!$YP!_w%J1pjr60K4+V@fEKGyBqmR?>44S_3oTifN4)@);I z;NBdI4^pxX;=OR+Jpyu4Dy+_1HqgjM4t z#4WJZ!2ibA@0uU>z zbw4GUKPvg9MCv9YwAB68Z0vhLLjgMVXG(YC+ozmL2DW3hk)Zk!PBf4wFVxF&zB?Iu zO}qcnepGH*=(pXJ(JpfOM%~LuZhXMx)g8JFAafgKizhgMN_G(xw=Swk5Cs3^!50zz1+wMrEQ6%pA*1OyC- z?3tSV*j76@_y-^VIXUln_Vazl%Z9t>LTTJ1aQ|{-)DA~e zbuIrVwONO?-u|e3avZj$hUdI+g5L$@2(KRZ`WC&KwGdXAp7rr!)W?j)2d=M{E7%ya zW5 z8~=3sR@ubQ0>sw33Osud$t@W<|+KUy+PQ` z3J71@1ecH0ZVBSuhxK#-briB&BokIm1e)01~@ zP+gXnc0)9fc(=Uj9nU|WlsVa65XM@bQcp6m1~Ohl!=ZU|o_$l&blk}&S1yY)T-*BS2+jWv zOIXkRh|j-pn$y&`&8j$Gn533CvgC1hE_JHd#t)rhyarQ@{O9xXaN;6h+i<77G*^7n z_4sp%2ICNg9CEU(f{ynqOIX(*Q5ueflag25BT64!w(rSCMw>NUpY2k8cgs0thnElA z!~cgGy8!~X+slrBWGo;b^y_W1+u6!v6;;8hBW2Q;=Pfqy((A{^vv4a)L{lioPTJ|s zY1HVI>npqQIn0RBAI=2RKD%lx+6*CFi4IvAIveH;&Fc+qtQLQg_L}Y6zy@0CScy%r z?w}!YCUAMpm*rQ+d^UR--F0iMY^0W-nzwID0UG*R?42Imb-$?`7pE^SQC$#Urp=G7 zFPrl)G6jBBYE+%3Qo5?051120A9c(3LBTDOh#U{DMcdA||E4kToBAJ>hh@~k{Q%?U zqQY+i1T)h`n^vON+*_{l-=sqO99+Q|DJ_3A1O_N2P%J}IbH~YCZem-G3q?5H44pqU zIud`#tnLB^nfUBo{}S+A><;$blD90;tV8RUns*XbyU1_X-`>SPwa-4|DBMYNv+ViXd%NCRpn7R^D>FkhHxEx}p|($u_OC z$CBE>mvQ7#?4!-%fX@_ zg8%alueqbz@`G3@-N%YJ18_HG@5RxMHA3~^k^9xV+D*dbTh9OrG9Lzjc%#@}`W}@} z$zJ+*`QSjTE<`<8y}#}xS_``xymc(ZDeTudg_GEnW|ncWCR{Z{6c+R4>QI?qo}q2U z7q@;jkKa_=^}oCwQ7V`Wr;N0w8|h`!^`9ELbQY0FZh4)#AHMYQp54mrJ8xNqC*;5l zGJ0OHO97S>Ua(|C53^_MiiGaxJ7A}8&ZT*4`lL2STZ0fep^vcj?OZ;K-*)n8nNjqv z?fh^8L?WL0f;W#a{UXvQ%wXetk_uk@OlZ#B%Jc2lxwHz8Ow! zGb~>G`gB7)fF2NDT?11@))E{xOi!D7E}@za#(jT?X^5m5>w=w?##U*U?wRMs(CIM` zV{F_uX@#0RTfXQ`ph9rKP#0Y6-4(w_5x1(<|3;Ua{iP4iU?586*I0|bX^L{!>Vm~CVd7=pjn8S&frORqdgmP+syX=rHz(SY(-Cnk*CEz{af^o)_4H3~ z&LDZ*SZg0sM!O#Jt*PncCDJnm_7)|gHPS=do}OvbclEMFIxYXSlbnXr<$o=2h+1X& z!`@XN?OpRx^OgONRu1|9ui2O7iO@pE9B<_-`>C@I{c_H$dR?cA5$D*D0n@?>;a^_w$>a*;9z*ZVTp zOGs~fD?lDuz_pV%<3gy&8xM#Om~b1mF(RNMUEa#bG8%y=Nmj{KkMIA_$UZ3 zP2~H1Wr!20YGe3AlZ5?=upU3=VqvHo^l~vfy^K=V;Pr{84r+NkWKayZ?ID(a1n=5H zy@qtZLG#7PozCWcs<&R!Gb0e+vJkijwZhTg#D^<=m+|=6N*R3btK!3xG(&C`Y50wS z-sJ6y;GI#!pq9~ePDA;2nz|AEcr~Xb=Zq3HRH|N7 zR7G7{&0Yh)67;c}UA>cErD>KWH55^R7(?WpFz&E#GxcPOoJww4JTbmMGd%V*+!e;W zD(iB-c?|GF{l_3iBL~iYc%*5pz4Nj>>=F=L>i0bw^a&~;#CgUBt6C{ZMjrjH+FVS4Lwg9Xzkw@l`5sXq)uXENXh-uA9@py zt#rz4x$gRT+b8e8@qD8!X@Io+yj8S;RAhLMZFjCe(=qSRqcwOlU9A$W1~oAof|wGU ztquMF9utbc;h&!lm39H4BaW@j ze5BQ&d)^B4V4qZViNfLHyT42OZ?r!D`=Pm{U&o0?HRS05e43PH;NX=zl~(HUU9~~kKq6KX#Z*<;@?~Z8i9Kl(?)yOq<5}y9v*Ym;f9KAN(_0|7t zUNw|)OE=XgEUz=PW+762S`Ou=v8&YDjwu#?Eaukv-38nw*Tau!S~y+XBj!3Pc0b+O z@I=PQkLB2_6Zxu`GbK{k*XM0BJo|Y5>_LCnRLEg3xJHopI4V1~a zXze*hEg$HSL>YY{bK}an)1WGLF!)z1^@);QUwTeLICp%2+-wesOTq9h@ zOtFKbh~T(3`ppzw?PM)C7wqJ!5|YO2HUgKn6I#s_>(|eT;7{(XWvf*a-ScUm&40by zJ8hlmX#;JICvGV~I;Z6h(F=T!kZJrX;nButFAUO-+AYIO@4G#SSyDzi$kx>x)>bjQ zv@y%pzS9Uv!`l|#%M$f9UPmp2-BrxgT0Kp&t!zcL3AV_il>EN!A!B@qPMi5ScVN*E&CeS0Ct{uX7UYeoRFz3G-Fvx&OCjvLRwq7UeaBrMA7IS|7co=kT^BD5O8+PP9{HQz_2T$yr zcSFKmyJGa{u1>&x;p^$4z4KNR%W=DrXMJKdfu{I$T=WNw{|D3XXbgerw8jut9C#0v zq9SFOT6v;1^)Jl&{h%00u+2yVSzqttc)+uF3HC4cpSKK_9;1)4PfZ06mANhEVZx=b zpvRKo_=0h*RhX6A{)*TvfX_D;nUw#4S(?mGBkZVh5+nTpJW44LTzX+3Ylr!?iN~jr z7N#R=$AC}kGMdm>B?ybrR~kiFf!QF%RIY5)J=dR5vq~Z zNu^x9i*+wKzow10Tx+eIeXx9^&8TJQBug4oW zeY5nGHF$afD0n9*c#99#Q~zgH->06B`jlsR_l_x=OR_+2brud+B+elj0cTMUT9%X0 zC}`16l_Fo66Q-VpJaGI7a^GH}sS*)XRF${RvfJ!zk1Lu>%)Pl}p@?I52ZFz9gj%Hi zb>?O<4)Sx1oz`0*z>=^>7%D^Ghj(|If+w+G~uK4EwLU#bx^$psrBU; z$#>4{C&>)%v~pd#nYwnP!M9kB+$^Nnl|6v?zf)qTsbY4#j@@0ke{GaJ$66?&Jj?}c z_Xlk^db|dYM&X{jWvdDMt5$&qElg-45*Jnc)YNH!m}^8=7|=}U{}1S^??Qq1l~RP_ zsPlqp|i=&*U7Hkyo(*Vv!^@{F2l^E8eTS%V3z?xNgN~DxOwhg%%izTo33^d z_z>5Y;Gv&BzRS3AXTvZ3@gx2VS!A{|B9q=8p-1d~1OyZ7z4{`)I%F0Zf0T$43@%%%??)E!W8kJsO&$+TIVfj!Q3sV1-CV-HD@+gzM;~Cuo^0=Fwt= z^m(I|Qm$yYV!M6&)$W#S?${-}o*{H)(ahn+9MWkQ&j)ggptnE53UEFRqTMUF*>dfh z4_+!$CgTFFc83IoEy++NxM@FauC!th zq|ainIY^I$XSV~Tw2{0!nEOVH*_AZrI$ zjBBL;pkZ_cy+Y&%?#|HzNH+-M7KC6#STj?o)u8bKN8h1W ze}PUEBZ`D^2o>gSMi1DGLa-UBTYSViy9UKVx*oDgX+T&eZ;=4hE7 zfTW_u9K7yizK;RF*)zehywy53_IS)&OYBCv2RX`~w;EBb^fVl2J!bupVIe8)1+2q` zBeA()uP#%JalVpr>A0zti}?xW+U*2qG_<4LKi6`t=h7mCMPF^sZs>WvxS#FOoet37 zVn`kr0T337>I6`!WE@9lF{f^KqyD@P;FaZU4O2y*MJdM!?TNoNirVFz8D>Zt85xAg zr{Sisn=K%FJ6q5nh8lV`*NjIv&Z3?zaBE3u0!ayXT_4x#)QyjMyLK_sLa>>9P=~&H zG-DgQ`jf>Ft$+acb41<49}Ra&!FebwMz6bwu1&EVy08*bx-^9-lbE-9i+D4s&D;I? zBx=kOQ_|9;x))=SSnHNaDj1pRe4S|OWa(4cXD~oEg$zjVYgTAe?2^E=ql}Li^Al<}?iVDXwp88rq-Spz_BhBJ@eS73 zYlnD3&ll{%+3xzGvi8NWiz_!;lZQeF8hZM9T5i*evBkPIx*Mc-D(6*DJ5K=gxfsog zJqIX0^G@d`cy*lat{u>&^H|H%c2PgUxZ-7sp4`~j!X##w+G13MH9q{E8XyVfODd9& zM{$oS;v^TtF6~2B*(t!T0^z{YmTOImqWAi|;$0Momp!WnhsshG<8XaL!lI@hs!l7I zDdh&RX*U-8c(|hCHZ;h;YJBoI;GB#3;37FKcXeU^r7fUcjoLl9sEcD6xRym7J}#4> z0SSr@_ojtK%%eq-Y(<-7R8w|Wq_8JduYH$j(C0O=gN$nv~+A-YhQ} zVva`J#d-uI06Z5Xo~1TzrF)n~+-yiPSafa8(RNb4mZ#ieY?>?4f3O2JCbFdU;CxI@cymSOA}*^9@4VS+v*wwReFUgT1+xK758_g4yJl*e(fpv* zmPXUO*|r5mEq)K}p``TpMFnr9=FqI*9J59Ptt!9*bibh!r5~{&$SxBD5LeOCA+q_w zySgW7waNQcsa~OKr3CA-6Mw@sV0py7Vut6V;DUU+qF3QS?UjJ1;VZkqok%5A#L>>el6nbloD;0oFm2Cgt z`0x)nrwofkG{A>9QLo*=IE z^XVxGmCeZc3@cA5n=aF%kAoTNXAL@RM3d-+5j5cDf%?g`WhllW5aD_L`Q}R> z$n3^OpF3H_6ZJo$mWO|ukb0E=Y00M;z&;R#(3b?3I913bw3#X9#QWHLVmoSoJ6syT zuW*)vV113`A)~;R3S`{y?y1J1g+WI2y;AJrug@Jv1GxU525z>6ed%j|4%3^f0@(t7 z=34M;LBh&JaInV|)#H8bk7IqfILn&=uO-w3u>om(Rg%4RVGy`i*!J*bEZ#bj4oZo_k0}kpm|Sh{pUzqdtgVGM3dn!o79V^S0lI?Z7FMIy>C

%q# zt&}EZ9<6F+z5) zMZJb9`J;t_Z*OFWW|U6I4J$MNxN$!-Ny{Xb-C(HnEhaYAZ=%9DSrd268Ojq-Xt)PS z!m*gGHN3ZpYkpY}9hG5GHrYklot+iC|2HOvX;SAjtxFzZs7-)~)NiE5#rotyBL?I{ zH@R=N*6~L6t;I$!6(Y1GKviTCO~nA4jHX)MT^P+p&&!BpurgE~%w28*E~I60mE9eL zO&9tt*iIe9FND-lS8zVyNbam$uV)@JFT3g-i9HvorcpgM@f?}erhMm#+$)_yjs{r*8E=dtN_;AUcdv++Q| zX-7?tyfG*?ti)7FAQ|~+ zQ(f0bnasMCsd8kaOr5%p0&0kvhn>WvZ9Nvi!%sffgFYm+--+@MopWeFpgP$#-6#NA z?|g35a%~Lyvas>K^ktRaALMTbI&t@OKs)CPXywG@iZ@Q`z%6TN)HHNs2Xr-}J)jsL9O)tL z@<)2A;HBDLMh82&a;dl&S*%~XCG1@c@Ju88m}313tbPra1JoVOf(UV6Tkt`)+2|u& zv@YhCM%YdJiXi~UzYY@W&e3ouI4|+z zPvXpCc3~!xNi|`%MgqD9(Vk>n^g65@-8^tIhiF{r{p$>zw+7X7+)b?7);y`BI~Vmk zbuy6~SOvkPhQN87$;n!l3@~d(_cvd{YQ;RQ!0fw8Y)|c)voN- z6vz3JBE15Lw`bE2*u#)ROG+Q+=XI$sr*qI6(-K#e6r3Dp;*xJMB9nWZp@@plDbYHO zHBvTxsm3T7H3}kA^wiQ8@mQ7Gh5lY>A9~b2ESu5!o2OsEsU4qm>LGpsm83G@NWvx7 zLt$VrEod{g6gh0Nc$cR*r=Ov%^j&oYQ$U|>9-F2RXM*-uT-|QpTf1-itN&n%t?hH( zDYR&YcGh5Qg0VKfo zEjqC2-cX-(9)>UGda=m90Pacr#i8tW`EZ~IBd4tq9m=UcQd8c#OpMk4VMG88bi&v- z;_~7lz9yBjTdn}TuKWeP{7oO9xUEt&^0fY&VRX`#A5P-Q$lw*{dgXk78#Wu885!y9U0po`o9}efZT2O%PhvPZ#Z?G6<~;6yLW7H z?)DcTnw<`d`Hd>Ie)36F9E7ghQgGSQt5rW#LynG0?$BSb?58`5cKJi`2hfMR!a9Nf zOUflcsTxb~zWjYwjA-FBR}p$&4wr8 z|9%0&ny{JpRi)9MWY5yuf@|#NN9{)XI8P{4_$usyzTwKH4IUMjS3y;S*P2(_a^E&1 zr%^n7QghiJ77p0+CI@al*s5mV_;CLg&(x|6JNMf=TziTu825FE?pogCr~0_Y$DIZ~ z8jY}vP4O4nvO|!WkeH^CDbu+|$v=)*01URLN=kFAnDxe^LBZ;KMAR9Mi=>K}JPvnO z!GWK79i}qcXFo^Bd{jQy^YgBjqM#=$=)JDA?)NEVKOXbyYVU{kIy|hNhwLPlTkBtUZL4nDM zeJs5+39)d$H)y3B5=7Se3;P(~uX#M!uEz@e&EzLB*$=ehmoM_+gvuj)-kzgq{R5Z2 z13zt=%=yI|Tl9KYC%I<(X;B55x=)A898+AxlXlg&k)36>1FhMK_*5zLKNIb@3Bo^` zTA-NPzzNuK$RC-qf#kwfA?{?%s~`Ww>c4C`13`&43a*^Dfsuu&TJdvc#!d@t8SvA$Px7tmt41{e+iT_7{VP z0H$sx)^Dtgiwnqul+$YfW_5^S!!h5|I6r6fZc6iy4tV)SYC-?YrKVZ)4Jmg6vD3*h zSdb7{S4|cqT>mfjPbAdcrf(BPdEw9j+hSHsHaLx;W15)HYi#CTtUecU(P+@0=8pZ< z>4P()eNcyMwaZWly_ep3JZ3X?<}w|E?G5wL<^T;njbts8k5Tip(BuH>7OR?K= z=R$|q1?!Gk(TIMwzPy%uzE7g#A`VkKF+&SR4On?f+PVw{Uxbu9(jIxw#XPpdjEa-G zmmA~WW2vj?>11^~cdWa0hL&{&JCV)?mn>VEtRV0Qo58P;PiV|uBhgfr7#el&gk5BA zaLUa)j`Vo{7Bj6K*jblMDCUh7N**LT8axa^oWJMOrnrgvpUAgnXKS^cEKJz|GQsA{ow1h3 z+h*3y)~$DaO8;SyQS14vf#coJ`vYyqElQu!s2q`RLQ*To)D%~+8$IM<# zJUyzK6sJ4eSwW$`#(fkskL1dB3cUnFp=ciUha>`0Qmj1)|y4VL5M%fIBE+PtAsB7<%1Ud*8*cZ<-VH%*4m*o3%Z9JB4k^lE6II9`1>CdEQ5$XfULs&r4MIZHOK+ z_IAK+%PmFvRh#bV;?v9`LrI+R5^`GO4<=s8s(LeZ^&!G3cH2YUW!z)QKEcK8#Oq`! ziWPj@Mp^B3OHZlfOn%}$oX$o3N6A*YIMKw5Yc-paT|eQUX0(;~*ZSY2-1_z=rW4m% z>`1dOXm;Y4OrAko2l{3y^btQZMHxJ=D7U_>KpOv@XywD?B>gsCW!G?n-&9&Pl0LQ;Io!wYKQf&60`cki?CaSeZcp__Gr^VrJ9xLlcR^8#w5cqO$vMLG zPzyMK=THAy32vL=Lfl;PN-vjL>2c0IGt7?u%)ccrThmfG_ZvLd#aN#>s1c(OM=5%g zT&1l*&unSq9LvnH=icL7<|5sLRKmm(It~Uhkr)r2e@QxVs-iwaSRH-4MM(?WiI_

9b;3R?@W+T-pAl0#r0c$m54+xjIpdA*2*}r+`=>` z*wGI4Ip@uv1eowA)F?Q5K<{;rDGAbnqG?vTmF5oJ@TpP!WQ0%?u5C!xL0HqOp3-=t3XwC*Ol)U}@;2?y3`2MxoPIAS;Xsav z`Fa+?>D5*{JFeSk8Li!7!KV$}{Aw$y=a-U_62tP=tCq4&bSp|C+b@eZEv0{8G|l#S z+?!n`CQdQ1`QKn2LF=MCEhgP>>@vwZK{`0isv*9)r|4a(ss5)$4RgU>m>hoEDQ(R` zJMF&kLkHt#XU{2ynQupkZOiC6VGILf%XSVS8gAFiy{NEjN;b?Znbwi-c(hQ!wDt@T zYzPfJmf`p7^A$m|B-vBZRqXC(`mT46f%&0rzA))!Qtrr$3(TR=PPzarv}LrNAfS?R z%Uh{|!t|`~Yg`@T==7~5r&vKwAECd%X`I>^IXaw5y|b>o>s7=HSyHZo9`PKbKq+o^ zPak)(IP1)QPkvWbV(Xh1$q0UB<+cEAOTnu=SzxeNr!U^jG~?}I2bSgEFY=gkatDKV zbhfqrH!&*)Z$OXI^JJMd8n~v(;1x3}8`Y&s}W}T57AUA%93U|!NHVqhC zx9~jKvXcsWKK!p9|J$-XJoeXxrS3$g=Q;9WtFmDAu9*twn@@-Ly02ZG!C>9+ zaUD(_3e)mkIc8tX^NXgkg2G76YT@RVTXOXTF((x75OkV%=Cemq0)Bd$5k!_mv|lbY zQz=}{tS;sJ`ya=oAZPX1Xiz!0CTBO(i6I*z`XwuyAEF%@j*r{*=4L-hz&ZYo_{WwS z0}s;DnjZg9wb3Zx=*%uPzgEW_sp>q?J zkgAzUGcQWuUMJIw#~IlHcEY0Tle4?a=>gukEU7Sx<5m*)nBN$q!+OX)6E=SL4}}eG z>&RF4w|ONgYd2d+>&Ub*m`dw&>dsOYPM1?I29O0dciN-A!Dv&=z0O2L-rTz z?VO=(8+!dvSW_saX=|xz04XJXHJ&#-m_gDyxCUS3#nNNe^|8I0gdT5QwJA6ej;t2u z{@=SDvl6`$d9eF-Q$Y6+y8E_5-Ip9TzgdL=tH4I)z_8-O?q$$X04S>*16>!wq70(U zuH^94v?U%AVmhrTivE*hLE4N5Tt%6a2;&~2XFnNL!)O~*m^zQrnK<5JARCGh>w61w z^k?Ju1g<0Pp+kDn#271jxIJ8VA}iaCkpxKPu$+$f*Umk~1rro@hOwa7i~@XdM8+yu z42{dkc-%QyJsK0os7iUErJs(-dZ}OkMTeIo81_~si3Gj{|Eor{;Xj^}j@G_2zV@QR zeK+Y;QmhokRKS}Y=2_^GdgEMSE!RyXhEbLgj#%)xlWp1)?3mHVmPNTHuLd#{NLQIk zwn>J|gpb&c{jA=oLcjftHmWsjNVGK4w`Ok1;er~>Z^@}Fzc=_dwCUQ&cDT}5P`k!h z#DC~M+~;M5b~^Y8MRah1O?B7GTYG~y=IHwxuf`X6w*xxc0jRrqf%~~W_Qgb+IVHfK z!T6svzM#1piJh!uWRPCJzQpP1(rAJ)FIxr!5xtH}4mPUMrsTS(ge5ok%o?mJ7jNK_ zF%l&F{QgRZxg^}O%B}zH?a%-L%fe33cz~I_Cu2Z|mp>kPLcUV`VxeV>`uL zz)Vu`O}%!;@fp7y4YNv)J9!S&^%-wVo-F>x?tiH?Ex-N?g|5#xFxg8e4KvXNU4`d3 zCHC}qA(Tt7c*+*Jv|O@_`8LmUJ@@ssN^}@g9xX?WFG`y$*83+Is0;ILrOI0?ETdBO z?Fl|+^Tbc?Ob%l&P7! z$+G9nl#XCXn|5p7q9wQyKLVuX2cPOvFC zU%w@vQ3|bjJkvFwOr%hJx5=F58BF&2sgzH$OsDi`0y1Ggk+Dkdrux`p!sW(BuG09<>9Ozi<@ueGddMy7 zhttQi9In&@m73-prNl25|2{VvRTsWBH#U0Og3;#t$oWEe&?6~CxBtv=Yu=c1JFEG> z2S-c(eh7Tf$G@cF7N(RO+Tg-5e8n{LFa^| z(dX?PzgVVHC*oiiDyR(esSl4ZHZ#{DC(zsdjrMnSk{9SZT1Lf zJM*Z9?qPs6W`C73qB7b`y_QuN_VD0hSW}9Ff3Tcp<9*ZQX7<2BS*-DZH-s=r=Z<;} z7Rm%d1`CUPd{Zu791WhTMC3jNki^o7X@UjDAZ+U_E;ileY1d=^^>#~l>Mu~&DDPCj zWz?>x6J1(zceKR)(Dz|w=I`Kojz{o76kR(ddT6Xm*qVk40V__v)!Tn+I+T)j4LcCG zKiE@Sqxrw7W3_88$2vj7p!F*g|8hy}g^rRi8}21t`}z)^QBW!&=1W$w=aKlS3Capw z+|2MWGX&bXGN%899mUHdICYh18dbnXYzyuHRT>yV*zP*t+y-7oM@rhzOUaAhV9S8HUZ#no4Mae@4YVKuxi$e6T{h8|*3f;3Eg5yI?!M5sfOVy>`fY@K+ zCi?!vKESy&vs!ZwnV%{crXLKoQ%;BRD=3v0t1fJ+OzS76f4m7th33^mr1b)v=L1iy zhxG}LvbqnWos%$JTAxC`v|5Qo-wx*COHkJC}fvzw`fkg;z71!c(66`al0>4DJja|Yf z1bf)uyl%HgEuN!VEA*5sfr3;|_}FjV4u6A3O4ijxU#V$qb6pS1VN{Bel}Bm5PqY%z zHA^f*?m`(|;M;-B+t9Q*zj~7i(;isZ5%0r;yA?UPQI)hb%Vb7xh(N(#}{aX!=his5RsRawXGA9rnvb!*S`(~F&@oECfq z@IS6gf1|vPU$)!+H9+0>mizu))$XlTtg~+hNbK5g0*Icw(a8r)&($weom(Kw-%ZK1 zFR$oEcRN8R54vl2A!*lCC@wBJWdnkzc50@0=%@8)+sq%=1OJ`-gxM+=pVKZ)?rE@G zX6PqWJ+MBfwQ~fAZU}?A6)doTIW4RNCg>4~XXduYb@hj}ESJapm2t%*a7nwR-i3qk z(hjmzBY$)jEwE$cETNRRc88-Sif6;J5SX&U{9=U?3vG{!K&2A2pgwXf$eJ=%-lrMrz9lWt zq4NIzQh?k7?=bwP+}Tg;(dmQ7bv6)2`jlqC%CYV5#Oxo(4xm@SOqC$5VrWev9zwSj z3+Yisj}n-boB^OCG=;%#ZH0ZS=M(LTkgpux-x@6Lrh$notBBIV>As)QJ)8FEk|(T! z!?K!NI{n+4&An?evw>bxdmn2#sARjPT!6V@N0+t~&*mHuKA z_4`5ndfx-~zb};5FC`t+y72aUwEhm&cVhiN?im(W>?*B-)gC*aL$%V|59VDK@u1%8 z@Q_2$h!@Aw*r`mcpNvio)Fs{VwmVcmEqF7E;oz3Ct+;d#w$T z46OYAUc78`3JroV88Dh5VL#Ohnquc0zgcLf4YoH&N5aejj1<*@ENV6QV&@ComXazD zJ%(sxi|%#8dej;wac*}sy2csDS-FS@+jAMG`1ReP5CrA1BJbu>5OY_Eps;>vgrNJR zf(k_M_b8{{zB+Na_Fp literal 0 HcmV?d00001 diff --git a/src/main/deploy/FollowPoints.txt b/src/main/deploy/FollowPoints.json similarity index 100% rename from src/main/deploy/FollowPoints.txt rename to src/main/deploy/FollowPoints.json diff --git a/src/main/java/com/team766/robot/AutonomousModes.java b/src/main/java/com/team766/robot/AutonomousModes.java index f186a180..fb038b87 100644 --- a/src/main/java/com/team766/robot/AutonomousModes.java +++ b/src/main/java/com/team766/robot/AutonomousModes.java @@ -17,7 +17,7 @@ public class AutonomousModes { // new AutonomousMode("DriveFast", () -> new DriveStraight(1.0)), // new AutonomousMode("DriveSlow", () -> new DriveStraight(0.4)), //new AutonomousMode("FollowPoints", () -> new FollowPoints()), - new AutonomousMode("FollowPointsFile", () -> new FollowPoints("FollowPoints.txt")), + new AutonomousMode("FollowPointsFile", () -> new FollowPoints("FollowPoints.json")), //new AutonomousMode("FollowPointsH", () -> new FollowPoints(new PointDir[]{new PointDir(0, 0), new PointDir(2, 0), new PointDir(1, 0), new PointDir(1, 1), new PointDir(2, 1), new PointDir(0, 1)})), new AutonomousMode("DoNothing", () -> new DoNothing()), }; From 98b2e43be700ba6ba1467e4cc9d397255338899f Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Mon, 20 Feb 2023 11:14:44 -0800 Subject: [PATCH 067/103] Fixed config.txt name --- .../com/team766/robot/Constants/{simConfig.txt => Config.txt} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/Constants/{simConfig.txt => Config.txt} (100%) diff --git a/src/main/java/com/team766/robot/Constants/simConfig.txt b/src/main/java/com/team766/robot/Constants/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/Constants/simConfig.txt rename to src/main/java/com/team766/robot/Constants/Config.txt From 135078ba203edde1b69ff65df13578f5cbe2de35 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Mon, 20 Feb 2023 11:21:54 -0800 Subject: [PATCH 068/103] renamed constants for adrian --- .../java/com/team766/robot/Constants/ExampleInputConstants.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java index 3dd6c518..aa7cb28b 100644 --- a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java +++ b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java @@ -1,4 +1,4 @@ -package com.team766.robot.Constants; +package com.team766.robot.constants; /** * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. From a06b8ef127da3cb3394372194b163fb71017c2fc Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Mon, 20 Feb 2023 11:46:48 -0800 Subject: [PATCH 069/103] Added Input Constants --- .../robot/Constants/ExampleInputConstants.java | 2 +- .../Constants/FollowPointsInputConstants.java | 12 ++++++++++++ .../robot/Constants/OdometryInputConstants.java | 17 +++++++++++++++++ .../com/team766/robot/mechanisms/Drive.java | 15 ++++++--------- .../team766/robot/procedures/FollowPoints.java | 12 ++++++------ 5 files changed, 42 insertions(+), 16 deletions(-) create mode 100644 src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java create mode 100644 src/main/java/com/team766/robot/Constants/OdometryInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java index 3dd6c518..aa7cb28b 100644 --- a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java +++ b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java @@ -1,4 +1,4 @@ -package com.team766.robot.Constants; +package com.team766.robot.constants; /** * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. diff --git a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java b/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java new file mode 100644 index 00000000..31fa5068 --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java @@ -0,0 +1,12 @@ +package com.team766.robot.constants; + +public final class FollowPointsInputConstants { + + public static double RADIUS = 0.5; + public static double SPEED = 0.5; + public static double RATE_LIMITER_TIME = 0.01; + public static double MAX_ROTATION_SPEED = 0.2; + public static double ANGLE_DISTANCE_FOR_MAX_SPEED = 90; + + +} diff --git a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java b/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java new file mode 100644 index 00000000..ac3be89a --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java @@ -0,0 +1,17 @@ +package com.team766.robot.constants; + +import com.team766.hal.MotorController; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + */ +public final class OdometryInputConstants { + + public static double WHEEL_CIRCUMFERENCE = 30.5 / 100; + public static double GEAR_RATIO = 6.75; + public static int ENCODER_TO_REVOLUTION_CONSTANT = 2048; + public static double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; + public static double RATE_LIMITER_TIME = 0.05; + +} diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 5194484a..99966b3e 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -21,6 +21,7 @@ import com.team766.odometry.Point; import com.team766.odometry.PointDir; import com.team766.hal.MotorControllerCommandFailedException; +import com.team766.robot.constants.*; public class Drive extends Mechanism { @@ -50,8 +51,6 @@ public class Drive extends Mechanism { private Point[] wheelPositions; private Odometry swerveOdometry; - public static final double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; - public Drive() { loggerCategory = Category.DRIVE; @@ -119,15 +118,13 @@ public Drive() { m_DriveBackRight}; CANCoderList = new CANCoder[] {e_FrontRight, e_FrontLeft, e_BackLeft, e_BackRight}; wheelPositions = - new Point[] {new Point(DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2), - new Point(DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), - new Point(-DISTANCE_BETWEEN_WHEELS / 2, -DISTANCE_BETWEEN_WHEELS / 2), - new Point(-DISTANCE_BETWEEN_WHEELS / 2, DISTANCE_BETWEEN_WHEELS / 2)}; + new Point[] {new Point(OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2, OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2), + new Point(OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2, -OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2), + new Point(-OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2, -OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2), + new Point(-OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2, OdometryInputConstants.DISTANCE_BETWEEN_WHEELS / 2)}; log("MotorList Length: " + motorList.length); log("CANCoderList Length: " + CANCoderList.length); - // The wheelCircumference is somewhere between 30.4cm and 30.6cm - swerveOdometry = - new Odometry(motorList, CANCoderList, wheelPositions, 30.5 / 100, 6.75, 2048, 0.05); + swerveOdometry = new Odometry(motorList, CANCoderList, wheelPositions, OdometryInputConstants.WHEEL_CIRCUMFERENCE, OdometryInputConstants.GEAR_RATIO, OdometryInputConstants.ENCODER_TO_REVOLUTION_CONSTANT, OdometryInputConstants.RATE_LIMITER_TIME); } // A set of simple functions for the sake of adding vectors diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index bace3307..79c90a32 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -23,6 +23,7 @@ import com.team766.controllers.PIDController; import edu.wpi.first.wpilibj.Filesystem; import org.json.*; +import com.team766.robot.constants.*; /** * {@link Procedure} to follow a set of waypoints. Waypoint files can be passed in via @@ -59,11 +60,11 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private boolean[] stopRobotList; private int targetNum = 0; - private RateLimiter followLimiter = new RateLimiter(0.01); + private RateLimiter followLimiter = new RateLimiter(FollowPointsInputConstants.RATE_LIMITER_TIME); //Radius defines the radius of the circle around the robot - private static double radius = ConfigFileReader.getInstance().getDouble("trajectory.radius").get(); - private static double speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); + private static double radius = FollowPointsInputConstants.RADIUS; + private static double speed = FollowPointsInputConstants.SPEED; private static PointDir driveSettings = new PointDir(0, 0, 0); /*public FollowPoints() { @@ -180,7 +181,6 @@ public FollowPoints(PointDir[] points) { }*/ public void run(Context context) { - speed = ConfigFileReader.getInstance().getDouble("trajectory.speed").get(); context.takeOwnership(Robot.drive); context.takeOwnership(Robot.gyro); log("Starting FollowPoints"); @@ -330,8 +330,8 @@ private boolean passedPoint(Point P) { * @return Returns a value between -1 and 1 corresponding to how much the robot should turn to reach the target point. */ private double rotationSpeed(double currentRot, double targetRot) { - double maxSpeed = 0.2; - double angleDistanceForMaxSpeed = 90; + double maxSpeed = FollowPointsInputConstants.MAX_ROTATION_SPEED; + double angleDistanceForMaxSpeed = FollowPointsInputConstants.ANGLE_DISTANCE_FOR_MAX_SPEED; currentRot = mod(currentRot, 360); targetRot = mod(targetRot, 360); if (Math.abs(targetRot - currentRot) > Math.abs(targetRot + 360 - currentRot)) { From 4cc79a032bc81c6fafc466c0dba239e625bb2beb Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Mon, 20 Feb 2023 12:05:24 -0800 Subject: [PATCH 070/103] Added swerveOdometry Code --- src/main/java/com/team766/robot/OI.java | 51 ------------------------- 1 file changed, 51 deletions(-) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index a6ebf35c..783db8e1 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -70,45 +70,7 @@ public void run(Context context) { } else { RightJoystick_X = 0; } - if(Math.abs(joystick1.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ - RightJoystick_Theta = joystick1.getAxis(InputConstants.AXIS_TWIST); - } else { - RightJoystick_Theta = 0; - } - if(Math.abs(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ - LeftJoystick_Y = joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); - } else { - LeftJoystick_Y = 0; - } - if(Math.abs(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ - LeftJoystick_X = joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT); - } else { - LeftJoystick_X = 0; - } - if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ - LeftJoystick_Theta = joystick0.getAxis(InputConstants.AXIS_TWIST); - } else { - LeftJoystick_Theta = 0; - } - //log(Robot.gyro.getGyroYaw()); - //TODO: fix defense: the robot basically locks up if there is defense - // if(joystick0.getButton(InputConstants.CROSS_DEFENSE)){ - // context.startAsync(new DefenseCross()); - // } - /*if(Math.pow(Math.pow(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT),2) + Math.pow(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD),2), 0.5) > 0.15 ){ - Robot.drive.drive2D( - ((joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT))), - ((joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD))) - ); - } else { - if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST))>=0.1){ - Robot.drive.turning(joystick0.getAxis(InputConstants.AXIS_TWIST)); - } else { - Robot.drive.stopDriveMotors(); - Robot.drive.stopSteerMotors(); - } - }*/ if(joystick0.getButtonPressed(1)) Robot.gyro.resetGyro(); @@ -118,19 +80,6 @@ public void run(Context context) { if(joystick1.getButtonPressed(1)) isCross = !isCross; - - if(joystick0.getButtonPressed(2)){ - Robot.drive.setFrontRightEncoders(); - Robot.drive.setFrontLeftEncoders(); - Robot.drive.setBackRightEncoders(); - Robot.drive.setBackLeftEncoders(); - } - // if(joystick1.getButton(1)){ - // turningValue = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT); - // } else { - // turningValue = 0; - // } - if (isCross) { context.startAsync(new setCross()); } else if(Math.abs(LeftJoystick_X)+ From a77d350c4acdae5f4ec8f112d4808b5bd6f4ceab Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Mon, 20 Feb 2023 13:01:25 -0800 Subject: [PATCH 071/103] Added quaver --- src/main/deploy/quaver.png | Bin 0 -> 624 bytes src/main/java/com/team766/robot/OI.java | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 src/main/deploy/quaver.png diff --git a/src/main/deploy/quaver.png b/src/main/deploy/quaver.png new file mode 100644 index 0000000000000000000000000000000000000000..3b9ac787a62a808e9740049b0ce34581fa731936 GIT binary patch literal 624 zcmV-$0+0QPP)EX>4Tx04R}tkv&MmKp2MKrk09S9Lyl%kfAzR5EXHhDi*;)X)CnqU~=gnG-*gu zTpR`0f`dPcRR;4@5YQbVaKq8)FhG`RT5YKGd z2IqZZk(FhY_?&p$qze*1a$WKGjdRImfoF+^x`-lqd<5UXf+(?``B?>CqVESxY9fRS`(Q4B)!qm zqDR2MHgIv>(Ud*lat9cCGGtSBr64V#SOnhB=$rDu;4RR%=Jl<8j?)JqOTAjY0S*p< zu@Ysk`@FliyKn#2wEOo183}TO$)BtX00009a7bBm001r{001r{0eGc9b^rhX2XskI zMF-~s6ch>sgo8B=0000PbVXQnLvL+uWo~o;Lvm$dbY)~9cWHEJAV*0}P*;Ht7XSbN zT1iAfR4C7#k}(RvPzXa4?|)u#5bRJoeYN^CijTw~P)Jp=QbeS4xnR2OlPMj{Y#j*z zNq1iW07PU5kQ@OwwZ7QYAKnWu}CZs)c1KlcE7x-81!{OBbB0000< KMNUMnLSTY9tOGUx literal 0 HcmV?d00001 diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 6d5b5d43..daf8ddb6 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -32,7 +32,7 @@ public void run(Context context) { context.startAsync(new DisplayImage("cone.png", true)); int imageDisplayed = 0; - String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png"}; + String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png"}; while (true) { // wait for driver station data (and refresh it using the WPILib APIs) From 533fc345d73486afd590415416b9766ac6d1768a Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Mon, 20 Feb 2023 13:06:37 -0800 Subject: [PATCH 072/103] Added a template for documentation and an image folder --- docs/images/template.md | 35 +++++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100644 docs/images/template.md diff --git a/docs/images/template.md b/docs/images/template.md new file mode 100644 index 00000000..0b0cdcc2 --- /dev/null +++ b/docs/images/template.md @@ -0,0 +1,35 @@ +# Mechanism/Code Name + +## What is mechanism? + +Description of how the mechanism works. + +## How does mechanism work? + +Describe how it works within our code (no specific code yet). + +## Benefits of Mechanism + +* **Point 1.** Explanation. +* **Point 2.** Explanation. + +## Limitations of Odometry + +* **Point 1.** Explanation. +* **Point 2.** Explanation. + +## How to use Mechanism + +Explain how to use the mechanism. + +### Initialization + +Explain the initialization of the mechanism and its parameters. + +### Running Mechanism + +How to use the mechanism? What procedures do what? + +### Integrating Mechanism with other code + +How could one integrate this with other code? Could reference to the procedures explained above. From 88853120caffe52b0c5e5a32991cc80777d7ae8e Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Mon, 20 Feb 2023 15:45:49 -0800 Subject: [PATCH 073/103] Wrong folder for template :) --- docs/{images => }/template.md | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename docs/{images => }/template.md (100%) diff --git a/docs/images/template.md b/docs/template.md similarity index 100% rename from docs/images/template.md rename to docs/template.md From 89f6a56e0e82c5d2c163b6ea48bbc4b646cacbf9 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Mon, 20 Feb 2023 16:09:29 -0800 Subject: [PATCH 074/103] Update template --- docs/template.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/template.md b/docs/template.md index 0b0cdcc2..499979d9 100644 --- a/docs/template.md +++ b/docs/template.md @@ -8,17 +8,17 @@ Description of how the mechanism works. Describe how it works within our code (no specific code yet). -## Benefits of Mechanism +## Benefits of mechanism * **Point 1.** Explanation. * **Point 2.** Explanation. -## Limitations of Odometry +## Limitations of mechanism * **Point 1.** Explanation. * **Point 2.** Explanation. -## How to use Mechanism +## How to use mechanism Explain how to use the mechanism. @@ -26,10 +26,10 @@ Explain how to use the mechanism. Explain the initialization of the mechanism and its parameters. -### Running Mechanism +### Running mechanism How to use the mechanism? What procedures do what? -### Integrating Mechanism with other code +### Integrating mechanism with other code How could one integrate this with other code? Could reference to the procedures explained above. From d4805a9182cfd85fd2a0180db81179cf5b636130 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Mon, 20 Feb 2023 16:23:31 -0800 Subject: [PATCH 075/103] Added swerve drive documentation --- docs/SwerveDrive.md | 57 ++++++++++++++++++++++++++++++++++++ docs/images/swervedrive.png | Bin 0 -> 49020 bytes 2 files changed, 57 insertions(+) create mode 100644 docs/SwerveDrive.md create mode 100644 docs/images/swervedrive.png diff --git a/docs/SwerveDrive.md b/docs/SwerveDrive.md new file mode 100644 index 00000000..f56501ac --- /dev/null +++ b/docs/SwerveDrive.md @@ -0,0 +1,57 @@ +# Swerve Drive + +## What is swerve drive? + +Swerve drive is a type of drive train that allows for independent control of each wheel. This allows for the robot to move in any direction, and rotate in place. It also allows for the robot to move sideways or rotate while moving linearly, which is useful for some games. + +## How does swerve drive work? + +Swerve drive works by having each wheel connected to a motor that can rotate 360 degrees. Each wheel has a steering and a driving motor. The steering motor rotates the wheel, and the driving motor rotates the wheel and the robot. + +Here is an example of a swerve drive module (mk4i): + +![Image](images/swervedrive.png) + +As you can see, there are 2 motors which control the orientation and speed of the wheel. There is also an absolute encoder that allows the robot to know the orientation of the wheel even after it is fully turned off. + +When 4 of these modules are connected to a robot, it can move in any direction and rotate in place by using vector addition. + +Strafing is the process of moving in 2 dimentions by orienting all of the wheels at the same angle and moving them at the same speed. + +Rotating is the process of rotating in place by orienting all of the wheels at 90 degrees angles from each other and then turning them at the same speed. + +When strafing and rotating are done at the same time, we get a vector sum of the two vectors for each wheel (speed is a magnitude while orientation is well, orientation). Since rotatin and strafing are going to be different for each wheels, the robot is able to move while rotating. + +One caveat is that the added vectors could be greater than 1, there, we need to scale all of the vectors down. + +## Benefits of swerve drive + +* **Agility.** Because swerve can move in any directions and rotate, it is very easy to avoid defense from other robots. It is also easier to move around the field and score points for most objectives. +* **Modular.** Because swerve drive modules are modular, the robot is easily repairable It is also possible to drive the robot with only 3 modules working (if one module is broken during a match for example). + +## Limitations of sweve drive + +* **Very complex.** Because of the complex nature of swerve drive, the code is to read or understand. Moreover, the chance of something going wrong is high. +* **Draws a lot of power.** Swerve drive uses 8 motors at once, which draw a lot of power, it is **nessessary** to prepare the amount of amps drawn by each motor on the robot. + +## How to use swerve drive + +Call the `swerveDrive` procedure in the `Drive` mechanism. This procedure takes 3 parameters: + +* `x` - The x component of the vector to move in. +* `y` - The y component of the vector to move in. +* `rotation` - The amount to rotate the robot. + +You can also inpute a pointDir, but this should only be used for `FollowPoints`. +### Initialization + +Calling `Drive()` will initialize the mechanism. This will initialize the motors and the encoders. + +### Running swerveDrive + +To use the mecanism, call the `swerveDrive` method. You can simply use joysticks as inputs. +No procedures are needed for swerve, all is containted in the `Drive.java` mechanism. + +### Integrating Mechanism with other code + +Thanks to the option to add a pointDir in the method `swerveDrive`, it is possible to use swerve drive with `FollowPoints` (or another procedure). \ No newline at end of file diff --git a/docs/images/swervedrive.png b/docs/images/swervedrive.png new file mode 100644 index 0000000000000000000000000000000000000000..8e01fa6740f823a64cbed9fac188a3a27713d297 GIT binary patch literal 49020 zcmZ^|V~{31)UNxqjcMDqZQGi*J?)-0rfu7{ZQHipJ#G6r^Pas=ef!5gt16W%D|aO; zE0wBLq9QFJ;nE8LXo`y{X((}N!2$pPs((cT6rc$TkQNnHDg*h~1b~#;n*4GGMFs$V z*||8WNQw|?{nRFc+5&(8umNBIY5=#9iL-;Sl9Jqi>i@evul!U0vqk#<#`?c&{(rqN zre@A2|9Wr#6$29oCzpRQ{Wll9n~TGLto4u4oc;y%k8S^Bi~q&`|FQA^;-vpqqoyMI zPXqstg)IILHvT{Of6w(#0)Q}KF|qm&{y#Hub^86k8RuU;2{I050+9f11NV$9h^~yw zMtnyd$AZP1AOWH5rgvrI;0Y04pW$6))$6l3c+La_x|q5Dix&V86=eeam&5-U0QjHW z{EyGR007{60sz3`{>NvW4gj+HY)b%e(<)GOhG@77V zpaT4OQDOze`IN=1o@=*I;TCp@L>zrAy1i+ZuLT5_w`jZeU)V?o3;`aoHy-EDCY`LT zyNr{--3R~e*bajX!ly46pf2za(0)tjKKDNLozva^hVZQyO90hR6v+Jj@Kt&PoZS5; z+=}%DZgmR@7WhRyjX%YHzg+NtIRB*w_5zVUZo(9=dmn+;{Mo&G)-PVG<+;JWVqd+V zm~Xppz?Qbp^*#5? z@8TO=Fw4&cSpQA>#o22C1iIyR`2oLn1sw!|zzv2~;Ex2qC|% zn9}sX(k{cokYMFs)acdNw!7JNVc5~?P>>R$S2we@#+ZCdMsa3ES`1Z|S5e`zX<}bA9b6*G4`Z3kdvubi}4cJE)G~c_#hW`zv zkcL_IY4bVKZUmpISymCF)6lJCMsTo4zitGdG$I4U6mNuibz?_^qBZt}UZ`}E`SQjd zK&i5Sp;FA7=^)pS`E8n=bC=x7oRFd+V}jy4bJEL8Z0JM5A`uvRVHEIN^(yHTKh>-% z){cPj#wF2?^|Z6x4}14we^xTj9x1$!h7{KZZuzmw4cw04g4W*ng?OVWUC+=7gmf5_ zyPY(X4$3sNA2prKdf`owyx>6Q>&5q%u`{bo-Ylsu0D-+AUslE-O{e(hSJ9(h$TAbsrWU@NZRt02WWJ? zGp^2BdH`_eC?S4CKB0SBsHi4r?j{4E&buyv9&u32)L&BnsZ6}LnAW97YQqd_emt{n zhyDt0D1)n}^zzA8QP7u4kU6|hW7&<#^BYeK@Rm3%%sh&5={$jgC!XP__@a;w^Adq; zOh6P1`ff1Tu=h5Fk15V@9XXOxNW}XY=N)eFNET$ zm~Q2-f_smLzIRa=GV2X0sbAbsQ2&U$k2i>oGdkZMOoDF_bg4L;h$FSh!N)nzU9ear zVIk>c{V3vVS}l6IT$Sh`iM~b6&;VDVJ$TAKM1_+J?q-(*pZMu- z?WjOxUr@4)j7XJCaJ(YN59gI5l9(!J_*Pc!Ve#e5WE+Az+Qe#QH?ed%II@cLR;YRt zB0y_I0@-gY9+4K06|=uPa$)7P=6ODbq-H=q9d6>1LD*>LdR^ZsJV#?=7xru>)p>ir+{>*>NZZog=frXGh8@0HC zld?M@J&Gk2dfEjhp*%?Ji@wp}P_o8$wWzUCqtSc_=Xgu<^O3d%^ zr4hpmyz*O-(|0JRwVr6-R0wZ_+m48Tf0V$uncV^2c&2|GKN zLZ)!YUa~Y1tJ&0sV_sbVgoa;T0okviW6H#o64~&9X@^%K;V@ufZkbyaFyPGY%KgHJ ztyr|yDfu2uFrfO(cet)mkRDnftZwV{3*<$*R{_g*_s#DLw7kZqR$Fy>g8znAL0^y(EZoa1M5Rr1Fy?T;XQgeCl;>8NLvwVD_&oGQt87}0zdXcu- zOoYZ_Dqg@SZY39dYYEmz_hRx-sO!WWG@577&^SiN_>}VUeyW2y<((WtMn5QW-Fy3Z zdxTu7Lv2hXLT_fod<<(Gu9og67h5dK+}Ez@7t9Odln?qEGKGLAVg=v7S8@P<^i)w$ zX}tg*rc-a{SvizTq>e0zLs8((BE!Zn=oPg)BW8-ZC%VEZV1s;#>1ILG(EF@U|616- zYlTvst@SxP!)_85! z>*5+CnF#*~^7EyItn20yo4C3dJJcVfOE%3h2R=j3$5dwt;sTL-iv<14=pgQ5!rojK zzFO*eRR?2^CyCQ1y)!o~=QrJ4`?)AXzb@ouNAB5e?(Z3S;sXwyy{2Gu2>EL~+1h~j zP%y=HiV^Q*zsR9FT)>AddkG^fVj(aRyNe$DWW_vB05uNKK-NWC^|wetO1N ztTr7#R}Z3qManeHtt?zXYHL>6vu-VruDZR|4Qd^iJzF8%FAahZ&(1~ThB~1IODWH1 zu354IeyX=e+x&!AR`+*lgBHBXk#O`B1AoxnVgPg~0&TaA=T&f})6U5oi-6nDNEHGK zS5#FAMlnB3L2theT-Rh_SF+3ic)JevMnLwq0%766YJLjr)ue3C*PLVhZl!eP;+ynQ zCy72tJk&+YeSiZoN!*;vqUBs&a$O;*i0#@pqkqy(lfb7?Sb<(+Meb=5MX5)!kp0%d zqC)c$wwXQXiK>Xvnut!W8qG>oiM~xHWB z@CR#zlin%3p%-j{dnuPC|q?C|h zp2(8Y3_?R=;9Wd1l3`M~ClY~bNTSO=QNJflW67d8Sh}q@91Yxr#?}F1n7P;=(=STh z7Jf>Zto*+{inW2ffBHVJ0ca(O_3zTF8ka?3u{sAW;JNuf6R;|Y&Wq*B;x^0ClaLPO z>vR32+Rc=4T8B4I{^AB1^d?qL7GbE!!=#!QWj@|QIx8k(@ukyg9L3Qm1Bk-_o9*y* zVvXm-4HY1ctTxDzu*b5$m=+?S3(UhVZ^iI4mBpYT*c08^H zH*;1~5Q&VDY+P$HCL^t*H&YqOT@jkC{anoI)BO1zENMdI_#p3%m0DBsg*P0k%dDAH ztN2qmf)pOBWggJOH8&T)wNl#F1KL(+(I}XO)~W=kY~Q<@wle$1uyHUQVrs@OsdS9d z_jrpQQ-+ObAHhZLD0k#={OLO@E7S^G;O3bx>ABw_H{NB5uOMB;w)Yt%EnqU-kl6Ty zy5Xh&fmzW-Rx$W2j#k7VdK)cH#!NrUR@ir%auHksFzq1j@9l*Vol-{#g1mw|{jJHA z+#1COL26GyBj#BVL7u_DptE+;MRyi#=iVqbP3JiY62)rHU@_u{gQ*?JihE3JOxiD1 zhW&-M7Ie^Tu-D5_s+@FI_;<sQ#<5nSVK0Y z??|?GlW_uvbHP8kx7@g_;yjg}pFxBAg|lB30XgHh#m1?0j3G5KpK^6MN-Z&ZYZamt zve4zxyuT@H&wIcabBLj%)sH2uI@BY4bEh@lDmpO?x-*y%>T#%ZMW|VrJyTmad5)5G z#x&UZwAm(j6rGj&02+>$B;_7;E!1qs;phk@QKGD@8_`GuQf)`kTDk!#<4nEsKDSi4 zC3v`Pmz4MTPu*QGFwy{_`$i;Ue38}03`x*dBT>~1Tb*#9Wnz#zkT(R0CDCY>;E4TM z_6<^|^F_o8{vqTvm@WSFX8)SXt79dO&PC#27cmT;lDlwx)rFd$kH0_fW{sg1`%~{X z-7ewD-6Bvhf5jh4x~P;M0K03wJ#T69_HQFpg4_=|VdRxjmFwdB zW+fa&<93bBEOYgzOtOVtks_iE?MBO}F(Nv;_4WXu17cIDUI><2(56(!7r0wht2N%5 zh(xfCxM;cQMWkJ}k5OA8Vsb{3ES)T_T{Eczew`*Ahpebb<7yypLO#2T zs%e7)2DWh42-++iKNa5n9yGis6XOimNgWzUIj-J^yF;O<%I9RzR6sOW+XG?xj1BM1 zrP*y53KPct+VW|8UD;0KYo-( zXZ5a>i!*ZfHtH@d(I5>EUfT>3V}*UPTF7uWYpmbZ0z~-i#mZH4GZsVW+)>Xa{F3ZWq}N`e7mv+9J#|j$CLds2X0wm`gD$eXJKa z9*m6^cjWoQWsjrojK;T>@_C)QfR)U$Uk+WG%jyq~Ij=5+7`}2TXe&Xfu@5Kj_>5V*Lv}m*Fmn1gD3^spdR^G zjhEI4!r%-gy%7P9nbBp_H@^k-IEU1N`ja85^7E?5@9biJ#k!?-9(DfOXNM{BKVNMwlzoA*Kn7yDIIVnz;-15`_P zWF1OAq+hxGoK*xUh8i+S2)~}rSl}`0Z3Ki&BqIf@#sC#I2#jJATu@quQXGNKUQ)Cs z!iRluMBsSobu6n<1n3-riap~j^>znj;Z#6(nG?uX#luaskDRc-1lB;@G$6wlpU!@F zn2plBT;BIO_sV9~AcKlmg!VnHFuZgLc8ik@e};jo@prH+WY(KK;b{A&!?LH!Z`SA| zJ5Ai3{|;LEkmwmZ*fuwNWwi0u-kqU6cqys0ArkS=^QMck30LF=wuo?owBsvs4mU-Q zE;|ZfCtJNFxcpJbygH7p3{g?N^$MjU9A8&0@Sqk6W3!ZaSOeIGFe;0D3w7M9)H%N= zZzW4yaeIU-L)kxWRTr@uu#^hmoW$pdw+oU46?yVAZ0S%|QQ^WdBoHbJGyBw}{tSQt z&#vAa`ti|s@`#4S{NV39l?vr8o?qT|9j##i+)=C_u z1c_J?l_|?wUfaFL&MzZW;;yiPF4Lru$(wT!g<)|&7%HMv!@JEc zudYPZGkiEdXqn)*e+M4NSln|G)I!M0Ok4p6(E={~<+>1^5*0{Yta#(%cFsk5DD8Hw zIhCXwmxROt=G-V-wZ*x`#g9*PgR%p@sr8JaFK~6ws?Dv(?Nq0j_hkYzJz$lOD$o*i zAZ^Y4H^^14QuUdF0c(unJ(kSp5QxM{fx=>$671iWKxNY{vqDj5VsXRKFls|ErI0h{ zRGo}!SY@@_E^rb6!xH?+SIu*LlnWV6>dbpZ9uFL|0jz>0xIzj^3)FjgYm~-FfMT#w zWg8*(w(!8kbzfUaFk`r??mI^qBuX)Dtc$2lYV|yPnNF-Q&9lE?YZ#$93?Gx8vOZ_u zu=%kHyBXS+LM*r887P^E*5P6_&uRX7$k?(5lCiuYk6C00Gg%fC|LI!D zyX3nQBA%;$rgpFLO9a<8@=-B$hD#H^XR4;n!i_lD$x9Gmgr8$2$YSC^TgcFGm5_Ow zW(g|I#DWzjQ%_W_I>#5rPBb;iU*6)UHBX+tfeHstL}zrD0&E-aKBKSHKLd1(SJ6I^ zvP=~U~XOP@FUJ>0B$$j;@}N6G<3$cGRW z$c8e&~VA=jl?GlBH2EQ^Nxs zH&b}PEX8gY-Gz!0AJNP%)K)+uRz>8`n%h8EJ!eIO7BeQA6YMMXvt_Z8?9jPKeV_u) zp+dP%7+MqF;#99TbYwdF`F*^+7`H^wr6X4tXgw+2oBST8;;+}hZW=fg(f}*;>)nJQ z+}`iuJNlY{dn(_pR54O`U7@L_2fwgcr}^Gd)5(0m? zWd-}wOr4osaL~TDTB)y zXwa`o+RU*1!ek+(9(?tA)7Bd3@4)vLzX+ST$NmPW4O<<5ahfSOrmsa~elZy56=x|y z?0$Puo6d%vH8BkS*#mL)vM6fiJ85IK)^D0aT05Gn9w|=<{4tS0>QN1S9(%|5np%m8 zwK8ly$GKx+^(L^RI;bzio#OA?`retWP{%$`pearF%!Z7ME?TTOvO|9q8yv29nPC=7 zaoSY^U=f~pzg@^#d(#f}{#9Vgn43Vq^txP!UO}J=TC1T%x8g$~wV4QI()BJP$!}mL zpapI5gWgCJY+yx{MaJtep`73n#fnjSZa}|}$*X{p57j7r&V8~;9nYjZfg2Up_|swy zX!IqT7hY2lIGNF>b5_hO5A+aj#jFfe6+KVY?+4C{fy)6kU=8c!g8Lp-UQ$4uaLhL{ zK7{kH3U%(J>&fd6^7To6ffd29(X7s3z?|b#3U_ZR(>Ftnp)h*{a?;TepH9Ov0=B}$ zY$1Vw1<@(4hR<%Lc>7>uLSMn9eWqqc$dVQQ!bI;tO>doLIA(61HdD_WZ-wsA=HR=S z6k44YZv*F47kT-){eA^e9%hXDitpG3Omw!^g(f37rrgOJC0cW*-4JxUplT3h%yMto zy4iWz$^%PGhRHoCGov?SRq<@=OG(*EL8$Kil|PlM*XUC z>0IlhJ(|@rdAQ_mHVpc-v2KU!C7$|eBz$Tsf`vAN_0AY|M8&^_szp7PV9Tvi;)XMP z-FzCprOEK@?nwmHfVjfbL89S42u4Qpd_Etp!Zc*zW2R18OED6(s_o*HY(TP=WKQRC zPDaj9p`8qQ9{R0_Y*kND@YMIq*4OIdqi>@*yXjPr!SF)smiNV)q-+L+zGNKsgd)Et z7reQIQOs?SN1H~ZW*Ihl!@A-Y(VpUpZtS~y&uiee@hPG&h_|rBGh^Ox4ei~P(hu-+ zDGp^oQBp)Bd`~sLMo^bxqu83AJZGssc$#|P@FXySo8^q{MXZyFb4Q`l5c4=)edAg=)Y;UGp@ejB5QC z)Z1N9*D`4oq;F*+Nz}Nuv-vATHJ*@C`vJuf<)eUyB`&pFPL^H!#|J_M0k8Y1@+K88 zei92T)tHnq&p3C;Z!($XjP-oM_)jAe@Ob>KrCS?KSieQ-=lB93kwU#7#I2 zvN%8VI))ggM9Y_hN1th^KfluJ^Io9_KHxcb#6un0alJm9eyg*tIBiNLBU#a+z?ur z371geqT!a*BYpO2Z1OpYGSho|uSFRvqHv_~HthTkr3(i`dU~p5`FmW~?zzwdt^8o! zg*B&5;P~th=Z+mQ$sw%ioI;D9gUpJ<9EYK7;#Vzx>c8(`muvK?@+WT40N7*Ii>Q`5 z^(gqqzZ&yvf)|q!b2Lo{Q?OQq0eh9HB3^dYtzS}9?N*DpW-u&p?#NV0Qr{PJPYoPV zcg~EB^4w{HW%y{^fK(;~l&H=4GKEzO&WnMq)aUM|s#S^7V&ZLW3wATdQB650fO*jC z-yME~D{;X^Tu$g_32tEe$glhCm$G}TT>EtI%06_yykqJDh%x#kz8xHp;Ch32=>}a} z@g-Wwl}fBC94FWB4)okoWA1>%-wvu%H{s66a6BHG9?stf{3Xqv61FJMS*HsMJR)Hi zyOxBbMTTYxU?X1^_ZV5&q6Bs${b(C665S-lHcHq8ATS>8#=! zTJBeD{NxU1B*FX%0+dr#*xg3yEXmlCsAzLx>NNjZ4^zmS6xO8QfRL)!q3u4t>+z~#v^q6rc!|?#C^se)$ zb7Rt8{GSqlfS_2YQu(t6Hobizis`FYtBb>Q?KPAW^QY2bR}4Nh!6`v1j(Y1U5UnHepnacaC+hX9olGp^V^Q6e!G9i zS^0drO-wKO&^3J&M%RSVsBegd`X!$^S*8!)K<#9`!D^l7as}S~ktrB$h?)VrTPj+Y zE-GK&Z+?MOq~5kiAeqffqW%Q>>rRl-MgYyPQr89 zTx_R^0@AVY`amK<_|%gvpD~Vg!_?yYI5T?+(dB2f;A*p3S}03BeL=`6^~FO8_VOAr z*~V)$02BEq(IaExJW!FdJ;vXH%AW=82Z@_16uI&Pty{h0vsD_pge_@n8c0?{1*t;) zUX_m$UC=MRkiv0eKZ z$q6OSNL7FP1_U3KlXFvQpEL4{bDT*bD@cuX!5YvNzU8i6a^r#@pb@-bqtPI170TwH zBv2t)uTxbKcYu^BFPjRHd9av@v*or^U;{=cA3D<9+L;i`R9IGkwZwR)m|7Q<3eO0P zy)~X9%v^Q4Yl7`id_=;)(tW{9$`V7|+K5kb!q6ar9)J)fSovK^ly2R5Fzde1~ zUU6yc-t4i?LsEoIpAc{!@kmYo8f^0f_*wIULrhGDy~TDjetFDT;gDa5_Jzeaq}acD z6?0d=Cd2*3tsOG<-IfZ`*-iVjsMQw#cT{W8CUaOC(s0&j2$xSB^k%imum7?o*KV@O zc0j~&GhKj`rO@4>*>x6w;44R~Jg&G&EG_C6M&OV@D!s}zctUFdYeK2*MaN>Y%t^HY z6W-h1J!XL(HNK_U?Jqhq0K-TbOD^YGAckJ=G`0Q(H$M?cw)AGfbe6XUQOzH%!s|-` zKMTONdBww|dTVi89G|p}VPg;ZjF4UEX`VH+2bMKw{z*fsUfqXdz4FVom|z%S(fsM$%#2B z?$eM?1ySA13bSF$W|Tqr)4A^=oq$UOA*LX>G8d_QSTX*?3D^o))HZYjSj}>>3(%1r zHo!+wSR_P9GWGZMLloGwFWB$vdWnPX z?z*$xPn+%$On>`)d{%DWUMl?E$flNpzN5xHWfUCJFT$26;%c0WRHH>aBwFi31th9Z zdO2wtt}@h|@?RJNm=-_hYo_oO`2RGb`2n7=5fG3@2;T1ND-c2bjCq}f~E z73*p?3w}^Zx_d*rZ_oUQ{cJ~49w;S%)QwEYI1s-D2D!z2wVZ2|-~FbPI7BL@VvUnY)uFIdl!GdmGK4ZT+8GJdXl@k>V z@+Ndt!PDlsnMeAem&v-aAhr(mmUTLgKg-h>g);}bT+;&>N8r91f=;9Hi|0@qx(y}9 z{|!H(u6NhS&h!Da?3exOKY|NWMP;0pKMNb`DYB*r`hwe41p_ghtRpC5d~8gp?+TOp z9jiiWX69?&>?6bLeM=~%(HbE)MSw$*&6u(pl?0H6tzfIwAP&*%X+f_S_{C8WTo)esdDOT0M&}Rovhy3kH18&gRVW!i{QBxdq#X*R6ug}?>Z;Av zPkK_Nh;aDkmAgb1YzJQe4MGYpEqXEIp`W*N8A4-i?!&Rosd~FOMHH1H+LtrpT3^xxVaCMjJ!No4jg{Y!VfO=BEM8u zB)e_)DM8+pyK>442J3Eq24~7(#uYi^tlCY{u&f9z4&#V;d47gSzr4XyiyFY;a}7oz zT_;!BMV;{^kmgP;ZtCb3@_Q@y9=2QRPp}@K`Tm--mM(3GK<(ZMw4}Pu!}pv)jKqgf zVe)T5bAJ@?D6=ei7skxqEvDt&cVmE_@rEa4DoF2--BvqTjZn=hdpY#247yECTho_t zN#Q8{cosF~zkwvHO31+n=0-w!Oz*n3QV+@_8PP9lA)a4XPDhc$=i-QET*=}g*b-HI z4@xQnE|oXy&R*TeRze{QK69&OEnd@A|AHZ0Dl@~FYwhUF`z3q)#BXdG4!I}FmUP`i zPOb2V*YH)K0)8lccaFMNI?G^(A$<~3{gj!i!)AnWo6;fX?@o(JKH153e5Hx9<2i9n zj2oFiUIHJ8O^yb?@l4-M)R8ql@LqWDwiy&OH0#{5n#i%xnNO;3NHgMIf` zA>p)6b#q$Qv9BTzUmwPGB=VuHkCdql3S~}fOPZ!otbD#c($;T5QRz`A}F0$Y#g#@p$-5l1g@l zd2Bzr`M?&tFD?lT$~GmpVQZ@Y`CY9yPi1wC9D#bbbPmYTcMDf#UN1t@A&(}3i|+N` zQ2M4rI&#qt^43Cwd7IfDIcYlHaTS%WZAe~FYysUqAM;*UT4|lnpGvi1`jeaoU|+bLUIYw(W41!cCaY1gu9gIVUT2X!LsrOYg5os3 zXRwHFa5Ge|&f8FRCYw`zez_|o0)$KR`&XtF#tzX4#kRP(r?|lf;lTkID@hal2L2$Z z?diX8I8Ezu8ZW_UL0|kBHiuI8`!#7mKH1#~}N-7RAjw9tpIH-y&i%M{Pfs`U;HPeMMKpBR#6aY<0Z zrI996j_cmL)84xXL1o~fI1EgB_O1x;qT??Oj-g+D75kDnrd?>^fy&iLTT?u@Z_^!W z=|E+8+W`ehZb+K5-BCqf?0HCjRy6|n=9)!ufVn2sAaz^i8Mv8CJN3?^qen$O`RtPo z|DIh=OU&kU4I}9|l@_I8(r95W_v9=dyzmS-nF_Mn$ zEvz`J2j7zRP?6r_R#HZP8CIhIDuFdj7|h@>F=vOAnKSA1L`WOXs8Y=BCHp$7Cl#jT z9BRrKe$!8u-M`A|mUfPCy=m6kLWEB9umFaAc}kl**@r1<4l8I_v<(uZ59mML>2#%M z#uN7(&l5zko?XST;uI~04UA1Ux??uwBQU{n9xed&i1%USyiWsnc}h`idzCsX{E~^v zCzi`YQBc>f%~FZxYw{CmN<{{z+1oxeyJnHb#3=2Ec{T)q+oq=qd+XIcl)5>GW=wI8 zk8!WZ4hzuLxomdRFwk?1)bN0}oR*naSdu zhh*&-L4xoViM`FGEpLYgC|Vxv}QO}LC6dptW~fsyJw)nO!=rvploRM=!x;%wji zUQXKV;x2U2SjieCYuZsD;Mot)%Z(~G)$$|XDsb;Hf5iDXi>WUx8L&T<@Qn25QHtgr zPXl0#60B=awRD#FaW|d3W-~1uvn7h9>b<#jPGJ>HcW4qIl-bPaR)QhW^aJi~3F60-2-f-8N zvGnFuCGGSo1EyMRxoC>!F21xBeegn?1fEM;A)MiM8`YS&^pLf76{+Sl@Kuwc%Uu=p zW=W|cPsp@#i37NZhGMN<1d zW~B>5k_)ZKn+%aPP~36QDh(}-_p|}uthc&Q4hK#T=L@~(8Gv^q7uY9HF3u} zyzAUn4R>b7lOKg5M|K~pL#VMDp4a5?{Ws})a95yKBZ}S^vOsJJrg;@JCa#bSux9QX zK+mWaF3PoG|8fV{7O4I}Om&;SpW~cS{+=F~v`k1Jh%n~DGhu5Vt*nGdSaOx|Da+)8@ z@iVfk9uKK1tttqs>8vc%&_P)sH*J((j>&DS7-?~n*o^i> zLGJQ?zewiaN*`yO-q;3nTT2R&hTA*BuB zT5@8rtmvq}Ox;1*S@h$h6iaHNp>(j1!egRm7DLH5_m)`Ut)N466}9fSV+~g?C4R4x z9OCO88eh+?AIsMXBuKNun`YJ&t!@#Ea1A(!?l-qFi{fne)kj)}e};R_^+PSz+)I5a zorTL8Cy6WD6j;Olb9E8_9D%Gh(_-90wL8~UvQ2)nikOU18=-6TyUoZFm$D#BG2&f0 zEKW%Xk)$5TV z@&4iQZw71EnnEUuQ)3*lar9~i*zGndMw3Ud3`uWuJJRw(9v$5M^fH^~*mA9NA--yA zA^rXyR{Vmyb7A(NO&vN+W((UZ)k0e<>K{W+f-&(=hQUjJT*S72*Cr+#4g(Z(VX`-c zb<-mSP4FE(V84^r<7pE21Gzt}L{$Do3wl>b2kUc6J+c^vVU^Mo&(B&{1G;08As0{^ zKjwa#y1)m@Vi1|Q(w*Dd^HJ+N-K;Vy zd959bf>i?_j2&Wm{oXQWE11QDX_k0J%vDM-9*0LlwJ33nM0mMkdZM7j<<*8kx~}9k z4^qKL`HJInj+t_PQB}Fz?idh))f-5$D?X%}q6!_RnO-%vo2~$cbg}`30mva#>Uz5K z8K6TZtavMLI}_z|QxxG(op3M^>&z6;A&~q7$#5iiqhHLGmi=85u}H(RLFENONNw3a zL<(Aqqq23#*}^ZwRDMwk0k&^)(2r))Uaf=DS((PgM ziHTnyWRILh6}!~x%wChw9MSV-$XOZWUbut{^6M0T zynZtTy(|z-Fm|X3OJ4SAX$RJkG&iz)c>vnVv|o{ohfWtPtN}?UCu>tIFISPXbdxHD zfV_2V1MW+2pl`+ag(Ba%VgIcspqp<6XU|H<9tHH~MlyJHx0{pg~1?(u9%kkQCgDHS-Xu zX)_e7KAZx>>!NUw${|!*28V&h3vx+&GQ;V8<#D#QRfb!31;@)`JB%j6a`=_FuZZeH zrdmai1I*jl<>?{WTtdDht{5tU3Ae$#UjbK@0QoOcxqX7l{wWU}Dsm50EQ5D~w@n^Q z7FN0~W3$pMM!vhP;7#qb9!~NJ2p|oXr?cncXw9{dm+cY>uf| zMmJ&SiofRFRt?zsH}r?bC5E;ZYw&~D(xNwl%*+X5f%*0ypT$6v&o;QJ81GIHhql~$ z8$YlVB@aErKahUtC4Kt((rchMpx@Q5M|YodSrYc(4XZ;WGPc++-2`S%w2LTKf9}D0sDSC~af}Z1zHnXo?NEAX4oxB`7glz8kWHWpM zau!N5SIhfmKMT4wqfi9h=rB@rJ{68eUu2i(e%<>k^qs#PZeXG0YmC8TDV80p#)kUN zgUbn5U`unL#HAohO4Clwv{Jc+3+>pfu(GWIB1EhVw#*e}KY6g45{8H)FfQxV5O108 ze~N!lFi;aEKNLvPCmWjOb9pItZao+g0CtLne?ArdAO-@mq(e564mmfeC}g?fLZO@3%OWEdd1!-m%hm zwyQJ|{t5r{ucS+Ls)c)qijTWAK^R9rFBTWUvgP{dBxWReH^EPyH%>(tA(mRZnwoAX zr{+*rtG4tclF8f`i9LGmqrx8=Yq^tP1TIieZub{ZjYK^mpD^^KUvll7DGo&VTyD#? zUSRIU9Jk8S7I9DEd#0iId{1xCBkAgF1zF*JAkRx4W(TJBUVJ6~SUli9YlAO+2aF`= zIg-w&@P-bZnj^hi$YyGOQ~NnQGtme=i6G=n%5&?Owkid5(h&ni%I6(-Y#EM41BkeL zrcNYP>oDSKg;#o1Uw?o@JHL@r=}{IM#adVbPKIlYpu);@TqE`j8LIb7P5LN#<9KV@ zPDZynX;$2tTrsIF-(gARInbD>T`FGexf|vX+J5cvdvu{-EuG5=J!H81f^yjgF)FjR zb)!3?Hm2%;ANB9IX1frW@FaB4*5r@VK?U`W7QP5+ydWiXqwC`Kf{)wcIS}R7xhn~L zPHrdFDg-^rqWa&t?H?CvBMO2~h_QZ?h{cHjzTQXN*0?ZCJZ4|S3bAYKb{5}qI^3qD zCKrgFYGV_(oMoVb^F+{g!e&Vjed$`oCaV&oSYL>EQz)}2iz=zwtH3pD7?x09q<-MD zG!HSJI}ePajBXRDd}>hfj@tpijp4sVNDrf4FtuNHgP!zqb!`}P zoTuF*Sj&9Plc4a>CAvoBba-wXig49xL4jDxpW<~vIRuAiru*IoGA|yB6GLP0+7`q4 z!aO~qJs+s2w1`ZfeQgDak}Zk&za8Caw8~~FnL-ix7Fd@M4>%b(okSC?d1=?Tn-!su z}&7#0ex-ih{kEK zT{0RGtVmf0tkP3xN?S$37NztGj@xerHhJ)=2uA`1VGU0p!?N&;bgc-7y>>~w&%?V( zn-=mL&-{a{xGh-XV)~Uu`tjPVl{X<{sM-hoNH>+=wnTVjwxSq<=w9f%E;z;SPdk~j zp=16^lvm|msjgb7OrkAuMR?i2KMvK-S~^ENmE8Mf=t{O=TW_hkv9Djy8_LuRPY8KQ`PQ{jkz5l z?Z7{34Rs`RH3XxG8K+g}YAv5{m~MBh6q~TC0k)c^uh}pnOBcQRVj)JJe!4aePj}#(sF) ztZ+)~9(>Iqu-RSiG80Y2%ItorX0U$cnRq%;MkabyQmSP(IOK1?!&%6^eGiR@YVa=2 zH^M`P&Wt#{dqY}n+r}B}|V@KV|mw-~MlXtv^pOtx| z=wDh2*Gk=%25B#r8Vu)_-5OtlALBO*Q*m zQT&cG(l(^@r5T>CE{+(&fX_c8rDU(k2Za^n;-b3!=+fmHwVn|v<4>NJH|YJk zw#cNemhetB=~yAFTGqk3kNZD|i+BAfWg|1&K--Y?JTQ&?Qc& zutBl81b19Ce~ELy>;FsmjGi*Yrqa?Pw4+JyY1pF%et+vGJ!aM+{>R(Aghi=l1|jKI zx$S9@NMFHC1i)E1T+aa;&*YqAd-a#jcL|Ey5$G$pU9L*vZbj=}|(E@TYB~7IC<+kI_dVr4UiJgV^W6cO{7} zT39ZPG&{zq`Lqs!zceXcpBJY$fs{{y>;e8rSDvwRNt}^xLGh(6c4Ykp#E+R(-W#TT zp=(z(YgxAy$Woe$e{zSkj;AE1RE$e?UJJl_OsA`J{N1hPoiuC-;kI}#vby^$w?a^# z@BOgVeL2O_4&&B4-AJKmW^8esOU+|N&bU80lBla3{U7|QlY_ym4#q2STRSysr2FK5 z=GvPEKw6TXONGWjt(O&~E_;%7nQ-QDhQ;hpEGh2;>D$SK*u$GHk4&(_bN1*q6xd(Z z1Nf#{=Me3#AVuY#rT_Huv^qq@izMZ;#aL#KB*VUT(-P!q4$CaXf&xu5(tP@s#-o2s zUBQ7E3PI>~Acp@yC>Kx=nU`jF`|ymPtA$kMUJ z^7j2Mi=}IH;~-bp8^X?kEHy3oEvA%`AVt3jmUdaHDIl>{gjJ2^`9M%gikD2_5XN!EJmvj$<;O zaRjx@PMy{rfqt`-??5oE^C|=&=8DpH1BYJ+b-_<|K@fvQOCxCjs8!j@0*_X6JPDrh z#^=099%{CH=`}uM;Nl-1oay))doNz}SK0JI{|^8wK-9mIMiRT3kKMpUy_@OMZCxPV zGXyHiNaD+;^88V8%S16zj=rELv;s`CZ$-hqglns}df4iy+2e~6hZ?=M!rRGKJXX1m-VO*o z=5k5^@?pWrX1aF+kNZ;{86WSPb`Q^IshT9R?=Kym#KlL33IsZPf{6$nNWJ)!;`}yI z!XoBk?7~f8f&Wq^@ROw@r8M+EnweZBGwdMkl~ZHrZ6g7{T(}_0R(5M2&joIg56C)9 z3cg_Bf7fX;%BVH++?z}D%S0J&{DeSpw^%7eKVt1_GCIQH%H^o+NCeh$64+iU6*9!j zRp1X92dun){#vK%hTId{MJyD+AyUCfgJ?}U+vFArz^jCC?mD@2vx z*J|I7@!2qfU3tflTn-S&sg2NXaS(=3DXnR%2_t5o=xu7K^E+B+(G%k;_%6*`8Smpw+U)nYlJi5QRHb^yd#1ap((3hMmW}5_wWt_RWzaSErD8Vgfe>| z`3c(-+?hnSk#rR`Iqba|Yi526YQ=wcS__983HvKm<-}e3vAP@WgWoK!PZ9O+=Y59e zfn1R5do1N(|NCj}j|1#R^Q1*bl92d2xrhT|bgRY<;&aP~87m?Vj$ph1&H1RmT6>-F zVu4jr&o|8XzuSzOpnhyL5GW1)#BJlcrI~qoI?7mRPl9&=!<~cHjYR>3(OX82JK=t> zN;9tcLT(W0F$-7tP`DRU4SSdTAS*ppu7J62Vvz@%t$b2P5|kC)2t^{qslK^fH+3vz zWtJ}Y{e2`90D1SWOnH)FZ`(<`ac&md`)#bD4)%bp?Lx;IX)TxiRdV#wI|^bC8GH+I z09PLk-J_G_l}$bbhv$jk*`Log`5c)A!N~X}nRIJzaW@_Y52x1PI6W5~|Np_VU9qU~ zF|#JwvBLmVy<0#jCc9Lvh@q(zfm`wLS~+0-sXl4xrYCerO;yi*R%Gm?3M^^ z^(2BF?qbxQXpMm-#^0#VMS6?p+k zXgPLC562g(Ay9^wrThIJ|6cj{yjT2Czynp$pyF2ym!xQunH$hwwFf=B%Luin3N0Ek zL7Hf@#2fvxfB>REtGooOnl6Jl{Z!IhFN_dlIXRUO2k^z5xX+uWvY;4hNXiHf2FR6~ zWx6u^i(%85wa{y#97Y0yPRhWqqS=p^IgBK3x2Q6ZLhBq$jXAG|MXoetEJv(uvz87< z&4_{=TLOgP76lA7ud~<$5L5fFfAlTgmGpEYY{wwg#Z$I83n92q}f@sfC~H$gO*9ufectPMD!I#VoDT`^VW z9l!U3ncrPctxNo2B=buCPpoLF<_9<5ehqFo5>rcL2EM~!rt6k}>cEA}a<-S0zJ>}o z0od@a6HDOff)(}Q&lsazGHNhW-i(`OUsNf=Xs=lqm+kN|XhPoHwJvpT48Y?%Vs`I1 z1%>nQv^Zr_pgNdGP|;pN&B<);d8FC1Q?33=mg*(G3YkX&Ra9k7Q5X6sT9{K1>hCJM zbajn=p@PvY5OGeuaIu5?Exwe=!;OB4YuWnJ8JtD1gg}6LIbgQoBTOv#7blUKx$_wE zp0~%Nw%2U^M+7qb#D&clmaGQHTsw~GKT_Vb_*Dc?5TV#-p#$wxdtDE*_2anLoAoU3 zfJ8o4@O~5?9IU|tLC`hA=iU_Cr?LT=MiKa$JmnrEoyGG{oj?+>U6@2ekB4D`L~u$- zW}{dWQ`@>sb%NJ{SgKhp#C+e*WkU7EMFgSQ{ryQ*1U~Vv5-_?#9uiRsII*hH)l8a- zE$Kiuc@Og8TDaNVm{jud<>uV12q#iyM-{7vP|x4~yoR35Y!;UGLOQuhNhC;{mFtUg zvYq$_btHfjj??{+xf0&^7vIs?Q4ji1J?5MtcPdd6n>875Q0yxCRwIGKGhwvlSVp21 zzv|X`k-p_?SD&Y_vZcWR=@^-PbUylb*vzn$xmU5x`}G9!gc*Avd4RYo zAMOev7aD0uHONNgwz!!tk<={bo6uMG_)}>=AiXS7C79Fv+(r$&kALa6KRKrzpKxl@ z`KA$(c3<*V{IsE%<|wZ2^^SP%ivV@E!_S}3z!O`b5*vnNu5zM%S{L}D@n0FlbLZRb z|1P7hp3SwDI`~JRJHOQUpQk;l8*ozqp&i}(Fx)Wa62q3hF(wyOAyeG6-PifCNZ(8q;|Hhzh8hZPY`xVDPG(4dY}L>p*Bm<0 zi2ezf8HfMMV+HNSgIN~InA>$HsD(* z&h-qLe583!CP4J~U@SV^Okr&loyaBL5g&9!-zwy0x1!X!2|WbJ zf%=M8p>waMmls-695Soz$zOv|eM!785<$v3> z%to&4@&3Au@oyK>*k6hZ||dAMF8aBMjR z;H&tC{S)+Uan-y$ac;@Z!TDu4bXX2#$VnDnVt#V_N)^YK>ViZvR#+>kk`+g@13M6m z4+_Mk0oFB5Z`7BuO}lgkD*k$YE>k-m0 zA*NF9`k2Cjt*B|js)QdX{4mzhlSz|c#2zfrooOb0u&!cN*^{|=>gV}c_fSx;CDnHaNltqrhpezBds^>*E>-@ zL$$~dl>T0Ibsr|ZJe`R@fcGl_vkcN_8`+r#1y4LQ$!Fn0;2M4$Is)Fyo=NZ>q{B^x z-1YOKXq7>?)wHx_pTVeBwDfTzIWD>JceOF=olK7`rVR#K4E-nxf4-4*vm9ch2;IQOk@#r zC08Zu`r$xv7%hEjGy!9)XwLRCN}_#n6i1}0^vlh3FP=VqcZH? z?wX*U3Mm$(2I6hHL@-g;22dMZiewe~9LoSkvA{>6fmd@~FgufHCPqKIsd0vG?}dl( zyak0=Ma=p_eFMrz(QwY4O0K2s)Tc9A9}2b6!5RD^KOmb5Q?KKri8giDzY;DOMNaBgFUNZDe1O;0|# z%Y$JkH(sZ}jdG)(t$z)60`IUS6+Pq}^HvT8FnaaT3N8oZ&Ebknf8(=E(>Er9ns~_& z=-E#8u<6qc6S3e3U5pFr4lqDZPq-SvTP1-w)m<+PRx!|Vz z2y#)lM(HD7i>?ZT(>Usz=4(zX^RD)EV^jw!hf$nvuK)`kIFLNDxs(SL@)iW2<&OBxazWW1UC!v+XC3DprYPh?&dgdIcGBqM^nW9i9)UX%i`6hU zVt4z3=@ns;AwnY$_hXqU{X?Zi*Mza6o@zd)_XHU`sCHML4UUwN{TsvFNV49zn8tks z=Gi^Dx|6(0!95fHr@;+8h%5tX=k@w51Y0i5XfyFur$>>0gPIj0;{nYhG`;}b)^?!~ zvKrd69|e8u7SI)+ez(QjKC6)rpb(WdLux#C_q9)KOld8d!DM;gO-Lt{#es5%CVaL^ zgFg)mTZ#-C5Q1}!0z{n40X~-!ZUENPeUw{jlpTr>AXI_WeBC6}gJjZNY+f1lSOeKP zkh&3#R~K`MF?1pQxUqB_EuC<{l9bSc&$zYHU~@V8^|8i|0;4B`2Ti_k$HKF)0kScU zzoKS>FA<9Cs`7DwO+D#3i}6D$)l=kvcelQ=BT0pKu_77K0VixHd@umUlefv?bC-Et zA!l-wU2d8VO}6Yn`TgMUOcC3V8^w;XTE)U&-%t$q)6IaR}5X!b%1ri0?Q~*kR zIC7-O+PpCq!}c4h1_rVNTBJxL=vs8bA2`-y&4o1US4RW3YC7Dlihh?hY{-Ucttk+K z%;61Edh!tW-0tL}Lus2+Dv_n=pj(t2Imj~Hqb0AW$ihAw$|F03(FF!0+sblKO}UE9 zr*eHJTX0yr3e<|xNL13^n7$fuY{+}2^+H`vu0v8UsKk4Y40}@M8#F#%%E<7Q6$V&SR6PC1^qZ~WZZaB;3({Vd3 zyiPMmICN~g)F)Z0rAVWn<@r}X7UN2ucf*V-mu+BlTYb5MNp}m|*X1Eu%H}}VkkA9! z^FvVQCGeFs{Jq^8#cUsYo5BBtPTLOR6{H)+prquSlyWGynj;P26DpWu*sC@$){a4{ zA)WV4%C@?!^O0h~^3&5yb((s!S#GGk;=@4)i=Fw$t=g2xB1h2Ohcz8Rer)L7+9&A%z84Z=%{RRwp$?U)gtN09z_R(gfP z6v4b3LlIr(yXk-CA|w4x(Vriypw>r@BLLfYX>#3Hi$=_q$_BF;CC(j?>fRmG-(;#L_OV<(VEL$tuErV9M!_vgNcz# z?N9)VzeD2y(})vD;ME+nCe($O>!5`>xSvPIv7f|e^oP<%;A~l0Ci!H}!ZX)lcPwU2a>p9Jrj^N8cDldOGF`4<(kJ(KR7# z{h6xWV2%2V>yX;$)qn)vD)0Uq&Q9*8lL$^UK<49kQa%U7y8ooFIM)MYX7r$YPKw49 zRbQ;YJLUR1g|FsLw?wuLt+V{gju!@K{0u_O`(R05(Z{u9Y*&_DApwq+J+U$b{& z#ks9w-1bATE7!XCAkJ1W|IUyikg6gkFl#~kbZ^M@lTqKhEbDA?SkR~9(o356pdf_= ze*ZI|w)Cx(I11)2@J)D!f@_De50-yj+H%0>k>^@l|Dk0gqK@8UCq%v7+Q*WZ3BrEV zO$ZuZ}jW=Hc?_lIR^j;v5hyQ(mvzaubg@bn`{LhbhBSM4PzX zg~#Jk?fxNcl1x2q9EN@WUjFu9mpK^fpQe)HTXySP^Qo;#DLjpfkcZYldwu3^$*4Mg z?Te{Ur|igg`;^jx6f-5)wswBd9pkuM-E?QWFQoO?jPJ|BPLZz+P1ICzFpfB*B9DHk z$QvP3P{~mVa zSR5#7n^<#EXY$pkp4{F}$mgkX0`W}T7tG5~W=X*mTy2=o zLXDO^Md`&_VR~^kvOWQ$XgY+@{gA{f0-?hZw*QQT3v_G1-vxX8f8f_mun8 zn2H}$HZ%MLOmJX6-suFx6EP>k?F9fQiA9X&R;D#GMl;mEjOZ^2SZs)&8fJJTrw`}s zJFWy=e9_89l29}Xdaum1{6{Rbh9+tX=;W9{(aY0*2{u}~i)iH(@geXb*`MA$igdux zG6=!#J9aYE%OI|gFD@7z+?3qu4HWIMlIF70&sn#mOeqty&w;ghCb98RR6oGn!!A#T zaZ|%5HWXUhgM&o>d{XkSS*Y1Zk^m3sn{Fyb;9L3Nqy}IFBD_U9N)jaVkaliWjG5ch zvnv@YW}cp&$;mrnv5?kfSvko`WO1^y8iZLf4l;)EghmN%dEKzR6=IVGH<3Rk42-!p z-glN1m3<7SU?b8uaA-raEU&O}M~&}lL!dV#uc&xIq+|kuayxgE1e2wBGl5nWxSTa3 z26q@g=TlGw&tu}zCVGF2#o6dClU_ic>A@6IcE4JBWlVWKVo@{oluCX@TA z``MS=Ltlnj$)ij>R*{z)QAS6E3j=r5PA3!kk} zc(?#=PLs44eqTTuAc*Gbz?}H30zDQUL8tIW^^7Y-Zh1eliMrNWDdoc|iqJQeFiY^U zSirF~e}u{G(S6K|#q6<~40GZT_VG%adtKLy1UH=}3GyhRYc04Kg_^Opdw~Cc)AzbQ zq=J!&SG%J{`Tb{qfh-wgq3x6~FlY56+uEZM#AAX?`tZ=6#Cw|FNqpD$1>5!}EgDdl z5HL91q8z~OX1)e)(5S7%&qOdfu-{(iWiury?;x zB=PYNxTZS!jP$uxvPy1n$hHY5Qv-p6gf8DMTT9pOZk89Q$kE+76g%OOY)I>XCK`{c z4`qyvTl<&TUJ6H*@y;|fOzwk=k{eRB+@Vr6aH+>Whvx3h#<(6@g(L8!J zreH6gl3{Wc)yLH6lqkGfZd#79QVOP5(Sg?N2j8QV2)m zPnEUP3s2(H2OrqQ*RzbHZ^(A-_$jX9*D1~i{#q26dkFc34c(^=2;RaH?xN%ze3S~& z`WOMSE8hRNzMF8yHifv_*0gc`_{r$=@6AqW6%@gfNXC}z##y~o=Wau!A z-PxDhST~>v5r^M~4zU_d_noeF5Y={m5FDx|dB)r9+>Y!;JkIJd=h<{m(q^~$OwWZw zZtI`j9ZkON34$>hb#N3v=5<|Dtqb5x@wa>+5}G;Ufv;xa($Rts(^N4;&QzS=i(jcR zS-)@dx)dH>gD{?Uk1!tNCHXXLib!2BvLmS`>=U1D_6XPD*GcGhdjcapyg!r{0|;J)xhV@PnSo~-%6_Yc)J+Q25B&`t%>B95&`z90a^+#9=j{8cj7k}GxM z_z_fT0;`GT)5oOn39U|+*!e>lwS32hj!4vgayp6WwIFfNm)X`O4X}Y#JsHu7G$Mm< zGcA@L?tfQ9ZawZ<$h6*z*HhgD7CIOJEcs^?TO~wT&bd{fG(tQZ90|`HS?^IWJ$VG2Sb2#~#so1vaGWi@KJkrP`;b@wi{n zXW#qG{4n{em*|jN>Wufzk=#+>W@14lbm?jz&jmzcKGA~lKAPpVI^?h%Pgl`3Ae~Q}^oF;I6da>V=hfz`U za|hR$rrT`3d*4G^2_kW)+VQJCs%zWlWf>xUFhxYH%7%XG^A8E)!;2Z0l|(1U-CP;T)}VcO-&(bJ)2H z2z|GoMziB-4@c(lkWF^duZif3pO50b5zyul06whLW{`|fvRWo1Q(_~?Zye>3n2b~} z+}Pd})}8Xzug^|9LL|w{3xGa;ni%l;t8=PcDqAruN_x|H4h85j@%nb8bCIOLu$iY^bPFpcNQN9g;R zME`FY`3RSWsB!hdP*l~)rW=tgpqc%KIEa$SlGZ?nO`sFv+m-r5$7?Wl^Xmm+Lr>E+ zOah=#d-|*|g(lB$HoR5=EdJ5e;d**=L>pmX9YDmmNTJWp$g3$4mayM;bp&0C?rVXl z#iR>;4&}T?xxdI?3izt;^l>OSR;;;X9<6T~jICbL%xPHPC2zLs-&ko-8t0ep0d;;rYs|g3H=#vwbZ2u4tt0-iX-g_jy8*M*qp_V&YL>`ufMV)b0 z4+=)G;HDVOm)Z_+Yvx94H1>B&+*^C}@3EC-P@{jJq&TZ-eEMdIG)fgIm$c}S>K{-B zv`7R@S+zuhqqZ`wZO#*G4N4+FP{v#S@rC349H`-v8<(d_4yAj0MusRxu)(q#JXz^# z48jYdZx___xR&jwnxJiSq01^6vXb_%b^wXWIJs9=q=5O-y{~UZ_#LY?8tWiO_5lw zB6#X@Vwin8|3<)d7__*oasHeduUoFmGY`7rrZodrP2zWVMc-eB3>hm_V$J6dqC&ri zsAdB~cU)yPdl(BWSk!y^h)K@jzwq>ezE-R%`vrs7x8vn(#dosHt0*(yJ^K&Xpbvkt ze@Oh~ZJ59cE-Q}2B;hlKT)F)m?3v-pRj)cV7Rc{M^8XBrm7)0)^7>5Kpaw;;B;nKV z=z=srhKWR~(W60))-W8Y+JWU-u@hw9dXZGBj8J`^nUjxR5Anw&_)zk@-^sZ3qMOQ* zE*e=D(N6tmc}jBFskoGIn!H;t@cQUN5s+Vu(cmR8_{8YBb5`gKLKTw=wg`jlyg)ZV zoLv|?R=Lm(1^=0rgnVJu&|E7bftGc)}1;ZQH4`*BL$sGwVCp1Ja? zayj}O&zE0sUOwGVy~Ry+*F`Iup3(2(zpXwY(ly9!-cx~}U%7|AS4lt&iU~3l71t_u z4qP|~gKf7rba|kO?@8pWrgN$tlB=l%@Hw35jy;8{Y#ceV)d;PW zuve3C0P~87PutY_3!|;b(z#W*WxxOxa^8Rh&T5ip0o6FC$LA90r}!|mAMZxw!f-TPDzqE+ z;9Utg+w-F_bi0m=<~Y)ygD`Ky+OYQBs(5pB?@2%@t6;KPl{9DNcS4B$ z;xRGV3$%u9)@R<#kwuhth9`uBCz^3BWS0o?85g;kiJB{MHc(}&d@EPxM+ zuPlpt78BxUX;C5AYqZ8pul)A7rgsNX%53Jlr0A!rS(&q*0&9*h>)-W4r-$}3xqtMk(MFqL*N^Iv{O;q5AAsWjlCU!?_D8TRg z52`?6oNaBP)ggb1`}02IvZI3f2uA9ecEtYtXt&#e9<`!9#87YwM4yFy^N&D0A~TYnZR>mU|YdJpF^Ij+nEuwSuidzh7XRd0aC}0-l*|NCYm#WG zd(L$Jmz=1GNadIGSq{=t$l`|bV%oup!E|Q(Fe4YqoPXvs>FytoF`m7r+pqvJd)a8~ zcK@?zPwD-*WO6jGXrH0VC7%F9_UM2(S>WY#l7dcm(I=r;*$a496Fz4P?Czw|3e*(p zPCm8gGoJNqJte*Va~Km2#HcjY`~HuJgfP1u=&y|d{Z`kdy(^ZMn(wKn+ageRj*;kY zz=)bjEkTI2Nh1wUxCxC&0|hOq@mVh$V8UI6AD6~BBoNAtw3bvv1$8GX;Yhor=OqXs z4OI*9SirUR|IQHurBFd$0ntE zP0{r4gSac^*AaTfWNaH9V8Hl&YF7UNsVC?40m@j+wdeS2h>iW-LGz4L6mLD77-Qq0 zoW&Z_44(QBYbd7UK?i1>Fu3W0iUiQcpxTWF0FUqhy}|pql%07AZ^$3W%tJSVOH{IC zl(=N{_O>3Y({0)=j5Vw5u}-+?@dr52vBe#v$hJk@8Ezs1NDil!cQdekvYT|X6IC9_ zrBa0UA_mtYN3Tf#c99jm9IBBVQ;H-bY0H(G zsfBP?{4Cj)U$0)_;4);!Fh42L!}AxK~BS@s*{i4L9lnPy|3B)}~6I9FH|+rAH8xb%;T>xyew&H!xv zl5TD?@&k(AjBj~T*VUy!H{5aLji-%(p3gSYR#__6Pe#d-n$q{P8uK5BazygGAqW|R zmc&rw^!&alvo>bBqjx>5nRgGBCSRydQ%#^!u8lezrf0l37CV-?i8J^=f?vL{nE|h% zYZ3=MW z+cKjwn4t7P#d#(nb#1J#f&(->zG|}kjMP!s1@M;+T!IyoCfGXK7R!UWvfBIU zEQxXY#?cd(d9wy?zL~`KrjNF~lw{ok#J-4h%EK{zCE|2DF^4={_rJe)AKe|JNlIoj zTR~rTc?&bjXB*t`JJG_@H7KeLB9v}y!%mBiIY*^yTt)ZGg;8dt(~{24?;CGfqKJQO zn;G-?gMi~4kb7H3rFE8W3Q9gJcy(ZgbXkeR3=(kONvQy+SBaUfX6AQ|1ZmmK)4PAM zoqumQ#;~Do>nPYr2>EA^(CZdlxi0_xU%Gkk~_1 zyNIl%`zNY;Jezy@q7ucUbkQ9Xdy8sGQMvGAxkNW0o&P>{?%H{Ol0{*}F8_{nB_1r1 z$uTws^~;{(#|oArqIIhrJW5xSNH1kgpx!e2iyv#RWweR%=(dm#hXhUaOx3=R2)iJF z6;ki}#ENtZil&9_t2>e`>_k-UX&Qu@UV{+BSQ|*#ztjF_MM;tS92m=?m4qOT+7B3o zxMckY_lqx+RbP}J!-$7&MD!2ZRe0UAo42yM_FKG2KA3-(>QJ0!phTREQ#OIe>3s8g zSDH>`Z_gu=verf$(F}i$WbV71b!{P&sZv{8|Ks&G#eo12+1CL-IG&PBa{V3uA(nCy zqSW9qfiNpL3^8izdBN5tf03P2Fd>Owcy0m2a7&q~C6edG9OPLA{6>kOR zGVNuVOx3afBz*Ez<{qH?a2V|r4};}>g~In}0lqU1&&`B-HGQ2P6%;Gdf%x+;)d5)G zNTY*}h^8==(J5@$!V?2PL#=agQ5o1?YKCxgLMZ}x8B z1C5`3nbqD9iTwt@WR7@)0oU)4XRnZexX25b_5K1NKi9;jL;Pz1X)3^XY-}01{#-ha zb%mbF*V_QnOR*>iEs zoHIqUGt4X^-Cs2+J>)_nRv$F1Gb86zJt2Pxp7JRIc&-dTDVS#wn+Jf;m;|0OD)_%^ z>a9WHhVkLxRgumzV~gtOy`amluy-3vS9ovya+-A1x8=G2n42n*yrkAaFqKS^bPy-wxc zH)Movy@XK&?cF=fG#13aBH9Y^3Pm1|dXFP?xKtdQeoO z0mj`Stj?ZE$zC9G&i+{%B&3LKXZAj2UYTKQ?Ayeg$ZVDGK>xwP9D`{FTUuX*6_8??el_sGjx?O zSr-l4xb@S2RwF6U#TFjFp?cE6DLfDd9y6OTsI}&&sg4t>J|#QAqVdHg%_zb%(8{;x>e~dW!Gp!iNX$acb=A;Ljs|fwfOpON*)k0BXDOa(MeR&{b_yE(i^Y zL{_4EIam!dm<3J+&F5Du(v06rV`^a#OMGuGbhU%)Q_&=2$SU-Y8P0EA-x$^`bw}M! zc}InA$ZP zmOGgUUJEpF9-Y)dbnPQi?D%*UktM){VthG&+;j)y%aH8re_z!{9uJCISm%k`UmH6N zYU3tT7G)sF8JzhcnOhm?}lvGDVxC|Bys_K~#*}KCGw=jrSTv_pY8kh~pbG zLviH+Mgj!QGQO7w+&#eW#SUC?w%Xzk5k%On)NayFBhFOWL|qq+E?v4(e^Du09iDR8 zy02NDcX-o;>P^sRl`Krz^=_xFo54;H4Dr+Nr@p1)M6iAisJ5`=Q8lB|%rAtlfM5dMiBBF) z^-Z48SG&O#;=@sQ4Rc}PjHubqIt8!&zrWFj2L|#*(}XKlZ%M*1t?`FKe|$#F@)YRR zV@05VT2p`FN^^VYee&ck^9;ZO{8%HorlT%7ePBrudn@crPf`KjaWA#+Hh4<_1M10l z=Ez2BYH(TOGiURX8j$tn(ZN?tilz)>;P#sX|AJ3AyIO z+d$5h_*z#nDw?wnvANPOdm^KO`PSD3c7*u0)+WF!%Z%!pu^7TxactV<* zPY~53-A2io5;jxh{j_~+l34zt&bW@-x-b zwyE^Y^5!1RE8wme3uQUn=y}Cs*;m}vX zG+*TzU?`|-CaNkNxoX4^a|exAADmoNM^uxHT2S^AezX86USI~#`FMNjsCnKSie3EJ z_95`ODjaQdjWSOWbS6dwLf&w9EN(>_B3JiO5-$QWN6ix`fx1Jg(9T)NC<0ie*uTp0It0I zTapceqx&Jc;w3Y)yKG?fE)uZ%J&S;1xHiRmx9N+~iY$zdsa^;@(jI(h@)+!uMD@Z9 ziNM%4_3h6oa*&rfopmbX{Ftj}P(g(6=7@V+W|A_xiR599Hg#9Hqa9zt?X^7dc{s_W z`O(tdVPmnoep>Ax4$kcZCS&(+(EV&lOWv2At1z%JB=mEIHPoGzY#5+aFCWPzyTwRZ zARvD82-<#45I6Gl$>1I;{9Iny`tUzTCt1gT%gv{IRGqfUM|lJ3iG=425XuS4l%h1C z7~;y$TxX;3q1;qWRvdD3vm{L zd*3C@5grkct~>i=cN`*HJJNmB){2oZzKdcm!*f0!;87_IvUm*Q+=P|t`iSap?nN(F z4V;dlsChXb&M#3t<|`D_P>&h1TZH;`f&@X(vp2pBA1wm?H|o##M>H+P%<;J3YVF7G zz@3%xrsS4lY@m2viG7z#FjodD9Hy8|dQc;&^zrSz$`-{nlk8yFp@A6e|zGmo*4xgs4q!4bMq!cNfE&4h4y z+uR?EDr`_pWC%Az*LUq~%t@(oY`a6yNL8IKek}JLp3Es};v~KvxLY{IT;h+Mf(@h+ zWVtzmr`O8H$WRka$MKl^ll>HtOW$__wnHN)@XT^mt_mfYZw4afRXZV(=M}eJ@JM_Y zBc~glj#{AYll{T-$E>!A(p@oFKV&DxiPcgGu-Jwtak_GvV6E(jBeNWiNY<%E?+= zgUrXjLL|f*ou|zy#6k8w%^XpnhCaDksOOy<{7(wY-!CrH0b{b`ZHXDt>K- zYx`kzccN^*dE{S6j!8hI$Al`=x=q?NKXL@Yh?C`+jZAr;Rsnxq8=~Tt|P=y ziizIdYz}GP+HBCKZhpF@bf=84&sz0W!XmnC9)HWSBz+aHJ5dWk5?*sp82FWt0v}k* zoxUo=T3`gPySUJyVc(eS_$dBP9ppg}u#`}D=&54QAAFq4#x^UDdy_ZB|3 zG0!+4vnBKIcm}SDqtB8KyfJAkdSm|hOwiUW!7QAkT8rZs2`^A?s` z&IZ;rzVAm~GtKIAyAIMq1PRWUEI#9I?@+LI1Gt^ZJOcMo*_?y6x@m)*?&g&s;cF2I z0e9?l!D_PpZSpO7-f9BitN|L+hw-0}6d2vq$%%viD%>|(t$=B#$_+zB_y21#uxbTm ziG9)EHsem1&SkD_z4%WV=*ZcJ8m4^0wB3eSg0@3pmuFV=>&Fysclt&2@W4A9a~g7Q zg5ZdI5u7`&dHw|T^$1fb*+N<>(D?eOBK*Q`zSBsh$X>X0x4OaQ%+C}d%ub0;>C+L3 z(zatk=mv@rCMgLM(jdD`duMw|+k81jP77y?J?!Q+yLSi!O7puKzCGvb8*(=Q<&}}K zr|KFTFsVpvh0~ynX{xNS!e?B@j)9af17{K*3WiC1YbsLa;x`^yQDJp|FTlCu91F;` zv`||0fgrzm1LX=1CjOyIu;I4NyF?i(pny*LN5qD7xHgri__xNj`5QShMkoplZyhef z1?RSjv)vU^H-2@;^WpS#(SszmEm^4G5-#PRNJnq3WC_aT9BJQM(ZZ=B*A_OewP0;D z*Oke|0ORO4pR=AUhddlEUoa1k2Zyjx6`w2HSsD#B)dZ+t5f{Na!#+@RO1|1{Rnw4P z6%TnFAvyWYGHYAKo?)rA3;Cq@q=;EHGS-o|0qWa?;u&fG0Kg)vE>p^5o$!vVtuNAU zu%VVny_>d$X57Z{GCWK**8*mJ1#-x%f_Y(TPnLHx)V{-5aYk~PWgy4>J|$qixn+CE zLCahyTS>(Ec0Uf?BePtCAdHY4{n^fkF(Qtm#G9YE$=3P4Woe2Hi8KL)dIC;#_79YW zdZG`#ddR;Ky$Oe^Qa8FRr37Ai@2t46`gi))$l!HqB=2k1jx;m@-;plKrZ{2%sqtRB zu7&K}FvU)rFl-2fK0z{fCs#~fj{?#EQ7exwWdi86PD~*qpQ25oyhaSnNd}|FL9?vVO}%$1T++Z&2iFKId7EIxY6`rMIopBygkRrnrzEk-s0jTy(*uE_ zLF7)|PtaD!=@r#=z;YglQ6S8sLQL??Z!M3TyE--d6cRaqA#&S&DWX!D&$>f-Xj<$C z$Nh2dd*gj8{ygbU0Sp1)D)(Lu1h>XR?aqg)rGqarG4ffJD5iw6tFcSk#-iC6(@Wtb z>6^VFM{A83i|nsOUy~`g!l-&-*;T;VI7$n(nu=inf~*1SC8j*9uEVpLV=AJjJaqPw zq|@+GH-eF`t^I*=Z|Y%hl5m>;Mm74d5y|zDzIq9s5AURPgPzO(leejT_s_c!!XAPy z7ZccajF?Ns8oseI$bGqp*)3pON=&3fYPp5%Qm7`56?nP@Z0<bx7a;9&y zz03&7*@!a${i~hk<6GvLLeu%M6Zg1j$i^VuYkUj~ek7;W119I&T|^rlgCh4m4d<)( zW1musc=!BXa(f&p#$D6N?95R~XCjfp#2OhH!D@|&IfP*fJKK>7;^hyPFl=LrkqY9T zGbh*QG=KB+gZxl601krr7$E2paulOuV-10CwDADRs>Pz_P{u(mbduwEjZhSQNA?WP zyfbf>EAOQCE?dJKFdGL_-2ZMl7o&8~Q_f7UEUQBU?{Fi-Aj{V|jMX~i?09d8^{U|| zqa?!s1LY#uix8Uh75vSoxBipvBYvK#SRMK~hMPs5V~{AYl7+{%ZQHizj&0kvZQHhO z+qP}vj%V-gdsUmNRG*}}I{%Z-cTgTs38sfrkj@cmY@}>^u%flRaL_)%amztK@D`2k zue%-%d)ni(*Q0V2;O-69xNO!0eSHT7kBZE_3+&xVsA_6^AS2;A4t)y4#vOvuigMZ$ zswC5bo0$M2M6ExicLIaJ8N;xs_UpVHZ(k4~G2uNauY~i{zr=~1f!dtaSq69%H*(@j zab)OO3)nK@pTCu7bNpsIOG2m(MF$lV)bDhtelZE@M50WKgH`4`HV_8Xl$4&~g?hyb z)M94xBPacDl#bg{<2({QbAY(c{TH;a3dztZE>7R z4^a#{cI6mF%u^9G+rOyYem}D19Qlc$=$H_awQVb_ie@NGxP#;CyY8H5@*4Y!G$bAM zG;xaTKvjrBfF0oM)mi&Wc^99x{;jQi6%`5nJvNbD&5{Gc4KA;{o35Cf#HbQ{hD6Gl zBSn$}Qw4Y+W$re@WKQ)WK7ozz9_{S|+5-l~6l{ycKI?*&e-VdH-BC~ZEMUGAdF*qy z0vAq-1WR=(*{jpfvM%V%7V~iy=dh@OX)E2WmHIh=x>)1y0M>oVA?@i!ht zwA(}WPdT%u4pG)FTgU=Nq4V zL)-B6asd20PVrWTV5JJ!z3mEF=FGNr32VEE(%V@}VXi69Rl7;YuWh{f`?{58u@83= zyC33er6QR-$5guZV}F4^@F~`e0TctWks+rLg%en9;$)C`e7aUrl;}ICE{J-`cKam~ z5XK7|bF(e{W-1}ZH%16N&OYS4lI-Ln{N84OmIACe($+D7 zIkcI65LymK&V1(~GFpZl?RNY{-$>684;%WN;l3v|%tKblWR23}j8gS{YJ;M-tn+o9 zI!$2ruAa6tg-88_Rh4o8+}|`0s}Hw0XlC+s1OmCeESPV}mWIy{HR5^hQ|(ABBrf)_?=*KExxG>B_3_UY-~9^?mgmRXP=Ilr~4J zJJohKY*9C8Bm-2H%4{u1A(#~Xx_K18=c;n%Bd?V9p!piK^TOp3){8C*{t&4sJ$98Z zM)HWC$b(EJ|3g;`Rek)V*Ofrttg^u4s*#9~prwEb13B_Lp?3=5rdRAV_21 zB*sW7o8VNv!cQu6SkxaUHa@m2e6t_OkfSt1`yq1@u|lF4`;KKZcKkIKUtAlY*yQU(<-VQh)Ah<}tNI3O%))XUHh(oKyKORkNJN5p>yJCzVDP0Rr*rxftT&9g=GE*2?wG zE!!;sxx8^pn1iWGFXr&7PN^>gV=FAf{K^G^Q6&NKXvnhK_hv)5wru1%jLTa7#iGy{Y2%B4T)-S%r z98aO*Cfi&qZ7w}!2I1BVe%G>qe6`(P@!xvl9uw`i5c>|CV}IG>;)pY{&yZ0FyS7Jz zV!0gt!+QK7pFtmvA<xIA0;wM7hfbRE(8R8h^FxLCVo3j+kRo)p9Xe9z z0}hO{B3-$dC-_;-;pr+4$H9o;n=Sj!sFR>FRb;wY5>!VLeWt}K!ub({ef9jDI@zL; zUlm;$h@S?v*P%=_&Le>w!OfuMrw9SQ<{8=jbb% zxZ|6_{AKjDutn<9BS{~H_~$2nl{dqZz6>)lr7lG^1pbKjzMz%47hq}eXgOLz_+mYo zXrbU&*3n0&IH(&G&g08z{g5858cT5IG0vvh0Gf4WyTSeN`>1fnCCq64#;Y#} zH7-vfy8gRbZQhocExv)(%iSEjT_zUrv$M+G4;$+*tuhX?O_gJw;`ke}1y5zST_Z_K zIYNc#iXm+6VE@nBaD_!cz7IQfnMLOUdSrLT-WQ|q>p59Y z+0%@ou1I8Rmhxy#?EWYG@*&}{`{RVkSQozqd@gp;-Cs`gxr7HW?|{gmf_L!9BK4)= z??516>QKJyBjaEFm0Q6=SKh+BH}jV_z26qpmm?i?u$M8{-az?V0=YZ3A6=9EBdk+O zTI|0ry(N>TT+!|bv2fUitYm_`?R9AVpdF`q!XpZ!EUEvTAzJ%Kvm=s;;zeFdrDc%=WruoA@QXr{`{2AEi7pSvZ@2T6bW$N32iq?+N4=t-g%C1T_Z6Y&Gf$ zajg{9UeU%L&;H~C)TR;0*QLa2rFtDl^XE#$wD<;b0RrYpJ;vBy*iA$niX@uMEGUQ` z)E4)Gwy0H^tSC6MoNO=ls~1Yy!mO)dB=%Yp6((|3rkt59RgCgRe+rg^zL4=M>YI)g zJwcf2{OROqU3Wzsc=S1#SoB8`CilBTP-8$o$(9+053F(|;8juHgeo%7*>8U*#V!_0}vp0YP2<>;VQljGuMk-r+pGn{FepA>#XZZL{*9WLZ zmKK0o8MKPj93o_pPoFLTv%Xqqi@!JN_bRaH$tdvaL22$aBR!;3k$iQrkmJi!UZfk- zE<85Gq7+?r8T4ht@FwGtX2jHv+KM4#22q+OR%UZt-x1QfGtQS~|7J=*uf?`KE+IE4 z;RQ$B`8D!>wYaREt^6QjEiBAyq4w{Jyx6@$y)P13+GvWpFMXx-22n?4RPR!>$0+nh zHOB)^h&+C^wRXVJL@6ppOZ6{fRS}~!Ir53Lb)|Zr{v}o#B1PuSw2U+dkZHP2xE>We z7&s&(&xY7&dlY|5+2!e_XZ>Tq*4QMi1-fT%o&>z(iR#e2Iu|#-6%zoDL}hldFr*+Q zux->A?|;y-cQ|H=pZze9H&gm3#o47zX*j3C=hfjsw)z~;NLp4|xbW5<^=$ds? zoUd9EN3=oYTb)*fAHj87pvRf*It6TLk)(}b5kJOcu>WV@GB6<{|Ark1P|)%E6Z?KD zd0nC&vr}jX&+ZDe$smWHo_O!#(as`QGC2PuZ6oDx@JhhtxZ1 z(?;!;Zg^Zs%RqiusxoH4GpRK-D7(KDg?%|NL$(;XQJfhJdNn`6nHnn5SjEU>!0a92cg4 z4J(Cc$EtIR?!T@ebl-Jxu3PFi+?7T~<1no>!wIMzS@Lm}@Hq0_x>amu)c=0s7409J zd(~qZfwKPd%0!|Dd97{g+hQkr#zA~~tM=-9BMraR2&tM~2=u%Jj#U}gl}%A&R;*j3B{O83;mYWflRuSd&h%Akhg$>#(O z!{?@V0qVM9??Q78m)TRrP1XI|xa9Grvfby|`=scT)yUCr;&s)&-BU$xF}{E}ANNzC z_J+lZo(HZ4Th1IK7%i}&3Yaw^gCs`wK(Aj&xmVC^b>9Jo6(sAlqC`?S@BQ8G~ zF#9Lk!RVU}5O8wN(&C+vwtZd2oZ`#+q`Y8m7Zd*h6;xP;(@ybbh-Kef_PPiWKkDk) zUbZ9XceTvApzOyNO^@CYk}gQZN`se-Y5*V)q1M4sekUET9XYr5RV$MdjR!c~hBeh6 zTFw%*ydM0OeiV&vx;nZgZyjS4eGCFnp2l{IetkbcsFvWlla3+_065Y_?Ts`Y z|4H&3JaF1PEW0J|ni#ZW$@!-t1I;p;__x?&N{?a#8}{H?gqz-$)B^h&YbPi3A|^-Z zUlduE8Oa{a$zpsJ#zWxWXWUzspQNE+(@s66-Dtq6Ycv`UfEexDWiG|GlHEMz11mNZ z;Cx(NLq2xkVW&=8fyNjqjIhRJn$ zB-y43cfen^=)J{W$UMY4Qke%rO%qGGX_p$#D+Apq-I`-qzNnbh>tC$rLi_<0#=DNw%R>}B!xeEpJs5r?O*h`|wCF&a4Ylza8bRwX#LJCOE2r1)z=Q&g-Fl8ZyeO z_L=R)xS}lXJ&~o(Vh*VlgOv@gb`$I#zA8cB+=65{bw7>t+afRq%~lZ4Ci21L&@9-D zAiMT7DC_A-gp5M3%VF|#g5zzWHzLB#yLMxl!YGgCtBd72+m{vP!556)>mRUFh z9vJ;wCm2}-P$+JKqejijJUG@I87%?!8@KXqCL_=B0DR{*}=-0*5pz zEfkNz+NKgqvf=7bz72(_tE6K?QhoO9quY&RU%&a60Fvyqs=|zse&y5K%V|uN?*(KB zrd;H*pli?md&&Yvo$f8tS8F}$D}B`qM%?LZh4AN$<-qC~zoGONL|Hq)%87WNhBXad zTT`F&*^=Q|^tG2T1u(Dx`Enb1>)1){m|Xy~7~gEx7e}g!1rmaz=$IH@)zoYSpvSHp z8qfCU@DrVPf9_-6F;x-!X7XCN+?;m9SSWD#`w~Xg&ae8@bxWwy^*$lCzXG!eMB$H< zF5mMqd*i{@+SA@@R(QQZ2>Loi)d4ch$t2Ys1f@5KT8etkRF6xCy%fNnh{ z5tqvf49S_m;ce`wJJ@FIPR!UZ3~ekP3_S0Vv-+3LiQC4VS^2E=6oe*Km!JcP zs2s}D&E2J>DvAt}B95XUZdfg<4;XkcMXMF=HPIx(gS=!{YiNG}f9v!g+SZIMHI(!g zb18|^Td}{!b3zsazVHA80^o7=G9$y2d_h)Y*a7F27ID>1isDK*l{v?D$4Hg*T1zck zTbddF!ECrowq>aU6SA-(%75>AcrhIxy)MvQB$1Mpw+{|6dxt0pltydDM|y&y$FE;b zG@<=f7E{5)OFcqJzpu*!;(bSdtgT|Wkl-4Hl7e}%Fy}j+S@W*Ah+xp8V^GZz3}8j? z!_QM2Yk&iljfSwmNvtM@O^BrW&J0sZoHg_l%&ZJ)BT+5v+(5UJ%-rw)H244|fD2o% zQ8PfjCke3Aq3;4~$x9y;qZ|7`0Q9fq;dV~@HW8gNp}~Yz1I%GS4bcF1RzS-Ge0XzK zTz@_^VEkZLa*G5`ofCTGBz`fFF%N>waNMT=IpMeAK|U{~DYa_2ak~n)Kp*iu(M=K$ zo2Evkd^n*GSCdVs&qb4O8}_sJDL1B%-KTQEed=`=&5s9~NMG?dwQv4@juxObE&pXU zN(AX=&@@J62B1C2(n8BTz_$CKWxoFk$BR5?MJwRYywy^F@m>=K%O5?#fQz5_$1*3X zB~OmKHNI6uqBZ=u48C|lXiQNU1(AFptcC2>wn>rf>)B`rbX{^Xd|Xx@Jz-w@dxVE*@Uog7i7W&N$TAVF^XY$#GA}1iLUa5 zYPoONOBwY)*d_(mGtOu-AovItm`&nLMDeATpoWKcTd%CEKl)DJ!uXcYVg1w!uf9v0 z!#aBU$)IA96iX%-0yugBSqGAUvLEG%$B-Wmh?Z{tOd8L_sM8)3ip9n-A>a9l(mPeE z4C}0&Qh_df%Ku9$>!*yf(d54JqnnYG$?xeljy_6B0c~`c8t%qgiysW6y(vv6 zj=vD0;{GB~W{|#SVW7oAEs>1Q%H~!#JS;=W6VB-=p+A;5uc}==Rp}NpEQ>*3D^6%%G1q;^28sH$+ zA++|7Zt0NDutFMAyDYU#J5QWbc*&SKK-9if<)Php_{v6csx9TOfCk9z)h4V6c&LF* zVCRY6Ep$$fvVjIZ$1iE;R;seaHJyzuUW(=DUG6~aPZy3{fCnOsMNB1-E?WbRGI$m$ zvI`G?RisR0d{=z(!A9R?I&4VWK-Zt;4Lm>`NWbJyr)SexEZ4haaQhitOXY^(32$!3 z_mgEPtR-&0xy!sG1EnPJx;u{~5|i}ZLyE&`5I;d^>DjlZeP%_X{wEoC$ilRR-D`Gs z!z{ThLDc*!Y@%cs*I>WwXfV9ci#y0VZ@B>rgZ`er z{#X3^rEtMcbVC1i8M~6lKQ)0)-rU)h*HjZ`DR`K2_NW(F&2fqHl39h!C!PI&+8$7k zd3w8*gW=s6ATeCxU?d_4Wb2TH4Y^yzMQJx^cclOi^5o7vWyNF+XZQ(L!S6S?XW3uSl;lUmKH3QCE=2ttSi|zV zrpPRK;NZ9=j-r+>ClI8={lh7Dkuq`cs~9&k#C_Par6RdN zZAA8uoT)@>crs#8Itqo1`nb-FJ_K=W)GCKAc&qP_*JNxmc_oli%KyC8o7Cw^kKWBw zY3Zj!I$=$0)eQF&+?Oh;BCSG7U94X_708&_NgpsMcHxe|5A4zT?OP1P$jx3IrtS74 zmsITNJqAogsF{|iJ=XHK2spyZ@_KK-Po{yGsjp_+;m%^Q<+nkPD+9`zu8RLzsSF%K zK%dlrkGQ`F|NH`@Iq`%0JJFl3ZDEb7ML16I08Y#{3xu%F9PZ9BE0Lwatw9r-=hkiH z<8Mst`%9cAy!eh7Rs|Ek#L>gm~M|sEB*`4wlV0?ZbT#(_N6}B%&=1YDh zXI%~C8vQ7F#cCUrsdS5N-p%7;FR=fvzD3D$7pFm#~y)3-vTs*?bqAiO$++OHqz#FX}Ii3rLc#D&E?-Qz&r| zyv@X5RUc6Pk6D39t)>8Z!U6;wwmp|rwEJ5g7&|}x^~0E z)Yh0w&8$Tv{lN=db521kq{%KEsy;1xW*$Zs-h(jnW1%?9>7D7iZ-o~{cksiY{1Cvk zh?hqE9;0(MQG#W$_~e7o&XcV`s=5xP#i>(PN)^WWu1NTcq_MJ2cM&wI$QBHjV_D)x z&0>wcDV=B%#pqgr<=Dc9JvGBvzF?@Kw2G4Mf*at$!JPDA8>i(jo~_2RR3SN@dYEvdezlc}fg|Z^ zlL)E&h?LxPqB)x*grZbu51(1?EFh<{E z{)_MphHq$2%=&LX`^Fmd!bkJN#Qg0Rba6Sb)I0)PO(^rDAIymGHc=;qjF$o!jAJ#-7U8dcD_QKfuVyT?cp?n&SI!-Dg0#` zfxOMx^kdkITdFol`>QrN?U7ZlQEwCU1* zbf*)#L2FO=4;D`3OyP$&M1yz;VMEJfaMp!I4$=tPj!ZUUkn0(`Q|A2m;&Et(fP;Fk zU#{kV7o_7wM-o0#I?FQqz@DNltt;!i?{(W+%Wy}Ckav3J5(hgs13Ei&ljGzhT&CLy zQJH&(*mDgLk_En-2Ni%d24kg5{SSNy&}p(ncIsd2*Q=FHFIXHXmE7?tr(a^&AW=3O zZJT_o+8rVve@Y`5lUdSFl=Qv&|AN4=PLdHLcF|Wo zemG>T45;A;vFAv)_urcZkiv~Fg@BqZD5v*N@GM71O4(@UtA2*i){|ysB6+xkJEaL1 zfQ0v&34xXqiYq1ythBH-;@`W!S5N}JO1o~k&|WH_9CgonE6%Xj7Yae`3`PGo<2Uri zOmM@$?dC-8v%*t7c{YAu(i4TSKUBv!F*2%-l9{-zf!wl(uv^^EOSWPV%jX8FLYNN$ zR|)jXEh7;fCx*1%rQgtL^5rod*}zEiu#vqSykpsv!eXICm&)S7JA$XKv_`}EPS=a2 z4@|~z>o-V@t)pP;3JrTFSB{+G3<;{UUAviqvM-z;rQA}Yo~XAtk&p|K-Jl0*OQ8bKp} zKo@7aeBk|d_?s?3kda?h9=%wht=64>;Ea0i!u8h&soSBRN+PCv1pBl3M_SuyGIEhp z5RP3vUmn~<70~DCurm{bKxa=R@0O3upMcSK(wViqZafPc54?aOw@^#2;+wNl4>Y=@ z|EKG?0jo89@ey;-=W{w4FY)fD>O^*mxREPfXGWp{CI>zxuo zPi(8lCvZr{6xfkjX-cM4IZ-p}iSu=`D={l#O+FqytjwfaI9R)^g*995K)q1Fe4`x18nH5=5Wtoo4oUcR z%Tvs1`t0d4u}kofX{HjS6P5A7Fbb#zwlwAiI0|Zhb3RY_uUkcXs$65l68=81H|K@h z)BU8;2Mj7AqVzR<)~&%L4;+P4@ITCpZDl>O-CN|Yg?AA%$!f1Y(jik9 zK&}(Nt+vvnftL_YwSac%7SxBUg7sF$f8%IuTGE~KGtJy8RC<93+6m$(I4vf;C(l$ zOPf8PCXgVAZ zyz|W5nL#jhueahS%M3w04BVXMsNF*fcRY4SRZ?$5W>$%sV>sMfCRjo%JjIkkLMlFCEscnR5lJd$Opk5WCSK0-qdQ0 zTa!Ev5*!R2da8WdAOWEm{`9T6s+LC?#rWd#;5x_RRi+?Fa9Df7iLsl*0j4k_)wkA^ zL|Igxan^7WUwq-dcot%Gw6I8=jYO-dyvtB!Bn;TT?5w$7tdme<|>l=A&yrR#mO+j3b@16k_?|C@` zRrdUnSj4dFeQiiShf_8>(LVfv?{^WAYJUg#zc#*6gWFkz`>_hK%ws7{UsB$A>mEgZSuCgv= zlAco3*Wk+?Q*@8W9h0z2l{yGO$6EB^AKV|-s)-u}Sj;I|WAV;f2kvbYB_LA{ebgL( z*#%G~ZqBnpIH*Wq5M4e`ef`8O9JEG(-}oF7jdW5vR63L-O8-F0!&8T#>I7U`9lkfM zVSpQG1))Tc4%d`$CgQEP+O3xp1J44+l$1wyGAkjUJjOwLHTe~tA?wydkCQG>5B_q| zTwlfF97$b`5O~zaX5fU%S{;h3W_W1ak6W^#H0#qbrtB{7=hmiS4y3XLo)4K(sYOr6>RI1V zEDO^4dh5o7m|_{`NuYvY{A^!UECfxU?`YjT8UEGNaWUGgv;yL{2yS+O2E`#OGChdj z$}EkQTl7p{MRm>;E1K-WME#>qCp*$x`^KvTDr@&vES`UcGR!GdWK)VGA~GUNe7qIR zpNB%c+${cOOoyo)1a)5CwdJTxZ@hoqJou~`JRfF8fp{0C^0Vos%+Q60%&QoORu7&c zW`%`}{I~YuemYD%MttiZndVOiaP6)?;ugMqcRar-?Ej4P5hykzL?W>I_a`^xkF~WFA3{N#gks|V^08j z&cwBaMbf0+fsQdgoV%SVDRNJA?(l#X7O3CRc*ELsmx&WcCAZxxFiTuD^o&n- zg?%3Wx6o@^4=wr4Z__K5c_d(VrN=OqT0=cl<1 z!Q%GIu5a9Pf$QXY$g;5Bzu-@~v(@Sp-vCo998(lqER}ENq7gLxNb8GMgDdXcY#@DQ z*OSw;K_vzQjX1Cs!Zz#it^)@42*ru{)yN_ekU|j$xqg63%u|df5oncTUQ84bj3tIh z#7YN?zj+*|zfuFmu7-CgnOgB9lGo3f`IAkamot*^pNR~Npj}_JH`d;wKQl2hEJuhh z|dzzX}3YR1MFeCCz&0U*v$1!{_hAnrN zlpPriQ5=6?lO%c_X=!7&af{KsYhK_NmAY~jAl^(GPMVE%wqX^3O<}-@&~wc&c_P#o zw0ic8X>Q*N#lzW6av1=+;qc8FWJgjg*z#WxCUnV+|IsCeJq>)sd5U>;d_&_YavT+b z8SwW=TH+&yzUs7&4ygVSk0npAxMur2JSiQP+Sc@WNey$s3@0!&#DDtv8vN+(#7viiU@&6 zW~zz~X=O)IR+0=4cg}8P0sO#$Y=%m{?G`T9*&>>!PzJduPU_W zbxcp6tw%>RmK5Z}MUL4|V<3$Z@TzsWkHBReZ6(0SV#1#@2aQuu)SBHBn?ol-lIVbn z*vP>gb-|yvmgH<8%0C?_Un$jE-a=?n3c7xn)Zb->LH;x!u7@A~$ux^$h&a^`S%=G4 zL<86gx_mgO1Xw;fug$7;5*|6Vpkp$~f}(J(@rFxB!=--)M-T_{ zqWfS;Y`_LVQtMafTgwrNIB*Cj-3Xhc66Cv%XO7Y6nUTKyBUMFdm)l5C#!`?6^W^hE zwRVFk@fiR%rj$Q_u)%_6H0p%PO8U=2Lp2n`X1#&}C$XHQeu)TEHkBbs1VI7sN1_$m%9TYzK4FP>7MqNZ;FEhLD4_{YLI2t+Z4XTKIuo8ay{zibV=27KM>*}Vd zeR9=;dz5rSjY=r$jS!Doki4T;)+`|ILDwbj`bBm&lP@S-wi1AA9WKqa>++p1**<9d z8+4rZo~W(qbNdRbYyA5y&--!({)tNs?9{tZ)w4E6k;NZEV}hpc&>R&A^tURl1zisj zETCS|mP9AR?c-XQ zturv_)o=`QF>=7#Ym7FR=B(d(_P1Zbb#JPxtzbOVnH6o68@@sGa4G_UD(6}J!@QOR=}2uQS!1!w}KThaD06G+!nD{;Gslc zUiGvuj_7YRdGsr#Whz|A3;VU8`l(`}>5F4HpJhu;ab`Ork?kq&E!N-lBLCS?|hUEj-{ zn(ut&2b>BrHMpvky7ciy*-{J%rcxGH~3HmaE`8m=pC|ilrD9Zsr|L z8~0&oyfxsW>A5`Z6~hX;dHix>YC}T42NLjmeV3lUh0;f&uOQ!Vrkyj#86BFiZ)vtO zuVMBp-QWWoRvn#mft;5X`v`Wr`{r8TElm!o!HFg35)rG`#;ouS``Wvx9oQiT!e5`_)@krfeB1%DN z_#c!*P8lj!4cG<|k{qRSOUU>~K4?S9FFx465?LdWrV752u~KY4as+55qC@WzEjDp{ zbdx!=xPjWqWx-}JFyPNSZRO=RM4uz!_${;v7S9`y*{u2bUD{-mMbCqySPp_NP+x#v zL-Qa17Jegzt`JO2zG`m{yl5WV?loBDJ6@$rM%2z+>N@Ar^UQC9TM>ls)jhrJe!s!+K{}0 zdJ~6!`D1S*vdxVrX8X4T%>Yx_GQN9MbDPIVSX1LRUyvT~6-&$|LhfdpXPNx&^}+Qj zT036?S4Pb6COamKUob4u4`)CJ8L)=KCN#C=Tz1SH;Y|# z!4nQ=7#4Bn95gae*5o~C?8V>B$>HgHR4_q=`F}7X1Ixdh>gDR#%@jvGV5Nn2ZEHCD zMJO#Y*!DYONm)0Q0|~JSI{_?bVITx)$bo>LnivIk?5yM8Q7!O_vV<(;gfRHK_<>!W zmDkg}@Ch(-be2JX%m#Wp#7@{Gt5s$aGxuxZD^XB~~a zUc%tSA0rK1#o!a&OB^t$3I4;|?d65W=`BoFnAy54?-Szs`v3t$-gN0CF9OVSU9+Ip zdNF7nvG1jF<|J;6c&S-sk54ztvB8Sn;!X(XnyhVs>?&QflWeb7`GdPo>An`cs7O;G zC%f7!qdG|1K;n9XpO3SQHCV9FU7%t~R`5#%S!{1aKA(!BiXbhoBI(2fq>aZVwol0A zdiG`^0E_2nFPOLdQ~eR+g9p|t**y&@)+h=AW%!Je0?@uEN7?kxNf53}QS*l-4q*Pr zE=8U`g$*h(bLBL_fA1}RZj{q1nUmL`p5|5`nSW#~`qiJXOop;`k@TwB-xhCWwrAhRqBxgf7=pKhPRg(~45!<2jV`kcJ=oLuoNggqRSsoFq>nLNaD@y z#M3YJuq+knc{{#0R-k4!j2ne?1`1Z^SCu;s8_1OKX6?)&EL2nS;q|w za-v%D0uL?-NTNLMmJcLoyILK>xm%v^LVN0Q-F`-(KJ)TSwzb= zqQZM*iSweby!mTfdH2rD6k@Mpb(Q-G`HG_a3BaFREuzEy6nAC1 zBQLP4xg0;Ji%b!~HXqg> ze25L9!h9f{5EPB2M#?)lB^?e_!; zkJcuT>A8BLe|(b91;@!La0VSvQ`3XXCZ`J1+@Y4uU3z$u-tZ(}QuQ&{I`#-W(RR1{ z)A#qXAhaPjI#Q1N5y9sYd)#++egr^C*b13g>gHt}d{Fsba{g&{krJpc}_P)V-2<7%r^>0;EU z(=?g1zo=S*F7{bj#0dpebQ1|vd@G#30E>ALv2_3L2DF4GZ9`ku5RJQ1pguYrp>?I# z4MkR%Vl2Yp=c(xVu;_P;AD!~@j#gcu8vy?h=SH&9>9MRcL_U{k0@c*1CF#kqDv#&_ z*O@@uMbmILy9aiXes@!{#8I{TSXUt=Ex&-)b*SDStr%euHJ1FmXyMOQ=_63ZM9r!~#Ut0J-7J=h{}?H82psq5I!ipg zi3khd3a6aktivM^F5!nH{5qwemxPiFwKv3K5nslo%KDSL3zw?J>ezw9>&0iwT%Eoz zQf$BSG>o}Cv8@zeYv8|-<7Hs*M@NKMF?Nq3etuogwKIF7;%5qj0&Oz~+m@?g7D7~H zmH18^YbQbzikeD=lI}$L2E=qS016SFgyw2d4aY7W5>#Q&r#WS8D<-Q)-En^b*zuK+ zlz2aY9QIg>HW?ST^VQen&RbB-W8#|@!q6i`uLn=Kp64q&kH z!)i4UjWPY>X9~I?RyQIY(i?cK=`ycX}iZ0(L?d5B>qRrr*fNs342@e74jz+X*!S;4pWK z2R)%v66iSKP0S&Kr95B|G4M!cV-aV|A^B8tNspf(6ao8atK6^qXa%qlgpk~c_LI$i zDI5R}Fd~B^4;e_7nJd6X7=;uQ3|$tMSihaeII`oVEcXib#nZTtCwxGRsW0=?_D{l{ zvS@>2v!44#)^_I;R!Yh01i}%)3lFdG7JCz4H3Fy?KQ0Bhzwf5MUN(L<=e%Qh!vb7K zCBB8u16FHL%Lnp5u-n%sVTET3G)i;yWigUGsGuCJwty|xtwDBZOvR?En9@Cd}0-x3Oav;0;c1#SnfIwyLf4OJgtQ1#P;p)cUA;0CJ6Ih0(14Co8 z%6W&tIr)CjOUfua%>Amd2XG-Q>=j)Y9|CYF?;#+I7;SS^3zX$PI5*~*SAE@H$g9aR z3j%BHGdJGIoSttSd{2}6p-^!!L(|p>_S3(4y$laoI4Cp5HkA!@@0$;l==#d9Jdjs4Xm$L+kvo?4pqOBS}VYU6+4&64f|ug?ba(}Uh?9!FsX#D((VN}pCuZy2hC9Y zKMeEe6lwoB`T@S1Y4eGVf@i_|hpq$ysMxJBtJVNdPK4%`zP%U@dyTu7o@kg0ULCyt zID5R_%WPmh%QOgRu-Ok>DuBy$)66}NifzLC zl!NU4~?EoX68vm*ZDT<8TX)6E!A-l^Nl)mLhYi zFjRa401#D|6zc@|7u_vP0RSW=sQ@7Ut-t_~0D%Dj|Ed3-Sb(7a7ghgh?Eh-rf12XI zIY9q3GSL6$TZDo9U;e*>{~2z80O!E} Date: Mon, 20 Feb 2023 16:58:33 -0800 Subject: [PATCH 076/103] Fixed changes requested by Alex --- docs/FollowPoints.md | 2 +- docs/Point and PointDir.md | 16 ++++ src/main/deploy/FollowPoints.json | 96 ++----------------- .../robot/{ => Constants}/InputConstants.java | 8 +- src/main/java/com/team766/robot/OI.java | 34 +++---- .../com/team766/robot/mechanisms/Gyro.java | 1 - .../robot/procedures/FollowPoints.java | 14 ++- 7 files changed, 54 insertions(+), 117 deletions(-) create mode 100644 docs/Point and PointDir.md rename src/main/java/com/team766/robot/{ => Constants}/InputConstants.java (68%) diff --git a/docs/FollowPoints.md b/docs/FollowPoints.md index 723a359b..0dfb9715 100644 --- a/docs/FollowPoints.md +++ b/docs/FollowPoints.md @@ -34,7 +34,7 @@ Optionally, an array of procedures may be provided as an input. If given, once t ## Desmos Integration -For the 2023 season, FollowPoints has been integrated with [the Desmos model of the field](https://www.desmos.com/calculator/qgjgrwb7tx). +For the 2023 season, FollowPoints has been integrated with [the Desmos model of the field](https://www.desmos.com/calculator/v6mpw9cwbn). ![Image](images/desmosFieldModel.png) diff --git a/docs/Point and PointDir.md b/docs/Point and PointDir.md new file mode 100644 index 00000000..777afc5c --- /dev/null +++ b/docs/Point and PointDir.md @@ -0,0 +1,16 @@ +# Point and PointDir + +## What are Point and PointDir? + +Point and PointDir are two classes which make it easy to represent a position with or without a heading. PointDir inherits from Point. + +## How to use Point and PointDir + +Points have an x-coordinate and a y-coordinate, which can be accessed via `getX()` and `getY()`. PointDir additionally has a heading, which can be accessed via `getHeading()`. + +Point has several useful methods: + +* `distance(Point a)` returns the distance between the current point and `a`. +* `slope(Point a)` returns the slope of the line between the current point and `a`. It has a maximum and minimum of ±1000. +* `add(Point a)` returns a point with an whose coordinates are the sums of the corresponding coordinates of the current point and `a`. +* `scaleVector(Point inputPoint, double scale)` returns a point whose coordinates are the coordinates of a vector between the current point and `inputPoint`, scaled to have a length of `scale`. diff --git a/src/main/deploy/FollowPoints.json b/src/main/deploy/FollowPoints.json index ff4feab0..9ba1ac18 100644 --- a/src/main/deploy/FollowPoints.json +++ b/src/main/deploy/FollowPoints.json @@ -1,96 +1,12 @@ { "points": [ { - "coordinates": [-0.96, -0.01, 0], - "critical": false - }, - { - "coordinates": [-1, -2, 0], - "critical": false - }, - { - "coordinates": [0, -2, 0], - "critical": true - }, - { - "coordinates": [0.5, 0, 0], - "critical": true - }, - { - "coordinates": [0.75, -1, 0], - "critical": true - }, - { - "coordinates": [0.25, -1, 0], - "critical": true - }, - { - "coordinates": [0.75, -1, 0], - "critical": true - }, - { - "coordinates": [1, -2, 0], - "critical": true - }, - { - "coordinates": [1.02, -0.01, 0], - "critical": true - }, - { - "coordinates": [2, -1, 0], - "critical": false - }, - { - "coordinates": [1, -2, 0], - "critical": true - }, - { - "coordinates": [4, -2, 0], - "critical": false - }, - { - "coordinates": [3.92, -1, 0], - "critical": false - }, - { - "coordinates": [3, -1, 0], - "critical": false - }, - { - "coordinates": [3.08, 0, 0], - "critical": false - }, - { - "coordinates": [4, 0, 0], - "critical": true - }, - { - "coordinates": [4.125, -2, 0], - "critical": false - }, - { - "coordinates": [4.875, -2, 0], - "critical": false - }, - { - "coordinates": [5, 0, 0], - "critical": true - }, - { - "coordinates": [6, -2, 0], - "critical": true - }, - { - "coordinates": [5.5, -1, 0], - "critical": true - }, - { - "coordinates": [5, -2, 0], - "critical": true - }, - { - "coordinates": [6, 0, 0], - "critical": true + "coordinates": [1, 0, 0], + "critical": false, + "procedure": { + "name" : "DoNothing()", + "stop" : false + } } ] } \ No newline at end of file diff --git a/src/main/java/com/team766/robot/InputConstants.java b/src/main/java/com/team766/robot/Constants/InputConstants.java similarity index 68% rename from src/main/java/com/team766/robot/InputConstants.java rename to src/main/java/com/team766/robot/Constants/InputConstants.java index 2b95d074..97970e25 100644 --- a/src/main/java/com/team766/robot/InputConstants.java +++ b/src/main/java/com/team766/robot/Constants/InputConstants.java @@ -1,4 +1,4 @@ -package com.team766.robot; +package com.team766.robot.constants; /** * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. @@ -15,8 +15,10 @@ public final class InputConstants { //Navigation public static final int AXIS_LEFT_RIGHT = 0; public static final int AXIS_FORWARD_BACKWARD = 1; - public static final int AXIS_TWIST =3; + public static final int AXIS_TWIST = 3; // Joystick buttons - public static final int CROSS_DEFENSE = 7; + public static final int CROSS_DEFENSE = 1; + public static final int RESET_GYRO = 1; + public static final int RESET_CURRENT_POSITION = 11; //Other buttons } \ No newline at end of file diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 783db8e1..356c0f52 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -5,7 +5,9 @@ import com.team766.hal.JoystickReader; import com.team766.hal.RobotProvider; import com.team766.logging.Category; +import com.team766.robot.constants.InputConstants; import com.team766.robot.procedures.*; +import com.team766.simulator.interfaces.ElectricalDevice.Input; import edu.wpi.first.wpilibj.DriverStation; /** @@ -52,32 +54,22 @@ public void run(Context context) { // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. - if(joystick1.getButton(2)){ - Robot.drive.setGyro(0); - }else{ - Robot.drive.setGyro(Robot.gyro.getGyroYaw()); - } - if(Math.abs(joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ - RightJoystick_Y = joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); - } else { - RightJoystick_Y = 0; - } - if(Math.abs(joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ - RightJoystick_X = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; - if(joystick1.getButton(3)){ - RightJoystick_X *= 2; - } - } else { - RightJoystick_X = 0; - } + + LeftJoystick_Y = joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + + LeftJoystick_X = joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; + + RightJoystick_Y = joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + + RightJoystick_X = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; - if(joystick0.getButtonPressed(1)) + if(joystick0.getButtonPressed(InputConstants.RESET_GYRO)) Robot.gyro.resetGyro(); - if(joystick0.getButtonPressed(11)) + if(joystick0.getButtonPressed(InputConstants.RESET_CURRENT_POSITION)) Robot.drive.resetCurrentPosition(); - if(joystick1.getButtonPressed(1)) + if(joystick1.getButtonPressed(InputConstants.CROSS_DEFENSE)) isCross = !isCross; if (isCross) { diff --git a/src/main/java/com/team766/robot/mechanisms/Gyro.java b/src/main/java/com/team766/robot/mechanisms/Gyro.java index e08dffcd..5e291c62 100644 --- a/src/main/java/com/team766/robot/mechanisms/Gyro.java +++ b/src/main/java/com/team766/robot/mechanisms/Gyro.java @@ -48,7 +48,6 @@ public void run() { gyroArray[1] = getGyroPitch(); gyroArray[2] = getGyroRoll(); g_gyro.getYawPitchRoll(gyroArray); - log("Yaw: " + gyroArray[0] + "// Real yaw: " + getGyroYaw() + " || Pitch: " + gyroArray[1] + " || Roll: " + gyroArray[2]); } } } \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/FollowPoints.java b/src/main/java/com/team766/robot/procedures/FollowPoints.java index 79c90a32..aed26669 100644 --- a/src/main/java/com/team766/robot/procedures/FollowPoints.java +++ b/src/main/java/com/team766/robot/procedures/FollowPoints.java @@ -15,6 +15,7 @@ import java.nio.file.Files; import java.nio.file.Path; import java.util.ArrayList; +import java.util.HashMap; import java.util.List; import com.team766.config.ConfigFileReader; @@ -67,6 +68,8 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole private static double speed = FollowPointsInputConstants.SPEED; private static PointDir driveSettings = new PointDir(0, 0, 0); + private static HashMap mapOfProcedures = new HashMap(); + /*public FollowPoints() { parsePointL$ist(); proceduresAtPoints = new Procedure[pointList.length]; @@ -82,6 +85,8 @@ public Step(PointDir wayPoint, boolean criticalPoint, Procedure procedure, boole * @throws IOException Thrown if file is not found. */ public FollowPoints(String file) { + mapOfProcedures.put("DoNothing()", new DoNothing()); + mapOfProcedures.put(null, new DoNothing()); String str; Path path = Filesystem.getDeployDirectory().toPath().resolve(file); try { @@ -94,7 +99,14 @@ public FollowPoints(String file) { JSONArray points = new JSONObject(str).getJSONArray("points"); for (int i = 0; i < points.length(); i++) { - addStep(new PointDir(points.getJSONObject(i).getJSONArray("coordinates").getDouble(0), points.getJSONObject(i).getJSONArray("coordinates").getDouble(1), points.getJSONObject(i).getJSONArray("coordinates").getDouble(2)), points.getJSONObject(i).getBoolean("critical"), null, false); + JSONObject procedure = points.getJSONObject(i).getJSONObject("procedure"); + Procedure pointProcedure = null; + boolean stopAtProcedure = false; + if (procedure != null) { + pointProcedure = mapOfProcedures.get(procedure.getString("name")); + stopAtProcedure = procedure.getBoolean("stop"); + } + addStep(new PointDir(points.getJSONObject(i).getJSONArray("coordinates").getDouble(0), points.getJSONObject(i).getJSONArray("coordinates").getDouble(1), points.getJSONObject(i).getJSONArray("coordinates").getDouble(2)), points.getJSONObject(i).getBoolean("critical"), pointProcedure, stopAtProcedure); } addWaypoints(); } From 62404659c7cba01ccdef4fda0c8141b28362cac7 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Mon, 27 Feb 2023 20:12:03 -0800 Subject: [PATCH 077/103] Added capability for rotating images --- .../team766/robot/mechanisms/CANdleMech.java | 2 +- .../robot/procedures/DisplayImage.java | 74 +++++++++++++++---- 2 files changed, 62 insertions(+), 14 deletions(-) diff --git a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java index 2f29298d..0ec5ca08 100644 --- a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java +++ b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java @@ -46,7 +46,7 @@ public CANdleMech(int matrixStart, int w, int h) { public void setColor(short r, short g, short b, int index, int count) { checkContextOwnership(); - m_candle.setLEDs(r / 3, g / 3, b / 3, 0, index, count); + m_candle.setLEDs(r / 5, g / 5, b / 5, 0, index, count); } public int getMatrixID(int x, int y) { diff --git a/src/main/java/com/team766/robot/procedures/DisplayImage.java b/src/main/java/com/team766/robot/procedures/DisplayImage.java index 22177d45..3759938e 100644 --- a/src/main/java/com/team766/robot/procedures/DisplayImage.java +++ b/src/main/java/com/team766/robot/procedures/DisplayImage.java @@ -20,11 +20,31 @@ public class DisplayImage extends Procedure { final int w = Robot.candle.w; String file; boolean interlacing; + + private int rotation = 0; + public DisplayImage(String file, boolean interlacing) { this.file = file; this.interlacing = interlacing; } + public DisplayImage(String file) { + this.file = file; + this.interlacing = true; + } + + public DisplayImage(String file, int rotation, boolean interlacing) { + this.file = file; + this.interlacing = interlacing; + this.rotation = rotation; + } + + public DisplayImage(String file, int rotation) { + this.file = file; + this.interlacing = true; + this.rotation = rotation; + } + public void run(Context context) { File fileObj; Path path = Filesystem.getDeployDirectory().toPath().resolve(file); @@ -39,32 +59,58 @@ public void run(Context context) { log(Severity.ERROR, "Could not load " + file); return; } - - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); - } + + switch (rotation) { + case 1: + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + } + } + break; + case 2: + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + } + } + break; + case 3: + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + } + } + break; + default: + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + } + } } - + display(colors, context, interlacing); } public void display(Color[][] colors, Context context, boolean interlacing) { if (interlacing) { - for (int i = 0; i < h; i+= 2) { + for (int i = 0; i < h; i += 2) { for (int j = 0; j < w; j++) { log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); context.takeOwnership(Robot.candle); - Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, Robot.candle.getMatrixID(i, j), 1); + Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, + Robot.candle.getMatrixID(i, j), 1); context.releaseOwnership(Robot.candle); } context.waitForSeconds(0.01); } - for (int i = 1; i < h; i+= 2) { + for (int i = 1; i < h; i += 2) { for (int j = 0; j < w; j++) { log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); context.takeOwnership(Robot.candle); - Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, Robot.candle.getMatrixID(i, j), 1); + Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, + Robot.candle.getMatrixID(i, j), 1); context.releaseOwnership(Robot.candle); } context.waitForSeconds(0.01); @@ -74,18 +120,20 @@ public void display(Color[][] colors, Context context, boolean interlacing) { for (int j = 0; j < w; j++) { log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); context.takeOwnership(Robot.candle); - Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, Robot.candle.getMatrixID(i, j), 1); + Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, + Robot.candle.getMatrixID(i, j), 1); context.releaseOwnership(Robot.candle); } context.waitForSeconds(0.01); } } } - + public class Color { public short r; public short g; public short b; + public Color(short r, short g, short b) { this.r = r; this.g = g; @@ -98,4 +146,4 @@ public Color(double[] color) { b = (short) color[2]; } } -} \ No newline at end of file +} From de157cf00c4f07177ac251a967b9efa1e40e4c22 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Wed, 1 Mar 2023 19:08:02 -0800 Subject: [PATCH 078/103] Added rotation --- src/main/java/com/team766/robot/OI.java | 4 +- .../constants/ExampleInputConstants.java | 40 +++++++++++++++++++ .../robot/procedures/DisplayImage.java | 6 +-- 3 files changed, 46 insertions(+), 4 deletions(-) create mode 100644 src/main/java/com/team766/robot/constants/ExampleInputConstants.java diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index daf8ddb6..cbfeb3c9 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -31,6 +31,7 @@ public OI() { public void run(Context context) { context.startAsync(new DisplayImage("cone.png", true)); int imageDisplayed = 0; + int num = 0; String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png"}; @@ -43,8 +44,9 @@ public void run(Context context) { // of mechanisms when appropriate. if (joystick0.getButtonPressed(1)) { imageDisplayed = (++imageDisplayed) % imageList.length; + num++; - context.startAsync(new DisplayImage(imageList[imageDisplayed], true)); + context.startAsync(new DisplayImage(imageList[imageDisplayed], (num / imageList.length) % 4, true)); } } } diff --git a/src/main/java/com/team766/robot/constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/constants/ExampleInputConstants.java new file mode 100644 index 00000000..aa7cb28b --- /dev/null +++ b/src/main/java/com/team766/robot/constants/ExampleInputConstants.java @@ -0,0 +1,40 @@ +package com.team766.robot.constants; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + */ +public final class ExampleInputConstants { + + // "joysticks" + public static final int LEFT_JOYSTICK = 0; + public static final int RIGHT_JOYSTICK = 1; + public static final int CONTROL_PANEL = 2; + + // navigation + public static final int AXIS_LEFT_RIGHT = 0; + public static final int AXIS_FORWARD_BACKWARD = 1; + + + public static final int AXIS_SHOOTER_DIAL = 3; + + public static final int CONTROL_PANEL_SHOOTER_SWITCH = 1; + public static final int CONTROL_PANEL_INTAKE_BUTTON = 2; + + public static final int CONTROL_PANEL_BELTS_BUTTON = 3; + + public static final int CONTROL_PANEL_SPITBALL_BUTTON = 14; + + public static final int CONTROL_PANEL_AUTOCLIMB_BUTTON = 9; + public static final int CONTROL_PANEL_ARMS_SWITCH = 13; + public static final int CONTROL_PANEL_ELEVATOR_UP_BUTTON = 7; + public static final int CONTROL_PANEL_ELEVATOR_DOWN_BUTTON = 8; + public static final int CONTROL_PANEL_ELEVATOR_TOP_BUTTON = 5; + public static final int CONTROL_PANEL_ELEVATOR_BOTTOM_BUTTON = 6; + public static final int CONTROL_PANEL_AUTO_SHOOT = 10; + public static final int JOYSTICK_TRIGGER = 1; + public static final int E_STOP = 11; + public static final int JOYSTICK_ELEVATOR_RESET_BUTTON = 2; + public static final int JOYSTICK_CLIMB_RUNG_BUTTON = 4; + public static final int JOYSTICK_CLIMB_FIRST_RUNG_BUTTON = 5; +} diff --git a/src/main/java/com/team766/robot/procedures/DisplayImage.java b/src/main/java/com/team766/robot/procedures/DisplayImage.java index 3759938e..8b253073 100644 --- a/src/main/java/com/team766/robot/procedures/DisplayImage.java +++ b/src/main/java/com/team766/robot/procedures/DisplayImage.java @@ -64,21 +64,21 @@ public void run(Context context) { case 1: for (int i = 0; i < h; i++) { for (int j = 0; j < w; j++) { - colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + colors[j][h - i - 1] = new Color(image.getData().getPixel(j, i, (double[]) null)); } } break; case 2: for (int i = 0; i < h; i++) { for (int j = 0; j < w; j++) { - colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + colors[h - i - 1][w - j - 1] = new Color(image.getData().getPixel(j, i, (double[]) null)); } } break; case 3: for (int i = 0; i < h; i++) { for (int j = 0; j < w; j++) { - colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); + colors[w - j - 1][i] = new Color(image.getData().getPixel(j, i, (double[]) null)); } } break; From f35e3c2cb1867cae986106518a7bed52d16a30df Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Wed, 1 Mar 2023 20:17:29 -0800 Subject: [PATCH 079/103] Added animations --- src/main/deploy/anim/0.png | Bin 0 -> 603 bytes src/main/deploy/anim/1.png | Bin 0 -> 595 bytes src/main/deploy/anim/2.png | Bin 0 -> 591 bytes src/main/deploy/anim/3.png | Bin 0 -> 589 bytes src/main/deploy/brian.png | Bin 0 -> 6506 bytes src/main/java/com/team766/robot/OI.java | 8 ++-- .../team766/robot/mechanisms/CANdleMech.java | 2 +- .../robot/procedures/DisplayImage.java | 10 ++-- .../robot/procedures/PlayAnimation.java | 44 ++++++++++++++++++ 9 files changed, 54 insertions(+), 10 deletions(-) create mode 100644 src/main/deploy/anim/0.png create mode 100644 src/main/deploy/anim/1.png create mode 100644 src/main/deploy/anim/2.png create mode 100644 src/main/deploy/anim/3.png create mode 100644 src/main/deploy/brian.png create mode 100644 src/main/java/com/team766/robot/procedures/PlayAnimation.java diff --git a/src/main/deploy/anim/0.png b/src/main/deploy/anim/0.png new file mode 100644 index 0000000000000000000000000000000000000000..b4cec1eeb1948d4d8e2cf47593a2d4d26c21a11c GIT binary patch literal 603 zcmV-h0;K(kP)EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsGR2m^;^|NrIgVNHxEu6iP+V?Y~VZjMY` z*c}2+83&+N|1xd{b!Ef2w>0QW#)GKbO^ovuQ9Wwl*$q6!&`_+T!d-r+mhP#n0B`Ua paJ|j~*e1{!ILNCzaGdVX_yVlL9}y_~3KIYT002ovPDHLkV1kY)3{e08 literal 0 HcmV?d00001 diff --git a/src/main/deploy/anim/1.png b/src/main/deploy/anim/1.png new file mode 100644 index 0000000000000000000000000000000000000000..0f82a4483aaf2d795d570d9905fc6da1273a9ce6 GIT binary patch literal 595 zcmV-Z0<8UsP)EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsG#~0001DNklgPBHX|rCT6f}qVnNyf(OiTD z0PfZR^zYoN7jQLP&a|EQQ5R4Q%N;u0=~xGFoo9q8BT}dVvjw*5WEAUQbgNHBkGdG4 h`B|r7^Q+Ex`vX&i86LAXS~LIv002ovPDHLkV1i&C1#SQU literal 0 HcmV?d00001 diff --git a/src/main/deploy/anim/2.png b/src/main/deploy/anim/2.png new file mode 100644 index 0000000000000000000000000000000000000000..331a4440df2bb60276bf8a65c34a8acabe250c8a GIT binary patch literal 591 zcmV-V0EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsG)Q$dIQRM4TLn)Z%b`fxO% dcZaz9-B^4%5h*tTHd+7x002ovPDHLkV1m3J2iE`q literal 0 HcmV?d00001 diff --git a/src/main/deploy/anim/3.png b/src/main/deploy/anim/3.png new file mode 100644 index 0000000000000000000000000000000000000000..eaf4e44d798cf3273c6a6685e9a9c2a37d5c69a1 GIT binary patch literal 589 zcmV-T0EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsGD`2R20i-}7B>s3Yy5)ee#Cjfvl ztF?e-y00000NkvXXu0mjfZU_WQ literal 0 HcmV?d00001 diff --git a/src/main/deploy/brian.png b/src/main/deploy/brian.png new file mode 100644 index 0000000000000000000000000000000000000000..4ed394809a95994abed113e6fa4f2cb693657208 GIT binary patch literal 6506 zcmeHKdo+~m_aB$sa?dT4F(}EHs~N^McQNiHk;cqBjN6QvVI~f_R1}2@$31mKMde!2 z388XGL{hmFIfO1!NvPjD>U3GZ?^?fg*7|+_Yt}n6@4KJ9KhNHuy`TL)&mk8lTM02` zF$e@AVQ**U2L4O)z9RhKZ$@Si4gwLLkM{6pyOB6h29r*ug#u9aUIqXKxHKvR!hKZg zz4O>JZSj>!IhLScfRSWK+t8k)W>V7KwOh}hHzI5RlEf|U_5JO((zGx6qp;b!<6g5C zZ#!a+sBL!IM3#Q{sV;K!of*A#u|oKUhTTdTxIdTfc$chXJ!DASy{ybV?yz`fl5WajG5n=561 z!@ZrauTd#@Wg7HC7vE|Pc9Jgn{GPSdu$r=-ygNCPC`dYk2^htmekufsXXj# z5!=m;k$DrhExJ#!hUT1^GUeo~sIi@Dm}Pf@l7xGH#wS}MW2)YCA;;>n;zTHeV>6*D zeQYsEqi`dl8!@{6zCfZ-?9qarbgM%z5qSnaXsL$5@S9zmZ+S)^T*{vuSbwHdfkUuH zUF=x47dRlH<{u=qLad9cc=~eY>_(eU7!By9tP=-JHr9-IRwuh={XTbVZlpDlQ6{f& zJa6LY=!3}V#sgB+PsyK7TW!t!^UmE@UBxqt&9D5cC=sWY?hp1asdt;JjR&3C z&>kmdlx*Z=`v5;UYJNp)DMZuSJa+G#Hh)U^R@kU}RZ~&wg(Adl6Wrj8(!5^gMd1U) zCZ)RZtCNcU`^dEh+1=QcevPtd*XbaOV68X3E*HE8(lWY|N|Sdu56oK>1QbMCcLy_i z63@HAlCBx2oOL}@QhsrpmYiY)?Zle9!M*( zQt+8P6S>MHL#(1f_K; zdv1%wqn`)q=JN}>L=%%T4pzQv7J4UTyLDEyc0f50x4}d-0@K+T)(7`5fldh|InVa4A>)DOxrYco%$nx0CzDd#HLBhFxUlw|~L z-x64m+hQ1#Rb`sw=2&$gb?f#0vJN^|Z^Y{C*bytCKj48OtbN?0jb*FC>-(8yk~^k{ z3a76pZ;YAV+x+0*2IHaE8fgaiZYu^SPUp->xoB*=qx;9-4U7_@V3DP>*-h~sZQ?2G zH$gXU;%5Y5P<@%d-?0i0IGC7R&JeO_I7HMa>`?K_Hd>FLy7BVBklNFO9!m~GU9Vte zo7npf4c#C{E*yL;-0!p7`kvl?s+?1Pu#p#VcN5iJTJlhq#=+pIzEh^oZ{`y&6b=|~ zUh$pdo=e?R@G{ZX6=oFYol(2P zlQlZ010~}sM5B9M9PR!j_BD>&LzcTcJ*DFwzDzGF;a*;x!e&^u*~lzjIy{~Rv3*t+ zedcAXsG5TMWs`(cC9XQOh#d(s71ve*Zu)jHy{w-*MsIy0)A%^Gr}MYCbDI;Q>jKhJ z;*;WU7?e6Ct2~U-d?uYeCx=OHmT>D;qt+C@SR zdw-(3?7&qEm8taNlUlSsGGIHTkcDD(vz6<{a%OL@i;*cy2=!PHHw_<`elVwC8Yvs^ zx#fK|(WIQeMjLe_OZe3w{6mqd&&|q~`GDi*c9C2?_s&Hr!Bh{yr&fYy>Q1D)&0CxO z5r#*MQllN~Ivq8=mFmGcJIy%>FcZa}}~mY40W z>+MI&EoIU0Y)fFkXux&)QN6y{I1av}bSW;^wOV9DiMNoR#LSC{mVw{2(nevg|MGl5P}}dV5z&*j4I9znA2w!>y9R+&d5Y z_%yf_?A^!pcajOU4LuKTjV62wtyu`QPKWMxJ&_&(c~+{mX-!eA@kX6Rg27=g?&Gc~ z@uNpNaU&H+iAPO84K}ny)g_^Bo=>Cn-qGCr((^RuWspo$g!nrcS9C6~%*bf-PEpZ( zSE}HhqYCkwIl?|(gNwFT&-JEoGi6`6s@^IZwl7d3NZ%j4l^@3MQ*LtMFGe<&AD>s5 z{^98*|HIp*{USrh%;e8PiZ`6UK;&5H+s4U{q*Uxl?LSW#pS?8O!H{y(G?2_o?-(kb zzV9S{+jO^id7AEaYgHkIXB(<3$P391g~Yyz`!w9F*@=gE!||9K){-(yJJ_wN0v6By zxTGZQb~jJ3*vnfgT+9 zmsK{0;Dv3oUy%~qV|^OvG}{Y-@a?BrTDsUZoA)Z-)p`7 z8bY)-Wv*o+wqT+A>GdT@i6{BoLkwSe9zZ!Jit_iCx4bA~aq=)!59RI*D6(Gr`7emP zUeW8WS$?&0Rp`X2j`(;x<6G=j*a)=fVJ*9Rsm;|ZQ*Mkk7LlZ^8TYJV_KnJ9bu0hf zH07&Z#t|pHbvac-?G*v#ZGCMh>-*aNw;L-MBV!c<%3U+Zn~=W!Ue&&3%G+ce?9?S> z(8}efgw{qp(sy&DOc_5NSBqMvF*}}}OUxwmMV4o%ntf1PE~?y_m&ZPSL-gcAd%c-W zLXTcg_@nm=RbiK%Ra^pi&l4kH z&{Y+7hzZP_=mNE*GXW@8537fSTXShqXqc%O)R;-365On8zCwUcCa@qjn?XPzI2?{1 z2ct)41|m>~hK2|v8i7W`K@B)-Z#bL8g@>~=co1JOtN<37Nn@~S^l&H-lN3OYWShWX z;5hUj|H2qV;y3tk)>jrlJ`h|I1A)>*BErHDKU%QZ)=?nHSBL(i1VW27toE7!cl(zOnmv0t43Ib_ij8!X;?4LB* zH0pPV<;SkcLmJooIaOklkE2^2b+Mj@=;q5&Kl z7eGeCNhk~+jzy6va6~Q&IYGJenK; zdV|8l4N)KzULQ@S8tPNAB#izl6opK%p)gFc-?qwf8`w0X-1YWyYXb~F|^|K3&6mo?=MM0|Pr z@)$~6T})8u>ark^$X`NWk)i;~s-Ga%mmzWxDLfDW`^VRU{YOsw55+*zC!gW>1du>td4)p4{EW_`Q`sC66WA6A@(6MT7U(KhQ0=d&+VZnLCkWu> z0i+C$1h4Ou!4O}AMesVtKhYW^{udv{s|r7~7|`yE3~XIsCq#T}g;H`|vG0c|AROEQaloU}aO?g# z@R%jau-nOkK-R9~efc1H1xlb$m~BtA7M>K~7f{#EbU`M7C+83LR@*$Z?;bg36y(k) zcd+T2KOX-;x(}=6+25~x;eoimg1slfTSrf!KmLmL3D}sx<1y%1#q+T-9X*(2;%P}f z*9h6LB$*_+{D7*;yg!~3qmSDp57mlBy)KTE{CvwWnI--t9^IhpQtFpkG%~XeuZhw= ze52>JE7>7$Ute<>q8Qc0}R<-|;`yM~h-RJBC-W;B3m(TAjrTO68Jv$*@Dy)!ekY>S< zW|%>6!CK7Rw)vIj;B(y*({zvQ<~4qN(^|ooYEiOW!7I6?Qj#}^th4%c{M7|uB3`hV zOuk2m4N1B~hM`wKdhOF$qo-p~sPsZ|ALFwAmChkCB_qSyW*cQCHYw-QBcka(Z*i{h zu@T&pVSe*L^Y>Ebf`SOGEDM^SxQKu~-^k}RgRH{z38;Am?@VrQ?PPVqVo&1#0L7X~ AvH$=8 literal 0 HcmV?d00001 diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index cbfeb3c9..760f1c56 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -33,8 +33,8 @@ public void run(Context context) { int imageDisplayed = 0; int num = 0; - String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png"}; - + String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png", "brian.png"}; + context.startAsync(new PlayAnimation("anim", 4, 12, true)); while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); @@ -42,12 +42,12 @@ public void run(Context context) { // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. - if (joystick0.getButtonPressed(1)) { + /*if (joystick0.getButtonPressed(1)) { imageDisplayed = (++imageDisplayed) % imageList.length; num++; context.startAsync(new DisplayImage(imageList[imageDisplayed], (num / imageList.length) % 4, true)); - } + }*/ } } } diff --git a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java index 0ec5ca08..2f29298d 100644 --- a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java +++ b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java @@ -46,7 +46,7 @@ public CANdleMech(int matrixStart, int w, int h) { public void setColor(short r, short g, short b, int index, int count) { checkContextOwnership(); - m_candle.setLEDs(r / 5, g / 5, b / 5, 0, index, count); + m_candle.setLEDs(r / 3, g / 3, b / 3, 0, index, count); } public int getMatrixID(int x, int y) { diff --git a/src/main/java/com/team766/robot/procedures/DisplayImage.java b/src/main/java/com/team766/robot/procedures/DisplayImage.java index 8b253073..ac5f6c4a 100644 --- a/src/main/java/com/team766/robot/procedures/DisplayImage.java +++ b/src/main/java/com/team766/robot/procedures/DisplayImage.java @@ -16,10 +16,10 @@ public class DisplayImage extends Procedure { - final int h = Robot.candle.h; - final int w = Robot.candle.w; - String file; - boolean interlacing; + private final int h = Robot.candle.h; + private final int w = Robot.candle.w; + private String file; + private boolean interlacing; private int rotation = 0; @@ -124,7 +124,7 @@ public void display(Color[][] colors, Context context, boolean interlacing) { Robot.candle.getMatrixID(i, j), 1); context.releaseOwnership(Robot.candle); } - context.waitForSeconds(0.01); + context.waitForSeconds(0.0001); } } } diff --git a/src/main/java/com/team766/robot/procedures/PlayAnimation.java b/src/main/java/com/team766/robot/procedures/PlayAnimation.java new file mode 100644 index 00000000..64d937a7 --- /dev/null +++ b/src/main/java/com/team766/robot/procedures/PlayAnimation.java @@ -0,0 +1,44 @@ +package com.team766.robot.procedures; + +import java.io.File; +import java.io.IOException; +import java.nio.file.Path; + +import javax.imageio.ImageIO; + +import com.team766.framework.Context; +import com.team766.framework.Procedure; +import com.team766.logging.Severity; +import com.team766.robot.Robot; +import com.team766.robot.procedures.DisplayImage; + +import edu.wpi.first.wpilibj.Filesystem; +import java.awt.image.BufferedImage; + +public class PlayAnimation extends Procedure { + + private String folder; + private int length = 1; + private double framerate; + private boolean loop; + + public PlayAnimation(String folder, int length, double framerate, boolean loop) { + this.folder = folder; + this.framerate = framerate; + this.length = length; + this.loop = loop; + } + + + public void run(Context context) { + do { + for (int i = 0; i < length; i++) { + context.startAsync(new DisplayImage(folder + "/" + i + ".png", false)); + context.yield(); + context.waitForSeconds(1 / framerate); + } + context.yield(); + } while (loop); + } + +} From 8fb9c0b52fd3fc31f0fe2d3faf80eca5fe5c30ff Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Fri, 3 Mar 2023 20:00:50 -0800 Subject: [PATCH 080/103] added constants --- .../robot/Constants/SwerveDriveConstants.java | 28 +++++++++++++++++++ src/main/java/com/team766/robot/OI.java | 18 ++++-------- .../com/team766/robot/mechanisms/Drive.java | 16 +++++------ 3 files changed, 41 insertions(+), 21 deletions(-) create mode 100644 src/main/java/com/team766/robot/Constants/SwerveDriveConstants.java diff --git a/src/main/java/com/team766/robot/Constants/SwerveDriveConstants.java b/src/main/java/com/team766/robot/Constants/SwerveDriveConstants.java new file mode 100644 index 00000000..5699ee58 --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/SwerveDriveConstants.java @@ -0,0 +1,28 @@ +package com.team766.robot.constants; + +public final class SwerveDriveConstants { + + public static double FirstFrontRightAngle = 135; + public static double FirstFrontLeftAngle = 45; + public static double FirstBackRightAngle = -135; + public static double FirstBackLeftAngle = -45; + + public static double SecondFrontRightAngle = -45; + public static double SecondFrontLeftAngle = -135; + public static double SecondBackRightAngle = 45; + public static double SecondBackLeftAngle = 135; + + public static double ratio = 2048.0 / 360.0 * (150.0 / 7.0); + + public static double P = 0.2; + public static double I = 0.0; + public static double D = 0.1; + public static double FF = 0.0; + + public static double CrossFrontRightAngle = -45; + public static double CrossFrontLeftAngle = 45; + public static double CrossBackRightAngle = 135; + public static double CrossBackLeftAngle = -135; + + +} diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 783db8e1..a38d6c71 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -49,6 +49,9 @@ public void run(Context context) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); RobotProvider.instance.refreshDriverStationData(); + LeftJoystick_X = Robot.drive.correctedJoysticks(joystick0.getAxis(0)); + LeftJoystick_Y = Robot.drive.correctedJoysticks(joystick0.getAxis(1)); + RightJoystick_X = Robot.drive.correctedJoysticks(joystick1.getAxis(0));; // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. @@ -57,19 +60,8 @@ public void run(Context context) { }else{ Robot.drive.setGyro(Robot.gyro.getGyroYaw()); } - if(Math.abs(joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ - RightJoystick_Y = joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); - } else { - RightJoystick_Y = 0; - } - if(Math.abs(joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ - RightJoystick_X = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; - if(joystick1.getButton(3)){ - RightJoystick_X *= 2; - } - } else { - RightJoystick_X = 0; - } + + if(joystick0.getButtonPressed(1)) Robot.gyro.resetGyro(); diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 99966b3e..b6d5e355 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -378,19 +378,19 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta double brAngle; double blAngle; if (JoystickTheta >= 0) { - frPower = NewMag(power, angle, JoystickTheta, 135); - flPower = NewMag(power, angle, JoystickTheta, 45); - brPower = NewMag(power, angle, JoystickTheta, -135); - blPower = NewMag(power, angle, JoystickTheta, -45); + frPower = NewMag(power, angle, JoystickTheta, 45); + flPower = NewMag(power, angle, JoystickTheta, -45); + brPower = NewMag(power, angle, JoystickTheta, 135); + blPower = NewMag(power, angle, JoystickTheta, -135); frAngle = NewAng(power, angle, JoystickTheta, 45); flAngle = NewAng(power, angle, JoystickTheta, -45); brAngle = NewAng(power, angle, JoystickTheta, 135); blAngle = NewAng(power, angle, JoystickTheta, -135); } else { - frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); - flPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); - brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); - blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); + frPower = NewMag(power, angle, Math.abs(JoystickTheta), -135); + flPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); + brPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); + blPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); flAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); brAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); From 7216eeed1bf710e12cf014231544db374277d576 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Fri, 3 Mar 2023 20:37:28 -0800 Subject: [PATCH 081/103] Added filter --- src/main/deploy/colors/0.png | Bin 0 -> 957 bytes src/main/deploy/filter_adrian.png | Bin 0 -> 6324 bytes src/main/deploy/filter_raj.png | Bin 0 -> 6698 bytes src/main/java/com/team766/robot/OI.java | 10 ++--- .../robot/procedures/DisplayImage.java | 40 ++++++++++++++++++ 5 files changed, 45 insertions(+), 5 deletions(-) create mode 100644 src/main/deploy/colors/0.png create mode 100644 src/main/deploy/filter_adrian.png create mode 100644 src/main/deploy/filter_raj.png diff --git a/src/main/deploy/colors/0.png b/src/main/deploy/colors/0.png new file mode 100644 index 0000000000000000000000000000000000000000..6e3f6983461787d493c7a479a069c15ffba54f4a GIT binary patch literal 957 zcmV;u148_XP)EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsGfU5L6@u+>%*KhjjIvEmm!<07%i37*wE^UnOwGxMAicihP( zbs>yC=Ug}G{xEU%keJ#p)#MD7FTU7{O({#4d$BeQmjBay1gEILZtiMDt5nc)dKlEp z>hfq%M+^Y4lid=e=h(1gc0}ELa5DXyxH3xa=C-yr_?=aMT#~hls0{!MAx{jO2Y}g< zyloxt29P~#G!TVcB#)Q(1QX#hzT>^r#-@%A5$3EqGGCF4g@cI>qZZUKohJI(X{-n< zxPY!sey|=Noj8xPK`q5JCNbjJ#JHp%4(Z0Cb}qQp+^~G5u=JJe1-+yg8{sFqXybYC zB>OL@+-@l@KJ<8!>O6Dv$Y77`5xe-6Ca#qX9&EPRQZ%|$UwA34N+BE#REetoPJTz( z#y~V%ipDmvPxY>6(f4di`ZPZ8)W~-bm8AJbHn#hTnfJt&2hyG)L#J)aP==;qOe{I|!fV f*w2Jl(l`7Czx|}{++kgB00000NkvXXu0mjfxfshQ literal 0 HcmV?d00001 diff --git a/src/main/deploy/filter_adrian.png b/src/main/deploy/filter_adrian.png new file mode 100644 index 0000000000000000000000000000000000000000..a8e63fd900d6218074e55644b1adcef4b0aef638 GIT binary patch literal 6324 zcmeHKc{r5o`yY`#p%Yrv7%Hk+jWIK}EMa77Y(>cM5=mMVSwa*-DckoQEvNJQeXr|#o$LC3|7))Iedm4e=e|GBeSe<&xu55Wrfjxb zptw{K0)Z?b+1ogS|EiK(UKV_=9GwLq5ZUk$S9hT^5CrA%xlEQn11b#WF`x_)iwS{< zo?qJLnJ}oYGVQzgri`9URL{-hrQ2(VhV>oZW*g6{ydC8iPb}!KNlCg`xG40uIE&(e?aZA zqltIB=Jndvl@X4X+chqYU@c$DtTI>9d*c=i?}SH{%ik%+UTXJRmiIhoY_tauT>IQR z>#Ww2nzCAD-x>$CPl*%m$xn>4<93vdroMY>P}2K2IZ^w**1(d(`$g=#PZn3S&&MJ3 z%S+Iagf#O}Pt{)ikpa1w43kiksfuZnL32fm&%<${jb{q$b5`mv)tCCc9YL8vXZjdT zx$SW)jw(mmzkEHp@7C!FQ{m@s_oe>>nf5a$g!xS|q1 z1es(ES0kr9`VF35yOYbyuO5gh!R#+d!Zj#NYQ!&0GI-3IrwZ$9Kt-ynMjdh%TkV8x zgWYwKq8#o?KZt~GAdDW2UvIEjB`GO|lm6$`Py9D`{Fb(;Z|HV)o{xhEgsn=b$Xu(a zGM--8oxUm0!U5$dGmWNdW}E2=)FJ8+}d^pO{(_-G)-(K>2 z%i6}Dl)apmYRwp{Ig$C{v0diJF-;@u@sxp;r)?vba?d@v^(8Cv8Rg=U({7tT+)<7y zP*uIGB&C|B$#fze)Z{A}UR|QMk*Srci31*4DXTspr>_htn1p^R<|%p1YH+4zk1Hu% zKOkKS=?lI0&iH(N%e5-oLHg?$mSfGWXGFh+`}#$NxY&_3Q5`q!R%N?4M14-vThbHj z(C*^&!K=J2@sWqpcFeQ%S1lh6GE2=HtG%|HtT}yU@SYN-VNZkeLi^^kxjP1oFJDe? zslq*~X?-ScVxC_-Diw%apkJih5IR;pAn3^RrS(3|yp#pGcFit&W7`qG_XgpoF`r(? zwjFucR2|Z*EBDd!;06_}^A%J8<`c!GTV~lzQOLYl4L{4ZmxZ}8hYX%z>!)o$FE7>F z=V@a7{vh#q+eZVe4u0`uCX0Y{XzmHKz}I?67q;XPA09dIX7 zt8Zk_>#q1fJl^KWR?a%Z*1^Q&iI4WjIFKu9$_{l~Evg8RD%76 zp*Dca4a~aq?iI}jEUj>5ADm5G`z{@g6DPSjMU~+xY4oy_^>n_^TJQGO4VFqWR^~AZ zeq|bwT?vQRUrV_)o&Ab;BMNRu4cHexLr@z=jA~8TzH{H#0hB(qvqu;jT*$__M<2FT zcv0bOR#OkD)IERYh#CC(scYow*f;M23U$`cyV#;J_G0Lq^n$~7c^pFugb=J%3utarl z=#vjZkk~fn2h(C|WwLwzS-YHyXz~W$7ecDNg-Dd8XOe$?Y}4+GDIR}@%#cK%C!HJi zmAfB(gXO{drQH6bi-=$@5*TzuQZ z;r9Q0+*ol{qbh@l^d4d+tKW>acxAP>Yf_P{ECS4 zQDxYkB4sy!q z+5i4w)5UJG?1W7xLA*?3M0TW3oGo~@M&(MvIn~TX$Ce2#JMHpn5#@Uj#P!2<`SGOs zMTevBQRQm2>l`8-Ov%fgT#tS@lv}IV3vbw+UA6sFH&VH$C<)ujQqhfDrFZt zF*0Fihen@=V6Wf1t}&?^%C=hL+Z8&f?dJvqjs*n;ef&6-y7hpCi5owjQAXDWHw}R- zaC6{Jb|licYy?2(QW*#ln+I+lAP`dv5f7mGF@#Vm!8El&o8Aaw< zGj_4;L--7rkj<{N5I-7$4zn;r}p z?qmwon#*TEu?Q>z1>Y!Q1!7?4icnKNok?`IvHb=Cewo2`357f&5(!3u2r@))`MyXr zfj~f_Fh~pr4r;&!!5kqVf^!7A5{R!DHVgrc&*BMLTn#R?xp3$-B*UM<22}-Mujs#ZX-6VceppB-@MW=ib5J zbK(5#2x$HT_ix(YW1mw7wa8?m4VM-magStU29xwpq;qL3I&tpR5RJkb8RGyroyx?) zv2-i|2aNG3@IhyyaC96Ng9m=k)CctTc5gLv)L>a;H zOoA~SXACfnXvP>c6+`$5Vhf)IW+mYNvsV%*ItayJQ0ZuZMu$^TbQB!R#2Ui!cnkqf zKpPujsWcpb#Zu>>=rp1&m(K>k;bgG^Uj~xL@ttds5KgqDkj!8h1nMsd#UBtdK?86O zusC#Xkl?Q-R~DP$A_OFSqH)H?1eBp63WZ1G@F?tGN?RFx0ho&tR5S`{eS zh{h6)2yhghi26yNOJ^~I|C6?4`an&;4!S){0QMg|C;B?4To`-4etrG)XU$C}D0FUG z5CPiP5ClLVgFfdci1oFJwhQ3+GQj%rEn&aQS^p*(=mZQNO~BCL01iulV+klU91k#= za3j1Cj>$k7F{zmUgD&7Qg+TzHVd)F<2yz7`=p0v2{cl5M@ON*5b}=O508$1=Nv=7{ zj3i_szXgkwRE+P@nj-%nAEt8(Kb08J?yC$eU0@|d{wRgt_>vTz|Kac3IQ$QL0HJ?% z@{joaMb|I7{t*NJNcmTG{i5q1G4PL+e`VKyjV{H%4pR&cxC06Tk4lga=XAhhmMnFX zoz2{VYxc3F>j&^nfoJa_fItwsl3PlYZ4n3x<%A^iM!8;T8JUHUV^vR8Adq=kBpXXt zeC_;-cl;MNT47DT7FQoVNM2rD(Up)e&ro@)V@0Xd`>16=bhZr&WHJ6+^^ zQueAIRUOldf5pis_7**F+!8H6k+pNj-W8korsJMkw9nQDAH}k3kqf!!DT9F~iaCE8 z9!k6Isk1%mT6b5iW`>V>Gj>Pm$dZq(nFpwEHR;~^e{_mJbTjTZ2KH%DfX=J!`7d7< z$W(jZ>?v=3h(Dp~k)QKGw^X-kai&ROTT{R`{@LSNjS4rOh?s%d)rTTnf@P#}hEGjb zJIab{nyLzO)soZ|k4nYj+-dRy4&Ji3YIu~dkF-F(PfsD~H``@;iaN4cHZi8vn)7ef zSgNbf15%p`sp@^IPMhv3s;(+fF>Jmb_JsaK-GzEInw1fa-Whx5U0zt_ZnCPq!eEI^ zRJba0DzLVz{2{hCBWqZcqcxfQhJU7}V=`#ru4Sn0_LlMq`P29->lcL%sQKYD;*Yr>=Xl zhv}nXvyKTHH9eD1l?GcAuO*IW9jtv0{C=7WEnd=9be62fhTq?v)wENcy1@oe8q&%M zug=+GYG!^V^6u-vhk4KQWMNirY|*DK&$rjbY`a1A`9n&tUX{O|5j`9q zf6$omndzdwf3stJ3UY@|?Rk~Ola(14F2u_S-1A?SP?9vRhC2!b&jouu3u@Q9_4mI> z-tH$W!#~VlVqn?q(=T3JCgW}s@43l794e*5;~;X6nW^iFQ77BtS%;irMguy=ADu|= ZIe$Qxmd#~U3x_;MtUBB;t&GkI| zz#tGv+TPCE6?n=CZwWErUwv|s1OkbdM!0+NTuFQgo5P~fgQ*bSUN#j%4X4vUpzvo! z+r85aHb~76DQ;c{Q3_etCGoOOz+dM2iB~%;SQxO&fck7LZfag$wI5ntuBB%2Sv(WrVH9W%E}&caO^!iy=>UEPk4Dx;9jUQ8OV z?Y_D7US6u60ONMU*i|_?Ve0{Ow=(JEr(M>E>+bUv(4{INXJ0MkGM;KdW7-N9wz+>u z-}DBnds*>t$jlu}<{Ukf^rlM;HbF4gu%k7w3?el$D3`S_u`R`o41@KxoE_yZY9 z3&XD=NzxZ57?Au;eWUO34L3TPphLZLlbX$|WA;11(pGexx>;0a5KCZ9R^B#3FTPD<+&;)kl2(dTD-~J5 z!yXki&3tw`p~Q|{y6mQwTl(wy@O{5-jBr3tsIoRv6Mu=h-V zTmP6U0$(KS)4Mhx_fvcF@ZRY6{12D1J1-K?;4yBlvb8h*1%K${zt$fQlHTp#!4&u| zYt!ydXAYJlWmjlD@XlaU=WWX;E5RIT#N)6B&08jncJ{0uvN+kY!enP?OWWkAjP@OI z{K6ZV@v4FjL3$MGc1QBXQpC;qH^Xt^A39|R#XhFM&R(2;oPs_$(2wlcB*A?%(YwfA z@O*%KIFvOg*k0N)o_KJrYGst*YN_M2e8JsUzBQX;#@uV##GkhvmG*pIoT$_@cu7Hl z7i%*+0JfZ!IZ$WcE%iW+bW{`Kd*aet`Tg~CqwD6I+ZF3XEc5$RA#Bta5zQ!w14w+U zbdT2wHPM!Lmuh=VuY(fpR%)m78&qRgTUyV*u1m~O(L1P2PQr2w%5)qwn$lgJ=4Rbo zQmm4(gIU;9J2Oq$uPMr*$0Xx(B>Te^9rY{OdU>9@MaOrR-SV?6YBLGUY0B_nzHqpr z_AvfxvU%qDO*4-+CYeijj>TEk^|{!bV?xtur$h2HH{3^$SYC$tkeW_2u{)9MEoQ9cTfC#mwC)PIc^f8KEaHXP2#NBd zPwM6>(fuTx`l)@T`!r_yXnpq=lg_?u&Xn$1jLYhNupm~sCuDB_v!~*)?A zK9a-=s5wwj-mdtU$ra>|$_2p1}lS-D*r| zcl@DIrSo?Dpvz&Oa8iM^8q2ug!)~o|lBthA`z(JX{civ15<(p)Ct@b)(Qt{z3N4t- z3_3AEkEoXVh3s3i9(DOv&AG>nCtFr7({;xeMS9%W<Ut&qDrRGHI`P z!N*?6U%Gs=>go)sN!_JcF)j_cCJCFZ(bj~O@Ozu>; zk|0^;(3ypUhEqufX=akUwj^KWhe@#eb3n((uAfdk=cQ;8|FWt0&(=FIht_oHRC%}Z zI{2{dpsSOkd$@9(wp50*7AM+nXIw%2SjW8z{?*7gtT2qsHI5pVp3E8*qQH z=Yz6(q4)hxoqedP_5dGZy-L!V5bo=bC;NgJ2hV`~uNHGjmv#N7PBEAKNYDF<}xlT8vd{i>C_O`s+|-OH`@Wj|F# zVt313IeRs&%G^|5R^06`!rE*`Uh1P<`GxpxT{a4H@vf?Y6}gEUGD?fhPCSlv(~04f z;iomCMg7}ayNWL)?0=b+p}gBNqu5}u^gei{KV17tu|1`;j_1E7avblmEmY^+RHtf= zZE1!+iV&hCQzwW^2*~#J%z1t|-qAO&cg;Q-k7q}_h$}tCysvI(Jg`l{HAJ5{pxdur zOwxW)8Kw0>B{x=E4;g%YK0g7!vZ!VAgZL7kPyub{r7n0Vzbgrjk=z?4LF5eS3_d-% zM!Fn&QmK6NX9vMneNVlS94#@~7rJ7$S3+gPvBOin%lmhi=024VPD>|PZkOH&TT?c1 zMTdIp;nDa%hA$^XjM<-2k&idEH&1SQ(s)jc_P$|_Z^mu-ojET}iE%{q;E9bA{_irG z?(g%paJSX2qeYglJ=TTMUUf^UarGHnR034%nk3I1y-&9gk))#+SB1c(BB^>7t-v!qJID7#7pjF5=ss`ay-OO zIM!aUw@Mor(5+BfH}7>7S7AExu1{ZLzdEEC?vw;~9av1WJfbX{JojO&_tlsh1f##z zNK_%V(A!3Ty~4Fh57aCezfA5y3hHoX1hnRK+|cZ;Ln$SEm-B;BWA`6kc}*0XwI0Cc zt15jE`_P)7$L-x9b1f}bE?Xf*m1i+vTigP#4T0kfCR$5V?b{R%9d7ayZ&7P?IOt$T zT<79`?Bju}E#M(odtlyOpPAPPsln?fF;D0+n#tN)#}g#h8l}6$9ndXO(bI7)SD&1a z#eUVQq;O8wH1H8k)lA^QWiBGd*MQn>;wF)GCS^u*V9c1A8ei;#M4)#ekD2EI%qd zoWTb6S|E@aKAcS=2T^$tKdL{SX$~E)s)a)66m#fyBO;Q>wxR~m?IJi-w+JV9azqdr zOM&7ygU!Nm004u^BSFF$!AveL+#I@uiv!+;-3TaTNrV?<4)r2BL#$XFDg*<^z>zRQ zI6Vvv-3*49aVRvLtF_H{2%u#S4dC(EI0OQS0?s#tvpD_;6c&p`Akhdk8U{$fxO99atIS4RN#pSb^!{t^3< zFd#)F;;dQZP@#MF*5**5eH?{Frc-cBuPCY?#t4lxhM`F$V;IKBhz9dBK~Z5OLlo5r zMI}*DMy9_&*)zF35|d07LIL1#I)Fo>nxJV|V-pzJ4@-q%jA;~@sWBD>BO4kc(MT-X zl!P|?1!5bA4rC=M_*bulP!s?Pg(j2yC>TGOAq9hlVaP~R7>R_!z$ktsQyRtygTat# zOHdRt&W6Qdkbvo=Gf4ha1e@uqp&z5Qykh9hBUe@F%l35&weC`K@2v@oAcjE!I13s?yeKbOMqd;z}xH-F#f;lF7D0{Ly^U-A2!uHSV1 zD+d0R@bB#UP1nC-;9m*<&aVGAy1;)Qrl?F{2gC=CN{R~kvA{7)%+Jx*T6o?9Ep}SC ze*~T@*>>Js5D2a*yhXzE@L@owIM1F)5FZj2!ZH4|SYgPH{_6m^0BR6uL zf>X?=&k1Ty5xhzlc)47q?Ab3@5Y=26jXG>fx_qnwqH-(-sW&?$PuWIKD&jJ>G6xR-(mI)Cu+gjN(3COGPDA;=(#~UUV6A%w)F`fMT!DeZ z)L^#%Wk{V*3Tmylr(DoI!KN#`Q-0~LihJ$-PfyG<8k|Z5&+g*7{o>M9qNb)|ZHkg- zN?$P8C$#X{~vy0y5-F@g<*^gx{*IV+{7=;|=FP_zD1Mf>AH?Mhhpj-Y-= zfoyFpCFYt{jZc3mo^q`Rv<`iIK4NyiQ`O;g@WPvU6Qz7>Ti7!TyQ=)mytPH1M;5ki zzVI;6aPPci^yXI!%y{&eoF^3ir39s86*)OL)Vt$IA!e=AU5TOYXYU{G^sx*g=6MQE zYTtXC(eX;NU2J6u`0&K~qSd!Bh7-v?ml}J&n)lv5E8m17xcC+|iB2AF}UWObh*q%U6EmAeJ)q0LvO2Xz>Y^fUK^4M z4Qy^6MciL`U2I&Wew+CH%F1&WR-NaW_P;9;nQSd>mQ267b@yW9Cqi~0q3jt$-p<~` l(o@j@aotYoU`OrC34~`rY+(@-k|(SZdxDd7v8C_+{{h%quD$>O literal 0 HcmV?d00001 diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 760f1c56..6b1f02a7 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -33,8 +33,8 @@ public void run(Context context) { int imageDisplayed = 0; int num = 0; - String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png", "brian.png"}; - context.startAsync(new PlayAnimation("anim", 4, 12, true)); + String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png", "brian.png", "filter_adrian.png", "filter_raj.png"}; + //context.startAsync(new PlayAnimation("anim", 4, 12, true)); while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); @@ -42,12 +42,12 @@ public void run(Context context) { // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. - /*if (joystick0.getButtonPressed(1)) { + if (joystick0.getButtonPressed(1)) { imageDisplayed = (++imageDisplayed) % imageList.length; num++; - context.startAsync(new DisplayImage(imageList[imageDisplayed], (num / imageList.length) % 4, true)); - }*/ + context.startAsync(new DisplayImage(imageList[imageDisplayed].substring(0, 7).equals("filter_"), imageList[imageDisplayed], (num / imageList.length) % 4, true)); + } } } } diff --git a/src/main/java/com/team766/robot/procedures/DisplayImage.java b/src/main/java/com/team766/robot/procedures/DisplayImage.java index ac5f6c4a..f56227b0 100644 --- a/src/main/java/com/team766/robot/procedures/DisplayImage.java +++ b/src/main/java/com/team766/robot/procedures/DisplayImage.java @@ -20,6 +20,7 @@ public class DisplayImage extends Procedure { private final int w = Robot.candle.w; private String file; private boolean interlacing; + private boolean filter = false; private int rotation = 0; @@ -45,6 +46,32 @@ public DisplayImage(String file, int rotation) { this.rotation = rotation; } + public DisplayImage(boolean filter, String file, boolean interlacing) { + this.file = file; + this.interlacing = interlacing; + this.filter = filter; + } + + public DisplayImage(boolean filter, String file) { + this.file = file; + this.interlacing = true; + this.filter = filter; + } + + public DisplayImage(boolean filter, String file, int rotation, boolean interlacing) { + this.file = file; + this.interlacing = interlacing; + this.rotation = rotation; + this.filter = filter; + } + + public DisplayImage(boolean filter, String file, int rotation) { + this.file = file; + this.interlacing = true; + this.rotation = rotation; + this.filter = filter; + } + public void run(Context context) { File fileObj; Path path = Filesystem.getDeployDirectory().toPath().resolve(file); @@ -90,6 +117,19 @@ public void run(Context context) { } } + if (filter) { + int min = 100; + int max = 255; + double factor = max - min; + for (int i = 0; i < h; i++) { + for (int j = 0; j < w; j++) { + colors[i][j].r = (short) ((Math.min(Math.max(min, colors[i][j].r), max) - min) * (255 / factor)); + colors[i][j].g = (short) ((Math.min(Math.max(min, colors[i][j].g), max) - min) * (255 / factor)); + colors[i][j].b = (short) ((Math.min(Math.max(min, colors[i][j].b), max) - min) * (255 / factor)); + } + } + } + display(colors, context, interlacing); } From 1ca79ae67400afd3cc44db9ee1639140967219b9 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 10:39:20 -0800 Subject: [PATCH 082/103] Able to apply filter by adding "filter_" in OI --- src/main/deploy/{filter_adrian.png => adrian.png} | Bin src/main/deploy/{filter_raj.png => raj.png} | Bin src/main/java/com/team766/robot/OI.java | 4 +++- 3 files changed, 3 insertions(+), 1 deletion(-) rename src/main/deploy/{filter_adrian.png => adrian.png} (100%) rename src/main/deploy/{filter_raj.png => raj.png} (100%) diff --git a/src/main/deploy/filter_adrian.png b/src/main/deploy/adrian.png similarity index 100% rename from src/main/deploy/filter_adrian.png rename to src/main/deploy/adrian.png diff --git a/src/main/deploy/filter_raj.png b/src/main/deploy/raj.png similarity index 100% rename from src/main/deploy/filter_raj.png rename to src/main/deploy/raj.png diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 6b1f02a7..83e05bbd 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -46,7 +46,9 @@ public void run(Context context) { imageDisplayed = (++imageDisplayed) % imageList.length; num++; - context.startAsync(new DisplayImage(imageList[imageDisplayed].substring(0, 7).equals("filter_"), imageList[imageDisplayed], (num / imageList.length) % 4, true)); + boolean filter = imageList[imageDisplayed].substring(0, 7).equals("filter_"); + + context.startAsync(new DisplayImage(filter, filter? imageList[imageDisplayed].substring(7) : imageList[imageDisplayed], (num / imageList.length) % 4, true)); } } } From 0256c772eb536a46f72d1b519720eb1399b677b6 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 13:01:52 -0800 Subject: [PATCH 083/103] Added ability to display purple & yellow --- src/main/java/com/team766/robot/OI.java | 32 +-- .../team766/robot/mechanisms/CANdleMech.java | 12 +- .../robot/procedures/DisplayImage.java | 189 ------------------ .../robot/procedures/PlayAnimation.java | 44 ---- 4 files changed, 22 insertions(+), 255 deletions(-) delete mode 100644 src/main/java/com/team766/robot/procedures/DisplayImage.java delete mode 100644 src/main/java/com/team766/robot/procedures/PlayAnimation.java diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 83e05bbd..392f99e7 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -29,27 +29,31 @@ public OI() { } public void run(Context context) { - context.startAsync(new DisplayImage("cone.png", true)); - int imageDisplayed = 0; - int num = 0; - - String[] imageList = {"cone.png", "cone-2.png", "cube.png", "cube-2.png", "progamer.png", "tnt.png", "torchflower.png", "quaver.png", "brian.png", "filter_adrian.png", "filter_raj.png"}; - //context.startAsync(new PlayAnimation("anim", 4, 12, true)); + int color = 0; + context.takeOwnership(Robot.candle); + Robot.candle.setColor(0, 0, 0); + context.releaseOwnership(Robot.candle); + while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); RobotProvider.instance.refreshDriverStationData(); - // Add driver controls here - make sure to take/release ownership - // of mechanisms when appropriate. if (joystick0.getButtonPressed(1)) { - imageDisplayed = (++imageDisplayed) % imageList.length; - num++; - - boolean filter = imageList[imageDisplayed].substring(0, 7).equals("filter_"); - - context.startAsync(new DisplayImage(filter, filter? imageList[imageDisplayed].substring(7) : imageList[imageDisplayed], (num / imageList.length) % 4, true)); + color = (++color) % 3; + context.takeOwnership(Robot.candle); + log(color + " "); + switch (color) { + case 0: Robot.candle.setColor(0, 0, 0); break; + case 1: Robot.candle.setColor(255, 0, 255); break; + case 2: Robot.candle.setColor(255, 255, 0); break; + } + context.releaseOwnership(Robot.candle); } + + // Add driver controls here - make sure to take/release ownership + // of mechanisms when appropriate. + } } } diff --git a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java index 2f29298d..2005b7ee 100644 --- a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java +++ b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java @@ -46,16 +46,12 @@ public CANdleMech(int matrixStart, int w, int h) { public void setColor(short r, short g, short b, int index, int count) { checkContextOwnership(); - m_candle.setLEDs(r / 3, g / 3, b / 3, 0, index, count); + m_candle.setLEDs(r / 5, g / 5, b / 5, 0, index, count); } - public int getMatrixID(int x, int y) { - if (y % 2 == 0) { - return h * y + x + matrixStart; - } else { - return h * y + w - 1 - x + matrixStart; - } + public void setColor(int r, int g, int b) { + checkContextOwnership(); + m_candle.setLEDs(r / 5, g / 5, b / 5); } - } \ No newline at end of file diff --git a/src/main/java/com/team766/robot/procedures/DisplayImage.java b/src/main/java/com/team766/robot/procedures/DisplayImage.java deleted file mode 100644 index f56227b0..00000000 --- a/src/main/java/com/team766/robot/procedures/DisplayImage.java +++ /dev/null @@ -1,189 +0,0 @@ -package com.team766.robot.procedures; - -import java.io.File; -import java.io.IOException; -import java.nio.file.Path; - -import javax.imageio.ImageIO; - -import com.team766.framework.Context; -import com.team766.framework.Procedure; -import com.team766.logging.Severity; -import com.team766.robot.Robot; - -import edu.wpi.first.wpilibj.Filesystem; -import java.awt.image.BufferedImage; - -public class DisplayImage extends Procedure { - - private final int h = Robot.candle.h; - private final int w = Robot.candle.w; - private String file; - private boolean interlacing; - private boolean filter = false; - - private int rotation = 0; - - public DisplayImage(String file, boolean interlacing) { - this.file = file; - this.interlacing = interlacing; - } - - public DisplayImage(String file) { - this.file = file; - this.interlacing = true; - } - - public DisplayImage(String file, int rotation, boolean interlacing) { - this.file = file; - this.interlacing = interlacing; - this.rotation = rotation; - } - - public DisplayImage(String file, int rotation) { - this.file = file; - this.interlacing = true; - this.rotation = rotation; - } - - public DisplayImage(boolean filter, String file, boolean interlacing) { - this.file = file; - this.interlacing = interlacing; - this.filter = filter; - } - - public DisplayImage(boolean filter, String file) { - this.file = file; - this.interlacing = true; - this.filter = filter; - } - - public DisplayImage(boolean filter, String file, int rotation, boolean interlacing) { - this.file = file; - this.interlacing = interlacing; - this.rotation = rotation; - this.filter = filter; - } - - public DisplayImage(boolean filter, String file, int rotation) { - this.file = file; - this.interlacing = true; - this.rotation = rotation; - this.filter = filter; - } - - public void run(Context context) { - File fileObj; - Path path = Filesystem.getDeployDirectory().toPath().resolve(file); - fileObj = path.toFile(); - BufferedImage image; - Color[][] colors = new Color[h][w]; - - try { - image = ImageIO.read(fileObj); - } catch (IOException e) { - e.printStackTrace(); - log(Severity.ERROR, "Could not load " + file); - return; - } - - switch (rotation) { - case 1: - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - colors[j][h - i - 1] = new Color(image.getData().getPixel(j, i, (double[]) null)); - } - } - break; - case 2: - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - colors[h - i - 1][w - j - 1] = new Color(image.getData().getPixel(j, i, (double[]) null)); - } - } - break; - case 3: - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - colors[w - j - 1][i] = new Color(image.getData().getPixel(j, i, (double[]) null)); - } - } - break; - default: - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - colors[i][j] = new Color(image.getData().getPixel(j, i, (double[]) null)); - } - } - } - - if (filter) { - int min = 100; - int max = 255; - double factor = max - min; - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - colors[i][j].r = (short) ((Math.min(Math.max(min, colors[i][j].r), max) - min) * (255 / factor)); - colors[i][j].g = (short) ((Math.min(Math.max(min, colors[i][j].g), max) - min) * (255 / factor)); - colors[i][j].b = (short) ((Math.min(Math.max(min, colors[i][j].b), max) - min) * (255 / factor)); - } - } - } - - display(colors, context, interlacing); - } - - public void display(Color[][] colors, Context context, boolean interlacing) { - if (interlacing) { - for (int i = 0; i < h; i += 2) { - for (int j = 0; j < w; j++) { - log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); - context.takeOwnership(Robot.candle); - Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, - Robot.candle.getMatrixID(i, j), 1); - context.releaseOwnership(Robot.candle); - } - context.waitForSeconds(0.01); - } - for (int i = 1; i < h; i += 2) { - for (int j = 0; j < w; j++) { - log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); - context.takeOwnership(Robot.candle); - Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, - Robot.candle.getMatrixID(i, j), 1); - context.releaseOwnership(Robot.candle); - } - context.waitForSeconds(0.01); - } - } else { - for (int i = 0; i < h; i++) { - for (int j = 0; j < w; j++) { - log(colors[i][j].r + " " + colors[i][j].g + " " + colors[i][j].b); - context.takeOwnership(Robot.candle); - Robot.candle.setColor(colors[i][j].r, colors[i][j].g, colors[i][j].b, - Robot.candle.getMatrixID(i, j), 1); - context.releaseOwnership(Robot.candle); - } - context.waitForSeconds(0.0001); - } - } - } - - public class Color { - public short r; - public short g; - public short b; - - public Color(short r, short g, short b) { - this.r = r; - this.g = g; - this.b = b; - } - - public Color(double[] color) { - r = (short) color[0]; - g = (short) color[1]; - b = (short) color[2]; - } - } -} diff --git a/src/main/java/com/team766/robot/procedures/PlayAnimation.java b/src/main/java/com/team766/robot/procedures/PlayAnimation.java deleted file mode 100644 index 64d937a7..00000000 --- a/src/main/java/com/team766/robot/procedures/PlayAnimation.java +++ /dev/null @@ -1,44 +0,0 @@ -package com.team766.robot.procedures; - -import java.io.File; -import java.io.IOException; -import java.nio.file.Path; - -import javax.imageio.ImageIO; - -import com.team766.framework.Context; -import com.team766.framework.Procedure; -import com.team766.logging.Severity; -import com.team766.robot.Robot; -import com.team766.robot.procedures.DisplayImage; - -import edu.wpi.first.wpilibj.Filesystem; -import java.awt.image.BufferedImage; - -public class PlayAnimation extends Procedure { - - private String folder; - private int length = 1; - private double framerate; - private boolean loop; - - public PlayAnimation(String folder, int length, double framerate, boolean loop) { - this.folder = folder; - this.framerate = framerate; - this.length = length; - this.loop = loop; - } - - - public void run(Context context) { - do { - for (int i = 0; i < length; i++) { - context.startAsync(new DisplayImage(folder + "/" + i + ".png", false)); - context.yield(); - context.waitForSeconds(1 / framerate); - } - context.yield(); - } while (loop); - } - -} From a443f2dc6523f658636a3b5b6d3d0ef31bb164ef Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 13:13:29 -0800 Subject: [PATCH 084/103] Added documentation --- docs/candle.md | 7 +++++++ src/main/deploy/adrian.png | Bin 6324 -> 0 bytes src/main/deploy/anim/0.png | Bin 603 -> 0 bytes src/main/deploy/anim/1.png | Bin 595 -> 0 bytes src/main/deploy/anim/2.png | Bin 591 -> 0 bytes src/main/deploy/anim/3.png | Bin 589 -> 0 bytes src/main/deploy/brian.png | Bin 6506 -> 0 bytes src/main/deploy/colors/0.png | Bin 957 -> 0 bytes src/main/deploy/cone-2.png | Bin 6078 -> 0 bytes src/main/deploy/cone.png | Bin 5719 -> 0 bytes src/main/deploy/cube-2.png | Bin 270 -> 0 bytes src/main/deploy/cube-old.png | Bin 1330 -> 0 bytes src/main/deploy/cube.png | Bin 5753 -> 0 bytes src/main/deploy/example.txt | 2 -- src/main/deploy/progamer.png | Bin 1586 -> 0 bytes src/main/deploy/quaver.png | Bin 624 -> 0 bytes src/main/deploy/raj.png | Bin 6698 -> 0 bytes src/main/deploy/shulker_box.png | Bin 6238 -> 0 bytes src/main/deploy/tnt.png | Bin 6275 -> 0 bytes src/main/deploy/torchflower.png | Bin 5756 -> 0 bytes 20 files changed, 7 insertions(+), 2 deletions(-) create mode 100644 docs/candle.md delete mode 100644 src/main/deploy/adrian.png delete mode 100644 src/main/deploy/anim/0.png delete mode 100644 src/main/deploy/anim/1.png delete mode 100644 src/main/deploy/anim/2.png delete mode 100644 src/main/deploy/anim/3.png delete mode 100644 src/main/deploy/brian.png delete mode 100644 src/main/deploy/colors/0.png delete mode 100644 src/main/deploy/cone-2.png delete mode 100644 src/main/deploy/cone.png delete mode 100644 src/main/deploy/cube-2.png delete mode 100644 src/main/deploy/cube-old.png delete mode 100644 src/main/deploy/cube.png delete mode 100644 src/main/deploy/example.txt delete mode 100644 src/main/deploy/progamer.png delete mode 100644 src/main/deploy/quaver.png delete mode 100644 src/main/deploy/raj.png delete mode 100644 src/main/deploy/shulker_box.png delete mode 100644 src/main/deploy/tnt.png delete mode 100644 src/main/deploy/torchflower.png diff --git a/docs/candle.md b/docs/candle.md new file mode 100644 index 00000000..999075c6 --- /dev/null +++ b/docs/candle.md @@ -0,0 +1,7 @@ +# A Simple Guide on Using CANdle to Display Single Colors + +Use `Robot.candle.setColor(int r, int g, int b);` to display single colors on the CANdle. + +**Yellow:** R: 255 G: 255 B: 0 + +**Purple:** R: 255 G: 0 B: 255 \ No newline at end of file diff --git a/src/main/deploy/adrian.png b/src/main/deploy/adrian.png deleted file mode 100644 index a8e63fd900d6218074e55644b1adcef4b0aef638..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6324 zcmeHKc{r5o`yY`#p%Yrv7%Hk+jWIK}EMa77Y(>cM5=mMVSwa*-DckoQEvNJQeXr|#o$LC3|7))Iedm4e=e|GBeSe<&xu55Wrfjxb zptw{K0)Z?b+1ogS|EiK(UKV_=9GwLq5ZUk$S9hT^5CrA%xlEQn11b#WF`x_)iwS{< zo?qJLnJ}oYGVQzgri`9URL{-hrQ2(VhV>oZW*g6{ydC8iPb}!KNlCg`xG40uIE&(e?aZA zqltIB=Jndvl@X4X+chqYU@c$DtTI>9d*c=i?}SH{%ik%+UTXJRmiIhoY_tauT>IQR z>#Ww2nzCAD-x>$CPl*%m$xn>4<93vdroMY>P}2K2IZ^w**1(d(`$g=#PZn3S&&MJ3 z%S+Iagf#O}Pt{)ikpa1w43kiksfuZnL32fm&%<${jb{q$b5`mv)tCCc9YL8vXZjdT zx$SW)jw(mmzkEHp@7C!FQ{m@s_oe>>nf5a$g!xS|q1 z1es(ES0kr9`VF35yOYbyuO5gh!R#+d!Zj#NYQ!&0GI-3IrwZ$9Kt-ynMjdh%TkV8x zgWYwKq8#o?KZt~GAdDW2UvIEjB`GO|lm6$`Py9D`{Fb(;Z|HV)o{xhEgsn=b$Xu(a zGM--8oxUm0!U5$dGmWNdW}E2=)FJ8+}d^pO{(_-G)-(K>2 z%i6}Dl)apmYRwp{Ig$C{v0diJF-;@u@sxp;r)?vba?d@v^(8Cv8Rg=U({7tT+)<7y zP*uIGB&C|B$#fze)Z{A}UR|QMk*Srci31*4DXTspr>_htn1p^R<|%p1YH+4zk1Hu% zKOkKS=?lI0&iH(N%e5-oLHg?$mSfGWXGFh+`}#$NxY&_3Q5`q!R%N?4M14-vThbHj z(C*^&!K=J2@sWqpcFeQ%S1lh6GE2=HtG%|HtT}yU@SYN-VNZkeLi^^kxjP1oFJDe? zslq*~X?-ScVxC_-Diw%apkJih5IR;pAn3^RrS(3|yp#pGcFit&W7`qG_XgpoF`r(? zwjFucR2|Z*EBDd!;06_}^A%J8<`c!GTV~lzQOLYl4L{4ZmxZ}8hYX%z>!)o$FE7>F z=V@a7{vh#q+eZVe4u0`uCX0Y{XzmHKz}I?67q;XPA09dIX7 zt8Zk_>#q1fJl^KWR?a%Z*1^Q&iI4WjIFKu9$_{l~Evg8RD%76 zp*Dca4a~aq?iI}jEUj>5ADm5G`z{@g6DPSjMU~+xY4oy_^>n_^TJQGO4VFqWR^~AZ zeq|bwT?vQRUrV_)o&Ab;BMNRu4cHexLr@z=jA~8TzH{H#0hB(qvqu;jT*$__M<2FT zcv0bOR#OkD)IERYh#CC(scYow*f;M23U$`cyV#;J_G0Lq^n$~7c^pFugb=J%3utarl z=#vjZkk~fn2h(C|WwLwzS-YHyXz~W$7ecDNg-Dd8XOe$?Y}4+GDIR}@%#cK%C!HJi zmAfB(gXO{drQH6bi-=$@5*TzuQZ z;r9Q0+*ol{qbh@l^d4d+tKW>acxAP>Yf_P{ECS4 zQDxYkB4sy!q z+5i4w)5UJG?1W7xLA*?3M0TW3oGo~@M&(MvIn~TX$Ce2#JMHpn5#@Uj#P!2<`SGOs zMTevBQRQm2>l`8-Ov%fgT#tS@lv}IV3vbw+UA6sFH&VH$C<)ujQqhfDrFZt zF*0Fihen@=V6Wf1t}&?^%C=hL+Z8&f?dJvqjs*n;ef&6-y7hpCi5owjQAXDWHw}R- zaC6{Jb|licYy?2(QW*#ln+I+lAP`dv5f7mGF@#Vm!8El&o8Aaw< zGj_4;L--7rkj<{N5I-7$4zn;r}p z?qmwon#*TEu?Q>z1>Y!Q1!7?4icnKNok?`IvHb=Cewo2`357f&5(!3u2r@))`MyXr zfj~f_Fh~pr4r;&!!5kqVf^!7A5{R!DHVgrc&*BMLTn#R?xp3$-B*UM<22}-Mujs#ZX-6VceppB-@MW=ib5J zbK(5#2x$HT_ix(YW1mw7wa8?m4VM-magStU29xwpq;qL3I&tpR5RJkb8RGyroyx?) zv2-i|2aNG3@IhyyaC96Ng9m=k)CctTc5gLv)L>a;H zOoA~SXACfnXvP>c6+`$5Vhf)IW+mYNvsV%*ItayJQ0ZuZMu$^TbQB!R#2Ui!cnkqf zKpPujsWcpb#Zu>>=rp1&m(K>k;bgG^Uj~xL@ttds5KgqDkj!8h1nMsd#UBtdK?86O zusC#Xkl?Q-R~DP$A_OFSqH)H?1eBp63WZ1G@F?tGN?RFx0ho&tR5S`{eS zh{h6)2yhghi26yNOJ^~I|C6?4`an&;4!S){0QMg|C;B?4To`-4etrG)XU$C}D0FUG z5CPiP5ClLVgFfdci1oFJwhQ3+GQj%rEn&aQS^p*(=mZQNO~BCL01iulV+klU91k#= za3j1Cj>$k7F{zmUgD&7Qg+TzHVd)F<2yz7`=p0v2{cl5M@ON*5b}=O508$1=Nv=7{ zj3i_szXgkwRE+P@nj-%nAEt8(Kb08J?yC$eU0@|d{wRgt_>vTz|Kac3IQ$QL0HJ?% z@{joaMb|I7{t*NJNcmTG{i5q1G4PL+e`VKyjV{H%4pR&cxC06Tk4lga=XAhhmMnFX zoz2{VYxc3F>j&^nfoJa_fItwsl3PlYZ4n3x<%A^iM!8;T8JUHUV^vR8Adq=kBpXXt zeC_;-cl;MNT47DT7FQoVNM2rD(Up)e&ro@)V@0Xd`>16=bhZr&WHJ6+^^ zQueAIRUOldf5pis_7**F+!8H6k+pNj-W8korsJMkw9nQDAH}k3kqf!!DT9F~iaCE8 z9!k6Isk1%mT6b5iW`>V>Gj>Pm$dZq(nFpwEHR;~^e{_mJbTjTZ2KH%DfX=J!`7d7< z$W(jZ>?v=3h(Dp~k)QKGw^X-kai&ROTT{R`{@LSNjS4rOh?s%d)rTTnf@P#}hEGjb zJIab{nyLzO)soZ|k4nYj+-dRy4&Ji3YIu~dkF-F(PfsD~H``@;iaN4cHZi8vn)7ef zSgNbf15%p`sp@^IPMhv3s;(+fF>Jmb_JsaK-GzEInw1fa-Whx5U0zt_ZnCPq!eEI^ zRJba0DzLVz{2{hCBWqZcqcxfQhJU7}V=`#ru4Sn0_LlMq`P29->lcL%sQKYD;*Yr>=Xl zhv}nXvyKTHH9eD1l?GcAuO*IW9jtv0{C=7WEnd=9be62fhTq?v)wENcy1@oe8q&%M zug=+GYG!^V^6u-vhk4KQWMNirY|*DK&$rjbY`a1A`9n&tUX{O|5j`9q zf6$omndzdwf3stJ3UY@|?Rk~Ola(14F2u_S-1A?SP?9vRhC2!b&jouu3u@Q9_4mI> z-tH$W!#~VlVqn?q(=T3JCgW}s@43l794e*5;~;X6nW^iFQ77BtS%;irMguy=ADu|= ZIEX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsGR2m^;^|NrIgVNHxEu6iP+V?Y~VZjMY` z*c}2+83&+N|1xd{b!Ef2w>0QW#)GKbO^ovuQ9Wwl*$q6!&`_+T!d-r+mhP#n0B`Ua paJ|j~*e1{!ILNCzaGdVX_yVlL9}y_~3KIYT002ovPDHLkV1kY)3{e08 diff --git a/src/main/deploy/anim/1.png b/src/main/deploy/anim/1.png deleted file mode 100644 index 0f82a4483aaf2d795d570d9905fc6da1273a9ce6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 595 zcmV-Z0<8UsP)EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsG#~0001DNklgPBHX|rCT6f}qVnNyf(OiTD z0PfZR^zYoN7jQLP&a|EQQ5R4Q%N;u0=~xGFoo9q8BT}dVvjw*5WEAUQbgNHBkGdG4 h`B|r7^Q+Ex`vX&i86LAXS~LIv002ovPDHLkV1i&C1#SQU diff --git a/src/main/deploy/anim/2.png b/src/main/deploy/anim/2.png deleted file mode 100644 index 331a4440df2bb60276bf8a65c34a8acabe250c8a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 591 zcmV-V0EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsG)Q$dIQRM4TLn)Z%b`fxO% dcZaz9-B^4%5h*tTHd+7x002ovPDHLkV1m3J2iE`q diff --git a/src/main/deploy/anim/3.png b/src/main/deploy/anim/3.png deleted file mode 100644 index eaf4e44d798cf3273c6a6685e9a9c2a37d5c69a1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 589 zcmV-T0EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsGD`2R20i-}7B>s3Yy5)ee#Cjfvl ztF?e-y00000NkvXXu0mjfZU_WQ diff --git a/src/main/deploy/brian.png b/src/main/deploy/brian.png deleted file mode 100644 index 4ed394809a95994abed113e6fa4f2cb693657208..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6506 zcmeHKdo+~m_aB$sa?dT4F(}EHs~N^McQNiHk;cqBjN6QvVI~f_R1}2@$31mKMde!2 z388XGL{hmFIfO1!NvPjD>U3GZ?^?fg*7|+_Yt}n6@4KJ9KhNHuy`TL)&mk8lTM02` zF$e@AVQ**U2L4O)z9RhKZ$@Si4gwLLkM{6pyOB6h29r*ug#u9aUIqXKxHKvR!hKZg zz4O>JZSj>!IhLScfRSWK+t8k)W>V7KwOh}hHzI5RlEf|U_5JO((zGx6qp;b!<6g5C zZ#!a+sBL!IM3#Q{sV;K!of*A#u|oKUhTTdTxIdTfc$chXJ!DASy{ybV?yz`fl5WajG5n=561 z!@ZrauTd#@Wg7HC7vE|Pc9Jgn{GPSdu$r=-ygNCPC`dYk2^htmekufsXXj# z5!=m;k$DrhExJ#!hUT1^GUeo~sIi@Dm}Pf@l7xGH#wS}MW2)YCA;;>n;zTHeV>6*D zeQYsEqi`dl8!@{6zCfZ-?9qarbgM%z5qSnaXsL$5@S9zmZ+S)^T*{vuSbwHdfkUuH zUF=x47dRlH<{u=qLad9cc=~eY>_(eU7!By9tP=-JHr9-IRwuh={XTbVZlpDlQ6{f& zJa6LY=!3}V#sgB+PsyK7TW!t!^UmE@UBxqt&9D5cC=sWY?hp1asdt;JjR&3C z&>kmdlx*Z=`v5;UYJNp)DMZuSJa+G#Hh)U^R@kU}RZ~&wg(Adl6Wrj8(!5^gMd1U) zCZ)RZtCNcU`^dEh+1=QcevPtd*XbaOV68X3E*HE8(lWY|N|Sdu56oK>1QbMCcLy_i z63@HAlCBx2oOL}@QhsrpmYiY)?Zle9!M*( zQt+8P6S>MHL#(1f_K; zdv1%wqn`)q=JN}>L=%%T4pzQv7J4UTyLDEyc0f50x4}d-0@K+T)(7`5fldh|InVa4A>)DOxrYco%$nx0CzDd#HLBhFxUlw|~L z-x64m+hQ1#Rb`sw=2&$gb?f#0vJN^|Z^Y{C*bytCKj48OtbN?0jb*FC>-(8yk~^k{ z3a76pZ;YAV+x+0*2IHaE8fgaiZYu^SPUp->xoB*=qx;9-4U7_@V3DP>*-h~sZQ?2G zH$gXU;%5Y5P<@%d-?0i0IGC7R&JeO_I7HMa>`?K_Hd>FLy7BVBklNFO9!m~GU9Vte zo7npf4c#C{E*yL;-0!p7`kvl?s+?1Pu#p#VcN5iJTJlhq#=+pIzEh^oZ{`y&6b=|~ zUh$pdo=e?R@G{ZX6=oFYol(2P zlQlZ010~}sM5B9M9PR!j_BD>&LzcTcJ*DFwzDzGF;a*;x!e&^u*~lzjIy{~Rv3*t+ zedcAXsG5TMWs`(cC9XQOh#d(s71ve*Zu)jHy{w-*MsIy0)A%^Gr}MYCbDI;Q>jKhJ z;*;WU7?e6Ct2~U-d?uYeCx=OHmT>D;qt+C@SR zdw-(3?7&qEm8taNlUlSsGGIHTkcDD(vz6<{a%OL@i;*cy2=!PHHw_<`elVwC8Yvs^ zx#fK|(WIQeMjLe_OZe3w{6mqd&&|q~`GDi*c9C2?_s&Hr!Bh{yr&fYy>Q1D)&0CxO z5r#*MQllN~Ivq8=mFmGcJIy%>FcZa}}~mY40W z>+MI&EoIU0Y)fFkXux&)QN6y{I1av}bSW;^wOV9DiMNoR#LSC{mVw{2(nevg|MGl5P}}dV5z&*j4I9znA2w!>y9R+&d5Y z_%yf_?A^!pcajOU4LuKTjV62wtyu`QPKWMxJ&_&(c~+{mX-!eA@kX6Rg27=g?&Gc~ z@uNpNaU&H+iAPO84K}ny)g_^Bo=>Cn-qGCr((^RuWspo$g!nrcS9C6~%*bf-PEpZ( zSE}HhqYCkwIl?|(gNwFT&-JEoGi6`6s@^IZwl7d3NZ%j4l^@3MQ*LtMFGe<&AD>s5 z{^98*|HIp*{USrh%;e8PiZ`6UK;&5H+s4U{q*Uxl?LSW#pS?8O!H{y(G?2_o?-(kb zzV9S{+jO^id7AEaYgHkIXB(<3$P391g~Yyz`!w9F*@=gE!||9K){-(yJJ_wN0v6By zxTGZQb~jJ3*vnfgT+9 zmsK{0;Dv3oUy%~qV|^OvG}{Y-@a?BrTDsUZoA)Z-)p`7 z8bY)-Wv*o+wqT+A>GdT@i6{BoLkwSe9zZ!Jit_iCx4bA~aq=)!59RI*D6(Gr`7emP zUeW8WS$?&0Rp`X2j`(;x<6G=j*a)=fVJ*9Rsm;|ZQ*Mkk7LlZ^8TYJV_KnJ9bu0hf zH07&Z#t|pHbvac-?G*v#ZGCMh>-*aNw;L-MBV!c<%3U+Zn~=W!Ue&&3%G+ce?9?S> z(8}efgw{qp(sy&DOc_5NSBqMvF*}}}OUxwmMV4o%ntf1PE~?y_m&ZPSL-gcAd%c-W zLXTcg_@nm=RbiK%Ra^pi&l4kH z&{Y+7hzZP_=mNE*GXW@8537fSTXShqXqc%O)R;-365On8zCwUcCa@qjn?XPzI2?{1 z2ct)41|m>~hK2|v8i7W`K@B)-Z#bL8g@>~=co1JOtN<37Nn@~S^l&H-lN3OYWShWX z;5hUj|H2qV;y3tk)>jrlJ`h|I1A)>*BErHDKU%QZ)=?nHSBL(i1VW27toE7!cl(zOnmv0t43Ib_ij8!X;?4LB* zH0pPV<;SkcLmJooIaOklkE2^2b+Mj@=;q5&Kl z7eGeCNhk~+jzy6va6~Q&IYGJenK; zdV|8l4N)KzULQ@S8tPNAB#izl6opK%p)gFc-?qwf8`w0X-1YWyYXb~F|^|K3&6mo?=MM0|Pr z@)$~6T})8u>ark^$X`NWk)i;~s-Ga%mmzWxDLfDW`^VRU{YOsw55+*zC!gW>1du>td4)p4{EW_`Q`sC66WA6A@(6MT7U(KhQ0=d&+VZnLCkWu> z0i+C$1h4Ou!4O}AMesVtKhYW^{udv{s|r7~7|`yE3~XIsCq#T}g;H`|vG0c|AROEQaloU}aO?g# z@R%jau-nOkK-R9~efc1H1xlb$m~BtA7M>K~7f{#EbU`M7C+83LR@*$Z?;bg36y(k) zcd+T2KOX-;x(}=6+25~x;eoimg1slfTSrf!KmLmL3D}sx<1y%1#q+T-9X*(2;%P}f z*9h6LB$*_+{D7*;yg!~3qmSDp57mlBy)KTE{CvwWnI--t9^IhpQtFpkG%~XeuZhw= ze52>JE7>7$Ute<>q8Qc0}R<-|;`yM~h-RJBC-W;B3m(TAjrTO68Jv$*@Dy)!ekY>S< zW|%>6!CK7Rw)vIj;B(y*({zvQ<~4qN(^|ooYEiOW!7I6?Qj#}^th4%c{M7|uB3`hV zOuk2m4N1B~hM`wKdhOF$qo-p~sPsZ|ALFwAmChkCB_qSyW*cQCHYw-QBcka(Z*i{h zu@T&pVSe*L^Y>Ebf`SOGEDM^SxQKu~-^k}RgRH{z38;Am?@VrQ?PPVqVo&1#0L7X~ AvH$=8 diff --git a/src/main/deploy/colors/0.png b/src/main/deploy/colors/0.png deleted file mode 100644 index 6e3f6983461787d493c7a479a069c15ffba54f4a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 957 zcmV;u148_XP)EX>4Tx04R}tkv&MmP!xqvQ>7vmhjtKg$WWauh>AE$6^me@v=v%)FnQ@8G-*gu zTpR`0f`dPcRRyy7QT+~*wT&EgA5=%%S4G}ULsGfU5L6@u+>%*KhjjIvEmm!<07%i37*wE^UnOwGxMAicihP( zbs>yC=Ug}G{xEU%keJ#p)#MD7FTU7{O({#4d$BeQmjBay1gEILZtiMDt5nc)dKlEp z>hfq%M+^Y4lid=e=h(1gc0}ELa5DXyxH3xa=C-yr_?=aMT#~hls0{!MAx{jO2Y}g< zyloxt29P~#G!TVcB#)Q(1QX#hzT>^r#-@%A5$3EqGGCF4g@cI>qZZUKohJI(X{-n< zxPY!sey|=Noj8xPK`q5JCNbjJ#JHp%4(Z0Cb}qQp+^~G5u=JJe1-+yg8{sFqXybYC zB>OL@+-@l@KJ<8!>O6Dv$Y77`5xe-6Ca#qX9&EPRQZ%|$UwA34N+BE#REetoPJTz( z#y~V%ipDmvPxY>6(f4di`ZPZ8)W~-bm8AJbHn#hTnfJt&2hyG)L#J)aP==;qOe{I|!fV f*w2Jl(l`7Czx|}{++kgB00000NkvXXu0mjfxfshQ diff --git a/src/main/deploy/cone-2.png b/src/main/deploy/cone-2.png deleted file mode 100644 index d42301846adb624481c417dca1089fd879d6d837..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6078 zcmeHLd011&9u13vEQ+A0EE)qpOQd4HAR0!?*GgbCtQ7E3 zDCM2UD}?DSR(ieHtpBTh>ta|s<8|i4$?M+6XC9~w2)Y+aZ>aY6obHT%|a4XW9j$9~g0-4A)3Zkp=R&9*!{?fSmGk3`)$*lGpTvH0=fp3)|fQ$py~ z4a%jds{@KHehT$=EWn&KMZYj!2*>Co>nCV#zWi))Yw8^J=ZpL{U}V7^w%(T-&u!Vb z`gRW?R5!!t9{p_D-1u`fj1^aYR)mEtOLKU$b7@@du7<+2U#hbHXsnynm)U4I>&!#C zC&?kZ;b~!#c69UaH{0skT_ub#9&1~~l(NFFmtTo^$euj2qGA0j)0GE(t<0UR*!$fQ z-xOxq`0CxIZYHkCzCdE;S8P?Fs6Tloe#H}Typt=RTWU8&?<*0lz7j-SbXR+aFWWQc zyvS)oVSG`<_Rki(-xr-q2z5L?hwt0+(8wQ^bTQYfQhj}CPgJvw3wuS5{#4_d$2R1H z7G?aom(^FIi}tR&;UAfzo}?Z1>Gt_*>P|bXJf5dfr_WEHyk2LR^U~Kd^r(S>c14jl4;=bz$dTowBsXxDTwN(T7~o~|>Uv3SLFKEvS6q(h&w>6-wa_hr%lNC4XbR$0kCwkVeqpm}#dTPD2^yE#%*~(u_5#Ov}A? z3+FLsdAsJ}8}54A$$rI&qFdGT73Z&RdFoaEEG>Wc^$gN9Fno&-7J$Cil@>k8q zZm0Fa+0}dBqOTu2nbjS$KDV;d@AU~AliiPgH!bP;^3lbz_W$-p1g1>u&-0knwuExz zL1swK=lRJF^_vUleSczuozv?MZJWvRy9hN9XHU#_X^D|%x+FUWAs{n;3=Wnm7do<~M5?p;*UkJPM_@MZjRNnGD8Ix&TQc zKmJR)_YW?!lba6tc-SPw8mzg*-cy{qRld{4_`I9o(=+X1(zbba0&o8ivq`@tBsy;k z(wY?>Y92Dl^{Lj6zg%G6@bGzSYkem5S^6Jy@Aur_Rn>{ww+uRR+kQ$>9(cU!r zU1r)?)=ulws#zCheCY7q17Ui9ZaDQgV;TCSu3blIZ+vv)RiktLdLaVg#u7DmXXc5r zlBd(J*XW0Yl-aMHR(@A4xj=q7)9munB~~*wb&=j2GQ%r%UmmZBkJ|IcOSMbv6WQWT ziHxvf@7o=7JD;>YYOJw8*4K;b43ge{aDAH=$m_8JkiUajzBH~_XbbVg9N1PVlz{w> zLOD7sB@j0XmZLdvxIje5bXL`1&;lMEv%;Q*XGs`vgupva3J1jb1#;t}xKtj-*-6Jy zNdp2xSPr3;!f26hTIO(7r zr93{(-`#Ui0zA<%5pubNhQlco3R?xqRxAz25vWuu4o}1piCBQZ%GQeHkP<7BSs)Sv z8t$-+D-}rO0` z7KjW6^j?N65PS{d{9&0mM#_afVquZoVzdO0JIt5FNTXHL;c;#oE~uVJwG8=3^-&A_PGM5+83z93{mR$>flT3nNlM z+*SZ|$UF*(OW@mKd3YiLYsaM!u~a_zfH`D7flq*`c!)YmVyRRBb|n-&Ix0kp2c#f- z5{F14^00WANW$8Y@GzFjgQ!?O#hy7@{qHq=g*~$@zc)&VWF~6DwpRU4a5293Y1fKM7<9vV*-HoAJe1sN0z^Hk#kt${9X1SATFLH-!rutV*F_iP3SjsqVeIZ&`< zBE-Ymkzp#9!sYO=RI(k_fk%SK;67GeCg#f(kQ8Ct^n|qhfG_lf@w!V`#RHxWD+}r~-^iF@QJF22vNugt*~UIOrFWbpFLMxDNl~ z2tfMdAQSTUqg@~Enveq%0)O0HAMKiu0}}#&++F`SyL3igreG2H1*8D4O09V_Pk`5~ zDH89`WGIxb5pt=a^73bcMlCs$<)PK8Za5QVblX^X6#Ua>%5--Pq)b;c(Cq9{1CV}j z{o|tkkC}tSaRvJ7T~Nq1UKv*aA*#Kq8;_6rpup&n`)iSZFW+B2D1gBKZgd1Qt^fk~ zyYlY{AoG7W{15r?-U!|$k2j6?3XDg1x9=|k9|{#A-alpXE*~{~7KYaSec?B?8;l_~ zx2vOE;1*Sz=IEZ$vhs@d~*|1#O}N&RHi&<)2VQ^{$idEVDrBhtLL96Npbai0BAzu=3s8yC8o zo2M=9%-EZmpXDBDH+QXhVt}!3q zdZwx6YA+sr_B21ldEDy8ruK>VSKBl`Sl?YxprKW_XR(ius9E0oG@*RnNc9Py-40(s ziK`)Rw34Yi;hvf>HqfE-pDvOiSEq|v!3%>X{aiYO6Mo~^plZ)|D)OuEvJ-C%%9!cy z8aI4B6@p|%<9x2%Gal6EmPpGyd!|Z~zS@o4*rmy{|D@6JotP8Ru;BKXPQ%t1kIG9? z%Tsn2Ou6pbrnH?FQ&GQZNXTAI@uQ&5Qm-u)W#XXbxp#bW0^1Ml+a!8+?H^G3>=`}Z zBn&g`*la6LFBcv8Mr>2EYRUB@c6OQPD76&%5Pa4|j$2&Ewn4>$I+7+^df9V2HLJ8` zaAW#Mu`2n|gbQ|>992eZe&~~6b;j2Ax_3HKJ8L#a_>-OJ4_(BLy^-f;6&2k=GFbCw zur}v$bl-pZ`S`QaoR-=ipW;nZw|&aFf37os7lep^`t}^Ozu}_SO~KXto3Sqb$44v> zXC4oqTpeDw=5f&~&$7Dc?xPN3?8CJSj=Flxugw`LF8ATpFL9vp6G~g(tCC$R>ss-_ zfzk<*Qh(N+uebW1$aT0=pV^TY#2j-{?w2&w=5{RylwHU>V!sZ>Fmeq63640rnVQ)T+{x;L&e;w z53(9R+txf}mB!XDuiWjxL!Yem(v3%ogtp}OkJz>DFD%^S>?Lx}Y@eQeOFC)Z_Rre* zjQEaIAIy*8vQM0K>N<3;rkm8ZtW&eB$GyszRGVtQg&fv=;gD_dM(!co>_a)D$)ODL z4PoG;adziv2MfH()0^#1XxkhbSj%eOYTHk0Yus_!w}}8|kpd2n8Etc>auCGs{=wQ0nGnd{+Af6iV(q(@~BH66OBoet)B6+@#!S2mZ zT`vmzA@J>0&D+C6Ca*|x`S6syU`NIp{L{(q-;1#+mH&z}w2kIsVUe+3gX>qM1+0CS z?4f?oJ9cnTC;3?2acNCR_!GKMWyalgzl>^n+_Z6j2Wjgp`0EDV(2_i~xP`^qJb#4k zP8Vh%XU)*e&lgb-Zd(4^!+oo>I+EWiY<=&+Z?~elCfF{a-u1fZwAPenO1fAp>=?d! zjx;jkeCA1~eU!Un>(PzP0uOI@lj_u|;+vV0V~SmAt;1B~CF2Xn44d-xwEu`Np)0%H z)m4#5`Qk2*A>CKP^KMs8b2;hi8YWKv*z-)u5pjCbCvL-ipsbXKtG$=z#Imc;#Qi!a zaKz+sC!L>?4=+w|-~QFL;yA}!AMN^g)-1|54&2+{^`<6X{c-q_XO6L$W@(j8aDa5@ zo~q8bE*y4>jorgbao&5)W>q16I@{}X#PmsS%N}qZZTDiD9C|9MQxgh)>9IK_-?>4z zEKL%(Bdp=}sE#{r?N<-;%AfXKvJzBGDO83YX5MGif0vEQw9^x2O0S zlqx7Pcv>F?=!vNDIIf2njO65GdNPNuGpHFXp-{+RvKeeP4S3LuDOwyh(X_^~1ciko z7&RgWOpjwaErsBO6}pAEh)Mb2&SucbPmCEE+ z1R;SM)9B48AodHMIHu|s>xJBi5py{M69I55?+f0~Yd1RsFPRJq)*%at^rXQeDiI%2 z>JUr`nIBb3CCe8Tz%;Is&82a9Di%%1frT`lFM{&f2#?9wMHD)A}B!x$mtm1 zQTcM&d^QK6A+V4|<1z&*nt;bbX+l0%$YUcy1&7TaKoMcUz^a532WCZ3DFGFq!}sO! z5Fw2z{d9aOXih0gWkum;?NEN=%jV-@J+KL-DgrdKhK|@l(tu%btotKeY5L-9*g1 znJ5(Vwt!&7Qi2gqLY3w`0heV6iHEgn6r3M@3--Akd&OcG7Jqr8u0=fR3t#2Ow&JYyJn;@^H z?;E+^$n{zZyq5Eu)%8ZM*HYlMoZqaj|CwC&{V!9f7W@a43|^Iv54($i*Q}xXu(?JO z$zeG0u_5KR94>Wsuj7@P7z+Ss`o1e^&QjtKpS8zGUo+0IcAOTKRH@f9&_C^k?3{ zZlSY)ZLA#D2<3~dw!WAa%R~iX?+1X671NI(k$|_w)na@BV8MVpNW&Uupf?zL8DPbL chnHM|1+=;m6P)~8%GJcPG-PIQg*a}-?;h!W1^@s6 diff --git a/src/main/deploy/cube-2.png b/src/main/deploy/cube-2.png deleted file mode 100644 index bd5037baa11d5e73a644eea2b29007da40c96559..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 270 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`jKx9jP7LeL$-D$|Tv8)E(|mmy zw18|52FCVG1{RPKAeI7R1_tH@j10^`nh_+nfC(-uuz(rC1}QWNE&K$eDm+~rLo5W7 z6C^%02;OAhyy)M5_K)^9%)uvuG~R4t_9>|K(J*q!a0~BGVo;oY(X{!823ta~gGUeR zd?w%Y9pRGe-XE3Ivxs%*Nt^K0BDUf5vH9_W>kefz?7HqCRbS&Ie)KWZjG&a>_woN4 lI1gv8iBnj@xvsjxfZ^*(jnX~RT_6uKc)I$ztaD0e0svXpN}vD$ diff --git a/src/main/deploy/cube-old.png b/src/main/deploy/cube-old.png deleted file mode 100644 index d08c8b8ec6ae6de3918e21b5329150827010e796..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1330 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61SBU+%rIkMU~J8Fb`J1#c2+1T%1_J8No8Qr zm{>c}*5j~)MBDvkUaneAWdemK0_Lvi=qj0_C3es$Q+vy+grb-7CYc^VF*2;zo0{#r zL)pdCV`XDl9Y3%ixq8&|qN~>*JXFyEr>%Rw?bB(fItwuJ-=-<%08`#(sbPBKVUUbB)qRnajN070nf8moHhq z7jBR64C*-Fd7O8b!bj!nsnhRUh|7vqq@6giIbYS>Xf!d15ki>$ftx z*n6(uzV(CPh5fuSG22Zm`FGr5Y@1hda)QiBe{T(uhVRC|mdO}YaDQ31vo?F~<1dUS z0@hE21sKW7pWwic=P&29n;NtU=qlsM<-=BDPAFgO>bCYGe8D3oWGWGJ|M`UZqI z@`*DrFiU&7IEHA5G72!i{{z%RW59@Jez4+3G!Zy=?R|eBn+47XGJvXgJ;_EEfw0|V zrosh52^RwJs75vgY6HY2$R@$eVL(<56ht@)O#-3;(+Gr<;6~zSAZ&oB`}FHEgu%xq zi&ZDO23+dkn$a~-#|EI+A+ZLuhp?xSRRc9ZlLo;Q0rvy#88;>>FD}y9T?n$t)78&q Iol`;+0E@Z=S^xk5 diff --git a/src/main/deploy/cube.png b/src/main/deploy/cube.png deleted file mode 100644 index 313f02c31c01acb2aa041460103bf058ca59d46c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5753 zcmeHLX;f3!8VynbK?Y?I5i|zWfK75U4}uI~3JM~iLPhIMas#(yz$An)35eo6fKn|A z*7X$8qJk}2w5@e2Xe%m85wuPe1t%&}Z9%l>CKv+R*XLTV|I7;EobT+t&-d*!z|E@2 zh!AT_7fT!tXDtW~i~_&yupf(I;B#X^A`6Ezy^$UhtB!(G@ySYs1eGFqby_llN3^H} zhtsy~kDY($KfIAIn!F?;UygUT+WU)aoL9`N-fQi) zHU-eerlEv9O7bdPvsk$ulIQ*jgNQ)f_%7?qvI(9)8KRx38&1EE`V`E?9tTgx#*l zh$^ea?qS^x!8uMF>5FW}N`37kPF0Y%T3(LKAC++X^spM2X{8)hEAQIL;dUi4g)8$z zN0pS6%`S9!)KjxWxv5+*g-MK)H1F)lUw-cpN@UEV$CNtnJQ@0f_SY`Kya|c>DZ}rc zU>(Srv1^mH^MaZsLCy}h4;S7~SgN?!dMRZNv3=T)S*twkrjb2^FFY^tOW5g{J6;o) z=emb!LJUA{p^8Y{zN&N^@4$k(kp$~uh~JnLT7b#3g_Cm}_PBg*J$H0iYeAi=T${V? zR;|Qr(l=)7E>1@CW9!p?+R;8zMa=lUK4U^=_uWkw{PV1)FSFy{bWmMsC-yiC*E&W2 zRCf2L`IU*1v&zCybM6;=@8<9Qd2?~ncgvl&RbS~UYw>z;InAHB zaL%T(bDwKU2ifa+#kGP@qO+}w;;IlwO_ceW`~2+c4?pew z@$uP)xLWD9aq0XYEG-c9+ULmms~?sZP1;)jW&D@jhrZd}_{Hv?^V9Mh=jRt6+Y(W= za9QA(o!dX+ok=(OBqZQtejMprOYIo1KEl=L`kS9O%po2V`wA`mr)+)ahQ0!-sC0dlDy8wT(g-w>@q&sy0E^v&%(y6^2)AG;&-NH*ay~{-=kbrG;htb@YS6;o_({{tUEWQ zvo?DD^f;;QILigud2Xl5Za%x+1a(roPptX9`YB_` zsghTxZcWIzqnIl4$W6lGOqQd3ex!iUe|^%y`QDyY;1hbv&pH2QSy+(QQjOi>y2z4> zm8;d8y_`-2pi{rPzew3Jfq{lb#k&q~TAJs(W{&xogavN#!~K6VKizmna49J41=;hf zl~2~Uj=#}+W6QBl+|JqXzGmi#@?vDy9V&I(d`HuRc90)^^@vrUr4zp0ntSh$qboLa zrj9CYTk!l|dvw=i(@eq>*UQ#xw0T<19zCr-@h6ekIJ&EO#*!d2ai<$HtOPW>-hL1%rx7tubbqTs?Tn8 zJv(a#(IMwKy{F6-(pq&NsL4tyY3(+ti#+(LA}5c(s3Nra!T8R{9S^S^XYPO5hwGf9 zY;L=_#vEM98Wdc;vEeg$B87|$ixonItd%8$s~Ly$_SGiCq9jC(7a|F$+=tM4>^K3B zihT(4nBh=(G9O7qL(`Q=bb3ULC_PEU6%%}?TY77GKtP75VZ2r*m8*DKAA(Mo2ijPe zLcr@F>LedRYSP{;lA4-I zPNkC-$^;6P%jHra8iht90R%~vCRf8+l3eAEN$52K5tT@ZCaY0}9FJ+jLPd(&hd==1 z_}BT#lEcFd@^V$b3&0PG7EY#6$q+>*qZl((>L3je=}+jb3{?#H3r2}TREiX(2no_4 za<#j$gji(YC#NW-x^l!K3L-^h0ICABQU^^LA_$K(Ffa=eP+78$1gk>ZpkgL?NT!dg!K%9&M9S#c;GGPWnVoDfn5(D8vKnxL) zU@nctW(heg7~vX8%u=FYSHe=`tS~7tkP^cjp;#znl3*bXWFuzNNE|N0A|Yathzg6j zEIOB?lM;(~!3w1e2Fr=c-~@z{EKkr4V21PjBLzML8W|dhL`q?`1Q5U(K;>dZs%l^; z29+VvY8dmA3i4$$Sxh#S!=f|j>;ceRM5zLM5mTi?WI9bZf-MXWlmo1Vv7HJ8ba7A( zkFP{vwL%%AP)L0USWS*-8ryHZqlnDBVrvEacXeF-X9gNSu`0xkWJ zC=r$?AmIM!->|Ra=vy{}gd^s#xhydWhPc>%;xI@;h(jY$sT?5#f*`Jh&K#_+Qb^RP zuoCf406qe*zy{TMg(vnemFHl5Y9fNI1F(z)0o?)12$cR}DcFtix>|3_8-94}07h2~ z;OS%F>H;?*#c&n&`-NRP|Kh8E9sb1`fb{!G-pSwhcD=Xjog8>4@cZ5M-mZ6Y;GMwl zch~>TF3W+3DMSwb14;#tO3VJl+k(fe5y_!(Djd$r9{VxD6>oP2L36brJjndsu+ffQ z^mX>RGr*T*;{<{JF+@ibJJZe=*yGuoujq+Y;QeMCL_Qc2)#Hx-3ZBVv`u6^tvy3q& zhK@1R5Cn~2*COy~pkai+gT9r9egCI_0VTcI>%gG6K1mSjuffpQbM#%~wn1fR(ftVEI%sPc7iXXuBn?nw*w8kh>6t?Za5yA=hU1O#2m7!QK~O~Cfq+Fz F{{lXst_%PG diff --git a/src/main/deploy/example.txt b/src/main/deploy/example.txt deleted file mode 100644 index ea89fa92..00000000 --- a/src/main/deploy/example.txt +++ /dev/null @@ -1,2 +0,0 @@ -Files placed in this directory will be deployed to the RoboRIO into the -'deploy' directory in the home folder. Use "Filesystem.getDeployDirectory().toPath().resolve("FileName.type")" diff --git a/src/main/deploy/progamer.png b/src/main/deploy/progamer.png deleted file mode 100644 index 94842224b5e3894c43eb481f2258222b0eaaca25..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1586 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4(FKU~J8Fb`J1#c2+1T%1_J8No8Qr zm{>c}*5j~)MBDvkUaneAWdemK0_Lvi=qj0_C3es$Q+vy+grb-7CYc^VF*2;zo0{#r zL)pdCV`XDl9Y3%ixq8&|qN~>*JXFyEr>%Rw?bB(fItwuJ-=-<%08`#(sbPBKVUUbB)qRnajN070nf8moHhq z7jBR64C*-Fd7O8b!bj!nsnhRUh|7vqq@6giIbYS>Xf!d15ki>$ftx z*n6(uzV(CPh5fuSG22Zm`FGr5Y@1hda)QiBe{T(uhVRC|mdO}YaDQ31vo?F~<1dUS z0@hE21sKW7pWHD+^I@TLGLBw6AbQR1ARo125-%B255jbsBRvUNf=4g&*Nu!X_VZ9Cw?R!_Hr*~g^4 z8LYiL;Nma_Rs%qqa*un1)hvh7kuV)-G~57*-E$f4A9xRy&P7uO;eM~~VNi4s1an@v zCWC3X0U!a+R*1r*+km#Ofv{mD$W@G~lNlIX85ls8!2ns&2(ukz2;2oQ6G1e{HY=zA sDDXhw7z2>T5{RQonSp_mdKI;Vst0MQ}|bN~PV diff --git a/src/main/deploy/quaver.png b/src/main/deploy/quaver.png deleted file mode 100644 index 3b9ac787a62a808e9740049b0ce34581fa731936..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 624 zcmV-$0+0QPP)EX>4Tx04R}tkv&MmKp2MKrk09S9Lyl%kfAzR5EXHhDi*;)X)CnqU~=gnG-*gu zTpR`0f`dPcRR;4@5YQbVaKq8)FhG`RT5YKGd z2IqZZk(FhY_?&p$qze*1a$WKGjdRImfoF+^x`-lqd<5UXf+(?``B?>CqVESxY9fRS`(Q4B)!qm zqDR2MHgIv>(Ud*lat9cCGGtSBr64V#SOnhB=$rDu;4RR%=Jl<8j?)JqOTAjY0S*p< zu@Ysk`@FliyKn#2wEOo183}TO$)BtX00009a7bBm001r{001r{0eGc9b^rhX2XskI zMF-~s6ch>sgo8B=0000PbVXQnLvL+uWo~o;Lvm$dbY)~9cWHEJAV*0}P*;Ht7XSbN zT1iAfR4C7#k}(RvPzXa4?|)u#5bRJoeYN^CijTw~P)Jp=QbeS4xnR2OlPMj{Y#j*z zNq1iW07PU5kQ@OwwZ7QYAKnWu}CZs)c1KlcE7x-81!{OBbB0000< KMNUMnLSTY9tOGUx diff --git a/src/main/deploy/raj.png b/src/main/deploy/raj.png deleted file mode 100644 index b9680e405f2567d72d32317cf44a788ac222761c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6698 zcmeHKc{r5a`yVMZ){sOp#u75CvCKr1Wvq?tq0N|u!7OHmk*rZkMI@z^l%-eM-c*Ea zY4loJNT~=ViBN<>e$Qxmd#~U3x_;MtUBB;t&GkI| zz#tGv+TPCE6?n=CZwWErUwv|s1OkbdM!0+NTuFQgo5P~fgQ*bSUN#j%4X4vUpzvo! z+r85aHb~76DQ;c{Q3_etCGoOOz+dM2iB~%;SQxO&fck7LZfag$wI5ntuBB%2Sv(WrVH9W%E}&caO^!iy=>UEPk4Dx;9jUQ8OV z?Y_D7US6u60ONMU*i|_?Ve0{Ow=(JEr(M>E>+bUv(4{INXJ0MkGM;KdW7-N9wz+>u z-}DBnds*>t$jlu}<{Ukf^rlM;HbF4gu%k7w3?el$D3`S_u`R`o41@KxoE_yZY9 z3&XD=NzxZ57?Au;eWUO34L3TPphLZLlbX$|WA;11(pGexx>;0a5KCZ9R^B#3FTPD<+&;)kl2(dTD-~J5 z!yXki&3tw`p~Q|{y6mQwTl(wy@O{5-jBr3tsIoRv6Mu=h-V zTmP6U0$(KS)4Mhx_fvcF@ZRY6{12D1J1-K?;4yBlvb8h*1%K${zt$fQlHTp#!4&u| zYt!ydXAYJlWmjlD@XlaU=WWX;E5RIT#N)6B&08jncJ{0uvN+kY!enP?OWWkAjP@OI z{K6ZV@v4FjL3$MGc1QBXQpC;qH^Xt^A39|R#XhFM&R(2;oPs_$(2wlcB*A?%(YwfA z@O*%KIFvOg*k0N)o_KJrYGst*YN_M2e8JsUzBQX;#@uV##GkhvmG*pIoT$_@cu7Hl z7i%*+0JfZ!IZ$WcE%iW+bW{`Kd*aet`Tg~CqwD6I+ZF3XEc5$RA#Bta5zQ!w14w+U zbdT2wHPM!Lmuh=VuY(fpR%)m78&qRgTUyV*u1m~O(L1P2PQr2w%5)qwn$lgJ=4Rbo zQmm4(gIU;9J2Oq$uPMr*$0Xx(B>Te^9rY{OdU>9@MaOrR-SV?6YBLGUY0B_nzHqpr z_AvfxvU%qDO*4-+CYeijj>TEk^|{!bV?xtur$h2HH{3^$SYC$tkeW_2u{)9MEoQ9cTfC#mwC)PIc^f8KEaHXP2#NBd zPwM6>(fuTx`l)@T`!r_yXnpq=lg_?u&Xn$1jLYhNupm~sCuDB_v!~*)?A zK9a-=s5wwj-mdtU$ra>|$_2p1}lS-D*r| zcl@DIrSo?Dpvz&Oa8iM^8q2ug!)~o|lBthA`z(JX{civ15<(p)Ct@b)(Qt{z3N4t- z3_3AEkEoXVh3s3i9(DOv&AG>nCtFr7({;xeMS9%W<Ut&qDrRGHI`P z!N*?6U%Gs=>go)sN!_JcF)j_cCJCFZ(bj~O@Ozu>; zk|0^;(3ypUhEqufX=akUwj^KWhe@#eb3n((uAfdk=cQ;8|FWt0&(=FIht_oHRC%}Z zI{2{dpsSOkd$@9(wp50*7AM+nXIw%2SjW8z{?*7gtT2qsHI5pVp3E8*qQH z=Yz6(q4)hxoqedP_5dGZy-L!V5bo=bC;NgJ2hV`~uNHGjmv#N7PBEAKNYDF<}xlT8vd{i>C_O`s+|-OH`@Wj|F# zVt313IeRs&%G^|5R^06`!rE*`Uh1P<`GxpxT{a4H@vf?Y6}gEUGD?fhPCSlv(~04f z;iomCMg7}ayNWL)?0=b+p}gBNqu5}u^gei{KV17tu|1`;j_1E7avblmEmY^+RHtf= zZE1!+iV&hCQzwW^2*~#J%z1t|-qAO&cg;Q-k7q}_h$}tCysvI(Jg`l{HAJ5{pxdur zOwxW)8Kw0>B{x=E4;g%YK0g7!vZ!VAgZL7kPyub{r7n0Vzbgrjk=z?4LF5eS3_d-% zM!Fn&QmK6NX9vMneNVlS94#@~7rJ7$S3+gPvBOin%lmhi=024VPD>|PZkOH&TT?c1 zMTdIp;nDa%hA$^XjM<-2k&idEH&1SQ(s)jc_P$|_Z^mu-ojET}iE%{q;E9bA{_irG z?(g%paJSX2qeYglJ=TTMUUf^UarGHnR034%nk3I1y-&9gk))#+SB1c(BB^>7t-v!qJID7#7pjF5=ss`ay-OO zIM!aUw@Mor(5+BfH}7>7S7AExu1{ZLzdEEC?vw;~9av1WJfbX{JojO&_tlsh1f##z zNK_%V(A!3Ty~4Fh57aCezfA5y3hHoX1hnRK+|cZ;Ln$SEm-B;BWA`6kc}*0XwI0Cc zt15jE`_P)7$L-x9b1f}bE?Xf*m1i+vTigP#4T0kfCR$5V?b{R%9d7ayZ&7P?IOt$T zT<79`?Bju}E#M(odtlyOpPAPPsln?fF;D0+n#tN)#}g#h8l}6$9ndXO(bI7)SD&1a z#eUVQq;O8wH1H8k)lA^QWiBGd*MQn>;wF)GCS^u*V9c1A8ei;#M4)#ekD2EI%qd zoWTb6S|E@aKAcS=2T^$tKdL{SX$~E)s)a)66m#fyBO;Q>wxR~m?IJi-w+JV9azqdr zOM&7ygU!Nm004u^BSFF$!AveL+#I@uiv!+;-3TaTNrV?<4)r2BL#$XFDg*<^z>zRQ zI6Vvv-3*49aVRvLtF_H{2%u#S4dC(EI0OQS0?s#tvpD_;6c&p`Akhdk8U{$fxO99atIS4RN#pSb^!{t^3< zFd#)F;;dQZP@#MF*5**5eH?{Frc-cBuPCY?#t4lxhM`F$V;IKBhz9dBK~Z5OLlo5r zMI}*DMy9_&*)zF35|d07LIL1#I)Fo>nxJV|V-pzJ4@-q%jA;~@sWBD>BO4kc(MT-X zl!P|?1!5bA4rC=M_*bulP!s?Pg(j2yC>TGOAq9hlVaP~R7>R_!z$ktsQyRtygTat# zOHdRt&W6Qdkbvo=Gf4ha1e@uqp&z5Qykh9hBUe@F%l35&weC`K@2v@oAcjE!I13s?yeKbOMqd;z}xH-F#f;lF7D0{Ly^U-A2!uHSV1 zD+d0R@bB#UP1nC-;9m*<&aVGAy1;)Qrl?F{2gC=CN{R~kvA{7)%+Jx*T6o?9Ep}SC ze*~T@*>>Js5D2a*yhXzE@L@owIM1F)5FZj2!ZH4|SYgPH{_6m^0BR6uL zf>X?=&k1Ty5xhzlc)47q?Ab3@5Y=26jXG>fx_qnwqH-(-sW&?$PuWIKD&jJ>G6xR-(mI)Cu+gjN(3COGPDA;=(#~UUV6A%w)F`fMT!DeZ z)L^#%Wk{V*3Tmylr(DoI!KN#`Q-0~LihJ$-PfyG<8k|Z5&+g*7{o>M9qNb)|ZHkg- zN?$P8C$#X{~vy0y5-F@g<*^gx{*IV+{7=;|=FP_zD1Mf>AH?Mhhpj-Y-= zfoyFpCFYt{jZc3mo^q`Rv<`iIK4NyiQ`O;g@WPvU6Qz7>Ti7!TyQ=)mytPH1M;5ki zzVI;6aPPci^yXI!%y{&eoF^3ir39s86*)OL)Vt$IA!e=AU5TOYXYU{G^sx*g=6MQE zYTtXC(eX;NU2J6u`0&K~qSd!Bh7-v?ml}J&n)lv5E8m17xcC+|iB2AF}UWObh*q%U6EmAeJ)q0LvO2Xz>Y^fUK^4M z4Qy^6MciL`U2I&Wew+CH%F1&WR-NaW_P;9;nQSd>mQ267b@yW9Cqi~0q3jt$-p<~` l(o@j@aotYoU`OrC34~`rY+(@-k|(SZdxDd7v8C_+{{h%quD$>O diff --git a/src/main/deploy/shulker_box.png b/src/main/deploy/shulker_box.png deleted file mode 100644 index 4828587d7a0521822a05f3583f40099295b2faa3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6238 zcmeHLc~n!^`b`3ad7hk&K`kgDGb9m|S+Ft`P_c@V;RaF?5|aQyi**1Iv`)2BQ7jI1 zD2hX&2q@}P1gF-jsGxv?Oa=*~36PNAxd9Q^@2&NgYrXfMcah|r@9e$L_w94;NiJF8 zp^ME;rkEfQ2=m||{|NAD1;30?;C;{Dcy|QC;O6?MXlVp91tSs*xja6Ek*10u3?$=m z5eQk`Zz}|snw`zmf4jUl3To=3O%l~K#O}Ukj#|@n<=nv%+ZARvqKnGr_$<}7DPE{E zEF)RX-!Gk&8QZh27IJH!UGOVO!KuG;er9q?!|eyD*C*K&9a|I`-KV70dVC%Aun)g2 zBF3^%X;_OJ?qF^&-n%)z{{?A(&Man{_dV}#O8C_-6=k9%!Hf5^JD%-4^tIx`qK%6$ zJo9{N-Rd^mA;o$*f>gmeaX<7%b9xqKcnzt`l{Z;$R%4HJ;pFXI$eOeT9U(tIKCY;G z5Q(cw$o34fIHgH`x#tJZJ%3nSE9`vqwrBXV|5W>bwrYB=Dh_mYkgqtqZF+m*a9!d3 z8LctVEZ01VpMlnwOW`TaC;Q%|0D{sxwp-d$g4QXU+W@o8^h=XO zrt(j-O<31=$Zh&2-c*~g&3w)-e++jbJy z;C){&%&?1GLjU>x%5X}W1-*5@#LXbVA=*t=9_#DkxK>Q;-X%M=pt0rjpB&BQjrmh> zHL`isxwnr`31q*V8^7On5oK%a^8lmls#!=>ZYI}#uf%iz)ZE&gyWv8v&vK5*{VvyWbE<-V@jBaH z#CF_ytB{)q@eiy&qnJ*unM=)x;a%-3I8g9a+a1ip>*bew<{!K8he8q{Wj==HHg#{ofSdb7D6KkK{tr!3yxDE1SFh(k5El>z&% zKG|6^5D|CL=j8l~K5jym>5dn2Z14V7)?*Xmg;d|k$Ws55(tWRT-xZToO@aDeUb}q{yMZ>4615fNz31N&#j}LO?4OuBU%cE|E0wJp!cim$WuAm zVn&W53sFxS{I-)N_{}Kx4QFNKs*GIn`HKXL^6%cZcuh;Dh6MGl2LfuzQH|tx@*DL6z_oQu&Czk}w+mdXxt~xyL?DlNw{&@~Je0lSW-o}bMW>R=T5v!*eJlnE$ z(T-(?j&U*5R~z_r8{Vp^4E`rziQ3JjXnW7D<{1sc4LRis#L;hWYPv=4>nux?h ztL*j8TM@j;*~VE1*JH2#vbjxFmbqJzVtu3~M%mUL**jP7du-3N$L2d^TV=_QAJG-I znbE-!+yBn0GB3mQI6Z@M8flKx9c0|<>JzP5ez#Z`x3*Yt=lIPzGRtEA?}3B9Poa!H zhq&Sh_PGtcj_AI+CAspVK&vVnn;_rxom1|fzV4fz{G*+%3uAYxDs%b|`&N@m@5a7~ z_O_olyUKFJ@Y;q1hm)sXo`^MT-+1xe?r$&`Oeyj|HEH}84{Wb%%~taSKNKVV7X_a$ zDeks@c+GtE>Jni;iZAYYc_Ds7I_O-L!CM9|3qDd1>l4^?4tCK( z6Hgff2nZl46C)Gw6D16p7gnds0Btyo$6|C4X@VCvIwTz9Clo^%iW|j^fD4fEl1bQw zCKyjKhs%iY4;+&KJuhs$R4QWN@hK@OZYg9pp*Rjtq|@nm0trtd;Q#_BNllb8Ww=C% z6D%>R;SWjJVxCCK6DDF{O(sj2B=y2#!8qnaegaWQ$hdr>WXuKN2VTY$;fZbpyg-1T z$dE__l7YxrLjRT_i2^@U@DY$im?UOH0m)FJ)M=swhds_0C5idEayV=}#D@d`Dgm<+ zKbdlIa7g$#1GXTJClKja!0bwbd%P`eHcP$3}w zPA}Ns3k%QB;0W0~4nx=EvRO1X5n|)mbhaun8kvZrP-q@FCKrNmR2s{J%OSJLbPwtTi7+t_>`Eqo zVpgye2S`ykToRWHad93*4;GLjP;o4>2NOr2bEzBxokF9th&m|_n-M4!3z%Rzc>-n} zgcl{o=>}lK89w2`URaVF;bSD6&y;cj0o((;M2;{;@^L7NCx9ZQOxRDNyNA06l}vXB z8IuVl`bW@mNGt(+5mqG<+{h%|2)r;1P!6z`3GY-Opo@cQ7=B`iDHV#NghIX-7ETHS zGslNRzzxM=N}2vlDFj3bBr=0QVi0LjL=uBaXOL((0*yhKfERLj+|>VshHoE?=jfsb z@g!jWR9$HFo{EIljrK;ne4g%R!eDf_1%t^REkVLe9$RssH9EwOXC}r$;QScdupi>Q zf3q1lEFwg6r$9I&m&?Ras5A-=Y%q5ml?;)Ay(}h`%+|Rut}YRBr727?ZEDBmFK_Eors!M=p*(r@L<64jKE03=y8yb@ckML$X+{P{TCG;4 zR<*us&A*aAs2&`LjSY;ai@7}z7bM)#_7-42?rW{tvyXE?N`u3Lg zFhqw#Xu&K9FvE~$sIk3qKs5kH#w3-4%E6&QEmAu?GHhmOW^Q7R)FQjzclWFMU%!2= z98#k7(Q1u)jG!ISTA5e@8PMo`-#aik(DS|r`17{+ZC76xZ~}OMLZZO?7y*SsX|x)& z9vaMtR3kyg^7nGU0g@I*7GMGwhf+grENlSOz`y{Q+cVH( zf;ItOfh4AVNk}3Alz<=vQx-u%Ws*!Fl8r17K?D^M7u;J^ zz=C>EM6GKTY3o`=twOOZ(t=h|kb-Q*4Ujhz2;zA?=aqL}Pyg|9X6}63?|%1pzk4Uc zMqcpziN-d@002x3@aKde{bcl-Fb=uf^$bD)fT>Lmi&Td|NjQa4E)q*%oO-1K#=%;# z2mrM8?GcMlKcSoUH_uXH3?C&=-4qxu+y3NmY1TLW9{0+7Y>W4E62#O>T+88BuQc~w zD=BUL6>axc68*M%dW_nr5%gLY)l;#$%F1y;+ym!= z?X{N^re%qK+hB#;PkO#3xomd9h4hSOfRIjYs3MLVY`gk-b6MX0j5mkhUdwQ8w|hAK zCs%A@Myc_}8=)D_2G7$DIA;4@RXlo--?`=BO%fT?v^4Lf<&`6vqtDt8ZFVX1?dYp6 zS&~_6vC`=DFCFIxHnrVJm(1yxJjkei9G{j@ztE5LQ%BnIFDf%DI`N-v;FUf7`T6ZQ zsL{Z@LCq_up-fZGeALj9H3wJX7E;)9%;St^eKh3vpFpnB-nL^#;cBjSk zF;khD=vegd=Q^Kjc!MR+?8~M!M#t^RW|csM%S!to*w7lf)gINbv~tNqV-Bk=a*dVB zj2@?c`qun@!Gv>`VRH;uHGUmY8(vV*{`re2NBqf~8I0L%mo=t^|1u{us?2thOaS|} zViVAj2OQlIsXW9!<2(=d31&gTR^<=lEpYLr>5jHj#!FA`im?gw$S#(A)?hp^Q^dQv z$=pnO@(%7x3iiztuJ@!Ft~HVI`MvbIxLxM4d767GYd7<|A7^*h%;`w&{OK_63dT0N z(>}vGq-o~Nee{bhf-FiACfBIksKngqkh;@;1M?W`*Wb1&t~EgM0NLkB|k9g+>GD1^<}O&8}_6y?5mdZ zD_VNrWfUw6meiWAJq2QZNX-F^?k;tkR&M>`w&t#y^TzxRPFyBhf056t4CDXO@^f%k z*jd+C^DoYl6EAk1zgLJ!D)`yU8`dbhn@DXuXv1QY}iMqm)XTBqg2cJ#-TNa&uY@9auBam4+t>5pepVwg3Vm36zxUU>X*=argu z1M|CE$MtP%s-F1L?pBFyo7c_=_qsI4uVp6({g|^owYWk}s@RdHxuFDev2LUlv7CUbMHu*a^=n=jBntWjUMLV^mK$Ik#uJR|dYjRuwzFtmFv0eSn{vGc7&0 zxY+x;pqd!8*rWQ{ve#jcvoDaYBy*kwoh_OUZM-xA9QblqtGMn~P|}Sx>q8SR7XE&% z%Hf-BoKO4ZU{lB5ke;+R-5c*r4Zk#fHO3GVu{%C7mZw;xo^#8>El^sO694X2AC`At zDsMWNpAuJNL)&~exCxA%&L}^BwgP@)x;Dtlb+t7kbzEQRss=xgSL@!sb1YjF+B*=C zc)X~!Z&%xbWvOX92L>G;=M)a^*wj#@`&!CUqpd znl#zQvS{C$1n=tE4*6M|OZzujuUel@Hng61{(2C5@8a^Ss#OiwZq}ArS9E*6YHkTN zcKT!$zH9dViJP_g+T{CH%ntMUk&8pJDmLCUy@=~_sD*PLGIFM3wW90gMa@|b*ZIZk zo=y_MJ~Q^?x4Inldo%AIyuJq;doDz9Jf+(z)3{!l`8##Pj?4I+{&O?7*wA@v)>|L9 zndMY<*6vlO8S9-zsZc3R-yxVDeq{Spuh(|{FKT872VV#%WK{O@f3b7$R#?T=Nc;Ng zzR7h?AN=e>RsFjapX_<#_+4Yof%)EpbVWi#O%wZ(a=f*+YKD)}(TiIciD|58$?f)j zjcr+~Nr`WN@`pirNJOCfz0N~-JRX~DxSdHVuv0@n;-%)l6j}r^o_y`)8%vJcnabo{u zB^;U@941JP7chl*FHd6+EeipV!fFVol}cnPmX?jz;j)ltR87L;bS~<6Ha?Qe!}-XS zFpf&363GN#tvC_Hdm7_BltK|JgyT01fkKqFfnEqA;0E5*Z|c zAOZ0ps8-6L05v0R2jF(JNOqh{mrh#jZTPpaT@N8n|uVHOZR zNLoliq7ca>sgyK2LZ$XiL_mfU`qKzi81m*Og}^GgMk#=O6JeR!VKjtLFcPoOC?&e- z2n8fq0!tBB6*4O2gCXY!aCsvUC9JxS)rWe3r@{&BUK4WMrVaW2@xnakV%92Od)|u6}l0qG#Zt_pzs9*s)#OvXmocW?9S9d2?Z=a zxl#%t%PE#Zu`o#?i`5xW!dY{90c<=-B)`}2B#>H!1R#4rEECF;RPRk;VksP|hEP5! zba%QtgUqCZG&cs7L3{7C2v(|)T0~JPWTM;9e9(nqA=5#qh0sbx0CW+^Y*;=@7*flX zVRE^IjYpHhp^+nIF0!G7kQ(AZY8U|}gKjJ`$f7X9Kr#ztvJf)K3>JBmzg#F5t^9A^ z==Q;R3@y69ScQzgQl}c)Q=xFekTfJp#JbId!|ApK3la=XK?NnkLS3E+){sdM2gzb# zwr*3AcKSv%0LiL8lEf(Ju&pN^&tHRA09e~QAZ3C zH>5+3F61O6jU0u;e4&TV-`IxN;cpxPf&MtinE3rj*GIa>#K4%GKUUXAy2ix7n4CXW z*Z++!!M8g|-2lxnYbc29q%zeFm*Q)`N%}(A8!L)I6IAFo|8L z_?Kl28i+PD_>pxh;L>I^CV41Y7xKT|{&@g{L8MhwQ~+isCb~Iv_4ev|y^IQfrbG33 zCno?v0U91WKv!bq(#!Ym-5W$N)TY)j~f!`j~1Be2#0lHp4A_#&y9eP7` z2#8Kbdo)8d7K5gN8ucmbd(;zkbZ~ao1)(=RFxq!EJq7HXodDe`ph2UJ`Uq5~&rGjF zd(?mOR9hVf2H&4PqpQTx4r6&XIA!Uq13;?~ZMYV!uK%kt#>J*b7XUoN4wdp4<$t~s eG3YKF-Nq_c)6bnba-yUT#R%{X=A4)pv-aObaip#Q diff --git a/src/main/deploy/torchflower.png b/src/main/deploy/torchflower.png deleted file mode 100644 index 7022e26a78d9427d7e7ebdbcfebe70d8573d5f4b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5756 zcmeHKc~leG(hrO5AP%c5F(?Wc(h1oiY)M!Kf@~^_TPNLt0NDeCO;I+*869O57f?`f z91zhD#F1qb7=_Uh6&*n~QO5^^3JMA$jJyuGp6{LW9nbmRep5P zT*eL>b^CSp$@^~}vv)_#GGrZFe;(7F(_E%jV|M)9DeIEwBj3m(V8$BElgKNL*A|XO z90Kd+0kdgs&8=IO?T$c2O*RJ{+?xSPOPwD4K9cC5t2KVrzpdEqj&{gY@y+k|mhvwS zQp#f!&$Ih4H@~pE_>@AfHMmLIm3;W#wbK`pFSgd}-`er2seH^X_4M3QZ2on>404_sOxe`Tw!U1xRg`XNxsI_M<=y?#|z1~ z-^u^U*ePySSJ?2Qs&2gPs&CGO+B`elm3g^E@M<}~#b*D7@NIN`*t|R?<8>d2U#YX8duHI z_dQvSG64rrz`jeU&oz((4@!T*xRaSh%?AQDp9$aB~`c8^ImMm(mEH+y61gah?YHC?mJ*qfcB}lDt-FRJew+o8a8NNI( z>A*^}_~W?%RRe5M>R(9=KxN0LS1?bFi2w@K$#netts2b$wKN{k(n_sxP$bJDySNHq ztX%2%R9t)EKHOq3-~tU6oG%Y8<;}OtJ!_WPcv5@u8=z+i&4*W!Y=6C6O9bD*UysJ| zxcAwQqT85szsX>>>+)CS3Aof^tqd-^8wGU+JnE&FJy|9*$<1Z^HB33N=@H^oBBp0=@bCqs{64P8rXi-6Ns`cV0<0etwlk z^rDm74R6+u-455QdezoC8Qq(`)a`LD>G-Y_Z?){So}?Qx7JS!58dxOAZ5R;cl)1L_ z04+Hc#3tXSUB3R_vS6`?`k52b{nn=rlVov;6q7Xz$Wi)UIx$#_Dva##P0* zSPV-AoA4VC#YPGKa=%+$ubCDYsx;h}v*cf^(vRe{cV4Nw{Hte$WO3r{e1%~$_AxP} z{cwS_SWa((+b;fHw4`B>$W$$C(!Nm{pt11B7K%^ z_sR9$P6kOY85+TzxW;2rf^*=+8JkmT$qgoSdHUaPxRoq(C9}Ouy@nWO)3AD(u4jQE z#uj@cfn(QN!StjDr!^&x=nk83JMI}y1Q+j#x98?gxJ2GJmo?6}C@VrexD>gs#&;co z>NcU?x4}cQ@h8sM!QN4-#}o5AI~(igVmCr>c3VR(9hKnVOR3Sx_+@0vt8dye&lN1P zj=BI5(_qxN-XI_Lh*Qxrxc@{bDik#`g>&$j>~+5 zT)!3Ctb33;cp_t0Va>&J)hDdNS55`yR}XBm@I_neiyCa*2mJLi#HZ@$DI{J0)rab` z@AZ5;vW~y=TH&DW*%Sd;e!er8R^A3BmS7yGm<^V<3b{G=4 zPP^$JWx|kj%*c42*@=T&q;7w%urAoP$E1 z#-7inzcsx8$%JXUd5cz^{9%FXYpcn@yDR+tfAJ}z-h9RFw6b=S zSVY|wPE52{9a@$)HTRd+j}9P{kaOSR^pHNKQf^^1YSh))km$h?Oz{Qk7urr(UU`AQcpq43Qxo9_z@ZQm{mjM#geME{KIGJOY>I zNG3V*DAQ07kM1d!2|*;C0wEX)<0PWU=>ZktboT%s28Q4Oe3S&lf(kxjfUE(52ofjA zKMsWmgmAC|RPl)?Q^*u5KqV3#9SLNB{84E&ER!R(s6xd94vsVNs1id*!a=A7Rh5bW zOj{t)(3vtARET9EVsR`3qjCzZviva2K^7DQDnJ&ffDurD;7A7ubUZbL0MH2(I>8YO zQ0c%Y`eI1HPyD~MRm%tMJd<>9fgG7XaauI9rh;MV%+t(ctYCUEq0!UJf)4U#LXd;; zFf{Eaf;BV5ivmTFFw#HX73_Pt;6D@ti9*H`Ax9FH0`ZXylKFTnmF!5x@@N!@OyUu# z5ZUo_bh((XNC0K9dnCdm!WB}W(_EpKze|UxU0=k& z7b$hv$VLrUM$p<>RVX%Q!XOW zm3W8AQ7C;A)uo0ym~V*)wG}=bwsxPoiROGukCI!5kh3)M_Us-)y;iX2qOS*Nnq}qN z5OWM;v^Aiy_>PB{Ku@uKpZToaHU8Up)XXu>>YdH1 zGmOV=?>Q9L8__b}GEz50vr6MCwEo-%rmCe|hFDLUSEu=})-2qxXG;5IpQqdwKmXRm z(gR7N43qI8RNoc#S6w}!}$YH3yS)T5=BUe@ij^|m?UIog>R zJG*`J+dI(@qP{^T+$wp@AEYec*rj16o`w7W_%LVr<-HlW;>UlKKqR}vMtK%Z&RBEf zV(NIYnUc!-@!_L9ef0w=NgW;yc}E}q9q=MvZMjwc!<<>P4ui$7HmF7AtyenL+&;3! z-u#ZM%CELV_!4#EVBA#wikqkSX}Hao&OEzeqwA040OiB>XPx%g Gxb@#eV8m(w From a40266bc03a5aaa3c24105cba797646532ba5c57 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 13:48:06 -0800 Subject: [PATCH 085/103] Renamed constants to consts --- src/main/java/com/team766/robot/{Constants => consts}/Config.txt | 0 .../robot/{Constants => consts}/ExampleInputConstants.java | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/{Constants => consts}/Config.txt (100%) rename src/main/java/com/team766/robot/{Constants => consts}/ExampleInputConstants.java (100%) diff --git a/src/main/java/com/team766/robot/Constants/Config.txt b/src/main/java/com/team766/robot/consts/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/Constants/Config.txt rename to src/main/java/com/team766/robot/consts/Config.txt diff --git a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/consts/ExampleInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/Constants/ExampleInputConstants.java rename to src/main/java/com/team766/robot/consts/ExampleInputConstants.java From 67f9d2a403c20e5a204e905517846e91269f5d4f Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 13:52:58 -0800 Subject: [PATCH 086/103] Renamed consts to constants --- src/main/java/com/team766/robot/{consts => constants}/Config.txt | 0 .../robot/{consts => constants}/ExampleInputConstants.java | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/{consts => constants}/Config.txt (100%) rename src/main/java/com/team766/robot/{consts => constants}/ExampleInputConstants.java (100%) diff --git a/src/main/java/com/team766/robot/consts/Config.txt b/src/main/java/com/team766/robot/constants/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/consts/Config.txt rename to src/main/java/com/team766/robot/constants/Config.txt diff --git a/src/main/java/com/team766/robot/consts/ExampleInputConstants.java b/src/main/java/com/team766/robot/constants/ExampleInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/consts/ExampleInputConstants.java rename to src/main/java/com/team766/robot/constants/ExampleInputConstants.java From 94aa5bbc211e10c0fb20d2c14d35ca68de55e06a Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 14:00:38 -0800 Subject: [PATCH 087/103] Fixed error resulting from unrecognized partial derivative symbol --- .../com/team766/simulator/mechanisms/DoubleJointedArm.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java b/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java index a282971f..dad28752 100644 --- a/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java +++ b/src/main/java/com/team766/simulator/mechanisms/DoubleJointedArm.java @@ -110,14 +110,14 @@ public class DoubleJointedArm { // L = 1/2 * I1 * theta1'^2 + 1/2 * I2 * theta2'^2 + Ix * cos(theta1 - theta2) * theta1' * theta2' + g1 * cos(theta1) + g2 * cos(theta2) // // Euler-Lagrangian: - // d/dt ∂L/∂theta' - ∂L/∂theta = tau + // d/dt [Partial]L/[Partial]theta' - [Partial]L/[Partial]theta = tau // - // d/dt ∂L/∂theta1' - ∂L/∂theta1 = I1 * theta1'' + Ix * cos(theta1 - theta2) * theta2'' - Ix * sin(theta1 - theta2) * (theta1' - theta2') * theta2' + // d/dt [Partial]L/[Partial]theta1' - [Partial]L/[Partial]theta1 = I1 * theta1'' + Ix * cos(theta1 - theta2) * theta2'' - Ix * sin(theta1 - theta2) * (theta1' - theta2') * theta2' // + Ix * sin(theta1 - theta2) * theta1' * theta2' + g1 * sin(theta1) // = I1 * theta1'' + Ix * cos(theta1 - theta2) * theta2'' + Ix * sin(theta1 - theta2) * theta2'^2 + g1 * sin(theta1) // = tau1 // - // d/dt ∂L/∂theta2' - ∂L/∂theta2 = I2 * theta2'' + Ix * cos(theta1 - theta2) * theta1'' - Ix * sin(theta1 - theta2) * (theta1' - theta2') * theta1' + // d/dt [Partial]L/[Partial]theta2' - [Partial]L/[Partial]theta2 = I2 * theta2'' + Ix * cos(theta1 - theta2) * theta1'' - Ix * sin(theta1 - theta2) * (theta1' - theta2') * theta1' // - Ix * sin(theta1 - theta2) * theta1' * theta2' + g2 * sin(theta2)) // = I2 * theta2'' + Ix * cos(theta1 - theta2) * theta1'' - Ix * sin(theta1 - theta2) * theta1'^2 + g2 * sin(theta2) // = tau2 From 7bba535bf915e1ba7f73e36445478c48e72fa1b3 Mon Sep 17 00:00:00 2001 From: BCNOFNeNaMg <47834221+BCNOFNeNaMg@users.noreply.github.com> Date: Sat, 4 Mar 2023 14:10:04 -0800 Subject: [PATCH 088/103] Delete src/main/java/com/team766/robot/Constants directory --- .../com/team766/robot/Constants/Config.txt | 3 -- .../Constants/ExampleInputConstants.java | 40 ------------------- 2 files changed, 43 deletions(-) delete mode 100644 src/main/java/com/team766/robot/Constants/Config.txt delete mode 100644 src/main/java/com/team766/robot/Constants/ExampleInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/Config.txt b/src/main/java/com/team766/robot/Constants/Config.txt deleted file mode 100644 index 4eb7c3f9..00000000 --- a/src/main/java/com/team766/robot/Constants/Config.txt +++ /dev/null @@ -1,3 +0,0 @@ -{ - -} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java deleted file mode 100644 index aa7cb28b..00000000 --- a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java +++ /dev/null @@ -1,40 +0,0 @@ -package com.team766.robot.constants; - -/** - * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. - * - */ -public final class ExampleInputConstants { - - // "joysticks" - public static final int LEFT_JOYSTICK = 0; - public static final int RIGHT_JOYSTICK = 1; - public static final int CONTROL_PANEL = 2; - - // navigation - public static final int AXIS_LEFT_RIGHT = 0; - public static final int AXIS_FORWARD_BACKWARD = 1; - - - public static final int AXIS_SHOOTER_DIAL = 3; - - public static final int CONTROL_PANEL_SHOOTER_SWITCH = 1; - public static final int CONTROL_PANEL_INTAKE_BUTTON = 2; - - public static final int CONTROL_PANEL_BELTS_BUTTON = 3; - - public static final int CONTROL_PANEL_SPITBALL_BUTTON = 14; - - public static final int CONTROL_PANEL_AUTOCLIMB_BUTTON = 9; - public static final int CONTROL_PANEL_ARMS_SWITCH = 13; - public static final int CONTROL_PANEL_ELEVATOR_UP_BUTTON = 7; - public static final int CONTROL_PANEL_ELEVATOR_DOWN_BUTTON = 8; - public static final int CONTROL_PANEL_ELEVATOR_TOP_BUTTON = 5; - public static final int CONTROL_PANEL_ELEVATOR_BOTTOM_BUTTON = 6; - public static final int CONTROL_PANEL_AUTO_SHOOT = 10; - public static final int JOYSTICK_TRIGGER = 1; - public static final int E_STOP = 11; - public static final int JOYSTICK_ELEVATOR_RESET_BUTTON = 2; - public static final int JOYSTICK_CLIMB_RUNG_BUTTON = 4; - public static final int JOYSTICK_CLIMB_FIRST_RUNG_BUTTON = 5; -} From 27bda145cd5cb788c8b1dc5dd68b1fb7ba7f7efb Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 14:11:57 -0800 Subject: [PATCH 089/103] Deleted empty constant file --- .../constants/ExampleInputConstants.java | 40 ------------------- 1 file changed, 40 deletions(-) delete mode 100644 src/main/java/com/team766/robot/constants/ExampleInputConstants.java diff --git a/src/main/java/com/team766/robot/constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/constants/ExampleInputConstants.java deleted file mode 100644 index aa7cb28b..00000000 --- a/src/main/java/com/team766/robot/constants/ExampleInputConstants.java +++ /dev/null @@ -1,40 +0,0 @@ -package com.team766.robot.constants; - -/** - * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. - * - */ -public final class ExampleInputConstants { - - // "joysticks" - public static final int LEFT_JOYSTICK = 0; - public static final int RIGHT_JOYSTICK = 1; - public static final int CONTROL_PANEL = 2; - - // navigation - public static final int AXIS_LEFT_RIGHT = 0; - public static final int AXIS_FORWARD_BACKWARD = 1; - - - public static final int AXIS_SHOOTER_DIAL = 3; - - public static final int CONTROL_PANEL_SHOOTER_SWITCH = 1; - public static final int CONTROL_PANEL_INTAKE_BUTTON = 2; - - public static final int CONTROL_PANEL_BELTS_BUTTON = 3; - - public static final int CONTROL_PANEL_SPITBALL_BUTTON = 14; - - public static final int CONTROL_PANEL_AUTOCLIMB_BUTTON = 9; - public static final int CONTROL_PANEL_ARMS_SWITCH = 13; - public static final int CONTROL_PANEL_ELEVATOR_UP_BUTTON = 7; - public static final int CONTROL_PANEL_ELEVATOR_DOWN_BUTTON = 8; - public static final int CONTROL_PANEL_ELEVATOR_TOP_BUTTON = 5; - public static final int CONTROL_PANEL_ELEVATOR_BOTTOM_BUTTON = 6; - public static final int CONTROL_PANEL_AUTO_SHOOT = 10; - public static final int JOYSTICK_TRIGGER = 1; - public static final int E_STOP = 11; - public static final int JOYSTICK_ELEVATOR_RESET_BUTTON = 2; - public static final int JOYSTICK_CLIMB_RUNG_BUTTON = 4; - public static final int JOYSTICK_CLIMB_FIRST_RUNG_BUTTON = 5; -} From e2d84bb4b2443731f16c65aa2da42f4e8729dc43 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 14:23:50 -0800 Subject: [PATCH 090/103] Added "off" to documentation --- docs/candle.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/candle.md b/docs/candle.md index 999075c6..b026f770 100644 --- a/docs/candle.md +++ b/docs/candle.md @@ -4,4 +4,6 @@ Use `Robot.candle.setColor(int r, int g, int b);` to display single colors on th **Yellow:** R: 255 G: 255 B: 0 -**Purple:** R: 255 G: 0 B: 255 \ No newline at end of file +**Purple:** R: 255 G: 0 B: 255 + +**Off** R: 0 G: 0 B: 0 From 8edac058d8236027ba60e9a7a0a90b339b22f2b5 Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 14:27:08 -0800 Subject: [PATCH 091/103] Reset OI --- src/main/java/com/team766/robot/OI.java | 16 ---------------- 1 file changed, 16 deletions(-) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 392f99e7..95817493 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -29,28 +29,12 @@ public OI() { } public void run(Context context) { - int color = 0; - context.takeOwnership(Robot.candle); - Robot.candle.setColor(0, 0, 0); - context.releaseOwnership(Robot.candle); while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); RobotProvider.instance.refreshDriverStationData(); - if (joystick0.getButtonPressed(1)) { - color = (++color) % 3; - context.takeOwnership(Robot.candle); - log(color + " "); - switch (color) { - case 0: Robot.candle.setColor(0, 0, 0); break; - case 1: Robot.candle.setColor(255, 0, 255); break; - case 2: Robot.candle.setColor(255, 255, 0); break; - } - context.releaseOwnership(Robot.candle); - } - // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. From 6d5557e7a0ad53733c376e647ded2d77cadb875d Mon Sep 17 00:00:00 2001 From: Adrian Deutscher-Bishop Date: Sat, 4 Mar 2023 14:29:56 -0800 Subject: [PATCH 092/103] Removed matrix from CANdleMech --- src/main/java/com/team766/robot/Robot.java | 2 +- .../com/team766/robot/mechanisms/CANdleMech.java | 13 +++---------- 2 files changed, 4 insertions(+), 11 deletions(-) diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java index 81cc79b5..757745dc 100644 --- a/src/main/java/com/team766/robot/Robot.java +++ b/src/main/java/com/team766/robot/Robot.java @@ -8,6 +8,6 @@ public class Robot { public static void robotInit() { // Initialize mechanisms here - candle = new CANdleMech(8, 16, 16); + candle = new CANdleMech(); } } diff --git a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java index 2005b7ee..1b8f6788 100644 --- a/src/main/java/com/team766/robot/mechanisms/CANdleMech.java +++ b/src/main/java/com/team766/robot/mechanisms/CANdleMech.java @@ -31,17 +31,10 @@ public class CANdleMech extends Mechanism { - - private final CANdle m_candle = new CANdle(5); - private int matrixStart; - public int w; - public int h; - - public CANdleMech(int matrixStart, int w, int h) { - this.matrixStart = matrixStart; - this.w = w; - this.h = h; + + public CANdleMech() { + } public void setColor(short r, short g, short b, int index, int count) { From 346e404dbbdf4f00bf3a640ae39e0d56645fc0d8 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:00:22 -0800 Subject: [PATCH 093/103] changed constants name --- .../java/com/team766/robot/{constants => badconstants}/Config.txt | 0 .../robot/{constants => badconstants}/ExampleInputConstants.java | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/{constants => badconstants}/Config.txt (100%) rename src/main/java/com/team766/robot/{constants => badconstants}/ExampleInputConstants.java (100%) diff --git a/src/main/java/com/team766/robot/constants/Config.txt b/src/main/java/com/team766/robot/badconstants/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/constants/Config.txt rename to src/main/java/com/team766/robot/badconstants/Config.txt diff --git a/src/main/java/com/team766/robot/constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/badconstants/ExampleInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/constants/ExampleInputConstants.java rename to src/main/java/com/team766/robot/badconstants/ExampleInputConstants.java From d19fa734300c1db8120c7d22df748db1ecbb0cbe Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:25:00 -0800 Subject: [PATCH 094/103] Delete src/main/java/com/team766/robot/Constants directory --- .../Constants/FollowPointsInputConstants.java | 12 ---------- .../robot/Constants/InputConstants.java | 24 ------------------- .../Constants/OdometryInputConstants.java | 17 ------------- 3 files changed, 53 deletions(-) delete mode 100644 src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java delete mode 100644 src/main/java/com/team766/robot/Constants/InputConstants.java delete mode 100644 src/main/java/com/team766/robot/Constants/OdometryInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java b/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java deleted file mode 100644 index 31fa5068..00000000 --- a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java +++ /dev/null @@ -1,12 +0,0 @@ -package com.team766.robot.constants; - -public final class FollowPointsInputConstants { - - public static double RADIUS = 0.5; - public static double SPEED = 0.5; - public static double RATE_LIMITER_TIME = 0.01; - public static double MAX_ROTATION_SPEED = 0.2; - public static double ANGLE_DISTANCE_FOR_MAX_SPEED = 90; - - -} diff --git a/src/main/java/com/team766/robot/Constants/InputConstants.java b/src/main/java/com/team766/robot/Constants/InputConstants.java deleted file mode 100644 index 97970e25..00000000 --- a/src/main/java/com/team766/robot/Constants/InputConstants.java +++ /dev/null @@ -1,24 +0,0 @@ -package com.team766.robot.constants; - -/** - * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. - * - * TODO: consider moving this into a config file. - */ -public final class InputConstants { - - //Joysticks - public static final int LEFT_JOYSTICK = 0; - public static final int RIGHT_JOYSTICK = 1; - public static final int CONTROL_PANEL = 2; - - //Navigation - public static final int AXIS_LEFT_RIGHT = 0; - public static final int AXIS_FORWARD_BACKWARD = 1; - public static final int AXIS_TWIST = 3; - // Joystick buttons - public static final int CROSS_DEFENSE = 1; - public static final int RESET_GYRO = 1; - public static final int RESET_CURRENT_POSITION = 11; - //Other buttons -} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java b/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java deleted file mode 100644 index ac3be89a..00000000 --- a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java +++ /dev/null @@ -1,17 +0,0 @@ -package com.team766.robot.constants; - -import com.team766.hal.MotorController; - -/** - * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. - * - */ -public final class OdometryInputConstants { - - public static double WHEEL_CIRCUMFERENCE = 30.5 / 100; - public static double GEAR_RATIO = 6.75; - public static int ENCODER_TO_REVOLUTION_CONSTANT = 2048; - public static double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; - public static double RATE_LIMITER_TIME = 0.05; - -} From f8b8f0be54e37e4f09692f10337f37198ec4574d Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:25:35 -0800 Subject: [PATCH 095/103] Delete src/main/java/com/team766/robot/Constants directory --- .../Constants/FollowPointsInputConstants.java | 12 ---------- .../robot/Constants/InputConstants.java | 24 ------------------- .../Constants/OdometryInputConstants.java | 17 ------------- 3 files changed, 53 deletions(-) delete mode 100644 src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java delete mode 100644 src/main/java/com/team766/robot/Constants/InputConstants.java delete mode 100644 src/main/java/com/team766/robot/Constants/OdometryInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java b/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java deleted file mode 100644 index 31fa5068..00000000 --- a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java +++ /dev/null @@ -1,12 +0,0 @@ -package com.team766.robot.constants; - -public final class FollowPointsInputConstants { - - public static double RADIUS = 0.5; - public static double SPEED = 0.5; - public static double RATE_LIMITER_TIME = 0.01; - public static double MAX_ROTATION_SPEED = 0.2; - public static double ANGLE_DISTANCE_FOR_MAX_SPEED = 90; - - -} diff --git a/src/main/java/com/team766/robot/Constants/InputConstants.java b/src/main/java/com/team766/robot/Constants/InputConstants.java deleted file mode 100644 index 97970e25..00000000 --- a/src/main/java/com/team766/robot/Constants/InputConstants.java +++ /dev/null @@ -1,24 +0,0 @@ -package com.team766.robot.constants; - -/** - * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. - * - * TODO: consider moving this into a config file. - */ -public final class InputConstants { - - //Joysticks - public static final int LEFT_JOYSTICK = 0; - public static final int RIGHT_JOYSTICK = 1; - public static final int CONTROL_PANEL = 2; - - //Navigation - public static final int AXIS_LEFT_RIGHT = 0; - public static final int AXIS_FORWARD_BACKWARD = 1; - public static final int AXIS_TWIST = 3; - // Joystick buttons - public static final int CROSS_DEFENSE = 1; - public static final int RESET_GYRO = 1; - public static final int RESET_CURRENT_POSITION = 11; - //Other buttons -} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java b/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java deleted file mode 100644 index ac3be89a..00000000 --- a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java +++ /dev/null @@ -1,17 +0,0 @@ -package com.team766.robot.constants; - -import com.team766.hal.MotorController; - -/** - * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. - * - */ -public final class OdometryInputConstants { - - public static double WHEEL_CIRCUMFERENCE = 30.5 / 100; - public static double GEAR_RATIO = 6.75; - public static int ENCODER_TO_REVOLUTION_CONSTANT = 2048; - public static double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; - public static double RATE_LIMITER_TIME = 0.05; - -} From 6bf8907d5bde4bfb145b86af5043f275e107f9e4 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:25:43 -0800 Subject: [PATCH 096/103] fixed constants --- .../java/com/team766/robot/{badconstants => Constants}/Config.txt | 0 .../robot/{badconstants => Constants}/ExampleInputConstants.java | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/{badconstants => Constants}/Config.txt (100%) rename src/main/java/com/team766/robot/{badconstants => Constants}/ExampleInputConstants.java (100%) diff --git a/src/main/java/com/team766/robot/badconstants/Config.txt b/src/main/java/com/team766/robot/Constants/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/badconstants/Config.txt rename to src/main/java/com/team766/robot/Constants/Config.txt diff --git a/src/main/java/com/team766/robot/badconstants/ExampleInputConstants.java b/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/badconstants/ExampleInputConstants.java rename to src/main/java/com/team766/robot/Constants/ExampleInputConstants.java From ad146efcd255300b89e3f397dfddd9e852d6ff5d Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:27:07 -0800 Subject: [PATCH 097/103] Revert "Merge branch 'fixConstants' of https://github.com/Team766/2023 into fixConstants" This reverts commit c42a6559103406745d318e98fa240db7805cf877, reversing changes made to 6bf8907d5bde4bfb145b86af5043f275e107f9e4. --- .../Constants/FollowPointsInputConstants.java | 12 ++++++++++ .../robot/Constants/InputConstants.java | 24 +++++++++++++++++++ .../Constants/OdometryInputConstants.java | 17 +++++++++++++ 3 files changed, 53 insertions(+) create mode 100644 src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java create mode 100644 src/main/java/com/team766/robot/Constants/InputConstants.java create mode 100644 src/main/java/com/team766/robot/Constants/OdometryInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java b/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java new file mode 100644 index 00000000..31fa5068 --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java @@ -0,0 +1,12 @@ +package com.team766.robot.constants; + +public final class FollowPointsInputConstants { + + public static double RADIUS = 0.5; + public static double SPEED = 0.5; + public static double RATE_LIMITER_TIME = 0.01; + public static double MAX_ROTATION_SPEED = 0.2; + public static double ANGLE_DISTANCE_FOR_MAX_SPEED = 90; + + +} diff --git a/src/main/java/com/team766/robot/Constants/InputConstants.java b/src/main/java/com/team766/robot/Constants/InputConstants.java new file mode 100644 index 00000000..97970e25 --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/InputConstants.java @@ -0,0 +1,24 @@ +package com.team766.robot.constants; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + * TODO: consider moving this into a config file. + */ +public final class InputConstants { + + //Joysticks + public static final int LEFT_JOYSTICK = 0; + public static final int RIGHT_JOYSTICK = 1; + public static final int CONTROL_PANEL = 2; + + //Navigation + public static final int AXIS_LEFT_RIGHT = 0; + public static final int AXIS_FORWARD_BACKWARD = 1; + public static final int AXIS_TWIST = 3; + // Joystick buttons + public static final int CROSS_DEFENSE = 1; + public static final int RESET_GYRO = 1; + public static final int RESET_CURRENT_POSITION = 11; + //Other buttons +} \ No newline at end of file diff --git a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java b/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java new file mode 100644 index 00000000..ac3be89a --- /dev/null +++ b/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java @@ -0,0 +1,17 @@ +package com.team766.robot.constants; + +import com.team766.hal.MotorController; + +/** + * Constants used for the Operator Interface, eg for joyticks, buttons, dials, etc. + * + */ +public final class OdometryInputConstants { + + public static double WHEEL_CIRCUMFERENCE = 30.5 / 100; + public static double GEAR_RATIO = 6.75; + public static int ENCODER_TO_REVOLUTION_CONSTANT = 2048; + public static double DISTANCE_BETWEEN_WHEELS = 24 * 2.54 / 100; + public static double RATE_LIMITER_TIME = 0.05; + +} From 97f6d84d0a410360d7809a87490ef75c346a6bab Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:29:12 -0800 Subject: [PATCH 098/103] HEEEEconstants --- .../com/team766/robot/{Constants => HEEEEconstants}/Config.txt | 0 .../{Constants => HEEEEconstants}/ExampleInputConstants.java | 0 .../{Constants => HEEEEconstants}/FollowPointsInputConstants.java | 0 .../robot/{Constants => HEEEEconstants}/InputConstants.java | 0 .../{Constants => HEEEEconstants}/OdometryInputConstants.java | 0 5 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/{Constants => HEEEEconstants}/Config.txt (100%) rename src/main/java/com/team766/robot/{Constants => HEEEEconstants}/ExampleInputConstants.java (100%) rename src/main/java/com/team766/robot/{Constants => HEEEEconstants}/FollowPointsInputConstants.java (100%) rename src/main/java/com/team766/robot/{Constants => HEEEEconstants}/InputConstants.java (100%) rename src/main/java/com/team766/robot/{Constants => HEEEEconstants}/OdometryInputConstants.java (100%) diff --git a/src/main/java/com/team766/robot/Constants/Config.txt b/src/main/java/com/team766/robot/HEEEEconstants/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/Constants/Config.txt rename to src/main/java/com/team766/robot/HEEEEconstants/Config.txt diff --git a/src/main/java/com/team766/robot/Constants/ExampleInputConstants.java b/src/main/java/com/team766/robot/HEEEEconstants/ExampleInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/Constants/ExampleInputConstants.java rename to src/main/java/com/team766/robot/HEEEEconstants/ExampleInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java b/src/main/java/com/team766/robot/HEEEEconstants/FollowPointsInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/Constants/FollowPointsInputConstants.java rename to src/main/java/com/team766/robot/HEEEEconstants/FollowPointsInputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/InputConstants.java b/src/main/java/com/team766/robot/HEEEEconstants/InputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/Constants/InputConstants.java rename to src/main/java/com/team766/robot/HEEEEconstants/InputConstants.java diff --git a/src/main/java/com/team766/robot/Constants/OdometryInputConstants.java b/src/main/java/com/team766/robot/HEEEEconstants/OdometryInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/Constants/OdometryInputConstants.java rename to src/main/java/com/team766/robot/HEEEEconstants/OdometryInputConstants.java From 35959b9f2b5d26996b7c6544b565b225b4b278f1 Mon Sep 17 00:00:00 2001 From: Alexandre Sauquet <54484828+SauquetAlex@users.noreply.github.com> Date: Wed, 8 Mar 2023 19:30:11 -0800 Subject: [PATCH 099/103] notHEEEE --- .../com/team766/robot/{HEEEEconstants => constants}/Config.txt | 0 .../{HEEEEconstants => constants}/ExampleInputConstants.java | 0 .../{HEEEEconstants => constants}/FollowPointsInputConstants.java | 0 .../robot/{HEEEEconstants => constants}/InputConstants.java | 0 .../{HEEEEconstants => constants}/OdometryInputConstants.java | 0 5 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/com/team766/robot/{HEEEEconstants => constants}/Config.txt (100%) rename src/main/java/com/team766/robot/{HEEEEconstants => constants}/ExampleInputConstants.java (100%) rename src/main/java/com/team766/robot/{HEEEEconstants => constants}/FollowPointsInputConstants.java (100%) rename src/main/java/com/team766/robot/{HEEEEconstants => constants}/InputConstants.java (100%) rename src/main/java/com/team766/robot/{HEEEEconstants => constants}/OdometryInputConstants.java (100%) diff --git a/src/main/java/com/team766/robot/HEEEEconstants/Config.txt b/src/main/java/com/team766/robot/constants/Config.txt similarity index 100% rename from src/main/java/com/team766/robot/HEEEEconstants/Config.txt rename to src/main/java/com/team766/robot/constants/Config.txt diff --git a/src/main/java/com/team766/robot/HEEEEconstants/ExampleInputConstants.java b/src/main/java/com/team766/robot/constants/ExampleInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/HEEEEconstants/ExampleInputConstants.java rename to src/main/java/com/team766/robot/constants/ExampleInputConstants.java diff --git a/src/main/java/com/team766/robot/HEEEEconstants/FollowPointsInputConstants.java b/src/main/java/com/team766/robot/constants/FollowPointsInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/HEEEEconstants/FollowPointsInputConstants.java rename to src/main/java/com/team766/robot/constants/FollowPointsInputConstants.java diff --git a/src/main/java/com/team766/robot/HEEEEconstants/InputConstants.java b/src/main/java/com/team766/robot/constants/InputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/HEEEEconstants/InputConstants.java rename to src/main/java/com/team766/robot/constants/InputConstants.java diff --git a/src/main/java/com/team766/robot/HEEEEconstants/OdometryInputConstants.java b/src/main/java/com/team766/robot/constants/OdometryInputConstants.java similarity index 100% rename from src/main/java/com/team766/robot/HEEEEconstants/OdometryInputConstants.java rename to src/main/java/com/team766/robot/constants/OdometryInputConstants.java From 39183335512da4a2230aa0dc9608ca8739a447b3 Mon Sep 17 00:00:00 2001 From: nate19428 Date: Sat, 11 Mar 2023 11:25:05 -0800 Subject: [PATCH 100/103] update build.gradle to 4.2 --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 8d64237f..17a2c676 100644 --- a/build.gradle +++ b/build.gradle @@ -2,7 +2,7 @@ plugins { id "java" id 'java-library' id 'maven-publish' - id "edu.wpi.first.GradleRIO" version "2023.4.1" + id "edu.wpi.first.GradleRIO" version "2023.4.2" id 'com.google.protobuf' version '0.8.19' } From f4a29a008b301b0f1e489efc7c5f7cb80265e6a3 Mon Sep 17 00:00:00 2001 From: nate19428 Date: Sun, 12 Mar 2023 01:41:16 -0800 Subject: [PATCH 101/103] initial revA bringup --- .../com/team766/hal/GenericRobotMain.java | 4 +- .../java/com/team766/hal/RobotProvider.java | 4 +- .../java/com/team766/hal/wpilib/Solenoid.java | 2 +- .../team766/hal/wpilib/WPIRobotProvider.java | 10 +- src/main/java/com/team766/robot/OI.java | 139 ++++++++++++++++++ src/main/java/com/team766/robot/Robot.java | 9 +- .../com/team766/robot/mechanisms/Arms.java | 16 ++ .../com/team766/robot/mechanisms/Drive.java | 10 +- .../com/team766/robot/mechanisms/Grabber.java | 25 ++++ .../com/team766/robot/mechanisms/Gyro.java | 2 +- .../com/team766/robot/mechanisms/Intake.java | 44 ++++++ .../com/team766/robot/mechanisms/Storage.java | 28 ++++ 12 files changed, 280 insertions(+), 13 deletions(-) create mode 100644 src/main/java/com/team766/robot/mechanisms/Arms.java create mode 100644 src/main/java/com/team766/robot/mechanisms/Grabber.java create mode 100644 src/main/java/com/team766/robot/mechanisms/Intake.java create mode 100644 src/main/java/com/team766/robot/mechanisms/Storage.java diff --git a/src/main/java/com/team766/hal/GenericRobotMain.java b/src/main/java/com/team766/hal/GenericRobotMain.java index 599f9ff3..940fbcce 100755 --- a/src/main/java/com/team766/hal/GenericRobotMain.java +++ b/src/main/java/com/team766/hal/GenericRobotMain.java @@ -122,13 +122,13 @@ public void teleopInit() { m_autonMode = null; } - if (m_oiContext == null) { + if (m_oiContext == null && m_oi != null) { m_oiContext = Scheduler.getInstance().startAsync(m_oi); } } public void teleopPeriodic() { - if (m_oiContext.isDone()) { + if (m_oiContext != null && m_oiContext.isDone()) { m_oiContext = Scheduler.getInstance().startAsync(m_oi); Logger.get(Category.OPERATOR_INTERFACE).logRaw(Severity.WARNING, "Restarting OI context"); } diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java index 4698eeb4..6cd2c027 100755 --- a/src/main/java/com/team766/hal/RobotProvider.java +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -24,7 +24,7 @@ public abstract class RobotProvider { public static RobotProvider instance; protected EncoderReader[] encoders = new EncoderReader[20]; - protected SolenoidController[] solenoids = new SolenoidController[10]; + protected SolenoidController[] solenoids = new SolenoidController[20]; protected GyroReader[] gyros = new GyroReader[13]; protected HashMap cams = new HashMap(); protected JoystickReader[] joysticks = new JoystickReader[8]; @@ -212,7 +212,7 @@ public DoubleSolenoid getSolenoid(String configName) { .toArray(SolenoidController[]::new)); return new DoubleSolenoid(forwardSolenoids, reverseSolenoids); } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Solenoid %s not found in config file, using mock solenoid instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Solenoid %s not found in config file, using mock solenoid instead %s", configName, ex.toString()); return new DoubleSolenoid(null, null); } } diff --git a/src/main/java/com/team766/hal/wpilib/Solenoid.java b/src/main/java/com/team766/hal/wpilib/Solenoid.java index e72f4694..e033aabb 100755 --- a/src/main/java/com/team766/hal/wpilib/Solenoid.java +++ b/src/main/java/com/team766/hal/wpilib/Solenoid.java @@ -6,6 +6,6 @@ public class Solenoid extends edu.wpi.first.wpilibj.Solenoid implements SolenoidController { public Solenoid(int channel) { - super(PneumaticsModuleType.CTREPCM, channel); + super(PneumaticsModuleType.REVPH, channel); } } diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 70f8ffc8..279c9f28 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -33,6 +33,7 @@ import edu.wpi.first.util.WPIUtilJNI; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.PneumaticHub; import edu.wpi.first.wpilibj.PneumaticsControlModule; import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.SPI; @@ -94,6 +95,12 @@ public void run() { public WPIRobotProvider() { m_dataRefreshThread = new Thread(m_DataRefreshRunnable, "DataRefreshThread"); m_dataRefreshThread.start(); + + try { + ph.enableCompressorAnalog(80, 100); + } catch (Exception ex) { + LoggerExceptionUtils.logException(ex); + } } private MotorController[][] motors = @@ -102,6 +109,7 @@ public WPIRobotProvider() { // The presence of this object allows the compressor to run before we've declared any solenoids. @SuppressWarnings("unused") private PneumaticsControlModule pcm = new PneumaticsControlModule(); + private PneumaticHub ph = new PneumaticHub(); @Override public MotorController getMotor(int index, String configPrefix, MotorController.Type type, @@ -128,7 +136,7 @@ public MotorController getMotor(int index, String configPrefix, MotorController. motor = new CANVictorMotorController(index); break; case TalonFX: - final ValueProvider CANBus = ConfigFileReader.getInstance().getString(type + ".CANBus"); + final ValueProvider CANBus = ConfigFileReader.getInstance().getString(configPrefix + ".CANBus"); motor = new CANTalonFxMotorController(index, CANBus.get()); break; case VictorSP: diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index fe54fb7a..880d5097 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -12,6 +12,7 @@ import com.team766.robot.procedures.*; import com.team766.simulator.interfaces.ElectricalDevice.Input; import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; /** * This class is the glue that binds the controls on the physical operator @@ -32,22 +33,160 @@ public class OI extends Procedure { private boolean isCross = false; double turningValue = 0; + enum IntakeState { + IDLE, + SPINNINGOUT, + SPINNINGIN + } + IntakeState intakeState = IntakeState.IDLE; + public OI() { loggerCategory = Category.OPERATOR_INTERFACE; joystick0 = RobotProvider.instance.getJoystick(0); joystick1 = RobotProvider.instance.getJoystick(1); joystick2 = RobotProvider.instance.getJoystick(2); + } public void run(Context context) { + context.takeOwnership(Robot.drive); + context.takeOwnership(Robot.intake); + context.takeOwnership(Robot.arms); + context.takeOwnership(Robot.grabber); + context.takeOwnership(Robot.storage); + context.takeOwnership(Robot.gyro); + while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); RobotProvider.instance.refreshDriverStationData(); + // Add driver controls here - make sure to take/release ownership // of mechanisms when appropriate. + /* if (joystick0.getButtonPressed(1)){ + if (intakeState == IntakeState.IDLE){ + Robot.intake.intakeIn(); + Robot.storage.beltIn(); + intakeState = IntakeState.SPINNINGIN; + } else { + Robot.intake.intakeIdle(); + Robot.storage.beltIdle(); + intakeState = IntakeState.IDLE; + } + } + + if (joystick0.getButtonPressed(2)){ + if (intakeState == IntakeState.IDLE){ + Robot.intake.intakeOut(); + Robot.storage.beltOut(); + intakeState = IntakeState.SPINNINGOUT; + } else { + Robot.intake.intakeIdle(); + Robot.storage.beltIdle(); + intakeState = IntakeState.IDLE; + } + } */ + + if(joystick1.getButton(2)){ + Robot.drive.setGyro(0); + }else{ + Robot.drive.setGyro(Robot.gyro.getGyroYaw()); + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ + RightJoystick_Y = joystick1.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + } else { + RightJoystick_Y = 0; + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ + RightJoystick_X = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT)/2; + if(joystick1.getButton(3)){ + RightJoystick_X *= 2; + } + } else { + RightJoystick_X = 0; + } + if(Math.abs(joystick1.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ + RightJoystick_Theta = joystick1.getAxis(InputConstants.AXIS_TWIST); + } else { + RightJoystick_Theta = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD)) > 0.05){ + LeftJoystick_Y = joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD); + } else { + LeftJoystick_Y = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT)) > 0.05){ + LeftJoystick_X = joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT); + } else { + LeftJoystick_X = 0; + } + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST)) > 0.05){ + LeftJoystick_Theta = joystick0.getAxis(InputConstants.AXIS_TWIST); + } else { + LeftJoystick_Theta = 0; + } + //log(Robot.gyro.getGyroYaw()); + //TODO: fix defense: the robot basically locks up if there is defense + // if(joystick0.getButton(InputConstants.CROSS_DEFENSE)){ + // context.startAsync(new DefenseCross()); + // } + + /*if(Math.pow(Math.pow(joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT),2) + Math.pow(joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD),2), 0.5) > 0.15 ){ + Robot.drive.drive2D( + ((joystick0.getAxis(InputConstants.AXIS_LEFT_RIGHT))), + ((joystick0.getAxis(InputConstants.AXIS_FORWARD_BACKWARD))) + ); + } else { + if(Math.abs(joystick0.getAxis(InputConstants.AXIS_TWIST))>=0.1){ + Robot.drive.turning(joystick0.getAxis(InputConstants.AXIS_TWIST)); + } else { + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + } + }*/ + if(joystick0.getButtonPressed(1)) + Robot.gyro.resetGyro(); + + if(joystick0.getButtonPressed(11)) + Robot.drive.resetCurrentPosition(); + + if(joystick1.getButtonPressed(1)) + isCross = !isCross; + + + if(joystick0.getButtonPressed(2)){ + Robot.drive.setFrontRightEncoders(); + Robot.drive.setFrontLeftEncoders(); + Robot.drive.setBackRightEncoders(); + Robot.drive.setBackLeftEncoders(); + } + // if(joystick1.getButton(1)){ + // turningValue = joystick1.getAxis(InputConstants.AXIS_LEFT_RIGHT); + // } else { + // turningValue = 0; + // } + + SmartDashboard.putNumber("Front left", Robot.drive.getFrontLeft()); + SmartDashboard.putNumber("Front right", Robot.drive.getFrontRight()); + SmartDashboard.putNumber("Back left", Robot.drive.getBackLeft()); + SmartDashboard.putNumber("Back right", Robot.drive.getBackRight()); + + if (isCross) { + context.startAsync(new setCross()); + } else if (joystick0.getButton(3)) { + Robot.drive.swerveDrive(0, -0.2, 0); + } else if(Math.abs(LeftJoystick_X)+ + Math.abs(LeftJoystick_Y) + Math.abs(RightJoystick_X) > 0) { + Robot.drive.swerveDrive( + (LeftJoystick_X), + (LeftJoystick_Y), + (RightJoystick_X)); + } else { + Robot.drive.stopDriveMotors(); + Robot.drive.stopSteerMotors(); + } } } diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java index b925972a..11c96c48 100644 --- a/src/main/java/com/team766/robot/Robot.java +++ b/src/main/java/com/team766/robot/Robot.java @@ -7,13 +7,20 @@ public class Robot { public static Drive drive; public static Gyro gyro; public static CANdleMech candle; - + public static Intake intake; + public static Storage storage; + public static Arms arms; + public static Grabber grabber; public static void robotInit() { // Initialize mechanisms here drive = new Drive(); gyro = new Gyro(); candle = new CANdleMech(); + intake = new Intake(); + storage = new Storage(); + arms = new Arms(); + grabber = new Grabber(); } } diff --git a/src/main/java/com/team766/robot/mechanisms/Arms.java b/src/main/java/com/team766/robot/mechanisms/Arms.java new file mode 100644 index 00000000..28d07cc2 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Arms.java @@ -0,0 +1,16 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.MotorController; +import com.team766.hal.RobotProvider; + +public class Arms extends Mechanism { + + private MotorController firstJoint; + private MotorController secondJoint; + + public Arms(){ + firstJoint = RobotProvider.instance.getMotor("arms.firstJoint"); + secondJoint = RobotProvider.instance.getMotor("arms.secondJoint"); + } +} diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 99966b3e..35fc37ff 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -77,13 +77,13 @@ public Drive() { config.sensorDirection = true; // initialize the encoders - e_FrontRight = new CANCoder(1, "Swerve"); + e_FrontRight = new CANCoder(22, "Swervavore"); // e_FrontRight.configAllSettings(config, 250); - e_FrontLeft = new CANCoder(2, "Swerve"); + e_FrontLeft = new CANCoder(23, "Swervavore"); // e_FrontLeft.configAllSettings(config, 250); - e_BackRight = new CANCoder(4, "Swerve"); + e_BackRight = new CANCoder(21, "Swervavore"); // e_BackRight.configAllSettings(config, 250); - e_BackLeft = new CANCoder(3, "Swerve"); + e_BackLeft = new CANCoder(24, "Swervavore"); // e_BackLeft.configAllSettings(config, 250); @@ -598,7 +598,7 @@ public void configPID() { m_SteerBackLeft.setP(0.2); m_SteerBackLeft.setI(0); m_SteerBackLeft.setD(0.1); - m_SteerBackLeft.setFF(0); + // m_SteerBackLeft.setFF(0); // pid values from sds for Flacons 500: P = 0.2 I = 0.0 D = 0.1 FF = 0.0 diff --git a/src/main/java/com/team766/robot/mechanisms/Grabber.java b/src/main/java/com/team766/robot/mechanisms/Grabber.java new file mode 100644 index 00000000..08aaa418 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Grabber.java @@ -0,0 +1,25 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.MotorController; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; + +public class Grabber extends Mechanism{ + + private MotorController wrist; + private SolenoidController grabber; + + public Grabber(){ + wrist = RobotProvider.instance.getMotor("wrist"); + grabber = RobotProvider.instance.getSolenoid("grabber"); + } + + public void grabIn(){ + grabber.set(true); + } + + public void grabOut(){ + grabber.set(false); + } +} diff --git a/src/main/java/com/team766/robot/mechanisms/Gyro.java b/src/main/java/com/team766/robot/mechanisms/Gyro.java index 5e291c62..effee44c 100644 --- a/src/main/java/com/team766/robot/mechanisms/Gyro.java +++ b/src/main/java/com/team766/robot/mechanisms/Gyro.java @@ -16,7 +16,7 @@ import com.ctre.phoenix.sensors.Pigeon2; public class Gyro extends Mechanism { - Pigeon2 g_gyro = new Pigeon2(0, "Swerve"); + Pigeon2 g_gyro = new Pigeon2(0, "Swervavore"); double[] gyroArray = new double[3]; private RateLimiter l_loggingRate = new RateLimiter(0.05); public Gyro() { diff --git a/src/main/java/com/team766/robot/mechanisms/Intake.java b/src/main/java/com/team766/robot/mechanisms/Intake.java new file mode 100644 index 00000000..ccfcaa1b --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Intake.java @@ -0,0 +1,44 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.MotorController; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.wpilib.CANSparkMaxMotorController; +import com.team766.hal.wpilib.Solenoid; + +public class Intake extends Mechanism { + + private MotorController bottomWheels; + private MotorController topBelt; + private SolenoidController leftPiston; + private SolenoidController rightPiston; + + public Intake(){ + bottomWheels = RobotProvider.instance.getMotor("intake.bottomWheels"); + topBelt = RobotProvider.instance.getMotor("intake.topWheels"); + leftPiston = RobotProvider.instance.getSolenoid("intake.leftPiston"); + rightPiston = RobotProvider.instance.getSolenoid("intake.rightPiston"); + } + + public void intakeIn(){ + bottomWheels.set(1); + topBelt.set(1); + leftPiston.set(true); + rightPiston.set(true); + } + + public void intakeOut(){ + bottomWheels.set(-1); + topBelt.set(-1); + leftPiston.set(true); + rightPiston.set(true); + } + + public void intakeIdle(){ + bottomWheels.set(0); + topBelt.set(0); + leftPiston.set(false); + rightPiston.set(false); + } +} diff --git a/src/main/java/com/team766/robot/mechanisms/Storage.java b/src/main/java/com/team766/robot/mechanisms/Storage.java new file mode 100644 index 00000000..6b00e5c8 --- /dev/null +++ b/src/main/java/com/team766/robot/mechanisms/Storage.java @@ -0,0 +1,28 @@ +package com.team766.robot.mechanisms; + +import com.team766.framework.Mechanism; +import com.team766.hal.MotorController; +import com.team766.hal.RobotProvider; +import com.team766.hal.SolenoidController; +import com.team766.hal.wpilib.CANSparkMaxMotorController; + +public class Storage extends Mechanism { + + private MotorController belt; + + public Storage(){ + belt = RobotProvider.instance.getMotor("belt"); + } + + public void beltIn(){ + belt.set(1); + } + + public void beltOut(){ + belt.set(-1); + } + + public void beltIdle(){ + belt.set(0); + } +} From 0dfb69c87a1014faa1a30c290115ec1fc19e1740 Mon Sep 17 00:00:00 2001 From: nate19428 Date: Sun, 12 Mar 2023 03:33:45 -0700 Subject: [PATCH 102/103] initial revA bringup, got drive working --- src/main/java/com/team766/robot/OI.java | 4 ++-- src/main/java/com/team766/robot/mechanisms/Drive.java | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index 880d5097..908b962f 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -176,12 +176,12 @@ public void run(Context context) { if (isCross) { context.startAsync(new setCross()); } else if (joystick0.getButton(3)) { - Robot.drive.swerveDrive(0, -0.2, 0); + Robot.drive.swerveDrive(0, 0.2, 0); } else if(Math.abs(LeftJoystick_X)+ Math.abs(LeftJoystick_Y) + Math.abs(RightJoystick_X) > 0) { Robot.drive.swerveDrive( (LeftJoystick_X), - (LeftJoystick_Y), + (-LeftJoystick_Y), (RightJoystick_X)); } else { Robot.drive.stopDriveMotors(); diff --git a/src/main/java/com/team766/robot/mechanisms/Drive.java b/src/main/java/com/team766/robot/mechanisms/Drive.java index 35fc37ff..10b06052 100644 --- a/src/main/java/com/team766/robot/mechanisms/Drive.java +++ b/src/main/java/com/team766/robot/mechanisms/Drive.java @@ -383,8 +383,8 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta brPower = NewMag(power, angle, JoystickTheta, -135); blPower = NewMag(power, angle, JoystickTheta, -45); frAngle = NewAng(power, angle, JoystickTheta, 45); - flAngle = NewAng(power, angle, JoystickTheta, -45); - brAngle = NewAng(power, angle, JoystickTheta, 135); + flAngle = NewAng(power, angle, JoystickTheta, 135); + brAngle = NewAng(power, angle, JoystickTheta, -45); blAngle = NewAng(power, angle, JoystickTheta, -135); } else { frPower = NewMag(power, angle, Math.abs(JoystickTheta), -45); @@ -392,8 +392,8 @@ public void swerveDrive(double JoystickX, double JoystickY, double JoystickTheta brPower = NewMag(power, angle, Math.abs(JoystickTheta), 45); blPower = NewMag(power, angle, Math.abs(JoystickTheta), 135); frAngle = NewAng(power, angle, Math.abs(JoystickTheta), -135); - flAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); - brAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + flAngle = NewAng(power, angle, Math.abs(JoystickTheta), -45); + brAngle = NewAng(power, angle, Math.abs(JoystickTheta), 135); blAngle = NewAng(power, angle, Math.abs(JoystickTheta), 45); } if (Math.max(Math.max(frPower, flPower), Math.max(brPower, blPower)) > 1) { From 2553cddf12b33125d979762409e6e25bad945d15 Mon Sep 17 00:00:00 2001 From: Ryan Cahoon Date: Sun, 12 Mar 2023 19:34:12 -0700 Subject: [PATCH 103/103] Remove unnecessary import from OI --- src/main/java/com/team766/robot/OI.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index e2706a6b..43062305 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -10,7 +10,6 @@ import com.team766.logging.Category; import com.team766.robot.constants.InputConstants; import com.team766.robot.procedures.*; -import com.team766.simulator.interfaces.ElectricalDevice.Input; import edu.wpi.first.wpilibj.DriverStation; /**

Q{1_iy0}lwen-%kqv(y#q%IH>{Q zm3Wx;&3mmiW`u_Yh|WieMxQ1w1}~fjfB=R>1;`{uv}DMTMg;5_$j*jz-qfL7v816| zSK6U$$#sHKg%DT%C{W?Nu2E%aY3W)N;@P^m)KpRR;J$U8VM~&*B5k73(erWixpmE* z{qC_%JLCH>Y6x&N2XBKFBTBhDY&g$FGu2Y$E|5-Iaf6iY;&`1#fz{hU!$nFPBXN(7 z?yloOD|Ww0(HZJnJqY9_>#^;+59TIL;zL$L+i??)sd!sz^%loe(_RPlO)zCSJ;b|u zJ8W6Q)2^HRttR(17`1$>i0X4ROa;7-srh9eDImJfSr7LzX+4oKf_+-ht z)i0T}@zDYB28a5!5JmElQt6?Y{+)cps;n03s^zvEw2i=bQz=D6P^L$fC?h&g^ASzw z?o9?S{VamW-DhPYOg4ucQK;n>v!jCy;oKskz#WIwhcayfE~!GS$Ss}ME!WCAk0dj^ zKPJ>pjx+u+ZF?3*v>zvB;i;%gmK0`^KlV$|%3{K$dSwe${BcMiOpGzFo_Z|-+_=6B z9A6EkR``4^J%vulQ zq)F2}S2a@){+;lulbU8XbxlC_z(W z^3Kkw0S0As=|aLXDY=f7Qgo_Wd2g@|>mLp}8go-X=OXfz^wXnoJGi7|NP=U69(p7? zU0_GJUA?WRCee~K_}|5ps|V7gPWF+Q22ukvtJ4#H?A zHD-dzo)p`AIN##s?E$t&>)_KxI@v~2Jk<+nks(4D5SS1NO{;`fQG$rB(N~2?FqU1$ zn)oCM;wA%)s;W`%va?9*-2)-jDCaG8RDyv->KA+aZ4$*D;4vfuSG~;9L)MI3S;1)f zH{yWC#Epa~$X4VTLf8Wl^_5XApO!DiBmFF5!gt!{5qsBT2sq`Qa zgK0DsnHo!}NCKlIMQB^~nR=sM7y@6Qt(8Ewjjy(g3l~?^#=Qp+qXu^DF#K)P#Ajby97s zqeo@<>G4~F1eaZ3@PxI%T>f5&k`!UBOS#y{rR1>ZI`u%PTcskXZHm^L#X$I_7-m5B zSKTL7^0Ej^*!?#><9@p&_(d$-{pQSEjq!U*7{dorn211yPlr@ZsVrOU%{glXX%ee3 zYC2PhieUs*2$e6>-a{o%@3e6=$9SPa#W#gjp+e%MNs@N|vBBg~mVL5i*2$@TF_Cd_ zo+Odz*=IT$_J^Cs4NYUkVegSvIz<(?fw;*B5e0;Sg(b3)5OJ+LVTCZcN;|rDhz7&9 zhK+XnMO&S1E#>K;9W~Dd7-QYNPhqP1ailc+=O!n4O*}dvE^97Ka~+0_q?8WoH0dD1 z5}`wpO~ZLQRTPg}AWCkvNMfAE9V578@dmAQMZ0pSYtI|c%>6!+L9G{EIG)~+K#(GO z>eeNQnz%C zSMMV8=Ly9!qj5oGrPDqc2T!}~9WLGUsn%XWI55>6 z2~_EuS)ufUys?cP3#}QLMLMyKi#}8}8z$kALIv-FTorcFV{SrN86p^8*e27UF7 zFdw)lgWdq|jaeyX@W7Hh46Wsmy;M!WFWfCRZOX*>PAi{|8 zyck0_rY^3nl+|k9c;}ndo=QrM>0fVK>c3hwe61~M+Jxf#8rqw!EtwFntYID(8B#TX zrK%u`RRYSU{*+PwQshjnU1KhznJeb-Bo@V%E@0oI%Rx<%F>_yD12w-pG=c7|6-X$n zCJVu+k~4A1H(^2bgD#3Z4>N*{(z`wBiGb!H($ZWSY3%7O6Yd^5pn1R$@ySr`iKII= zL_HVtk|4{93!UDBadtpxT&7OY-Ur*(8?#bf9`PbF`LRZ3F%_iW^0`Uqb|L$$&dZz# zCN6rn*HofX;W0w%LX>z39>GiteI>Rs1gX(>CNZ7fmlWcl#|{@=D$Lg+IhXxKUFn3H zlLRd)<-NyWg5H4l{RqUCTi6M-OXQ=dHqKk!Sow_ios8T?OY3p05c$5~9$CR`BfH;% z6obeca|7e&_3%59iN*Y4o~_V+YlhP5C9*OgV%=rM9)+Uq3nK1g}c z&`Y{D9BvJGw53>I@GRZi@UVJmLtTpn07|;qR}Q329#{?6X1h{SmwuGzHkEH`5N8{P z9#i4$BL5v| ziQ1_HiczB*Bt%JN!g$D>GR!f?WjHb4WmPA9lXt%XjhjL7bA|>yNBi}pg~K^x(D1vm z3hm-q1W=`v+gGjj$)L6-8o|m;tv1@AmKT$FMTYXMlDQzdfvmmt@r2g>x(1RUY@wd@ zI96=0kw84P03HT^OMd^CIYQ;ZP!K+G z!`~-Ui77tB#R>l7BfI=Fb$oZfcI5tTrJo+#Eyw%xIW-iHt@ZQI(6i{%ag16)h#d`l zyEwiKi_uuL^}!&q*Gi8+#f>nm+p;2Zw*Zb;((o=0M$9G?;C5lyifqCSlJqcOx<9Hp zg-+hUjbeIm&VtiNdNkSWr)Kii_8#~8r-!VBBO?}o%45I7mWM*ym{PN-e`!$ zogoLa9?#T}gb#1lk$EtY?@HQ1YntX7)zVt*EV~$k$UJ1h>m$FV_pC0?}>fn7gFHbLab%*lz#D0NyruPB1dYfZv2KFf)pW`aD5|{>=(ZynQ z*3g^PQa!8+HrZwe7p|O{UFu+IH}WY}g}q z#&&UO>o6jkR3gToL&^Nw{aupwX=6*uSj2_FrK>UO7qkt)E;&8Zmbkt0I-c?v`8dV( zsEFhme9BS6|F~dimX(zAA$VIFJgM&N+AWEH`}oxrq?+lJbMUWt916=> zq+>+TRq9dc`Zz(3nV5#+Rt%!sL-G1U?i5DmWs_rLsj?ZZnr1BlF1Z(02S2*Xq>4xr zw&;9NswAf!mp3ebJ5t37L*v5XN#Ts9@d^`(suEs5w59;W&y^t%r&A}_pDfp3EElQl zo~Jd`L#yWe`9z8xpybYew-bw{AR4v+g1Ek4^t?ex?_hBUZ+pNcnQ z_Xx%avp3U#wWlW6iPGu5l_y*5TEoj;?o{RE2Ep5*qPl@#D&@tMxtf*HD3d;{;F) ziju#*?_AF_qhLx7^nweov)L0HxHJV`5QAMpoNdt&ySE*w3h zS?xw0pmDSkRm~ZwY)&ft3vAX66~z-ffWo<|z0dhguvkF4YE@_|+UHmBsyXeJx!Kl+ z`7)<^oe4f8f&XNIV05+oZ>8FWFJDBXcz8QBi{G`AV@|~im~_vkcDfJnb{<(6l(G?d z9L#vxth#LRE5I~{QHmjG89U6T4~n&C*3}_*5f2NQbDiwc5?P)YsjY3{)W>2G?f4^Q zK3LfqOrq8USxq*H1gg~jlGMX-7UW*#AoqXAz)SI_RZH{=IFM1xkXyC0f;|^a>2fu0 z+cg3LEU33sOn0!GaB$0AFlwgrU&{m17grkvvIOm&af}yVo$AgCCzM#VD?Cnon&NO2 zGfqH|3sjXdeew_MYtU zu=yEA72<9Zu*PgmK zWx-3My4}xwCcjbG9ku>9;Y3wdKgI*&{V$_ie9!~XzPC7ch$`AJ=GpttmVYI4o4@f! zOk1mFB-)gfg#-3JANA8Y64BxjzvK)UH8(EPBUP8D9j#)|nv@x6V=hS5ra#KhjoOSK zag93@!@=B~HO3qJ+i0!t7CLMJf#uY!pZ$k_f?={`EJ$aKsC2!LY{Dvdov3-y|-v!oYYUm1; z)<0wH27ILeWi#uK*|-DRR1hr1kC|`em^d?HlJyKYfP(CV7VTKf;^Z4A_<||rJLoD1|(xKn+Kv;ft?vf_ZM??WC*nUET!gO1%&rIk z0P#OPtpC;E`mZ~H{~y3a{~E^F{)_yzs2-t;w2b~eRZn+u1>hfAElxpVp$EvS!VgkN zb`BiDw}D(xm9Fj*IA$sxrAyZ*$a^2;4ef{pe{oLVtg{||sd`}CY_Q$u?9y7XqXGC=6 zvf$#W&VS%L@HJ+U=W4j?B@irU&>LqXMz*aM9j^Y1l098bWE#|=A{ zVaq-Nj`38EX$v9_S8xLKNn+^8rkdXZ2<;jR+Bm8Z*Y2?NOMWQnrdl9v7~B4^0oM?y zZ(33|$}KW$@*cX$VP$BIhg^^;cWQ(_>hvxbrFRrR*9eZ*Z+Zd)r9ol9p!DjeGJ1B3 z+;+i*_m8{WjrE!r&!#_s)F{tzqaxoDzB&0YWWhWK*Gqp>=ZJcdmEH~N<7SZoCrml2 z*^#U)^aH@0Fa72%$>0H}O9`$~YfV7W0_tr_gUg5hs^$0!)^Zk7LgrOXIGDvt|7rI1 z)uR6e4p`1qLBD7QFQ>`8Z>IDdi)pP9C?G$dH=H;<$fq_Z=)fjHZH%o^gLN6_oV0i; zQZiRF3}Q8!+LjzDY~)?K9-dQ-_!;g5EEph8sOczT3J)1HiC2|s&sJGmpV|snX1{nc zPZ&;PAjQ|Mj)d1VVi3NClC*ChlyB!oGP`i(L*k!hqX)NNbSf#ubCAhsLUL`^EM%2p z8YW$a-u#rBcfv%?DQzLWIuaU|zztu^p%{57ftwT>FQ`qB+qv)OCH6!L&3tA{>QGF04yqhE`HM;@myTdj&-a!hp7@y z4HGr=&UKDE*7CeV9k75bUGt@@;mC|kIWN~Y=}h{GPF=Z!b(9a;uE`bH0B z!DX#wE_u}rRUO0q{#%?dEqgIIBOr<~Etub|Gm04jV~%JqKCouLJ`|OxGt?elmFP$L zns|etlWd1f8_`O#i|i%YU*RV0@Bc}llX7G2B|7Lz>;<=-as&J!$LFo$9?-8?&aK%LEbe!4u|8Uv$#ARike3w;d% zlrzStb1bKm({kFl)7dLcO*e(TfQiGh0Y}OceJ`HN%jAxq952^R)AKlbr+X(F=DnTM z<<}`1i)0RJIC^H7rN-~t3*No-h+YzQ8><2eb0OG;Kcni%dLKgXnAv`EpwY%R)wD9( z2vB57moc!7rK-xZ-}L!b7L@XrDf?ODo55vwn-`8T>g2NiQeMCitc&9g*(*yXJp3;qd0ZT?5UHxn%&}CnHi89X=G~WN0y|w`m$S(AG096u z4?7p*rWo0h@x!5Zk~ZK(#nsq(dY*cQD7v=A_2f;Y@?w(Rl)nbQB5qS%NU4gtpKIan zm>J^*9g@Qn4U%=0`eWAd^guGn4BsgzYJhh5xV2#t&KlSE9-Exzh9^EeAB2pIX9xZy^or7A4$EgpFQT209xiuDXL*1BKvZujPSPPa257z~bBFVoy z%a~|VmozlJ5rmhL;Bfwt?`TUU$hxjT7Zx|<*9kbGMjOE5Fh=z-cPjJSR~wQr1{$Vs znfpNnASLnG`cy45hu`g!l`u#G02l9YVh%FecJ*^?(j%Mg3*{0GcZ#$udm~Svq1Sjq zBPV*z0L4hx4<0)+zJTBW@!l_)QM7fCQ}mj&)`8s5Mh_u{a5%|JH7CUTpYVfwJK^@q z5ZQrU6~jO8Y_j=t+CwsAi=fTqr!+spuk}*8VZWP)RL?hSFy7lI=C1@~K-6UnE=Xu} zX2n94`GVxJ_6dS38yOPQvkALaYEZ>kJlP>B=ng)69=Td=-o(%Osyeu~!W*4s8xiAd^6(X2dSO(JY38 z*Z<>#=|y!t`2~IyW7r4YIkHPJ($8p@tTh-#*yEG;w5?RFiqr_JD|RIgH77(2No{u`j8y`Ng^%y@#Tr)(_c4 zzJQG6y~8s;3`{l@&^XE!sCiQ>K41!XM@QW>aL^xBIG1JAigb8F`lyaB`v`aQW$FIi z)%gv0X4_^LOT)pxN|RZv8@yB17XHe-ug2kToaL;#TULcRPz8Iz#Txbmapn_m;0Wn> z!-ld0A)}f9O&`xP(UrovQzXt{CNdxKoC@1m^te6n4(8^Y^}Ia+f>shC)68K9>_z+gghcgm!6j@?Mve=Lsg~)Ys2K(M|{+~YqjEB-lYty0lc{NZALHKPhhwn|XC@e2($@GUAUBysNwHz%%BXj3 zi2^!;eSk{htXgB`NTH7`1*VH2N!ijLHtJLDi~iK{v-Ghx zEZZBwl;hfgkWf%3Q&JO*!#=v@ostoSAf&3&3YA4746vv(c}W-bd?(J1ltpTrGYj)o zc`+NWiqajya^p0OZVUP1Adzz_@5}(QZZnRty03d_3z-T_*N1WYM`>xwywNI+YsC)5 zXI!GB)zxo4`O%3(B^%LA#iDo#Im%aTo!Wz=r$tMNq0)4aFRg}-u4~*)P8;Be6TT8~ z_)7vKB9O^2v0ZYA#mYT`qd1gWJc8iXQ0RFj=&2lbXl+xFf@&)X`rt`oCj`L}1s8Yi zRi!0V7FEY{$bkmQv)R+(`B^}zqBNeV>oe5HHZ zQwMri@}|wYF_Z2R97l3v=L~qzQy$oWyeOO;?Mf$Au+zM?qBNTN%}C^+R<|$+v()&ujDC63}6HB-)3_O4ng5c`(3X;w(YE2T;$_VS&yfy{axTAD+gL ziiN(O;VY7{cDmUR0n-NP$zb~Srm$zdokGaX`h-B&xf>-ym@T=Bt|gJ26KMZNA-EFX{+X^RQAVVGZC8oOuxc@&4L~l1 zaD@JyucQ#vA*o|2TN3Qg;>v?Jcm>#$Q2J`33gul+({6qTzS9`DQ`|tQsQ6v0TBMvk zhP>Q#oG#!&F>YX7P6FGL`M@0yz-cOCb-%717FpMoV z-by*itzS$xR_iudH8k6#%Ph!7OpysAAPh2V=|13siL-$id`tM(@9XwGV!{y`QM6Le zsH`=AUYS)_?dD@+zvzQdt2l#GX4xHF-2P6FZFh>pJliZy)NCUtL5HN4pGS%(?h7&* zXG?^PyFTj16f$T|nnfHFAmf5D-wr%CSP|*e)@Hyw6Qoloy6u02&PmbsTI-L{5CZ)F z9y|pMp{|}Dsen8|tu<(1Rv1*6rjxn- zRX|D%4@L=ahp&DL`25+jZliW>(RVC6!M$sMBp~<%{35e|(kOe-q};fgWc0kBKD9&>u&8omUrnhv zmqRR==lVidJnE$y#I<#(f#HQ!31U$!SVs+`W+tk2Plu@Cb5OiA;O)~JX89vkU@jWx zjuW;pG8`Jl26NqIFWvPI@HAsn6Hd?{D}14s9r4ix`4Ju_6W~~zS2YGCzh3fSK+}rV z`4+D5s$3k0fA)lb`XaxVaNaMW_3k*$E1kGZmMGF2+sTH*1-}zaqGf-Z;s-x6GGM`! zc=hh5ot}y}G%a(34Jl$AW?ZfRpkgymo97AB?%1}WHIfu+7FfNOCi#RwVsOnUv@2n%W)uO5f<%DpwX-uetfw<*DlZVu)40e>jkI#xN5(r^2 zlrz8ze=aRPm^k#4`_2}Kys2K|e5Ft)%rc2tlv&(lJ=$o=Q-LcMKSX(MR>+95e`{|* zxcbWJO2JPz>y#vaN+8wx2$}*9glK0@Lx`r6err`sCC>VsCpE{laXk2RfBO%6pvR!z zqw}8<)c7Z4|Mw>y_kX`g{SR9NMPsLb{;EyN+W)Xb;9f|kp#p&iL>3+bO1`TD^5>I$ zl@pVqNJXN5YfhBzD7=inG&pemsYq+?%EKgP2VX95=XCM2SFI(XxXi-LIUJv-vpi?m zT}_`xu4%UcBK3uZDTk3FD{k~FA*fT$hPkC!3?ZKne~e*7JWMj|0TU>I4Q%}UTm9KV zApY=8Q*i)Uk6C{fRbO(L$Vkp3BAQ90rTJf7tOfV3g&n%h*E6Pf7nC#vCpX`@SIGUn zYfs3UWe84U#qyM0pR*oulB&={VOUc*8*8^lyM0um>dWDyvq6yx0r-gPgXwqEv#y&C zDpaRaalOw7?y9yuIx&~kFz0T`TQByaVF#93qJo_KpbS?=Auom=tFB_TzH!7u%7n?K`CZLz)`eLszH_S5>K!g?YV?PFmgKmF^6C_UuuhO#94Ll! z&5zvfuYt3{5s*iMp?Ye40^kv9kh_35kW!0a}u0E7*b$8bZ?e;duBLg9l z;IqY}SRE(oAvq|sDBOObK0(*7fFC)(U-)uxQ`nmwK;PPI{a&wjAaew^aI}P3k1d(A z&ohJmCN3HU#bg3!juha+vk3+C?(Yiz0@=!q2qw6}j;atOyjFAiJ}HUB;1EiHn~A1( zA{@0(RA=5eBBhIj$WO~>zT69|7l1Rg*+X$H9h{wD%c<1pC##}U4T?|^aliGZ>9|F( zp)Ie;SK+M!ba+bbq^5^J%+U}oxK9;vI$%tHj`6`3v~_JE0yoG$L;<&~18T#Bp&{c% z>ZcHdRmBT=Er(O#f7;_7-GwwlN3P<-$sYn%@bBy=T}4|&;s)u*ze*X``7o1$*IujsDbdy*)*d7dj2rs(U^=@vl}DUwd*$p{<f_X5?L{0uo*{7h*iG#EH+JKc#A%36;|G!i;9cArt~11+!hzf7M)L@(rcUAwW$%f6G0`=8CrfQt>7yt;rfVf_L8?@##Nk}R^|xvn zYK3Nfc4Q4o!p?ZbSbNRkR)2^M`Pm>Dkc3nPJJe^Q2Zu0|Qy2LOj@NQ|4Z0v@v9{`c ziqxY5S0``%h9~WgW2eVS)U|9%gO3! z2>@&3vF4zR#s>*uC8EKM{ln(wpk47)v#OrJx*n=Z-;&vC8)f&zvAo?VCn##MgI);_ zYFhoyA%|6asNyQkrUU^~+En#%haNtHmUglLg0Us0*GoMx%+{5DneV@GA~Cnqtd{pS zN6QEZ3g1oiO&eCB@D;QUNIbB1653xYah_TZT3e&3uO+K{-cF3pv&u&iuJ^bgcoznR zj@ZNInfMnZ1Ou`-H(!i}12uE9H<$POynJ}E?|!`n7%=cKEM-zmN(DLa)yl$8uVFYl zgYwAoL1wk$vIsED=8>fvh1Nm?(io%|HKx8ofj(JG4zVIvBLKU2BJ?tBA;w1F4Q`R7 zfwJ=bi~>-eZu~C@H8<%uFk5@rd2rl~t7Q0I;_V{c1u4S$%P|ei*I3htpmu*Q$hxqR zEKO117Rnn^bFN<@{!w+_%~8>I{v2T>|Hd-@uW=&r-#^CwleYE$@Rl~E=IMr|jQl;- zZPLIgEx87Y;`PhiG94`MZ#Rqi7>l*p8cEeAnw79!yi|hu^UwvAHJ`iEFAAifa-^bA z;V`(^5b1gA-w|e%YTIPp+qSp7yx&MOX=zy(Hu)|t&yt_rMo&D`uUU>W?9UsH*Aw3y zuUvk{FP;FZJ95ZE8zVVzAh-G(xVcNf{8+=HLS9OPBS1I%zkP9__rP%wZf^mIunfX~ zD*FL`tRX^vFN7G-TXL-Z8AAdd>>ri8$lyNUUxP&69OPSeoDVMmd@p=I;Ym9rS-W%b zpMp@4d#FLSq13eXu`-mFz7PKj%haF#EArmde^s^?b`=12hsaRM;hFu*OMUR3pql`X zjw@cFQAtXM3`nDeq$v-Dofr<9k{Wo-?f+u!En^#DkY&-COc*B2%*@O)NgQToW@ct) zW|}ZFPdIUynVFfH=4QX$mCo+fTWQa`k|kUIWm)ZZRdsbWPnu|RpOKfV+h}ZjBy}s> zOnf}6*8IGofD~+_WnG#Em?B_4H?YElMZlaMx3rRdr8Ro%z+7BY+08zLNk|bynG=i^ z6RNzDWuj?ATM$(T`#856IkuD@C_rl7)ga?rOw1{&oYkfzMZufq+Ld=d^3I4=x}1&^ zYv5H^WWR}ZcLX$7|52>q7x&RnHT=z;WmacvX+?mL#R%%8G!)di#pp<5w5A%9eV-$p z_WW|Pq_zjo=$CK8A#geAW_kJ6Vptp^*oPnuD~zgk9fWOOWlVIH8Z@c+D3cJdnV2HK z$b~MKv-4vAcNLUEo6A*y8&wdcGlz z`jF3u3su1>i??Nk^5Es@L0d`>C8brg+rQFd4|_j3vT8uR6;f^?0c#xWK67D&z)EpY zAU>@xry@$oQA^>Kxi!~OULj;I5GVgi0jW=*3wvCrlsZnfAv!fvn%c32er&c>Lz9j?9gjpZPEl(LE+I`D>UdRaE{K%B*n4qsEN>E2%SancZD@LtEy-H5SX zI@$o}EVRMaR&1+x=q3iA*g1I4s>FjlKAY$lnXG(cKh2MOnzs5@ulgo+-j)Y26PP&1ZlxoMJhqRa0D|@Q$e(MeYbI+nNW+i($=6aYdvqwB zN>E;|Rp)%f7~~QXBg2OsX!G~&1}6oy$uB%duBki}7AQIia5F(^MNxa1s~47Aki?0e zFwGV`yIZtm2EsNfGPy!kkP zH{dFc&j|gY1!A3c&eXM}d_Gal(2pR~2ml_+8vx9d&CZ>Ew9(O%G~Zv!fjbWVHWa1@ z%^Qwn%W*7wb9cCo96a8qQR~HOC)gIJNvT097xGjRAZL>}>IO%o7heiK2Vqm(c|w~~ zo{_3c@Qq&y4XoZiC6bol2(W={(WUaRiJt`~_K>y*rjV|Ek?Lb7&FpU$^3>>cxza-1 zOt|t|Bi)8@1$4h*o(Mzn@0BJM?(0GE_x^;cW)kxFeP0=fzl#dR-y=i%2Fssv1@jjF zeog%_UrqWJ49M!SA$|J}0ajs85hD@ks5p&z{)qJ9%P;294? zSuFJGWa3l`K%rf5g+ZwCQH~k#uNae&I4Epr^j5(HyUX94A}NcYzLo}XxHW#q1#8?sz3!)?0T zk}xD%WoFN-25EOqk=6@~e<M%!kn|9N*sMIA85u7`j zi)i>Izsve;9oBypiRlbCz5OxKqcR4rhfYfu+}NpZ%1esnVIztb9fLrl`pN@gbGcPd+Oc#E#< zLiLx%-D)<>YBoTYXjz(2*O|LpBlI@6zchsm90~l?2|h1CEP`UNMB{5ULDjn)0e+VR zepg)rQ7K6-b4d_-P}bU|4E-F=l5cNv`ca|H7-I0q>fU~_1GyyRW#J-A&YLIz&Qe=~2R6d8iky2bSnvz3>!XZeLA8#u1BFh;kM*?H4TH_m z)3Gwh8Q9OvCiJs?Y3Ons_u<^?OAxORtPdAFzZTaJoWVTTsScg5*lD_Ay+6N4NE4!< z3GSF#Zf{52hP)Hn;iN?F!fltyCV{o5YJl5XaUk5xdOA?V_G4?2eI6gw@o~Dl&%jPs zosK1sU~iMv9ZpIW+(fBlh)zh_f)TPI}|lNIE@ zZum%`-HkBa0?8hsS5k0@#1qX+0yJ>FR*%;eUytx5r8XW7U#{CB8BIi}B_*+hqPBz* z)9BTX*A@N|{&6gA4(OI3sSO_(#2VHyVemm}?M4C@R!RzRwoizaHoC}9mdGg6+u*m5ZD(52I#yf(Y#%Qu1U2y%`KbH#ol$c1V1I`Q;X zceHADsEGY#kO5{do+~_=B@vy4o{Qtr9Q1oby&wkN&FvaGWpDerX#3f+T^gt1swg_e zuHlWn<&S53OJ%E_l3c^~OhNWO?{nRg|4)hJ z-xW=X{~lX9IhuXy|7J!G^gop)|8{?#M8U$y<)4J?^X|MZinsPc<@(W=<}mx~=vF^@ zgzI?3y0Be+EKwRdwI^M1FWi1@(M7#C6(%G`EVy4$jEvWh7?T=hexh$XD|?wdyeWsA z#Wt_|har<+imn;ppbB9J7zqtz2hL$%7$_r)a`**%DB~C_3FzN&!N9gn4A+cAPaFI1 z4@apbMq%Tx!@G=SRd`|`V4|1JuhD?<7Z6h8YmAk&Rcf85FWM3gMtv2gBiWa_Gg?zCwn{VyJv*jauNycQ72|HjW(}Vfqw7Oev<&pq#dQc=NvlnW8P6`y3+hlW*8fPqxLj<3z z);vk~&AiYkQegk4aW$|PZ_=vS_d!&|JGPvSJHZT_oo7*~SbSnTTEtrj*LIwy$DJb` zmIq1Ukc^DZ9zDO%-o(9F=y%Xx%kbu`dkxTt%p2Gi>nYx;;Ft=aGPaW$@CsH}F;$A( z@(UkrLCWynQ``%pBp94>u~!W)*nh$+rACn$M5}H3Jzg10R`OO&6}-G_L;mtGQjD9Q z&^wYu`4anjL{Fgf`Q!WY?0E*$3lAHC8xC7w_x-SkLFkCe&CZBR_j1Z1v`<3-7HFs- zcSgM*qsub!3m|jXzz%Qr#v30JEA(?R%pb;ZKA%OiuaH9el$0Cgy#&ee+s#wo(N}qo zKNKlq_-2ER6eh6HRSCTEy=F*uO8f%mdwYFf6TJ$EW8;XXu)nfm`dOYJ=L&^Hy9l1- zESi#V4`IFPdia1(0BE}iBQ67dw#dT7`u5l%p>+B%Yw5~jZDGD8ZU2>Gk#{Gh7liIWrr%dd!s>>iVQxG?kuvDL6b4(}_ z69uyzHNH)-Y+a6O%P8{wQOg7BXebQI&6J-LFGqz|Knrhl#R$lT_NP#<@Xu#viq60B zK63foD76;(3De@gt_|&ld1Y^45!f;$03bXNzb| zZ-0qUGaf*E>F#J?ZoI$n2=EL3-MvnMopBxZh)mm`0?D1FBtr(BI7|@=tgx|xu%k(W z9q8V=8X^J8$87vP^}0b^o;JPMR6%nLB$xOP0AWq_80Swp{{iTL21`A8FQ@Y}3+gjb(v?vLi zdb~&4h>{&$lpp4r7y?(A&nP{nXl0;M!fcivoIGkEu$$bFe!@1#u>&1Hy}?(eHN>0T zzcDB6uoNP}d9r0Hpt$Jos;t*apU!jwYB5MFFQI`OB{B==&rLN*Pscxo463e#p7nbI zIzlYhbj=bM>xeBO>jknWQI-fP+9@bOj@JdPV?}}MMR=MHb8KprI&51A++Vr2U{R9Y z2*gL(Xg*A!E2nPc`;+3GJnnmv(zw68^#umxpuTZf5&b6Ai4}L~ z25smaz<}3q!6+}Eo)cx065&QlEPY)sJSvq?o{a<l`44$GNn;zG z#{rVpffTaKfl$AWa95#vSA2AzER%j!%n8jMcP8r!55IK(u{X`s_;Bi}2*SKK&44>U z+DYRm!j(aswel7XKUU31Op@w8(B!QJN9D=3Fvm>5aiMtO$&QZgc{;SwyWwaWPjg?S z9M5Wi44?0GaK2?A#-fpF(X4T$p$xb683)AwhQ>If?R8w#ooKG!CNZxuDtBPPN$QY6 z{}uplz@#rVHW8@nZhf#^RxyKWGVai5A&ZVAq(iif92H^^$TQc_=`c8O0EZnW!OiXA zKl{Xz0c_SIOq`%Tv4=K+zI`$n`0WtT1!iynGdPy!{lo3Iv{aSUc1&9Dy?V5@$)!;j z0Rj)C%@zYR$UMY0)X>jRYen7bpD5rLL6-#K7lio`PL?u$G3VG60~s7pHhNSW12pY| zfX)55%WE;1vg2w0+QgG?EHlAG))^{yS^n@*+usMjHNi`p2uDq4FjX%~)`u_=^O_!e z9J-atW$D8Qxi)N=IR+PF)EQ}z8zLy5`X6iow~FqRDtJMY%>GEcJb^nAOXX+r zGZL?ZnVRtq_WO3^Dy_nGAY8#DqSFJ?aDo0jhmhh<=vdE>UH)qIMW&&KSc#G%wPW3e zX-2p#z>O1}0tU=-+M`pEY1kCw7Ck$*)nH_bTuV|#ZPEjUu-VeUpQLEf8c;ptnxx*{ z+78u_s@|!VZ5<>iJpTS$UnS~$iBpm1c*Qma;_z^%;8?u?b?J15ssbll38bkc5{ybG zj9L?Ylyx9V_GsoD+H@vuKe@t=mboSkkCusXQPtk+G=oQtS~QnUXV5B#E#m5E_2&|^ zyNT{~Xw8cNhckIn4HQBVE2h(E>T}Yc&vJ`{`f<`tjnROv<`cwkWF@y3U!PE|flS;g z#t?V{%g;C-0W`$q$1ipm2@e+fR|q4Ij20aDev9>+69v0$6wV2>`p!T@3m}Hb*^jh9 zMyb}?A4KhqQY@k(X_`H@ZAj&Y@B;RzO+(suqw}I8tV`63 zJ7~Z0bds>ISbrlD-+-N^(C_%J1qR%Z^3bvGVm>ovCuv;Qd4l;QtT~H)as^_ty4ZcB_CruB8FTN7u=wx&MrXb>)WsQ~IqaQtUCBp0YfM9V z7I1e>h58{K4sUE|Geq1beS08YUQ;l?G|D`P!{k8I%v#5Npf&O1^3E99g4^QD-gk@} zDH=UH-T=nh^yxX8P2pnC5HTlo=OOR2xHh{0Pk8ovuJw@w>y*n~x^yRY;wSHwI|H{b zF~fqc0^Xvb_yZ0%klxh%_Q-X}f`Kf$X|8uI*f%9GLJ=^1sNWF=2fkbz;+c$3s+)SG zU(_L{WdVekCR!JaksuHY?TAh2h~Bu_4>J?8?B4tQ<>TNZ21EOiAx9EaX=Drv-!cIg z=rs0|Ia=OfRyR2Adv15b)mLuMtO^(GPp$2tHba+JTAbm)8zj6$gQwEBuQH>fuG$}g z=zEi{Vf!=z{cLB>wH(ekXoH$G>RL44msKGLbgxe!bhmMX003@+$V!1p42 z(8a-w9~-dBoai%j+LWZt#?D z_=1X7F-V%lDAtO2XDVPE1<==_H{0Z87&4_u?K$Gtc~n5^6OuQnq+M24Oq&ujR~;!A z#gTWe9C3B(>bs#rC>`HX!;TAf#+pN>t)b#s6WKP!nXDGRRv)!!t`(%HN|01 z!?v09TQV`S#b8wsfJuF}sEj-r7;FeYVf~f|VuPh*xA-lmiMyo5%3pf9zUPWD?+9@@ zv(2Do%QsT8yP$m$M`^#ZzB@%!6;;DDO4&` z3s)Fata?D^rDL47VCTiEopR-@0QFq>xF;Zi^G%sDJ=TLwAj;Xa3ksHWztqkb0NVd- z%fYD4xcFP&_FsN*^2sK{H;m6W(I-Cm-CLF8OFXn`zJ9(Pd)7SYg{F1$)Lj5iR|M~V z96;eUC4+xf0Iz@7^TjJR2Oj)5fW#{{58hd-0DdIGH6;7+DaZNDq-MlBawjIAFQDzN zcC8)t*I2!pSIhX};W`bzKJziU>Uof|U1?65QRoiKjbdH3x`H2x2j0zJnOE2LB|4Iy z4lY#e|3uvW7Y5A#o47IlgSGu5i|rc>OpAJfH-T`abJ^8S(Y2g`I<~3Y3nF1(0lcv) z8H3X@VZ8*lPaJ(`Nf=|)G5nPX<|U1ymrX)e$KjgcL>a zqDM`IO6V>$rN3KFcldx`FSAQXFfPL>7mfS+6+sP#zwxFWQ5+!0MgF>un?p`Zjq#+C z%tI<9MvZ!+kt0OJydC#0HYwO!hrbCVbXYQ`XonO)E!`s(Y}zMjlG8>(e;m=S3RyCrOt>I7wArN*Y#$*W$6Q-PuM| z=0%aa>8?H4X3S=oJ45A1nI77lT~}kUro{Z7F<`oz8_gQ5vbXZ9?E$^&eXh~xV&%_f zjuY} zX840cuzvCKNyny{%_W1SPI_7SxGaE3@>b|8bw}aXTgH9V5m!H^$q^;&FASU4)qqkc#qOfV-HMy4T>1nQQPG54DKfx?9aKmLF;B|>c^O&OCi zcEr=eV+_TrQIr#^*deA=f;?(r(JFU@GE^&UEpwjlR4(^@B0hDm*y=ee09bHARo`!fJ?io?|bw&&mD|kSy`wLh-!FA z`;2M>UL3vwbv$&V@Scgd@%tflJlnto4w^Xy0bbfUM9zmu8j&Ecg(!nM{zG8QRXaTW zmR>POBLCsjrX`3|{mW!nH!0Mg1|c-Pz9BnyZO2_wFdH39h06=8buSInIkcd3r)9}b zU1MnOam8t(uI+5xRS)*NhgB}t)mD#J123<2w#yi+)oEl6^wUi#TCh!BHs1Jg)ieR^ z+>_3G=&G|R*$t{Gcgdc(kxRKN)wCWhogxX-%-Jw*>I*a%; z!(54;W&6#Sg)HcSR?E!CvQshRiVc1Dn50wo#{!Dd%i-_orCG*wlK+R(=i0CT?u zsD?WpgUGn)$lmd}2VM<03~uFE1ha;yDyQGGMNHasV46%K@~$c3YNsQkl4x{6ynUa- z5NhT4oGyc)qyDV0fDJ29Sx*Zvk3m~0&o0cznTcpEK`qg@l#h6;YGBlH^Ns7KK&^b( zbECncTD7L>zLNBc5y8t=rVChuv{nXBl8sH3CPl#1QJMn)P~PK8g8zNn~b6SY_IvtGAWA8kX4gv`vs zgz48Fpp`kzvIm7;h(XbA@tGOdyP{__)4;pkABukvyHrW_c+h<9WYDV4aZ8zw0iM9 zZtO9=Lovpp@S~!^>GvccfYlS|1E<~_Va;+IWMybnlxk2%#+=e_5pY>hVD#z8%KR}dSl#8H;%sR9N9?Y=&1jG=bh2v za?}A1p~jKbFb7t0Yuh7noU#ogyFKKl==Eig6XSkj!nWfSXHCx@Pp!S~2}dh}7`>PQ zP0e!@wv4eFr)eG4-YrIkfJRd* zqnPms>bEfhMrw~z*7g;*Z3@^uisrZmj(y3@ncfI5vg*({x8F;6Mi>m|oGVu2_P`I_ zEf6emlBmZr7tVI>2|`z8Vq5M-IhunPP}t7;Q(KIC*Kjqr^ciBId(5@ae4!7uJQrA( zEzXDD+a@9V3!uYvR;y!PGv3vkGF4o+_?zX3M-^yDW6E?(o&Sg6(0OTeP0h zW^Z67W-tx=2WiHR%nEqw>OqZTr9VAJYoik*=4G#z4h;g|Y~ zmEH#N8XcZE_%S@^(xK>~X)rlLWL+1zHJ@NuV)`b{n4X}}hMcE4!ng==R?>G29!bTzuS{v1H@Pi9=&@f6Yx& zwk}=i4HKh3@zdTyXMD!(zqYK2+~N89-=AomcU^{d9$f=ddBXUa6nylJKP2z?1;a|Z z#!XC09lq+Ao?V(`9Ud9M(7JQJU-T+xf$gw`+`_t3D9qsl*`jWZ4~kR{cky6#xhVsZ zFH8UxBqwcZs4ge%lxY^ud;_HhQ!6G|8KE@f*L;|ppqT@X1(J$V61XzG=+jDC2fRib z<)~mbOu3ZGb!V+5f++&m|- z@qe`zC>u|PMjN>EMLykWmf>yv0Qu;#yOCkp(t+IGw9Kup0j*ap@-2}+Qk+wgwv?k= zt6am7#UoK<6;8sBDZ|21YUC(7xk`uLLNOwp_jOT3I8=h{l3(01Xhi5zmT-LO4Rnl* zQnQYh>)ohE7D_#wdBlVat72TvI4+yK8QI`P5v9rA3>-T^XMtJ&y9oE_+S?7ZS zdl(J{V1^-DTE9v=5wDejHI|`DC<^HiE3&a2+EbqDr#QROU({=TByrt9{esi%BGYvS zXLEw`XKra4hs5$bMUHRub6e5+S&zW;wI0+&S0QN515kR&bnN*>4->*149A>Q(;T(^ zQ+q4_&Qi(>SuVYn+ghWr9-Vly@UxOeXYu=p9}0}-N_RivJ#SPUy5Li%aA$V>dMg|X zc5j2Ab|K-HVqRk27=UNko8<-94DMTXpz}U``Er%#%|o-)nq-21WqIk>s9pY!v%4(R zVy)2n!#$QRy|dZ!^Vvq8brw9;-+!)@2ExPbX*HIW^a`CPMy}Ry*%V|dSj?!I2rNWd zW3XSvuh_S^#&O!;tc`=_i#W@}ez#pal^sfoD7bv*9C8wKZUBNrWEZ5c9nbM!gpy}yVKiD*Xes0YRoW>mg!2U7BV-#xieU801z*t!att738$eDn2cl#2O8ilQEO&%dx;ZuvxpLtS?2ylk z*wZjPmw$e+WdqMDmR-kKV4gotU6>P_yEThQ^yMWeK~v?lEfToMSxfEgdl8*W-ioWF z*ktEH*u2E%_jJ?A_Lq?&%#p6gpUhF~n9$w)(YC`L?~c4WuYnf( zEL?@>p1vj?vk8A`gtW?ObX_O?dg9eD#cR=BLTa%BE% zIhl`sK{{)e*)KC{^xyVB)~9V>ets?0G2%FZ+ox#jUSdU;^cYEJ+Nb>fYFAZVF5J(( zslkQL3YgXcA{LI~cKo|^I~H?BqtM+-J^N1~mPu6haa z9HY_h>fm<1}pILDL7gE(xZeS?}ghSzNRS z!;h4FoRG)iS^@`#l&B0093DSHHQ`FFO>}*EO7VKf*Mxv9IeoP>j1CjH=2A!V?_!1bTqnA6BIL-hzXFBnX+&6SY5MZk5du;T zS`^c&1+Q1&lp6>Ck&o!@148U$A8n5}Hvr1L=mf#t*1PsQl#Nb#17L8-ifI4&$xpEI z8%{dSQI)#Pl=#*qJ+?sP`12g&z}^_|Q--#Xjk}GE=Zih_CXe<|VYeK9xx~Xd-o&59 z_u;|TTg2{XTw(WoiBPq-u^4}r+J1I*?Ih-*S5v+I{j1e48@(lc=+nBp&@|QPewYM9e=XQ6n>|N_ZoEJ9-d3vkJy54)iD&u|*Ihp_Cy<+bFez^blT=c(p;YOuZ>)9U&SylowMU-YOD829U1i7-!iafE3 zxry?AC_fcNc<#pS&|EY;7AqDLefyX<`@Z3Kix3VtpCvz#*3OGgzno2^ab{;>{&{{q zW&cvqtB$A~UZWmp0$Rk~%YuTO`QsV)P_eTKZZaP)`_9W4eq&Y;&=oI{Lx zku6RS?>OV!M!K=wwk&B#x`k*zh)kr$O3}u-nE2r>iPDxfW_9+F^Wz=pNp`T_)twc`JhjMI39AoiOUU$3I zW)l$B&WIseX*P4|oZ_b+FokkhBwk#U1-{ka4zQ(*&aHIJOpd-zRI-|C9l^O!@N9U43A$$jC{i_3fl5l!i*7O4bXMDt?RWej8?ZsvT$3fB}V+{CQQrcP$73=$j2K(gnAJGDg-E z=7Bi;+S?d^Hc4C+{ZLN+K;PXDsw3cuiH76}cCA!G`h>M}YD?V1j=1T+n!CxJe^0k2 zF>y((9S9K{5R&_0`iMAZN1LNWY{(N_7vR9hUhBULS3m#zY8SJ1Ff%j~HnaXzt^QH-DiW61N+`UO&O1wKY&tWE0vT-J z`s7h!vv&zG*yL8}D2JykiQYK|CbmUO%*H&kTQ_plBz+)C0+ynrO;Jyxp#loMAhkaP z^uOtU<4(3*s{a}Ky3uEiqh2y-#CYkl$$Po+I?;AH{^;X%&+3cUelYl5$jh_`l3v)& zZY>5GW4B+7e&GE|KM$?=3YK1u`n=sv|$w8bU z(XpMFXM!?26jEQOS4JkK(x~VvP4S)KX~$eVL26VM13W7ic482M2!|@8$=;x~kd~>Y z9`+-$3>BgbLP?6181^0ayA>QAgRAg8fT@A5$b2L*NsMBkJyUd6)Id^Zam zX7hJDZu)AO>=Fz5sg*+u-TZ_QII_;fzF_iE%7zMGjh5Wjpb=o;xjDeL*t6=^z+EA) zw>@24Kq;r;;0In`@xL%i%Nr3OwUOu~13?p^Wyt9$#S(5=t2Bh;<-bi*!)4qGvHzmg z!`F_jfr$}Y3Sfism_FzSKrta9#pi&o+M+uNEzX8lh{-bS^+zDdtH#?Rlm$w-iV0w0 z(u-CQQ*Rq#AlVc6Yar1XsP$4akUHw|+mN=ZGLm#)I6KftleoAY+p;a5o z1zR;79DK+=TPHr*cAN#YK1)C2+gp$z=qQix%@kz9A-H!7!&~M+fV$`S;w?quZL!k? zoUVZer1ToPz;iE|$dgF8;u^k(KjVY6;`kB8O*}o2>^ogIjIoCo(-a z2&%zzP3+|H0%?{og=S6nfmyZDS2==d5mj!Ec1O3)k*a76U!dJ()px^ktnQXcIs}Ia z5#5+-3?5Kg_`tt{d-Stuq37}5yK(}-+YB#kNs*ePPkYEs9RQ5$pNKOGfH~mV>46P$ z`a)VItWycA(3~F-0PNPut^;c1iGpQLlNc9`XFm}IIizV zYK?Iq82p$+2_wWb`%ylv1{;GoeBEZAkzi{*oNvCjPpIfu*mOJa?zwMblgRui3;rw? zArtPgMsliWuyoAdMlCVj9_XrSP}?W?2C>g1G>!PTv0gE4pwRFeeyiv*Hnt)j;N&gL z-cer&#CnM*-^as4EJ>yNsAdL_r|0G!#N{1K=NbFRIry@iBQuEJKIn#ud!ywmIxHw( zpT8GiRGBkAMKdVWkz1x>(qKYC&0KbnXPQv2dBB4nZqzUfaQC0;*`;HZ&WoF1-?JV8 zDRKNSZT>chm_k+~(ECI$^$7oyPX7Da3*f)+=l@)L`8$ds`RA6{KXM7cp&L)_V{%*t zwHjreI(7=zR#vFQeio#tFwq*Q)vc4RmWIis9tFT-?f#llAw@*S_q^-DH{z+M?N26G zZ#^DsHgWE}9p^ML{&;(ThUuoI2}bB;g~O@}VTi`Yl3Y_9uSBrkjTUf0ZAI^MM0gBv z?Vh4$uL!qG(BnIICrz-q-U()iu>O6aRy&#i{>Woeq+I6oySLc-A^@)$Ky=TME; z5y1d6wVF)mkzoe%t$64uX6F}qG}|{=9#a(vpk;=FNnP3z&N#eLMLf`Go*2_+HA*Dv zti+#buh?QbuGgWZ<4lBN#k;Iz3Y|+6L+a-N5!`_cKf0nyPZ?mqtJ-g-qFt42X_B%~ z7(6ggf?3y_f2b~SNNbd&>uhRh$sA=Mi7ELgUd_+#&_uEi^61TF;el>$!xigcBvP-- zq{6)re8r4ztD@xqBahV@mwS#ZfRCKk>>x6f6rZG0BsJqgrymObYbtDUeYL#Yf zm5&a9`(AcasKNH*k2h?rQ>-ks*4>vC#Xat&Ie15}{AO!dxmAhHFRK_u%8#|dh>`OA z3x=FfPF7jHnELXWYVHb|ez=Z4R(c-0^-&80rt_rFVpPn7j{e3hkO@%N2t>$cUp_7xEM z>mUkR3TgpF1px&4paKv(zk=)8nhK*~z9DA`{hgTj_|R$7r?VKQ4NNw0qH95u1P6x$ zzJs+k<}PoaS14UHdS+RMq<)s{5)8R(mWZ!okPIxa#>3B&LSyDbFt3_|KbJV+1bZjS zOBg6t@3j(g<>7madSZS%nPMw%x%q7}@!;W3U`lacol(4*;@mRW6OmuxcA2G4_-Pr5 zcC0U+IW25{9rmUU_n5B9#&Q5Va!tTt)DMikmNvnDofbsHa5b9Z(u zKRleJ zOTpO;OU4Ygk*$^6$Ui%p%EdI4EIz(1!IdvG6ysbuL(nmEaPo(&7-RDn6XtX}Qy8kRqk|X>^kP%}=*d*Bd9R;w9 zQc4h@fdM8Mx5S}VTZdaiFRDrKoQ46k>TS4-l6}Lt=(|QG*|V0x8<|rnpvwsj>}w2c z3w$xcxY+Kzo6UiYxTz&S{x(;7TRBi&wDA^KoVb{5 zGB=BmSWG#tKm>`GRIHlB%S`NL9=|Uhw-p_(FaWPU?$ZivS-^e7KG`k(XF?Z)vX{u+ z3lO7zA$5Gk+DkoO)fg>k(uBhixTX_4pY+Z*l&q>TQ8JAw>S z-)~90gvWz%2Kq~x$uH3ik+rA>A$n7>N_|(YIvC|Gnj`ko?JQCTj-%Me2ZNe%W<$#& zorw!dRZOij;lCnQOG!umWUy!82Fhb1$x+g-kG#Zf3W(sz0QjKp|3K_r!BsrN78@{P zy$c9FQSB$_6XKIp7oxZR){s4J7or*)Np@75_fA?)`Otf09H0ZLrS^3A@4Y*@#4j{I zeXpag9M+zzvnn;h_-N>}MOt9e*FDOGSuk1pvAOFf!YhPVsl&*|@8ECsOTjS{MJ>_u zFRG?5aKH`u=`oQ1j~;{n#b5is=cxR>o%E|5yZlWkmTEGa^-E5!q#8n!$Y=tkut*3_ zRwr2rN|$F-BO9KAC1ciO`U)KmO|<2YowEh)T{5_P?JMA64tOUye46GT+Vx7{trU;9 ze`2uN@N(F^e82E|Tz@^7?DF|Q?N;|R7!=2;=!3@5AJ@an!%f~3^=18uN61ZOJ0)Ibp$}#kLL>w|xuVc}*ePS05&xF%AU`qi->@+&`x&`G>wvz0w1t&guPKbeqni!|O zql|3_$v~fh=C{8&OBt1&isBs5stQpoO1zcrBs?sg?zFCK3O0owafuNtp+Qwhk%T=& zyo)C<)LkHf!!ZTy0Q07;BalNy`G#|$K=suCQEibl3U*okO#IzkH2jrxUCV#?__vw= zyqG_yqa~hNoD+S>^niX(^Rvr$v-mwa8~pTOPSw^h^4ilR)KY##IMJ0@jL<1jt7>%p!j zgn0xfT$_e|RCV{P=9)uf+A_0^hYAOLl&PN)H{Php^}%-$1#2|7-Z5Zin}uh!Vz&Dm zm?N)I5Ut?bX|2cyO-5f{qcUs|I5hQ+?sW3UpV}66yaQr~ZXSEz>YNp5uG6A5fzsc# zVbS&`1`5B?gR+?jXKJ*sS_Pjx05=$zn!1M z*GB*96t}jq?;5^CT>PzrJH^ zT{roLza)*j4ztXcrI#TZ?GUX8`?c7v}rv zpLw!lL)maf1x+uKSCpG*B4KwHsd-S(uxe1xs0>@!_A;iQxE7Q? zllEE+(TrJ-QH6!DWv3{U>ri#lInpUr7WM?WvrnE}9L#~G2%^>>H5g*C$;CJh9Amkx z4*StNG8Woot(uN(6CGy!{u#lG+xJ+{9v91vQG!!AT~xnUheu-4-uF0QbT2O2g9 z{m9u#`=v+=)YC;JSHx3=sms+xixi9l)xw7-ME&KpJ+39|e85maXUVByO{~4o^Mgw4 z<-jd7@w_TD)piEPmx{#X?m0#iqdGBn6Bi3W-&^7a(wNGct&+Da?tOIeO{%NXY1T2wMv@+m?lZ6$IEo?zj0DJD>%;3nRH!pE&euXEjpX`i{1w)qi zRkwuU7>ca1NqR>NdSQwrn`oXC-ci+IE?0)5M#?*bLXXVQ*wKsMR? zjbQ5&tNwDu&n?p*1n9DUu=G0M_Nnj1GO}#wLt@|T+1mx zSfzELgs)+x_d&G<2dcn()#tIZ@9bRET@Ik;p-u?pTX z3W$%*Ow60hX5V3(7@~qL)SO9D?;WYJLGRWY^{bZ-s4v=zAH!VK3x7JUX%bk<0CZpE z)^;#+^<_GSKJ(+=oC|UlxCw`(!lZ4|%@DpCJ3{I}aw{bY&Y0No?;}6(>5{anpKz8O zmdK?dYO#j?NTXOwYB)y{ z&w^W3MEqf%xQZK*6CJffZ*i|;nS84(pqH364t8OiOwfgPLNT|@DR@Em*|%q7>V8+V z1o}7c=-|v*gq<+^ZEiHcnIN+4`neGMI4x{nloio~Dfc@uqRPtW8sVq$6B;gpW0tgW zJzlAd{QCvB>fO~Bc;34$cURDhZN_8_w39>vWB`)osVQ19F=_qq6owTK&sXx9J{ArG ztW0J&tfC(JqMl!p0bSmGDxVQ#R%k&i*l83JYD`aE85fZ;hMJ5O?=tAY^FEUN*dm9j zhV?IklMtgJ+hF4Dx~5&8ZQN@HuFgH4A{k*+LJOgOb9$G-)x6u(Juj-&pD^oT!egl#Yl(2ldJ96;)G>7NJq;ZF?4`Y#yl|Gm7z{C5miDF4@( zh&O}74hfc(c1rdKiunvE2~8+ftS?cCIwC82;A-cc*=|KO%@zD({JAo7m2^X+g1mUw#Wm(B9v}Uz_lA|4ZB$#w3_XJ15ChH z^!6k*j*IKkV#mE}O8CKEn0dpz__>TL%e4ohTr#5B%XZ4ew6OwlLnJpp9H`)4?~vRZ zmPjL_dZ%Fh`o=+BD~el=#iX#KNwWVLWw-koWry_lC_7R(RaZty=5gRzRA|ZU`#0~Q z(ivl<0jk1I-ngjwp#fU#X55Ny2U#E|gv*p|O*k1aUhLW+Tj+05cDC)L0G^dObu$Rs z+f^+VjBI3`KdIF|y^E92FI~?sJ~#J&vPUhLeS3~c!ltkpWfbC=T8b+nfZq^}VJAPz z;RIjtZ(|na`Sz~IB=1_5S1z-2`;gUlPA{yxYn%rhHICyXT{A8Gh2&41UW&5s?Q3pF zw8-p~#VW=sGu|;{h`vuGbo>y_6~((cf?1kwULi-}ORs*yOlEb3x8M#j@-I{{MW#8t z`c|l72Ngk)D@|nV4V`j(!@o77m7~ztzm_owq84HAm*HsstQ)vCLjSj_ za`4^m_?vrJ_g|{&-y4#`|KElrWM*vqX(6^YF!~pYrK+KVtb+0(Z7sN?N(?QkLATNn z1RCm+uS-Revt%15q<-wggwt!vgiMZ{Xl`Kx?{(7V)6I96yPzbu+SvNCwmF^h5y0o< z^a~Rs;>MSm2A{*^7q5qp$>szf`P=hlb=Nlzf17;M!5|DShTky%hqJGWs(Vke4jSB@ z;O-uRySuyV!8y3QyA#~q-QC?aKyY`0Lq6{9?)6RIHFHvVP03M zV+=5&3w@bKF*S^3#O)`WfR<&F9FNDMkJ#^!cb9{^lxiV92%`MBR%rMrZthK6z#Df} z3N9k3;Xg+By(16%897)9qQ9absV$HGw!vb-B6w4L8O`!Zy{#__r+H%0QHP0clGshA zy5P`i(jeGeq5LR(k(HxAlsz#{(f%9PS(-y4ks+OB)PO;71^WQBNF$s>5+eyoT9t-I zaQ5@7fE!$_SmV1}u>6#ILCyu0IcK)b(%27Ls(osEP1xWvhTU5DO2-S| z33TF;?POMZua;r8m{c?9zGrmTKzRScz@=G@ zua#Px1hiMDW}PmJu?0DLT*i)-tBiehqEIzkLHJpbdyGK@XRYSkzq|e(f6o4KaZcq{ zlxCB?`bg90`v6ep)IX0w72;vIPsKz;LJfT`i%M_5Y`;+wMUMSe#X5}c%n^?oM@DHM zHO&j%`ea3@4-uQ^D9Iiv0;MIAOxgHjBE;A+!T=kmf3x^K8XFSNMQ2DwJ3&540gMiA z!9+WRDxU}vRtB4KscTkmIdB*WkpdKX5KcRyoeelxLCt(n6Z z;|W(O9Ht9>E?h6KeQxH}9*0nb#e!Nyhh)^7;}$Fd>H`RsS__+nMvt*-e!!`n|l06M@K5ZdW>zZpC-pkPCl_L6f5J-9GFAyU6V1|9XI zfMVtrrsQam4f1LFg~Hkd14tH5EUbxv&xwHFk=c1zYuRvxee;!pwgml3b_PYC~#IbGKOQ?0bek5NkvdF`tEUeOt;V{O;QjoZS8`@fD(i&J%O42N9|epTwPf4jbDF zmTVd6H1bC?U*XYwk7?JbM01bva7}t9KLb~gcXID1T+!gnLCWzp-O1b_tK_&L1K~i3 zDj&BmMELck`N9xZCs+ys>73E1&f2%%B$TnR1vyOeL%$gVob6cXZN>&CTUxL&*@apV zf@kdV9Mkru^j&!peCE9k(ijTy^_Rg$tl-;=DaDD#4rxH7m6#u5J&)K2s-c|Cj-c-$ zuRc{i*!f}^q|{#G7a)nyKVrQQHYVV^vvw;F3-=50a_aBEg3=#qIBA$JJeMgSmQ)N_OPfJHfGggq)z%*@k)66!gG{KN`*@zHL3v9~Llc|84c}YrPzi;7+ z5j#$?U-C*Q6w(Y#~e)9s*hr3c@bJeLZ4?@YclAQ*f zxJav9Bu@sG$K;b}u-QhKx0YgB%ASaguYNea2XpZjgV9)?_RR+s)Yl;Tusc_M zX%Ld5m1Mzieqc!-VQq&UyA24PqJ!OlvcRZXZ}FqT)!4JT>o=gpPmN!>5*|0+p-t%8 zd&!%6t2@x7b)>^6vTj>p$G-8fWV@?(j7gB?>)-voOdGsDI#N=oC_=m-RhEx|x|Nz@ zT3RqPar?9A?5?A-@N!^TuM53#kdXAVCdJbn%d!q#rLyW}`^DI8P)Nvyzt7CV zm_q<1r5R&@2Kp{FzA2+W2LKK}A6t?)9{m>QW{z)3KGs`c5H(oYXv3I z1J1qwR#@J}wV9?3Zn22K5w2^xQpZ634=a>qJGYj0eaFDda7I_#vs=OjvbB58q2QyL z^}Fg|bjZfWM(p_x3+u}2rLSuZ-#T?HZ7RRRHL?dN6(F?CCjd_iZ+y&)7v7rv4H^I* zhMk8Oq527z-x~5nxhq}Z(hCpp`F;lXmj+-%E|e(ZXK+w#Wm@B}#50p^Z6di5B5jxsEh2VdTV1P@l6$Z8l^H&xr0|h1kOqost`lZTPZ9 zq7tO|G_hBi$zu>y;CY?Bhjekq9$F>8pQi-Wl_}(u!vqG})GN|S?*D0iG8ZE=f|r0U zz6(?3pDR9VeRDH<*UM{o1RjQn#v~mpBhpG%mOY@X-5r{1&Xyj+d<#8_N{Pbgh+r30 z;jI~b+Jd|fkQ>Fw=gR zEbfj>JAPdR3IdT)mF^wpqI<*qM^&`Tok}n|B&TzpLLsY z_`_lP{rzyd8?+@Hk@e1?1GUptN&=Nh+TtUr!5c_h9`#OQnX(Qrm2YFzS)|Ula1{r8 z!rfZvhHjr@*}#&*l;7^3Ss1t-+g#jxUQBIx8jx|RWlY0{`t!R?)uv||cvy;7k_q`- zBOjIHBEn`l!cPOwGUn@e{Eiw-v^FF8DZgu?LLFwnQ`wc7uL4U|^inR$YIXAu9A}xL z*3z~$E$}G&br&sQeo%7SkQuSU)l;(+DOIC#DY18)G)B%}RkSsplbEVjxaX6fM^;Sv|`(o8Kn0767({`hFnl+!9^6IamL!6=%SVgI$pL@k}Lzbc{6XEkfnO6N$ z6z*kRWi{nT&MBf?qfcguth9_T(%eroiSPtgqt~k3%gmi?6lBGKQq45JM=T+MVXl_^ zALvfBh7vgs>LQ$U7!}bbiH5FfV%RjCs@GZ3Y>AE?G4VaW66BYd{0n*pB&t(;Dt~*Z zb_j|I!!}XSNMf!lQjVv0d><7oTWJcQSj^@w+O(xmI++`!0cPj)tQwbf{s3?L`sxXp zzLM@5!@!pyHePS>9U}jj4mf(=aaD0;tg8{^+8co1yQo2&vc4XuX!d)9jBz4(eRy-j z57Q3EtjFuUESm-cV;{M-rincp;@!JS$*czi6>%mXnrM}|aN{&;!zNC04yZl(U@!DQQ%3#DUVhWJ zs2(^Lo|#MIAya>AEsM>briIayt%-Ed`LOsG24#yprU>;4cFqtWZGiaD=U(iQb*6k$ z<(Nh~$8DE2r-+BzP&VGin0EDRCbLRv3~>Bcslw#*te%A53uGa$W^!k&E&$ZCy;}+m z-XOyb*(qoe)Z2qKg)SRMh24AQo)CWI@zh{Bk6FN47%_pfxc@e&%aaXk=Y3zDXuv1Bz zW}>S@qsbLje!TEC=1}Q)tV~Gg)_b5nr!3hCCWnb*O`)u8LDCu(XY~F9t@BA_1u+FK zGjQm_IkOPn1z)V8Ae|ig{Dvt7GffyUU=L=7abwvbKQ55ZyE1}#CTno%r#Gt}@J-We^Jmom2!Y8~>GCtV z*X$*fy4B%p>IMe_psKM3rK*`SJk+irNhXy0%%fR?uV1rzjPY3pv(3C=fBY%blmrs4 z|G~Cr{u}E0E8G6hiSfIO{bu?Ii;dW zK`jS%t!Ob6b&K`6_!X}hM2@r+%9UIcZoT^U<8qdsEE&KPf0&wPMdC2I8nJ~aX82(%cUri$!1JVZH>SSIdw_KaPJuwfR>TC3A+C1^qP zc`~at>)*Cl_&mWloiM>Fi8BjYGfIFHx{;L9%^uEG_%U#q#8EwmE`N?pY)L-(chLUh zDS4{C6ABAUEO>)hrx9nUyomCZVUe=438I=XDSl*YWOSOmakM1LF8_0geImCFEhpao z)Lzo$7$3?qk<%LA%IRT@n#iMM0cA6F4bW>xXyNa7N2RAN3P&BSsa+7Se-_40q@0z5 zk64obw+!{ySYrNX(%8aVtRpZTR>6x}-*HsmN70dorDKZH@vH`Iv>E zA|X{#;1w%vg0pzLQnMC+cch*GD!c-U*MkuD^jVcW0o0v=+{P>I$s>&Z- zXu1ddwrkm=|2NF5p9jXd?%YG}cUwb3kGDP2l$?K5(v z3c`X&OB|u(lC%%c;j#+*)qqwh7gi)wp-$H@U=;nF-<2DU3l4R$N^VC)#+lUVW$Zx( z>z4o?CUsj60N8zzu|S)KH6#@8n2fJ>({}S4FsDL7PH#BEKN=Xokx*n1y?v~ap|W4y zeR;z_ki-5t%iJ<3P5moVj6_0FV5IdoshwcD#`I7T|c=W3Z zH>$C@DG-rsA^P{ois^$w1>HoqLH<N_jDCbH#2;7=O|TbP z>7(gP``c-|zmD|HEbPIN7!{?6m$^`h!wF{ z8a)YKT_(V}+3Sko@p=z&7My5y;HaE$%+<`?RX#g%)%f0flH=j5^JVuVMSi*hHbaHzSZ zQwVLNu&$)tX7=KlmjZ(YL#Q|6Mwt`wCCP5Z;B*`3&sZ(3gAIi)l}yXXl3c%@xrnrl zw?m8cB}a$Fpwc|;>N8!AMgnEBZZ{Ik&kDua+e3)Si}Z!4;=ZC}nfP0L)#Bs{ee@mX zK^|<|Di+P>o%XPd!{4i8(7Vn^6xJ%5{z`PTV6n2ptn-ZOlew);{rKKA;>et*YFgH~ zL_}~+xqU*&Nps_J#~3we1X#;_!+k7kMc0R`4=9gWBTZ}@j97(S++AMEW$Zfn4*g`@$K+=ytyKSI_kS1ci z8AXWl#048|5k^lLMcL!J>r&+dDQ6(azk;8lKs%)wwyV^5HfPYOMH1oEn|})S-9lO9 z(k>L=M+2>Iu~AK=6&kHD5r@6|(es)L#H*T=@$q}e^A^??qvW7SeY6u*u7kLwbG6gt zhGh6z#6trPU*0O+J@@7HPxDu~-A}pDACc(sx5@Kwm(>3)692VKAY^OfYyvd;ead#ejfy-yMMO-n7&;p3PmrM6P8a=0w@jaDVqER@ zLubVqZiuVgU$}d}d|c#I!huzZ+GJ>YvVRCxZT5Xr)D)i&oMAN(IobM>JY5~@&A^JMfiQVDI)LM92 zySQz!PfJhFbTD^}ri{2lCXqo*bQ6h;$dM3N+>w}uwgHGt{Lo7wZUq2Czu-PZT}Wx+<@jB{80`KDe$ zX393gh2kFmpr{=|zAHb)f_3*^*{2ENpL~5s?`DxL<%E?TAs4iu^uj^>%C8La0?i6& zOv}Tc<#sUt$nAD?#G9KRFG}y<*z&&;ihpaT{BJMnzqUyKV{=rgEF*{eF-?u&7swhE zpL{jz8@M1O1ySCY8zK`2Lr1BoN$L+I_^P^Nu^ip8St9bL#G`WJ2PWo?X6Ot;L`@_g zA8>x{dN4V0yMmeWd+L*Cj|DWUI<YK>nop69(d$S3Q=a+Z_Q9x-Gd5U_~+iTeIxgsqARmVFc8UV&;kh)84-#ae=ZGG!n zY_DX2IShWUOVajsk_2G$o&!=ljk(&)te+m;GpCUEq~4@b(L%;+X|0VB?^gX)=`#cA z#;*&{S7!3sk0p9q9+DZXbvCF+k{YV3m(uC`-`Ydhj7;~MXEM*N?ooEZiOx+cCQ)bRc zaZRecEivVV<(?af=t2J@W|a7Haoay2?CIa)f&V;a1PvVio7Va-4RxiWj2tKvQYLYo zubwN@^#usS*I-;E6m)i?JR}ABtl&n!_>E-8c2f6WdTv*rk9?SA?em56i44<6S|mEu%UyJZdUI4+el!tI~E z2f(XO`c~zwM=<2$Basg5h zifu*t2qW=C{&|eE7KsETX*@;ZE9u~3RI!1)y1h6P&iU>IOei|XH9&}&w{mg&FpgbG zc8zIA`J!%@?SuB~#TMUhkQz{~5Hy=Z`_KEd^d<_UMlhDNWoJ+HA%Kd*W9xv)OAV{K zl{q`z{;wVv7O9Ih`3AE6owODjKQMiLb#J{We%u*1pE^RItRq5<{UYRUG8X%)6}6T)$vo27+zfXm7>kHeR}pT{QiW)gaV3#2Lj)Hrk+ceA^AabC32_ z@FCBZ8c%qyHKF+&WHvb@`gYw!C-26LVspTeFORsm(`TNfnBI##n^}_ZAW-df6d1FY zE2dWmV|ZEGqkH|klQt6EVj-aD4u{zhn+8()sZNGk$=-{-3_%tN=??7_ujsMAC*)vE&B?afAsSyu5rZQXmE zk3sF1gU2=p=&m?kv~f?c1YD3o=K0bUqjJh%bBKWky=BRXWCpK00bX&t2!!9j{l0^k z5&*|I>2Lfx3U)s)K-l;&>)??)JE2|k4|CHWt@Oum;v4D>e}UmN)yNPN;IFV>0nJ<- z`#3ulc0I3@kNP^wJ%R4$I1lT2xI0q-ohdN;|!Hu?s8}#0S9lEkQ?ZAT#BcnrI%Z78-6i!=k8bh zIW{Zm*B47HZX11IvReEZ9Iz#F`q-jFa0z|xbx)2^m*g5_6!WL$ZCSXnp5Km)C-QJL zac)<1rbyY{=Q-QBoxp+8Kn97EH%4tEyPNs&_&t<|SkgH(g*M*bkl*KaE=RgN^^7t) zdYsCf0_reTDzR_u2jeY5w^|BGMeLX01vLj0rDupIM~>%gN4%xa4?Z*3RM>W{1et(+SGNyoD;}u7Sej$``JX1qr z*kaJj9)pmc0qPYnM1W^Tn>oYkQFVq_qd&4=hjx*9MK^$IB znYz^|aiF{-XaY=od%afq+JgH9cA?2BZ-c~7(t!o7y5RpdjHLgp z8GkA6ok}`VpaN)}Mh9vds^oWwcZEdm%KkNx5M-lQxy|7zY$UXp-ji}e-X2>C~$y)NvSu-@T5_-VJk@cfo|oS^;ll^+PAM_e3( zss(Qx+O{zR%2y*2gXyAF(z46*T}*--d_n3yC6(B-Y>Mq&^2p9X4Nj0jr{7}?GW0N_ zvG+WfXZl1iu*Y9bqN8LQ(uIMl@(8~oe$y&W3oi{PD=$0&<4u`i?j5u6?5h|Xj$lJ# z;AAg|Wf<@Gg%QwnEv$b4L#ZQxl(}GC;kn(cU#aeIFjxm^Rz+aFl?F_f-9ox}EF=k) zV=hAVZetC42qA8hWalG%SvlaEh)~z93>{)AR1Kzx-x1E@Q~Zgq9}H~?Bx{F2&f%C4 zKzRS;vr(z&%Pl`XZN|UhfWLzN|6H8=Ck{}tG5mwlHZlI66NK$NBN~rxn<)()t_j>% z-l41`*Pb+2fzv?n(_om~q@(y09zyn7O}S_tG6bPr#4871Oj6QEkXPa?Bz6eaKxGh= zxSf}6hpEo{Ux(EMydWz>2gLNd;W3Rk2elWwWigg;~27 zMPx)E{hnvO{mnt++f8_GTX`h#0lQ;KbwGZ#KFnAhCNZv)7;o%M9*)f<%`ZwqHTK&e zUpzXyDu)nz&1z^wSm<#4@K>2q47niOt$pVmA7EPL@>s|R8DLsf;TxZ7{GhEfbpa1-@Y?e@X){|CB%)P|9a@bIxR{n9bU{K zwWFH|&9-0Tty;DR!*#Sb`$!SBkve#Xb_v_FKAgDy7t&-;r~}!GKNdBk1M%fAZ!n)b zyK|HzCW{jkitV(|Go$M*E%EczfBPT5Jy~< z{}9{^oc>W-HZ)*el@}XzEp^RIflx@y{7?eQ_@ksu{OErCXeju-fnq5BzI1S-MA)el z1K*(;8ZF=!EiEg}MPiAIlGO{*t)YeG%T=w<#|w293(zVQXd(V#Hl@(TcYW5Dl;_z-u8@BYU%Ff{4{5;}z^G$Dw ze8fDDn|#!$jvMApdq98>(;-Y+%F7cZ1^NaJTLyiF728W#6!ZCG6N0`RbKEgF(saxy zIc2=w_3QNYoHcXx%p(e4)b6!zm-42=K9d}Nl5Q1By zGN~N_qbiMmURR@@pFQ#-8MS*OYkt>uCJVEQU|?LI-F&6`-6lb2ovmw3?sNdC7Gbyi z2;lM29ua!CeBzwWpm90x>bg7M25r;D&%9|7*rgZPA_{a4J$89~LiNn&wz;|OzMi~k zk&w4RNlXWan3uaLe)WX)S(|RYG3#&)k+zw4EgouS*{A#7ZD%9owENl^<#4*BN?)m= z&~9u!`NQqjG8Jg?HTY}D7;&z-l!g~GesohJ3w&v$2nc{bBbK!L;wyxM+5&5Z zjzWD!R#@@+PJ7_kKCFV^Anad2Wa6mj7G)x1AY;K{glkc{2d zZq6S1MGC$2-5`!W??4u97a0p#Nzk?pm_tK{!~)sSmeC>{8$>JxPotn(((T5siz)Re zEkv-3SA$t{whs)_TR zjH2kr?UOMq^MjZ)mkT7Rr4+T!t)wA7_jNN3$=^1Hn70lhh+b8^lgEw_hJ$rCZNMB7 zj0?6t7kxS@%M&G6GpWEn!KXH(J2uy{9l#Yvvp-j#_ch0uNwR_$%KNYn7V~PU3%czCV;U5la%3C8Aa>SQC)W8ppV6ZquG|gQnkqV0*e{Akd)wt zZx|Jk*tn!yIAzM28aB2AOX}JvQhj4TXUr(s?4{OX2G?m}3l{qN`X(;494(?811Wr^ zVLCVg140MAB!<^^Qr~dG;fODqr>#ug32!9`eo)M7yfLC=O&??&w>_Z8Q-RCv4x1fC zoyE?SM>F-1Boh!l?bKH(m#1ARvT+$yzXUaoWj!42$nF`EE zfWSWpLfJ0jguaUlS`?wmRCQtnG+^zl*_?&h_LDaN?Cv7Jk)-X`-kVhB1~M%+AMDs@W&w-_h_8LCz&l#il#3DFVZ6KDBw2PxWM9X){4|$z9w1Bq@q`qYUZD0 zupryUgU$GXl4YnqKalt&~Vl$2(HnO@LJ8SGQN?50Ii9sQiAc|6g+xpaC} zvUv72TrPq>rwVPw7vio-otR?==j9pDqu+IKbzoPYJM$xGQL=&-6~kIpUdA*G3q?mY z&xoflhpO~vR-XmxMgT$w2`K#Idf#mHyS0$?-qL$(GyJ!0=i{P|nQ=*$-4{k}V=^z0 zX?7ma4CROyw=~+;jxfK*$%9Js0(17pO5HXCu$t7HT00BdjqWm|#wxat>%JyKKEX|I zUn*!DfwrcR+77nvw%KO>EX@z<x5@9LB*1X*~u^2H=oZ?MXD5 zR@CE9*!&>yb3$ItNnUPCDeer`3G@;DS-4@^y+XXv`)E>nF42-o?N&Ql$P**E5Xk6s1f#(n(GAS9D! z@!8X6CUQ>p7m2ol)+0qzA;cZ>XVsaF3oqiRG;vmxs^&KwySecPpuy~`cQjAZWx0+q zGHr_FP8>7v=Z}?`-{3Zi=55w;=kZS#9%VCKu61xOm)sC}%I7mdJG2fv?>c0sXW1R! zGa{W8il<(T9a9K@# zMB5c;OiXJzy>o9-#4sFr`g+7hH7B2(sXC%?dMtcu11`~(EkAjG*M0PMrz{EUE}7>$ zmgD5>K|Jw{?Jl@YSuLNRK04&&8whbESLkUz=Hld=i214c;8#{VrH7oRx8Kjn0_DI! zF#AOLaQsS1F#p(6bC)_5bBl`OBXdY`OqZFxQ|#oP)>U=8T#E=beRRjZeR6q+7$q<; zJbnBM?+*P0?Ad|0@8@q?eoV*VtG;c1T<3iA)tx)8241+VY{g`1LJ31`Ek1ep-+=NF zhj{7jqH=bR@Xb7tz2{CLD7cJqL?EU7iZ|U{2QMCd&5KRhPbC1n8fEHjt2ueg$o>xF zX1&idd;IiZJ{zUCn=Q!m+BUU%S21KevS)_V-_xD*nax}2Q13F znme>W4@tu;k$S+zQA zI+3R(=JSR;i((1I!e;dIgtDgVNpVe{62B^jzv2*r&GB4H=V&UlztM+ND-@hsU&o_F zW=eEE-GZ*={pa-pnMzJ662NHcVn(aHs)EX!YGx(N*E^ z4ajh6)k?$~LH!!1gA99?lvXV@9dRqE?yW>d zCrzQ(C#`Y}w;PWOHAT7zt;s^iMHQ9BxqCp_qz=pj9`jK!Fc`aZ>DkvmLQ2bn(uQ?F zdQAm*J>W&0COoR5N3~>Z&c)I*pnT7OV*a#l2u!*{t757aq+-kU)*=QFj(8G5OSFFT zJA|9Gc7lw(fu^H%!9(UTlGCPh11nZ7-7R0ZPLQqs36U#|f&)kzXyzrFDsDO~86aej zOf2A8fSW`Um!x52zz{l)46m<}bz+Cr{UB;oY7tZ*z~ZOpdin8gH)YseEx&#Zj73o^ zy1yO#J$6^Ls>W|B&OvN|ZbY(3LeIrA-P~31R{kQi>EZlqCY?-BXUv+&cN|Dwbzo9+ zR~oe2zz&ZihuoHyT9s>sBScVa$ z<5V2ir=QuXS6WQNPW-(tMLo8ktyzD;M8EjDUn<&$H2k)R#tn48RJgr&Hrknh+=ua#xN1#H%AGC_irqQ+!ZleUDFWs*`FpkB&^v1P;M7*tgMeJz{AMne9zC7%Dc4(D;!(|ln@)N5;?=>UzELM zryg}V*}GGwP77~k8t4zQ68J#FZDT&L+R1wu;Dy3u)0S9HR*2qny8j1<2>G4?Sss=F zK779e!H->hte?6q4(t%QEkUl!f*kPjqnzL7L@D<~J8bcKQG5#f7 zpe5f#2g_lG@N?re=*N+SZnS01=#%ahzw>Lq(1~SUOgTXO0CC~vb}>hElSZ2m^)2{p zQ~62B{pZPnXEH@<$io7+8iNdMOEF$<3{+5Um8lhuA+gSi(CUhr%-7NHWBwq$1J{_X zX}8>B08WgIdA38xYKJz4pY!ty+v&jzA z2gCwglSQ=cq@O{*SPGhsqFn+5_x(Wbe3uHZ+j7;r@XWNJEI;_x1LON;8_PTR<-)ggavI<;$!Pu=9nBc zSGdkGlRHSY8HSd$&Apge1`cW4Yqq6cfg@8nBB?6m-O#0)f=SSB-JkC|Q7a( zM&*Jgor2<_F+rb>Ot0;kHscLR{1=6`3N^d!{9BXG9H> zb<%V*QwW!UQIsZT($w|z<<>!Xe8x5UjDSP(D`T4Ib4>BICq4SLn{pp&NhHOZDmEg9 zboo(<)0^sdi*fd(F6akid0HXD(A!cu2aE(4^~MfH59B=illZye;`WUBxMR>Nn=v~0 zmg1?qk4_e#v9J$m+nxCuJDGli(eqi|M&P9@kEMy;8Uh=>qI`>mka6;l^6 zy!JSzCHrj=1MU2Famfk2*I&2H10fY6fJqO1u{G_wLd@M<-@-ds^_zvx8)v1XW-?}^ zOaEIl1eR_faju9oi9}bVd8! zIHL9;!FyraLU94~)de^cr;jjg{(O=$BR|qz>8yudEo|~Ke@J_*=6JY*@r=+d3|HQP z4)KA%vPI7kd=vHAb)MS6LOcY=w2PnKMd0ez6V6W@&2*&qKgxm0B*)2xI~S%-rqFYqG!Tl2gcW zygKG(;*-WR{D#gJmkP*X%Q!3yf_x{a>KR)51OMGMT11=@-{eELj`Rz;%K|V>9~ao2 z`A(2a-ML$C5IWpDE`JaPgtYzfTOO%aH{LI`X8KMhSzOb_#K!FVR5^F*?dW_}c^LZI z#)jfZWA0hg#?I>UadjpdQ{-S*OehdI?vvE^$XM_8Y%i@leUbdMuSpSY}@&oi4pM0||v zx4S@}>_{%syA|k$oUpp1XbzL(a|ay{ckc!(DADtX9EczqnAVo92wY z;!m9yNhz$#^$c@2Nu^ub>Q6$1{LbHZS`KJi@KY?_gJF52Oc@`Z@T6L%iTo9}O}>|t zl~4`W;u#%Yxhp?xM9Dv_K$u-~i6qNPSDiW=GL+8;C3(C>mrWzW*DOSK`n!Nnf&)U|?*er$uiV%tP9lOoW%S=i*!8_@(d0 zB{8EeKlKZ5#RD`x>GacxvgxKH{ls7+|XzXYa)wT-!#F6KKxATc+2DNBzWNd zXBw#t*h*bd8}j^T%8A6yk&fiKkw?1c)*DL=Qy5&i!Yflz7#}eLfTB8F7AfMfB%7&* z2W8aIrP583jZ|s*P}<^=4w*^S>%IA`4n$^4B`>^VL}K53!nR)SN%tx~(>LsUR02cf zlvxR-pc|5+%1AWZms7I;b5?r#7>}wbGRH7Sx-o*Q1x>~fTJq!xu!iYammtKt?HxJAYwgIxP39y0g z6T&Kn#cWxL^-NamYJzW!Om`#~DCkFElnGblFKkMwg)3(g$8ZC=CLsworJ%7*ozn2* z&RDBC@T8eR>(jaB&mBd=lV8%!J|pfMEO|BI*rEruj9DWS4~hX!`T5IVGDsxp#UdTW zJjT4}$x1YED25hwHK7l*zaagLTLOuwV6f#xSizWBMR-;#oZtHRRY=}FL3^gc4imdJ zkLdc`aBJtEFia_M<5rPl=SRgDL-PEmoQr$*mFyAY(=8h!ll z^*GgyKh{5g>(s>}HF;90nD^oS9xVb41|ie`IW#{jt>Om79$sVk5AH$5JH+;SaeId~slygw~7bc3{jU*&$`jTfSh6e-xJCJ8Adh@4y<%qyXBsZNE6Xh#=g{Bfm{=9cWhmMJ$Kk6EdIOWZ$5lGY}=w%TqYFoHkc zG?&+75}7#cG-edGCDGQWP==87vvWB4;XOAGo zmR^NqIA}2%bCD})T|c-`!X)mZB4N|6CS-%(o>>j~BA`{YZF=r#iRSnvRw&1}5%Tvq!A@gW0w3A+bW!0o{mJ)}BW&nXize()qJVKamFgutlgxoWO;7Uy?nvZZeQT!{5$2xyG zR%4lD{k|rZ#6|+No`x`dR%1jipTBMQgXcHnA{c)a!_tE;>CQIO{@1u3yR9i^W2?sj zESH%npoTp}EbX>{!+Ru~fucdU{jT5~Jg_668=h!spQxO_`_ zcRUTzE#bCVHa_p-4F+q``a0*9XqNsbdyU-bt%(~SgZx0x1aSRgdmzoRpPvaszpx-y31JNMJI)j zS#sqa;h4qg1v;f{uM)Dv&F>M^8u`B9ap00}shA%HK98so@uj~cF*+q|J*08|>^f(# z2+{ARN6b<`aTf9sT`LZVr6Sfe`*C6IkWan%HN9EyXm)>Ri95iTR$y4&JK{f`$*+^Z zU=do+7y>Syvr)Z929_PXEEM=ShXD82;OAi?XJort&wOiWVC@w1fnN2ESOx zf;Op9rPE&-Ur%sAn6}(+5jO#bBP}a2CkvmG_eJkbE8G4QZU)U{0Rsvr+x|e<)a#mz zqo&Cbyc8i~LM+5v`|Pc|YiaH6{pIN&dia3)h;Vr1P9y=SnoxND_F$33jg6gXDR9L! z6^4NiEAT6Wm`wK^g$6$We0?iMzo(jo2%2n)a#fj|Zr@2nElgJ$iVL820^lU!&sd&k zJ;6v7W5cQ5rH0bib=lQJ>1*{-^Lt#~zpzVaNMWM6SJANaCzY{bUIIWP$$)1biOuUjVZ ztBTmd;j#D>iE`+2Fw>)&6=*?SqHrnbE=(LBCK1bIBkf%tz8L>rvEC}9lqmnLkicq# z_(u7uaKbXeq}6ezM}1l5*{B9_h{5=vIhq-p83%~IqAygOhVBf7Ks{K9ps1(1M7Zur9R!T&KCUfb-JFloMk?5LL z(N6ubPe5`69Jtd~#To~Lz8%d2wmd2@v_Lb3e6z5OtB_7#TU&*=GfBM&AWs0BL3%u% zM5HP^ClBX&CO%=9#B#9tK^B&=Bp(gW!7)B_9kYF=Iv;HMT1mC8f*=$Kr2MP!nT6P1 zU05fuHzOpKq0B&A5U52N9h3DsKB6E5@r+)7c70Y26LRV@)KiC-N{E`y+{l-MM^UyS zpd0wBu0W?;N^>emndJ@_N&QM)-DGtQscs_h*_X~kLUYT(#F|Ri*dKS2qLLC&p6S(M zvh*xbWRNZbETOqP>ny=WOt*AzG23?1^)r0`m&{3wwG|B~s4hSZ5S?;;+HGIZ;k}W} z<$542XE(&tpLG=Ad;rL=5P@@N<)->&o^}>(f!mYS`dhaK+`DzEUlwK4Uj~y;c$*V1 zXUMz89<#+UU2z((RVS;oIo6~BdK<2w%s?y`?FcRT|7g<42yW?w$va)iLd}1Swd1$GG9(QU##+&b(Iy$yxEHN{Uwk- zY@cdBYA=wFyO(_)!&pS)9Rt*40W8PsPT1RN;bu|wp@VIm8KxMXD|^fHam#V)Dckm{ zEwkgx%Nwc}G)ws=01tA{=Xv%@6dug05jH~qH+1OWWuy=GP+kN9L(jqRIQ!l(m76lO z=pZH-%zzJZ+`Zs%7#hr;zLKy+aK4_sN((d%PoAdwzy$XBiBjIVyxgX~Nquul9ay82 z%+q@|yCZ}0!?GvjPY6Xk3aVeqD0>i^r&!iuYr_e4qHI%z$zM$AM?pIx-3MB2lOyOZl>v{} zaz{VwU07kr?OfBu|5l$A4}5N{)Y{<8gv@J|U$7umi4+=mxu9;kjO8J6jR{^PCn~MZ zMMX_|P==_D)Y)-F&^FG=R5Zc2q0`KfbBjs9p-7h2<1|c(CTor2kz8s%oofQ#YOHM3 z`oN6EYvEswcf$lMMVvidfX)V_51ahN5ONnm){i7_;JtT@hy1;$TKlC7Fz)v`Xrvwb z?5^Z5f>0$b(`VJTujL)g%rT3wluf_VTqIfs%e#le#T7MJldphD4?C(k%`uvDwpDA# zMy=9h#B`@{r&m9ki!BXl1SnI@5exNs*+4$EOA%jNtAqjaypB8^(RKC6g=C751emq} zZXL=P2J@cu21Jikf_4_QHMcWi=4{Rfdr4Wd<{TyXh$F@%Z9MvVP|r@DM23sbJ;)T) zau%ck4Ffn%(2JDf>>Lg#pekVvXat5RkQu+BA1VgQKPu})s*IJ=fTH%*6WZ#{e5X&sg#>w+7kC=C1?4{kQDf`c zm{)bnhE$mzbS-MKa_KR5O>dK`9{~)ki*^s!qEo#vlShpVJRwa}{DDTLIEG1awoO`X z*8Fr0ol2;mpAer^dbv2oLf~0jUC=!J-Fx_Ci`{IcfH&)4{w8NHD}tvq!#mj=r3hv% zxB=s=enfH#aJZzoy1Vn^!gt!9QmP%KAkbO3=_}$TtIT%XFchYeGB*;DT%G8qsRi9* zLw-ZEp&lku6X6=v)j;uTC-#VSsW#)|XaMF=oi(MwJ$y#b4cXbnlS6s|9os!drp(AJ z*=eUuZL-I7)#UI{fAFpD5k%Pb&&@G%{rO2#P%3L8dh zh=g~j&AWvC9KDc^Alzbv==7MjM5t&BpsvJj?cL<1+b7)=M4Zvaj)y!%du;~Ax&<@} z@LL*l_G&~muv)1kR%1%r{w53CI7N7+^6E@QySoeKh(G_$&slyU67Z6W=F7LqRhXno zu%O~kEBjp=|LcyE4HcaA`%2I&oLD-BSGtDIaW(_6M~cZFNV;{C_o|Korir!iuXcJV zR)UWHg4a;Pbn}{Cn^;l&Qbi6}oR$pe$zV#`Mk0GglytPWi4^+Nzn>Gf<^RRVDq=g( zBO7P__e;47q1?RU$~P>JJdV}*&o{lx8^&fi$g;q%Lo4DNDejuL#})C(1NR7r{8n>N zpW)`rUB5me48EZf*Aso!p-kC#l{H|S%DvYM$!~%P#D73qK~{I{CFD@X!6&b98!Jrm z$1XuN4~L5*B8evp#Ln3XF;Y0;SeiPWgFdndmrpTOH|;<*-O8LdueT8s=a{&ccFkr= zd*f=z2278Q3H<8^kOfhb^MtN$#+U2RM<3Sdbiup7z~>L~OZ!_@2U|J>t>a{lNBy4r z6GuoN+~uU$pe(+T+yo^FARlc^e4hBjW{?uM69(TB1GOysEkXfk)5mQW;RS88gK36cYPro*}AcK z&7v^*SJA^PSo5Ry_e9{MJ@-XjX=&-#eOAsqUr`TNL*_4kN1=pm8 z9p5WJ>JRE6UGH(x*w3e%z^`_)uvi27u;LX|d=}z?M|{*>5e%Dz-M{z+t-^q6{-D~) zmi_JFEWY$LghA_8o-i&uQ*bW(ROsCJ@Q&bDEAZTbBje|Q2s+3&TzTg|)N3SvIu0Lr z`D;Z(-i&8~1$f8@1R1%j_TusX8fK1MCF`q&h#K4E%IP9nzbSL04*s-KylI{AQV&7E z$cft(M|h8r(?vP;gVt5NNs1^%S#YY-*zC@C{AjB5@JP(w)P_ug1=&qjsWCg_@GQ)s zz<_LwSO}TQ(TO1Di87S)w>XG285)ZpI~BxYd@1<3&B$cBHjd(Uip5HKUDG(XAUALR zH>yUVd78Xx`Hk^l!9|0Dr$L@B?N-Oc;{qs=GsRgW_>+|9Pbp|rNmBA8qKu+S3s?%X zy8HS>2HR<~`C$g5QUzLu$D|dnA@qYrI)C9zMP7S15k+(91C~oHhuJDswG@S9(%C6r zk^xxO_cZkJMg`odGzQP|cGASENRQ>@$ZGIKRKzI#N=;cnGgEz0Z|=7(!SS2eqZ;&h zRN@+(a;KK5wc?DY2`#DYt|31vLut8Hj-mc<#B55@MMd}l<-cAa&X=bN)+QMV&3(!# z)K5<*!c2!dNT%2V*iwJzhTuo}yJjrUKr-ivRS)M3M#sq6C5r&eA8a737c#j9h4a*F zhkDhH2vgkMRn13K#m;?iDKuQ+h2tby=HtRP656^xAt(cs&?b@?>l3C@g};kl9C%d3 z*id0dofJJ5<;F(1YAT*Ncae)LJVEaZ>e3p_E7zMOVpEpbynfs9q^NI=^R!byKs;&` z3yi5*b8_9Zel&>n3xvZG>C!8-Thn9IITvFuVqi@ch!3wha*QvHpQLe+#3Wj3urwN0 zL#vvp`J=+57D^AWT}OqO8b6bYuyBVSsV^qFo6{lRUnF3|Z1*!!>de@|8&VFjVE5~z z&{=%5ku9HN%-qC7Qg0$6R9U>xw&$m zOP|w2a-r6Uc}w(hR*sgkR8H9rUaJtHI49Xtj0^}9F@5}XEuK-fX09!P+Ce@refIa< z75moa>*tNDS)It>$j}vLJU|yKc3a#e2d=I?VSIb>SUPFc)^EsQIDp4q6L1%7v z*Bb(2<~269R2!i@#x9+7r~tAo<1*z#WkH1}65eJcjs}u`&?Y7lc?IVg+_CL%&6pJH z*vu-a4&@HQcRLaevI;vEOxAF%2b3+Ns>@`FFx&)-{HxNNnrdGUrN`+&H5!&_AHY_Y zXxWHWicdTnEE^gDRJ|viI`m5osV}EoZgB|X_Y|5FlpGgQG~*nl+M(dmT-`mha6FS; zSmn6^Q_d|-`b@EF1@l4%HrQ)W&20dw^u+2!|Le>{R9YR@tj?z8oDmZC=1N+_5f=lB zW``+BZSR3_HRK6`AfyXd+f@Z-DUeXqf7;B_ksf8-AtaD8c%{S!^F-JJV z$zGZgFcDgbSZ8@sa4`dSSq(LUZeBlA3H*Mk#LsDoR}EqE3XiYVr$}GR!O6|D!`ki( zgUN5YP4PdIDlc-*TVtmxZbC{Cq04i?If(wDs6@61-j9;|xjgW|eKKYO>(G@u{nuQ) z7=VQrm{As^ba(PpB5LQefmDtwn74}du*g>rw_8SsQO+Br7wKx+ zGd+!csB4`5`;X(Widnx!?1+$pEkSlFgqWaE`40O2)gAo>mEBX|G&G2-fh@DKRZRv~ zXP?qohSjEPdJ}SVktW8|ge|fgKFmMsvDHRGZV|5r-2-XmdUQ1i7AXO$@YeD?5Wa(S z2}EX&VJptzzqw0d^j(PY-2!Lzq9a|WbQS=|V5|2BSzXtFh1qPMHQ&SDIx?(b`qUoB zN+zO}{6_W~G9@x%A2#Ul-xw0~sMLZdC>78o$Twt-VW<#Mc^s$_FJ=bl(l=oujx@V! z&*W1v!G;9G4m5`g2tkAz0@1-5UR*2%>>fKSiVWMw0@L~vm59j-WVod=IU+>EvJK}o z!syGpR>ueT`Ve!}a)GOOdMVOYy($hhWXb#~UnJjsvC{WVasxK2a{^Pm=6#5bFjadb zItR9W>5TwaJF2b1bx0cprH%Yw_J0_mI+9jbswW1#$AVW1srx@9$Z+MHxXaSq#8&-7 zleuof9N65ScI1uO9x0yo8A?^Q0n`Q-eIB0zLd|I-Yhj%Ts)j`Fl<}_LxW!)Ry#$Fz z1o5mp>w~VqwkfN)<%Q&_s$4hKeM}Wb+t;XmQmc?y_P={b2f@j>V_{h$Q5P{12jlM=njRA6r$uK zX=zb5C^T9Fkew0oYJ)z`T}b)RB;Hx$2E5x2$tydop-@_s9j@qGN6%GwB4zQ@A;80* zNKbKk8(A&`pqO|mb~JjesNLKr`&tFSe9}rj>CZ3H3Io%j>hE@8cZvECSI2wfQp;1n zE+xlXLDF;8KvsWtYmTJWZ33!BGn$Fi8pF{uo;%Wd0Pos_c149zhT^4uC}6ane9sKT zr0efiWOlYp*S-TF&s>^s9ni;oX@0&kKr1Ss>~Kd}$a!FF?3hs0`Y#RHy_6es&wT$V zdgStjKhu5}JZg~sJvaT&qR0PQwDRu~XyX4iTuIoL`8He`>RC;>u&GvnHzxVy#~yJI z6zo)hW@|;?``O1b7*x4>X~bo;wkp+;_AH=N8O|_t{ew5@MvB1x55viQ*0$5@q?hB= z6(1iRkd-0Ppf+_A!j4X6{Tpm5uoE^ncrD@%!hj|3b6Ev57c!E~d0J$+7}Ka?;!z2? zJ8i`|2V0`V;b~%75=E;@Fmg&yV*6i4MWm3SRUpALWeGgxrtuwTHd%~!9;O87JMY&+ zvkbUmZ@Q2S6Vx|SlvgFS!)Fgh?6h*}!)}LK`pO<>TH0SH_Yq2&3Ml)6>c%F>JN7|j zYSA+y=(`k4gxtWUYW8PHG!ga=MxgV|>#7Q|9!r>5`Z$)*Tn8*|w;5WV(iVS4tCkPO zEEzpfyC;8y9Osc2ZO#`^8;`<&t>3u0(auNg0-{^=%yhtcoZCA#CmTMagI&ttKeixN zKj@-+SK=vyYQ`m;AGhvh_LNU6Q6DfOxh`L|MZBO80P8|{JMy4TzJA)DkUjY~i#%Jd z&!0D@&$gCUh*OKtATV?4{fvKS@)>R9tae~2m@TtY(@I?fLqc1pP;13zOKm`L=fKUi zcgSr%{)s(8G{#El{MI-9`hTkA{^v{O-_aQVp?@rvTbKB@7v#CA|4ut|e|>-lKDQQ- z&y`B_1zgRuTPfC$CP?ys_2J$2!Ce;)p1QoJM z^}bz@i_^HFI-}4UiOolr92hlgBNkU)G!!H)rWD#r>{&-b_TII={p3XW6c?t(upqrs zr4}S_GYDn7e?Ox2K*f>VAv?uY1{WGBm#S&2{2VBk)VUGMw7N8^{xm;gXR>X3sA9Y& zxAV%i3VGoN<6-i$u8!=Q#J6i?+;f$_RQ|A@X(Igv>q{%MbDEn;_3Ia_gH-{S<_lp@ zi~N1tpv)KFh`iAf{PRC?#+~3R-_EK(e(Zcd=Kp`3vC;qdq-bRB@QszC`}ZgP-+dfu zeLFjI8&iHGeLE*(2Vxo9|HAM6l8~#bCKGz=C5e?22$cpng2D9@6PW6!nRAmaC<_8GIHRYtUF_5WgTRd~L<#n>@US zRn~3eWg|fh*sW$b(zssUr&jrCvp0I)tC}H5IvwB1AH**cj#J;>a;>mAU{}p`2%tWT z!}MJHb)H%y?8c7Ft?7GkW0Rl&5{yEEf^op}8}U&sG>x%yvg`A9kJ*}6{W*ijzy#s$K z2?(Epz4}+;i~TxG`knj?`g4$C5N+qr51$5JjWu{|FikEduDh6R&%3S6Rk}~FFQOl3 zH&roM0`RR2L5r;vK}v~aWz7R@ABT25994gbWfgOtsMtv5S)D45WaIsWvRk}y?t zi2beVJ0w0dQI(#SR3}85J+;!Nw&p~}Hpr;HETP$wS(996xSv9VWK-oyeZ*m#gXhnBV%!$Bg~RS z11%`?^3)gS6hb&nRRjD9Mh(+0PG} zjECgEH#(;{Aui62<4I(+hkBqIco5nZ&g=5vhur4dXk^oLNLFlGn1bYRHKJa}VO4Z* z8)(dmp)G)bRTp1(x`PEesC1QE1Wz*jh~Ls#e8Wyhgzv&mH{2MNlS%29%j;0E`$8O+ z;1`US8?sjAY!2EX(?+=A$!I^Kzk3m#hZovm0)KHR` zNJb0pBvRp8LutOBljNRtr`yXsZ@*M4DW0hv4IpLCp;)Agh*9ba$CO-2`mNdY-fxgX z7J)IoMj_IcnjoM5n1W?^2&%R{|4XX;{?Ca?mIKOUhf2hWPKK&}-i}&2_ubu|M79rN zNgm++Zs`~3(L!Tbf{T-Wut8*cVzGg}*KsObu6y1@E|Ye0N*Kpt1(Pj#qAQ|9WpPaC zb$I9==OJ5&iZLhTMowu2%X)8{T46?0#p(!rCG9)ReZll^uCP`|29~wnRd!R}z=NEi z36GzkcjZbgi4Wmvv%?vrW@G=`HNhhbdM8{r*J8`e9xPIMY3mEUk8|F_!d-j6ia z>mRtx*YLQk*WkD;*XX#*H$nb5ZgahgZfm_vZgDNi!sW&qA3fsuGj(BVs4Mlo`)@^9 zc@^`{;wLs#xdPQF%M1Hc`OZ-LdR!mKqbS2cTvr_>tg#LS>lj<_-jK_qddDTbm+)l#j2a><~7(YozQL#3ZrN z_LUU4zLIO+EQ>b5$#d;l;${T<6kL1DIX|RPJQ(jjDCJ3+g|Jv6 zVsp0YRbYOG%Ff&ow&~v9TT#!XJ}~DYW%3YV&IC*HoPuhF*i5g0TJgg%?;S9xFT60C zTdWRefNAia-Zq)*Uql76w~$mdHNRnfz)?pc z)(H6mRkP7)z+2mKMp$PK0xr@-%z*J|I6p+Ka21h|J&3`KvqCqp8x;smc(-UPG;hc!ftj} zwhqQd|3QRlQk1s+M?$q;^g>^wAs|QqVuAl#VU9BlsZqc}0A2(ELON_svB|kPoN67b zI$Pl;bEmgh7@ysKPn2Lt{6$WY7XMo<)nV(hmAU!ydNE-7<4I0tuL3m0l7d=zX~qtR zjqs`@g!xu{Lt>A0Knp)E^6CYTF4+DYv;%mha6BbM0PiJHP7oQz}<<2Qhap%bFM3c2Vh%Ta z2ok2JgohI;bmp4zF?n9vV0}yn`H5Peg;VM1%qN}$hC@%16|8qa0gen>Z{$fi?#Q;>o9~GQZ_xU?1NE?I7t~a~0Bbx$N+d1;?i<{BqnJ2$k=spj z2FXeh)DyOm;_W>`z$-fnloD}2b<7e~D|deaX2!kbO!q%6dva$i*oeO&gi!w%Q0_n1 z>i_(t^{>=UP?}#@@&7E<|LPb4JR!W479XxTp1RV-N$IH4=>-vguO^7&|6)k14WWj| z|Aq9MHC3OH70Sp-tyB08Gnk1i;t&92V(& zi-32xluLh4ftE|Mck~>b9pSrrEy)E9@O6Ar<^Hk^>DE8i{O-XChL+3vN$26*2JeLQ z2TK_C_Xo3xuL%7_3*TsDN*W9vnl#GE>Yr3vQz)`$%Fe`qhN%sgs=?uA8K(t>BxBRw zz#f!iMdQ#qaM;$P4Y6ZLic~z`Q(}mU-0ge;&tYQ}k3#$gd{0ZW34(AJ$3@O=U=Ii* z#Ks&Jq-E~6vPWm`x3O<(Tu!ExPA!*ODnDAODnAkHEB=4GhM(VvMiZH zyi!D6P-BHuDe7`be>Q}#y0pqo)XA)KOAi~~;%w`@mpVr;tCQvSSicn)ZcDbvh+Vj0x*vtI#_FR@Q%^)lWhLun>w3q8=6ymuc|A=j`zv?{k%%Fs=AvliK} zuYHr_x4e8K)qc)vc7`lX0j#qop=5(ET0yPgcY9&ZuUN6X9M2Zr9WGqlL@Mh5%(|3( zXKo)LG&G0pr)NUSs!$lK#K9+kFspqXj?O@f)gEGI>jEjQpjh>z=+ADu)^?tq=;uJ7 zU)7}W*TIw;+`F}OQE^HbR=Qhzl@QFYON2!eP|Zy(Zf+)lUqA5ziu<+~PWjQ5)Rncn z^`_n(sZ3OqCu(XaZOLYU7oD0 zN#|>+$oDT%)rhW)$yJz_(_!c_(N`9>=8#tJ=fV#l;?&aYE;I2__I`QKXm5jIUg1S0 zVB%C$SL7|Uv3bdAZ*xQ?f{t=oPMxl_%niKWlfS5 zslgNfcRoTO=eJ>PQ<;tmlh+`jEHQdUn4a}bBdsklD)Gy};o!g`Z@50F^{%$^#a$53 zV0VO`Cw_q56WH1s5$O2foJ7!|h;Jnw{1V6Z_rNI#a8645?{Ur??3xF#_v(ac4C&YS z?htT$KI|LM6PpB09!pEY4e7I&n*MmbO#A%C9L>8x8mKi?0%G)N;X0pohjzI_hQ!At zoPwrob4b?3=2*en>YJC$45CKO-C6bdJ-BD?`~r{M(&8l~h?iwVRqE=CZWO9ASgb*h zF0C1n6cJfVtYsZrJ74!dW(P<1r8$&Mcysqcf{ zH&{6r!5QH6Z)fA7n}yZ9NS-1wKL~Q!6okg)7v)Ofp4EKMle<|l31)4C>=qMq;zX$L zLqD9v-0|U~gy`s~a?<}|uJKP+>YrD;vq(~XbA5hGA0}jE_*C8@>h%02Ucw_|8bPml z3>GWx>V|Aa8ie3o{kw<-ZcNsV;8-#2Tx}VtqkbIZ$`eBVsK!Be%qI2D9m_`?eEazY z<&s0+?FAFx`IWfdbM*CAM+P8KO{AN%L*`14PxUP-#&#Dvl0PqO7@p#hI%wp5JT8r& zxUBQE``&%_7e~n9hVIgdciLwGs#fO@j}b zL;4H!k~XBba0pN1PBwvjKaXe4aB+VydLyx>B9i5jCxqP9JN;0#Ba0M~4uww7;kmNtGrh z4fBw8ST6PoQ92=T#;!uc3#cL}H$n*mWa2J}yPCJ2MJR7fA2Yhyu4r9Gn9=o_hh`8x z-CFJTegGQdjzZAFmI%^IxiXOEB5HxV zKYdCwV;Qe-Ew}AO65ionkSbtKEsm|?JpL(ak}E{;%up2eL#(!vCkegiVGDD2?9+NV zw@oru|LaYJnQF(<;sH#cySArpa~^SkF&vbe#(EOBynrG{t}E8dnLWc*Q@qDKM9Eyn z^Ed|aJ=zk6e)ZT2Jj4jux|G1MYeNz?14jk38ltMid??I{cZ zcaHdEGrp-+zFx0rct&*ToK`=-Dcg~bMGo?BmimAz{+l`sjIZqT@>@lAg_A-C&OSVr zXzPnzlbEAal~d0Ikm7xmljwwj1hKuy?eQxlZmQhs%xZa1c<#FRy9D*&$`x}!nxM0Cz6Hi|lRp06Q_{A!?8hr}z zhEVyJX#e}~IILMZA8F_EMSqOf4)x+)qDI!9wrkHhfpTJ!7Hul+Tdv@BrdB3)tUg*z zpo=wman<$krQ{w4&T`uzN5m)hGG+TDuBn!#Dju;t{ZwK%I3Q8*{8Pb@@ZF>+u>Wx_QxXrw=*Go&yYTFdNG=_Ezz{;Y%rWJv+pr9X=<^#9zYH$i8or zr0WtG-lahg`(V&7V({)A?N1O}%WJrPRNewo6NY9Ts|7nknK?TW917O3Xx1BG>38^X z7W?97g#Pm{gX0O}4>cs!aA{1he)3=RWxGE@V0RrcO%N+uQT~v?`4GNqho7-{h38)! zFI@w9!RwEW7HebL44kn%htvpfH2!N=!M7WEn5XMbCmT+&V8ApWF~coF_Jd;-w>yl^%ngqXE}n5$R=n@p z{c=4hlcf{v>bv{>MV~$DrGYdZ_QrBUjW!*AgkbWXN@%n70g~w^k3Mf za^ai&31A#|QG;Rsnb9GIL4Tu<8#d&4*yuzJ3_x2fpPrCdG0(jb{+eRa^7amUezI+A zw635+zm9AqnUbXo^5Fv;s|t5CG7?#a+oxl)3nhtCRu zR3bhLxvJr2oveKT^N$7u61pA{)fSFE zmhL#_AP-M|&CJziJI0RM)S)xHlH&G~VUL$eDI_Mw$mEMKpZ>DOSm~HjQJ>UF&GtqG zA1s-L#kwq(2=gjPq35%>!K7c6I~{37OlCm#={;tig1j#pqY`Mgf7hjUo*dvg&UxM!v!6Lb!Z3uOm6qU@sn?`9S3^j_{ySC;W zF)IbjscOGyb~Lflcg^8KKXQI#{roe4<#$cR4x@Dq=9akA^5b_eUik+Z7S@q%fip0w6E&fl7n!|7%Ssw5t=9s28+cq8WC$2i%fYkbms#3^=R+JC=I4l zBSUUsTSt8A^>UGHlZ6wJZ2bjbr%sNJ6_B=Nap0eBiU zbKZm3;V0N0v!ol`AAY#9mbAo5%cC6f%ORitYL4OcK)R9LNW~u9CxpNWEm;YFGGO1B? zR>NTx4WOFU--cTPXzOt$NCklIg1bLMp5_<--Cg~@UUv}<#8rt0>uV&!nuaI|mf$jj z)B+I?e5kR)>tmY$KFElW{KklOBo{UE+n_B}5V&1?0+h|w;CqlWc=d@MtxUv9|QwPrV3r>yH=1o_*9Mo-%lI|a;N zNSyylUDq$YOVf-vSfXzK*=rtj2Nw?D3t(=A#J=`yuV>5mvl54}FT@_t$1ELStoi|` zB7mgAPo*M=ZraP41%YM=qvhW~+_HWkY)#+R)pzg+nz)W7Wn=rFH~dG<=UCB(_z;m& z+PgV*3x(T3HQoTxjS=?KLo5tY^lM(Ka0W78B3Rd)gLcX`n|Q4jiJEodWh4(fZ_XQx znKv9QTjH8GJ=PjOraFkJeiL@Aj~x>A+kMK>3*!VbDruWPNm;@W45q^Uk~i2$MS;s80iNox@6kRIYn3_9YVr zX^h^9h-*dyxtT@xTSgc1Y#f2C6c>((3tO35UQ$wHuN%bGPo!8e{-Yi~g~in}@vOsy zFIj(G%C+gkCYH=V>kZ#dR8DP;w)x^bW0sFH+0sK2qcf!jDA<*^j4)-0q?L%7vz_Eg z))mCt$)_8$`8`d5%a+?a@P{w9pxWU2ce?0ne!xmh>|u+L`E#3qN1#Os=G+Wqv}zoRTz|fv0dh zK?{O5gw%B)$tF#sq)prFo;lo$EXrlo1DdQOVRE(}xrHhihu>YiVk%Iog=n$(2Jtdy z3rKt;egg#M5+H;>T~X9ip=W`lyjWS5hHxH|zA4vGffS(~PTRp)(#jkSl=|VfCKes# zWxCd^xg%w|Mx9zbF~+93Gv}1!G(i0kf|O;Bqvu?5;wr_)_XZDbuMQW#fH>iLQQuni zrWXS_A=LLiC9&F!6T&`!kCQe+y@#Y~S<@3vb|YrZHnBKOIbLLv4aAj{KrM=@+b@&W z>w4tCULVn+pF^d%WXfp%5X7pz^4q&$%?+!`?(3DhJy6j83~ck)O_ zk!^x*a?T&5Sf&I}59N?8V+xwRKjBb<0Gyr;MY7a77A=zOEYV@AFJIEBYsm8pHnhek5g&nD;t%)g{+Y^7G zU&Bh+?SvXrFu(^-F2=^?MmRQAJH57lMu0=;C{}Ko$a41Pp^|nSw_YBp4)v%{X!A23 zPE+8J%&3pIu=myl#i2=3;r4*tAoo)_rLa3Mo zUYdqa8m>?$C53zxVZNszPrDQeS*NTNp(&iaLQ?@?G6-?gSqNhrq`tvA^^{zQcminM zRF^6KUZ7Nw|5FqJ3ZVE)g*2!xk*-$799BFgU>`F_IHeq5&{nVEmYf@gGWJoR?k-oQ z^cbOXXpA8DNxG(_9JHV{TN8s^xky+iLW5wrh+&Z3E~l0E3J5;+$gj{G6h7A_ryBLg zsSPe@X5%05h!8Z9J1FU!oROYg*N+fr?sa636uB@UlS;X(A6%!`3QfwLxtJK@pa)+n z7gv*{I>t@<+R+L)W=*22jVb65x~DAN;pR@<)9*=;KAM?ol@ad;4Pf5824m07Gupe; zZ1u}S-g`W2jU$Xz+Pe|qjx0!F-n$2B4aSOu$K9t3(4h{H4Cj_&I3d zc3Eo1IxNfr(i99M%* z9+O7lN$iT!hLDT>pbt1;QlXu|3U*vMewf(RWvEqAfCD#7vzO3@1YrZHoH#^%&jp>* zCBCo+NkSM*DZFEcx-JvCkH-$>!5YPLV#gf2m~;`8ub@EBf3h{=*AEKjc0|o0@*;(b zISF`keBbpY_oC)wjFSF*vDZoDk#)xW?Cgml8?^=tB#ip|0N_)_+LQ$s30kJZr2Y+i z$i!!6Vw3)MSjgw{culPy9sQ>UJX$R+G4-3LzwM%l>w4pv5Zk74MTP!5kua?}JCa=b z1j?zd3A;wWsA;n4)AL6UAZqaEyGoE)+ZByPE!f`kuzb=WR3#iGy|JG9Vo@O3ONx^! zD2i2ziTnDx-EL(@_WcIpf6JUuf=D1`S1`?LR&Z8N37PIu+Lk+e|IB~o#ABveEC)Rd zX@oP5lW|U-$2<>`4qD=1?iRl#JU$$A!PRd{=TgP!Vz!66st^-7!w{*b;%%t`WC3u$66CDjs7=uT35pi{8>pL;zLtHhPg zTl&^mGtnPWS$d<6g1i*EA*(cXl2Zbk(YgQO71QwB7E3v(oY$eS4hv=ZiNPyzJuci* zLD6{#dcBo$Md*5x)9T*s#GrBmWYdlc;D0&WX=d%J0V$`l>nBnKQCyNS?*%TLb9*}J_e!i>|@!N!O zZJR$g#}7wFHLI=9 z$Fct?jTr8wflUzhjG|skl%vZDAlbuEBghGkbBoD(zOxH=gQ!8KOGNSo!A0ru8y>8* zlj{Vf3)k(x0-RmPxcz^Won=rZ(UzsFaCdiicc*Z7F7EEGg%$2lxKp^hySqDF+$r4M zhWEOAqNii##k`38aU&!D-IIHteR8e!feI8n6z?vVL~I$PKk+9=a5@Tb$5;>WKIJ^I zcF}I46MfKxgms4l_qA{bAp2+q(7se8n3)hDE z#qGT-k79hPi7V<7b#eTO2*G7g$aUevUmLL`i&w!SeML!xb2vs?izrzn|EptZDi1hI zybc)|TZr5;N?p$oc4;&c6>!2sqpi&%qII-ouVSunM$Q`LI5qV=qN84vQ<~faAjt)l zxn5V<#XEIJfH5WC;1M$>(iEKFI->CAwc=ioN4HT>-G<7xFqSEnZsw%Ow#l7;1ElqN zEnL^p%Y_sy9oU5`11J6UcLY{Q9f5h(TPXeH6q^vjuC0%$eaxx)m}s=J$|yPFQb96k z@J%$MHF8q^m`QA-9?erA^UMT)XT?Nf zXKDL39I311y4VYYete9o*4*SAwT!CQUKz$sYL z$^qRXC23qVRhuW&c=yGIfplpT^>7P=a8Qg(kf?he-IbJ=GUxJM6WJV|GTZ>X7W`@X zq;pvhgQR0|x-&qNd%uX%)-HUq7VFNAaVfQ$;-+jad zS70H7QyK$|wT--b>0;7_(~#zBoeO8TPQj_CPZMoM%KZIU6D{vhZ5tj?71XrCh;_g`Xm?&Wg5e1WpGSt)@^xH45=f$mHdfdhC&1c z>f3Gh1KFnpWyDKr_^VnL!Y*ZuoIE??t!S0n+-lADlwgNY6Wy~MJEGLjGT zJM3s4)I!)-luvMs`Lo}z2s&a@R0#ccpINJl1t7h_yZdQN7-7$^`0R4J{JFj%?24Z_ z?_&M!A)LWxkQVET6)fnosoN*$h|j^hfx6s_HMwEM)$b!jO@xwr%30v%wboGOgl2I` z$bl%$fLoNl>_IA)DGORz(EO3>a!=E*VAD6*b{HXTrD7DYoNmP%fsV;pa{x@mi8)0$ zG1R2MgDTSVL*xE8ZoJwjxeyE@uZT^XIqG@eD!0kt#6E4snpGmPb zt7DPj_B9)vC8{OdZQyi2R5iqxWE%bLR%>tFoQlYxn7@9zXL>u$LV&%7$z71IzJ;in zs~I-i_P6H3)+nl=y2G~8s}3vXWC34%!nK`8mpsh!YyRWiP2OVwpcPR$@s&9AL?sE* zpx}lGjS8{%7zQX7wpn07)k2O>Gs~5K%=E!GSE65uR5bo;N8vOOa=BDy8ItxoN9-R}<$xF;~mT zHIsqUY*_<=oruP@z#I>j70@jSqsLDJ&M8#)leJ|*dt`bYX0MbX|AEc5SV{;1j)O`v z*eD@DlLEZnffJiL$Rv+Zx|iRhTBw(J5B8wWcw-cs|H7oDAjpoS{n||$F;881)Hp(Z zzM4$#iwjb;;X?a3Q@JkF>_n)l!XLVNe*)^*tZcD4rkYS>N+CDC56iwaW|L6#Dl6jf z+s#0PNrAr)LJ}lG#f+L9Ba~b^n{?~EW?zz|qkc&n>d_rG(UJT4eh!9jD-`{=LW^iq zkpPIit00^*VKCplxr<=z+&iE6<1N(eeUOv_Lu&;7O~xw`R`}z%3my2>Z?-z}RCC25 zp+ZaOhtxaov0kFZQx}j0d?sK=C1wnpqo&D((>iwqv8il-J2TFmrj>p670F;$!u%si z!WHuyPniIu+r8(An*J}PlSt7!Skb%j0=;gcz>*R?X`cGg&!aXeIP$4lrrX$B1MK7JXJjeR5dC?nU22W}cI0o)O^`5fdt(F+wy%@uW2=q@VwJ z6{l128|ASDFEJmTc^~GSF?h5tGg8q>ISTUEXSAz=>)RbqMh&;_!7i}k%!aS5ka zs&~$C#98G$6|87h zeg-lATX&bci2=Dnr}^6o8;To)GODg+n{AvZRqUS6im_o|8s!9cHCq8LZ^ z-p)w5@FN*0o=h>a1>mYci@2`F8KRyF`e`1Za{qPn4~-`B?>U75xA|s}7fo05cr}|QUT()%E@Au8y zddaJot_E~TGW2gVZcqqqY2qzq2xEHG|2tp6{HZ1_rWkq)(J z?Sb6vZRp%H;rQ)W>t7juZuiQZwznSU@&nJ>5ZN!GIetR#Gg?bJ& z#=v(k;(HLgUHP>$96Cgpq4|5yjc~+L6?gcrxu3%TFl7dqG6zgS9!)_RJ>8oku*m+R zpz~%-@u^U(G46~H0j=SZ5l4L&h6n;O1M``d-w z&xU-ln^a^@_WqLi`tzUIw0-?MHZH1f-T-o-H9F;y;NXg6{1 zjWzcRXTF|IMU#uVhJ2!YqddVUT1-t%O|)^F>U1~1;CFtU@P561ru_xNVT2_l4zJ0+ zzfglD0oQDVB_)q!xJ zfUUunnGBt9{%|U;Rhzfy`3o2>JB@GGeOG8N;A$e_%8#^WJFL8jMSu{F9zIHl<&~BV z_HoPEq#*U)TfHkySyCpbzB8A97|bfI{LWf8P~%Avt=JV^Utumeo36%-^nN%VQ}O`7 z$gMPwOwDg65?789k)cRp`6i4afrtu92Aq*Y$>R);WP3%?6uTh}nr{te(6B3tRAkr^ zqxzR7Jiiyxv|@T4}5un_^K7MVkwAn6XB5$$R3qL8moWD(toZ9!LCQOg1C znKCXlcM{c7DGNMy((d;ghc@5euPoXRs=XUg~IKStWgFN z-lbL`eR9pU2xqbZ+Y^Ilm-IEHQNI}mm#RxW{4#+en&5z%vi zGKYc`@a`}F9wgKpx`KV-mykE$EB)pF?dLQ2ci)hI0HXgZulB!t`~Jhb^&dvQ|NZ{_ zht9WC?br!b0_j6s%Tma(?_AO!?>CW&Go3nKO;9wVtSWOzUk(kZ-%xot->8)uFw0e# zfQT`kaL4?qkf!A78y^Uw$ZS3Bejuq)Z6&?!Bi_aqCoBKP>)Szs`L`*fzk-?PKYE7>L2PuInCOM7k)F7Es}UW0HZr>DL(nhSMFYM#NT(k=qFR z4<+WG9hXkky`Yw>o$@l(BfocgI|v)_Hg_%}9CW%j9sqwETJ>7DpYZ9|ZWO8tt22w> zg37Zj2_i}l6d~6aIY|`80egT*G2n%V(Q2$JYe(8jc+MD82l9*I5xciDuA{a4;RVBl zDkW4m6D`mFFEb8o>1I+f6;Y9pcu866gHtSWHc`Kw^7ZQ$D{gC!{T*r3A4RNPTIfPD zRO%BIP>UCUauCDV;m~)+m}N#=FuqA@8j5>>~3&Cto9d(OQh;)3uyG z0?UT6RiHwys0CQ7QTkU5(Cn+MC!8js-I@A%&>crRPvf9OK)IQNq;&9Cyx&Qpp3(X{ z&&w;}V6}0T;Svb3W#9yD4UuLGt7oDM$Lb$l4@zn2K}=a*BJn2-Kyhpk+O1yt0O8Jn zex8VpyVbA~wh2bRKxOe9Y3}&J+5TdA?N8$NL?0OIQWMuW?K6_k%Oduv!M~WO83I3% zB^>Dp7(|0(FV{&(xZe}DJ?AHH7MuV(55_=l(WpJm~{ z+j~1zv=zSi#2-Z)Zl>B`WghhOFsqScBv|@vIJv~c)HmO3clR3b*NEF$C*7JO{Kirx z!_uEX-;{<}JNYf3XORdwUbEKRr_!9KV*luOgL*{CK_XnNYB(bGpTL$$5F0H$pjtUR! z>G3`Uk^~Ws>#QNN1s^6d0x8lVj94gx(uJz#HBGKEOcQ`Ylxos$;sBA&E6Ie?6N<-^ zkmUWiIT+r$;Tny_OHsvBH?bO1}zI z?h-o_6dzo!mQ-#y__kb&ch@I-2u~*@`Zo05O>~!Fq^a6;Ty&~9Ziue`ML$U0RXfB| zXQ(3jo{e66X$T_liP2uZ+^WruziRcucQ333>jX3FXC^H-#C0AJNcri6+<@hCA;vcM z4$FW#?lOjerR=hg%_`aU9)%6}zIQk4J=*p|vae_j^5#IL=7w`%6HU4}>`xB~F*8y; zWsP85WG)LEMo(SM3JQh>0(bH-`Wz!-*lkP1Y0tNf9yw{F8G2#IzUDamLLaHRYlS4i zej4xILM{P$WimM|ZR{C6Qv6mq3l$BV8J7K`c;NhKg!%6SNE7C=&8ID5#CgN0?CL17 zpM7ZW%kfi;|7dZ54@w*1uNEixFI$|%zq_>mPp=A@ilw=&;eTeFDQo`&tNlUIY}>Tv zb;91nuC_t8+Sqg=qDmzdENl}bDfGeyj2TTlvs>8!y9QGF`6C9bLcWqwSL5SNH)V|_MG_9n!$3n? zPFzepjf7~ju>%)3i6XLFu!2svcGJzOuY1~B?nXA5KZBFA zg)wQvokhwkx~?w-4ys@^kYhx$GQA`qTaCj{md28?2rMb;=_vDTlk|6H_wZE7I} z*sA#L(%IZ1a56>6z;S+P#y&;cS9Pl2cFQD#yv>4s?hEc*^hnyw`S zM=Rk=-QQBSVCB?o2e4X08+LgAG@u0)4-XAOXJ0HvAWH6Vdpv4Dux}DOAntF_983O0 zprZQx)yxS44vx{Bku3v7?aWlEPF;u|GxHs1n+%?{pXpp`Q9b<%>Np>Zlv{pDWdMo1 zHFFIza#Q*U(TyoXfiXtFD<*t8jF0G@H19Rc#}mb{U9kJ;#w*NEY!|e_UAF<6$2{lz z+1JQI4)*{<-4qCSOyMQh-6FHzgLh5#yBAG4Q7kHT2s)=ct6&UEK8}F2l!h;wEvu~0 znhbk%XWh%f3+szb89D&%I=JZq9i^v1$PvK0;S4b>RYpN(xQiA4AKNkqP+M-nuQhx8 zFRk-t|L&Uo|0u`*_e$ItFY^yy;P7Wgs2rY%4Ag-fY$C)~j+OcnL0c zv(X=QZCX6GcZo&V6;$GwYxp6Kf>q}_OiCIan;>1zPvQ(Tj-|*q4@VVEAic2?if8AE zVr)QJ>>*O94#rX;5-A)5fH+w)CWJtuVF|@r4n3u^v{UO`cu*&Q{FoBBx0Cpq;FM zBInu6GtfcI*?vzFaCz(wcb;kC*(A53FAk9)_wMj|Xs8@vilX!N$}mQ{fR;s@1#8FW z*8Ci2Gd~!!x>AiG9|>Ilc3%0EHMeu&dJ}J5V}rb%37*UIz};wpi(`6xl&KmhsTIoNdG&?M#v|{_5G;k%%;v6;N%&)$| z9#m{Hh3LKPY~~Z{C1{MNS&UST@>7a20`xge_%$c`H7_7)!}r)Ww$OAuA_x0?6WSo{ zN%-wcN97ZixbDrbum-e$>F5*vcUPResf~%Llborc z$$!Q+{6~qbRI_%_mO%e_kY2jgN=6-*ltL>;EFlRkq39)R3f~*@Oyy$aMZ`IpwLTW_ z3U?`#UJjqLo~ojr55>>CXY=8nso!W zRaJ$?=_+hBBiU~5KAnB(Z9bj7IR5GT!TYW4$^%LYtLwhR$NRl{35=Vcpidb~NLmxP zZ(=-l7^X8hz6edNsmw!DXk14fRP%Mte8wbAHQw84sH&J`9fK$TBH!(be$Zkg|HOPS zEaiW-JtPO}72-}v0IU=F0SCioPXz=F*JO2y8_wO`f0j16CZ8Q{zav<8QaWGl) z@ib`0@F#_%tQn&w|4`Ya!hnAO&@y`I|1s5`;`wfGW$~=%hAYjjl4H73H+h~g=vZI3 zhQ;V$*6ToRjrM?pF7x#XyPDMy0KSBnLh~G@#8HQ8MxjlEaqL!P!G&7RQdnnq$SxF#o;za90YJL%CvF#?aw9R;3WD6m8nhPah!Ls5+m&wyp06^ zkV`gFv8q^7$FG;=Y^W6~}-HmH}~NuTag`GH~Z zf!kV#FN=2=y;(vbix2zk;bSw#JEO8JtM&BSv1-Lf(V$j8J*fFgpi|@MhCtYJuC+OSSpw% zk0f|4mt`NHlJO-a>zSubWoJ3JSLjbT_(@~;2erfA*I!qnI51yrlOuB!CR*_3b28M^ ztI%%9!m=)&ol`U3^_BNxP8wRWQmB4n+^i&rT%5u-o&8Y@5ZQ}Ua~_|MR2D5li{&QZ z?5a>5BVUm$*BrxJBP$`zF>acWEJv9*h6B7CFH#uxY0)1B2H7o>3Ff%PZ8Na552EcV0$j?Vh@qdAXs=CKM6E=qkd$;xK=wup74WEJ2V z$ya(%q5oZ;MjXUiQ|ZX7y5E(R^blDyBW2uZk-r;nUpFCT(*>3S{@FBooiU-*w(71x z_*~0*9KTfaxz_lNigfmM3VXDp(I^>Kd`Wc~2;UonyPkmyzWoAVQ?wmuretRmJROVC zhLT(F2)LB2I7qj))bPeLELdEzyMeKfjL!k17 z$d$J?;QW>Q22tmIPZN_!;m5a$XX{s{q7 zPnso1k9_p^OCnhyj$%BVwPfov@v>Zo2Jr(j1UvfUkk54wo)A?ow&}qjk16Zi70K6? zSHn(TsKZDC)80f{+3|bDTIYfWNw`2qRwa^6-fMsi&_C9Z9bL~Zhs9xqUD`2_U~ zFi(|sktyWNQ`mO_FnlbnfjoqIMYZTFZarsZdnPj!h$Menr|TPqFqsQZRL*j!6XF6A zWoC-CTn+`1E~9*)K>I!O1PRK#P4Gt$)M~Y z0A0wl-jorwAipZTW6L|8%eHKI@R*mfmxqx%E;#ds-eSYJdrH`Pcm(6y=+$6)M*qsm z0B@zj6wbbIpqprY5GBG8m`Q>f?9&Ct)f+lqj9Hrp+UQ$K3Fv6yR-DpT91jK#TS@!< zPVUdP<1cc)e-Py=QW3e777YD`g5t~ZY}`<)@}9EQ*Vm4^GbQ>2vdZRRhIBfsPSyea z4zkMc0TZc4b|;#E;~fW`JfkkV$A2_{x!7u=9T-$)LI&@@tpF_|&zS~rx%l+Vv_pEs7-C+fIb*fQSyD6k&bfSa zr&hJEGF9FP5jfVXV}H`P6&fS6V_sTbyGR%-fqxm|P}pd`_dCrLibu$(f;c7g?Pp0# zwph}sWqXruNM(|<-1F1iZ<)}5Zke9wn*d)4jGhGMKgicZ2$^#A&HD6rb>E3Ob|tV3 zKb5BN`)EgYhN*Tbxq3g)d?Q$&us@aF@$`*9UEe?$chzn52Tk8_?6)}wTBB&6Dm8+} zjj(+g)%Mt#e=QHHy(vX)!`DLkVeCCcj_g(EMR5)qpZyuo-nD$w<%{%-fPG5wAW$EG z6%LCOMokHlc#C;I%?po}{b7wkTqzgSm>OnVIPT z>5stO6||hCSJ+&?aMC==N`E~10QNQF*?|rgV+3YREU!y8|H@MB1;vstKzKOJ^@kK> z8t#pAsvsfz<@b+&CJi*SqF_@%efvg>{I3ou|Nq%B|2=R_^q=8lmiBgrHvh-&WKvDj z84ZBNp9M6>5fP?fp{omHNdpTZ2a{YO5h3~wUuOUnmL+9A$28A+clYB58$-vFT`8iL zmIelfX_B(EGQ(gwpd}eGSs}T*??#I6QCP=@{*<@KP{ac+a7WOGcg^1l(;Mm zEonOSEY|nT+vzvGUb_KL=5%y9hHtFDIszn56xEL$re}c05^d;I)Zj7*hm(1gX%At^ z^v7rFYIqlC=jW>1+=8Z5SEda*@+#X~#;GBl3jUm%8*F{Uy>DQgiw{^uo9biHr%S&% zvJWJE6a*?wCD_K1e9UL86|lv?b@@GM6Bb~!eo8A8-L~S9N*=O#S$VPO*FaI!w2i5%qM!9$5? zbvx$IkRTr`h)3^K=-$T|%PIq{ zsOwXXTySh`EXvH^oqxAGSv)3|VU0}iq@|pz3VWr>TBf8Ntn1B8o*bLIlEvZ%?|v6t zQU9}K1%O37lu^^VWEp_gXdEeQ)f^aWr0(pYmLtet36GaD@EM@O;S;WeUN&1a2A9A<3BLA%1zb0Uli@6 z8U2QLXNhBTT{AL^M(n2RC~l_jbs63;EJUpX4b5}LnbZWv>D z82lm7n}O7y+p2Ee3%7T`>C-moFl$lfN(q8hoTeBkNSf8uN7>XSpVBIy!tD~&sK~NWK(adw9aux}&%4;Rje-etv7G-kP7gt^WGbU^6&N6pGbdsnMrj}xnEkcHz;?e;- zL(TjopYXAhC&s^I~=VwrRL>$#V8M^Xt*` zr@g}kXwek~&owc^9x2|}*?FI>)bST*X9R%1(odw_YR)*V@&oL24)3s4fXEU7b&op! z#_$_tYrlx#aB98}*?Lc_NQ3v^_%Zb*!owF*7#=xI7N-?Ophp-7OYh=6s|p>8u~ zpZ*Hpapy<;>4nF{zmRY@+!2Iv2bsZtG}Z-WuwfIsl9mk+r!9hbd1l9N5FGU(Uo3)= z_qu$iB6w0A3$wnixPT=|>tE>maml~ehWS$*GO2urOqfjRWoJ4@Sd~rwklqlvBS=}N zrer?xj{a%E&W8B-XNKmy@12trbo}mhV^JHF~o*C=o;Rs_Q!PR6^EPV@r6@@!xC#%xnSYZKb@F;AJFXRoMp+v#Z z_ba5y?3n;KW8RP`f2JuT#Q_``V?ly_T?At+Qo{wJ6Y54IPbk-HryswL`mhFJ4Hrl$ z47dHV3xme+FCZw)j>&TmKEC)f1gOo8z6$Qkv(YAmgU)DNElhF?t-j;O?(ibQWXY}V zsT{~mNTqxE)Y+SOEezRgzrI>{daCxbU^nnAIoK1U zAbdLOZ$zAjZ9WaxPajF;|3NQw3{y~M*C5odrD1j!a0eKzZ|b$TI`3}!_RL3G_#q)W z`+#|?{neDcllI0}-ld30e-aDSLBW;7)z8`G@HQ6K3H_8eBE=z7)9j&womnQ4*dG`I zkfoD2(e&CoVmCG;W1+stfuROZb|XAb1<>if-adNl(M0TpvnReq%+N^h$yq~r8EJM5 zbw}KIu(gE1AeO$3mOmpc>pgtyKoHzCn6xK}YOX;RhBwtBrxT4UGrEC*?rx8E;TOk^uHcKmjG{ zgy>Cq9L8mLdzofyu zLme~96%wO6w^IFGN6)~Y zKDl8L(uFP8n5yVIFC3$kic|NriM!Tw*YLQn7{gciQtt$e#^BCR{)wNGEPg|feC<)V z8b$Ab^&3fiqg&&GQhzjX?h^WAlbfv< zzCGJCv6qP#mdUV@5fO==ECLgrld#YuBX5GoXv$cd9Q1m83^rRAo zrJBQ7MU#e&Ali+J2}D#Kx@HF@jkuXXHW%%7c59DLWFgKy&c5CH%)b5H`s6zjcziG( z{zfP-PI20x5eoy+Hw1?Z%$`;uf3ycqVeNWlB_~in=eyd+tNRxD&|7w zRn5K0?k|>x&v8ih)S^%2hHW{xX!{S%v53&~m6k?BF4Mx$glpoPKJEEYkD=@_=fTn+ zIr*$<5lf-NeQ}260`YkGaujp-`G#IknJ@dP__)!!LWZNF?}~J$VrMU#`v|lIm!n;^ z%CHJKHW*hG5#&a0kv*P`=jZc@Yss=v+NC8)VH&pmY9<5H?91>-y4p@*f29lFE++n} z(KZryu*=JPnzNw9AO@*0KW7@Zo$X+~&#};ITl`As+LN@0wuqy{^PicJGpzU^yc}3@ zocJ0AblE4fI!8772%v^p)$F;Ft?Y=?13om^kegVkK~|VEh$gWD;p}MHr#Xb!(z<+D zbRw*hh%-{N*1wK&i|m4B41XuuQ+e_=gQ+boP0I2_@(k%i`q60(6Vd9ZoU-PFoEB5F zCWJ+g!!=aCMBeU8Mev=$r?pIiV5wTI*qz0IHNt2or?T^ie_P|Yd2fn_Z}1q2STnR+ z!-*_2-E{D_;aW$Rad2IgcWPXbz0erLi6v)^QrMH#%@JcMO-v$!8ml`yP_JwpVY74{gBR`h(tu*S6;|S4$r3^n zB1_MhnD9@sSz1T|Pj#`~R*1h9N!V9`kIS(PP{pPMYo!hY7e+)ekThGlo1{Yh;SSy; z_%h218!Z$GiX~}ZY?GTRt7A@mKbC|D4Qr!1=jW|it`u9uSXM;ua|{vu9r?omV2adL zBRi7J@XCc2YIs4V>d0QXid{);DC+DBs#iMudhVY5df}c;CS_>#DU?xoPnn8QvzvGY zGdQ1@xJv;iS;Bk%j)(XCH78D2?w*~u3QR{R<-Cgt`MEDIdgRJ=_@)UD#q?YU7xkeY zzD%v?uqMj-D&pU##DK@Y8X-TW=$C6TACFrIziwf4RqhFShq}YzBO3k*dFMgcHpGwJ z&Iu9Wp>Wg~&Uab~DTzsHkueyQwURsWmF-8ykKHQ?G3Lqc!6jpw>#?mpWp&!YoxWZgZ2pY`J*q3A+B9cj@fA zGrO2=y5C1ysg$eFJx_JDi9O03YC_|ldG^40}n?s8sk{@CGGkbvbmCcG~epI}%c>L@}$B zml~7BY$>@X9k zfYnQxR}c4zo`HR=`j&Tx*B-YX9o&4%c3$!qY8NR@CyBKD#7=RUG_Ue#yA0%B!F@SL zrl+33pPOp@_T}02i@}Q;35!QQN3d>F`6M2Oh%=6bA)HkA? z=1p60;oPOR7@AjJx71th#lnwwj z)YermZ0>M^;eXc2k~sN|h9#scFBss0RfC>ClS z+dz4Oh<&HWp=y1WN29GP9k}95KEFYoArO>@MT_SY4)6N0W2g$rhJgI6gJn2oS=E`t z{Xtp+G{FFap=1^`DS?cYZGO&$>G#8>k$YriTe5wU?XU1aD{d$9--_6d2jwzGJOpd_ zLCm^lt#%f?#`Z934l*XF&R-QwbAaT)p$tYZFkZnXJ8zsiJ_&*_E5K@y8dR=9%Du^u zAkN2_)$)Uz*#e?KJJLc0dGK;7T^%j1o&yEnk|n9pKi*=#;}>=+W-4d=0lFzRxyhAZ zB42%~$MON5E;YWcshTOiZj!r;>C)_?S)+?fl66UKh(FC} zMkC^Se@9!2W-Fvv3nE0d|DwmQBu_!@r9hqLSkKl!=$_wBub7thh^(zpe7K?_J>l2G zhF9WZ3}9nOB8)4}DK+P}`q@2T+OK`q!-^ewvv(?=G^JmO?c=5$kCdw3p!NE0Jx~Qv zK?E^_pMp~(F-75h$uV}8^N<-M*q^dAVz(mo-h^!W2*u$1P}JkPFc`yeuj*Q${V?3O z(XWv{NC*b?2UR=(e4*Xp`n&Ac+8qpfy|}xs9n_nBf_Qds^GacU+|t*{#ta|l8oxeA zPEcu;0>4%2$(*i>c4Oe5!9rYf&MnESBE4Il$!wH}Vi5vP-}3$}GEgV*sFk?_78EO& z04l?HcUQLXalpT(o#_M3_?U6&p#s+`KkcDUKaH-9?-FSG#IH$hhyVdX*L3e~F#!ZzIXi$-IP@vkq z$xWf|P&~HEWl1l1?If~$7qDRS`sT!|jyHR;CQJ~ZE})twdW~J>)f1_?_b9H_k&ZeP zRY!U2l8K~sB8$kSA9O_r6NJfndRA3Db71u#b+U+?X>0Abl1<(YN?Y118sC@BfRmTH zBQ&?K-4&@}4=Zw$5%blEVT|J+j9cKxc6*T(1+;ls8reFV4z2*CCq3NOys zh(A;hT$RkfPwSq&UL(9sJOzG=bW9>JQNa$6cj#T3vmIauoP2}mH+P`r0m~6 zP~h^a=ugU4bYb&kl#DOYzUX$@>ldR8+-eOli;WsxABEtRlR-?^s_nx}d-+0Pb^X{SF`keal{O8#57Z$(7 z%H+p4R{>pVIp34hNK1UjD8npkRjsjM)n3*&i?;>zYfdTYl3I(;7mm zcO~=BC7=S&tL9M;k*A&U^jP}E*uC{CZ@X4H?J{R$#j)k-nZb7T@n4H$8hiV*3%g^p z-z>#NO=eSX+%iW?%Sn?}ne`2MX7Z-z9qDaa5EUUpvYzG=?h3{d(*Z*duJjsWwzyW(=8Tn$l_hC{h}x<|r;h^Dg=6t!FFccrj4;$ER*wO(H6* z%qfQI5@TgqhW<1W(xm#5>a<0VuLN?ukTBaCg3Dcl zOXabRJz3%8xy|WcAze*dd|Q6o=yQ18(>AXYZLQjpuG&^x{L9rkJJvM9;Oh zBZKipTU;$g5gDwf^d(o^=k3pSncS3PD>px zZ3!9U<(9dss-eA8ZJagC2DW<_H#uV@oz2#&{MJ0%!3Yepg&>z_B`RO}>2HrW7$<$z zuS)Z?>vaU^9p3WB3hKDRxm!biMq)nZjLtV*dLj%Z5GBelP|-r3Y~+OlYi zFNzNgyKpV9Mf-!B3AR?Z7;k5sP!QR|p8A5bwp?LDXRou|aN|*ImYIQd3PD+yTfa3w`=u1ccU zS~IBw2@QAYa?>Ss6Sqv(QeCb%w{fp4z?l_t^?-~hAd-yYQH-{-H&^!v$dGqYNz|}* zYA+Z=h+i0xwsvYPsFcW7My6H#fhWV>(NUWr-T_(+FK6F4iH%B5$6oDL@tYr+i%I@Z zDKE_^j#Ns!CF;pf@Z)?jHOqpwIw=Xth)TCOcIB@8`pA%i_EIG))&97Yh=r2jDWZF} zhu^YX-RkZHM-#tvoKo{bqol0uidtzPZMaLz+I1;x?MUL-<`#?#E47Vct&8IpmU4EG z5EW<-F}aqihyXYSn)+g`77tdPw5v-pwOZQhE{!dViU%D@aCLxq6*Z2yB&RvHxa2bB zw%JF6E?dw41w%l*zq4Zm-92j@0DFos>3D@~t~NP?Kuz1*R!65B&UH`QnjTz*)^#IC z&#D2~-`UYpcU(&s`L|Lsj}@!sldKEj)iPPXS}L(+O{1IQ5CuAyuR{NV?#=DBj%#Nn z&Ub3j+$KlJoqOnqR#T7y#AF_@xNXM|NqcHTA_mOUAls9 z@;K5TbvL&(QHJy(Paj@7M~Zb-#4Y5vVvNG8_prZ}y;n&jYiw^4a(t8Au{e{OVBG!qT0OJAimyEBC_ zj`_9@!bsVPMP1Ek!Vb{UvcAVLdZ{Ii?2lUMB!NSE-I``+g6C9J$c2?RPoYN$ zyFrc&#o6F^A<@%_YV>rk?dqv;{RoB{>&P3@(o9Q0+iG;SGE@$_F^UXZq-FD?FeDCk zwX9u-i)%B^A!nu1S4SZ9m+kEootU`7&tBDdT;sTQ)Zn;z=nXqsQS%IWn1c!$R(5sv z()x~NMoW7OGAFM&~6;YP{+FlnfA?9M) zkpVzsQ&UTK_lWW1$7A2t@fy0zEXaok@O!Kpi z>^wg_0FU8=Ge2Ap7y6+eF7?9=_~4uiKUeU<&R`XOu5wN1x}O`|@q(O@Sq=Vh1>kF8!7Wx9_Q!rJi!n5 z!Yw*a^uv$b^s`C$fEVFe>h*(uxE(vp%CU2>lf=0j?xdDUe%L`Yl9434l~)J=c#_Ui?a7ny=*qp5BF1*y;Pb;`b_5;em;b!Fev(Iv?%l`8@Bp$>D_kHQf!Jo%2?s?-(S<7-BY-n2p0-+Has$x2~sd zMLq3IqE!5RJj#Y7Cj2*Z_%HiBYKyT~zW)IrEDLFDCA@uw~`#2xwt2-Op z8;)OtUUTAa-YQ1g;24kn-?hNiP@YWHEU9EL{(sModVmwVtH<4$t2s^_>_vPbdfay8VT zLhgI9p`;Zc>a;zMtR)HsCB#Zr!!3%#K=0|4^Af`bq`zhzTGcNCZ`n24%rq`XGE;wp zqmZJ>BL=jt<|^DjHOlj?hWh#Q8kW{qR@cqo@MCrV4!XV1xgiz10|;dHk$QcEc@^*WfV0yZgLbQ?ObXd$22gnX3pH%l}qPT z&YM?SjiwdEVL*pBXz=w;w0jvcE%`4Z{5q=sFLUB>A$ZhmF>?Ms$MY z0LSF~y7<>E+(plIKLe+F4AKv`9T=!?^mIBX7zSsQ9fUV&7&Y*7Ak%wIVuzX|i32j%NAfAt~sQsJ6G`9+xj>;fcfo%@<(9)+ClkR%wIPsKNaFBPL?o+%9zGev@G)&6w4H2TbW`wD%0ED z`WPt6^e#8O+fDCr>+f*Woo>3zO?SKLy>5D+o9=Pby>5EHo9=Vd{W1-p>=^Ch^C8St zfQBUi{=BqA;EAB@0?m=)Vfg}z%H9Saya$gUl;qTfKf$B&^@rReASI&sm`kw(1kme} zq&&6@^t`kkVC3cO08gH!>;Ufo?Icj~`2{||L_S|Z5dID(d@cFppoKW``aX5+&@CvSBAE{MrPIB*vPuLoV}2Sx0F*t|Uuw;0j! zyC7i)B+7c`%sr5_IPV@v+zH8;#9j${Za=8Gy}Q7=BP#k3(DC^lvicrH{}E#0C&+@I zVIpH-Gcl+O^W83}Fc+T0;m4&MX2DYkaj+pBp2jW+gmLHNbb-%9<@o^E>fMmy2$EVP zLW-$mY-95gk!C6rY!!iYQyGmg)iITwkkPsmhF~VsRPqmlPL~-3JiV7+1t&x?0nFt% zm5Exkav)00QW5Nj7X~U3m8NJ-NfUF2a2JO$FM>Ov+1y&6~Sq&7%pU`u#J_$9jpR37M1WktAdwU zHGIfsz&}_GV{9giVY65&o5S*19V=vWaff*%o5$+eGB$;+V2h=>91R|vL-FuuGzcAe zjBufH$bbU~c~FXScn%>I0&EdHkMltxGl|R*gd77S$T2VoJ85pKUNXbx^g;Y~9)#i|vVX7Cr*$s%NlP>KkpVx#;}8V#bIZl&8p0`|~=Jv?BK2-qV7c22;~3)uMqdu+fS zAFw9|?8yN;6q^{DYEHeG^kkkXU*rQM;@>>{D@2Vg!4&`a_n1BppwWx}4*~RKEL(|g z@G>kr2Owb$rZ-?y)E~z>i3eg6cf%O!&Xw?!2-zZ3U>0CsJ4I-kIn6BC4ofN7Cc8Y= zEO4HV`HwSg2gos}ArN+F)L3(x^ZZq}eu2-JFi1WLZQn7YnAN!X=^Ul8`;EZ#p)AQ+7U6-Nqc{jwBc zV{9R+A!;gi6e@^9)1pve6q=rA4N0+63R0$}6sAny1rrL2Qi{X`JD5_0J}%B0Vi#M% z-7wKEwTi7$oWk~aYkVS1veLs>Y-V{pWZ{y98LWo?hV78lM4Gy6JNV-GIiacjKgC!> zt>Nf>WR(#Flw0YEa737zRa$X@%ddeXtK32`jG)`>-!CI7z0MJ%wiyYJ%`gi3rwVj&I7NJ_RmIf|Q zD!G=L>1Hk}Bz|KpFS;mEm)Z zwA>h{$rx*D@9M5xNFBE9Ch`mBniM6&|xRYlcTMP?`I?IiX6^cbp7 zgo?}}B>WoIEFycE7M8s%qE=GoVzZcJoPndBkBllT5bu72$JK zqM&}umVx#l)MOLD0Bvv68o+*)q$5}~;k#yd#BRM34 ztCwlhU|kll3j%gwU|{Mmv)*paDU5t;f0R^g!~QKwL7Ir{x|8^>MTnBp~UtAHj) zLD(v63P)UmEqw@1HY|14y8fTra9wxg({OD?`9!GDEF@uvNzqC%W0NoNnuV@leTCTW zEi1<=K>DrJ+-;F3xfD82@~ndiI15{$v~^;9VZaUs2HYg-VxQ~^8Jt~&9<>N3coWqb za39005|qPr6-5zO5pfQ0p-(7@(m*uo+?>8FR3<{@X1VmUC2qU&h~mnfnk9YZ-QhsMJRKfTkg z3R+cGRhXiR8P*J|B5X}W6~s%>o@f?_QmqO*e}L^wYciJMavhd!Cd*Ebi(@Mz(~s7S z(WX7YE|AW~jr^uafTk2qH)>dvPjyPTOeqSw9Pnv07vQ{H&c}ET1#Z6L_BAkYmcsn z8|%7Zs^fa`QpYHqa;IY0E}^n5;Im55L@_I=I9?uy%`s=GyM59>UM|_mwGrJ0k%$C@ zr51)UljMpcDO;toH8pz98i_V4zzJlq~(4Yh|`MY~~!J=7X+rQc2-V_#Hi#xTp5j*AwPq7? z?f`NqA!DhF_11W44`}Wbn>JvC20HC*h%ipApUl)ynU#+QEhj|fpb1fJR#U$p57;wA zXr?)HU=mcDGiegcLW7%S&BAWa=$jdx1l5i;=2$br(i}0al#>9X(C8$nrnoat8ceO6 z1a)Zi6ot|xsC6enWv5*mv}&zd*@3y%T#8AZNkAY@f@+)uv)xG`+16u8y;UC$+YLA! z8k~txjr68i6G?xQsrx>&4BM4sI}|eCOx*Q836k>D?Ax~s@|v(kA+XqHC9H=C#9!#mk&0 zwJLHWO{WFbJ?NM;%f_H(2aJ@b1JfhzFLOfVK?)fX4VuyT6I^ee5FOa1ltlK{1ALKqU zBFt1pdO}tjmRubql9Q;WCc9eN>f_PnT&|8)&eAs_AV-68cc+r7`qZG=?5ZV|cXk;F?&&i7zT-Zxpj?nN>}yplE~jr7)|EjyfvB zxEyFAlwzi6TVXjVM=|x?un^~Xm07(F>ZGzPhewo@qi3vvx=WCjS%pJT6-DdYAVyAy zD#xLwNVa!S*yoKc#6|vZkJ7xwH4Wp(CUnm(_6}ORa78L}k6|igM1_5+kjp_Rj-P{( z4X1_5-CN9##O~2$#-L%uL59hvLgf4F59bLv%D_+PEYX;Nn98%H3w_Rj|kk z(dm#aW0Dah-VnLlw!?DG{pE5h=)9;FORXVPj=`{%PIBg1_;1(_#xB85efqkj=5tO@ zK7Ga-OJS|k;ZOG?Nm{yPfZ*b8#+r1xl8$}wB6_KFK!xlj2BQL6_!prNe#+bF{Ww7o zvjj2m)>!NSp~Hmtk-W7ClH@WXK#`p=#Nk!!%EnewZURPN&go;s6<8(`{o{WLC3Ajz zD4Fv=hmtwJEtDJ-AC9y}-tI(EM>|ne{4p|wiX6Wi=kVbG>Eby`4LmWFBlGr(r z!On$jb{>pl=R*Oz04muyWmN-8=hhJ!U1+4yukLr%WN;a z#_oqV*gklh?T7c+1MmTR5I$xP!Kdso_<}vbD%ex3hCR*ZvS-*l_AEP^{h6&`2iR)% z9J_?Q!0u%)vb~6V2+JO4uORkS_Bwlwy~Pf)kJ#&+v4dP^Z*r5p#fPxBc`>Gy>{ULC zeZl9lFZmMo6>nyL=N;^8zMlPqpT_>lFJ<5HP3(KVh5g8{W&h?kv!D1q>}UP}2mUbU z{3$N@^IYL?a+QC;gZy(I%fIDug7bKh$P-06PZC)?S>$s|jOQt$il>S?o-SH=hUny( zqL&X9=kQ_TQl2HY@)2SO!h85g@dO_wp5r;f2tCU5&T4~}lly+XD{Ep95w((iYjeNFpH=m z_C2=$nJ-j5e39zsi`5`sqNebp)LeeFTFH-5=V5*^U#c$W%hV0LQSIZ))oU=lmN%=n z@)mU$U!lH%>3dk`V;)w&;_d2pe6_}Shvws*T0W)|d03mu7ivZPc&(Ig&}Q-zv_^iS z7Um~u7x3R{w8*I&q(9@jUoI2V;FzX$m0(g75ri2SpJBy9`nEBj~W;8$BfPVapO9ye=~p5xQ#z$ z?B-7!d-yZPpZK%Jo0z`O4;Y{E=ZtUp^B#*o=NZDE@{Hgwc}DS^jKE<|Q z@lU*Q{Bv(E|HeC(f9tjRcit-gy>~wUm-krygLe)8(Yq1hi}_F9Kk%QuR}0;{MHt?G z;ql%iyxv=d&wGdPd+!r5-iJlN`>2TZJ|W_~FNg&1J0j8h3Bq5BWbY5c@);t<=M$+u zv{c_{k>NW6;b~%+uS^X0%@J9?MPh_+smS&~3YqkX3ezwazD#dn^V>bp!# z^KBM|zB|Qq-+iLU_kbw&9S|kH4@If(Yf;@Q!q0sIc}{2aTjBH1=hJn@x*Ocym7ZGzPP6pf7}ZQ zzorD@-dBQgA1bkNUn+6&UL`g@R!N9YRTAT;U^-n1#Fs0{@pBX_ey)-dzgS6)@5c0a zB|ZKuB_sX{EW1X@jNhsZjlWhI7JsWUJpK+PEB-!ZMEu8?ey)s4P?Wrc1Z8wWhB780 zTN#@$P8pXlLz$ScP??m_s2q{dri2o@l_?3wDR#oCN zQ7RI4E0qa*lyDm4iQm6-`&D6@@ z9G#f29Gf^zS(;d;v?k6}+7j!PRf&zt>cm#1BXO0|nb@PON$geDCZ3{nCtj}fByL5x zUpX%EcBMD*Ze@MqF06CEa$4d;%IS$uD1C{4R?bX(M>#9;Z_4izzf{gm{8~BR1myzL zqg-glDi@i_$|Yuoa;cfETxRAgmz$H6E6oyRlUc27HRmYX%!SH!bE$Hzxl*~#T&rAf zZczHo)0G>{is8P`S^1Oxa_;s_Zr2RrZ@7 zDG!)GDi0>9%0o#$<>90><&mTb%Ab;ol*f`9l*f}AmAy%=%2P=_$}>s5$^m*UZw!Y6 za1nUr%lIT%1ykT9xDZUX6q+P7jV*vK`7*wMy$d5HG@V;8MwU)zZ$T@(jBTf}7oitk zk@e=mckn7gw%7`Z@EVrZiSuBrEUgviKph-J+-xx(ZiLqnnkh!Yy^?Yb{}#T4HxO4Y zID7zaB2+1|P|~*$s>W#HLU645dKPhwPrX{@+j7J!*bc8SgSzo z5#=I13(l0dB1MQB;S+3YE1I|-KBdvpN?BNr(RBSC$dUC5^yhH&|AxAe>4Q?1rz1viAqn%ij?y^BHhFd`%knl|eE51EDJ49GEOe zVTP{@g76Jlr}u7n(b2QFA8qcR#1~_ZW8hoTDMlVk(B4s}zRj>f@-6V)2`!Rdq3=F8 z+Uc9`0azgUmiR72JD`5p{!NhOSd;&EQ0er|e+;xcBj|qv(q-FX|NCIdwx#~3UAroZ z`M~Y@teEHAp3e-7M;z6w3naKbuZ?*Y_R5~m2mp>HwU`-*fs1&+I@L29crBs46essI`!^@T#2g;{?+w9)v+mv zqtcq-E;v_OXL;~L)H7LUWo#1UOM2D8Tj46l)?#P5Ey`l|xPGlN_BL4KSWfJ@aHTUZ z<0iX2D&xYghpUX6;Ci_7xKXZ$D~r1xCb`gGBQrie0rDIu?n7AU%=oxBu&tyVKQBT# zelE;#O5>|wkwYc^ZkQ&anuG**%xe;|-LagNurP{ii{egoJ!?(;9XJX^uR6Y;aVc|E z!Xu~+2YLqP!H=Z1_^s?@_&3>o{I%#YekIWgm*cG`FhLC$D3?cVQSkfu(m9V&^4NQ@j z$dZ!QF%=;dGLkx&hL8r?Nh_F+kPhRLj%Eg~6$TU}9mzZhd7v_>ig^+8!px*n=0gd5 zP?uE5{0PNBL(&u$gHR9_CrxAlgyNtzX#@)*lmIuI@32^eOt{T_lf@yAWVq8j$l?*Q z;2!f8mVi(S>@r_ui3p{_{pPdGL?{g&HXmn6*ft#=Gaq5e2n~TJ%?Fu<&`@~B+{aQ7 z!Zq96!%`6%0WX-lSsFqk;bn6NOGhXNUNi4v83^UU8|Lk72txVrws{N7L})C$XWqz$ zA~YU8Ft2CB5Sj=do7>rNgeJqM<`$NPPzb&-H?t8a)l}g0VV85cF7Oy?XClT8odcKa zLUiHK2&n^?<}?Ya1nL9W!58dA$ZL8{bsNN`=%!bm?0Q-M&z}=sHI-(iIpo6%zHLB9 z!lh}ZmtOYxMJQkfsM$zt7N9>m6!Oax+<>g(oZtrJ2`*8*KSfWYgBdTKT6x0}63RA6 zP0>s`*(^#UDtVD+A4GX{2JD~+#hG!=;c`$O=LO8T$Z=krbLJcDi=)G3E9i<79@J_i z@`$595_2#CN6a`WX25w5AE2v+u_6>NLJ0voQG}ArBou=`YbHfr2J^iEJ2_ydh)|lD zM)Yk-GRaJf$do3J7}Kp}WJ<8SKb35ySm_c<=}SXqkLFk@yJ2Fdoo1!=+8H90DMCYo zRvH}|4ilj)GYe_6Y?pRcgm#vsJ;EA62ZpCu8Pb9KFd3S8SF?z`sOWBRcI2 zGph#&Hq%OTnr8l@4wAje8g`fhY)of)X=awPEHtzq`cMYsb5cZx!w~upWJm_25f$Mu z(vOlN97cXu1nR=jzAV=N(?Ki4jx{qwSu}DZ%%rp}u+d5mw%Q|6uw?uj8Ey@u!qPC4 z=45iLoZT>kF6zxdAyMactd)aphZ2!VR&rP#)?)i`tDP^QG=#=l`PSGlbvaia< z>89WyN^w-T6N!ztN8kwd!y+pqXk|F;kqrVPt&zWCJ{I5y&&m!|kz+MH+q)@ySYbTmnp@hC9*8lGb zj!~oG&Xt-?A`4BFb{0>WyePJn%vQcAOOk_;6gh{LO_I@4og3Fg_UGHpgw2p9YbW67 z$OZ(s=l==UNLPi0vMiHQrzj_<$xf1|<|FKsfSnewGXgeFhGFI~60#L1(J*oz!&3}% zSRisHJS=i-JWLwKa1gW0aIPEN>cR_l-jQy{4sX0mI7f zwX>~kE2|gfJ3#`$M5sqAXrgyyZJ4*RJMB>-lxyY^w=&tYT%tD$dF491@?XE$0x7a~2DZy^TV!C1579ZL49o~C zr9S#;iWmZq0VqF!Q2q^mVY=Z3+q%LoUHm` zGp5@RcY_*)JJeX%ttP@lstGS(`kI;y@2eJksHVV|YAW-pDJ)h^XX$DN8>tRq<(Sr} z$*fMzVfAV*Td3x-CF*E)jGE7usbknGbu8;v$Fbwo3G8@vB0Eu?#LiSFv#Zr3*ez;^ z?Zo_Ebt?OlYO^QR0``nLjU7-6*{f;^drvK8->YRD)N-D#R`AJcC7-5N^Mz^+?@?#* zlhir9Pp#!!)H=Rfoy+&B_57gPz`s=&@SoHYp{U0SLtQHT>M{|hHi~3*xyVqPM4s9# zrl>8VQe7cx)K)P^T`7)KSBb@HSTw2aVzs(j^r{`=RJBuFpso>@scXe1wM$&Bt`}R> zWObvG zsh+1~spl)B)C-i+>V?WUb&PU^dYMwJUamB$S14y9yivVMxk%lt+^Alo+@}6fc|^Tl zc|z@1o>p&Ao>OmBUQ};ZUQusR4yv~*e^GB!K2vX3zEST`$EkOzQ`LLaGWAwK^q=-LHP7C#iqeQ`E2ZEcGAyG)zm?f9mrP zzgYcFU#fnuH>*GBC#(O~&r*NVFH(Qj`!&#?MEHQF=&x(4{+_1kA83aDrRLGU)nfG@ zwKzl5;tf+vFtQOIt(nF+Eyv34pnl4=z~4D*?39TqfIT9#^IJBPvYWmGuI^B z2H_3pcIdIIAw}ZSacenU)=OjGGgab7u-BQh>CO_T;)aHf5yp!QI7MzLM~W%1LT>VM z#A2wBo4h>H1O;+4m@ii2_JlTrW5r!iF6oVA$Mc;m2ccwkBEMU1Qc~ET_$uUbDe`@i zx3D~fGT1YGIU9|9GuZ*Yl;tBdl)cIqvN2dXO!!$A8!M%XV?)?Dl2lYVEZi7c^Nl_?20;$)*MQkE* zQ%`^g9ldDhVqYc^H?1D-l=MbwW$53iG+R%HY&i;fdI}Us33Bux%#>1%()(Sh^7M0X z1gS-?eij_XCL?Z?{yJ`KiEpm{r3;PHf5vSf)f=U}B93B5kgk-2Vi5}=l&LoJXW10e zkXFpTW>XQ$(*3yYqodkvqXaT!+YH+JMYi8Yr`*6Y3DJg=gWqV9+iwNpjbr5Y8#moX zJ+pB$twD}a%?c3GVUkhkZn}$%3GSx*4t>AeV0&S=zKcyGJ7x8H1}j7;z!vHjn~qQ{ zTcVrt04kmxqsOx%gc8^?J;;i&G*Nj%T+d1nN>ZK{+gT}Xx|Qd|HF6W5qP!@sVr676 zxT!5?70#yCcni4?15i7D^~D(N4|l?`A^IMXzP9s(Z7pbNowh;Wl6eL0QhgcQV4l2# z;FFgFe9l59LVnXvOPu^53_)LjZs7ZIdHcjEQ=PJ+L(BSn_`DSfXP934Kn)8`zjLi+ zoUAuQ*7%!bP4q+Z!iz89@>EQ3b0`LB#yI3lsr@g=KY@+0uKcP^UcU&M!HnimtQo|; zO`I8v&-j3iyHL{%su?S{!%bMS6((Y>?Lb!@J$8bOB;wrQ%CHi8B`VhpnsHVFvg?O8 zu==&|vc$%k@w9=bDxO~3l<`Qs+c*W|8mU@IGTyzaWJYstou!dF>295&w&`+=w@k@# z6~f-;jP_760?8RGo3T@*>EvZ{oUVm9(;u=BBD6&~?5Sn?@tNY1vSjKrE$52~7n|aa zVTywl$RHVq{bV`d$)nBW3DN+Pce-DF1PRQ;=yYg4mPN0eL<(dlk_X=?ku-i)Df1VV z@|{Y3$vB3m4!*(ce#&cD$^D>N$-Q<;^drL2X3$EZZBUv*_nK31#OdqBen_=a2Hjl2 zn9`GH2C>9U!y#9eZD-FTv=xpv)6mqnLqi_jxr(z=te93Sq0{+zDJ^5!Ha;PUd7CZ+ z6$z}6-s|YCNSZ==B%_#d%gi|Xh(-(3V6lH;YjxRH_IEUnSY;X7Iu1j+L*K-Wx@B4k zt#+og`*ga9<=n82m%BsU5Jhf0#z)bXiQ6VCA>8VeS_z1t&DV0Lr)1+!Pmgr6gOCm} znUmTgt(d_r;L9V_4te!6mq6FnqK22?_D>LOnN7WtYv+Ip;<3vEjd5HD$_U}MMSO3h z0m7|Lol-%~Dd-U9ZdR-Hum)`%Yt)WoE45yBoVK2A)J|ZVv=iAK z+R5wz?KJj;b~<}e>tnBLXRvp*Gua2)S?p8o_v{PpT=tE&k^P{Z$K$l~`6%sDK3@9+ zKU%wj_h?u0Q?;x3mD*;0J>qZCw(xtkt^7%C8$Y0J=dWwm@prZB`3G7*|4h4q|D@e0 z6zwh%(C!xL+72;B+bKfYE>WoM7B$+vVu5y_Sf%Y1tF`;ZI&GggP1`RvY7dA@vs{l$F}E%0}&gvQ2wV*{Qvt z9MoP?-qc=K{;Iv9{8M{VRkXL%cBdHuH@_qI2NOn z3o&l`1}3sfiTeTaSrr|r^E^0BQb`tt7|~TzWGYT$i{$H!bg_}u%7`gLT*9hl6q>0H zhcc&BErx8T6uwu&YzE?j@UzmwY7mNLsLlo7E{S|Y z=lAlPSuOR8Kgl=AgZUJGfM3e$zwJGxILOsTPb&;wzu(>jd z%2sRGkw{O2(P}xXN63KjYLR@g;e}6?)7dgI%R2;BN19o|UzT2n{ z*fke z6jI$pXp|>1;|4d#lmJ#q8E8NsR#1Z=9YrWEkt;##8^QAE61(I&#+)B*L5t~p`u=Xz zDEYDQC}d^(V-rbK`7u3sHw^lkzCr#p2K|-+&`S`O=zLW#HeuR~={8K)11Ke!UWOhm z71MnfU!LcDb?-S!eoc?cjU6IWRL%l(0qLX(#a-Zv8%R;j1*spGP=!to$%Ckhh!j(# z6s`6YE8vP2Ek)S^RC)UNXN_%j@tt;Fzcjt{Ul*VpbLn$+E6<*5E(m4G9-R}gGp)Hq?%uu-vyw^dJTr@L zfuU9&p;IisJe0Hj7Dnccs7W0O_^oQ1XVp>3j~Wv(1#50pYmU7~M!*~sQGc~-1l3N@ zqW#0B>OfN|-?i3U`7xO_H*6)-tBM8If&c~Cnbs&Pv&kN1W?cn!IFpc3R?soEEIH{m zLk!`ZSt?n`Q{M%aZ6OUDeA}`E1J?9oKh3ZHAGaXGVc2*w8eqegXzAHjCYfN%Ap84q z9d=||Crum5waTyk12|8cF*Qe+hSIz>TDL~}qKSi5);>r#^@FXm+*MDxH8F}F6EVbz zzt$otEm~1dL| z;*voUkCbzLK)|q7?#kF|Q84){DfU}=z4qjwJ${hEv#J4#Z1Q0YK5EIW_VlQ^N9(ml zE4JFj)^r-pWXBX1IKv*>jQxOjtzs%N-J)Q$;PF9PkGQDCQmfWtYcZ-eZLmlYK^9tR zuKUPyrpOqnCzk+W$J5KO>GFNkbX0~to~9f5@chH{;n(y=52n`?p;s*5rxi!(1?_y& z>reMOBm4bFad4S5z+|~cj*E`k{6V8uemK`=B}DZwfK9OC2C#Yr8z+bICR|&2C>PgO z`dyILa3Zudoga#IIL2;+<1Cc$tgsn-R;PShklhrdXBfR;3c46V#f5Pjh5ymZ0Nh+< zqa9k4TWO-Fgt50c(QB+4t5kl{SYwxBhjXn;dv-s>B8yyQ*%ov|HFhojRZ5Z0Hgh*e z4EMV?%v=&9*Q&Kgs9o4IEZo4jz7E1)A=Yg9z@|5oBmD|3)T`EJ24 z=KJOW7ik7tqdK)x{)4}q>FD1w2hFjR!4C4bx(A(zMED)bPU@~{kSom~)opU_l(wuX>Q118 zr13kUy(DR?Cg=BEq;gITj=B7bTya zmYGe$4D_D%)z~c4! z%+wdKRQ*^sL|?{w^yTb$y@{QuuVAO@t*lR9$mVd7Iuy6Er?B9AXSM>GV(2wWw`U!l5ej?A;`}k!2EN<(+=hOAGd5L}wFW1lI zbM%dTv3@>p)-T{4`h~ntzldLf_-ph_`E~jq_$~V7e6M~5e^|egAJDJj2lcD@TlzKp z1APnsO23}}L+|H5={E?kexu0LZxW;Rn?;3wt5~AnE|%+eh!y&sVwK)6*66!Mw|=kK zpx-A>()WlyeXqDkzh7+9_lfQLe$lT#ByQFp7Psk-h~4_1#Gmy?#q0Xx;(h%I@tOXV z;?*BfV)bX0VfvqyT>XGDUVlkBLVsDAs=uO?=&vfX_1BaI`Ws54{-zSv-%`5tx0Mb0 zyUMBhN6Ojy$I6BJUzIELPnB!+zbUuqpDTCkUnuwKUn~3de<%;>KPr#u|5gs@KPj&o zpuBD{9N?;1k+)KHXf4NXO5s(!;zhZ$Zq*YK&648K}##Hdw9K&>@|+F-<~i;Q@6 znUSov7?!%yNKw}rscN5*rfxJc)Ju#Z>eWW3dZRH^ecBkVzKHpQMz;F4k*~gIj8Q)@ z#;RW!mCT8S}9D>o)x>Tl2BTBI*;u3BW~|ls7+w0GjBfooqep+oSf_t&9A|iqUL)REZzLJV8>z+yW0-M* zk!PG}j5U5|OfugIl;Kj zbCz+v=NzNobBS?-XOnT8=X&FI&#lJYp1X~EJUfjYo(GKGo_CG=Jl`36yqdAsYZ?2z zBaHptkny0m-gwx1jPZ!K)!5-(Z9M8d!Fa}ds`0G1&-kza-&GO{R1IfP2AOH)QO$tizKyJz-ho24?`+nB&S&0$&enmseR=`%2krq#T0jzO}3aaZ{kg z*C8*e+feQcvrf8#3{}3BYzRJ%=Rs3T?myzoo^}YMyMR>eMhq%geqaa zZ!uekP&Mjz0Xq(%8aT=~kM$zAS#YdxE?bYd+0f{l!;VL&7MguC*#?B>LaVQuoq$k1 ztnyW`6R|}D8{)lCUbUSMoc{L(&Pkne0Ckr^zsES}q)wA3b-JmW8r_j~uGC^?nY>ji z<3oDkrEi0=A{1lBP^dA)^15gGF&MAxh8eW0_x8nL#PP0tDfpb_O@z*{?NwxBZ1S>f zpwh{Go*iSw(8WRe_WKqGF9;nRTqn*7TEVathrzo%p-C91NH2%XL3JsgEI;ulF_&0Q zS&ERqkC*IZWJQb~QzO|(EvFz-O}2@=E5WRlO7A&SuuIoP7)IZG=0-J>o#HY51M)e# z5$@03$+`!zhDvcPRV#MDfCEMmL5g^D<*hs`V8wRY@q@aIS@!}j@*5)yl7toS0 zihY9=zGmQ;kDrA}03Hp5#{j>_1Mwa&qBrT;F-?;g6Suoa`q2T1^dBM z$zwcKJjYYb%RMvr98V2D!841W=9$f}!u(cGIq&z(mG3pma2>K?xb(C!=w~OoZ#aH{ zN$g~t&#CCAj+LG^1uloH<;oI-YcWqZTH?@epCWIxB%p@Y%G)p|`pialihK)l3Opb^ zd*WVh$vg*FQsQCpa+H90q_WT8K1n4> z{+_Gr;rR{H`!Wg9X8}S&iSqq|pKq2vT!VOine^d0r1A6Q=Mo0w@{`%A@|H$EKarhA zex04b#>o2`es(4s&Q6!NG`28<^~qZr{fx;T#j~BL3(`g+dbcwocP{wtNS}TNdIx#8 zoe*C;W*_|sG+m0=18WzX%5LaV@lV+W-TT$O-o*k7m(?w%I?GH&zA&yUp!tYFtQfl$ z0uHE*y%w_eKo9Pq=qKF_BthjeQ7G93$L-HEmA(27NQ>M&u(d?!wGHR11Z5l0CB`(< zn{Rq2jK;s#ddqMy^e*2vpm*ou3j2)awADqcNl*IVKWm5)cDhFpO z+>Gpk#1y+2SLG5nZeXgPNf&24OK_?m4Tk3!obJnTx;MfIPcsyGTA;zx3O$|DI#3>0Wubu*v#Ut#P=-x~#d-`J+})6+qYfo#jXP4kM@gYD>gui@ptDLxON&c?LEAH@FMUUk!4`| zqV;j@Jc4xB;mI*`qvvkY24PH*ARM(iP1BXjCCwqm0C>5wb$(_T>7%sA=mb>m;fL!? z&%YS6vg6|4tQY`+m<*9pK?N3kp)%;-kP z^98`?6kUS54CiuhhX`;hy9Dm%)=`zBtqoMgotU~b8UrHd!rl?*ZV#%jnU*2V`rWtR z`TiPpg~HuQ!!8a4RO|V#MqMfVyQ8lDTW+4Hg_Erb0PxRn$bXD?Rn?Kh7DM4_=d!{! z>!lqaE|L+)5~_h)_DTT9SqF_!;)O+Q5SPI#Yh39mGPQAEBEA582w|6=3cdCS5wXNd zhLk1!n9iOK=6$HVdXHJ%7FbJh>ud zwGFJ&+EeKrTgK|^tq)o~gWIhPw1>43ZUs@m%^^UFT`>D|OhagX0s) zRdm)BjieQ#QNTKlxNGB7Ev!y?;-fNPhPu1q70XeLtLrpck&hFOiQF4hjbR!a%-F2a zYqGr*)2DeC97$(r>9T=)N^Rj$Ml6TrMQ54~IZjC0p~-nlLv01gT|&(;5{7K^G3%OI z(DQ4|i)SorH{#%HG@3dIqS1bH>h#lrA%5h#FnQ+N;FH)Gy(NCGwdVRzM9viOkA4eQAQ&py6MQ4fT;;rc>%_>G<+Bw4o@w&Khlv2W~ zY~`TB`P6ukzvg9$z`;6=X+{(GB?`X)@jbVY5CVb10q7m-StTQu0W|Op4tMqHc=m%o z`hjdRZYzfzhbD^cxO^LDvU$%3Ec4^%%6#+mk37Ca-T+1-^Mav4B~Zna7Ixv9x)%6f znHGO&>TY0jgPkxRPJ%XGhajedf$*6@1NoDu9RxrfBm(HE`;bP6aTi7CUqgWeWQfQS zQ<>k-61gSMrAR?dS(=o(Eh1MEaW_y3v z@f^rUw9NMD&4&!9YH#FFwFP@xrg*pptPr^N1e` z3Z7!V?>*rj)}JDj(q~eqj08XtViXE=DOf$eWnMhS7S|!Yj|zlgf*|~+13MD$K|=P8 z&xaokiU-)MbFJ2g0Cs?NjE*Um_l1|8sDXl~i0KF5Bt_QictVVr){t}U>{YzRHvo%) z=$(kByO(vUl5aY+;>Yf8Z8QL-81jg|mPOFoWSXk3;0EJ_D~iex7>pq_-4Oam%%>0o z4PbPfJ1mYxwd&kV{>OV=$H`V+ct+pkF#!+UI&mT;m5$IjK?%?_eVtdoIRNs)> zO^iwCe+qyIIj)xr@#5-Do^JJ#32?l^p0nBi6v#$h2>RXg2Zighfk({2kAQQxMV4MN z{=|!bX*B1c!(z;ehO^4MNg=)N9g0DvFtsU94QWAQhwBed#=L)+l9_tqBi5a+x#MsD zvsIre%2VfbG#HU7IxR!d1j;6rKb9<0m0B!_%0bk2r1qARDv0b^Rx(^&I?xsCsYYZ& zQ!MD#-L9DKDFm|jOnuE{+(CvOgFTpz{)mj0dKMv+_v^8=x=8hXWzfymndxo9UmZQ+ z`*G;X)_Q3-Ym7n_gr|u`-rO{?s|m;m5t$z_F^Wie%5`V=o4tPDf<|!O2ZuB3sQiQE zQeLh^#!Vf^VB8Uis166nFNhc}S>EEjXJg4a9**`m6gP#DtfU)uazfD>u-J`v>4V@R z=rc5PWul~HM{y~W*DL;|!&g22?!d^fcN`C7U+f^4{0*g0f!?#<;mzNkkqHvEHh$L=N(hJBFp#-A(U5(c8VDHFoKq+u+-Ed@K_1;F2W+NGv zL@m$}fOBVjCx7P^M%}WC{LvJmy!!(bU|M1r)JnsH_1Z^{>#{&QnCXHsR&o%|o|NFK zgA3P!0cA(tTKtPYm;pWjQ}@WjSUJaKPIFT&_72vLr=@=8LK>M-lkfW`@gh4(EnAj{ zW5Pga9(T;)5^Y^0r;NGlJ^P=1oOnz1${SE5*B8@%tLS_W+{Hw>X zEA{r`+4xrsb;jSQB6(^~0STJ~w6i zsTcVPhl(f@Mu_5-B!>C5Ba^YR>Qw9^j0Oh>(u=M^AbbCs(OLX2XLSDmk-z)5IQ0Kd5_)6YKR1KHqM>Od!B!zZ z#bOXsMk-1f-BKF!-KdKrpNwK)cekIw&I6V}_=a z_gqKIM`u@4dO+L*Z4eMkXww7E@ND*Ty3N`ZEiHSyv_edC)grw;E*KePiW2ps)5qr( z@W(5Qq5A6Q5+qq_`Qj*^++!oNrza_9AiCn^a*=RM2_*fBQ^3tmg>k%7fboZH3X-sk zh~&bYkdoqX=6#OnV8V!d^8yvjs1{6KXlL7f@vZ|=OH|T2gj%Rq71MpcN)zE`#oBv~ zI^~nOfFn_qaxy92A~Y&gjbGvqcZbt_-lay_jCl+;T!R9Sbw)51qGO zUcPN!?ur-oUts8u-W9nQMEq+a!8;3|SxH^37X%Y6lKmUz+4Qi#=BhZ$4<-UUhA&4} z*EthoHI@$wPvRwacIk_`<|z6vDcFKhSM4BRX)}}F;Tm3@Iq@dr2FXgLUY6@_psb0W zLRLLzE!o8$pKFh>v7Tg8`NScTM$K-~LxXFLOB)DVLLL%YB`}c>A?E#w=J#BOrPtuD z0pHJN6B^&xsA_8NAS2@|^Z@F~!xdOn5qs6Uz@0R4X)Tc?f7?rE=VhWhEfvaxPo zpP+^mN7|8u#+uHLuPiAD85kgDE@%i$;aAqVq8$g*?wY*OzGHA9WHA$_iE0zON~!Xz z5#BOgMoJTJQSirJ#K%DdQ)QGUt{Ki5-y)yz8ONiptt}Gp_$&ca>(=w+qj&f1(=^Rkft_~FZI08FyK9*imEo?Bcmq-wNFe%~@;)hpaaq#mk%ZHav9~&_@Wq-8Y zSW1N5O_tr!9%L8MPCF7_JOfBH)271a2hRu29*-RT)$5yk9G~1x*N^KycoLjs25h<8 zeKG0xl+x@Gj2FLpU8)Dm+!0u zJ4Z;mao2VHU8~i?ieb5fcLn?+0O}d7!huBlY)#ZCk^F(mFiO#_y0U~^k+QTqd%?)E zHbkiklo)e0x8^j2lFTPU9hnq76J}tl($vB;i6b8cNfnk7BCwTu66RsKRn2m7HS3%*OA#L5nEr{>m8JtBD{X=H5G|^ zt(_T=SP(&6Z${jh$cpOu`h%A+_28Cadd8 z!nVDhm(rLmz_t`TI*!k@-UUWcLy~Z=;HKqYIg=!zZ%)@!>FcHuO88EL6@%I*7sy7Vb_8%4>uzuXSt~^&5oxd<~wvfUb$zOcbhPQ#9ZlHBd0J6`u z;8rBCuQymtP}EbjM&v&jxt4|BD~p6#3+9dE4!SRc!55lfQs6vPcA=C%Px7oKAaX-mo#6mS6(AsBoOSYCgCq&Ph45q4Q z#;C+o$Eg#EV=%d-L#}KI znXfa40g6M1_-NkfzVF%<#hNrCL65Hrl|-mvVEHHSKa1;L;upvd;{Op1kS!L1Js`<1 zMo|Cut@fJmtcE6oV*FdWXywL9#RBJ~1<~o8c`;r2j5rZhCb|cvB368sGx1T{n@e)3 z`=0dgdJ{+|=>YO*kq#=M0h(pYcFV}fW1@kMc%$u0m)_^0-e+s}@jF?^J)LD!su#!| zH*;9^utRu#%W-;ASCt}%IfSANf`|DqH3k|8x)gP!r*8A4b3#FI9uOqLfejIcT5Kjn z7Uxtc&p#Gs=uPS9i1xG;KXFmK`wI1X7#?lCf*OoE@q(=L(1RtZ(B1Wh?`Ws!O`Q_m zg5{@UMR(NUap(&-O*0*gQTM*ml3H~mJjoXU(vrCq*D1$cqP~) z{preRlS&#bKan~jIo!~1Z>W-01cu9Uj8vv;DUa1ragJ{Odf#M;-V&rxfA#bczW%WM ze23_uUOpL?G&Xmib+9RTRk63MtZ`gfb)Wb&X)vT94gdAuP!!ALR|?C|z=4OkzywRE`!7h?9>6peIInDU!oXmHPLHSY?JIfzl|(yV4zO+nGdrEX^d|8 z9Cy$o`{^97A9c`tFCjnHnQc2^KYW=6wtO|-dLVu9Bf<7=0@;wgs*_)>nBFc~wy@&j z`z5AwU1Ku=c%O$mPPkf*c$M54wBFEjLA5pGX|M!tL-l19ckD@j7V8SrQ}mh|hSYS= zJ>Q^EzUOz8zo7<%dEe!tRImf+gY&MJDmuV0?S;Tef5I-uMDvWsB%BY=EUuLo48i(MwGT2a*dk zwqUa4p;!rHvW96a%XWAUaNmUi?Hcl4A~)|6)B*($3gRFN;2qrI(E?64nr7%eb8E7(_wuQsiro!#6vs49qzysLodeBV3F5mgH1Nz@=_2|f&#k!aUC$}xjA*@y#?6%d`zVPN@utb0c!Fx z-rtKsm$I*p>ep>KU_T9v@(gbQWJhUo_|!t`^(8y6)44{u-Jp7@41+k{Sm{RW2+$?% z5#YjmDujtS;oRrJitYD`IeTpY_KiyT=*Di~p53H*@s@4^(9f=Ao}W}1vIdkKpVxG~ zAmq^ZFtTPG*2B;21&8Z7vyi9f4#g>LanP1m*RmSGg=UnQS&ah>M`L4+330JPSA~{> z<0#f}7_P!sO&JkaEOrY2~xgnn}TRpf2q5Uu^-|K`ZrRv-ys3A!;~{w<{XHeyoCRn6k-X ztls315{52r6)<|yU{g>MKsKFT*q$DyG1R+eZo`ac*GYyP3D7$yvx(q^;#$K=0?<QlzuZ^wJ%O7=_6s)&YVMT_?p=+=S5ew~;iu#^(|3=H?11@w#XPfA0< zQn;d{NWU_XB`%sI=}4q74wpEs7RwoYW@Heg!N3#l_91>ZhxLTS6HF>>kZ@*2#y{96`obKEVw;EiY5gYVlr!bt$|we!VnPbDm}TKm>I`1!->MAFwqbr#j|Sy zXR4@jv9eXsp97A%WUDa#2!VHoe3t*EiA(onk3?6OH+8(a!Z%?`bnhWC+ycKf_y}sN z8R8?sWvFF35fyzYQ6#g7Y?L&Se3KV-^?D8MgYVu=Io$x1^{iXBCJmrtWe(pX?P#JO zbOGQ+4M+AK7k=F4VhQ-sgnvs`-f{l1*#qzWgy`cHi>?)i3EUUVc9R5ew@1dgd9#Be zJI;j6N$Tx}ZswG6zk@Sb|A($8VlraGy(WAjGCYHxq-HN(o2ZKTEpIQgo|Hy`t8CTt zv9G4QEZY*f0|K^zga(OTY)tEMb7p;WX=AmKuA`h~7X9)#JiztJ!mcx%!uL7g^M{v4 zxNWy!W!7iIx%!&t+R>pOC4T)b7Un^th45w!H5KRS{M2br;c(wAb!oVv#$r!b)Z$`N z*JRXU7f8U{19yG^|M8TW`$9lf5QfRvq9Mq#}h$CAoX5t4nverAox z22?npGIyMv{Hm=?ddw#`?xzT&ymM(TH*3yzHVL8hzVp1at1uUFd{WuF8t?`x9mzgm zWT&jEdB0pr=W!}PB6XEIU+AaBNx>kmGI9!8U2->2!eq0M#H39~9or=Gje8Dq65PF_ z9G!7tnU>a+TmcC}i9ZZjo%9V=DSwhp6iHnWKpQ-gM4zejl%qYg9yrS5{?r5+!LAf! zsXUsh)r*OHIgrMS3NT_1f;B&!993ydhEi{%VS15a@yGi9w1*g)bUSU_jxB6D_enKdQEGAxchV5*-X3rzeh=EPJ*D7-5FYB zVd3h!cWY{!hCR?wZ4QeATMQ<6m*pO}3jB9<<;?epeA443RyrORV3N4Owd>YNqfyW# zSqPm*+U_FUlz}=1nT|i%dQqs??xsT->Cb`CcS@re&x@ z((9|9se}{;I$_3Gl%|XhG^mSdsQi`U$y0kIPta`i@rFTl?%Q>^sD3H!r9i4KvRNLi zCam*PY$&Y8XUg>OU0B+`ZY1sQpDCROKgHgt0*~I> zqt{cpeDEaisc#MH?yX{gALYXV++b#f1_iQs@rrkI3+r)DOnr#e;ziF@%T2q=%@)fs z7|J2%3{QveMJz$V?r992a7667XSw;2$?h^tX7{mY?VuhqpG@wkbObM5^Xd*)uQc-Q zKcWA5#ZGUC(1jj+(-GPv$kR`Gb7kPg`vb?6R2eaW{zPYVHbhsWI^#ZK!?P-Wboizs z>PvRN8OB7p$w)!Fzvum}nb8&O=xEe|tkUFu=wihw{)7;Dh(_mLbQ2S=k-Ze^+KF-!0H#kOQ|-bR0O=kwd$oHG1Uw4{o^5?QSv;Yg}D z5XG?t#AN;(imF6tRXzC?R8pQHuodAmtj&~ZNk--zHcKFv*%_sOkIa)z)dAgNq5f^` z{(x{&$5f&&XNH4> zso@!FF|r%k{JI&M;KnP14GV3a(EH(9%?qlt^j=fV_I{8 zTpHa09%s4L&?!P3_9KZ?4kQrJaM@(LxZzXr(bTIlQG>9CHAA)RPqe&yhLg{L@A5|U zidBtNb3PFq`H~gL_smP-Lsy+?{LVYsm8-M>DeJJyNUC4B z2OOvxghCqTmt>MO)7tssrpL~81~1p(wB{#Jb)vlZ?k@_PGFA$+`qoDJV^g?6oC?oX zsQws(fj0>pZ?+8*XnHYN&s52$^CZ$h&rtkRw?WROG)O!`$f#zG?ce}2CW2u#Xj5;k zn~dK6-QmEh`Ymn}y53Dyupw_Z<8mE_a;UapvD)Tb(fd>IB0_JRxDdZcm`$bwnFL2I z6py4l&C5yjmULmrB%rx$JjpA*8S~_XaiK%!O^z~)LKh~-$-c}M>xu3!H4I9I51sWD zzov-(uhj6r?Zy7LjA3GF3tJN<69Y#h^M43q)ptc?HI&Z{?y}roW6nPtxyD=VeKlOokwiv%N#RL~hnMLY7k*r(-gC z9@pamzDMh~4p$$~Q$Mc0X%Fw=Weh#etn2M8b${sKMi4&LV)#rW4yHs2L=4Bw&HVb2 zXv-S}g$sUpk}{Bhgx=SEetAh*RWi~*NRp{+X4vwhpZb?>Qd0@!Wf}{((PC4eR*hRd zMOuV(?$wOb^T{8<=aaEFNt3pbo?{*j`}3kckB(lIm1TIb|+x`1K(>hqR# zjm>RS8Dp7Z-QvU*&PPkOdfEPX=VzwJ0wXi6ruE&b{j3pLFe|CqO@vE!q51MrQ^y1X zU-1gK6X>~dT28t^6B^J@P;m|mDY_|nac2k>>L_K*2LF12_A52S47-J;!1jqHnmFRI zsL{%@Rrudrf-*M044SCMN99)X-UDs!+wE@E#L+TxMc3*J&L~ zfrqhRb6FDK;XG_SN*$M(g1A0yg4WhO77~7Yw-hGXP?iUj*l=ce{opA`XDaA?DS1%s84;o!xU|&F zO@Q+XtS-fgD#iNBl|R*ny#+_BF~|Q!0un9HP*X7yMyT>OKo5{c!zBF>!w9&z@M92G z6d;qCb{mn*$v2Z~N$+FjGd0yF2v7>6bzWL}ZMRzd>Zh1+{xve)PSFv)Fm6xeygan7 zc0>1lc|kzOMOjLKmT=#G<%UQT*7T7CmyUT-;`9SKv#}x7<@9I&xf?Fm;%!7!@SKw~ zFxKSEEr|}`$O0|z2#5AO-AcTK7HrqSx!{RWKHXaiOJW!2PH57IPz{Tc^h_3uK~C=#rG)qOg4{P^(%_#jH?S}L)J6yo-??&gpHqvUK#M#v>X{gsX0WxDQG9PAYA19 zRCsZLB8uW_@k`&oN3huFv+0A2m0oELulKS44g^1sgs%7c zDAU~i(x-0s&|97f+4P{d$G>%8_(xO+)L`iyu;`WdEZx9?Ka;X;L2nl#lwqD9AXwg9 z0CgevxC%k;B?5J!3*tVa3z_#&MLc`k`t-ylw>%TD@$DWC!+yjgkX~B?(Y#&HLBGNB z9nBmd`1q;0-$`Y?qUP%v94}!!E^$Am1L?x+GybITgLamdI6zezKj!c|e8)5*t};&C zFTs*CowZ1dEJg)5d2-uXmbx`(G0!)YrDGa3^Z!&Okt+}CsTw?B)KHSLI--WVd5GXG z!XhfmQeLys@Yh(Vjyw)aWmER69|yO*Azw+JaRSK8#6kTsZe1-lAG%b{Q?R83HHS{X zy+DYWDp?&VS;CKMu5;60q)YD7g-Z#pGqZMb5Y;7BZz;?5gMDq2c(N}Ra4il3Gt@@fZN zpo9CeM*i%jzCZ2%IZ(qGs_>=}afo(os;95D@NEZMoK6RuV_{Yp6UZT%ZHSBDZ3ezU zJ#v79GPx~U_1s12To_V5V;S_=Hy1-LZjw)yCb+j&{H;kj5_*9txgwjU5WKK6*~*rY zq_HSxaS}r~VMeq;B{h+c`*yV8-0Td5deG2$Z%lU4!Y;v=M=>c+Q%5P0{rh!CyczfE zDtxvSHT_b-*REG6*pRYa?UY7yfF1aeCLP#)F%ovHv{+~ABip(x4QAAKLm4hp$bjX* z-M9Br3Xuv~b>`0Cs9?2Dd2;hI!f5B)(MUzn;_qhK#~crR3TZnr75Z6bSM|UkrcT?s zMh{wsa5o8;lOM`*tIq0t`3#C+ZC8Z6trru$>1uD?rpvOYdTz0ESE-iGM@*B6~4DB9mqdT5qA6y=S zUYOj8N?k0xW{0`6HndXE!2;PB-!(bY6=4MXI6REc`+u$9K{2~`L5@GMyNo=6x{RfW zc1LVE0#M-@gIMlNpfR|S%Fc*OGYXvD7K^1;?0cG`NP4n%msg4hJOdNo$yrWgTW z4(ZJY8%}Y@DgiP`zs0Y~Z3Q z^=g6C37~c;41nKYuFv)m=)}qN6PM1n#_C!+UI`8^fr|w-SN01&iB?^)k|+y)0f8~~ zD5W#$ZF_+XbmkHGvP+ONgM?q+3aY)3{LF8O{ck0gVi6!^30;-r>{;+?6P8x{q8#y7 zsyJ%4b*f)&ldbNEm^njyEK@}x?xi^~ym9>~D%#F1X`2t>QB$y}8CZ^wbG&q68I&X3 z28ebEU^%NS0SNB_7#)hBt{p&=dca4n+tzdN@z_5^`UqZtcb-bN%#kZo_*JH0RmlvM z)R`j3&X{!;yil#i?Fajye|}0$Eb2&&@P{2TGN%`%OgliJavnOeRhH%?irLSvhD2VH z+6)+>1m^wR5?xv!c8FMJsJ=DUXhjWluKjI5ah~1RW>}tG$K1GjrtOv5!LUD&Bj})O z8Yvqio6RCQD_$qs&-@1+H2fSKM#`m?!}wK32Vw9i^h|=xNHKs+BV9(j_&V1xi%x?( z{{bu6Z2ADx$sL@*Um-5@2*rs53|BTSP%CJmq0iJMEJkk1U3OkS@gUag9F5XcUWP&i z;0@?yr$*&{f>HY&RJamek|to&hb6Zcb!M#m%(9+({Tn}HnLG0S9m)dSIkbj3^5rAI z7aT6M#uv-=o{rud#)j`0m}KTX)Q(mqr8l!B2)wP{x)08ASZ3_7nVf8^$ltzPpX#TYZMYJ*f!*F}E$U{QZ>#%Aao~v4`{xpB!>d zR`Lo!DFWuO#T+<<-O|iXxJ6Zhj!JT$*Y{hjt(rYY=ev0bKatuDv3vkU0q}%8li7-T{LprC13M~4^k5gmWxThqu-e^QKJt(gR4Bk_y&8UGuvE9@) z$`Dklf&w7dqe_S+37O&DS7Osur_sKhct8dbZ>+O281OENq0$O zaBrs+8TLQwzozc%{iO-(Ix`g`zN`_Me`$@V{JWa)KbOh;vn@f!z~0`%)=a?Iz~1Sf zH8YK>8*(@*D4%ez4D=B{8^U42R152+yn%H`Uxi`Fa#6@A&;yO21`QFSKg3}iiJC<1%`4$)QIN^Xb6dN z{eBxEVKL~2V|9!L!62PT&*y=~6BY?eho>MSNUSa0?KV7FflvbRC}HX zKyntn9_=Hh^ayCabwXH~00T2Dj;=ncJZkq#8;4|&`pXtc6Rs{Wtl{2D$6qF^d$6VW zn9`$26)tvsYYxMI(3?70QL`&iesOvk7sm?p`JU)fd`UpraEDh4tfw zX0tW)w59Hr$&!`80p#Y2AT|<52QjL?n)ozY8QNSn64#i%iOS~;-ST<$W8_U5d&KvG3 zkzA4i#pzpyAqnEwT{@KDV9A^?Scp{cDBX9}Qf6tT9rss>3D6)-DGF-^_63ik`o>qZ zC)pWj6hiI%W8U1|YQ!WtjxqL?M0SUl>I6#Q^X-Ij9ai-7ZWJe1(lRu`NVBl4D*23oKWp`)o=47kU1ZG%IBVWI-5Uagt5YllC7rxx!O0OBb=XN^(ZxMQwkV&Klk6PTf&*A#=>l10l3JfKXe(O zCv>k|CsAb}=~mi-aV1%i6kK>(fzJTcx1i4aFYmFBY-Y@>jS+mg^!63q1zXAX$cz$v z&)qQQ`Prw6MTUz|!xuaM;Is}A;^CQ1Y;_7uOC2@L7f#4V$jK@h?Aa*&b+JDq zwKGcisb&(NEG)pHd_y;^XrcMMioIB|PpWIu84NDfQT;RtNkiet;zY1lvtOn}L&O&) z)>x4Tji0L%C$fROlJ{=zLS*+45sD;K`T>EO$uUIykSEVh0;LydhE@@j*C?h0^AD7E zpGgTKzudgzEi}V%!%>}B2(A#9;8J`olZ)jwGJe3<{gS6@foa6*4-(1y_r}sOYFEWOK+|TzSB$3(Nxb26=a9>N!K( zusJS)&vo>?hgPrQzPd%BJ=^+~0dqo;fk6uUuZBnjl&-&VkUz(~QSnzt2L<@QLWbP` z8X3YCrluy2Cbmu%24Brn|5>>G2TJ~d5&1Pq5C()yx0S|we>t$v93E`YyC3Hs|N_@9aCe_u;vYT@McrHbjq z44eS~3j^D)Uf%yu$Cb)ff3XtJ+|p`e5h^H{UQS6NKGiPF8gm*ez62Gdy3i9d^_+`z z``USaD8^^JkDoA-?@zulH?uYWIR2k?qnGE>hgpEjRIbOz?Cfr!3Buw%Mp71IrvUmw zq2Y$0Vatpe#K2r$xp^nmekC{nY$@vHbUSZ-(YgR7bNjS5SpATL0+LSd zevdX|E|y=-EgI-S7HsKF2Us$f3rDc+2ct#nJ6R1h`Q+s)JCNh?UgZR1KK=1Fm*SV9 zVe~v}8kg2+vMzOf2o%d}{sbCvNp4qc%>ngQeHh@9O{3VTs1moAh6CkNvx$6#31xTO z77Gy~m+e*ii@?7_lL>4eh3UOot~)UL2BbF&*}~(~Me0=C$=!*rQwa(d)m8cd;GLe3 zQOuZ|ICOzp9XErCRSNesOw)5xmb(akDMTkf88px22bYY0?`B=axNl7!YxcUX<{4>J z=^41k6;-cv86o9yj`n^|86Ps)0ag`JXv9+XPgwg$%H&MhL`2%+aD1&an$XD$I)bDq zd(7=;-7(^2@Iz4+#P|*v7|P{!iS0q?Fvq+Fa61j4I{G^NeKUL5hfszgg{pph4|)dt zC=WW9FwHzQ$K1?nV!{F7s$i?Lf7|09A~+E%cYQ=_o2}a@PpW{ja}TeueUv=F-3VcV zej_%nl)az-hO|c2)WBV5N#V^PPPx|#Se9kUZ|m^rn@=xYJn>94bw7P3z%oiL<*E5` zhu#O|eXrlhU)dcZ@Pd7L-p2w9M$VwwDvKeFYKU%?Skup3^nkcJa!#N%+qIygmK=1NrzoLCleA$G9Y`dxBdLiaETByjBrzgMnnUFjv)|h7My?r z9n1={JIG`;YUMI+Wrg$wxGU;|B9xT(C%g%F{f2*>x$rV6;EZF7`%sP$%jg6!UaR2VeH6y|=Adhe88WpLL1ZBDfgk_LG?Aw*C?hW#WSxstkZ z3vBv=qXIJLPy;5tdzJn}&vgsvwHqy(Etqq(rQaHBTXS_JeD*ZnQ&l4#I^;VRqpsSu zNNt);t#R7nY4#1(i)}-KsAQI~qjlX>7~o~I$mIrBVkI(rL-fk`xR;9&WEXq=1-6os zWp~k~^M#AER?AY_v7t_A7IF@lbv|@ZL2AXi=t4h4NH71aC5B!=J6N(OtVfEQil@{Y z^S)5E6JX;l<>sAMv|vke!v2WXFyc_QnW3@2oT^&iyL{ybcj39q80jAVt+_3}bf7%) zWPmk@glc5-lj;uFyqjSTG2fv_cD=uN>_N9B0*%yX`H`Ni* z_<|WQr1rC}JLXUa4qs03qFv>FW|U_AO_|$!KTLvIcJX$k&OE5Jxxi8HnyCiKZSF`_ zC(Ah_&PW2yNT*8r2pB|3EcBCzndksSBN~LJ+EY3&5kspV-toA^e7O8Yqp)r_FxsEr zwE09GNP@7#cMfACxPzc*8&!_+JENr`%s5Bzz;q({0XnxB%z@>x3(o5yhv@@;&$h$5 zu6Z^1Q=luF`kADw|79Eh?`E9D|9Tt$=RTrlVqs?PWMV95 z2rzMUF)^06v#@pghXb#;@dXMDo_<>`Etmvo$fsXVV(sWvA!>%w;^l~QA&4{{92-#= zF_*UWnR!pV+Sth0$aG#nGG0WHX2GIJvr=>q>2{M@x0y^_uX|I?S3s=tH2C3-+>9+* zN!S*xsr{8WwnsIz@>nIpl0UHKCq>_tkYj3rY0zeoS5=G36W$Mf^dls=9PP`G~I&n2#}dI^Ol)`Ow$#u1gy zP4mdX^yCUNGy-9GF(g8L;u%#hPOBt5l&3JnViK7sDh$B%TlHlpwY!{mXm-v47Q989 zt?f3WOZ;_ybiihA7>S-8$p4*I)&9Ht1K0N77pI#5dc5DBndB~$Va;S=bTTOIW`lBMA-LL2 z6;v&j(Jh>&dLSRbe=WYcz&9cAuf>=6FIzK}{_Vy0UquYDyn&;Ejmejs5p(_;Px2qf zSG5y>)|UmWVdeLNYL0xGyED+kfEP+iD@Sx$7q(^;HI;+Gg zu9Z^}BPWgDDg|UHDAqm*A zPxe?O%-jY0#W>LHheM~gZe;FjF)ZDbA*ED2;%I{>H2GPJlOs8M7CFxi+S=&2Hetf?;9Rf}FLd&&$yWavB@eDO96Poji}m z+ml%Qr zRI6@%idH6vi{T(Ey2wGX{~WJvjEc6~QN&Fx=14UWom@F2Lz`Y6>y_||+{2_NSPkHB zpQ_NWRmy8`Q-?AGJT_?105WEJdU)Ppd+t&*$!M0J#VV6B=OIZtQ|9Ln!77x+(E>`Q zJ40@&eX~d&JX1YjmN7$ zQPx`vYfO6NkYBY{g;nQ_Q*HkA{OFBqJJ!7guE*g5MDMTtQ5X(VuK}AA-rxgj4{Ejn zXSoTx*;TyjggFal4{!@g9~<$5_CWCmU;Ge2y`9Z3V~yH<#~*ydDL;IJsQ~4w_0xnz z2P$jf_DH(1{bMBpzA%N;L-C}F{Rnx!DndO1_A?D9Oc4@od`S{Y-vcjjPAH5bDI@?& zt#u5Iulm2z-bcqi(u;biDC%B!A|{&Io*dMsMq8fm=63{YYiX}i-iO}`IM=TS#ssfc^xLW$Kp_h-Uw4{ii)KO1%g zO+O#v#?{q3%LQSUjyEu2){gh`pTI26`I!bJ7wn&B*%M|EoTCBI4H$!D%xb4*zleY)v8QAlJ`_fXytX46;9((`WpAEl<{RCM1PJ6^^H{Si!c*M ztXw3lpIDhk>!_%^QF)hagE>1ORNaeZzLuHP0$0@n-)B3HOx@PfOs1^N-*LaU&&@{C zn8@;Rz;3utwuS?*RTmChKzt2t718Y68qMH7n_oDD1>M+t!mMgm;OY@?9)Q22!e3Po zol_<~54`K^bc$t-b?WLdcOGRXLKVq!B;qW$w}1MJhuqQsG*36n>vGM6GNDiZzZ+q)CglU($nLM~?{E^xlTc1160F30nL{!JFv zq#H1gpu>T|S6(qr>AXi~AUd|}Hr z{5r|g^3{dOdtQdz4-tCXL-Vahb1^6AQQ%hQaYe%&@!dR5?oz9Dl+&2Wo*@yz6zz0s}NIJ~%dX0>XjJL7c1<&|LVS-a|) zxuXm<2GfzGuThUo%2i1;X-)C0yHE+vyM({Cj~GLM$5AI6G)F<;CM`TeX5c2_yw46d zN;^~3ja|~*)O@BB)2B<6sgx4*$X%ET!+88xT4 zIKpG>ec!4uP!hz5nAUOJ-fVr}+#B^yDt9@BX77#*ATfc29mDDY{+){spS)U^8*n^j0{rj;vO-G&9?itah?Ri~Es{j;@dc!&zr2lx4kq)HN1r-MI%c zOA_FuOzMijT1cHFv_XO%egvIhD{RLQ+iL_EHUfx#1RU}}9Hke%N(KWE!Vn`+MZBW_ zUOcR7Z&qa>rz((34aBV$@W%1YU9JlF7qkavo(;}E6WZP_c;}q1AP`>mid*oUuCY#D z*pvrXzlsm?Y9r>VYD;m<%SbYbO}gSaDTPo;7SNJq9P?l$CFgoV?*#Hw!)`_2pTA(` zqBx?m)VHH;0P*i&<-g9!|Fe)5a``Tw{|!?T%UK&Mo154sq#28lmPS$Of;0IJ)MvPttMurBq$Xq0Z;|hb>kam*(&wVL@%rcOlj;YOI$RMR zUFCiWxS_ko&NN=T!R>&2K((%6R@%Mrr*QryKS@y?=lW<1{jj7u8VKc6mg!0Sjj8xiRK; zjn0I9(%LQi;smu*7F)2D)L|%vTRTk$6|8*|G(j6_&M>>s%g=`DQYx$mS~WGstVNfS zj+BYED;x$fECZ@^3kylMu{+sDux#BK2^Dle4=W-1;mAc~sTxt0brap1r3wCp2W%-d z^PjxXtGY-(J zZ=Y~+FFBgyGT2qo9C^QP?G9t5)o)=w2*bl+SCZ(g7N&EJNA$!|1NIh@vg2!p{~2 z$dAut-f~+5v8xu$IZIx~j>-MUB8p5PxHW{^icyJe;$=;_iX64P67?P-50K&08g>{Q zP$h7HyS54e4+`K@&H%l_+@fU;`zQ0*BGK!flpmy@=M(O_nDfyX67!4KksZRQTk{w0 zsX3c)+8N~Rp+vtH1p=>jev54XM{|^XT~OJbv(_>-0fpup6tHbV@m^S%pdjwP7@RjA z{x)cz{gE-=10tf$xZRm)_=)1X(HpOjIUMFt+GZi2oBRA2JqkMP6~Xi!E^U=c@V=FB zSzyuW&u1n>$ppt;n-^Xk)+22cu6nJ7fN!-(D{Axb%fZ*m* z+E6w~!$;*{Ha|^NaGI5#R$mC_;j%J&T+nEuZ=$iBLs4w1I5Z_NF)LcC5F|*E5rtE) zIFcU7jKrJJ>Hx8_9F{eK;@W(HYS#6dL{x?@ZCt(kyh5O2v&EgTFR`4LP0#pkN?UR= z6{TrFnu1o1!QgaKty1skby~x%0twh)y*l}9DlJQa@FyKs*X)EmQ4-qT_IMC)wJ!+N zdd%$<9R|8u794%0JLixQgGo2qb%Frpy|{52OKfx5IVLgEuRlmkl?tlL1<4>rJo;-c z@u@CR(T3KHr2Mr!-P&uDQf8~<82cB@wf3LNOBXeT6@C$I0^=M$KYt)+aN zLBPJ#t6G0%q!ENFgNZ5d;ygjya`k<_QeKz5wt*RH`r)8FL#9%Zmo<5kGe`nL&9^~o z!3b7|`(*xb7Sf`kvo?ih+c}_w>g)Ul%9JuSMo<0z2+C9zheETa29F1+tT4qnksVdz&;XZETu_KrzUJ<_T3m=(|%aS%7 zpn0EnU^eRAl7_UJV{E|?F5-C1#>;wj+W1|~wY#0qe{K(e4i|clz+3g)oBapS7SNf9 z-VYjc82u(fHX}xVaLo+|Aa~%r$Ag6*ym4cI?$~h?r-EW3J$nK1PeD5N~gtGf+v^mI7)fTWu zbfQWlJr@YK47y@Qg|dLMSS=+W*H}Pnjhcr21}rd8!=8q({ricx+=j1(-@kp5i0;?# z-qww+-5sr8=g0N?^gl+X9{kV^rpmkF$-!VIU2X$2GTIK70$UQ)xAw${-LLGA4lz}J zN^tF#RjGUZF*(kU%;HLDQ2D(kyldB&E}40&1A>oeBq1e`n{h!UyH2)>eT5ez_wo!k z7G^lqHFj7Oc=@NV3-`VJ@WQkPZROY;UH?#Nq=vJy?sk+6C~g~FK2Xc%J$zOXE(IjG65A1KDi?!!WSOyl-( zUQb|R*lquU-3v4`4ey$HyROYGJJhVa=aIR4=vt??hOV%=N9u6TN-gROP2mNnl0tyY zg37y?ulN9OAdambfUkhbZgFpJJ|?f}@e|PN4z-hfMVC2l>P ziL;g;u8z1JQH_Rc_fi|U{IUBY$G*i6ucQbG6YS?%aF)=98DIL zf=qq6eCBz$rv|NacW^(PJn!=P1@5Y6bNs5ui$}W7)=myVjaU063Gn4Mu^ewuKzymp zvpc6y?#=aX{HaAVN7wFwEznwv)XELe*Er}guct@3r;j=4AwBpZJqMt#P>4?)u{*iqJ33iiS*wFEX!Hy9Il_`TMY#yZQT2m?k*2wxRvxZljPzgyzbiF_t~s;1)bB z1)H#=kHlu3x(3T`!Io(uIH8N49kpaJpgn?ha+oomLArHoWfGK&5VZ-VR`sK-nNOlU z3^i=)qD*qZiK6Ot%UOt`CAu|iWYHI_Jk?=K5k8$+mnrAL`>Q?LirH$f300)0OH=Jt z?Tsaxq=SXcbTR{t&Wq*8XHsn(-a1(~s+YPCmrt5Kv#`9sm?xh(eR66NeZ0mrQU~8- z=RIAr41XlQ#ta~lDZD^dlFAmnKg-sDvUnEpXa=>2D#17xX33Tl~V`9n~4PEBY zj*T&yV_q*~li|Dwru4}03s4qFz;Gi5%B>ROx0J)#&Oyd46yX%HC6LyXj^!@t&J zBWQ{oyP_v@7-?T80Xzg@C!HL{duiFKF3QMagkOfv%$OE6y5RKvwRvFmVZA0;zGr+4 zx*TCPgtIR!N0M#}{qi}=r09cMOM)VbRDun)JO;JIJkpH1BGp{hR0phQ5VqwpVu>&) zk%KNIsePKDHMAXG5X-K{kJfG&v3O7^Ye=C7(j!RKilEQ)&KS2L;RJdhiB5QAB%3qb zwy0EbOgys@!FYT`e@UV;OT|5^(Tq4j?Z9J8s4^Z+T}RVYnCae$2|5y-e$!$Xu0_4A zr|}Ea#^IWrVwbkX@!4Cl>p+@C+Gufpy4R;RH=ojfp$_U$zPu0ntkk#JF-kr!f$aD) zK?o~|)~!qC)}WI?@(Fe!&ygN>wlSe8UIm{D zE};3P@f>%tX_LUT{#5e_!rgE6;D#o7M82IU&@oL&tYIC`VV$Vepy9Yq=z*@-?@x_S z+h)*5eNc}*l#P9A_nR6wktC75b4@Yuq&eg-CmHZU(_QCX_I})n6qGKE|C2o z_=Ubt9!b{Rjzk8J3P8uF*#Uu{!uHI+mv-xgURguerr!v9mUoZ+8NBptaWd34{|)f(t3>D~dj z&vaYp0{CtK2+KEmQt@zjLPQx@9Rsm0SBox?ZU)_7O5MtI&=Cw@Km20)`ron{!PCz| ztd<^qUp(?2dwG7}UtYTXP)eUH0Ak}x5F+?^Axo6fYLnhxZ8R@5E~Ji+siLHmhMcYg z-p{4ET&(D9MOwBDz}sNKP%FF6$F0irBr-yId#Q~yI=K{?Y@=4^xohUs5P4gauB3$)77+uLXJctc(kXFxL<$yx9hVnT>YyYzr)BX{wCFk0J zIeh6*p1sbcPGnl0d9&y+KWL)8pS*P$7BS&xAg<>LmJoTh6M9R`KlUSp1!FR^YNLU! zET+R19ikXxe#oMQTW3*k?#YjSm?bwIJ1%1U)a9|FgseGyrS7+%EitL07o$q?@NVO)w~Qda_TC_#FE2!5aZ1(|3S}X;aXs7^#Um zwOl>Xyzgc|Q|;Wj-@rI)=RG5ZA}Ml!rbsiZ|3I-lUMRiv1;&X^;T%3lY_G^Z&u@)M z!fZR=#n||J~2R_ut;# z{|9~Y@9LwPmKxR?#*SE9!tn6uuqq)Une6p&Vm-}4y97}3ut@KoVGsi-(&BIsy1uqW zXtXH$BJ*o&N3-kJc4mwFT$K|8^#L&zorX?T-7h|eR}Rcz;B*oreT!M2Tc6%XpPw1O ze$xH?`mrbRNfz4U&JinSudxdK3w$F`_ z&0us?HeCI2C`{$YJHU=q$6<6n!7)(W-q{tufRBJ%`Qun0u&7 zzy)%^;WWzfh@F-HFu;h0GGkC>>~QR`<;o2rQ4!HgHCmlOgZ`rI>H>pcIJ-kty`o&_ z+9SAwL6>oJ6&ZUH8Qb_RGx?}aBtg=uE4A*Y=qTwM&)BO4MUv9YHMO@OEM;b%jJ~5( za4_ttx2|o-q>87RXz8}~%Uf>E5%5sMUpSDq2juvq+T>E9jmfx)(;}IlJ0;t-Lyq1; zdn}>WEO?}CT~atHk!{GA$}AJj%~j{~^|`Fq77&=!hSn^%(}`2DU?Dx55y8tIJ35L_ z-=`hg<%W&$u3&Uj!Yc1M7kRS20!LuDe9{IWZ2?Xy`9SuK<9+Db`|GRHF87RI1puNyN#mU{~zt#INrn4R~72gXzT2U@^IORLEb5F09sb zFi2SggO&n7iRnOU5)D|rDDmgwO z)4OMbxjlEs!#jI}_glM%(_V7GSpyDj^Ns~$^|FfJ`X~$aJAY&2MQpEkN##;Be^VbK z=0*$H3dqby@$JhqO0e_OV8 zOHzN!;(Dwz-#0_Y@{s#<33$t#T)kGbQf&DvueWV`YY!F6mk8l(y%RTp6t@o(gW1C& z)P4W-4!w^bcOOj#o`#Wx&>tw?FYXa7pdX1^%Q#n=WQpu!Qyp#({-7Ff6rpye(Ja)& z-^9ukB0zde2AJu9R4_veJdT#Y5$Ql`WNFqcP)|aC5^|r|kUa#4ea0?J*H>+VAtbQK zU6R6rRGZRx9pd8otQX}P1fakSuVf@ha6APveSO7ry|w`LN~MT zVN)NtjDaW<7hEY?L5<@G%C1Q)7Nj5E2S;5b-bmA#e7k~kBWkrlu<{!8q~`prtra>-ulu)w?2I%`aZ9><=&P4^_62oUi={XO`v{ z(;K9xW?O}#%yp@rA2IpDRjvsS51KLK7#L^auhdsO8S+XQFJD*Euat((sD=kge4~Fu zsd)L6xddBc?e8rmNP3|;MWrsME)bTJ(OA7gZL(}4$b`NKCoYIw;Yx>6weSSpiVmZ- z`JF7z`!&Rg+!bhvN1MXZ><1W=WAJuIgAoCL!@^^1Ske{!D!w;);Rc$6eHAV25{Lk- z_Bd0!5w&S4y``bv0vKDyZ~qN|RC}|1yNJ3LwA1! z2D$A=Z3-i!0?QQ;(dYQai@-)Z{*_{%Amd)yR3`3P)oz(OUZJ_4Q*EsXwc+t}2ZuGe zLxRuPsLLF{pHA(|*dye+cQ{m+T&n7s@1dFXo^N7SpA^vyBurOB-Qj%Y4<#^)JG|q; z*!g6)BSq9m)ObRBfBwPk%_WPycYS+x3jS7R(EXpBlYc8S5dV99*rF=qge3y+VP`>#X(?z6~$m9q3^+T;3GG0DK zc^2DAQYA8O5)R^tnlTkhFa#LKwX}?7>DHyH%gopF?a<~2hc|Du!gLn8kS)4Ix9tJ; zF8V;0`&2&$PajX9o4qa^6zBu#HAOo8{SA1e`&>T=&@I-Rzkz&@~OuVU_aKpY`#g8-q>krUsBv zsHt}a0ddsShekko>gD;C1|U_StJL0+bJW#FK?P5I?AH5)tTft#sR1@nT;&QgPgD-% zmS>LFdpP|v5c=ik?=~Rk79`g2^r*=E9DkyA2Mrq2{$p7Z5(krG~& zp@kZ?c$b+MGyG_)j()Z%AJO2}hEq{8HVditm@|0j7n4OigyEhvhv_}n5%7shR^R)# zfs_O~EpUm)06 z+3c1j1u@&1)dlH@U4b63CFr+@3|LmLS23fb9xM?gxfB>$@ z*Tz&(lw{T>=GQV`5o#pBN^-h8B3}Ad9dUi^-&fD0hn_;zavJn|=y^X*g8cgN_W0`C zUkLcoZNz9{lX})RysleTU$0wGKh{q9tbyE-GANnz=i)@WX-eEa&&K#!KpBX`tX9JJ zbvU4_+~?vbyY*rahJTk2xS$j{_7a3Ka1bkd=N|~6NPxBu(`Pf+9GCZ2mNju_vOan& zkqbX|=Ja5$!0@>B;X^J^>?}TRw+ef%!jtSEcFu@JiEg5nGK}xFG!@RT&d|RZYMoTl zJRAhj#tEkd+dvs{a4I%SdMER?lgvOv2(2@O(rwD=f9JLdIzdl{XY50}NEqBj82Tn? zF})kcs$wRYYR=6}5IyPWDieE$_DiQ`p|*t-B~U#K=E{K57@%)sPMn7TlC5kU9$I-7 zpc&R5+q=K2y$WXY^$rzeWDKaUO?7)pI)>cT`4Hf0hBLiQj{uSZVT4|aIeRBX9aqmV zC7D1emC{>3>?7Jh%S@p36pKZ*j*B26XWC{l+HqGYMmQJS)geJUOauQ$gofKf`x25g z9$rLjYd476aX;8DoURv%D6_6gZ;e95gU(4MfV^UYY!gP^}xW?v{x0P8f9TF&=?60m5{D@6CYw$#5AR^`j&uYwioTO9-)cK z;t?=W?ZrlPVCoKyVDk20OExR|)6{uWfCRLJGYOvgk|`0+jU8pnkdmUPxMj|{{GQ&% zqBy+j0!H9o%8yRRi!E^8oZ6;(SN*K1lfgVWXP}l(x+)gp@`{DRC@0w|ARD`_;OgY% zXu`p^A+jXb$tFi+acX&rB*`mCN`(Bl5Xx{P5~0ubi!i0I z%IncZ<=_(AzPAwacb$rNN?|&d)DnFnR~tdq#*Qns_qibJ6*R1Fd`0b&%t`DHc)VK{ z2sr}_I0B0$(rUZM7{@^0-slu&C`7cS===ty`wftU^E1E)?ihm`ny=#UX8kKL&43>w zKA(|$5QX9wy05^BKN+I76O*Dd7ZiT=-btw5CMyS{;=;`G>88^NqH3wBqZ8W6wDmZjT2l7;qo0OT+}yOSsPdiV-Y zT-~)C_Pii`hXeXTHUU<4POV-f)CT-DRjpoDYzu6Wo`Ehh??0>`jqk>{#F*Yy%W*JJL4G^bnHJ-VH7YRnS;=Y^mVr9j2lDXbz8ode_Cqk#kE9s_jQ^Ekc>8;-te8j2q2|ZF$N> zC{X%r7`C)ofJ$YeY)ChX*%Ut-7ghC;Lb?Yf4L~i#Urezk9~JWao}}o6DFC5J1^p8B z0)~ugwbKms5uNS@y)%r?WTa@n5ZR=%@k<+{2*q4J3lk(pN^1gVepeDt|5}n!`AL~! z1W>o_ww)kvDXxU_-mK)}bWlw4VfZ^Pu1znrw3O4}R5DhKy)0PI`2jT4VctKWJ-~(C zc#mEYQxw{I5CO=d7#bTyATA`n2zW=j&S+dml4#GY5JS`NyJtxuRH-1eY%lll{h2d} z>s+ThGaasMW+=cQoHVdQ5&lcte*CjvW3&P^Nm$01u`!|qkHs&#l@otx{7-!7HFK{E zrhL`Ffy0Is^GlI)jS!T@T2eC}!aI&~ z@Arrl-Gk)1hwQuh*mev7Zs`MF(}zH``$Uaz!Q8xHC}o!_ER?B>sMav*>fe@lgvj^- zR%iGk3gU=MSVO~5$8~{3Og>TUYwLP$Y2L)wlief6X5LO)1C?t!VK%lw%5@ZX7elvt zw*sztRwWH92}=SUCRq9V2PNFk-oKpT==Pc|gx@vI?%y`){P)Rjc{^(lTRR&I1M7dY zRQYoj6si~>0Z+jHI^2>_xC<}0<#e)3eMk?^;hT_pfjL8fi<}VB3d;@w#5rT!I zczbb-yBoGrLX-#tq+Cr*Ubh^lxg9xqeZ5~l=wm)8oDWqIA+}}l(*%(ZDKw8(=o9*l z0o^bTwhAx62l^$UD?}8Wf@gUeX6Qc`+qf+vBb|>^2~KFHUfRiQrcBVu`;J{|F}5o$ z!#F?!vr4Rc1anvFR;GcE-#nX49jA$Q%l_L z=u2)S;*nF7plWR}+bBI6MZAV*5?ZvK)K}+uoJ3!B`ZH2Xo+8Y8G|GmCf!MKlVt6=n zbep@}F)*+493q7(vh2!@<||h_Q8~i%lK@VMYJ0!*4!eS>SSpny8ziW!HoqE<1MvTehfAQCDPcya^?jmXK!WV6_00#Vx_^tm?2#h zu>!ahJvX-i7^J3zA=t|@-IP4H_7olWcT?N)eOXPkCRrJ#`FVP;wE#|My#Y&C1B5cT zmgTQ@sC{5@^peY}EL!&Wsj47hU>^BCW*&#lnfYxIC)6J2aLP7<+ADy&pSB@C|!4ctAK5DEs&^k@gvcgaG@&gwf9U z)QI~=fH_d$V3_+h!I7b~CYB}p^^t^z0l~eWY{Ggt_^E%Q#jj>whj}}BTjvi2q&fIy z*bao2WfQ~fDU!8GolB^)@F4cdUJ>{rKRRb}t)*;Gi3)f$v`0}U<;T^8jyxh&S4=WH z$vDATx2(sT{h0u;brjoChky3Z=;L0>Pm}XV3M0FT>p!sl<8)gsLt7mC=Fvg_(}VM0 z`+1oEWiTLSXJD=DVgK*L)N+(>|8aQn#G!P?aGt!8up=Y50O@3e>xqH`FHmE|vupG7 z@k}~#FZR;vh!y&!@Dqv_?Kk-)-}l;H$oEdOcCfX*W_!)`_*}o@<@EuOA6Ni_I!YXU z_gxzq@Z_N(3GAG}++cqb-66c&x#b%+T7ote;rh)I3-gP0D*Oc@+d0-LwiP88D>% zf$MCz!2=I1h*UPLI=+t554-Jp8jilO?K5#tt-`)HvhC7dxwb?XSD`!hx=pTlgLSjw zj_(vGiz;X*bH2%gW!`91X4E!7?-Jza_%;f=lUqCptE{5HX#uE29y=5EUbW*q*rK@! zwR9irrqm^Gq7>Vyfke1L2y9B|H(s;>igBlTCR+7@gT#~`F)e@x4+%N+)899il(&{o zloH=$D*B?g5Ih^{0RFL;M6JDCN^htSCxZ^zRn|fuOAMhd)vy9l1Bsuv%F9zB zR%*A%4>*KQuuLw(bo89U4e}A*3pLCuFYHCc1%KQaj5iho>kHwtury$R?vyw02Oxy> zPK!V~u4#i#>cBL)lsg_P$`^vZ~+ZZYf-X00`WDpOcD zh=%Tk!Q>kIhJmOM&s?Zq|A$JXL5XwFYm@@C%1ocEuS`mWu+&1$O~N>}vZZTUzWO)y zjmYz@TQbiN-@nd)V!IV$i|?(x`nQsh?7zH~U2H8}4IC{DoK619id6aExBsQVd_;Li z5>Nn{*QmAX#SBDX9%x-g$i0kExsgO%@@pHfO+d`mEOkR;05^ZPJUyGv=0dBXK3K5e#m4y^b9m?hr`j!~DshJXws{I_@4d(b z&kC=P$RM6Y@nOw0Z}2E$Guh(pnNkYc+$b>s6DRIiiBLNN zbcQfTmE!n2M?3+Xilf6uwVRHcZEAmLFOF{)wVNKwR*1Bl65|xBi{#a5#vN_^g^F<_ zackVbrdOsoJBQ;}$o_;-)+{J)q)#%N6l#{O zCD4ym4+-r)uZO@Z##IObiaF_;F@;{AtR0|{6UP6>APe|}^w0zbCziHJpCV5njt`az zszwjs8Lgm@#d`Xk98h!L3&RCpr=yg5z6JF5*OD6Sq`9blcdc*y?UMfMaT@>UlKvw* z;J>V7&G#s@Y!#G0J6%~mCQTNZwvRLf=S0Cf)`O%rMq6|+KJmeb5=ryH;!x^rTXk7B ztRE#G;*jBjG!LjAFFGJ8_?(NYf|Vx1VfQ@rgqmOm#hm0!XVFaWV7>f)uUj(Uah6dN z({48%r@3CZ-|w~AozJ6dJ3p{~MD7Ct8be!c{~B3zTx+3iAgs`AareD`*A~WV{zW1B zLjFk@q$0?z0)EYaXh01RN7-l(dbGn>mNJ9i9`#6T9IGc}@{P4>(QL?vN$m?ka{Eh> ze@MqP)pCa#Tz9#!>{RvBkn$W1+x+c(HxTfb&=Z2=Z&>HUPvUQ=UmbS~ey zz&Kl5odEG%{Jlt_o8o=+M-YF7NJ| zlpe+`ESOu5n@4955t&jhu_MmF(pWKzHAN&0KPQ`)Vs1?@rzgZ>RirPl8V`rYJXLlA z0C;6}tiY3BOBP4pY>($B+{D3>N@Q%Aj22D=m~$4KfE4m@C69wwb4lfNC>u&cjAO>6 z6~`#IlJ$wN0J6SIir)ffH*|{t(%|i4@xBOZvt4@1=6nXrrg$-D3X6%sLfl9hCsNjLRiL5F5>?1LXDhB# z(_mbHy&22&w>p-0eyr)Hz1}1IV~nYm~`N>lQxC1 zDHQ<2rDP>^)R-B?&f9E`lJ3GG3XK35M04&ex`D|wS~K^EO3SSDC-aAB;e_$nawJmT z^MUGiDe&&BrzdOUw6z{G>HoS50CSiCv)C+G zJ}6wQWd{D(YSLAqN@YzXxuA17E*O{2TX(FCG-W?9H4)8#8cvajHH6R2X!4R@v&-q| z8J<=cjycp)(ypSnjuL{a7~?x2n2m9`*=ys#BFhK@#|hlthe1L$`5}h_Rn0W)g){@=UQnwm~R8&Pwo2QY}1WzHuE14yX zt+lV0l^%3jK8R3{vz9O)j8Kqz6_o0<(ro*_s`9sDRm^9mT*PnmBws6s=A+2=_V-}VM>2Kj79^h(eNA|Kw#z<- zG$)kEm#8RThe}kUFHtl@aQDF$n7d%mD{N6Y4q6P9+}%z zv9VUsLgJE2j(|_#ketSzGCj)YEkmC*YlO9s$#kkzwns9#c(KiZA4lon-h)1lA@gt_ z&JFT*_m+q<^%&N!IHK1&TBvJP%md!)cl#wOGL;<>XXOTmJYqxl+i?}&2fuxNm@f`q z4XBuFLP*S1+_IT@gp)3PsDx=+R1t7VB$hLgE74{vWg+F78WICAL&Fl;&6qvjfIXTs?U-~;n0k_u6-S z9?g#5V@i~2Qa)a=@vS0Mg_KCm$s5`Sxj`NWHHAYOCm>Ch+INTfkB!h94A+Yd*OTK6 z*z57J%ORE3WDmHXTd2X?ef@s{r1=#P`az|*UIh`=?}e`xtIYS1IQIs-%4bNDlYzCV zj!IV=chYAmPnsi`swK^8Z!pf_EbK&b4Q^X4QoiDrf|*dN%>EP`D}51b?~|y@=8u;K zU{oOzZ*XcH}?^j{B=gP${i9o-var~Gy4ieS6f z(;0Ee_BeZe@Ox+G!v$(}kF|N!-$Uq?g7FX9Em-e>e6SG(d8v!NrPq%U6o|<} zlyZ@6e`S-W(t+1~mXIgVLF94MNFMhMYhwv_%+Q`}Wfu;XMo?;%l&h-9Ru2Q_wj`mj zfwNtf$E+}g8)hdWSe?>iU<)K4Ierj%f~OK{`^4~!NI8W3h22Ct zZoNg^H@Ax<4AR%_RlWKdlc({cbDrf11dO^*Wd<3uzDtYgWwuT8 zJ?3tDcSz^TLI7pzvPXGtSO{4?JMX6quzHo0Tz+V|^0mUWd7PAcF{K2rZASY@=PWN1UWmY)NsgH^jQ5@7!aN+A zh?q5#%i(o0&GwVS>}5JG@0Je`eY6KZP#huwmLRx_U>qGb6?g&xur5zcOlO~tWEkEz=Mvb#_|vv zM^>Y5BorN0Q~NUWowLp5#{A-tr)3W_w)f0_E92+$igf@_K~^Wz#2xpp?cES)rn)J( zv{n_S5OH1BX112b!WBucVSEXd9ZE+7wQJFBC<8v?&<{`&v&>8$n>$SzqNyU*F+{9V zgJ{X#S_=GtD2T2H{^CkfAqyD}e^JJy}Z$3O?RzzQN}wUS5L^w1pRu1RCY^LSlwN}%_O zu;#N^v?DNf6$+PC08hgtI2urbZCY;iX}0&rM$%w^TXr-CzB~d>)$3#{_BkQe}cvaMph=yq87Hs z{|rAVQM0l~T0{Bz)?*?~5@Hf^MAp#}4XGmv^}$8bGt;aMFTel>s~`*#)*dz!R})s@ z7J~&BizSlaF~76-=7U=u^prA@jWEs6o;V6}nv*8tz9jwbiu@Rt@N#6gGMKM9)EXIT z$KfZV=e{G5J-ko1o#s%~_RpM=)l2 zi(lF^^dAYTrXMzT2Zh~JVEr;Y-}KYL;&j^dQyemK?{2;?u{ve>BW`AKxB=KiiwAMF zkDo-xz%hJ8pG207y~FdNw8=Hm0WyHTexEbyYwM`aBgd+aE{4k z)Fne)19y#oE?O34pWL#6@xNGm$KXt~t!p$L+fK)}t&VNmww-ir+crAtIO*87ZQJ;= z_kQ1d&hGo2Q@iTks-!CQ)bl3`bImd5m}8V1;I(fITeChCi^@;!6OGQoGFsfU;N3QH zv-qmJILJ!>k}%_<*b)I_xX0tPtvn2>NIk4uMdh3^qL;VvYD?UCnc26!nGF!4)EiYZ zW|<v@fY^e!x-_$sBG2m_UJ($x7YpXzxG}pz9NxNYIf$32W<$R zs%!HAvavRd8ayr7YmlL2%;Z5?mf>U#X(x)IR=~|`pej^?qE#E^CIUf9Q z6)(5B8QlIVD;v$cwz`fft@>7rm@qDEg15sG-+Nr!l1A!W!jzZ(9t2WvHU5o7@8@D| zrj2Q5Vf%iL7^Yo0uLUtU=vH=X;_H%`MQ~C%D;Llmc6QW*E}~?r^$cU;Wy5j{8ttI58f#LHGfk6q%5+@Hojb_HB_lA4X*q0nkjVC*FVm8l1dPO~sC#Ov?^2U?Wp+ z&nKIg_T1X|;G(x$26F+J@2nc=;W{1p8;J7MD6*=!==0`xK zDV1uiBMgs-&i%CFrF~kP>tQPk7p%-9Vq5Eg90#aV%}1|Uf|j4n!*+NIJ?xpdl%AFY z0;3zYHWw(jCyx0T$Y={rOOziVT-*$3!WO=wK5e2Y?s*Yb2eei~m{3iM-Og-7B;fYw<0tbQ7s3^jLa#;}|5uHM#5P08mO@L*YhiB;ky=o|? zlb%t$rbXOzrc3PO=zA{Zm0S2G(fKCnREI3khj@5>#}Nqp5tI%Pl(4+*+rJ|qNI)iL z#PN~aam>+MA>&G$4j0^{X+rXr9(_(O_HhP{i=pXb#?uSiWo(1R3&(tueMK0h_hUVU z+kLo$@Wd9na?&0^OTOD5WDQ_?RdnlS=ySRx$zkhyRdXwx6GX+mfC=u0hsNrlABDnN zr&kPyv4UpS6Tt0xt=_^Fpq^t9^|^r%3wTm>OG%!t%J?~MpslS;*&b8jTw5rFk`_9_ zSD1aCh%N{dR5BJ^8i|{K@A=j4Yp)ku0L#~YR4(5$*RZrVv)gS9b?$J&TL%x|i5Z|P zK$;oCN1mu{%&0A!TWIfq9fI#j+prnPHV4>?_teSghU;~E71iuzx5MB?Rk;dsMY9QexJ0`8LK6Z(Rd!&PTE3DyyvqKTA6czhd1hCRL zgan1C=$ybN$l(gK^bn}c+C_e)h?rjweH8VGCYx#CdW?2_-994gP`S+t!juPcbo3k{ zFI;mvqE*<~TpuAPMD2(}R`}!L;=^0sX`vM631f@G47kS$caHi9X;DS;VPJ+h?b{oR zd>PqX=ep~yetJyN>KofIYmMx9VqC?XqFxd!X4^qON;I4nYtiZu7S>OZPpX=i>SCP zcXgq#%@CT{JwBm8ur$N)6+_!Zrcv?Vkky44U2{HhpB(h>h{6sX0Q9Ni?25lfSD*BGqq;I%|+kXo5o31!ltj zbhN}kr73-G%bQtB;vlxRjBT;@|I;)^V%=_6k=E+r4XmAZzb&fOl*xSY1hZ4=%QPcTc` zFy>Rfuf$2VM{^dGflB{c^A6*bpqBfw#(pj*Ghj}RDpo{-zI-%fa12b&0^Us*BgxHO zn%AAKi`+a2D#BNyMI_2Hbcyahs97Udeo{ekgU=-^T*{8HRcL`x_k3L)HUajq|63% z*QdKLQii7#rC-L{#Cz)U$0Jg8z9MdVTn4%zi1-d9GzTh zHc=CT(uB|yds6FRZj94XT~g)ADn9(U+nFcyO#6@+;M;GXi+qw0UHXOOh5l&;hZT6aOQX$M3Idt4P2u{2cne`?~1oVsY973|ypHXFd4HjjcfbAxn$;&3g%dp6*+$-#9j0aVBmPk?Nq9G4vK;r}vThC9q~54p#B zvp7^0IUtn3;JK!3A#laB>cxBKzUID-6Y3<;%Bq(T)y43Ti@|}5Sp$CZf+8e}eTzW~ zw#@=3qma5G4B4i27b)~=yMQCY(TA(4dXe*q%$QH4Se|yThh(lCC>JewDW5&;pl}W! ze5gb)G6HQsVm@87TnFd_P$V1Rga@iXa>?Cc)ZaRANCoU=gY!*ik_(|ez?0k z3B#F7v_8}yp-#7O?Z|T67*Y)?t;Qnphq>>aOp9GzLk zhO{?ZQn4XG5dd~t6HrRn^#gDNBax28fLnUR6@gaFRjnHXl#WbpX7fJ@vMHX_R$pY<+2TNkbKfx?y(Ow0pbR zK|}>8;%X(S_M49Y`Mm{Wo%`dzcPcps^g1^s;FLUwUSW?wpI&oU5BGu%h7GDuX=JBRC8oY zDW?>)iNF&OUW*}^#WVWr*gW3WPllp&brBBsoF(q#?|hWy2FjYu&rPUlt>NA#qQy0}%&ZG=yj?2bnrLB|*}*gZ{XHmwIzq++VWqhZAOydQwB-ER8Bb5MV}% z?JyJ4x-K+!Z8z zDCqEZ%V9ARs&&{bKy|T?9E!ssvu{jn*ila(r>z1*YY)QN14R%CXR)-f%fm1%`Mm2h z3LI-*9#ZjHEY?yLgV(xA#e7}H8AgjvA|~~zjvs6lLYu!DZO@FYUs=ZNv) zMokiu|GG$m(P;9y5Oa;u1Sl=T@CmO9Lg> zRLb%TNM_!(?7aQH6ovRV8nG;AM?!+EIKx5RbR(oMnOPp39MMkBcY-S(E78m@4K8>0 z^$lN7Y|ivl3vyn=6>D!N2?|f|S6`)8Y#sHOx8G6vVMYqNYe*F9V!q?o_68H9pebNE zsaMpyiXag=YW?bnAida@dDug~8J$A;B-pMTqvP)$umblKO(~TYI``1H$r(|;$sDn7t3@o~^;-mwWxg|^ zcnP;)p1$m)FY_TkaTXDf$6$uG{A%!kZGd-9v#jU`XRpe;^8y0THVIk?0_$>cCR3HI zN`pbN$VbS*qcx`7l+&77K1MQ8u#cZ3Hbc)tR-};rftsFwT&}&O!Q~P0Z>DxyuZTFgCO+r#nSPK z|M2hSOh@FSC1x{;m}jW|2}Q}tpj_KH=r6C1YjS6w(k<%=^dPM-w8#q4*GMRfvuS~Z zP64OMXIK45G3@WHPSG5N=YKM49XKEpBYwiB?O)Y1?4&q+*b!FiUMOFh%xGA_xhf-= z`c-qlHbXHJs=C}q2X;X!Hw@{iVVz&D(36qzJ&URXSLEvJd<(*gNDT;2-qL{K8_KG` zOvtu^_`pQSxkO$@r=4dMpXV1Koh|6I?4E^y?Z!v=jV%Um5bbTIAnJpAhh(pA zmY0Z$t^$qo5$uoBys?nP-Y35dU=8`dy}kcj;O*aP#eX>y{R?LODKaTwYV=t^w*Mai z1tkd^tWSwa5*%KJ%(ff|np~-od?!hH1xPCae#`;q5+qXCs8HZ^bB5*`8}kX(of>j2 z-(HJ>2L4a8#B}QzywGoe^RJ-ZP?u{%Ob`JC@HI@I+^PMH3$BC50(QOwzv(x_&(+OY9~*l@xh_-YlX6iencZT6fl zjG52?d189AhwBN|lkI#4-t*E9Mm%S&9#`B`;1(^RhI}+SCR=sak0m z8dfZ)U5d<}?#eM5_eP4^&|F6yzb+{ObPQGu8JFX)bHD@Z?H_k{5Vo1Y2y54K>D}}d z1u>!sQ>5!_H4v{EV-MT`eQUuXx6;s}oT<)G-=7QupHk%cfrxo6=s&C_SLuk$=X*@h;~U!6IaY3P z2c6yyQy>g$#`dOWE2Oo-6r`r2={@a2Y{jOn@wlNdZMHi<*$!EfY7+*;Wke7m+>R=h zOmC?da+pN9#&lbX%A71qb)Q7LQwU~+^jXXz<>lAd9;pW#zt8|0GjX^}V)8XAD_69&rf@f;{3F!H@`CeJju#W(C6TXzDEo zoVT7xhoo-z3ScQaKBB1YDFYbmqh3~d(Q!OLcbp@n!cXk-f!zHHdMbyMWtP*){VoVk z8n+D8Dt2K=#gh|Y42*&*t8T^xAggt|1Yh1A@ZVbnqhq7acHl&CbuYmVZQw*6;Mass zi*IdjWoShFY+20eg_4A6}afGHh+LT$3fH< zpYwjx{J?bI-QwFlfIoQR(RluX^@MMPD|b&X{|LNrWfsE+0)aBX2dbnA3Hr^BJOW9~ z&deTRd16z@xDaU%lVq^3gwa>b9)cjN&&a-CH!0P)Thc~WW3Ggko8yXcRE&r7kTZfF z^-&xbBmSKZ6`K}BUFFjL+YcPv4BkHli`XZ{BZ)tWo+JOYf%wlIqW&#P{VP8G=_~PP zkdoCi``-v9zh?f2>k3J_)p9jGbHki+c_r^6@F{v*Tv(1)fcfO)G6*f{3Vv!_CPZsp z^CgJqR|G0Qv`^oa9l{V3l3b8dm-SBvwecr!PlwG&r*e+xLiNO*`GnFe}Wf zm0LJH_V^CO{h^~!Mz>ddqn+A}O!tvA6_YFoJMux1I@vghTjt658R&)7FjKm0PEtXE zCgPMY8IYWItJ3IYFZ%(M?AF3XQC+3Htr<2_Vfrx zqSv#A80?#=)%m2Wk`=?VB6>pvv_I2004blY+?HLc+7>!wpKyA%WtZPa&8ugkOacw} z8@&yOxjxC~3LCFzL+7O_keE?>M9JhoWzgs0B&3uL^B{%Rbxf@)T!h{i++jNh_~D*F zjA{9i9tZ_Z1)Kapd%Ao)NUSdSuh%vei*A=ubmW6@pZX9pKL&3R5G`k}1tz=Ub%B_v zJ(K#3Jn( z5FBk|Dm8$M(pBi9T&BkB@i_2H8^bIdFk~!h(w=$>?cK0H`O)&+1x#7$N)OuZ$lG4B zKJF230-Si81F^O@YTO)2ZNmNW1o~nCBW-@RN;&^#9r62|gU&yOpZ{(+_IE2XWg`Pe z8~gu=M1LwuSs;J5tg#nPjU$Egh4bYuix8}c{JI0aV-onz>9SCT6c1Y(H5wIp934R% zPSyGJ$8UCh4i6!go4}lO1>#%6&S+^VT+FGsygk3|kbWm^TIpx6V6iI?U6HCFAGN`> z=uYZhc)>mZOA}6jRV${M$fS0Z)@#aLBTHHJEYi)Gvl*sJF}Mx_v`Nn=ytnkv?TPTn z06lo~)SJBrA%+}LyfwcOvdV7U|zKIEUpzms@U*DXJw>aDRKd1bD+6wp!FIfpdG5aGa1Wa}+;O*ya~ zgSC~#;LMxMvy{{R9e0lk6y{t{nj}vW9wYktx`6(smSxWoucgGQl2_B?7W+7T(7|+Q zISG3azPwl!-ptFA^cm_KG4*y{wcrtA62%EB%}$uBxo-1zbC|`PH#Q~8evs$X&Ho%N z=TM1?@z0}G`B~lgmlW0SM@#M>AFV&?*Z+RJ{z|d2KR?i)G44GKNEh+qVcpe$HpkD z4&w#x4;uhm*kGJf58F+?sBh|lL13?;2(Ck{Y2t9?pBC`wcS`VN7*haahkkj2^pUQD zHkEXqerfr7PLy6fiB#`V8U+Jv5!#f}1Va1G z2bTA-)}DLT=6oDnY5J6)0;Py4SqIqoC}d&H%6W}D)EfOMge}>PEUx@pn9%Z07mYZF z&9mp4Z4oo82spUFLCPs8!KTojsrGkbm{HC5TT8z9?s!nHF`it7Jb<(&$fsh2hICHJ z18tzIycpN9coPZXHBun?4&yqBBjCl@HthBL5FB?RN`|dCH@v9epg2L=P%H|@8aKs#Bcjp_&1M2KcCHbK2J@#1bKK0 z5U38BnIq?6>sq2EzxOzwO@G`?k$ADHBEhTMgZ z73k0=k6i>T0 zS4{qYW0OL~wa+dP^2ge~fmq8?a9o;t?j{&fEFuNutv|nLm>|DKx;&VdZo|sTE`M#h zH46%ciJ`EpUB=ZEsncyAns!F)^c2SJ60i8{nw9C)FtmY-@df+C>djN@K^E`F^Bw+o zxi&NrTIs$?fBLaVtdtM~#Nr)r0}5CqlWn%}Htq4gQl&|Wsm}VM1DH0eO}}qt^>p0X zI%H$xn$(&pG@5PdR7%$e!!tr(@{_ruY8GL zqga4X@wu`vNyFwvW;nl|+>9{aKjPb{b0+hVk`oSYvBZSxQbsxWowJ@p(lv>*LAskx zPI+n5qUQF9xsj0jbPe+%wNt#HERI67je;&*jjDomI=a+32}4))3XVYyyI?$oXO6}& zswh&V)u~Bx)s(G%v7iY~c}bbUlU20ax_iIjwFLDiMENz@mHpFs*+6Aa@@T)T$!a3$ zAn|<3OXj3IzXcgd3_4{o+pC-ibXX{eCQD7o2;k1gFG-{yTQQxp=j-@7*VY$d7nZGr;!(8a z>c$mEWObCD9Y^v-Z36x-36i|{>ls`~&qmHFd;8Go$xLv?j4jx3+{|MQKaQJklt+H` zQU_z=wl`21o1$zJUW`JV-%nq?j>~n?FS3t*cxZ3pf!WfUxT0wb;y!nkqMv4w8V$rm z%l3ovgVWlw4l(j!PVjsmbY2r#nDF%uvw(B@KI6Vm7{rLaJH9$w^ngE|ob$`;H9z5k zbgm<~*?i+B0%eM2sV5Z-{H^#wqCSI<)fngk3@~-+s;U{NLKJv)WS8IfLxtm=x8Q;7 z=(6a;a988@E$A}Q&=4pVEaW{)O86bY9#3?jDAsTgW!PL&9VEAoD!!_LAI>Ha=R9D3 zwLCx;Xi#}wl7IJ53aBIP4Ma<8gOI);6&D_2gR>UafQu_{LG)0N2?HCN_Z6YA%a(zI z!x&naDYP&`v7*J7+hC2{p9p2A)^|~rU@lYKZ~@`h`e!*cMEPu zqtZMCQImJ~OGlr^dqV9B)d?)aBlN%}yYx2Hu3a+RvxMRm3RDLWnhux|D?~4S#1@?d zQ^^zP^sfG_%*;EU%t1*qaq=dw{{qDKeorT;5~Z&Y&yo&=Y{MB$$%JV7Br1nq36tj{ zfgK_UM_{W0aVw~@XVZV`X9rVkv??zY??wo5oHG?Aj zqU!+KC(Y$(#5C-y$B@$vbC4suDgyKiRnp>a6S@0~Nht8bx=EdY(8VmU%D* z$%gD5RheH)TTU}Oc93VhGb%=HIYC*!ni=PhYt{JN7ZXQmE>b1!00u;dJhcOyFZU}? z!yFr%(wQ&i(p1>7E@LA~*&=5#QHmeye4KGkB6FP0yXW8S{8_|g(INuz-Kye1=U#)A19@^&obfy zd(d<3YUv{V0y)XbLoBvvAd!umK6oGO-7j*~nt}l%7tZggR|kOl*avN&e45aO->JFQ zHnW+ELa&Z}W#%X2Z&IwiJDqPlXhXL$+Fbzeg=gEGrir+b)30*ownI;~r`U$ddd6D^ zrxeb;xM{)VPr97StNM2SEmERHX;*861S^`&!C#4wu# z-LQqHXO;hfQ?>O=_8GueaR5fLV}%1dz7;t(^}KMgdE#0yM}H=ACa8A0zeWYxlL?WC zK9jxEzoqWKCwzSW_%2Es={Yzm*g5Ih8#xHrSUVfp|39Y4h01F(8b;_JnGMCo2^=w% zb#w@~ed~(F14M@=i0r_N%KL#ZaOnsyz--loK!}dAYzHzyhOR(IgMZ1t zG`Q4aCW=0qGVjSxUDgaj9m@y>GDAiTS=Mfgmy2oc-CU52xMaURPgz!2-oTQ-XE}pe zIq)C>o?1sdR#wtYC3cyCos^TYaQg(3UZgo(>L$hSxx?VLHmOKSUs(E7VXpCv82=3B zD9{K-4DDnEv$3>w7y-Ny!!80Zg^`p-hGxuslE6W!`_oWzI~^gn{v@5pgOBu<5KD#S z(;074$NoHH(A0b=OPi`ZNg0zNGR$}>t&cOp62l#)t$B|teM?(0fzrG~l3P@8!lsnOtBU@_1{ zV9}QjHw~U)FsNF=6rrX*FA`=w2GxqZ7$tKbwysPrFKJGKYlJ#tl>-rkBxU7EGRPK? zG*et5McI}jKsp0f544#0)xV^c}Ean4SYie|D z=tXE@pg%z4^u0I;Zo17FF7?U2%NE07*v{OOy{?HWH+YWa4i8Bk+WDoDc35&F2E#SN>0|*&w2oh2$*SZZc zWPJm9vBL?j-rWqJJ8ph-*Ya$4^5jQKaKkQ$o{ROC7fGuk)DjWxhHO}v;@JOy=d~pb z=Gq|H!uhUaFugDpzzTjY#iM3}@7rhxf1wM1vHpea3{blD`wY!y{fx$!CZy;E012OJ zIlip52(7?k4{RwM!yP3|1~Kc>E@vv=WzI#MAKLtE>+hcOmJOr_#Wb#kb3PyIEYd4J zKz26bup`~2gg8m@UhgG~#i&=m24$>Y{UjfFRp@}C zV~g?Yz(K~CQbreAO0jmY(Rfd?E3VF#!SG0vU-lJ@cm6B33ikAdfyBK%SyrS-=Yl>`tl zG5|O@IKb~=@t@=1-zysbu{hSQa`G1*D;jDzx)v==8Mu@ zv}!4UN?&VPnnm3R1IL{mr`sVLWg}$U2IKv1Ks`w29f$EjcIU#n!X#TlZ!{`-zO(A# zePB1i{&1e{^LCB(z1Wr|f*D=zQXbu?)`vYpt_@L`y`SO=UOREjqSj4|MFjb4Wk8S} z$Pir_9YRo)0i^R_UxFn``6V4R$UwO*U{OW^ifV0Rk7kzqr7(K>WMFX z{0Bp+g_QZP0uFZ_LLsQzFqq^L4s}s9F{;$sC$bB+HXbA1+f`B)jF~fOsduU+O`_lx zE> zj3Nb8<6ipBoMxY6;1Y^USa8GnWYAH|E5u{c)Z$oeKKhXQ`?F=(SzsEGI~bwtcj&?s zf>`3P1>kn>=YxLV>V4g+lPDWwEksQlE6vvQP>JsD#kk%0ja@D3b48CvnoE6KA@Ap> zN0SazYgF@rX@peRAjYOgmm*?A(XxzG=EcP~lL+>3>zNgVjYm{PYWit7OTTeQXq~i1 zTg<4h&Q>UT;#tJ~n@R$(5Gg5c6BGm~6Mpq9&e{UHn)(C&AXiYLo5 zk6#_+;-9{d078`v3}_>W)V%d^I6NF7b;f3_ctOFEedA~JtYwU4rqnoHhRY3dMR?t0&2-+jse04^PR` zPi^fIS55IXnsj9@%IekxS*6R|uxMNHJ_lEA-I;a;9U-VRrQ5vdg%hvV`vxB3$Y<3q zGnDL2Xk48K827?_8k+TXkFZj7wQKQi`?~~9x!v}{hnm+pVI-Kf5obCP^E{B<)tSDL zQ++?y6HMb(4`3e5R?n3I023294ZI`4?6It-N+7jDWbl%S4 z>O>#o7S{Fi2f1G+Ls#y~*!PgU!)cem2X^CCgq`fwqzwR5k6;N!8YL~hwNoI#*7M0a zy)9T|xRt+xHUarr4I*!3_3v&QkRZ*U9eRFhB2z?2>&d8uNKsoPQkQ8Sl-?C1*0@mG40hkOSJyJ(D?1Pi6kl7(A-^@n%GN|>@$RDyJmCzkuxDGYk0Zx{@#o@e!BY6jaQhJ0lcB*Kb zE&yG;hXCFnX?M7ywk?Ev*he?9w5yYCF*mlUIv(1XzMbQ{7e$6Zvg|O|GwKRVgFV@1 z34ob(V>wNK7_A@TXE|uUSut^KZutXUyjEvWJ zZ%*ETI@#|HPWu;;4$Vwdb{X9fMB{F)tCYo2hmEhjSxB)#&&G!sM~X=5C=|1RVdHME z^b({&PwKpR+N(YV%sDL^fu9vr+@uM>Z2YmvT;oOJPoGN|{#oMvS7!11 zBCGu4MgBdr_>axEe+_4A*QN5m`#HU ziMpk+DR>OKFD%0mZo*tixE@Im1qfmSGnFag`RPpRC^XeM3y6O!3n6|PzndHVRPf^)9(PCjr<(dp{?-)WdWVxrmIL7 zT|1$pDY2eK@R5Gwl8m7ieYUx=$o9~MHbria;d__%r5D1u2Ui%dkn)R^Z7n}w1n%59AkRjb zzI|+jp|JoDXq6~MwOE|*sN$f)unOgQE9Z3R*gr%0qT^6|6!orfE^HTeynD3Pn?&ds zg9*##yOfqL-7?7LF5VYD$?RF2+1jwAJR)(%QN1S+j z#)|mu+Jh8i<1_b>ZauZvK)#*W+7v?N`S?S7iP&a1N5(Y*Qb$H`6k5?0x513D*TJkU z@$GYlouCt@7p`@}_75$W@`fc}VOIX&MRNl(=a{CxoBTy!nK>Uijbp#Zo$~Bu$e^){ zv7Dr^?7NjP^!ojD-n+^U-Owj5o)_sNxYsGU8mF*X#%apEIngCfpXzR%K!&r^ByT`O zL27a5CWZnd=cl?mfWy(E)LS0Cae~XQE=9M|61EM2{6af&4I&lNhr~|`N$JMxvhKr& zr~IpP_AW$xLj>K(KFFH{sccnF?}Mc${KA>7{B^= zUk5VzX3X5oKmpQQphCsg!rdQn^@ZBxQ1t?#u@2(Vbh1SkK+x}%+gn&8*ex}hGP%&h zrP3yJnN>7$vQv<;?ulIC&Kl%euYV4S8!;w;d3+XJitDI(~9JV?EVHHxbYZYk{IciY>UvOSj zwfVBot@8l(9m1WSgT5tTeOybNnlc_jubRAVXe_eb&Uq+nfV9K@dy;%Y-qJ`c-Lkf2 zj-k!?e#}s}`T^yZBzhIE-|!+yne%=?DkV}M$cbWtvm1_SVx3I!@S9@Uhd2K(?pt@prhz_Kz1u%-YQHQ?XR! z)9u;euLVhzmy*Gvhxd|ZQCqZx02Y;ycmgHn(+7ELDkxKArYNhY0GFjhaY9LBvG_n|1I}oLeHMkdqNg8t~3ywK2B*c=q}L&_zp!wQO^~1Py1&5JSG2?~;d1 zvZ`2AHL5O%3&LM8qetc~++-BUoj03X*?ldO0TEbA7Jo$-)v=${r(E;PKy!j-5 zIGUz*NTRR5aC}aDclvi+0%8lP6KnTMePkAc2@7BQVU;F6WZH}2oWlvlF=1r%UM_w$ zFD=Qimr1eX4P7`k3mvb)>GypknF(OrNyudM9uJ*F^j8I54N(XR%+Jk>$fHIQBleaP zPp4vsP<~_Tglax^lcASFBd(Y-YE~Tx3KwGoM!(P6K<{GFenKB2e}DNcR7&5BmF=_~#=1|G5?YAHn!f#V+YT zm@1K!trcW`VR@$AQuNaZuwR2>N`UL^<^uZK(dzoF(^Jo-WZ**k89#Q0dOw@f1CJ2> z$9%Q@qMAYj;m412OA$56m#+ z*wxZnS)3Y&8Qr=9t$K9LZW3K=<=M$=wxa&N@A4LxWU zJm%*2nAkoNs67zzn-`Qyxb3)=Q!KDXXop|Fzj*_zsG7DW)LM^HJ-ZlCLrdmf9%qOD zcy|PRqT>kaj^I>6&XS73!|w=bE^wTSV|r77L}vMjEkK#^Pze~ zW3tSI5lX6M{UoZ`IF4`FR%O||usbvgU1&;ePg+f+_{&cXcpm$YqWj$Yf zY_1i9hN{pN-%pkNf?<6fSMX(~c3x-&O{1Pg`GS`B5#UaHmz>GaY8bX6d;!#0P@Ve< z=>;Sw&e%>)HqQ~lA<+dWnVvS)T(!iuYSa9uPLDo{gH}h%6X@liO6KS*KXJxB&y>aA zs@=aQUqb&l&itNy{YGkNSCEqVB&TG4l2dd($tl|yv@Ahb@Dbv4L}Y?7;l+AZNpaS# z&aFg`F0W`fx98Ce&O^ei!trA`mJF#yUN`&gX3y_e*N_0k)fb&rKpwEO;0a2)O%vIl zvY75ZIrSp+-(1E^$~|?4VxCR+VZspmD0cDNqXM=hX1~Im2u(9<4$W^kL2&oexfjYx zDu1z9bBSh5ia<^_{#4r~+-(ucSvK-Dt~z`Fmcy{0C5U83`BAf;eS25uS&dppcQ9zk-G7l%tW}sw1wMC8>2IWz-*@ew>(Bq4i1P1o z;jiTRw_U7^8T*v*fFB_BK3#tHCGAQ!g^#B6llL%JtDbyel5SLRjwc>My$$?}Uqn1! zl|vB5okABtbd&xx@v(PzgaI(VNf!8q3@gv3IGJv*N6(Ul%oU~5B&?N3?Z~4O8@jak z#BUI3EVkTKX3ug6xpS@A%34s(cM#T(ZLhpQNB10p4Jxf|?8*523Ya>1TPrzvIWb!FDD`Kx_ zX!h^wq(pywLE-Z&2ByMJ)&_qhJAb|F?TQmJe=t{z)>`VTWMj=KDRRJ9_?MJpzN6DH zk=1;u46whA?C2xTOwg2Tgh84oHYD)hVbPoSTplMUTD1aShGwyV;>dE2guUd#f2V zC>*+_sG8hm>zgZo|C-k4(xio!bjFOCg{2CEGfzrwLz)2d6j#1ck!Bk>fo-wmFfv`3 z0+rReR&gb}dgZ1B$*Rd70Ob?ay^&M}eSk4Ph7|HkZn%ox6iQo3))%s4)zT931AoJD za9ZQu^1Q-MhoaqJRx{(G#2@NrPKB z7Ms5{(B}!Z#SDTS`SwMqg%8wPce)eVnnCeHgcLn4EOyVf(YVsm8cJzyR)^6cnUfX} zLp54+Nj~^%m`-e7Q48inbSBHs)RhKsQ)5Ub=4hF1b(1;We#-%eBfOVU%cqB`$wV=Q zs!U@tSeRNTK>E;m%neVE12^ zdGxbw&Dl9B3+rFIC=IX4&&2E!+NKheJ&k!6=N39TF9w|eXGfkL2YkduwX^4?<-2zYhwPJ0j|Pan0Ame6*U=3?su~Ja%)BQ^{Tyk6 z$}G|D7rGVb;c}7^Ya#Gb#2g^zr!yA-Q7IWDGmhy45X0O*%)}7R2b|Mzn7={q>u>lrxydt>&u0N1Am<%+!E^nSs^ zG;I#gVEpAvH@YQ!D?fi*>^D_mL~sdk3y>PT0O<0Xde!Ab7ZvnVCNr!wCh4{3wSrzJ zDI90)VmnI-zwdioDuv2bNmd$0lXS`Gf;iyL^E{rCgk{Bi^Tv*b#D$qVX@*^Sy}zUd>dNOF-K zC>yL2xQnG(@NJ5W7!G$JK?moH0LY$}E}8#8SvP!|Vr)JCH5p3+#{Z%0oq{usqIKQw z*tYF-Y;|ng`D5F*ZQHhO+x}zQNq2UyjXLM7sj*IclG2ih%@1P!=I01R1 zeQkjhyh}{M33W0DI~xa{`86+&)kfRrZ!2MOX|uJ3Sw4K(2EOZ>7?{XDt}dksnN=xM zL@l2nb|%(MPzxSglWW_M#@GR4_60ja8Do^OkE>8)=9HF3=o_g&rOMQmi&WNc!QHq2qx;L|K zGPmn?tQjh0_(^6&Gqb0c*eZdYn!A@3&5p7SyvDs=7kBQ(EoJkCFYQ)W!KRd!PZ@KB zjEmdB%hq+XtQhOlMe6`RO55VqX3U|}(JfJ&Y)KYml7ps%S}os=kR7++d9;Jxg}-G} z$K1o`hbc$#%Q-)HG2;t!F{IS`aoM{RR3ForJfdE^r z=k}qL*!Q`&d7)fh#`Kmw*Ny4U$e|c3Q`2#pfjtKtXPOkQ%O$+Wykw6W0J}gY|I~je)w9+dGI{ilB0X(N=FK z!ACZJi1DEArNAyV&P?%#TsVhaCrP`QHdQGzw4#=b9qFX~Tz<~P6{d83Q*%tIGdDQ~ z3K4sNX_pT=!I&>;A1k5Con`#!C2{1G$et&);dtcxuetCeSY7N^(b~r&G`39P19pep z?G5}Loq8xK)oJ3_$q-Zy$W@Iz^e8C7@H0=8x_Cim7Oz%?Zd&2c#`dE7*@c&x7Al)WJk5)>ymlOMFNNmR zG^{|!mL9t`11&kBCX=PCCh22v;QBOPv?qcWCew{CE|Wb>Ev#!*`A%b93GTi=yk(yy zw4^GD?4GG*J~+rEOwX*Ep=Di3?jDVOlYDfYT!1I>*tS6>?h1`?4ZA8h z0gFSj^9s(kU1fMAPUWJCm1;_a{)i6+f^vCfrjt8VT>6`f_qfWXy&nPO-lju@*Teu@ zsa733mSs@|JM_daJf-#Au=VW967r=CsgaMGUVeGY&`s+~ddsSU){IKEl?m!C_?97+ zXUnp|lMQe_44rqID`&eQ-ZY+xjKPnu)VBI?X$_w)@&%@Q3tp?rEEQ1g3scm&sGYcQ zo2x`_uiKSJYh|_wE_Gcd25AkxiX#m&c2yP#(XTGq7V(yJ%eqbzZn?7PA)%rb6&pjM zy#6GZHk}b6m4e3_sA`yNbuJ7Vk%vBTk8e|r6)g){`}|w9ohHN5mQ+D$*XX@+a|?@w zjPHWBU(^RFK7*3z1l8?YBU_nO>fjiPI7Ykp#k?Xoj~hk<#Qa>nl9=Z7N-?5!WVYhV zkd4riIZ}rf+H3KLQq>ilyoWFy^?S-5>oaqkl*NXf{=DT)g4`0Tvpj@Ou!~e~3)Mp-2})j%R<1)et&6tZU8B4)P_DEe+tpimpD>w5 zvu{pRGGWcLfIipaxLK}ltZXB(tsI0lrbP`sHk%A~>iLqXwbCje*{wQ98cYU`sloI$YN?f0L1~ZV3pbO98Sku zh8Mr;gc91z>w1LbSjn5tm2YIn6*SZDLt$vPb%^IU`P7aGosr%1ph4D*2saDr2}d-d zwHJO082<3qh>`oV=LY#kyB`_k4Ov`zxNXc*O6CB=_&Nv}~*&+!5RDpwFvOVS>zC9E5Vpy|-TtvlYB?D1?@v34m$*9XvYN=+L0Jq9+ikE@v;WwQe+o zR6p!T?-uaCGh*vdkaLB#Uxwwa^L-suI>V@HY3QL*AlD|~03)CFa=LzXO(0|Kb-aV$ z=Q#<%OU)8Qp8i3?;}py+u{Qy%xBDupB;?8CJ6eVZPRSeDhF|F58(PZ)9D9SS_5LQ` z8=MW03+EcPIhOdsC4CcjpvwWFjQT|UUK7R%%#7<5O{_%&@+=zG9{;AaBXXalJ*>1WbU_T^CxUwM{I0TN-D?RqJvD zA0M(er56XJSp?||W9g4EcMrBdz*~=SuoX?^1nEEwwgdbi#!^a-i=>cLoXWywPz;Wr!tUy=XfNMWonS~G z8$7YBC=99R29!8Ww$UQv+R-i}R_fkS4@qanMKW<6=Rf8u z;^Qdww7$R-6vNl@NL?!WaA21g({63|#RnV=S%WvgIAN*InYR-T7}a9w8R?go3@^WF zzbYo{|CU{I(qJGx9sddW{t#zyD81Ng-W;1z>fF`h(`rs_xg%l;`gdl)o{`%VBdQ1h zF=KDKW(itgr|jlewb!@xazMDy`e1!Ke#iK8;9T&1jDc_&8A1redrtsv~y_t|#l zO{{T2?zC5196iugR3Sq5O_n||M@dHm;<87 zPRoEqv(UOdsOLW2xAl<<%9h#8>%VO`xOEv&L%zC7=*5-Rco7`EVY}!MB1?WQSA_#z;P_5rSw#z1g{hJL9(L z$8IEiW!`Iu4o}li4$&_eb$6DBOl-j+q!a1KlQ{sU3vV#jq7|MHQK51Y@kb#i5$@$E z=rs(J^|R6Dkvz7>?(cOogOa$HBid21ya@bWE-paRE-a9NQPduZPd59&eCrskR5qn3 z&ZyQ{Af;$QQPP)2oB`+4`IoAsn|^(&9fe||#Iy4m>jk7$UJqKF9amuQCE!ENAi)lO z(x<9nQ(cg^O7Swv)3!I;turb0&RM>7%VQ%l53E6yc2(T2Q%=9kw^cm-g0sEv;J`M@ zmq3V0W}t8st* zCOKsTbl%$aM$PZ{ZAJ2q9(wPG-@zT5{8B<#GG#RpK-1e-z&Jm(XPpPp_APeHddYDn zrLHRQS)tnD9Me={X1=q!LnnkE8pFCWdLE4xP7{2wZD$#LUpOM#uyX39}SK7@| zr&_`J`YR;87n*Y3HlyIdIC|EL#g&&2Y-aYR%e%>Tz(7y1G!+WdCRlfxI zCdJf*eZ^mhb{ro@8B+f~F!8E8uIpm0mZ}6bnY;gu*Dac}n3Q%F?$>104D1;KD=89;83(()2MH#{z1nJHMDDvW2F4uizc75T+nOiQLVkJEuME; zP$>^?eUdDA$Fbyuzsre#op*CVcT2e(>vZC*U)b_++?g~m>umjeTp-DlqEckvtz7yjn26+L|J z^Su3^uKtarYm~Epy2u#(f7NLI`zq;wZZyh90BeBbf7xzE)c!X}w9#hMTVh0`;!O~p zQ5F_9P|X6D3ce#l$*lQ`Om z7IP@^PfNZ#JbE9y2!OYyr;<9>Vo3)?P|FDi_)vxHd4!jsmw0*ITdXu+8HZ0;7krS= zb@|ewSL0OuA8TY^@u}9YSX}lla^8Y=tGXNKmV?+@R1$U7jxJg>4^)!9TU;p7%|_J) z#X;f?+0YCI(9A^)_>B}+yOl?8{J}*3^BJGr!`7*uR3CF;DB6DX9y*YbU|>a% z=EmR@^=9MwsOAoSW_ip?FT-Nli-#qUD;vx|??$R%#9r$*~yVQZ?+~FLHC`W^5m~%+-0(h$r6RPfR)u`P)FpiH322i|o_vLTu$WNnF_x`{zkpYhtu2(mqq0(Yfm8~`pb-39J z!1+D4&ouHKFSfQMPLP=qeh2%7Z$4hbuNi1_E&L&GDZ`A77w&LEr_;9jiG7_ zl}FAvTI}r!BYfOahkyc4lv$Q#{lVi2`&(o6%mPEZe>k~oY|CMSmZ&0QM&Ce%be zzpL*y!s*@B#gevBk84WJmD{)u4gI5X$peQ#db629UMB2^C;1HLGRSjIx+d`W(aYsV zi(o}AHU1x7A}MHcVM#KlB)j=`y#hZ)yCsiVr*CV_XR&GEx8XLh+v#bPO{;nR{F4Wy z!`wIO-9i*-h){){bjmr2}VQ`1NE3(P7@(&rC0C#$vzThe3+cjjnfOTKdP$<8F;UwGUuyGhBO=1dK zqzwE-bi+oWJnKqJxu$Syhwv*znZFzxBL&9<@tO-DIwNBMkLz==H_ZPK9FT}GPMiL9 zj&r#Gs&oAJEe`*ubI6#un%EkeIGV`<9RI@yX8ix;!~Aa?mKU@^@=D7c*Q@W|RmQ~2 z0LKOtG%+q2*~Pd&Q2-b;L}1c*EF+mPvvCGvMtynvyh>Ep3T5D#aJ5p6OVv-h$Q>&i zpIS>OO$c=1H5s^{bO83% z*%_?{@20IV_D5KscxFBChA`srBRP2o64GC$a~=+KfSm&lLiv0Et7JtiEm+0B=SLRZfej(?q5fddqF5IsPHaKaW)G|i+OdK z>$}YrnkSks)3)==-KD$R@uJ7MwiO%tG@*j_TssxnRDjWA*+l$RAzPJoW*^l;-C-(R zzz`n4iK38ax|SzX&WTV&&A?4WKES!XHouk`{op~}xrRE=GQ5wSRjKAfxr}Q=6zLL| zor!BDUmYzXYtk8r?vT^|g{ZD}yJa<<`Mv6N~S?ZOmK zav<1B(yC;UTjg$}PPi(MeG%Q_Hd?WX$jue8^K+4BUGdOzDP%yujnFTjR@p(mB=6{| z$}+??>JjNQ5@hWF5M^4+vuT?*961MLo8%>KXN%m5k)V(YPoGD(xGdPJ4Q!agBbEBN z3OO4Ss=7<>)h}iVu&gxkAJ2+LxZ7DeMDrOtG=YVFf(VZgyDDsuV7crgdo(xPpmDIq>i6_$wt zEJD(e=68(1DIr5rB%-I!&83G|YpM!%d~8~VgdxHMLw*lmz9*hZVq_!}l*Zh3TuF{? zqVC9mD1i|-cu@y_Y(gYXXxK>sAGh&hYa481i#|+wsvVn4VzU9%lH&N_46x>U(hv!_ zN|#Vx$|M`AMz1Zdewz~R+DNkGhgsU}WD!%vel;Q-5g4*+;)V;hR*=v+wo?+*62y_6 zlx3ks<^p3FR*?sN@S2oBeN6e6G92ZG;v6Jm}cxTpF0Z_r#-mOjp;EOl`U7A>O6-aUcH+&S*@)(+hQa+*c8Z5)6Vm_ON? z?!qo^&22>=N4e*6boW3Jjmse0_TVhoj`LSRp1F~B%`sU>j+|u!>eTmoys2yr;E+`I zQBXmVeaIbgh_rfi zL$3N206Htm`KT|2h0EW$aBgtKo8umfcG4$xrfS9(gMEL8_l#89)0bE%lV*c&B=BfbaVy{TGtyLhU z*kBJW>ZMF8U8~v;t!2?q(uN5AwpLGsUp#gKbACmMqYdyJI2wYc#BEryN|lialBuRP zy8^(0*HT(IvOmjxn{Yl&WOP>LIp==1znh=J!JRrsYYd-8K`)?JB#i(=uKFl;_N>IR zu|LC-7!fmUeh`=2cDB;ocE$xb5C6iAwbJuih+MxYUBUv1ET7Keu>M%Zw^ex$`YxI)Jt<*OGZ*MCiJ0zCUE=lM4F62Z>kmLTu?_ z&4kwr{Lx6;__Ik+>zm-`pC6nAYF#LnarrN<qsL1;u+65EnE&;1nhz2DEfkZS zlrI<3-3*?v~qm@>D;Au8ee-j3ITVW&aF zGJ%MglL`rn#z#Bg;HCvAUFE5a5?h5h2fCaZA~Jq9C+Q)OfI>|JQ#W!1Aq!43#<-JP zR!yh9nzp5kjE&ENYLfI8!g2HpKMCmHQYT4o9$(r;?WZgAf5SI@w+Uxi9vcfDR(BjF zLSdpoq<3}5?F3cLb>?lNvy7ujKhcr?GO_SXQ;9B}MUN{+28Jy04n$jo2;Mfs1@<_T zlwvr8F9rTJ*#9B(5;iua(4c6Yz^9%-Ukf8kWDpH#W6L5*iiRFG7mDFqz#z5|7t;lz zICX0prpB}VOHfI|ic3FyhZ=pfKoKBN4QY`FdTc1*|C$ZOVJ_6PzqB1^Zkh=cX(!7c zcMG0KlZr->Uhj}vPpq65As-vgw6|cKp}H40F5jl&kUHx&*XeB(%hB|p2c(zi+9V7( z^4ATZSR%d+ku$4UCTpPunL=Mv)hNPKD>G|IN%R%4(4WDiB|?>u!4#Zi9d^AD!cWa4 zT650OQC>+2QQ2*w^H&4N`bzFnj<3Au*LY4tYX@*FXif(%AWRdP}epj zd^*556k=rDLO(rNtf`L7S1--EN2-rI?c+)rmN%N%5ja$dcK6$c{B7 z6hk;lx~Usnju(NUJ~@x&GEy01`Oxd&oVvo6bk;`88&bQB<^-c(F<^PTx~dD4Dc~QF zZxIa-5u_P600-|XbajYegAv?>zOkUErHh`)JdrN+mnEb-xq{%63=#ht!<0#vTIePI zdNe(Sy||h8dXhVddK zKyK=1xnCkZ-x7%>DO)s=hj_drohSR~HZt5E<7ltn^w#TN<)L?tt3WTRp7i~GB6lXp zuXIGCh95BYc*zFDGK2T_I2Z%0bOG3$$ff{lRs-zmF-P-J81oS+jnJfhkZd>`4e%UJ zaL;>Ito|hcZSK!4CNK^|EZYH#depKZTVB|g1DST*xlk_$cHY3}J2LiuWll`J;=fR{ zVfsKJchoFkT{{&1lisPD2gI*YYtNL^L#1p9#K(!JUwJ|d4~(^gT<$+-%UVR+LpRy4 zMi93BbK0>FIm0jSwXO!W>v8SI2)2c*UI8F^#eYA8pHYBcD3Ett=Dp`a1V^}Sx1>&V zTe!4CSUZj#I>(`$1Lh4%+=0zOSGzW^@T0&8&oJ^fson_Bh?RSrJM1m8-;j^efqDsM zAH~wWZ$_AY+Q^%KcJN-j^1Y&Fn6M-NOd~l!(zFz4n9|!h`wnNSa)0(#+)rGvdy~~5E{sqaX2`6nTk}!lhz|gGl+C%6FSFLQaiM(qCmYQRtpsyBb@z_o=i+b&* zmT1u>st>x*^=QaA*Oqa&D(KLp4Z^c>=#@qh4#t3?Pe~6mzcnUW=B0yhP($Y;aoMv7 z9zRec`+pOaEAdlis}$CTOc-YKg7H9226;W>w5JUIQzOkC)hz)S{Rd(dwv&zttedZ2sdP>hG?KQ4v`d#xi_f1_slP zX=a94$12|$xuF32PPWxfX;(Gr6l7zshbq_KdI3BG@bo8wcI{B+Xt*fZ1j8gn z^hvVL3|gyjP1BfjIcHG_mhdY@KTaF8mrZ1AKThdTxDR0G_O#L_c1tryIW1mMq*Z>k zU{HAXbg|WRHG)a040F-|ODQrjI@}V`Fzd)Q`;xX8H~C;dT%)c%OskusBy*%q2_W0p zeR^8SlWb6Pn0RU$2Y45sF={%=$TI296lGQOWSy=q_ENYRenNw`;?45ggmotVzWT!) zv+tdGoS8N027qllLy76r2C}gOyqUYeUt`5%Z8%Am0XsjpMo$BgQAW-)2Vg8yb z$zV{XeQrWg4cGe(RjW@?{^YMJ*fVf-qm%oP{ns&M(LYreSK?UFO&rH6_bk6=iXpSP zWyO3<*7Y4_>iov=;{gzKLusL)pZ)ogO0#zOR01St_UM5bOQ!fs`S-wHRAq6!`!^_O zR8Ht^G=F$SVM!wxmB=N7N=|&7asl;Vg9=X6LPHudQLJAWOZ#dUw@79K{92!#`3mHw zLx+Y4-ulZ!QH4KaBRlT2GrfeTgWN<&yD3kK&`t}ZV9?sk1@p}R0W-bnN`*`kH3H3$ zd9~?=AR6%IP-*SC&>5379B5fv35vC!G#qB!}FZWX?BC7_5ug5`%rOC=)n&oB=~q-4-=M=TCV7Knafz>cUji0DwPhBF|o z=C6~~B5e()9B|*0Hwar}>Jz{5JG5Y-tVIT~e)2i=xQlHQ>0xk09v(~`AhN!iIW)QJ ze}!=p+a_eLlTQuXYW{i|XBp0MEM2FaBXy5>i?l{{o3eF?+a`ILm>O0;em>CiV0cDc z+>CG6CqUCr+e1ZE$n;VmAbwLn0K9j)tNfLOn?N<}D~$rx>f|g&kDO|bIH;!);7#uK zagB5ph9?(*#mRpNTJpjX0o2k+@+KqA`P(T(-V4FfsatHp@0A$_F0~@+6%P*|3*i7| zR8_iF*vqO`WN5mlmUSR%1C&HJ`j6|!^>o2uRn8Mbcx-4OW`pFs#6ig`#WR?DMM?r% zUOm!nZ+#NlHNEo4I+hU{f{OQ7^5003%ejd6!H(Js<5|QT?&&Wg@XsFq^&@FMiD2YVQ5dCE6VZYI^_V@ z-}kx!0--_GkY$^|IxR3hF;+!E9W^L$2c`n*@F*}{K^-zqv|-Ue)NQQ*8cChI_-(K~ zmA&rWB9belJdAg@G#i1u>5wsKn0SUyAao$}c#*Ds`nC91Zm^wZi2n<1p=d~ayI|-) zvKGiB3cB1=W&F@QH8&Uh>4XgDfc+{C0{EHQzKfb-!2Xd;IZ0iuQhE`E5V2w%tFzX! z#eHtl6BECX9}013PH7V1+TV$3n+L$RpvLd~^Js;1j;93gI7hNQdG>C$?qhiJu(s4i zeoDH?gKi;w@D^xO2t+DF{t#PViLH-vWL;XSYjHw zHc3qVpGd;T+qtqbEwZj6{4?zz$EPE)^cwL>eor|zg)K2cbB8jHQ3cWvW-X&4=fY?x zCm%;4yW}g?^u{bN`q+ptLnzCDvV}=BA^rq)6&e1GPB4ZWC-e*e{3S`U6M<67BGYj?KRc1)M7}yIaCjnh7Fa z9^pLQjlq|W^|6&!1!*cfIxAqmj@L^VA>4*!Cy>l5me|w(9h39r@WnJmdV{@-AWe3N zT?{%lNf-QscMp?IsTXqG+$x3_W_!87;fuHy$pNIeXWu5-4d@!q1Nz=` zV4)E9w~Ywwd))Wgi)8z+4Ts&Og1L*6coTtlo}Xv_($%2ZaW8$^=k*+Amln_?0&UOD zZPGS|(4%K@fSlR+^^XH%9G~0B^@i$zryqZKciM>LM>=-c)d;nhh8mnqK1dHM>Tl@7 zKJwwvD3m-QrASQ~QQ_FA@!Kb=8iPseGO;XbCK*{_E;sfc~HR3lXyIi)BmsZb&) zQVzj0@n6)f_`k(ZZ|$9nH7af&@sZ;;^FLkQpFmKpKe>?^mjLDw`$*+>aF~5ays|s* zbTjb{XV21#p0m=izJ*^Y6VBe_r)1JFTB(^T-mq(K#-!J-6q zYS(~@Fjt=^%wi(J()H6SI@j#un(Jei6C=D)I57SmIHloFLY;s?@TmTlNcRZXMm452o*YRYO#4kt z{@1Ys#PV2*Q@A!T;{ha{L0y=3V9Eq-b-}YOdcglGc!n84``EKx$#pkN7W z77>M)>~sIq5fm?p`mG1gUtlr@&309Jb2m^(FZ`DWa!5{1IyJ+9kOy_@l#P4n7YO@= zpbkx6xZ*oG4Br;@lTMKOxRpa!H-cT_+9A?&*ipu)`yl*Qc-hTE+ zPrZ~cJi9_)#9iwooji|{{WQBlDszf8OzKj4`ED_KFA)46m%#3y>+ydnp{lX6mLP&iA^PtuMWZ1|NZo>s4ajMo&~Td2$lx4JG+Tz& z8RrC}t0Ce}383y&l5x1Qg6N1BUUe6)eSbmH^9hSE4`b#TXcuO0qB&+!xCt#1De^3Y z&T4il{v~BN5_dD`Gggd3@;m)Tskpu}5yz^LTg?(;KQV9Z@YcNKU3*Jl)LDi|X_{GH zVj-Q@O`-m!c`It6juxN>{`p6xgE=^3id4`9CDyU_ub&_muaRFX9!PRxpK@ zAlm{$QvlSx(GoO1crEPL&;Kaj?$ago+`r-=|MQ9d|C1d4`*@rGqbmP5Jfi=rrXw0Y z_9`pr-#b@hQ?>-S(Onb#puQ=V>p!HC3bTH&k^NLd4U`NQt3IDPN#I?-vVA2D)L##5 zZq;gOg@IW$Bv-2;fk9TjFRIaRv9z%&Ta_!5!*4m1xs>^?uqo;LbZrW*!veu~HNEY* z?e&^{&vBaLJKcW0Fq6LpRS0R*g*wmzU+YlxzufWGsN09&z-!kVSld=;OwxBVVrL(3 z!8LIzvSyz+!F{;qFmXz#}FDr5<#%uflBux`M+VJ-L}Ug$3Sr6aYU(+fm)9 z*RMv=tP|{RTxb2JUek3T95-We zXuSJ_2yis+^D$Ci8Uw;G1Q=8n%tm5a1(c*dQ7jD-o6%!n%l34pWS2#rG$zGhQbT-V zbT*}H^zt|f?$u+-Rnf)$#WIEB^0-ll6Mtn?Ff}&O>{u*N8d@;8(|ts#toC>d7iz(~}bpRcQAm@kp$IOb`56v|QZE_h-oS)MZa;J`g0pTbQ`bt8hKue#W}{eXhWI233q55fk=mr zr(PJr4Aztji)L56xsHvgos7I$BG}#Z1jkb_TLSLW*Tk3r#PO*(Y{k%#IsahmG0A+N zT(1`DZt5Z1*x#hOPlt1RZ;NmYq|-ca*zDvT0o$p8B<4ln!p5530@3LX-+clYxxL`X zQ-sBsvF!sP#g;AUjALp2Sa|8PX_Cb(`mLT#JvUCizmRF;PnKLjXjN`GnKo;SrOZP& z7h<|YF+Zt?peeFqDIKn{Vyj3*Bblj==nxh(X^JhQ60)!w`O9uQ0eU*0T)A|+Rw<(e zLTX?ju#(e-YVIHzeGX^3IDr-$9|I;siDklAtu`aILGFBQjU7P(ELYXE+Dw!LK!!QO z!ZcWee@GNv;wL=hjGPLn- zk%KKMT z6s!u9tJHug|L9n3h$WzU5BE~xjxh&4oijd>M3t+47Z{lbJO$yS+yx8MFDstbFApaz z*cU}-0GgoJ8RP}3tA3$8mS+X7seHlI(YgzdWWBM~QHg__R>xpL!>Y364K0)}&;}7V zu*P;P-lazF?YGhKAuR9Ft9>PE_)^+WK(A%F#TXrGuH{HkK1+1Qq%`GPGpg4x7dvU8 zKT*}T!eH-VM!&)lmdw6BV zQ3*zbbbp(Engajz>1Q0DlFH16%1~yGbD6@64~#fboN6YpofPD0d>c+KqeI2uU~64t zu(7_jw6VT2x5lNljQg2fiD29#xauY1J*(JZylBeWt|4Dy;#_Rk@D|UXton3T>qJzk z1y}va+g9<9wOD467>Pc0fx*V++S2AsZ&_2-*WS=mW#Zx0?jh==?yjk>?5=5~u5F}i z^=FYufZRJaeX~IT2R}m#VtO-0{B9c|JA}v-)IMK?LN8Xzc(cXx#NY*-8C09^68R+r zX&OmC5dPs1K>9CiNd`s*p(x)8s+D-1uq|~>a}OQ1T9hW$09m|bW29U>=y}H>kzB<- z6h6g5Q$Ff)yK81&`> zIHHY;>i95?S^Abnu*_gQnWVm@X21DHwly)7zGaAGZo?w3Y6OCA9D59m{5xC&j?LL8 zEir)#-blgHbWk;1P;T}mK|US^qe$BUlRH!})7$WD`5SIaFC$$*t{Yh>sj38e9{=kggfEj(eO;i+R@zzTqV7~bwll?@u0=cWwfC2Gc*2-USn|2T7+Xp?^U=K| zfY^iQ1rvDXy(F`5lwJ;_dfCT9<-_V^Wv>U;Y9%Y8t(J9jRu z>R-F=<<>~5x$&k|zg|mxnRh|Cr>? zXftWv46<5bLfngLx120d`N6O)jf+%0q)il*6pN|(;eS~R@4oICErZ+?hwY8*H)iCv zg8OdAG&vxa8quB@;1;c`d9J&DT>NQALHs?2P(4aiYw8C|FbKgLE$bfq_npeeiIR&~ zu2MJK17r@saSQHs50N|CwH_w#zO){P31$a-;QX?5SC}4>Hq6^ihjD<8Y`Pb?CW^a@ z#OJR3)aWd~PwxQwDeJDi9l96Qbr0D9e;W>YFMf~q>GPK4j_rq02jsg)*u^B=7rsaI zRxua~1OMesCm+cfV`cy`iFM9hVTG7?G)@jvUV-N^0^ZT4*TDVSDzhz0t2>LTN^vuE zzN*7Tu5L(v%6iX{4VbZ57m8N5mm6V69!awxN4#Ilht&tLdZ1!e5L`4Z9-2>Pn~Q!o7)BG#lrh#vQtmSRo!H-yv^GN(CbYOVFC+iw zl5SVxo!rsv*C>bz!#1!gFbHagRxES`pw_I*YjN0?${OLJACs!8siBI4KUk(jDG)LR zd91sssa=)05g$GA2#5H3jbFQYIUxMG?S|>&K~bXpW9cebuy@X&LwcC8RL4)Dt~#Fa zrVLdL-2wU9#~nR6tD6q+f?x?_yxj0k=L!1}Aiwc9Yxa#0V*i_&+Gq5up3n(fa_)3n zbkH=US8b3xsr27|@{2N-cL`tz#hf3{m1F`QX_acE4SbbqCLxD8m2@Z}DKV3=UlDjD zq!ZG@)e>|?ULu@(o8u8KXXO|QPK>*QKaHo9opUN!+j#;t;Sq~I1be0~sM4Umo(H-1 z{qNTOZ-{w)cl-(a;|Bu%|N9pHpNTmV|JOr|IKaipNzTO0+0OPqc}{B7tyEOj(ElQ^ zOowDd@z!~Y7PhnwEO6q$k1oWMjpDm^Fvveu+o_c z)4R}Ew|FLoX1SJ+0yF*xW$zeY+1_OfSCWct+qP}nwrwXB+qP}nwrxA9xGH>e&gp); z&$)e{e(wJ5^=a=af%PeV=`idM)0>ZbkGH zCIfM0X16PYI{+UDfbJr=Azjdu6L~oP{;|84H}+5_qI#o^9v<3$fFn}sTjqlCQ1mwU zFBjicHq}zT->=&dP#4Fo+O$S9ORf1OW}zkW`>s%*VMyhJUM3P-n?H_@;?=zRSctM# z_7DfCP_8A&pvj219oTJR#a50M{&43qTQfg?uCx)&CCYZeVm!M(<>=+Mob3#^81sk_ zkYJ!;>bPOtcS$iOG8aJg1<~$S<>;o%hQ@r+bcP13CJkzIA4Az^fMQ6F-AT$2b9QsX zQEX7)<|bC|qM}E~s+o5vS_r6eSr5y|pjO9wIFmS#P`^^*5y&{?!)a=3D_J_n6-!lo zOMvznJCb3yl7sJ~K&CxF_Uo`6UF>v_j5~HBkUx1Sd^PVq{FYSucP7!V;zg^9BYJ)C}~oSq9{w=PG#totwc|1h)oAkjdj4O9sOu&BU1r|lpHxz z)gAy9eMWU>Rf<3yn-s|_mmnHeS*za|88=UTXymTmH#)U<9jj1bX}g$6kk_0D1AD{- z!YbYS6|eT{p1$ltqAeQU)v!3uK@+wZy7&gk2BYEq#WbLZ{6v7)+Eh-gxuZ*gV5iSm zCv7jEP;*LkJMz`3h%@umTt!X7LaKcl-{r@WwDbg7XK1O)ax*2dM1p*#%hcHXSrJ}N z=y?}(b~EuBkRrrcCsp}DyGOf(f;Ue9QhaRajpdK>rd7f0>TI*~*tM|DLhrWhlEPRX zn<*ZL3x}V#4>Org{wwX3X#m_;KeN^SxW5Lb$e}PD?scE+q5+P)T-<)F^t4vB*(g@pe_mt1YPt@tV?MXAFx#3(EHz#3tknl#ZrH9%?f7$3 zue%_+O3PAvUO{^reron~inZ3|wTS8Xou3z9xXTa*;VS1@Ni1%VtAfxSBm-Q=cuJ-P zuQ^TN#xi#I#xy3qO&+Qyd&PnuAs!P>%}g?DRSDy)@ZnwJhPcJZ;n?%VGRjRXJnz#8 zSR5l+)JETL#rj@wL*4Wq%&_J##h=jJB`->>_IP2r$CuecEL0I$+@(%WVNEb3&5CRa zsx&145+Cab=-wh#+z(ofmv4jhi0UF$Xa1;h#QLbLEkkjNoqJadM3#o2ynDm9(UbIE zPG&R3J&|)8V!IniI)Q7on8C8Gh>!_a)M_C$u|NJ*m@20d8CdA-u2>1_zIx<3%%eH{V7b1o~jQW#V0Ff*=E+{1o%tqI~EZLFlyyk^3?D*9JP$TzT`qZNv zW%eCI6*c!|mH`2-Am=@R^os!Gwks2Xp99pD&Z{9Q1=d9hAPf?q4Gr%1(1UW!w@_0Z zk;9_CTPB`kMtSI7!E?BU`?7FWsM<8K-x*({3~5D|YnAUW+~=NcS+d>-o4J z_r6HzN++o#;cMqA$2G=tD&v?Z5j~=LF({1N+W~5n=rBaL&CUOO1xEt=E!_zm^x{Ij3(7pv#>XRRRAt}}hgy+9{b@@`=1aH(2Ai!kUm{QG5c z$m&b99Zxu8<9;JspUabSCZer=q_dG$#a-8L%zU(r}ExI%s;TT%3ryEESb~Td54}?Kao5h^$TO0%VpdTM>5aGhs;l zC=_%vVkTJHIUDiJN6TxYGM<*5Px4Q~O{A29%O}G`HVjsOZ{!6!coB!wX>)!xDiNuY* zbo0!e-2W%Mxl3V8LXaMb`)t=TXNhBmu+>Z$YG1*AAs=iAU`Sf^%+gG8TT&t&;zhY# z-VVR|o$R)|8Iqg^NeGagmGpTt?DY>dNXS52isgHp;;UlX+Y%5ONa znp?qkcZ1>W`C2F5uI4S>vfg}c8@g!0Qh6HH$q`Eof=@29z)6Xr;37pYs>PN-?v?x9 z5WJ(E8wf1~ps?r|W-yj&&$WHCZ#5|BB>NC?`q{A{{$qZ> zQt8A~*W3m6p~ph--_2xu=AO|{4J{!Sx>C_6W0P_jHx#G!GiOVBkdoH17Q?!| zrT8znT>WqImj4vGmHK~@kg_QE`uv;m&<7`i%rhLDPf;6SFo)eu9=xTT48iAg$i zL$%)2T|jXkOj_3r^u{xnZX;Ao&?{uHFB(VoeOyp9Z6paQmtM8}(-8ln5xy^SEq6#n z?LMf^VST*6-%7^v`HM`|OTNXj6!5x|;gSa-fB8*&$h_;|W@rminVw+x_q z^e$#x%R~Tm^Tj+O_3*}9?ymPXho0!9U78ujBb}X4gVHHZfc`{F+J>GVq2I=7xgJhR z8|7%>U_4=_ojU(DhQX3RK>L7qNTS42Rxb^KLZ^(8cvjt>!%ap8%5&Aqpf)WPn3%@PX&PUHE`69ilzu4xzyGpkdx5sL)N+hdQv&KE&h1_>4wy0@ASe z*oX2S`D{exTxXV&xNb#U*%U^29@U{+%auN4euX}Ns!e7SyhAEu6RWVF-FeN*9|ZSa z*f0zW_01l-Z3Z6KyE^KxlTH^r zPJv!Z%@*?~Q*wj!gB_$HANXNPpJJC*IrM9J^1Nv)7!vjM~La-r%OfD9$?YVh6(U@ z1+{FaU|tCHANSLy(*z@LG!5j3=$fj)msNK>Fe+KX(O+Jmet#~G-|Pb(;C!7raDNkX z{U=1g_isOhzf3s)bbkNSWmrz%{6ARE|FYt2tVE9MaN|d6Y)n$VND?Sg5buTf-YD;m zkqj{0*fHf2(TD0A((^;r+fN9wK$hf#>>zCoSxnQQU+`J$IP=EqWHRmJNK^DoJijV9?m znyMbe7VEv~WcMl(3n*>oJqaBe@D>v6*Cj7MKWe(nEa%Jg5$l@431@hG3B9!D z9H=YB`DC4F{B$+SO5|Zls6BO4LAp#z2~DbH%8P#Qv6YF#Ga3#Qen$#Emt82&jremJ zWNg=oLuDIl$OQ)q#ta4JyJD}&#*tSbC0{%&CRYmpV`6&jW^6?os4Z{97 zZ0CNsg~V+N8SG@mt*H*0og$y@`MKnu$?u7F23o{*6a#6#+sJiiBZ*!_%?G#^inzl& z9rJ`u8pkNW49c!)?MkmLxm$}thlt~rC?Px9p#YeQ3 zQuwHW4wAS`}K%{qu<| zc?lxh5Hz*G&BHa@5M(RbJnPNc7F~5MfrT?Kj2+OPG=~t!y^9q%jujxu&26-7l^H@8 zp+|{TCn=i-Nq99Y5g7Ur!|#=EqSE^1)WlfH_Lx7=G@0Nmj$P$#3uic>4utanntT3^wqhbjPZhUc4ZQa$a_ z-RFkrB(^^ZupcG&Xeh_cqok_CJ^O7Os#HkH$M9~n?oh0k&|j0o!e1e&Q@R3dD%Au>X`S{~yHf|H~;x^Dk{>)a2x< zs?bo?&fEu*327vLq;&%dBr!a$Ux#um#$zraRxLy?yEAbq-Fk&^OdvU8Z}P*88z5Ds z7R>8t`r+1|bdS04%2kyXa498M31k~Cu#m~|dR<5OJ`yVrDX z&6A?7XF?Y&vX0WN7+pfqp0(AVp>1rkv?>lvz_eryrDxboG$sTavnfK|6i`oks<_uF zgXl_BUO?@+56q*E4>51)>{*hibDRigXH?Wg2H;C5&WoWQqS4Wjs8dk#D3HlzD9x>I{rXL2@f4{2f(Ui%(6Mv{;F2 z1TuJ(7Ta9D*j}DK3LTgn+5F5M5j}YBJ~Xzjt6yj(^RyG$~2T{^dpSiXZ-?GGA<88lTON+YL>iUz83LMM`belYZlp zCGBkc;UU(H?cSFw&2AU;C*d#hz;ku*F!1(qkJRgPi6zgan&OMQmp8y(gkuV~z%&9K z)Z5}vb-y{}q9jdZHqRZpW<`Zq3cH`X`;HxFqwO7*V2M*#{Cb|DfOS91PWI=8v&=bK5Wu`% zM6b|_$~e-sOw>~<03x(Y9%LCRH(`a-_iM@|d>v1!q(rmHwV*@Fb&JdyFvqBmKK+k+ z&M!s`Iq*eR6S*k~qs<{FFO4%ZN0TLx2`kO5wRB)yOV@vb^GmfOZXN|1x<$4CPJRA7 z0bdMR?)Iw#nbqEPnx((BG#)^MaSMUZ)_ps7PraSk1BtxTI9%X)?QCJ{q3iesw9mOg zNOr5Shpl#8iZO0A^?b1U`F*sCp34}?mV3YrN4wuqicS$AfqfcD=kS%O+)vBQSb&;-L$Ta72x3R+qq@D;hP3yG2P7v`S*$mx`KAwBCC~3T>rH zWHaybMW)Lckj!#I)b7U_wkF+<$CJ-dU(`$wFNhtOYX0d!7?=k=O;rMfjBwn55EB1k zL1E|syXGY)=83Eo3u?ljiMW0r?JfnU7}3Y+%}Fhq$&_$7jMNL*s9;2j_kew!T}EIJ z$x;)k7E7qmrZSq9bBuEJ&Q&Zm?8R8G)47_=8Gs{_&5C1Y(9$&+=v&n*VOeFCHjiS% zHmxRGok#d4<0f75j3!nK4)@A}JvMCWe%3P}-D_%)Jh$ueBgZBVLu;381)`851N2T) z%*o$DOx=wdY$h|L6X4h<>a}S_6z5xutIX2UO_UihJ<;$JsgMd8-lOFY_K^*%&(WsJ zwGH|Bn_ioSinT46o|KmhX&{}L zrC2yJPUG7;t=NK#CML|&TUNne2#?pRAg%V+RHQnF7-4%L0Acf5u!fE5LqYsdjKa^j zj5Li!Xfu!{9W`O*UgC$EJGLY|#Is!lH_nDEgRf0ExgE~7=-V!c&l+Vct@3JX7>C_l z-jEYWT2`H~rCskos^scUh-BAn*xT*b6VF<^7-wK404bXFJHpvO3Y#={43x>OQ}irlB0Lqf+phOx175M{9E zb}M-;bK1ESpdUAF%2DI86Rq7SYfRIGfH;c6gNC0f_$W(33LhW+0XF9~hFDcml% z-q#0|J3*{-F#uqldr{5vCLXgeb0b##-@v1b*+^GK7hv({wV&r6DMbOG>aX-+Gxuu* zVBn?b2y&ZM4MDdJKA#w~T~}fGeO&G^i+xc&!o7mnu^i;_r_AHuJULRBT8-;Ie`(i+29=QB6TL@4vMiAz$^`Otb- zobAjmJrWvl7TzKX^m)GG^11s{j|6~v5h9_1j|>F#jqnz*p+$zkMo|RduL&ba5Gc3@ zj+(g&=%<9%x(A+`QO#wA7UAZ;zPR${vd&2>79m4yc3`9QaCPB!w)kwqe{2HfFqrZX zUd@O2k?rF+Kg8*ankr|^0_a}wa#i#^cB&^C- zWORVo|4@m{m)gUFKh&hZ2-y8M@*;(;1O>*$vuv(?`Wng7|Y{`(#<|2^maJsbbe9x(D7e|W%Txve!l z`pf$B&f)P?gGpQ|PWT6P%eE|BC2kps*8{)P_kr^E#vqus7)0Pb^#$sSIZThGr9H>2 zuzqXxZ$OJSWczXo;WwRZ>yzVD_{pHP58>=bvU27mt}Yh5e1t(ciBia@nY`?#ZJ?%Q zsR>N;8y!fq;AU>2lm@V7mL4P>Y^B`^8sGK40}6vGo6D2?;CCigTCe4pb=$|WwT4$1 ztVIHI?;(r)EcV8_G1IQV`02aw`_q!;IkHO*g=ku?DFh9!B|r+3{!D)><8bhDoT^>j zQZBUUhpemR!t^jw<|kH=e~53Ia3Nn`_8R=#TcdEiAJ!){Ih4NWHleKkP5OMHYoMObph`c* zp#3%L`lM^8I5#~ut zHvDe@glFx^I|r$4nMsJH_a;D`mN~UvegQz)IpV1eCLY5Qg?nNtOaS1vRDoRTloYzEl;D>i$ ztk%m!2{eku4sEh#n8XNWX{AvlsAD-ESLs$4v?0hFaXg{QNsDjxFsXb%tS4|9S|3l; zKQNcDGe8{aU@7Q)u)2~kMs#C;!quVIUPzl+Ya0}~c{9KJ_h_Ky(1gf zMjft=E~#33Tt3yrN5G4pLewAWrFWc`Vk^!N$C~aq>@Z2F1#Yb6b6}>f^>u7-(4lun z!&}s=PuZ1KcQFx3R@PopEvo88aY@W21A|3I5ZINYQcqPG40UFYp<*ZXr7r%K#ulL+ zFDN>4%(SIzu(mj7=(VPPyImCH=FV&VxKUqwMc!d>6&HW&RKt9sX?~rFUIVCSO;vG zQ?cGFt%VGzW>*=ARic{ycPr-Q5H>1qGKLQ0PmXOmJJ@#jf!0wd)Ykp}H0xYQryU@+ z$z#num)3g}^K@3`PUBtc&H+lzAat+?Wuh3RPlI;W%60NH5EYT`IV0W%g-X|{I-`x= zVC>1RVm0tKyCr$+mQ1Hn(B=d=R3r$7rJLWIy<8nuWX?p)Th8&SYTLU;CZ^LVTd1@qY6_^|;My_d znZ^MJf6Mq3Der-NG*FbfQ(aZORdR zM^}=jB6M&OeH6Fi3^)(N<}ENmpKG|)mYm(^OqRp6)fL!!=0e*eB^Ygwo*~M+4)Fu9 z8iCV@%~uN<^9j5ZvBw;?qjVjDgsMwHDplu)XHOtdElWe<=!Z9hA@{WRwEu(_9=h4R zl-V3AQ5qp=7HVhtAbfB%;|h2Q!_^b=8A>*`;-)O))!(>jJyeo^sKWBYxmf7p=|4ldP#cSwA8vxJ&<2v%bW>(*w7J)Fru}*pxI8qZf;h7 zLqYOaEL;vAAAb&t-^kc0vNYAly?tivM5};J#HI(#T=MB!{~HqU_Sgqw_{5^w{@v_% z!Pdl?XS4R_vPn=a?@?D=`xVm7XJ%QiV0*9V5jNIa;Q3z&=w86Eq-$lo1}AU9C8)Rb z-AB_miR2~bjrRFl5jZ>xOh&XXY?eWSuA75=1!LiJJwE~p!I?W^(3Ofzo)2OnCV-FU z@snsF(GDwv*>V)lc{psDSy95<@aYvKG|#H_KN>EAF9TrZu#+wzjo#q_x&} zGGnB*wR1AJHuw0`)|FOC-@(+_>95?EB>$g=XD(MRN1}cN{$voX)WJ(|U5lw`m@=5+ zxo1TsXAI^cPNwNsi9o){L||c{2W!0Jzg*fOZVS^UGk$kJZ$EEm{Jy=vVEtxWd(byz z2z#+=x2G&Oj0l^7?smSP7C{|czjwxm7A#OBecGio@1;iu+~ra*vFkNo;;+vWFX5F< z;vMJW<|`ycJx`D8>`uX$nGlUW4nE*hxWGR;!i5t~w=AB&L?qRUjuYr%Wkf*R8mAG2 zt=T@bd+{Muc#>T722q#QNlj{I6y;9pkv_aHXJTB=c=CbHdva(IVNYRTGe|zLeyb!8 zJePzhPVKEEk+D<%NG1s;ss-KOk(nGrk-c#L%gxUk7uoGQn$G(S6cnWEy68J2JmTZ^ z4pQ{B9}6p!JpE{PH&RUFmrp=|$itVchvq{X4I0jDwXyU<2h136*1MxxGgnE`IIFaD_Pw2 z5$;^Qb62y$2Ne}6rNNNMQk_K+?$MlOFYO;u5d1~47k?E=^?xgp{@Ld9{;Mc(b~3l3 z6|}WBFt_vU`Fi{gvpjmmYGcB@f1 zb8_q=3w(__4J6(zle($Vh{7?Sl#Sl7{L2Pj2`*O3`F*%LRy&&KPVO1@%miHC9xu?^ zfGj4XO$GTuYhZO?SLISNaCsU0g7`WDE*9iX!&Fuc+x4mGgcMKO?B)z8$g5chH?vnA z($y9~kg6+pm071>Uyl^6JQx?s>BBEWP?FVq<*_U7`p)hbUyQ)UTt@dsOBY*TDO*;> zcrKEs=kSF}O5T%AvCx>{wUEDTmr^!$!sf#>b+GWjQ{_qAMvK2{=S{3g7(T}hItTH= z4_t?>y=}gmV81Kq@}o39$6#BBk`W+Hy(j?Vn2zMycL0&cWvdyO3n)rdJM$DzBy1S# zbJ2E7STGg{vIHfBV5KRi;l3FX15KU7WfQV|naag#T;SrzRg{MmlCGBTvBARhzUt7= zbwzxpZVx+d7|C^2c|V%!M)mxPo!fDO*%xlP2^`CmvP+v5cxxwP!Bju6bM#&7mu>-- zXww7CA(n<&u977pQq3wM;`y5KUidK3&8hG~gSom`PEka;L0$s~(FZD0O zjVmMHUE@NV(zp)CO((PXQ2@fqeoPQGIkIZ?Sy+|0#7&NTf`sw#m04Bi5V$|2*a2Vo zb5;-Yti<*^$Dc^yC=l;gdI!C+l!%pxW#Li#7Nj^yA-Vy&Jaix>^#k8=6{QTH+3cEl z*~Y54%|7hIG>Yu~DgJ7eeWXtN6_^tJ~L7_7R?tFaHwklgE(N%d0>*nl;MZ)fE6^#N>f4yhSd>NqgymM#gKKw zAXEI=@TR@U1}hQ4)BTZ{Lms0)(|=F7EjRG`dcVTxA#SLnsf`f?fvR&25&~7I8~t4E zMFg@0p$eX?Ms=IR5uB&MVl1?%r$#%*(81e&@TAV$zDt%J7Z7aUk)pX{Gw)!2ouJ6Vtxo!h7fCnKN0g@J6MzRZfR?=rE29 ze*)W9g0)8K#T_anN){Zm{HsxNFG<`0(m6PA(`Yp-FdtnL%2MSZ(08|aCLr2-mIK~K zsjc!faY0mvbXQ)N_3-`Ef4{S-)s`#XA|K+pboesvl2Wzv;h}H(-ClQPP0Ss>wHvA{ zw}Cdl+6t2_m2AH(%-l%2a)6~)-vD5-%2btB7!d_M{NR%Z>h~NBJ=I5rFw}CZT5y_N zc_|Lo%O)}i*~F!v1>})iID#94Ua5w(>07aGWHnPpG){|@s8G$2I+yo!5G}e>5WY2g z^arU+bt*U}(@zlTQ=~00aSbP}2NuC(X-;U``5{`poH4Q9LQ|25G1t*JYZxrL2=`O^ zk^yv(o_tB+gULH~1Y!-{xHqQ$U3x>~T~;Hr3l5t>EkxEaiNlJ)F6P7Q*p{amWJ%sw ziUkf)52QC&`!;;GprTbv^p=BnnCszl?oH9`O5=W$eZXRaM~ufjAL5_>*Dd(h>$QUa>rIliGqw@8aZ<7svUN7FG8WT!G?Ui1`;Y8m`ya%8 zk+QZerZ5sWqkU&sgLoDa)O+X#5^6m3q6-2-i_1KViv+X`l(ll%QP7l!f~~#Fzrj|P)vexVk4TM&%HSEDf?RxSTW@5YieGiMOuC{7_ zP8RL&!xUf2ao6j96<5j z!7n5w*NWXWI6;Oa^v(4LrB%t2a(*Ay9djys3Sk?U>&;V%AuKb*Z1ohdSJs?cwOycR z7yNp>6rRjYiqEZpe6BK88nQ59k%-Em|Namc1tm< zX%^CaT{;UF^!JfuGTZ=Y&*O}Dp%Gc-S?m#J(!|W@fhBjnQak7_(|tRx7F97U5}>_O z8U4x#Q}S<|F}#*)+AymPEmH(_5oauSS#OiWAXKC)^C;+k`%Vznt}1GR55@>6ui#RI zTruxxR|6lnuZ=>iMHi$`DX}D+?TshL{4imfO|tRZ<_>1sz*IN`Gp}YXG?x15hkY=C zm1iXCK;(QA$dTvFRqdJLlE`Rfth3J8sHNe(cv5-BEoO=9z5I|8dYQKq?-{D0+q)`k z^hm#jxXCn4sKd;9=TRw3W&MfMH9OJ!#%C|n<12U)EAr@ z%Dp!^E4q%AYtF-NHwzF#gDotPn=_yvISNl?gmvJ6gnBe)7-z~6r+a;96H5-~2AsfM zi#FG=Ci~e>AdYe}YT!>r6DxeqtNwH7toB!AQp#e>M^Mo8Jx(x;ij3N`naFm>48+Vl zb^Ghv!mEJmct#!9Yc&im7Y3HK2^%k zXe}7o*xhcx4ttE6VAHn8=Z3+)Y$@0Dg2l73Qsyq$+h1$da63V%C$L-`VjhY5t`T;L z#?3^&4SUnYRt|5=0n?|EKC-_hxh zTra3^W%yT~A5w#KQ(9{Jcur$9#YyWl#RCG16U9jY#|Ic#2<(j2L$LeC4CklM5GbZ| zhz|ywm#RM6>`tZzQL=0V>dG+4D zkzw$xX?R-qta+?yTG26$#^JRC(cB_9y#aq@>(`FY<(4u0jfT+L z52^^Z=R9W;`?mWMlH1iL-L%0I;T0a5useI^1V^N~Bel5(83a$mLDK`?kDty6$U`AK zToBaOvA*;PetwB%N#tyDuO*hPe)ycNt^A6d zCsk0So~B)RQq^LgCF5p#fO1@p#GTTRQ%W~Z#QAkWeXL{L<><-#sTU-_-eFci?sy&e zN{W4@VVZbd(Xo9f)pPs^%DF+qDB+vkEwd-b;Bb;w)_~$|l*qH`(m<}Lo#*}3#!uNC zw9Vj(D<}ULX8m(xkRbW6IWN37G`M_F@~e^a|&v5LkUMsM_2Hbu`%u(PUS{c5#V^s z^o@LH?y87_EXV!`&3uQZC$ZL}H#^e?ujW*b=lNqAKRszrQ$_w(LM(L*>d?lP=J`nf zWxMD3I$-XtDQe(_e(kL$uS&2Mp;E!~{p{o9;k7AiAn8E>kRIb=pzY~Cb%Vi}LhvU0+2 zj^pRkW#t(QtR=W136axgs}yn&@U5JHjRbA9#wm&?GCQOh2?yuL9Y@QY zG0|iqX6Qw@xFB$r#X7pnw$5oOXbvG;ZB;2v=Y~&NOLSN)AkFEM>n>~)F;`3`0hCl( zB}>DP&>H((=y^GZaB>cKp=BA0=s0@zQH`1W6dtHb=s}NOx|c3;lEE6QCSGSzpcomp zsWP^_$)o9BpczHC-ct$I2Xu}WX)lOkmIrT4*AT+H>**knfHf5NBppb8of}=q!XX9X zs+YPlm?^7PaXdZ239IX{FeX}`+uE$|q$i#?$fA6{e9E2{bJA$wqAMfC4VrTRh4t~z z!r=-d<#N+v=^3oyaua9yTEl|<0Fw2rh2G$H`|8Eqq+#CBII;GjV$djp-G73A2v9Tp zR?iyS9c|>P;3iOnDj+GiiJiPwX?O z1UErJGV&M%qgP-l;3AMT()6sxr`WgZ&wDx?i@4$~w?vYcD7CuT1Hjcrt%g*fll=x0 zHvs&T9(zk{du=D3BcGlNk|IO1z*@V|BBO&1MI9qVBVY6$Xovd~tT2a!1dW-(Uvs_i zzUR#2%)BE$cdJ~NfbNLN|K9Q?fQ$WE(|-lb)k$bW24X>xq6SSgGQ>b}J{3&ghA!j0X)L zhNcJ;dwnq4gwCil&?~+RWt^una8X?s9LKpmE_n=j;Op%V3~xAIM$}o*UOt2p;L8|x z5_YR0nHSQ7^8Wa$GozJS1FXLqC$1arfm{mA&f`P07QM86P^2&z9UZUz%})Z@M@%IFfA zD=N(4C@vRDn+tcm;V5F4mr(uWq@sQakN}S%--}Pr-u^z)l8P6{>ytGFh;#n}Alt+) zSe9w~m?oyr6`}iJAWKi8jieua#OTvrq+oBSqlMQd0dH`i)=~ejNW!(&+Zd?v1&66f)iMQ*7O&wNDiHzVs!s z?ScL+&r_J}9A$Se08WJ{GbxNk8CxZE|G_%g<-CJ?$EczUl8yl#2&_J;mYo5Hiy`bQ za6Y`J`>1wkXwWZqa@J&pju3I;T;<84q78Qu&LOHx(xlMX*1=3kZi~sb#bYc-8fOaD zlkk(!k~UCTIuB)nxJAOkz;J5_#Wwfui?L9aq_p?>DU9Qs!({e$#?KDa{NZ zd0~|CTlD$mPUExNP$mi;=DBHT{qVEW&Ap|aN2jH~?TU2j6ez(Su+w=5{>40e;0*W< z0`%0v2HPVDaJNS!v-QeAactf?xdsFf1y?i%4K7dVA;Fag6%i0C5)oL5U z=U3eOCXB5zJ$p9WHI7bGtbeAEmA*M4mohD8+U%>wK0qFk{3(dK`SE$;Piuas%JgZ8 z;gd;{!v`|p%qHvPSF7JSYadM~M~cN3qh8EU^z)Et-yklKCN2^;lt~MJ-u;d_`woC> z56C^A@n6I4oBo_%%S_J%3!^S2X zkO>MeA><|i#QNYh3=IK)Y9KlHGbRTmEvjjpCf9%^AKS_~h7IKZsG{S8m6{=$6Dl_! zinLlt-Tb;38;Y_KuK+Y%g1O`MZ6Sc2h_f*BgdLc;dD5-d7fEMLm&~@2;T}5?kLL=Y z(eP;m_^5i>w#kVN;Kzl~7KRKakFr|igp!;OLT!GqaEnS_KJ4*D}?a>g5*q7oBfwDDsyk2fGo^b!}L(iAks!^d&s66WdAdU->Xj7f?#-t}7y zh}B`S=PQyYnbVk&A9S!^J_AV$1gIQP{L%=xjfs8(fKF zz8w7dt%AW!SB$q8iuP{Lr zfX6iEwp)OXGC`mqaNh0?iRJDtw`shqM}J zjL6=TM>hZuZcV2a!o6+k%6@>lZ<766n(MxWAZcle&mI#bq6&@pdY8Q?!QBay@PH=! z(bH|&mBDvA1akJN0B6R6VsAed_!r{k{0}roExon?>8`HHL^$ngLn?W#w))=2H*`6nc6kdoNHz?E4 zfQJkH??VS@l-Wi+p5ebQ%@@N7E17flw0~1oj2Ea)y!>>yr9A$Lsz%*2TK>y;lUhe# z*b@qLu)4qhI1u%*z3%UZc%W|n!CjGhP1VjNh1Jd-#->2D{Y~F2Uw2sQyitqkLdQVQj%1U59*v1ww8Ue5Hlt$)ufNy4j4GH6o? zZqi_{UZkj%uNbV-K)#+Y-t)P_x;$DXT!-Sy%Ze~seCPM1x4is1T=F2-+p?yoP>`pGD;^EDJ*>y`Fzh9MKBjCLE zSz#&)U&csE=WnrDjM#GR?={Weeyo*5FS*{m~ z1@;fQ5d-!@jHhi>RMUC$TWymMx5ByNrc$`0|N3PkY>LlG&IZ&T!{1n9x|go|rNZfS8TuVZx->O92}u6Evgo-*oN80DyCJAQCLAigyeCSm~E zM^NECDg8Ap^2XB8MT4ZBbB;XQ9K0B1eXsLiA2U+xdo5X=Wp3;4_jM37>rgCbQX7L|~6rqiK1+nV}t8rzteW$4BZTuTqWjcrZ` zabDQyItZPXx3P?QhaQY`nrBILCO1q3+@ZjizJMpg{k^UC<&J3iCit;+Xp1g@V=QBE zq(^dczn=00Vmd#Tch^f+DIEbB=Oiq#Tb|?67UGa|XP>J{{XCC>2=P3R5L88hM;TfP zfk$#9X=70xc1{M$wYJXG;pwX(Cl_#?NxhTX{9x^TROie1&eS2AwFtNlB--Oz$;W*! z7jqr0QJSp?_q?v3g@sr`f?ZQIOY#=Ab{X0=nlq@kYY{<*tJE@T_5_D$D5T|V(uZtR zG7bAwgd^tm8ptJCnTe~7N8wAv>UHki;Y|Yd28guEl}qtQ^=g(#7Yt(#nw5{?&TU4- zYL%2o7ZhW6YLykp7Z_s_jcP08%a8F%Ms+qyl^Mj8YX)2SY8iqJ&jzWHAolaHGlX`` zvVOg$6cQgNIe*|lFTe4$%i+HUw($Nt4)o9QIkx{5H~vo?h)CGY?hpJ}{|h|+4_;b9 z`;TQ2?uD4GdTl*wl{)|YMFlCnh@+|D!XX35Ef&aMc!YNVau+ z4g`&^G^9g*%!Q)0*-2iB?y3-}?u zoq2J;tV|ICfj8@0U-& zUl1v*aiItZMFpSSCwO>poHPa_{=v7;Y3$OGk{a_dWaOG^^z(LdR%J4?N9Y_dOtO%+ zceo)Ln5gXNTlk#6jTc_W1mc2hY(XWwWZoJs-|L^Y)kxf-)_q@;HR=~+_+PZ(KjFfE zsT=fvQr1$&ZsvxzrVjdcX6A-pWVW6D7lZxZIEKHxs_Q3M?8$Lil&mUBl?4z&`G6-< zK*(Gyzxn-8crZ{;HZqT&vSLZ}sABYqWRw}<#K!Kr1)AX}qsTQ_anHdorVZQHiB(zb2eT4~$1ZLZ9lRcD_awd=;+6*pqUeEjFjKu2p| z$22>+^qBG5u07$IS^Il&vx5(GIwGdfv_A!*X|K{F${Zz{uTK-DxWlFnENu()9ZjRng z1FheqM6@)vhT}a=8(CyJ_t+VN7H;2a27|(m!{(!+z322uL*XErj-yqM$qai#ugwVd zJUNfE_MfbnliBhE4`-;T+*Jjykp}8{CZ4OL%LbB>Dy5?wl{VKl(gB^tU$qB3H0J7y z^}n-XbRQvMvWf1!r*e0+N%T7r6$ct(P`l`b{PGM`Mr5ka+M?80yhq9Y`hmsW$Fgbe zZu+^r%l}o+^q6#zcz#{5N-s{k<9>kSSTt@==6c9PA#os?(u_sI!=hAKdAQg#d~GSD zif*twu~{y(nb@EJb{UM$xkN@Y{(Xkr*+vj{{=(IsSWA02foTT_+)_v0tEMZXc;wW&JltE6Fnf z68be^Qky&co*wWCIuILY7%2r&Xqfu2MtvZ9`3@#Sw$4lB-voY0ylWGkR{<#BC~3t ztJ$76I7@T3xSr68%Mds0Be^=9FqahDy{@`BQdW=rmR}UM2I?pbbdqT(bTA5ifwy&3 z73#>mGzvkqw&3!$LW#v}dB=BH9l&KCgOtI)!l+O4QI741`${wIVUOkRNt9`BQ52Jy zHSalBxW36VUIE(0$+(LKlMV-R^+}8*cjB;=dV}$l)`Dka+a3Ypm(n_7&C`U=lVG8| z+>aGfnNu?`unW<7S(tJu_D}q--Tu!1`DUC(_%?$GpUID;pQYilUIIR4RRa#k)ZXL?EY!z6Sr9;Bqq#bmitzWJ!iHre`oGdYqK2CP)v5KL z8yO;g5h_gUwXpaV#qCwCAFHfWuL8Qa&El6e4o8Po{p&fX;h8E z1fvO$X&sCU!U!&C-AriQ%_6rONDgwMJ{a*v)l=?%R14!N7EoSWyD`K#nA9-!KzzR6 zlZ@m2reR$D%kA~l)?%%bYFcubt4<+bE)&k$wjG_DW#Ku^^4BA4FYtVrL>ya-TiinI z>FXwO%he6~7!;=^t2HVw!G9BOu!}IM)Un!+4zs?%CC7MXaYNn$P1KaXLae|Am#Qq2 z+ZL(Z;L#Q{DzVQqbSWWitKSBka#wao`i42t1P-|=Q-7qCx+}J}}s~^9^J09#WYFwnY z?yyz)o;AlWj&UnZtqhf3u&nFuBrV|cccE&iMhyh}h!0V@!B}pb#j2owbjA8ekRfZ+ zN&>MzzIvF0?`dGvS{?64)ecI)0Y&uVXd{AQ78&+wWilZbc=T2_3{y^Dn)z+f@-PsY zJPg6pAVDKD6d?>U4#5ZN-%`$K_f!HIRz(^F5(|(#jb;$p?_`Bdp7sQgkd)e`*@|ra z7`AayhB(LpK@8s@alFLdK(D{^JWefCG|TM+OgQrrcm+8*%qq0#SnI?Ap&!n-BCafk z=~{=j`%yG>{=gB>M@_Z%$$qf5o@M64FyDbIu)e#`ofCik-v0_xnNj+LbYx^tZcP8lIE z==;x?UenChd;CXjf%U(hlmC^$@Xwe2zl8+0T~ndFF>)wNM(1B35sI?L%eYvA8)uV-rE@hM~wci=jP$S#P`!5zxMV(C0X}j;pnmBBgN@t`feQi)BQ&ycQ_LJdS~R@ zbyS)=E2oi``*wEn*dm#!{2naXt9+(L^;Z)Ca-JyscaCM0*n$NQZ5e^#d3jm7G^Aq2 zMn(omIBcLPGa0f4Q^qeh;e&w=Y)2%&o$dL4BSLW-tM&PgLJML!oj@Q99uwgMu1Do{ zak3UM*1$=Z94)>bmFGd9DQXbZmZqAW)vd0c`X6XSZU!hQ8!Jog&o}0_nw+$hjKmg( zub;)qonn8D`R8fa$aKwjgJu$KXcEb=vm0qCX^lL$z;0b-5>MfF%@L0-n4R9G<-O64 zDf_uNQ>=64slAYagXarA=`Z4_>ugPOorAosM}G+~;>ex_rf3^_`G|?>08dkRJt^!S zo<~63Uz@T2syyu&JS%DAEhCra-2oM3hhmq}K?3Sw0*`iH7k^|UolNShRFh86(MnL7 z9~Pj78M|_5E(z)3I~6^tb{wa4kO-i+@BOGL#(^SSwv0**+@+JW*t)k-Xa`IaF-R%EEdY>Y*i}s z%P2cSiqg`?*rv9VgiNUk5VMUq(yI#=e3M28%Op@(9TXx=pzYO33pyeoVL>egA%w4i~!zn zL45ELQGN?}ieE0o&cKe*Kr~wT-E%9Y0=W!Zmg-A?NaR&l{b?xO7!FNlftYYkD@Vx8 z6(1#xByLxx=sB!7sbdbz5u23I+q=>juxml!rahG&Bc4?~uJX{Urv{$8OQ;Tx`=+g#7k(I5Cqs*y(c$GV zd!trzfxRfbBs@vzLA?xen-D8Kmx>iW2&jOcWbCk}+l|090&{JFiJY@v)4I5-mQ*}Q zo)ufY*=!6w2O3Jps3?LB*4a|%>as=hmr(JJzQs!&Vr;csaY13$8_`6G?qB6?+W1E? zFRv$O&%1F{>XKZtUACHdR1L$*v{jY`l3`RHA#)bw^BlT-%7J(Tx20ZEHmoq6C){Rq z%B*(lYVTEjOr99^rYYT%Hi1s-?Wmwja~k7L>A@+mPMxzNL7J07ERj>r=nRWQQS5Sw zLL24Mc{`SOIZyDvOG&>MPQlLiMs%=z;+Cxz<$$rW^XM&{d78}^$4S1W3cpKsESi$Z zdsj~VPW@EggG6ucw|PF@!|=(rN)!UcLQjbU&%d)l#)-O1=O}O&Pk$wH3kGoyodSBw z7jm7^C2y~s#?rjzo_;I8`$d0A`yn=YVp-4epJ<86-x(hZe6!#-t3q|q2+_@-3$te& z)987Su4XW2&PfeBwoG=m5h5OxC1-m=B{yQQoN%*c=4pSJuP??2c`Hnlb&usM)HIyn zM@To2U}qPjtMzhZu(k?wY*2M~AfBvuIAGcmH#Qvl$86UYj!t9zdIx`OTFaPa!vNss z=yuOi&DW(=avTFiW*~_<^O@UYhq7WFK?gizb$%btqpJq3l;zi^1G;TrD^A)*A6c{H z@ti61gOmeNLE1A3BPmfc~f9Hrgl80X3$G!();NQ zqgFc{v!v&}BaH)*V+?$7-m_^fStWGE-gu; z27E{O<$A=AXkP>=?O&iZK5H~_Yb5`;+s*2o0o9*;a7fK1^o2!=qnz^+o5&T_XF-KS zj$Vrrl?b87A&W&OX`N+iETRLY5^ftH*=p#FEzB$EbXI78S=bcC3wF|hTl3~nKCFT! zB^KQrgJosI;y!rWAy67vpswWTuX|C}vJB{14YF=S-L6HoW<^Pa$1*XTUl5Sgm8?3fM$5E+Ob+#FUu9JZ^&EGzPv18DqO9hI0M zQkG)6@4?309?IN-Zty@!mH&ZopDXIW6HD+3(|-vl{z<_7L@55Pu`V@2Av59>Wye{T z9u|R}e`0N3d4jp)jIgiMiF5GMS1kX{V0I9zA8bKK!y}7lQuX+}7BIMFX1>hxl+VQM zrK52Q;vr~+p~p%l*NFBYKJ$Jo{5h1Lw{H(+w=mqrL^*5v`Uw$iNiG z79w<9PU#loZO#3tQntQ*Tn#_;$)H;4hy_ZTt#sIk7Qc`>C@0S`xgw%F150-5)ADqEEeG-0cKQ z7XHVj*HnK^9Aq!ti|gW|!O5U*AtWZ){7!gcwlY@v@o-4!jP8~pTCUQ1Qz8d-i0`eC zGAqU~{Z|-Hyq8svS!HbmES$-_`xY-6_=Fw)+Z`mf3IR{>@Lf0ih@An_F97px5g>PX zmQ$ZU_hO3?eEGax(0kwe{EFeu@c~5>|5(PMz!H_PV@M>a-r^nB;vfwtfLuE)M&N!A zd}66LP>~DD2`nW?c779gY`s%nC%=hIfP7%tiL!|UUduCv8jT#^Tv7e!Bk2R9{XXto=4J`&zx?u zgf*wgvkA}2DMt(A*EH=3DM?}zPqyvtw}OU)g&{peC@qMDQ^OfEh{r9;)5KH^0jtrV zEvnUpS0YH8G-!&e_o2=aCMd}I7wIb~2~}r#>k~wWRGcH#rSMT#X30fpeKZ#r80us2 z&|sO#YKrZ`V3F=KX-+Rq!^AefAUGt~RW3Nz?(LhRrLd`g4J*xy@PyrS6)AZsRK`e} zsVLyrmcSb+12FALntTWXn=`QZjWQvfQ(h@}-glR?j6i-SP>m@_at7qmE1z%_mk-{L zU1sejeOzvKpqgxQPKs#w2GOG(aT(719(W7bcL=;uC09XT_ZUs1fq(0FPt~JRQq%c` zyLQ4vc}AW{Vp)$aqlz=lC@v767q==FDH4$qZooe2TY(I2UWk#8#vr*dByirZDUIXW zFi-V4VN5y@&OIB;SIw zq^=^Hus_WnwtEC?xRSV_oKmKHh%M4VjGllsc!ceU z<(7FGCKUZ*YnMb&1x##Ui95FD8P~4UT1nf6#oOy4+F9ro65~+FCGzW*gxgy4u0++$ zpZ9KnrjCqGedf6N=4xC4aRPFsE zDbet8^eCk3n#RA5o9DKE&qCGui6Ikbsn#W6LDi&u1d^wm>=>(ZcH3>^)>*f+$-|tA{QtI z&;G~(@39Z~yp@$LpyQxdNM-lw7m}SbZ_bQwFD?$)7b*t4nvExZ%9rQoaVGh#*Ag`f zUEvN-cm2%Nqb1DM}rq6iBHEaYKc$ef3#n=k=MY%;Q;_P2>-RN z{_pLV|J4xq&um-R#K^+Nz?zl$U+YpzKWXES`>RH@(4wVdz4_w!-LO-ol7$-guOcOi zSv~<&Gm7eJsFmkjQdd;krCT$0Rb8L&AK%4Q2^dDb7D~dG%`C5+2kw)s%-r6dzX0|C zG68|!Sd`YK@qc9Nx)Sa*31@8UP>fN4GgIry3kTyk?ON#NGMhPtiuc-dqWum%<;**b zG-9?^Xs(~&Saz7Cud-)hBQwS9W?&4qahOOdLu}m1VeSO)A_OWp*a8je4OR=zv~c%y z?_(r#ibD#W9wItLZ*e(DYt0@p(K`CMT0ihwT^xHTQBF_^l>)8yIAMy{`U2ehn=kq4 zZRor=m}nH3JaU;$DCcOu2U!v~bZDKC2)0-|SYNzTe|3+AS)Sb-<}Y_p(inIxrL*MB z4%BfAE}d^eZ4tXwRAef=@JZ)a1=gF0fy+adsc;V$K%vGeC)L*$ z1p0(*VR9&Q4^%{;Rxu`>VDbu?cG-tK`KigiTzB}+8K#|73~Ehrww%@~@S~?}p9oYx z4iqCmOOnfl^uUcVHiUPB*LkfE-u_k%rilyvjY~5piwi=CU7|j~m?H}5xCcq#BYGJ_ z1AR9(t5uS$i6Wv(L=_RW1Dg&O5AIhdjtC9y$sL|NTrZ|nZ>4N+jgl#1h~vc#`au*m zW+EH@Z8BI3yYYxRc1O}ahKA^FLZzMqC{3)14`Yu`o&i}C4{QuvI|J?~xvbVPQzur_;4LfWVlrOSpZF;OrW*63! z5-Cl3i}N*OQu_ar1+l<@EdY)M zcR(^a=Xu{M_GoG7+K0p&UP9md98BoP&VAfNnONZFo*H24y3yEnBnvCGPYFF)UGzvp zU~=2~#pKsM&ZBnMC%-%PXo6B^L^@GLH9J3KSmV7qPo1nS($|96nI(5lx|KFg3fn1P z7ny7SzFbj~j5ANYbYSc{e)WM`g~`K^GF>tPK2yRZbSBN|72%!UN9^-`=P|QH zBNf2Nf1Z?{Tfj~8Q2^xdhbChw=r9^~a6|&9h1?0MpV*WkwH%eq@u-T|AimUMkk#2r zn?BRJQ`XL9yr?Q!N?G2T9}Iz{c%Oc;szRfIj+!00vbM^-n}z}zPPbQ=0agr`CiSWz zP@lsrt(ftoCXZaz?J!QaU@KKxGf@hiUj7nlMtn((DUl^eR$+?6JO{}sBLa3sPar(U zz%xumVOk}O3yQ5hdsATRmt(TzNlgwOsM$qP!%IDe- zFg1qgba0y|N ztcQ>z^2C-T@&w<8SWM@--3sADl<@}g`(g#cUuXbxURV{(d~H5Mr6(lN70q-9#U83$ zB|E`l$4Ov>T=s-ejnAV*Z{n{NjqtA#W_C7#yV&Oz#o64w!~sGye}EW1AuMnp#?liu z2jw0G*k>Ubyg;(=p6s>4tdm-<6pyBU7C*h3n8gDE&rmy$c1pH6_o4ERq{=FW+7T7+ z3JPl@0z|%b^f&oqD$zvLoCdv0ldp2G_}xCcvX`n7>l<@RNu+XCVCIP!Ju(InhnTi4 ziC2;d^X=*(d$dkgY(iCAomp^dLK-42&g4Yi*YAAq0oR$4#poDy^{UVxMncSY}z~K0m5lq>NiugG}Y73KN-cY7l4`88aPE_ zWf_pJZe16zGhXRZdUexQyae-{e|GPbBZ(}#k<=Hx*%CGEs!#1z-VpT@5RS|t?K^6~ z&q=otvk&OVaA~637TDx_1&8}qK<`VP*VoqlaN*Nl!6@%&pCfMO#GdP30X6Q3r^9kj zl@82MhUn7}d-q}QuuX^X+o-;@O>KamHjPdbKc{GOUvLZ_5t#tHB(xd*E^fKO(t1Vt zz!(m5+~}w5Pa=dzh_F-{Q8w55wOv|4W7_ILV;rp`5=)Ss_DL*YcR)R^*{-ogozU70 zKG{PM-5wY;$!~roVhV6QxKHG>28QBPPSxW%RH^nfj#pf_p4P0pt0zIew*8*bFZ8yV zHG}i%u;IVO|3@sbNIL;y@N;?pg8J83;@^Ap|GC5UueS34D%h*;{Pf~czHG%CjCFiT zQK5ykHdGRm6AUk6fr#SfU2P~6Lr)*6d%b&*3M=(e3hS+xAYv7xRWyDM$ zxA?}-+S#PAD6Wz?(>J|l+E2W9+E22)%)bBL)b;{O?`NVkyh@9JsVQgmCq-CH7Kwjq z!!#Pc3if41c+ixciZBElXse7_DD<(Q`n1*ThC~2LQ~pwcfqat!WkXFup<(bBVB(p9 zjHp>MXNL`Gm7Mmm{Yd^(q1LYRXyrm(C&;IdLFH7t&zXOdo{xOC&28+Hr)D3S-%IPT zqXpN3(_n)4SLXd@mW;1~L+3t7vadqRb%}D-xBA#CT5t-gG8Jknt`ii>IMHjqFdttu z$5edUJ~p%wCOpgHSPgSu#Bag?gTi5^eW}WZvk%v5fmEjBa3iJD5>$IMo)J%#1J~yh zgaP3U$Kh{mnMoQdd6Dwd;k~I=+t};`*Bb8hk<`XAPbI8toKAskvPZCfCLk!EXVu(f z2!~Wi#g@vSg;1K@`qc>isOJ(ZkL3RQ;})aP1s$w0iE!>+nvbbJt~Czv>-pCx z(h&Ht6YQmX+%ODP6t9v4Hm6wIeVDLjL$`F(43k*|%`+|~fej&CZPXO1EZ)&9uooDm z1=#>ktJ`Q{oC8Pb`|K|^rE~yLQY4vpZyqU~7$5~8(6v%KK8Vq3;074nnj9U#GpR8d z-yrcajM^So!)B+{v^D8NM;EOpYPM-2YhTXjbUj!F`1YL+sm#tTybaB6Xl*AeZAXlU zx^RT&4EP|+Zif}47sOeoW21IyhTCy+BP!jWwD4Ew2`Vd)a&`x2h&gn3&H<&pk8unE z<*$8c8f}Ynn4Z07-NNwm1q){$a*?K~Oix@>66>Yg1$R6Nl3|Iod00kkV*0d$cnK&2 zAA(|yb>aq)__OEM8%P|7fbB>y(lsDrQNGSQM2BP&4jE!mXr99jatLh0&vCyRyu`84 zpYynhv5NBmWREw5TY`Msoa3-$2NDNGvCD+G=Lzw`!-gbrYD1gw4Y{H6`5WsbG5m<` z#6syPlV3=hmRZB{FzIkEvbfJb|JF|z~LpV+$J-Tc;oXgn_k?or~=cjpF}h8kTX|P)6aINukwJ2|t(zknsn~Z^jLKm{VN; zJ*%H!cs}gE!HYSAbyY#qU5eLV4@v=o#j0#^+IbwD}G@Uy{v*7iPhwK z%7q2xt~P*_qN2UTx~ycy5qJVU%o+vMFrS*hocw%PHveikC}RsJ z7pYD8{$_iP!Fc~fGM66}BxvZsOz zP2WC-44FuBwOBEeF6hyo#f&-adRGcX=0qJc88&BGvxZ`>;g)ze7&mG?<7HKfpt>=$ z2`J8f#!yM}PVAy0IJEATyVw z;*YE*-nivTc5?e?|KSKVi}YsF5hCZhCL_&ge^6)duvlef=gmP{)Jo2u4G44sU$*U- zSuHy709>hQJ1U#Dl0@K{VQE&_DdDSs}u!xs)ZF^3PJoy}+9rIdbqEkG0xioRyhI6cT@L+4i?`U~c zvb|dt_SxZHH+G)G70Me96^;)D@56>bj*`A`tXACLeS; z9PW)<&4Uaz4A%9_MDL_t_uk6AJCS=qLUt7F`EId0;IsDQ9@%Gz{G*1SszpDaQ15Oo?yagR3yytB>qH2}SoSooy3IyC$~c~fDb0yJ20D&k~J z6;tUce6?Za<1VORL%m=);_Oju-~W(Kak(WIuW zCSru>((L*$1_P2|6Owq@Vs_dD#?3pO_$n*S__V8WhBKJ)NDT{eV=V!D<-B1=rW#|` z<23|6J87);vYaN9vESq6WUv`VEqkW8lnB%uK3r{U$~Zp-u$K1Y;kQ9y4Gva!iL?cU{k}T-ec{s2d@AU{HX?;cAY8LboX@RpWm2 z1Au1696Jo`L0ZMtbfEX#Fg!x+P=z6w<+kKx9JXbJo#@(+ewJ+jDWJ`aMc<7_OyLh+ z8^(f`)w0cTvjpAn`xw^;)#Q$F+D4wol;NUGf3&dmG<2S2!C~WDE*cIgN@Tq1A3q;1 z(sGZY61rjt0Q3CF;ntfv-i$f!-Y)SZq+u&_b?ZlG_srzr;GvYVzUCA&Jp@YH)#tn* zIYd+%>wn(|?$x2qkEss37&TNJA(cLJ2h;*tKT%_gZ$Z`=Aru>5A3QpEmI!U|nstbp zpz4lEy=5FSHPKvHF22`QHLZ=IepMe(!Oh*xh`DIX-z$lcyGxImxeMku4%R6>km@Qw zpf>4IJ;pY%B`i5;VRTdOb5p6YV;J()z;v-a>{7?U=a9=@xy}C5(=gKzasvuit$POo zmeZXB;Y<%jb<)A4h?9Mz)iaS6WJy)Wx7bs`<~TsQfNMs?WTNithrfH_ppqt*x|nxl z*8qKHqCgw;b=2AA*dpe433BmX6%r}LI_2$rI}H5{x9XtO!` zI8mOJf=Hq71ux@75FE};O5-hZD3Z2&3}j+TpC%G0t?#BA3T>*YPx}NW2LMpNw3`|=LL1~&X-!Z7*hVgQYn|IJX6pvx9jYHd*Y)f&m_82<3pO2kF-lGawof2 z>xo}uL0Qss-TsD0q#PXkEg@UJe)o*Si7eXsIcb4KbM3tej(^K|Dv4N zs+I>o{5P1*2F)W>77g7!&SEd&19a(0y^FI^Z>v3c8w$r@WmaKYFv>p7ImkPwX}#*M z81qAk?k)q?J6HNeJJjdr&CU>Nv?0@Q+sDDC)4~K+i60Yl*N}GdVG|~}!>AF`I1^-k zXfp*_x5+OHnz2EH5}5Qh;{@8Ev3SO`D(bOAEG8ZDL~LWnMi?@&3H^EHgfUvv4jD4H z(L-BI=@`OernNI3;3Z?EwBh%UH))leZ*X{>nW>-2@Y}jHzCsS4a-;`40$Gj9pE=|Q znUS4eyjJhUAfotwfS&JfTs@~8>+1VBJck?^I{P@;1id(hNtNaI%fYC9;}+HhNGL+Q zrl+}}Bp2SJP*6b)z?*RL^1wy#dT{eeVOUgqB9~fuf1i58v*`Kk$DLH2((+0gT`ol1yu)R-26Xc;!XQRu({q za?et6qlVyO32HL1e6_@>IO(;?-)md%ccERX0>VXnfAC4Ct3dM~hv8S#Ic7R9(>W$P zcl^A0KZM68GgmY5HBZ}=WIyMwbp!_3W!V=pH4s$kK%%Y6q6eag39F}9cES| z1}u%~);zZ9gP(a%F3!FpEP65)&4p3fzE-JYjw%OR$6}jnH(mTS@)T^&rSBIX)|URD zNgoT3)?#JF+3YI`Vx)r8w&qwJ)(LcZ2uD|7c!E15fHm{V5<%9ZEXQH47r7NLeeo@R znV$F3@SG`np_A_Y;lq$41eVJRAEXU|EbVCF#>8r*A#lGs*#&O(vd^|(sB?}CA!8LE zNBK6oEPkkckAO`4P3<Pgr9Q`5Du%ZtU0qP325sfplP@N-VlA|k@T@U#wKXjFkF=x@^Q&q1$7>Mq zKfDJ2zK^*6<39TTNK5{!q@kwer1VqLaGf42CY*%^p^!OLoMpC1RLs+sjBGkmqy?cs zqi)S1E4>O}4j+S5q=%nQLjMaHb>I&_O>y8qpOO#pemGiKJIy}Lu8Zj+>VwwngEaqG zlKnp0y`t;&Lne7&Zhe-(|MGd^^{;j>gt@R6gyV5!rwm2kEEA~3F1;<#e&)DKz%F$d zhDD#|beN7dVZRaX#h%FLVAvJqFq9qKDif}S?#Ke)YQjmFuY(TBq8FbMAxDypVvk3$ zcS-jYWm3Wflv86YH{(RoWUVv<9p4`g%bCQY%t6utLTxXaiytTT;N@gbTap3XusC0; zx~rHzFdbh+;z_BR2XDpoiY_u}fm{VH?L7A^zY!m5*V(oqc`9s=2jp>5#1@xVTFQ>F z2-l@G8g&t%q?=_Vvn#TmUB_X?Sed?7{z2pwH?P*=g%^v8Dvntj3p0hbia3_UhvAHo zN*7{urcexS_S;Y40loxGF!0zoM)qinGJHJqZ_VS_`34f$-NKxio-kWW=EeNze=M@6 zBuP5XNz5YgyOqYf#Prx%5oYPa+r`Dp!1jHE~|b^Avswwgd}fmuC7wlk=G3( zjnY`BVwY~&*wAP&C)2fziA*HWC%7j)VF*b~O`3$MN=eMm1weaF(k!WmCpdXYxi~Wm ztJyGqPrT&2>Z^303hFjbp1)Aee#*ne#bY+e{1ZcJ@W;)D zmFX2{syJk6(z_q%+W~s$Z+aB#c#HF(;@R9O0qEMFg!p8q)1jE2B2vc=?v@O@0d5eK zTQJGRH@8NS;f6=vqPuI4EILtQo3{v!n|2|o(kEl>Ji=cu?dcytKeJGK(#xkeO+%{= zT4PJ~#gZ=xd`T*echsG147Rmr?dp$@+!J9u!B{~65Ced~o9)2K4d6qrV})QtuKzH= zA;N5jc+T*^m6Ddk~|}&`1Q1HtgYGwObw7A>1+^LP>d9LQo6#Q#29i+85|46H8(()_AITqq0@XIO>+I#jRp-J zF;%&pVfZkr*|&MpU9yUeDPQENN_A!Va&PkGoN-mQ{|qtkm747_8r?x&$FGCtD*)xo zN9HSp?yW0}wMXi0Q19J?@f`t}fjNNZee=_>z%!+yJv^bSZIgId$g_OuaIt1 z&!drQ3(yBS>kKY#xSJMIl}I)$CpmaSJMP=JfqMs?&;LM*bW`96zVG=oL_&p60_v1F z79yz@KBH1qmxuIw#afoq?>=X4Sgg1M>fnvMF_3uv;@%+ldCNJ=rL&AP4v|+NyHqF6 zDnp}Nj9>)$jotYhoO}q%d=WMr3OfEOitW$ki~8D1UZ?n?Gh!%nIBmG5jP^yOu#3I! zbZ+No)bs?i3EG12Q2pm14<8Tc2Q@c2@D4}tc#p(a zhKi<-N0pV33N?8hmAK0X{{Em6~*~3l7KQKE5ixd zoW2fyy~9HX7&N%9D#YMWJu)}})iYCkkkf4%|I=j)?95PMzepgiuJpz<^EDL)A6xC+ zr6i61=V#Y&%Mhm9!6^6e{*F^i6y&MGg)+)W)f@W;5{SmFU!}{f(C0t(^kh|PxF$cy z-vZcwjf(y~KmN~A(SPgd{|A`w|2}43_R2@7d^^|OUX7X92?T6u)`4LV1|B4c>K@P} z*y@lVi3ss|V+~%3*5a-M*I+(fo& zuIqeUSI#A8Kc18qQ;8rK0J5En9H*X#PaiYBx0&DxVPz5gP76++pZ+N~_r!oxP0%;V z+f2}wf2eH|H$QUo~&WixDmKS8~!ysis(igd7H`LVoP?wK+6>qkllr!KUBrjWjok5gVqE1UqR z1QQ~x3tMKmF*Du7ZNk@4PV6G)7CQHCNi`IFD zCa@M8cts`sNg(w0j+X^VK{^SOZx%v8hT}!irPhCqmq{Qxgr)}Nx64vUHH>FM$pvP?ei7JIrjI{d&ng7wHYr?O(Ug80kI z5Hc=m{uglYxjH)w+(tj@58ry|Pjl**193Q@-)Zu>6hVZR*OX z)I<>XnWjQTl3bSq4t=&9uZ7?jV;r1{Q2*AgxQT$ z#!8#FDhTb1v*;TJJ{mtcO)+RsMp<}k)VR# z<}`-SK|RnCh%qCI`Q|k3eN8oMU;_oNyfu`$PBJM|lSRx~9PPO1U`FCIC`e3cJ)1h) zNY)zINv3C4bHa>E`p<)InTV$=nPE5L9~!>X@NOZ7xFyEcQLcl=lJ*6pB%vaso?`p3 z%L=k~{hPSaFNBa;_Qj~oufoY|kZQw|JhP4HV-RxwYg_SQH}&%)xHmD28hx{M+XRi7 za+%ee$1a7*Yqntx<@GIP^*_JU@>chT(~qCVW?i*h4Yrp*ljUTzaZ27@%RmEieq%-~ z-kb`4L1w7xuAr{tR)h^x&x`e8L|I7(l#Gm%wxb>X1rvmTeGHw_jS*EWM2z0~)l0x1q6FYnC)(9uwDe_eroECZX-%mEdQPE38^wrx=;!VmJbN z?v-_$waiwXr^-%QfXW6sTq#dseW;TyrCqFAz|#D&0=}_y7O8Rs>c@5jvqVxDW6y;#i}~%bpU*>7)vGRVKd$bKDpXLXYjh#dt0*&DK)$6 z5NVKTbg*2@lt?eea3zWVehxY4<`>RYanKm2hnKY{*$LO!sq(R*NMFY=Op@<6ZQ}Yn zPQU;?GT6u7H~?~e>>|p=Ib~eIYg!ZCuh&__pjQjqRY{VDqK7J&=QL;y|KtMP#B}<5 z+LH4NWGc^_s(4K~<_X7EW;FEgX4PNr%M-IJba_Y>`Qq-{eqTb`hL^-TJ!xMrKdxt~ zhUdv%W~*KpKMJ;X(W^1c;4lwHwam@J;X`fW6Cv&NG$}&hsz+v0n>^07vZZ-Zsc}p3JyuF^MN>HfVreXqq9~&FnR?^f zh-Os9buy`SEO8^M))}sPNv^)-Y|?3)NGGLkXQapt>u@iqit;pSpMj(UT*6kpJIry? z83YcG<&e=nr)dO8y*C7I0}4swFvk(w?0}CjMfpm2tjmzd7XqBW>^qSptD%3k>6`BY zfL>PDl{MFIBc`1Fz0kITnM5pC^(|gOAB|pI>O-7%$WD%udlbtF?6P?AB*nx>2(2Q8 z!0|a5L#sI9K=C6U30v@5K%KS`j_$IcGu>4~#4#JE5Tf&dUx6V!ARiVdDvQpT zSuhB_XYeaf@X+v=E^MWsY1ztAE+4UCh%t2{dZ%&;p9VH6C} zV@L`I#ju>_?e#Q$RHFQ&>VT;qcnWJgktu(NgZYRy{>Hr}IWXD{4UiS-|67XU(M=&E z)!@O)nSOfxOvqxHs;md$yLEs@Wm$pDkxO8NS4qGt_c2|z`t>HX{h@Eg^vF8QRXygl z@+d4N94Fw`)H{z8{CfoONX-QRgQ>;u8VASh)h>VgCU3R$*C$hkWUtsMpV)4%KX8w5 zgD)t_C)V&cp!mI5(syduPOi*w7vJ}~lyS_Kj7jdLUGS!{if+?K(uKH-%AGoImaIrG? zuDm%Kf10K%+NR4Vd#)rjN-+L|;nv8odE*#~HNalZ6?sIS)O@&mNsee}SQmja3rFm8 zh-4T?fYR5yty&EbC)m_{2W1u^Bghcw0A~$+^5S-}Z)dPPR$XV&qVpL{a$=zjCl=a6 zTr*KW8|)oWW3v22sl#|WvN>3y+z4U7DWqU#IqCf1{=5wl#4SSGqNjp1)^H?Cq+%3A zlSM*PdFf5T&OzyQYSRUQy~5BTZceh}g~WnDFk#YcBo$@~+d?P9dgt5cri-ePG__9{ z==KgZGL%|NW5ITFaZzOf@0oEDC57nN@h0cJF+Q3F8DJ>-e7Gt{1hU6o)k8G_G^q#o zC0{!&iOhLcx)hBCq&Sf!m^dgJ1ink^U<J<)kp+$}XljkY+cXL@% zuv@fZ_n2=WyQY6tF=ua4oX>;0L$VyfP)^@X`w(38Wt#5rPIY9fRo}aUe-GB%azc{ARv`kU@&=_lTX7 z*>_;Srm#F$Pce+N8A6kC0onEB95VSPE=zUQh=>-Xy{_c+-Zr3ma-!go`l0yMW)%>{ z*oSjFV@NJ3E}gBc0tnqnLeCbm6!#{xVXOm8iC69npTjGy0a&D!L~A$}a+;27Qu$NP z{7EvSl;aiy<>wd5%2RYmuthB`)9&I=-WSm%l3lR8LjoO~P^Q<-H@%~>L9Qjl*KK_O zJl{BWU3ECk`^~H-bf{%=`7kR~2d%v6!$vwMZTY&LdNwdLkPvdpj_u|Fn%NP5wK4c% z5^;V7l2?(+JpquJ+GK(?oMplhQX%|lTe@T9-bKG~Z#Z;ok2RHP=8pF26sa@BAzHIH ze6YI`sS{#*xQuQU!n<>;%(9zU!;JeJ##D&^0mJqZGDK$^9%&+^J;`&Vp4tXm*6)?d zF4n$J+jeP_ckYoi^J|Mn)V#$#^f(fF6vUYT2sg|1V=Q^}f$J3O;}ay`rSI z^v59mslc5SCy_6x@n7MN`(IHz{H@~P#|2u{3APJ&t&*$;c&^b$=I9;sTk~`6ry4H+ zZn*a6z^C+Tgx?YN4QgKmcSH~$#^u{EpY8b0bj}x7P591O9T}{*Ria>Yzg@ujPeQVS z9`lm3m*R%9-C?WQM2xShhK}+vg6rQl9GffxumC@eZl8! z>c60!ea64vx0BBLj3({@686asK2a*Rdj)FAsCL`UW{-*wUNPMcX+Jq5%YBG|^FvZA z243M}P26x;LA4VmbKyCCjpaWkp2q>-E*gPyoV~-(2DneY%O0MjCiupP1bJ}qGz2m| zc{Q~#JieKKA=7vD<~qJvNJRb>Y1bEZ!xwj;Wd8M9+62tOp#w$R&mB4F_s>aT*T3z; z>tFx?A~63oFZy??`+rs|{mY;MhX2Zjl6HQ8Gye}|?-V5ov}Ns9B`R%I+O}=mwr#u8 zs*JR4+qRuqY1@cO`{p^PyGM7A`~TAf3PsAHyJtC%;OXM2mdt{9acPMuoyN05wME79KD_s2wHh+uoLxD)81o4NE%x4tef zv~8gvLPBcTb@e=pVdhZQ3eQP?hxKE@o}Et7*Urk9|*ya?|qqXL8CpfbwBXu3w2t--(` zNU7EgeNH494HGJP&lhL_2>lPxfC%hT;lDrwNH|Ylpn+1~hSzf9#C=NWov~keW=)x6 zQGQz;YgU|I8%(-LUFapiJI><|6AiS`#zT%5IU8LjWHyT(xb#^{FQoX!QeBsH!m;A4 zP>j<(jM^Cz5`%g6f~0?d25jKr{skI1`km>1syN5d;1Vj5wxmwNAI+%s1sbqmH?lbW z7id6I>cIL7G_YqE*VO!N}Ag-TJ3jXJC z%yk>^TJ#CQXFKR~(BD%b0{^BM|L;aj>!UHk2R8rimi#l28Nmyj!~Pz?_dy8HWz9AQyTiziu9VA)cNo{F~7!yYd&5+6~0 zAd$GGy}mB|o@d+FSMA`fAP{U(Nt-5NP82cOEa5{_o&XMJxq-Kt5eYBOG>7!v{#t_w z1v}aqmoZ*ED1C@sPy+(OGh?)W|qn@AQYVWh6?HiH!qSzVR&o|iqXpj|N)8 z%$U!^R^HlOpJIb|Wo~T=|B94LWP+P>6aDJyx(G^d7VqN19<3Bdj*O{nltFqsInq=j z)WccH|=?cRgLwrX=u~r{Ddm@*^c2{-iwvw_vo^|$WyZL z(o?sl>8W$nYg(SW*8w{z3UMM#BWKaeq24|)=!CMB>YuCAv~;AXM8w3&b3dtv`dvXG z5HVS}#Szg;70*yj^S}P#*Lc0OR|3$3rf#B8=t_YFSsFoHi5SPD`)&o`LY9mgiD`z zB~SJ$MhtAdgg;=Z-t}M+>Qm+z1At5`l@KR2ijp&k{NDSMo?eVqf@V$E%Ab&5cLCP6 z;0FF6M4UZI(4RRJvIbt@lNrsjZGdwklaV!g1SQZ!JK)fV@8=}N+@#k0B0 zu0v{Z%@q|gn~&64{I@)dJ)b95T5bTx{9EfPqI6x9xBqwy0@farAFuT^0PANTJgB1I z#X-dRoVfwQ3mDrZ$s;M{FQvL&nYZF>lXM$@;XiWzc6F18P5INbZ=sOkUVG$Nuy3S% zmImxbKkSC!?B*=O$?7(Gu{{=gg@3w6p@p{URI=P)>9IS|QxGgo3n0UXEAZfLqJ0?! z&FhVR8YPtykIaOm4OwPmUOJn3v}k;Roxk>6EQ6}~Lx|QI`%R%55;l2X=BJcv-j1(4utD}YzdFi za=~?yw!`|MiJua-KO>=+a`V$dKyewM!Pc25=TMc)k{v7GZAjXM^bT*cvqS4}5@STk zv$ts9K~{RqKzt`%EmMaZCrVh(Op`32s6bAq3W)=lM4~GwX~%lM|Ga>IM0f~(rJ1K? zrcC)eU!19)e6RP=q?<{)S*`-R;K>mN{d?MyddWfdO)ss!X^F!kZLSJF*c4;fi`o?u zT39tD@ngl|SmJTL*d(hvV_xN2sj6(+=eG6scolt|xv<>dU)!2}f3w9^S>M0Z-`d}S zVFmL7+U*g+?Jl(AN02VBN!-%b*3$O?YdZMkbGp*d)8k6Vjs=1vhSh>*H?GD7ah0L7 zI;zPNKQ4&n?CXoExD|NBuQZ9S4bLXqbGUm5Z{eySU)`##tiG+jkEyCn&#Pf(_z<1Y zBi9n@bUAT1By?%|NuCW^pkfxaP&Vtt%fN15_0m;<5(v%ExK6e_{ZWQsh6i5GQ>yh=9>m{LURBB68hrPADd}|B; z%2jRpb3ifApG~|@HgaI*YJvdZg{y{>JO6`nLe1X0q$&qY}N}@$t<=ZM9;!V^R^s1hBGPByu(J)qtV-jewen#2_QyZ_!;$?v?xsAk3qk8 zr?20Jzkd00jw9EMoU>%BW|3386*ojG8Up3nX>L1L`%5$2ZkBZht}CiU6fbYUBAuTi zS1Hg<;k!epmTRBO>wTd0kN%1$o2`elI|FOYr0r)03ciaPwe9V)tFQ6!upz`0VLyJP zdcA-*z2z1iezVjRxTKkPswOdxI2}gTHVCg34%TdjY_LHx)3kDm>C!%;cq32lXGamn z05zl1Aw5Jw#SH?IK+{}(P;mk@H8IVY8;Rg+ehv^h2E`jENe(0%*U^p`VMh+3qi(EA zHvH|(#o6gdf`U%_BdP@Q`i7EvNlxwuPx{AVChw2D5TE!}6@QqMpUM-Sz_X+ZJdSYE zHQ15NPCWBRTfG~O^LtaLU-iM%7Rc5Cx2Sj5YM0()1qHBOo?jy1#5KlPPwkYJf?V*5 z!0|CZRe*XVjDm49G^7q3L zSmUAby;)DwGY4*k54+a4dG|pxbRUnL#QE!Iur@h|c?>*fz6YkbvrT?0?S*;*`9Mj{ zQT@v_PKKDn9TqPxIaZ=54@H+jhGheebz^vDdOIslG4qMZXLXpz0X36c^N1hz$iho? zqRw|mK|19~vm?mLCJ?lKh#0}qSjkSU&KX3IEuQA_U3Cu?WKT2<_A5>IzE$+_-l`i+ zJM)@s+i)5?)o|x77KiKbD&0h*=Jo`N2KMCsi0A(OK3O^S?<`(CIrXHF5dNMjbl-BV zKqr6;_ycPwLxZwA{C-awaM93*ZUf3!>{J?%^yGYINwTMpSX&$(6Yqt?mnT`LW|Jl& z0S`wxh}ZCoD1ho`4m38C9*dAg+zeVh2MJEmz5 z!UBbVaB*)0K0vs+mk>r0A>zaF?3Co@lBD+3%ssyM;`dbKD>074BC12m8NJaMnAJ1~ znD$H{orYtQ%4Pjl8x!>g4;hhPm=KVTZjOa!&IODGgKl{PaIjigQqn0l)TEO z={HXB9A{_cRrl+h53)2wa#pWte0^MIZ#{a-GAm%sxYQX*2b62(9&VJ&Zg}^xeVT^4 z?fN?l*W>B5@AtG#bGuUR&rmPtpdexN&_x#>feP_}rC)7Y#OY0ktxDPv_iI#l7E>!_ zx&f(6frZUKAR3!m)wN@U*TlHPrbu`AiUKRcltNay4IUxEuxAIrPT;{$3_)DN_GNUW z)H+7!N|rPaRUFw=4>NhSAavFiZ!9u!O;ziLO4Ir6Gz*PLK+MC7%qX&)+~q=L4VZ4; z1I7$yn9>H~t$8WtUl`=iM~E)pOXsRx3p0z*8;B;=fs=mjIl5D}we_{@*Tg~W2QN6J zPPQ#Usq3Mm(LtO|I;`-A#1+Sc-o$a6{KEAqf5VugF3wqIs(ThjVtGPI$>${cHcY(8 zbMg+d$h4ea$ZFqyU;BAXu~M73!OfKVoMIC;Oz}&g!ID$wNU5!EBqpuNI|+9Lf!xUb zvC0wZa${$+44W;(C7bEMUvCOSoC6S)^X@^;W;LsE(^j=Ue#6T|&Sia@T5t*!uf(a< z)R)#uoMU_fJ1Q;oqUM!;%=8_Q&{na&<}&KH7v3xJ*35}qm)~bbzqVCtPaUbeC5`G` zP)3Qn3ect>*4cEpNi_#L6oANUvX{&peb2z5#jx?+h3)&m0chPl%^Dil+#HlHcixtH315= z5CqQdOBb;fYv@Ou-ko&HYMjD5uQG|~hZmYhC(ua9z_u3T4+Uy1LlJp|?*?H{LT+a( zh8exx6Phx*nt0rA1@!EFlX=8)npa<4rjK|%*^Vo40PFA`dQSM$!g70UoslXBR8HpE zQy}}Pwa`V0f4@=Ly-QQTRAP>3eF`i~tFX?2=YL!zP+U~=uM3z4i5&`|;lAYN$TtCI z7x0DR{J;&)z=pu92gx1gl`crNM8EQ@-a%=rQ+{H}MWN|v zCf6kEVMM5JC<#=x?8xN$2`2gAos;zC$H~x;p0sE*$?5xH(Y<4O+!<5M<%lNv;YgQ4 z8+dwCR(UIgDpM&ZBU;gy8#P2eWT`!>#SbkNBbncLswSdqbGMpb?PRwVVCm<+CYH?z z-%Yawy2NtLXW%f+=p(4Y`Rp^?X8t`5qr5FsZ-VcwQv*PMAGBYbBwJKq*7`oKj#?|`4tFo~*{@TG2zHP0l?liAfH>oM33^?|5c zBggNDZlGILIH}ZiS!^9=e}F@kSaeTm(YlvfmhKi-DN|5n0LaSc50b~keh2jBE|;xU z5mGjz)LcIOvchFIdnZ45alg&kh+E%;tE4YT zS9v+1R*#wYUTIsz^lh=qRGBpKz_y`JTsh4Omo<CNLB|dpcLd|f6TZDIpY80Ef^nwi` zaX4`(Z3W8FV!!))c9lz*t6K1c+a>h~$ zmZ-51sYGoKFMG+2Y0;T3gnrtbLJ1$Mzs};%qgBe}3`McA=R0xdbt-l)2dDQB0k`?S zZrSu>6WN%!9HMVIAT*u+g6B`=={L6{1TS^g;6K{+p=%oxU)yMlB#xVZ^U&p@GVy0P zT4JU8IJk}{9GXDdQI}rW6FlBEj)peqc^2#4>)x9$UMlDRfiK}#sS@3NBZ z(prf-q+>d;LmmGK>&Yv1h&P$!NRwPpngmsuC<%7R=Q4)cJkCPI6r{*`bTb0hZGp)d zKrj0$asQ*+ChY;s!pe6{vQgO<_2LeN zF)}(tIHrG(59y9S2;H;F4vYoA$nlJFg2Tij(~W0iOKbUopo*97h-#U((>39Qu9~!W zej;r=vtl2LsZBn4am=ltlAp;7hrS0@=6)DO6l-P`e??}px`%wOFkB-l%gyfE9@%Z% zOsV!~fs4>DsgM2gtlR-FA=0=JN3H0X3b#PH_ysnfGwkxtAjH;$6+h&L!;;bT$6Tc? zY4k1xKIE$OL5sMsIr8ffyytIxMEHY-;}_x-jQoW7eZfAkC0~AmM?(Bf;~t?F{<3bu zH(J3NeO$e|ffuwl+z-8wd-Y4HQ@ryUTHGS=5}vH`_7d)G)BRR1oSh82v4g0I%3}5~ z(DG)U00oX6Gme1(Au)QHk2+H9kTbAk6^&7I1-cl+I3IM^zZ{+?&V>scT8F^{rd%|b zx)wwHJJuu_q5dk3A5ex4Y54^(mjafAUZuX6c&dztX;|{?lQMTz>$8xEEga2bz|uu(6K6u_~{O&W0A7bZryfL-lFZveh9xA?Kh1sj^Xj4 zF^%_4r%+9$Kw3s7KE?5{7>v}w;=L>v8X)^=u*S8Y!iqr`?O+y)r@I;@wI8C4zhD~kc2uC(u}iAah=dPi)a-CHkcC`<7#jGW%PPF8s#ot|{Ot2ELoPptWI`f7bNU0o+Frqf+4kh(@G7png`}iOMWx}Pim$+1hJGueq zpKXd@urp2NI%pJl6?0$jbogVq1)YJ+ogD?8wVHC%MD4U3X0E23#U5StrcXRWEz~;4 z(NP|B?J&TEo=&pqaYr^_=7?7d%06S!Z zX$UMUTlimh7qGVdVLTJ8aBV}31Cx4v9>07J~+_xVIiGR^t;y=`WgK7 zlFzXlRvOVTEE{2PJk-e4u@A$#2h20anPW#MKS#fGgQ_6L*TudhX`p4)LE`MRMnZfR zkh>iNq~7zB1=w>rt=a#QD^^F~LO3{~dvH&DcmVHMKMT4+KS4{G8Pv0o2e>NjH>?=;o!RGrPs5 zhkP`bSiQwaNN~bh3JuL0CpO-TVv+=|G&KB*uJXnm&?kkxv{g}u>t?9QG*0J_>m26E zYyRb)Z=J(-fsh$cYaYn^mVt;fMm9q$0H988!s&*B=-QGP!Biuevrc(&o>=a?<|z`C zh&_z%iaW^e)`vi@t4@xSTbsVc3rAU~Nq4E?SlXgrR)tfp%M(TpZv^=l zl^wVRyJ#5d`yg&Bnk*O+^83MqyF3To>M2RRtg>q=Q3%UORU1g0jsCe)cQ8FV5;P6R zt$LHdHx{0P%vXM$$@d;{q-ShwgNz&nu*VQc9dpFi3FIA{g3R(gM?GM{%|3t%%V3_ryhAOF~0 zwzI#5uJT;*Mp#czeh+fJ86DWTV4MN@=+Ij=2CWtC4Yl3aRUKvQo7ew`0fcG1X}#jh z0HX6h3?TpiC9_I~b|&_=3YKp6E|zxY$}V4Y2~%^=e?7!yDQnCBQ9%5VYf;ct6Bt~t zFZH;jlM+S5XTbt7vbsT5kU1D?*c7I8lOJ293;Y}%#6XEof$;yuKmODd^=c3dhCiK| zb~?%K+@1FEcK;6Xi*gcmE(*r?q;H6bZr6#wdZ!$8S#VKssxP=#K{`!hxMI99U!>;- z18k5upx`#bu1Kk*g2}D|FJDlGz6axkRf#>mxc85ek&wLIn1QgT;Jgh}pY^zl@!EN? z$Heo!f~BcRdMdX}H})w-7dgW|9#=;@mB9=-94SL9s^xv*W+nBl&XTcLXiEIAm{=d^ zOWu+!I}zG|)pzNp1&S@|JDN4Qd5JJ;%84?Eluh&&rkomVEAd{(WptmOGn5Bgqb*1c z>%#Jq>VAm?rWY6~_S8EAas_S5HXF`XF>g}K3;|j(P4R-yYSuQ&7E>tUR=xgjKX7G| zcXmUA%8>1h(p}zXU^v!cm!pc{yGrh5(F#FY5X4@v2bRm2&Y29Zi8(bAJ*c1iMXtF> zwzn}9-U<7?W!7Vi(Z)TdgD;EcEmKJU9+?%mBG}Ocr80|MIpr4Fy47}P*qc>wr>TQ% z5xPgVXlMK6Y>ioV{KMetg5T}?p5k>-e-|&MWg*9Iob9IU`P8?`Nx76;8YNAJM zikPY8J7OH6giy$JF)Wa(#1gZ}x)9k1V?EFc9mnmb%sgs=bp|**_t5 zi9&PcwvTNCQ^W6Kjq2Q~J(x2Ew9cBO^TRav5UGyNj~7p26s!8x@W*bjDi!kti=A#Jx+w%2aD)0ZEn*P6o6x4M8Nk*9_GfAiwh{U2rE0kiT zVcjjzuu?)Ll2{XxJE_+kU8@nk={ph)Uo7wREesZk;{kI`&G<9o&(XAg=7e%pRzbu(N&Va4f=hD)wQ=+=U^foM#cey?#WV`M}1?V}OURP`AHfY3(8g`5O zM!H`2ZW&OfLlV5p>O|S$DxF(m#l58DZN2$dE&85}wo7%HCEYsIe8SV>xAZv3SfssY z=oc$RYsitNW`jkGHi~*dF&s9lm$BqxsMdR(Ja0lVR=T2M==6=#qsg!_Iq+=6X&`3B z&+ro57*D~=Zn?49H=`E>ms_l1s&=4l*Bk;~Xo|Ip7LU45nfjsF_{lcrmCI@1_tY;j z-;rFzK!VDa9f=w~Hn-nG3l3~B%-QA_s+sLg+Sad4(VAyPTU?|{Dvt8sK{kv?^TJx2)6M2Qslw zm(10VFcy%UN11Jnn!W3q{+NPEZXw7?B;0_EP+6I1qI-uR=?=v*Us-Wy!3mQd6)if( zu~{Zvsa9TT0m9$L*Xq}$Snmg4?#LTDZRg)&6yo6#y(cD5+aIuul|9_82r8XS<_t~e z2i3jKR_Pe0zsop&V^8dJ))}UE#6)O2=#MPX;NXLujlfJ&Z)pVhf70s_AGjuT{yk77 zsHyv$vL;a&ldZlDfH{A_PAaU`_xr)`DFt!Dqjx%o?}YXFhJ?l}*fRLB?SHXvr8ojUPwTJaVSe-VcCL2nU`s1(S3 z%2wP)pkv5o*A!;Bz+2=n6D`6{4ZV+E32lzj_rvH6YQvchs^B+)?e_f49 z>XrtmhnRk$Hg3+aB*?N7=a|w)APS>YGv?s{PmTKY%ek-d)%1`eX@HlV(qK*OPv?-7~j(+uYlo z@7wA%-!y_Asb+uIr0ipRbmF*r1P&$8WJB*}ph50w({xYmanod*0b!$*X}Tx&ylJ{; z_8@4oO&!yRoN2Pnfx_tg(7Pi(yvl-4^f#MPG}HASl)=t~ne-zQt%&_Y&@4vfnM=2C zH)!bmhCr$)X&SwXUQ->z!e!0QzCBrVep4VbI=?v(2EE6mw1uNmzwXHu(mw1a1JSR7 zz#-S#y(chv%f+lxHe+^g-%Fb(OQu+PwYks?P-8ujCYFEcW^B_^P0B_|ae95Oq>#19 z9Gd*|53?q5*4p|)nZRnbfg!|dn$|eZA7sw1M(d%nvtwcW>in<*Xe;j+ixHN9agQvo z4GCxo)`aOIvFJZ5(|4uS1`)#cE&EWG$!7anfhvi3;C)kK;|whnr7^9bE$~VnxFGfA z%Mz!)Z3p4ms|C>v{d-$1f^b%-;O{9>-<>x`mBL3F2X$7m6U$;wF~4h{e@F-hg()Iv zs~#!!f6fUG>+ctxX>3UbDp{Q+6z}N9{-!RyRZys11FeTNvNS0bCcvgd7RH4ZYMdv2 zgDXbBpFSfaCCOV@5Ci5yE-5Kd{N+GAJ%|$OLI${?tD@fRN-)+7m~<31c7@NoG7&=2 zvM#Y1n3X0BzU;M4K&!PR3tzie$p4)e4jF&7M#UG*jM6{m@;U;$&0a99DDI5|Q+Wa3im%%Pmw ze`JZbSTUE$Ww3Ax^$b7rvee`9y13(Zt0Vy=&QJ@f5;*FJMSvT8uzM>`OBoAHU-|Ut z_oIk<9nSRWIU2-UX_M^sCaXa_DktBuN~swvGr@NYIcXCZuNwb@aJ-UkP62K@TflkR zDlY}T^5njj+eW(P#<$JT>|7~&`eeU6;o?KkVGSu}XUzId#+p8}9L`mt(PcSt?)Bx2 z4Uo(Z)c$J@Oy26B)slN=+c@&0Ksnaj%h;R>cKKjkDBiLXna=>OpIjo3H`2RSQ_(K# zzdTs6$X7D4eF(B92Jh{H+^ebX)$8gb=`vw=AE`cmt*bURoCuUe#u!qYZdUcJ6sCyc zN9of1(6}(Hiy8WkE=+S}qg zd|Bgj0;tbRTq8jov`!cOeU@t==bZRx7GW^}14PXEPvX6YMi< z*Z&n`#5jZGD4!szW7#^(D#q0qCuvvUFWlJutJ-yrC-KCSrZqg?;(jR#Qp6ZT(M#^< zmS8=45lIVyz(JCTCtTk$vS5q{89}WsN54DwNd!^27wH_NX1&_JPQEncRm>rh)9$&` zjjJ&x;nWT5nosm#i}K%l$!?O>l-Z`SAbU$ZQ@UVo++bg@4SL87T8fO?h^4gHYmN#S zuzNa5UdctM+9Ztoah`GARtVgUSIB3%KHR2Sn=7-74o#=q&5^nc9~1f?K4b=>cxZHT zI4&HFGEf``aldfgKvLJFdhxcKs$C41a3{mcmW=V5wxlEKt-5CH`%@0{+8K&*ep^PG z^b_x*6K`)?lKb#)YC`c7bUo1sfw;DnVB81rptnCUp5E+p*xsS^$7Im5tj8QS<4@S~ zCrk4`0nQN-@!+2A14QYrHm)6xze_y@;n6Z&0vf=t>a~0GA1nfrdCGNC`L7N9QnhxF zW-k3&YyyJZO4VRIg4cw!tJgwqsNwq)z}`~LTedGD7t3F3d+ZR79iw4x_u-GoDgKc2 z3STDX;r&%#WKeajgV|kx?>C2hN;EIcaxO1_uCP+ZW2Kv%;YyWPE}iiVZI=w?+N&v- zRavywh17RI?3U;?=M~;$DJgf{X1?IUID&ycib6g6`g#GA%I2qDl`Emol%Pl2uNsd~ zE-i({0Tu(=Gqzo51+1=L@hLWexf(vw-^!B%!BiOFg|Y18Ai@c9Fr>^jDiABKW2ZU* zIAFFZfqNSLgW?V`QN#hv;DFBKGl~AKP-Z|drDX`O!tEWXCtZ z6A8VfES?uKBHB<+xi1kdV~M>ExLpJ#jp=As%53W=Pr4Lc0cXs)K867tq;iI~N)*^& zkL4l1M&##eR%_x{nt=!lBX@f0@1viax7HPLes@J=xKeS#mH4J%(+k|L)%;y{AAb_W z8{QPDW^+}DDrp*>v64S({ZwA|?~I(f<9$u+LX*-xrNs2JkX^!HtL(5`UTAmWI|ui} zeTCd;ecPpWs+=H7nX|XPvTqYj;aL{Nlx^8hQMB@_(3C+a8rsi>8^9&lIkd_r?aE$H z?ik#eQ_z2)Id4whozg|`GbI*VT(C%inj6{YUs2Ma2XqB+?as-XOPS@PEGTFODVfp= zjnirrZbX`n{}6ASwtT|ms;qNISS>KGx>FNdS4wT6t)BA($kC|vRL4IAs3TIsHV+tL z$2KFtWQmurmmT*IFq$#3g)H^sZtTS~c347@MbS&8x-z*RD#|UQ<`3nL<0@<<$3WLg z%GajqGd!Fte!nM8+goG?^@663+#TJOSrVt@47p?pN#cta9!AMltZZMSh|gBARfln< z@1_x^3f9tn8g~w&DqudBgsRnp)giEf8)IeR)f?90WE{$IJr>EC?u01N2v2e`zuz`~ zDsT0>{QSqTm~S;QuKU%oA>;n{Vex-U-+BLS*Y@9}@A6J2rcNT3PNv2#UlDx&p*2>q zwV(gW|E9a7px-oLIPQIB%7T_DbEXp`gc+Sh#FQ41MCaFSht`#{meSnoaiVb)D_Ax6 zPXumA;S3I?&XGNCEZqL(Io@!7-9Jvb{)9F$;g?~76;)2}vQ1+*cbBM~L17zM zkVZo?Zs|NuL#ymRja(Plu!8i~9rSOTMfFkf4IXg^L45 z+6$a3hIEw)qIXO(9$^h%VIr+))0)O~IC=(KqzFg}q zVtw=@Mimda>YWZy+Iun?)4hw)$HfHr+_zIOh-grZA(BaAw|RkZp(7ZBN_D~FRMmTH z7HOh7Lp*ydbqR+IlPAf>C>bF#Zk2yFAHEk64X1q;_11E3nSVl~PGbj1f`rU->Cz@$ z6{tu-Wq%v0L#!W#H2$6^hsJM_K^Yk zgfvHTuwg!#DTMw#AmSIx<>IzoYoO`2TvmbW+^4F<9f*{j?K4!Rb|?`i*md$o7AbTJjPcd|A7 zkC^Z(HEjoMb<7VntxKu#Vn?HiXq+^*Jd#KgO*^GOL@fYi>K}^BP;OYOvV@wF*4{y# zPDQF#S_C1X($bb~E$}IgbTWEUmJkZE1}~$a_Bx@vN$z+rqsjyB0256)lNpat6Q73* z&dyEt1k?Lv1bl!Q2q3r);)E#B>PMWoAk7c~&18frUpV** z7ah1Eq%5dDs5ErPwZzSH9i}AOFH&$DV0yFP$yaPgdk6l zX`PRx1%JgpC$7F)F0T!DGk1P3Hm{dl0GAq_7W9M63V>Bpdr~{8!K`~Q!58H)P?O7C z%?7x|qp}I!QBJ_ASUpKTMcPnnKnim>G*quFOP7At4>Xx-k{+x3yQkD<)v@H!*1vBE z-gTRtQFk<{HD>E!xj}Ifg_qT8qQ{m{-E={=eqG9nXuBafx8QrQDPXzLcYX!|S zof-J9ZGElJM6G&Ws608%eHfXfP4GcQIlpCqB0lDFl(1ko2=e)Kw<>)o(ec zUE1h{;YOM}N9~=fwyJB0kn8~YomxQ6&nK$tpFewZ0mpDYa6v!10T{48(3ZIBa6X{h zEH|{Bx%=xs^ib*Pce%Or*lu(?^LMUj$A^0>p0YK%?ROxa@&fR8M}GJPF1vKv8GtXt zzM=9nJ0QnkJ+(PJ!RWBx{HQ+nP(G=OJfsCpcq$4U1pL63HU?cheIqS)elN9sV35LI zh*8wa@yHlawm<&eAYYd0x`GM#N%2~d{My=PL%)PRGGt(Y#q`j5>6BYKSDDJ|Zm;N4 z$zdt!h8o5n7SOZCb<)n;X_Too-PzGA8z6jAxPH^?Ip0ON&Xx_^vBt-|c#>M`G?hqN zOwj*mtHqBzW#f)py7c$FYZ-gW>^iY1cAK`w*dE-oLF5;wDYJI|o-nSK23Qd-@;O}D z#F(3x9EEM*Dk5ToJOC1$+>NDxTefg>a;!|MNXL?F*j$}_N)l=2cewd%wOJM?5UOR# z`UsG%>X7SPn*ryW>s*=9f^xoa{K;tQ5ZfbjmC&OIaucrj4P5*w`9OJh0mB=A+P91(pe#(pfpm}F|;Q)d#5)gj>L)?P4Z-D)P;?@qzVf-1_!{b~Hv&4G47cOB9&YAb8-ZHl>Qd6Nj#3DxgqKF+_NKP=L$_b-yin zq#tH>LHMNuA5jxz3Tc}?k7$W2DCs@DpFcr3vx&q(j~M{+6Z1Y2Vgd!5#!s;BTt)kp zZAfb{4Cpzw!+XM-V!e~!Fad+cKEd4~!QM;ZE| zh23B^yl^?z7=SE0q+iSLctyQC;`AHG_aVNz1cK99ITWMCVfqoqjD=5*hI^bCYB`}l z`~Q9rv1xCEe&DO;A4s>Z^$%mpPZuM7^;>e?F_OBpFKnSNjGWT8Df);VXSr?n2KWB) zlBQjE=e>=Gi1E?f&PP)4Y^~)Rw&g$I_eq;^=RWx2ZS)F?w2?T8XYpiP_mgxv(S&i$ zh;hTnQO8IgC%i8*t3UjIZyo>l!tdV;Fr-~9lud2Ey2by(t*g8`qx>V{y*@)$ zNQyf#B(f?Hx=_}ZW>LacFb@GL7&X2bUM0k~UbclKqkUDy;H?kh$xY-OGJK!oH#06i z^EfQ@)5#rq7SJAOU+d?t%(Q~!;KJ1QxZynWJk7by>Fxh{J0kjR^CyfkoEIw(QYbv@xLP!V6jv3`uZ z4YAs|Z&0YoCLs}cG3i6I;K>xnn1(3{gBFa`j}-{B$iH~5OO$F_S6^tk5uS5}TBFNB z-4&0^5!y{+wOKM}Q>RFYM5n;Ix0CC+RvEp`QpFTrrcWovF~5R=yeHeXb%4LkJve?h z&CO)ThP42smRB|k-iWIn@10u98Xf{|JZPX8hzt4SU zR!=hUxGVq2j*#v-Q7c~TrG|nS0D!}a zN4gmK4p#;VPlVe?e6qxV+((GB6dOShr5Nzwzv*y9=^TXt*MW$imI<`by)LVC;yL$4 zUpigmxa_1Y_iQ)@x-@BQ?4y>GF1Vd15Y)cYi7Mk1^cqIblDHG;x{=2J!jr90 z_+?<#%V@0*@$th84Wu&~a-^4!OGnU}Bg3cL+Z4BsNIAMn&_kwo!?hB>u(vo52fcH= z6i4hxy|qJd6rQpMSCnGX4tS-c-eAA&0Y|7b!9Av9R^YA{daj1YyGaacDJ)%5_CZ8g z%pBtU0k7C{AWu;@6nrKR#^oPUOd|j!XVG0u@=@N$Xw9|8sFOr+q00was$N5!3Q1$ofTsc=NA;}v7xzqfZi!BlRsHxyHQc z1v~Z2E-~hq-bVdP;glu%-MQ8Qi}?wX)CUAxy|gP5u-wxAFG&5ymJH)yx$%D^Z2$qu0>Ntj5J>DlYPNnmi{x>FW2K z7aZe}rlot$IP20{mL(~*Rz`dZm^Au`mA11Cf?G@JF~9JMjDx4)b4-s&yw;!J)xOH)JX0XQ)HMgK zGj|#?&z7IzI{RvNWYO=?@dmhm4tGfG`Zn+30CqszQ7^-Dau<$#^yB{Kk%POj+r&A!wPyo<>Cphi+u=bM5klR9GLwriCuY z!IDlmnp)4=OMl8Vq7j--G=y+rbfXMGr9yej3E+&|LbIDN0Cd$~;79`nkf&*9uALld zFR~Asm#@9;dS8hy7M}@RQ2CJsR|;z%HhU&=Vb+rc71meRj7F=ghmdc*o25j~O164i z4&zW{=|Ar5^&+qh2_U8f@WA07iiF28WUyI^GI>No@nq1{5{qD17ta zee^fx|F-`X8IjUZ4=oT#0wfo`GERz~$EJu;twkVa5y>UTO;z_0+)Kzo6W<+u#Uq9a zb^~>P5y|xb{VB|8Sv`nJa0~W;i156gG4gbsdRVCBE&76a0c_DI31GO6WxgKE2nUzR zM>Rj;jy+R6`KOlTOn&8W(3h4Z_-khUKR?X>d%&8ClcAln+1IRU>LhFE@UI0+m%64i z>erolRXHY;fQak{t}<(a{1Z(@!U%DIE%w*XaBQln*-4g3m$2+?$kyEO*1f>iU(i?K z`9?{Bb5t<;J~s$Ypgw=`p9=k2I+)YsxU7_t%hEeCy{|d9SGoB=ftv{5?0Vb4(2eYA z&GHDsjBvz2kS?MJWC%jLBw-D5aA-Ia_i7Jyk_U2e@ZtyjIB~*pUvQ`OaUk|RI3h^! z;x_PQV}ZtwIPn=Hhl}I~4jd8WjwBH!4l3~SBS0DCTVN$lc7l42{2n+?#J&a&J+ut1 zWpXw83u{GT#&Gkb)%Q9<1F06vM4QFh*F_=CsOmS{5#OF*dp|jYH9FfCExHwL+C_>> zwyJzHsEt`;t+qz4T(es(E^G8CpG>-PH$TgEoAZ#nVkgHEGgaPGL`aOq?*T8_yl1&* zTW6{e5;d0#&Y@N*w6eL|{%fapFy(R5?ihcR%9s}y84c%jQIXI8z-?X;MII&l1xU2C zNhcV%2;btBa>EqLoHI7C0HjbHuaSt|^yr~zo*~9mnRKU$O=JhuTni2iFf6R_s^rBd zx`G?kxd~<&j${l%@uva;3`JxGLy=NB#eNk^V@3}s_}J+z@faFQnav4e5`(yMPT`|h zfTCuK6js8h86#(&{TTNPKCFWzw+oc~Cb_mq@c=>f)bq`>3ni>)EUk?Co%lOP!S@^|a%t8M@X6 zGu*ETw*lx&?WN9PtTTyYd`Hj-9+Y)v{%Y8<0ve_IM)$K1NsB_3IMqzVECbD{gLAA` zl_s#l4eeo5oSXVf=v*xn)P?kw2ldXWb*$1&vL!lNp54FG-SpZmyb;4bt9h0V7L~TD zB4}bUwff9f6GZ6RWbe{UsVk}$O@Wqo811CU!TsnS1%Yaflp4QDf9E1~o{tr)FMXVU z;;o%AMw0XyvR@Mv#6ax*&K4z96|2;9`b#!PXc{mPvJk{ZmI%f zfN_BhPAlNF0C}ICjTPe?4w6k1zVYg6e3#dOaYsR`fjC)3H@<=3iLww?wQ3y`NcH~g zu8FV+aGTZuo5ZRAhp>0x(lqLp1k?GZZQHhORywoNwr$&}v|VZ2wr$(?)Ym;d(|u>n zy3bFDb)ML9&fYuX@BG^PmOP><1!5~ZB~PFu?PNV|E${Aok1?WC1t!L2wvUqQAgKK0><(=fqd_3N&dfwl8r*#c#7)ln?q~;yh`fw8> zL(a^SV?i=fr5Rr)db|O4a8(iQA%va~z@3OaQh!>Il>;7F##;oYFpQrpkJ;2D3Ex#^ zO;|r$L*jvwQoT17Cxf(3pk#y{VxkD=6Cd%5w(z3PaBK9#DNWcAbF9Ts5s4tx~WHCtSW zc2i-{NjBPZqN9~q1AVpHKD$CqO5xyQyP>eE;c^U#DcaQVJNd)Pi{l0B36H%=vMCyT5+ z@P7%?#qJpeRUfA(;mN=6BzeBtVpfTZDuo3+w#6)ilRMsw4jg=lj^{d%@8(o4M#9CX zQLZYJIA=Yv8a&Ak*}v%xpQ%I#PIMk74Ki_bv#^L}&@lVaSTFX8w5e7_QXQET7(69ma))tAnSrUaq1ALZAc3*&4;uk>K5vj z?LXTY8e+Rv^}AYqLTZXq)QfNnwYM}QQi-%lW;c#4_)Di2c-t(l7vJ87I@=2$E^~XP z@yhvFa0~TB;ppcAb`se|DR)%4*aEhkEiqZn+@W+pboYR(4bG;C6f}rV;b-`QX+@N8 zf8K$up9q)RNHZNDI5 z$c}$dKv7-*3#puVcp?Z9nWQ8X>LJL*lD_qo=UjcPV>2qQzX;JXIBEo@1?vOa&583j z9|-0Fl^BCq?ktS1YFO37A4czQ%B2>=!oOK7npE7fdfR}n7XrEu#n$uqeWv^2CEbYv zMq$h<%gl(M_VsW-8(F}m_q1irqr3)>RbfUIbO+Q*KI5l?IOeAu#pHFyXcLN`xGpwH z8?#gHirQa$noS}^E%Q)hVH~N$Fv+Q_LAiq+;TMqqfHW!iIM@FV0<3>B;{RVl{P*pe z|2l{&^`DR=Q-l9Cr0fz`CojSTD^??8k;ixoK3R)M1R)*_CW(b8iI*rZwRB@@TrvX=V8ZhoNgY zQ2;g;n_*nBi+7MTc;RFY#Yw~5B<1$3UfRcu0fR=DWv_ivzs;-%^*GK{P#bMAOX^a(#B)|FvI;nF#E49F0TLfVEqT9|81O`^xsIY+5bJ%U92pnj3R{k zZ7LNS3@i+$4TL5p+s{lKMK~Hl{kMdg-h@`3-Z`||*d9I0Ir%=!y}r}&E>9JL4&fWf zFZt*~z6kLN2>;kirst(=<>txz=k5u|U$fG5F6IulzLnfSxZedTgf@~=DlM6j%wRpx zXfHHG6V7zNZ;H*lI#flZR@9tPxS0Y0Y-cH6_lZQWGC|2+r=?X2^5Tx&IP%onb+`B50ByoR-Z8NWqV)lSvG-dhF|sx?3wntfvb5*1g`^n)IeDZ};AW5G-!T zMD%1`!iXG>&uLRa(kw$hWEc9eHLd>KFdglh#vgke8T4@1YgCqncphIAt<_xhUq;1b z47rt|I37?49!1ZyUzsW7*-*sYB1r;l6`T7sdW$qy6zyvEKXJ4aW7qY30>*uwo6+G7 z67BGXtg^Y`1V-^agkAP&jVfA1U#T8#nq*FRYc)ke4jx%VxP%vQ&P9^)Df}Wda4mVM z;#!Q-g>-2o0~>__ZB6EXAf{SsqkW1XrqGoLsB}jN_rx@U4Bt^d@Q7svd^TGy0DT{2N*5LvtQzuuIGrT4wQ=(B)bG?bJV6!{)TVC zpQ6q&N>`mxzXh~2GTwn(jISW*CorC}?DR3e7@YrxJWYHCW+sTOyTLceJ+0MKVoHr@ zsfyW)OjLK!jnOPMncT&NE0T1?PtX0&nP-9|ABy>R&7k_1f${&(6aPJ#O8uh+ga5Q~ zWi6bXO>F;H6jDt5lr*RiVsOPl#?osL*qr)ol*sL=rVv0BaJXGuSENTCv*6g^o)(1fgyNqiL<2b zfTJ3H|L>^}EX_YJjuu-RtqzH##n5XGHNk5jJT=}|*!&tFOa z`16C{sa@0NxlrMnTiOjigus8GyOqxiUHwM}I{yb<{MS0f{@>DtsEMh8i?#Frrx2y6 zOep>13clpz{BIMCP|D^3gWWy}#W60hB z7x_*}rO{dl~S%*UUz*GUg+|POb*EAy5qRe)um_CB5bVC4X)jtE{oF%!03U#w!okJD~ zG46V`2z{=Ag>EERPPDG!+1#ef`r#9ga^l8B)hZ>1s`2b`kE-j_&_Bpdowl4}nVC&o z6V=c>)3fK5Hdw9_4KHsZ)mWRfR&VJa1&4!Pq)z8^Th50}*u~h_MFc5>og&y!QJRUn zEjce!weJ}RCJjnaWP?)A*vCqj$d7r z!7Bl#{4Bo_X2B!}iYgPm=JVH$jM?nB_B>|maimT)_SQV~wZ;X^_U>2I7<~~>(|cgr zlXg6VfPf=OHmy8{9hqau+-FsUC{xl56Ra)YpkH4RR|nSDj%7KC?+u5OWGW-G)zaB& z*WYWvysEiFWuVc8X*zGjGwYJa+-vBWWZM%M>&#V##)b{%hj@DMcCPH9;~Tj|Nz~h! zimxMSrZ~s?>B7N)>m`s$0Vt2fmRK$=f$IWPl8C~L59*w`Nh5@pdarIP)yEl@W6&0- zpu&<&uMloQ${u4or3|`22#7#c#HxgIXTZ(0%N@`r*iS2v4#DGJX;t`wa5O8Cj1tJZl%GL%#o`jwh_Og|q!<4dA zsjVnA9Wft@nD+X1xT^N5cD$7Kbw9t=g}*#y8((3#7E9TPTnm41gb#%)uHSQ2aGrfg zh`xcLp0e2lK`Qovqw8Rm&raOZ5k?>%F zG2F`&zkYl%?#YjDd!*Y_r0}3dL{mMmGUuQ_jt=6azd-`+fRhI~QDuiJ0D}mZ#Dl2sW-CaX0(m5Zs0pTCNSEp_5_eeJz=rgZ zI9s6R*!vtJwWyq7B@D-1V0p%@xnvMUsC>5m(bK6dfGo*xWZmSBQr7SUs)jf+5>CE2 zx0L!{Tkw5APrROVwl0LPhkep%{?~um`}}WxI@9x9SYt6EaXT}@*N7S)X_z%x$tn4{ zJduW07>r4r6etnWJs1d#o8|q8Hp|T?k)cARCE0~eIzo?CAQ(k`^U^t=4 zN!iW^^VkF^z%#3+W+`rp2}GBS*))uHZUV?yor}!S0HLu?PIy>i2f4v%(^+9DX@S#W zYCuB$*STd}^L#;hj<#5RQ<3&yas6`ky%t}u)_{bgHMdD z4ZC5(h%z#vyLpFFsCtrk!X<3>(CLu0Uf~H?YMxfJk4CW(`k0!qt|al^y&~aQa3{BJ zOzqaE$WBb+Fgyik{-pdu!%kgGgPhS*Z(ZitRM8T(vOAI2JMdIU`Z&s0MqvBu@E z03*{GbPJ*(ImI`R`T7?Or15z7J+NFcsR;o4%0ATqJKjO!R^{}kM4|j9oGR_C1fCet zS5w|Rtx3x;!9jA^Y#i6q3pAb9z|L6Sc0aS%`>PMxbBm=w%=9~t*|J$H9f|=xgAX-0 zRBW_AWVY74s7FHoB?DZ@{(uD4tjLaJQ&V1XM@+F|E3%|x4HsZKyBH6(>mk|NP@MHdEN)73t|2&eBu~TYQbS9W_8vn+w~-mN z1Ayc4&`0X4eQ@8E?yqhPfMM$>p0HzmJAx!hN~VvL6$1Xoeg4}W1!!lrLu_bJ7-uVZ zMO!cvo)lVNmNVyU)!>7I3oB4(1##NqW_>e{AWE`-#bcJxO(#))gKGhb%@l!5@Ng!K zOA9<0awjG_CQbN}XUw|v`;(CHd!RLBVbK=}YsSfDbnuCd(23IuJUwb!A>M+aR@gKv z8a2IX+iS2Wt4F34s&{A@Emm;&8Uy4&I69+svxzDp0zYal&8r0@w=- z0d_mz!sHArFc(!jn1>_k#0@NwfCGxDWzWo0c;HHUCWLU^0w)9ha#ZYibAx7(&51+L zMTF5Y30iIBF+t(majVEVTU>|kZ zc1H#yC$eWeN}KH}dV6F}1KiA_)2-?0(TK(9{#QtGve0KPaORxPwsxNI^H)U()KePhHvL6zA#8r=c|;pKtRo zQI^G=zt#N-`Cz``>#<#&>Uih8rT=i#_#Cu|#0*GUh>&eK>#^{Glh#wa3VNM5Mq3=9gyamk}&3j6sCa;B$|V z^$!J$RQAj*Y&B1WU`xfwC3Xsv!(fYhqnN#rlOgK^B%1XQV+!Sb&5cqjACefQ2gFIu z){`o!X(HSA*T`z7Kh{p#Tz2?5ur1` z3>~SAQqUp|L9K8qdMAJJ1j^uQm$kk5qV*LIw?8Aa%{Ytz*7#K8wmX&0L44Oyn33*^j4`x`@XEFjQ1geQt zAA`C|gu;4)nXP^ieO0uc#m{lKCun1*;y!C zMmOvJI`Q-?W&@qWoPt!axHbn~5WNFM91?5D1~!UQgc*YY7>%yw7bsf{7iN4E!r*Q- z#WyQVD$Jcib{e7N?8L4i84tb@Sln&Bwyq4!CN^{N( zFrZ!$Z$p-g)?GLhm{J+lV#2gk$-l(I$=KcL0HQMoZ8 z2j?DYKX|#W&P+f_%$=rW7mr(#eQJrUK&-z)TRNjug{%=RwawEL7BjGX(`b>kHgQQj z{raOwN$4YX`wo+i(1KBr$)o2(XYlN3yt+OR?SS%2&g>{9j4KK@)`SeE@5HN12eIV& z5QBQjE*(^$C3L0ms52T*fvMvQ4Qm&)yC`FQk)2Njm2sPQH*ulHt6!3bJUmG5yiIVb zb-yHQWE{4S-~w674S+i$ZUY_Zzfth@|yxylEya&s}>7WNQW32&iqxt_P9agI)b||Ip;`4KXABaIeVr zS1rG#A)h^2f`EG@EE}3i=%Ds}m54@cyq~=*m|O*jJIj$@yTNK@uOspfIyjY)_5fOR zksC57bt`u%VYqFK@Kit{rZ8pJjswup6ayoYGG_5l_+lJR>$MQ#BY zjW16m#P(}7^>zJ>pxhw`tPt7@$8Iro&e;&ITAdWWfYVSudvrHys`#DFuTSO(HppTd z!YILLJiD4iTe#`s!{o@15G8j<*uCQ9FBtV-#q*rZtZX?QQTqWXm~hm5HoatGXA9b( zz{zJ@{)|*np8|Sn%YS~03>z48SoR+>RVhwKQj08<>*x-mjz8hQYEtb~w8mV+u$GK^ z8~0Ypg_y!&D4^xf6AW@vW7jZBsn>A~s;iI%FQBK(_LluV5;Z5yu(aD-_|?V}q#$AP z+zD;TA6$ndm~t*nYoLT?j7K{BOEuFcsJ8^_-(Dl(n>^UrFIRKw@_rcQu5;m#JoUnu zG#MA}B5<~w;YFxCaSz=T#`3$j5Te3+@Z6A$CPsdkCVxx?)?(X%6@{uaXbh|->^e^{ zH{?52b+1c?*bKR0p?;n0&sbaor4x^N(X_>sCon_}_#dH|9awazrKIJ~Ih9cYq3B9o zy3mh$PjwEuz%h|#b59o)|J!-O!Wc44xN1;u0BX%Xf0==9OhjDh4B>StHdKvo!Ld22 zZrU)J#HKVWcg$U?C2vNZgz3O7#a^*gV(g4?5(!ufvfNv%q;RFhdaFM<127ls(8GR7 zp2sUsC{_jr!@+m)+V=-5^8tISlts17eqzO2m|b9+N)#Q|gEn2d1Z%MP#49+xxz;rY z>l|w4s{gJ&MK_cdT3|J$E!jE!Pj3(slCj#;3(;%a4?I&Wy9~;;=((Dewg9I&T`j?Se0@p)3dRIo}*DPyexSNQXMHOB;gI)|E=9>L!1FVpyBo?Wu z`dS4&BTGJ&5JmS6RR|tK4bMeJ#sO}{#`;3UG!JiwV5?Nd*!=x*AzlCR)F}u`TwzcT zGoTrU{N5A(Vi?e$W$&{*!5#dTx?PS+%XGGMV$_@GR)ZlR-UZGkh3c2wcizHJCqe>} zkG?7N$d+zzwAAtfAnbe;X=IdJo>6%ay^9EH)i_(JMkqMD#*lW-z1oS`9q^6*f-S?> zpS2~V>V z^roy`7So)huVz(rsT&r3^zjkAI%;>p7HEvEx`?{I_rU!3+fQ@5?1IhrSUf4UE=B+G z?-Tc)i7a_6P8gFqoiEjJq)$@t>Z&&;37=7}od!0ue9?vI-5g8n2$o)CAIEqr3o%r> zL@um-R!n>xn31rf5&`hYo(b4}%4P8I;3HC`TxX@~ENV^6U8qzyCF3KumfHft^R}C@bl4+x{zgoUaTa+)EaVu*{14;Ey@}rta0d0LYpH>PJW&_{ zB20y>__H{xu4+3!81l2a$7` zTz6d^`5_+U5$>!dZy;d-yu9F1SlUP8xzIuZ-Ze5K*4!p-b%k&9aXIv8{?d7us0ALE z02bfk^2Yv1rDLv9Q(E$5%-#N>BLIhSU6_=fDu>?;#leorKZaW!a^<~_1@i67F z>0z+TRjMxCnri)~Fk%?v-pzmtR3V@})4;g!AXY{>iqds6y@k>es9q1qn6m%8bxZtF zBbDW8k@+E%w0i zX`cd1f{f&dH83`jnfGUipc`?~2DUz;V3e|gsxgjUvN_md%&VVj>Ax?$8Y)#9 zEM9ljFm#)D<%RLK8aDU7d`fyG=j?l(F@X03v!B46w2agF6!xWN31|dKK+`@FK+*$CR zjSo0Z<7Ivj`!q#dP&tkamqraVApG(MoN|Pme=PldAV+M9IXen9#+mo7%S!$4{uVA6 zd6VG|2<(YCOgh{ODYiEg2pw3-g5p7b>$gnYr4!K~$L2oSzc?4@4OUJ`9e&#NPe^@G z`>M&uex`kKg{ba!UnVbwOr$Q9+eYJNo$DDC&X(uGwn&zS7^Q7-`oPLjV47*^O?G65 zZ0paBX)ZVg-8wc4gx39W8tsNaHOuJ*iG7F=@*badd4FZ&dZF6GzUCbXfU`P5$X>nP z6q_mz5uC+X`J;0#j_Gk-&(<4bt*!_R$$WOBOG5cp98^+)z*xJpU1z`*@5=eWYO-^e z4SP_=*pd=hjRiCy1}B|i+l-^yZU>N*xzC|}vPGNb8Gq+8^4U)}2l26JD)|E3|j58p7uE@=ChNx%q(d zilqG+kelNrfhwMIePC8iqQSr}wvfx+iGy#=(hBQ2%3X?hjZYr>n&|E>d9Zzj#1s6* z5GTSMO<5g2c;6(EX+#t`qP;xZs1*wnKEfc~iIY?5%o$R;=wz+!iJjeF;$M0JqfO6i z^r%OeG~$XW#D&#t#QQrCea@%R2YhHk!JhB&Q#aHFnc-L;R=tz-@13SQ7V`lXW{u7Q zbnvQ`0_gFgZd-jTi)S|6$b6Ujf*7s62OQ7-8B)!OB{-lPV!zna4ySKs{P*P~zwl+% zi3@vRV_QW-s{t=X%oWNTvpNlnm+#9Uq;LdKyyZ6^ z(e{jlxtzhT#gSh)Jo)?vpslvA#(WV%cjYFR>mRJQhsY!!k5T#xeP;P66;AvF2>PZc zGG2g8^6vh{R>Kd=WBrm{E4`o)wVn8JjNnweV?J8hx17~mVP&0HF4UK`J=X&sv)kA_5y_4WnR7Mub-_ZanhmZdo5Fffahe5mcX^6}2IU z9A5{dfiKG%NcWI+Nc~&6xsaJv-+!T2@$XxF{mEc{{8g<(K1y{*plkgcyvYMIo)rL| zuXPHCKklIa0#2rYHxEE4oon%MYx!V;vVe}n1q`eG@rX2t0k<4|x6FiGP&3ZpsMWjw z*2;7);&xqm$)|yp4_`sRI@LVnWsxMCF=hbZjxhUtuquW_T~xEeXjT{j-EU)~q~b;k z?6+x%-B1Ck*9XH$t8D=xr@aw)mt|{&+lI&hV$HrIn(zY@UGMn7dr~I-_;hIgKEfJ@ zN_NPh+`&9P${$|Wq#$apNr$Z1B-uZ7vf_bq z-i-Ee&-UE%?%*TUN`#!oaY+#BhkL~kEo7#JD;oHJ(1X-Fm@)z1#ldDo!Wv|E%OR2r zh7O#AWn+Kr5gd$qUD!y6;Wo^OJg_$hFNuz%HO8PU#_+^VoreN3xs2b8&?0+whESyQ zC)d()L#3njRS+#HV<1h1-F!wA*_~$$@%GR%tYSutglBSah2)eu&`X5F7H&;od~ARG zZl4g*;rg4u2GMQOG%)@&^grI?K)o=UsYUXl+5E-AUa+JO zTS4*inj=M`_7>zKzC%Dw43RLa87c~MufM=x5Ops@ov{n9<)$k_b`%I*wx2}+tKf_j zPK{yULf$B!ztaxEb-DkfpD`Z(=N4FC6>#3G+K)=)jvHqoRz_e^<-OI%Ug|6d6C6!9MkVlP%koEUFmFR;F2vq`5HMRzsigUdDDC^Lj-N`YP# z^O@K{MzC*w4a}V+ZwLjXOR9pQWN(EhP~N@flV`C{F0T^NTAK=TcxI}@^*on%49ki8{r52_A z7EAi<^XAG(f~i29gATyV63yf?YNA-b;OLH@yPNs~+(R;DM^~#16N@{K(D7~~^6`h} z|9X6n23UU2qd=|`hGygNI5X9+)KMcFB?g?iMvrV82;-ti1X4&E!IK#PbCnc;uymv~ zD|ObU)v;?DtK}NP5FV$xG4u`AXBd_9s%eQOFb-kI?2)5gltc?zSj*C)*BCx*rp8mf z3^;mP%Pc{(@0bmi7+*rOEWa7`^z6aZysnj8z~}Th{fro zwQd5uZT6?1^;3DPEr8?v2I18A=kZ>63t+ptbytXG?_{&w52_#YWop?-iWJLpDoLlqAvi=PF6XhE)$S2GaWCb43*6;202FLll4w22%?*_z+8VrO5 zs}~%LC>$JRw2Jc7}hb}6|sT`w)6Amrmwm!0=7;fnNFoQ4G&4vNYA}_ zPZLSq@uGO8&R6VvBEn-P5Sg ze8`vg6N&m`Zl#YExa6a=D%T?uRPW{Iz!$-w4gDy%o)pjm_pLNgntPGu{7Ev(-_-b;X+K$8a}A zqKhOf{%$Wk@EG|Om#4OOtXL&3B! zIr7^TQ?v-1aMT)cL}Wf-2tlm;8Pv5|*W=@TPn@pS5e#22Ik9h%=HQAt$(ZL0M|uAd z#I1o26gjEe&eWZwl7>y&UJi-UeP88fSDRP=F{DlSrqN5(f3Al(Fj}X%3W@3O5@)DG zsau(Xb1Ud#l3=Xa%xuA!;ku+_fEHDj5hy|Py0JRAyYHfb{vmjSoS+a+>f7uSVZ=(j z{5!~r6}qj_GG;$F;!i{(4QXd8ew}~|X123ym^1f?my{8`hXh;4oO5FEKz4932oGY+ zOl669U>up0jF=(Yh2iecxUhy~R5cmySlMEH{0LLfN^6Fljzf=`Z3>UR7mz+l=2!`9 z?0Y?cYfLZzWsP}-ax}aU_u-7YHhZWM9JSrO#r?x!61AsRf73`u-uZ!DU5b+0UL%0O z^YMWma|AdR;7RZ8M+AONTyjGq)Fk>O2By~=%?R-ONfKtU=<|bxZM5b59uahMHhuCF zG-wh12>X$3XVdB6`Z4mwFZI-WAt0H^O6C1RP*in6!(sep`SsCisy_2&5_b*%~N4)X^5uU8kBc5Xhvgyp#lOF^Z#$N^<#ME5y`f5_o8D3u; z!VSssOsDTp{O5*Ps7ZQ$$>1-oCcP=Md?FT@9q<1ZR>lKBWlq1yu9+CN1ab>c7fh;K?J zJO~`E_D}Hra9hDqRX24ddcLtiBMn*ze7HDD317Ijnp7ibmIb9;I1TozEFly>eXhOR zuYAFA^-UvApU71qrD;e?mRe+m?R$+RNn%Y$sPZOJ@%eAKc_EXzpcgw#JRA0U*_18r za|&1l*M>2k21;we;5X?P@)Mn{fX9n>REwnf@a*-yRZ2PcPJKpER!NU42sgmuIW9Ah zuroqg5W7a!$A%_s^ks^`KSU81BH=eJK26kQ}u<53# zHpQP!(GU7&S*uSk&6@Wm-1oJpw02YwLu8ea2F^_UxNmDa!s1J+4%+4PZT=YUbPzvme-6tq1Ehs z5+IV#pOydH!ATJB+{FFK&>x_fS}I3b4KEG)RCU7xr-R|VtJneF_@}Z2_$e?zKWQDo zlk-sx@W&#_Y;P83dF_3~&J8FA@ku2CcLj!1)}ezk+iL?Cx0%&S%X)_jGA!sB-c}YN zqHpgroZ+0va9+?!DUgec@dssgFxWH7{IdfxOlBgJWpjSRza+tU-@bz$1NU3>=i+nD z060%G>#LnXJ`nj{jHSW||H($U+nQ?Zi0^?)@Zv37ljr$}Zd83P+e#zN2mEcMJE2YK z&m!p6UYywj#<8>i^Qd#@{r=d4AWw;!t~%-ysQJkgyHj~gV8HX$lcic1tM6!!N#j-J zjTK6sj?ZvcQqk6b8@@Y)szHANuZBU`tvnWG@O&0h&EF|+vV%@?|8WrT+1Z+nDzW|%y zg7hX>EPGF$-kZDXD}j5%jObS-%&dZhTu7O9?7*CY5)D>U17C0NSc{htA-KO#XqAjP ziw$0^<~`R4_u|YzojG5|C<-LXZkn>$H&)%jdaq(P%kZiH*)LAl_V>qE32_}x*Hfpu zv0`Z@eaxMz&*olHAk05h7;#*v*1!Y$146@T@2>jp1MlhDZnNOftU1s;37isw0T%KB z1NV#QsKGXlzwe4OK#cVNs1zL=iR(|I@}Ri+ub^N)Om8NSrzZmsmsIv{NZZl*-;LFc zjPRG?2=+Dn=JF#L_Vw17nSB>Ju2FuHejzBS-;>)^JlvX zZj*a4bXU={J^MkDH}V-Lcs$RBX9X6H7FE+5G!qovLl%M-&L6>7mwoLo`wCZ@6*L_ag4Vr_V1Rp8?SlW*M>h@3FsLY6!p zudOEOGW9wSl3dmt-FWM_i?3~&Z$86CPIsv&)6gdd7hDH_=}q$U1C_`%fDZuW;PgIL z)igh4F!7*1;0xfos~)hU`W!x0IL0V|njTgvo!k1bV^r?iZzc(4>06Xv{Y|x;n&J0!>JHu4|DW3+uO;{xC+UutI8h z!gs$p9UN%tV|hIZc9|LAX>6~feaa?#gVFlwx{WqHnFCk!&e4Yj&2)oSI0pf3^;hxg zZ#mHM6LN<@Ylzsjx##F{LsddyHQ_Q%2li@dlUQn%y~AtJ#Gdi``wQuJz1dc6eLUjm zXL}|madEuDYUrh3#^4)U|O$3j_MN+6-UvZm;R>_S}!(SvSP0 z?J>=yP8z2Hg;$e&9Lqlif?sn*$ErEG?#-9^ZSs(i4bADwXOl{z(+Y-LEr6w!@un1T zAUXa-fK1^AI-)rOj(@N0**izewlGFa3XMCkU0BrAz1LfJ_pNHDO3GuOc<~Im2&o4w zZ+n3;Ci|qJZ5CJ`G!KkR$gL1#ktfY|K z9$f~K^i1#d#O3+%^b~UapqHy)heYwGCiYLtb`@GaN`_G zyPr9i*H!5rBsG5@MA-m}$G#1silr+b9X09Nr8>9lRIR>S$P(vbdQ+Sg(9&p|*Ez zAU8uwtZgTmpZi~7u?s{Y^L{h6T`5=|#mo#m|JBHLdGqkU63G<&`{qD+T{jVSN2&1y-J#^;@L|LwyR~^^*MPfz2m3_T35jI( zo$j4swI6BH8w9+Xj0YLPIqQM+yrI?8%!ESv@0>iv>5E-h?#^f!aWfZO1Aj{3JAOSs z)CJt9fl^GD#oGb>gfx+~?C@3v-9L9(WwsUk^mj~DW|^; z@yz%GS@13$&J8f^1(vBT4)h$7z=?wcLI zX;D|&6~3FvO$VWmB(%>qoUyv*=(5jWV0kM})*%HOFKrBNJTk1(4#z5w*2ieeXZ#Ikl5> z4sv-3>H!#R%9bmvY??x&7vb;(M>SW3sGd*zpyPi^?U}e(lifZ{tPr_-&YM2|xYKKQ zu4A&--9H0sThARA(A49;k0k5z&9UOaVC>vv0$QCMaR7WQl*nhi53s@IIp*exwn?GV zS3Or$0Y9#m1~FDejkYsSf~#-fsWx?;94ekpx0q#-Vj@Qg5t9>ZNZW+ocNq`MB-a~+ zywr}J72o%Eh&c+>t~#US;Cm_2UWzG1L8I+d%}KHmuWu;f61B`w7bG zyNRBGuY&6rAczr*+jmRtZup|l*VvNH{6h$-vGWx$I$v}ksnf;vF{g^@{*o7VRVN&= zTOl$B*WKdJN6qe~%wtvT*Hg~QMg`Sxi%E^lIH{bapAmuHat|DJ6qkiKbD zA)ZFlbhEuA%=Lf)M_=K-5>@Q4JAu76N@S>RFyhKi+* zlIH@zI0oiT9-z(Q8w=$I#(%KLan>hrj z9m++5{W6)J&UZsj@nuS6J@_ig@N9T&sa3*VCPMpkeq{iu8Eca&8Egz1ZHr=9%Cqz`h%w+bPlrT)?)XpC4(w%X6d-krXPv_08D)^M@&62pYxiU^z9gxH_(f0w0a&74|wR^H5nFHI{#kzsP6({ZnAL7@vFhl?E5kKBKq=|L7$0vxVAg0aEZyQRB5qyi)XpwYgF%&!LJT$Z(DXvsOWq0 zIio_2NP;I!g{`@!u-gE4ghRmN*v}2`e_}dH{l@~Vg4bg~r3}y3hXI>78OGU!Vn*>F zWnPZAsYM8j4O?%0FZ3NK=O(^7PFxbp;7`qy!u1MHJc9g>i^cOWQTd8DJ#kg7ViE9% z1GZA%_A0ZWZ;>4nro$h$L7zwW8`+*dz=S=D_4>584Ak*{IeAip;!9rRw^? zZ#^;|J54ZXc|w_i)=w0Lyp(C8&C5O0QK6xPp!HLYK?Sq%W%Ko!O@#QUiQ=GWH{G%j zAx`fOzF7h}!Xj4H1tkfZD6F*f%+c|5Re}8jIV+!*J%{-T`6E^Y}54rp&z00yZRV#n`O=!@Yc4M z;Kl2#D6v5tn?h%OG&$MK+(0)3D9-aTG!bB@pGv|JiQ{#NO zU}c?(p6&GR$byp7D{Vgw`5Mae@Y1^WgxMi10|; z@9z@0vZ1snXuf>nkmZBibt$^#tGuT@xeKU!0g5~q6}8%cn=#5VzK&&%OI92N%L}`o zZ>o+Dq(zJE-2A8C>j*ZE#`8qH_#Z-B)7y@g2aA+tEI+i%6-5BBr!4vafz2eCJYUm& z)SCew;n`!*<0<8ASVWfkz6n?r)(CJFzch=JQ`&!W8z7_^ctKUAjIA$AR!_ zT=Lm(EG>B=taRMe(f7RO-1do!$J)F=cwRc%t0|j4LJzzqEGzi*?5C6$N(deONdPAqfo`P`p2kFuxOpyM5TS2Q6c`Oc{SXEYX3~n z&>I%|GhT?QT3`a5iDcMTEWLBDMa5s>w&=f~eGXJr!!nzmYO1Pn7JH|DtECde@T>Y~ z4!nJNLR%f@HDyRu2~4R2ufsAxBh0!+2~jxtwKV-wU~wML!LCOKkbv7<3_qkNjF99j z2MvbE9KQ*WCoSART}=7RVhwmW{IqT%I_n-5R_}ju0kXILT*>rxnVJhp=nu}kDJZdRDxsotw$vQ5oNBc7=q1X}1pbCsiu*E#kL;_; zHl_6u0l~GWQBx4fudzk4)v;?g%W<9sIKzW|cY2etz}Yr&TAOaOZ$WWqdS%&u$4&z2 zoEJ^95L0E&4n1*n@Q~3%wHs4AQ=kq%3a#k({~K!hVs`e}E^XY>zwoF3XZ*IzyXTXa z*|hp8&e((HTp=(VQmM=;r0!1qK#AgqdkQayjfti#0KSERZ*XFp`XsoLyf(a8&Pdlf z#WBGB8X*nT-u%2KR_eIYXOj;T#z0xL6}T}@fLZc?0ZBl%zqGo1;P&2_(zCzRnc;S# z28;~uxCytf&DLIyx+)HOMTX@~?>_DXz5Ak93u?P~&PN81U3DUW*o}fbP$O=Zey{y@fjr zgZn?MJ|+PJJ89ZG`rD?#z+s{MPsUqGFvy+Udq%#38VriVhj*#%Oag<8nRM5mk*C6) z9>>S2OdDfhuyln)aEGul7;NzE_;BvG78q6@_p`-;p zBGjeqHY}ykWBE>!^gAmD^rW1l$ZXx_3q1#74U5a@8^N%NCSWMPp&fb#PM)~r>%t2? zJ*?aVn@y*nXKAu%)UV_W7;X%by43}yff4(R!>r!6A~4cB`Ydw(!+kKaJaymgC-pBd za$aqq5FR6i-mL!T)LSbQ&|7X2SIrSD1-M@JTH~2d0pt3PTZxBl&%xbZwYiplI$baxKV)ow;h-bj{rUA%XIWD= z82=DH)EiFm1WbersH|Tn$*ZH;^4#{B(D!PrFo45D z67F#_eseQVW`}z!v|-B6F0p{AYC@NP@N;jt7cQunYG$+urs)jP%b8#2;a=|47SwsE zgK2h6!EM>zonU(No(@GkRV|n{=N;fA<(34~soxJZr{u(;pUzu)^`_Di^z-cC&n+G#yBdayFNR=#TqJ_Zq0kb{uRFM%sZag{ z=0l~&vJJyOfcc7Y7TYC>POxBH{oXmHs{|J89n_t2tCnCv!^9;)_EromO!STi-i&<% zgWh#7x=+TKfJHjz_D^+p)xaWIM^3#z!w@V=xoEs!inPFBSDN~f5yq1+_{1rCMeZdH zSWHZ=(alF#fyK-Vneq^^T(A^4YyW-cGj*_JOK=!?7VQH=%HzwQ8@QKY$m@Ac_OU!K zuuN(Va(odJ1w+}FgR-YZ@4`_176Ylio-|livL7Dx=>;&LS@$B13RV@sl9*O z8^Vr1Ry%AKMGV1;Tsx*SJSrHhBvZ5K-uU)|mABW(O%rlG7ztayd%QCC1z6<`Ke4|5 zga$^kn5a}PAF>Cll7+;Ug62#Z>HNym6xIA3MyC3sjIS0ifz=}W`#7^(mtmCR+`Z*f zJhU*%6cO8&wD=H47Pju*$Xtj4Yv;-A`d_E1VKlJ9^gtcHWG06ioOy1^55ZK9&uI{koog3C3)w zPTwD;{tC7nQk-W58qJ1*9HcyV469^O`IzbhL26CN(KijJ|>jl;tg z+klT9j}+kHm*j4fGl}oPo}KwLLq)9^jI$;gXl4FXg>jikOTAYKl3*XItVPc2XAR?t zd9>!8Cs@Ef-*-{;&<`pY_ivn7?d8aV@y^(ZzfvRLz`lPUh*Rnmf&F8H%8*lIDlq<7 zo03=WY!=vm(VS*Xvh@N7O^(<)G1&^R|2~!0u##8-kE~AB4wsa_hex5tBh4>!4B=5; z!ojW6-8bP;CA9>jOVC4j)XDwYJ^kPA@Te_nuBDD92p+wx;8hkM7KaI{lwYY`RoB3g z%}bKGpz}IBdaex+!7m<(;_p6l6Ihsi)8t-k|h;oxLo1ZSOl4Pmk= z@EG)unZV@3Lnmr9+tt8nL;p(I^FPZl`RDr$-!PIvm|}#&3>G(In37F;Ah5D&15-Pn zL^f};?E+_`Dg~pzYO*jD^lpR4sP!5+7XV!x#j+GQ+Z1Z&lg=)|)FryzU;A30fb)IF z%WV|BkubG(Z^Y?pg(OV14jxwJQ2GOp>DTTjUuwyNU2==`Dr*MUV3)a#*kAMT6nN}Q z^`L*^-AQ;H($Qbxx%N*JBbAZB8`K56_Ah6D7gtk)#}`CSDjF78z^*>=3a-U%+u-pg znZuicwoQ1v#-H%cxZ@Y>dZo|gQ?SGWE>aX7zn0%dfs0~gjz!{jNpNvyZ(_AJVg;9g z{GUOBcjv*yTWWg=D@_+X$@=p|zK?$ko`hVvGTq842rfNFeFpZp>%k% z#rmnk>dzWH`P^Rq_J|-4OiSHZrXew#g=y{9Pipz4Z7{7B_C8l(CYP3-tt9KLD2xgo%e)UL5+<_VYWxwyTKc2%(O4UyX^%WMF zDHBY)Ui_yS+$uh4(48S2fSJ+ucU0xBj^Nh5`SwBEM|+rgZ|hUd*x&&(6JJN_t1eN) ztirLIN96YTfV-^to0E3yw*s?nF2`Rp>>7jFl$R%3k4o9Wtn~%Q*5lup zz`at!YOeAo5A6OlKmwk$=8^*gd%a+uH`a4}pUxBTWM$Lk$`Mut zPc16%zbCDhU_NT0o|!R559W6tl^qXoaf5k7>jA^+SU>Qr@OP+F`dtQ|*WKy@qQ2jO z`L-8tasy(-!E@=;{ANzMJj`#iODJTCi|z$}{O{-V}IUeG<;_Wxo+DG!+lWIwbLcSKrMo%9@UI zurM8SKKAhU5LoyUb4h_>D;gGl9w=~ViPZ(K51T1}e2*5vqTp#>TSEy7SagkP$lPm7 z0^WWhM)Sdj^su;JolEqq@&Q<^b-H0yb4wT&8|VP|k?#hd@85IO&Y6;cuhDbM+|slrcxF^gdWgq)1D=^K+Du(#o`h$4`jl7t zg}LBa@-`9wp>JN`+pIumC`qpf&)R1?$}dGVf$w9%vnq#}hTz$szAc@_}|y_ii|4`h3CVX{9hVNtik_tA=}Ec`-%UUDC;E6(^(K8wAue|L*^0$h;#jL zwv;!7Wy=a}HugqpSazHp9$vh&4+0L3bCTcWzYNRA1$_)^{+2>O?hD6(WpyS9Xr9lP zxt1gk%fm4bETe9?!1B*dld*$t4=Kw|4o8B17UjI|7}Kh6a!I>+y`+B7o3ilcMT zb;;`zuo99!GSNeu4S{>bWu_CqFu+Qj_+3=-M`u(=H-?&ELbmz8?U`DDF`7~#x8reuE)UoYwhB;efNtYl;)9bEbJGD^7cpAXje}FXPdmK~iaGQBldxxL>nmL>ZA4k-hhpQAW{}s8FahNGgh( zBxFT1g7>W07(->5B!ipO_W^6lgyfEL5clFK##IbAajgN_-75TI3(b`F~ z^TEVv%f?^4yd|^9A2GSAiet7*h|@0hkIvUmpCf;42gJRKT=>YJIQ6BHD=Q+1lPBBL z51HS~h*Px9mhjr{`NZjbZk$a*@&@wfTbOR!hb|rB)GOdV^fEOJ2&7wjl|_}3;%lU!4%S2 zZjk<6Z4EaNE*rEo#*0X2=Y5+c3wHaF&TnZo_3V05q>EocB>ho)FzH%SGHIOoWew?4 zmH$zy@8w6j4oV)g68@!6x>lu@H=hoVAg&1;!o_c1$tA8=-G)qU-%paRXL?qt9Bz%I ztJutVU{#O~=^Fgy%so<;NxEk)xw9#HT!eHBE?lT|n3Y3ZdlfDo>9frzZdR@l%{ek> zNVoa?te5M3`AD~MlxwO0&m`%-F!z8|8|usv^j2I+qH*+MS4 zBbju6K6k2GC0U;IaQE0P9EjaRdR8WWIF&CRO?u>cG=5a38j>Cf%en{hchiWw#o3+F ztCnSvo}k18i>V$H;vU2~bupnqiuB~Ed(YES)*(GdNKb3!;OuWoouqfs<(8EqDpjPHa^A@{UU&tF2bW|YSw|2LC&^gV(_WgyBS9us~zWP_CjPxcud%Dh^twVaRt*wj3f8F)#e=uk(TQ8E+lBCoNYZA}A9GzVW&OyZUQT7wbOKNH86D)f&I)De32K-4v6((unkP zzV5wRa9p1B%XbeZU)YsI`n7w8M_f(Xh}W(Zg{>yG!=&F^D7jton*!-~dHlq%Owf_^ zr#$7C`zoAF`X3!kVgGRTJ?a0V_woC_x)RdgVC255dr1oM<|r4lRSI26ycal3hF;;P zi1*A>MS~V!^oh61SwmlT>jT7F|9O*NbEhI1@DKQWa_@<^#5+RVPdezPCmG1@ez2$f zQ8)26TXwqd@b?JfU3Y{_^loe<@ouIHyjxn&lYu8)*T21JI6wxb{4be)3K=DXn-=&b zS>@OepWXLQE^e1jB7^3okJf39)RRH)X|?_H(+`os$mYVzLjM)SC$Bx#QKIi987$sj z(Y5tfBJnAiw=nR}lW^kmeZ(lSZFvImDLU6^)bZ;C8CvYQJzB?EmiUUOmmAjZZXv$f z>3m01o7%~cSwvm7))|WUhRk16`|adcGIS(O>e5Nq7sU4@?cyFf*h+j0PAvbW?-M|V zijsKlTuAOGL*1>)xpQw2GBn8M`P6=(mJIXkm-Fb^B|-ew>|B%l`j;p1+r`l&z*o;h zhK*8wFFlxlp9~+A-Rkhgem)uYmtVOgYW6qcciN`zW_`gCGEC13)f{*wM~179rI;?S zyGn+CZ{P5!*T#$tkBspAO%978BRt*4OM73xBYu+s)4O=<^NIhu#CZ=C_%4tUHIsFR z8c*w!kTqZud*=I584%Yr}zguSAu}sO=NiD&PJ9642c7>3c`W zZ!+3e{6 z&kFR(*nukoDbxD4WGv}GCRaw3D+xSTVJ%Q%TSmsR?;G6BS+b4k%dJ+Kxhfm4+l zZ9DQ^$T-){1EFX0bjdhx$Boq<6|2a&aNYZPk9YEtam_z|M`v;Jksw$3RH?Qv%PU#z(TGi9V z&V)=!Zs*?};9f+gbX5EK3VueC&_n*e1bFP($dv2YdSjs{>SW4qo^VTXUj>;;>4+=%h~v<#sBQsb}1M%9mMMWUA#|6G#0JKbaphi( z9VQndk@^Y8N@v4qT-k)eR}E0+Mi{d4t|RO2TWnRtj!20FB4yTyRGh+A)fLF98%9>s zCS<*_LgK?&l=)nT#19T6ek&pI#~+FA0&LaajUA4N;#4P`Q06aAwU51>VfD=tWm@%d zGgsbNeGBfO%%WjrEmcI;iYO#j*I;vDJ|s3-AhG2-%18`hb6HjFP~im1u)ZNnT^te3 zNJMnrVDmj2kYyB#%}rk+VTotaXA_CUp-(96EQ8J6QT_V7yO0&2jYvo?${e1JtQaTk zC$0`<61O68>NK*FM^QM<3Y(`_qD7^X*?mS~Cx0Z|d6DIvhr$6m$O`Geehw!f>xdW< z@eRmI@vVV%7i$bFG^-Fgp`j z^K6me!w@hafVMNRybzJqAt)n^8Z{s~ABn9WQCR9KBHNii9l{!*)R9nIgsh$Dp9ge` zkhLcPn;RcM!b}!f2j-!$Z7U*51s2nnTz`nx%?Q3YZxMjZk<7y|3C5ak0?Sr9V%@`nWs8PRF`7&223-C zUS(se56iICmy<~R#AINoJqnR-j9){8!PsgHbAX}0%sW)9VGiaxHfwlJ5EAp5=NDMR z{Fs~!3(i79=mfSBUV<{Bm>Umo+k!GO7-fbPwUDKPv0!*7hW=rlDU{iZlOHw_Mj4Az zL=GAu;lMn*!5VhMqa60ZOn5l30$Jf0n}%c9v7h*CBu?x?*4b`so`!y7I8y;-a(*Il zGYMG*n6wW+XhWp*93oG5B2kT-Ioxmq=kxjivOe-7>uWtCzhV&SU?I^vfjtiwAu-9^ z>t~IyVNx-|HG&AwLqzz(5LwE++|C+VH5Z9>uaLC~4Q)gmO?X5Gv&s=g4ir{-jmS>a zs1aR%Y-OO0gz0J&wnQZvv28?_6TU(`;(_62#P1;X6QY8`k^eQ1WkclnFGNm1N8~)_ zHY4fD$jbh2fj9n}{2fCSet=GRq*NS*p9&%Id?B)4a3Jw|3|Svhe@4FjM%M4INOXQg zR{vWhMlslpOfxTmvqm{yG1C~GgNgm<0!$r87o$HMUEacUIJ%|-i4BC&MrvehXyKx8u8zfBeP)4m1k+8dp!p=_+@x&-I>OYRGu%(DZZ$~8F42cuC zy`#xjkhoBTV_oh?;<_LT=j}k5dzccBKEhmU^hpy6SF<6~AdSdtM{NEv9a-PrVn40( zk?7Jw)&T0y=oprhV>8$pWQ<_aHO7rHW4tv;EX97tRv9C)o_RZhH744QgoHE-%V91t zMl~TzV-5DK?SnFVs!+yc1+pxCkg&ztVa!<=3C~Dm`F}+sObMGuV-y}sz;hovc@SCW zu$CFSv=yh3m4eN0%tY25j0Iy4J|aP*`x>h#MwwbHipQF8d&k}{Lg6n7i2On~IMxx0 zMBf<7jG~hnn`U04WsP$(?_#mW=c1X9^J0=bz7!`mzA6?8;e{w8hDq1BB*wwE*A+-D4tVBDzjNLfT;KOmA6f<&?q zvMyBN5Leuh$i-+io{#Zj{DCJDv=BD0Xhfto5{Z}SGsoX|;C#MbM&h>_%5l(d_1chA- zkmWlMI}E`&Peq{`PbJ{@sHsz@Q26{P_LKSF=-1GlPUTBss|Wb4VCpeOhp9^Z`ZQIK z$36AN9+BqHDDxA`?WvANlo`PMXKEa?lxa3}!qc(Du%A=- z)p7bfeh8Y*^hKHLt57B%!{~I8KN4ja+NP`CA@L#}iFYg{z6@jY-&kBvcRM0$7~R+O z6!Xq4>n|tsZYt|9k3Ay%ScLvv-iNGpSeyS9i$+39AB7cHBB9oegmxJc2AIA7HN$Vh ze-C0>_}5tw39k_xE9eahN1|`}8=s7(p7l|HVh@cxtgw^0QB0I48QEn7Y z*n%=idr;=IAF|G+AuFvMTcx)nlEsV2H3dX&9zrDlB=%ECV?RZm$SPfitS4I7>RB)n z&u^h{{Wm0DE<)n%E+jsNqwtseNc`x=4qG?i5FIus+=G8?WyZiqL`DS=nZ&>FGIIv= zbwzn5$6KbunX{K5i--B+3(7MWrX#_R`ZIIcMkH2xB5O@C5+ZEaTvP`;+?s+c$)CuQ zlR!i<0%epNk)|Kh4u^Y1XS0G`v96LPdgZ(Jt)B{^> zoxl#Ia1YtG;~xfMQ_4a@RSJn6cG5)bW>cr1YZJgq|E>HuWbi{hY7Uy*ow28mBvD1(32N}28FLqytrP^Nn;68#-W zj9f#RNhW$Kv(IF5er0yfHYDccA~D|;Wfn2-uPU=IVZxs>`wH}I>}!r7A)<#Yv1Qm? z92J0Fx&US5(calv{|T!Lp|BmfWbI8sVxKFr%<*v9t?ceOi72#X_E=7Ab*vSIPu3zUIUk9%WMpN8Vb9t2*eZ7q5_yWqD%^m=#fuT4 zIguzILZa$7%G7;8q^TbJd0URiry?BvTRyUW;lZ*0xr{{5B@`Y^MP%&19h+wU1g$a$ zJ5vuTbIf91{Z;1RVg6T0nS(b234v^6Ex(D#>buxVxC9B&DrAYjL_``Dl0&`=2^Km} z4hbt)|1lH}MH}RZltbdEDasrR z!G2Drqi`~Y363-j{T!K?$#CQ-AaTPEiTsn;;XTxFj)#~dag+(-5cnt9lsRfpB{*K( zLDuWvIK)R(QI4+$DDyJ`hiFI7#?dnai9sb49t%R5Y4j4D?9Bh3D09xnsdCO^o`P5A z&&rLz!OiDt#Q7SEk?!*^zM&MjgnEQt|>Q|=kcP>YaI!@u&zsfpPI=kD1kY+!+i z$zANnayAMdv_ZrH!yl&`DnF;U7a{@ZMLEN^A`z8@L~JkilW2g#ryn44egz_zqLH}L ziLC4Y{fWBUm@#q|qQ~YeW^y*AU>QN<13~#cwi0eb*2dp(NN39KPNVM<|W`Hy*WX z@Ds}L(}&ENv4;p{L&`~;U@f6sGCy%UsyGqK_W*}R{!?K>g?X;HyY<})Li;HwrT;#> zj?f3H+b7xY-Xqij7v(M$!3~58exp!5!z7H*PRH)1OI1`5%1P5p@#BySp?z{!SGE}j z5z2Yh%Boz=U_#q}+8flEaf(pkt9FcITVBaO zMQ9aYqQf~+KqzgYBW+hjHxtTjVdItp#kYhGn@&71U*4C{rsZ$47pU?PDqv73x~KFm zp;teD_2I+HSA_PuFXgiP{TD)qsuXbEpO{7H@b33~_N&wg9Tc4N_(M)6p&fMu?Ma;~ zp$=XX`I1_C16EqQz};oy4xv2hD&e~q3<#y0?)YYdmj|KOi`aw~&3Qm5gR5L`IR(TC z<&)=-AC&oo(4PEve(w$vB9!-Mfj67ipM~WZd_SEM>PBes8_k1nYkm>R_%NAU@pu%b zI?v{e+=54hwiz#P3;K8fmQyz4_Dhj6V8x}MxPC~JP$8FdA8%+}53AUA`Mcvu=+Gg9 zD|+4zQ$kxB@)W5V>?gFd{AnwFE;&LQ^D8A>k(nTr$8hjCIeLQ72kVYmA5pzUXy11& zCmvkmf__p{ekRAhB1%JUTrc)%{ef+XYR?emWrJ0GHr8TU>J!R8RH`e~Y#FpVAbo7f zq2q8myb(eiIscBJJA!li9WQKDRDx)1h$YPVP-LAkJ521*sp|Zs6j?%<@B1D6xejD} z)#@rf=ly_bG_hr$KOGLcx`|5lRMRB1TcF;J^a^)qrM2btc>!%go6T@(IB{hMq4!=~ zD`Wfi1nhiaGHslEh|t;!OLgDq=Mh>r-?BLJS0b=@-ruoTyGLjP(@Y*)yXAy7^exl1 za6TS{dj*PHe&-Wft}1=UWWX6%mx+ht)^+|c!w;2DwuV@Ns^?_VJGm7J z?LBvC%F37hgbumXQp=HcmC!Eg>#{!TO~F~*u`hl}Rsym5TGehI6GFQ$rtG%7w}7?J zyM0@CyA3p7Q*iqB@h>p3@a=Url4&rF6~{`fE0z%2f9AFiE|)*TQ97PG? z$xn4zviaw&pg&WGb~;^M0Ba9esd?wbWkP$DQvph|^?;Bv%RIRm6x(C-l{=}fzk#?> zdh}Tdtiq*ba&wvx4VF^*QC5a)5)L;#>r~GDgM=)V{b1?&Wpy zgpxBnG4tl4MXi@f*;snopa{Ipt$ZV;oN-wD())rOYs&~7 z$a}hGQHB`^w@Ta)3TVu=NP<|K- z`lhpkotCdV9Nd&eD6b1`b#IeE$7}|}L$;oJ33JxCy7~3>Hc;9-hMbGaK_SC@&M3b< zFG%P;iop&B`QC(HOLKafOI`y_Se!OiZt##$do{fDefPW|)c#YVEzR3XVC&X>Fi;8~ z1f6#?>CX`Eg5{*JN)Km55L#2CK(TJgI#AK5l)il#q2O{A=S!4|gQNCzE^CXt=|yN) zbtCUSIYUCri=^%CvwjB0EfUhgxv2;on$E0FEMH?BOw_qw~TChb@dqdO!Far zhdVW31=_*&@`7N(>MSMYb-i#pzNT#XAEM`h<#tcU4GR0g#AHiU=3A{LltsqN>(eJA z;BbZY3g(9u!mgU%4cT}|o=}o!-@jVb6%7+JwOD`B2sSDp==Yl4%fVHKA4^-=Yd#6v zn|k2RjGrkmgyjz@qv~il-1sQlx(V=^9`$Dy-PZ%J<({9Rm)`+S&+Xph@AfMxBxxhty%GKaW0|s^5UyJUqZqV)WVZ@rVozW zHcCm>*g*ue<$eEpJ#IJxi{2F13%;pfJ3Yl~3dX?VTrZ7mQ&P7Fl}PqK=X_}%IP*Pv zA*cS%frHy~Z;NkN0-@OE>W|3gc@WA`w=BMm1#vn2p+Sn*>xD4Y`wc?{I_SnL$eN?O5o?+o5B@C>W8))B&rwpZ^x< zY3m=v?Ffe=HurIYk3Xn!+{tCvwtj`PnCA5gxspRDGvQaU0a0L9-e10_cWOa&2scZy z*wuXzRv~HHzhOK0Og9hZuIQF*Lb6WnOh_*uXhhUgX<)NZgpv z$|ah-vAMROs{=nB=h?$%ZXCMQb;b;gT4H3*iR1J?v(mP5*enVOgYBDvz?>B@4UehN z@~Ijba7{(kDZ5LCVe%I(wtY*7WYXVvt!&V>^RQ%j?`Yi=B|=%9;L@L|braId0|KI- zD#68hd|%laQoI;cYvWjq(q7O*yL#b+Tvt93$~M|^SSJZWwslgZuBA>QBtF)n<9+jMh%Cg|bn!L)`_&`kT$dX-dv$m0Auw}cHxfLjjV zyOkAqUm6^2={May8$-_$tsY5qE!Yl6^0~V$ z3*fj-xq5h|AoEGfdv*c8B-dQXg2C*PmCN0ubMKSq08N(ociaGfDk*`6pOGP>O_! zuE;jf`My7uhrdDeEs%R%b`=9nF*oLB`G zR~)hGr?e{^%0u2QPHQj19=_OlvN_cU^jX=tUVJ?vv_nOdVx{=Ky$3PPqq zH;h~Y-@f!c4Rdz(FJ7=6V(zXP;ZJzDzrp^@;cv9s0Gc3E*Vn(=34HG!y_l5rTv)PE z-s7Y$bI5`APd4&U&T-=AdwpZ*JZeu*y$8PBv13F!^_LwH?94ye=dbOmr0OXl^zvBeY zt$^SXcImQG3+q0lD-YVoE_6U@|GV$Rc~ z;piLSkwzD8H*$p-7w*uP^7)o5bofBWeA}%~LT_LBQ~#DOcqAW(J&)bAq4xB!*Xqv5 zfDQLJaMo7eDF`NCD&rff4m%e7bgvavz6*lyBHrhuG7N^8trs%qJQ%ERn5^UFKJX;r zukROUd;!yQUSrn0dV~k`*+O^w!FRA67e3JzF>4Kwx#o0}e-w1yUu6Cs(;QHMfYBmPE}SxwGlk~rIfVb|tX?refr~x|-H@BM~nhuF;Xzitvhpv$S zxc%l*bTx#q6~LJ;x^p%JO`p^!C)IC>Lj2mTdD%7;GJIF7Pqxu&onWv-Z&&TO2uVd4 zSAO>F3)nQcy_=kXKK4Sw}H}nwOZ7_l!Qt%TzJirwO3sLDf}VXnFxW*>t$+= zyESy^`8MZ8@4;d4W2$>9Go&CV3GJ5gykBMn$=kNo27z|q-hC>qs%>6FbrYy?%t$BY zDbygjrKcl|R>S_pr#_w#IRJLLKFi{2urPQVzAJvAzr{d!RBO?K7q`JbU#ndE!sjVy z=8T6!?ysO;wtN07s_!UNz5#8|4(XdLA(Uz3D(=x+aNOSA*9vBgY$lZA+yyt^&xdNu zW3So`J(2xHsa1a5P$(O$$RxlNvGSl0*k^glKld|uey^)SY#sXw;Bbq> zm-vW7w(J%5Y*pVkSh7c%%D3z9rC?B(tQDU^pe!|@H)y{(19_BRflO?H_P-obkw^B_ zFGyf~4kjuFM?)dz;V>+6eZ33};UB!rZv?`zw~2Sv(S;Cv1Kqyo^0QrqK&H5VZL3%* zOkS?xc%Q&yuy?WgMwik`aPP{dGe0gn0^1wz$+0xw3zFmj=MSUZ|AKh)?mV&c5F%C8 za)x;A!DD-f-qcqKhYfemk?&}*{{T~6*==Yb2-f7LQUC3N?0krf&Oz}7C%~)>XIgzY zx)Ex|z2%luk1s=6;pElwS#~iffVJFxE@MikGp4U`^>yi$unC38k}8QtamS zUQoYZNeN9C&0&9@znW*U0_@#qRncj4yESl3`l@Z5gV}@@f4fv`|0t-jkL2L$eNy24 zLL$a2FLy#F6R;!f+NGah?^e&~-j_KWp!q^EXETFSFrU0_&-dSh8qMqMx$if=g9Gtf zn)u{pT?R}{OY7YBb7_QL9JBq;wMwv^KtG>%w(Ve6dq=k3Y&U^CAt*mdefABAJO1LE zUFGINapd8*X9s)ZLm=*6{kWkAEX6%KOK(JaM$xoZ0BHIj;VpOWjrlm zfq~1CdOiPTu<84>wz$G6+bkJ1vbO_E(U`mb$ue^}IGsXe$0On(_EYhvC3OsjFWA zp9f(+J}K{6mir+bD>W}Fngd4de~fZfm4f*0;pob)eHhYa)&AAHif4k7xV8LNGAB?k z`yE(!tE3uOeh*aC^Y~7|{&1dYv*H6yP&(7!lqC#i<--bT489Cym(wY|WqsQq76eYW zXD%KiV1sK7|_Az1Uz;+e+}yyE_K=Eap1{ zh5VwF@>QF}q34|@*B*32I5y2NC|4ZLgI4_FG1rIv|K%hdGhWC+fL_Z!>-^|BsGvh) z+}FRd1xFWF9Q5nH-tq4fQ~w5?;1!VnY?ba?sL1!vx;I4%DgS^>*sEP4<#5$Pu%`MYO+Pn) zt2{(!xxOoe%t8O=!D9mw5IBN0`mflpgo4i7vD@(W@_smO%|ANvo-bjgJEL;V93Xr5 z$#HaKX+T)FKSPHvGd2VNBl}x4`zIuU276D+cN##FV`G-}h0KL&-S8`0xB0;cNbpGi znaLrj?94J+w^>`4fK^7cl$l>U`>(XWq_kxRG`Dn)Tqf6P0>Q;kG3Hei#3t{6S)T(4 z_!du+dT--7h?QPk5iQ3SKy$xM5i2(hZGp+3T|2vf8Jw3+bVYl;5~z)rg7%KP*Vll~ zs|aj7Di22F;~T#$+^U=?b!6up-s&-f(B@Lf-#2|R{^t+xHZ|UboGq|2d$+{8EKq*s zbH1(ZP$1NsS9ETLFdDv)z9Hi+ z4e|Z4tS^5TWYl)A_xKCxQ7~3NMRUc2KKt&!WBY3RF%TA0+NKo&o?p4Q+7^hxeOW?3w#mi8YtY1Qa|bxP3N-1x6hk{{l(x@7zo zC!vovrhVUdA9DWVwwFY+;?)S1XuNh#t}BGUgbeo3XNzFN9?05-|*_GY^+b=BGfTGNr~kFkc$S* zN_&241E^nc$fFh4eW4VJ5-F*S%>gTjh(FB3Hw=d6ob#u{DR%{-Slx)Bpv9;Pu4bxKmi(D3US-EeS4GIP_K!9)6*&w4lB z5A%u1c)KJ(7_zU!fg%nH+V=>xvL~ObtRC#tYqei&{uWSmA8ReiWt#k;0MmQo?kGbv z5865KdVK(RlDGhLK#RYYwN)#6AjkGdRZmvD?FP!W@R9!m*-1hlxm>!MPdNehkm5LA z-vvo~u(-+MhUXB(oixs{@4pX4M10sa;nh#aK@$e+zRY_ECulR}8qxb|J=leg=BzUt zz&}UI`Pmqs0Befj2`UWFm=6o&(AjmN9=wG1ywo4d-JoPxQK_}m%(V;@prQSFPA3%3 z3A4DfTJAwU=6~STg3qnigj&z*Cn|0U`fMs!a@VyJLUy#vp&q#}PyWT+9SdUYVa~@c zH|h=S1$U9?{$X^ZCj^&>M-D5@WG{nH2x*p+n6npL<(Th_y|0ghAG`nerRn(;2%}AL z%|C1*zQ-Fp-}UD@#LAed@kj6Z;B=1OnmRtZPL0sfe-9LGU6llrm*2CpH5+!!EzIab zZ5CA7hkgE@v$1j}bmWZMf_Dv|8^ ze$c}^yE!U5Mj+L%7+PW80NWBP)P5jL41#a;jBBc2*FqqRpPJq%NnHTf^g7YhYca$@ z*9oWFe6~;}#l?s(dNU3Cqa#+G+_tI>!o;2{)=Hbelf;bg;92n&6v<$6ExUL=1TshM zZOZbO*kD_BaQ-%KtbifLCww?7p{z*C5_fSEsVCHd_~j43sX;a9vswSZfWE_hZE-1Hk3 z_}%-=;Vwwkj?PmWn`;PGVDWkDi`soqhy^EA9a6sX8NBFReV^hl7a)yK-mLv~4{S?f z5B)U1E)y0=OBUT8mHd}pZtBoty8@f=PKf5*`vF+<5{|Cos{>+E^r-7gM^lMDVGO2YYZKRDbZcBR-^#V}Q2&Ej^CHb?^ZHE;2WJOs;$tyfC9Gt(N5 zyQp~1t{NyJVh*4F9 ztBr@8*5ymCgX1+wlI^(d->g3Y3FndH;;+`{{QHdgb;n5V893$m)bsn}BS6{quK8GZ zssoxEE%|$1YVrh}h3j0gCjNXd^L&f-X=Q8S1ee80y2Nb)mm=C*E5rvSOcZ;FpyFAK%Zkbn|mL-3gwb{Vkn0sB?{KP?8oH1rC`f5GPC)P ztb?;iJnxfP(#ru$UVmEosyz%Et?8&g+X8kqW|vF1p+3}uQR~ika_~)(-h?`s zA;m9mI|doiW)X7w0EAj=r{fQ+T$A7^mArLtXTWB9u0F@RO}mkl_J%r#^Q{L3u(Q~< zscFyz2HkexLL>`%c6)#Gl7}C-!T6gCXT)TIlSyLx{$oZfB%JZX62HRhVS7ERW4iw8 ze}m<8FkO0;GJ_kHe!9N@1$utNQ1Qy59mX zdbqpLY5_!$819eHi(W%IXaDd;d)xq+IY0Lt;{`Wh>kP6zUstTqfd!5muXSRBk~7Kj z#8;VTnb2Xu>htnC5CRf8w}=X}K{DW$d8Nmp00wneH*!pE1t$}6@8XM#Y%EX!gERes z#jhbt>HqaH?l;(%^SgPX{HvOvQn+HzXOT4*bnMlgR$c-LdC)BOPnkVeVXEt^PMlc* zg>$&;VzaF$JYl7cc?xj~;6+WP_%Cb3K|+4CLo4Kuyb~y`57jGgP7GBB=3%R2|z@ zIKjj7Z^-`Ug$&JP=LUI0%lojLR~EW@zHrJ(_S(WhA>iV?j3xYX&F4Zt?hEU7L_+h( zoo&7;E%PAi&HQw2;g|D}L)Mf>-P-_aocLDr^3&%!aFlZtb@*Qufd6^A?PJzz2gsHO zSKb=13j(9|jIs{D3gxZgyS0xJlLDZh3ppNIY~T})uaUL%Is*xH zgt2-)7nU4>tUK;~!ebdL$hzb8GYmxLnLz{*7kzp-_n%R>ZVP`L4-<2XzhRj)3gu*+ ze&&J%1&GUzi!)b0n;0jw*qRjX!vhfz);TWUzOw_IUaad-ZSqZUJFaH->dm&Gt8syC z!l{j*3CFLN8ygFPqmDZE?eaScawOa9hxSc{Spc%dW>wEDs6CIV>F%OKfru$P7NGm% zIiaK<3Z%bl0X2@z5?75ZfryrPF@7+#1SS?I*Raw12ZYGQ(cY#hA+S-=&B^Ml)sO(k z&Qu)t***n!`o7^)LUu4r?0%F%yc|q5D8Qy#W&|?x=&?iG#h=+hZGyO6Zh9%euDX8I z8!FI;sfrJ|s{V!8WVg`gbB`|AMXdkUq`-S{UPpX3UL9Qyu}LN4`FO#yYS0${RV?{@ zQAmWc3_qSZ2WAyeN-}~2pdZ6vwWXqyA+SHK#v8&yAj^$+|6|j63i6-hyEI-M3xnb@ zvLe~oJrL@zn3B|$g~uRgJGz$hQCMUH1Wmt{FWv7zni0>Xoz;9V5uEwkaQnmCAhAE@ zeqKjE1$HCJ>ce;c)^^C^R=NqN9NG%XziaD>+sl^VpEeLXPgr`BGyeaJpwef)yL;6p z#0kr4l#M~&8ulzbYT`v$_9Gns|FKYMq2zb5M~lh`%e{9FBh$5ekach53}JZ>#4|E~ z=coB)=YJ$D|8C~D-=%{hO)e%u=7bg8%KU}#(w@N|ZrlYCgcbgcxr13c*puSVUY$%> zhdY?Rmrb+%c33ulY7JpUwK8|NDW3IL-;c7J5?0Ljk^lFs^wq9EGSu3Eu#Pq}cL%8X zhv)cxUe8BZac`O5kkf42RlRq+Y#^+J7tHM;nmwVakZOz}tmD<%|L=#I%`3O)nxYS3 zC6zHhAS|8c8kIXxu0vQSnl%`iC3$s6Gm|C>>*Tx9|0DDw>qSfDqoxS!)GOu&4ZT3? zniAjEEW$e7z`RAE^ha9sYG5{ue&+clX3qV}{&$!9zay-(75kYvFD!Z$d%AQzVI|Yd zZyl+bSKKqd>fI!)bH&Vi1xkO7E1a^@8wo4r?kZ+oe8zfxKeCGn>-^1DrWOD4XNz>% zJP0c_$BUWs$~NiiZ;S2|R$4mqD?xgRzMBJw=mo;MkiuNXq~^>#A#$U=nXoRNWG+L| zd^esdu8{goSeN3N-#^pK2i6)42G%FJp0dkK;q4qeuQKNMZM3$9_DazG1~jv zYoF!<322oQ&OD|>uY4Q*A_@W-D`%W}B!OC6bw9Es>K0*L^)bbsQ+IHACkp}6&0J}x zH%ZXZVr#Vs>zczg23a}EYa`DGI(F>`qb;=Pv!B+Broq0hn==n3Q7cYXy&Z1^8@&FO z(ZkYSwoaMxN=w4Z)%(LBRdc<{^@WrHdG5vZvnBDH*OU33gmpue`GGgRqJDW~(66_E zlrTSWES-99wPTsa48po8&Ahxs37uLcR+kE+-@NV3tYYT1kvC&Aw-VMZ5$35YivRxN zthH6KfMo1s5P_<7*+~a`3G4P!F0_>0Wuo4)ih!JCej`n7Tr_I6Z}b>p<;`KP_9$iA zKPhHXC zLmlm09N@>pPGNWcVw}F9AVuh%pGT1G^aymh0QiVRG8am zl#F0geF3uTnto%>xw(z$>PFu#AM7U;8AB%TH9F5J@0 zSkqA2iAi;1(8EGUW?j@~zx#Comox#%W`2iH^9NFY%dHmy@@*mR{EmCI>GXcWx+lo> zf0@!A#Zlf*^FYV$8TB%ARv66FcJKx}y?3IPL1u)nERER#nsBd{`H3|p(WTLIawAyf zePY7ws!VmB;_lUp0a0PDXHtS=f66?bssa+s{Fs~;T@yCz(=IDO?lbR!&|(>~zZVHZ z&-Z(oX91}7HE++!K9?e_2cnF(p%y&6(pmQxJmdqr$4o0lQ?|r&)L1 zwG08|qaTAvM0ZIBKME(TqD3^e;$l57n$!kl_bBdj+lEaNpWsZ3;+T7Ol!V^xP2-Q) z0C}pxATrz1gobVw0y2dwmG=J9c|s6;X0a@DO@@*-wfy|l8$3y|Cv$6_QcODdjk1G& zif^bgGD{*F?z-Py0LU*PW^~!H=Xr1U!{`rJGC%&OWO>0E01cb$07^f80tZFiN z{{@f$<~l7crN?VIQX&sX0mZbEbZGZ!t;qqT;~F!%+#-A1qq`tdm#k+Ve<=O-Yz3Fy z53ueMOXlqeYRiMfBceAUyC^xw{OX?C)c2D0rHKQOM&=e$Y4Zfv%~K^{-KDcfaP+$m zKBfO{1w@Sx_u1vHg{7JwAR%iRWSLhzn~Vn7a_K$hj)u}`=qdjgr(r<4nV&{e8*hC4 z`FI)hOp9=9ucMm+8Dul* z6|mH}Ls*ah^J91Z`LP;U>0?#qeKuOr;uY@$iEn@eGdCPd2ddZb&2IwRd0aRbSMhf@ z=dc;%NRK;DqK0d3iobCMPN$5Qxk*Y%eHyb2yaoA2*%s!FDT;sW&pys8>j2T}z!`?7 zj-Rlr1H_)6X{B0Y>b7Y~4Ioi+%zTtN-@UcI{uq#S<{c_(ck9xp)D`d>WsjKW4rtvX zBlGvxu!m*un4itlOM{O~)v7}rEE|Yp5T)dcS4`W^64sOXiOlE=H`d1`1)cyz^f>wi z^A6v8oh(3hGPf70)fea7xg5I$kb}&NH}u;3V?}}bl7NJxH`biYSukBF3`iPtTZh)$ zwxxnsdm$hXHZeP}1#GVd%=Y7g~){Cx`jlv{K$h;+c4D=~U7=kh@2 zbseQ4#~w9N2{^&>vj)uQTO&lhUbKN{E6-;xbkK4a9tyqV0!t~cW9~uIQi}vF`%c~l zq>ag=s98K*m#%k!9zJD%hco;c{&M<^4IrzS%e*wlZ^sL1$*`+W<(b#UXz7J5){++B zC7v2Hx57)mbU4>KF9lEX)RTG7f!6!(kx(Jw1jup5vr)SitIaxdw-S(RjJD9K4d(H) z7Z?Fj!8{2??H+M=Qws*Id-|1m4S=SEy>B`-Tn1!<@pZJ8(>rOQnnQ$Dv6y+sqqHwS zmQ79tbiQKSM`jf>^dnVD1R;y7&}FV-(P~nW-&4fkEGitB=OwB2b1SBN=0QGI5yjk> zp|;moJv?&(R$6gsl0i09jFoImfo!?rA;x97T0?2=yZwN?ab~n-XG$kq*&N7ZDtc2H z8JS0y()!1z3G3NhW)+mY!IArCYh(ZsW^S6$I+ohi7J~m|RGH^ZXkq?#uXDT*3!Ygp zl>(){cC%ZJ+bci<#F({j?|PMWa1VHiXQvr!qIRVS#k|re0pvDwFPoC`)g0m-oejwU zA0_?gCG2W`zWr?i$WH~-F|#*6vQy##`76%s50(Gk#C-|mNR`W&YmD@6tA%_Ey&zkz zlxAK9q<0#bT+@34vAa@_d61J5*B(utybQ6R(y5*qo$svEk>S6~0g1_BkX_vqQASx% zl~iUhZ%|OmBe_kJYjy(iXeYC-9Rib2WXvJ~dAoqwAI;yJTfA<-3@iVOu+slU*s8hA zlN!{{%v@iIU^u}lVdjDo#oF1HAk+tWU6nF(bCZ@1KXKpXJlJWK8FOKZl0NylIXj^O z5I-HJm1@#zkzMRN06D>2&!m(pDi8G-Tms|<^U55x;7GORS3%grs>)T&Zm6U@U!ME{ zw594Bb2E|JAztqNBI+(66U;u-tJmZ`_@fE-Rn1?-p!ySWG|U{ zRzggv)?#kr&{6{y$8*2x0%FH_b$X}VfV@a5vp)+3c|Y_o*aAqy3*6Ovn>RNatp=oh16o|Ht8%VMI$=F$XI>?xHCiVW zW1QvzvVwVR?`2*&pmYX}3;k3eo<4Uu&mhVq z=d!dtjQ;!x^CSYT8x}6JUKi@7=b20vN9{<7Idwgb8<0mbxT}#IA-Nl%@_qis3fFaU z>lLYK(7NY6%w1qg)h|`@B_H^on%T^)I$C#$y`R0eJ|JtEYp|5wk9!A~%0k{!qr_ZN zresC9>BcnBpPGGNQJ+5*ND8KcE!TK5Z*|xbWHXn+ z>CI;ARrb1W2IMjGk_N3(+*KHKArFub=zsJgz3Hsw;E`$uo})(14F7fKLOEg8@-R

Q{1_iy0}lwen-%kqv(y#q%IH>{Q zm3Wx;&3mmiW`u_Yh|WieMxQ1w1}~fjfB=R>1;`{uv}DMTMg;5_$j*jz-qfL7v816| zSK6U$$#sHKg%DT%C{W?Nu2E%aY3W)N;@P^m)KpRR;J$U8VM~&*B5k73(erWixpmE* z{qC_%JLCH>Y6x&N2XBKFBTBhDY&g$FGu2Y$E|5-Iaf6iY;&`1#fz{hU!$nFPBXN(7 z?yloOD|Ww0(HZJnJqY9_>#^;+59TIL;zL$L+i??)sd!sz^%loe(_RPlO)zCSJ;b|u zJ8W6Q)2^HRttR(17`1$>i0X4ROa;7-srh9eDImJfSr7LzX+4oKf_+-ht z)i0T}@zDYB28a5!5JmElQt6?Y{+)cps;n03s^zvEw2i=bQz=D6P^L$fC?h&g^ASzw z?o9?S{VamW-DhPYOg4ucQK;n>v!jCy;oKskz#WIwhcayfE~!GS$Ss}ME!WCAk0dj^ zKPJ>pjx+u+ZF?3*v>zvB;i;%gmK0`^KlV$|%3{K$dSwe${BcMiOpGzFo_Z|-+_=6B z9A6EkR``4^J%vulQ zq)F2}S2a@){+;lulbU8XbxlC_z(W z^3Kkw0S0As=|aLXDY=f7Qgo_Wd2g@|>mLp}8go-X=OXfz^wXnoJGi7|NP=U69(p7? zU0_GJUA?WRCee~K_}|5ps|V7gPWF+Q22ukvtJ4#H?A zHD-dzo)p`AIN##s?E$t&>)_KxI@v~2Jk<+nks(4D5SS1NO{;`fQG$rB(N~2?FqU1$ zn)oCM;wA%)s;W`%va?9*-2)-jDCaG8RDyv->KA+aZ4$*D;4vfuSG~;9L)MI3S;1)f zH{yWC#Epa~$X4VTLf8Wl^_5XApO!DiBmFF5!gt!{5qsBT2sq`Qa zgK0DsnHo!}NCKlIMQB^~nR=sM7y@6Qt(8Ewjjy(g3l~?^#=Qp+qXu^DF#K)P#Ajby97s zqeo@<>G4~F1eaZ3@PxI%T>f5&k`!UBOS#y{rR1>ZI`u%PTcskXZHm^L#X$I_7-m5B zSKTL7^0Ej^*!?#><9@p&_(d$-{pQSEjq!U*7{dorn211yPlr@ZsVrOU%{glXX%ee3 zYC2PhieUs*2$e6>-a{o%@3e6=$9SPa#W#gjp+e%MNs@N|vBBg~mVL5i*2$@TF_Cd_ zo+Odz*=IT$_J^Cs4NYUkVegSvIz<(?fw;*B5e0;Sg(b3)5OJ+LVTCZcN;|rDhz7&9 zhK+XnMO&S1E#>K;9W~Dd7-QYNPhqP1ailc+=O!n4O*}dvE^97Ka~+0_q?8WoH0dD1 z5}`wpO~ZLQRTPg}AWCkvNMfAE9V578@dmAQMZ0pSYtI|c%>6!+L9G{EIG)~+K#(GO z>eeNQnz%C zSMMV8=Ly9!qj5oGrPDqc2T!}~9WLGUsn%XWI55>6 z2~_EuS)ufUys?cP3#}QLMLMyKi#}8}8z$kALIv-FTorcFV{SrN86p^8*e27UF7 zFdw)lgWdq|jaeyX@W7Hh46Wsmy;M!WFWfCRZOX*>PAi{|8 zyck0_rY^3nl+|k9c;}ndo=QrM>0fVK>c3hwe61~M+Jxf#8rqw!EtwFntYID(8B#TX zrK%u`RRYSU{*+PwQshjnU1KhznJeb-Bo@V%E@0oI%Rx<%F>_yD12w-pG=c7|6-X$n zCJVu+k~4A1H(^2bgD#3Z4>N*{(z`wBiGb!H($ZWSY3%7O6Yd^5pn1R$@ySr`iKII= zL_HVtk|4{93!UDBadtpxT&7OY-Ur*(8?#bf9`PbF`LRZ3F%_iW^0`Uqb|L$$&dZz# zCN6rn*HofX;W0w%LX>z39>GiteI>Rs1gX(>CNZ7fmlWcl#|{@=D$Lg+IhXxKUFn3H zlLRd)<-NyWg5H4l{RqUCTi6M-OXQ=dHqKk!Sow_ios8T?OY3p05c$5~9$CR`BfH;% z6obeca|7e&_3%59iN*Y4o~_V+YlhP5C9*OgV%=rM9)+Uq3nK1g}c z&`Y{D9BvJGw53>I@GRZi@UVJmLtTpn07|;qR}Q329#{?6X1h{SmwuGzHkEH`5N8{P z9#i4$BL5v| ziQ1_HiczB*Bt%JN!g$D>GR!f?WjHb4WmPA9lXt%XjhjL7bA|>yNBi}pg~K^x(D1vm z3hm-q1W=`v+gGjj$)L6-8o|m;tv1@AmKT$FMTYXMlDQzdfvmmt@r2g>x(1RUY@wd@ zI96=0kw84P03HT^OMd^CIYQ;ZP!K+G z!`~-Ui77tB#R>l7BfI=Fb$oZfcI5tTrJo+#Eyw%xIW-iHt@ZQI(6i{%ag16)h#d`l zyEwiKi_uuL^}!&q*Gi8+#f>nm+p;2Zw*Zb;((o=0M$9G?;C5lyifqCSlJqcOx<9Hp zg-+hUjbeIm&VtiNdNkSWr)Kii_8#~8r-!VBBO?}o%45I7mWM*ym{PN-e`!$ zogoLa9?#T}gb#1lk$EtY?@HQ1YntX7)zVt*EV~$k$UJ1h>m$FV_pC0?}>fn7gFHbLab%*lz#D0NyruPB1dYfZv2KFf)pW`aD5|{>=(ZynQ z*3g^PQa!8+HrZwe7p|O{UFu+IH}WY}g}q z#&&UO>o6jkR3gToL&^Nw{aupwX=6*uSj2_FrK>UO7qkt)E;&8Zmbkt0I-c?v`8dV( zsEFhme9BS6|F~dimX(zAA$VIFJgM&N+AWEH`}oxrq?+lJbMUWt916=> zq+>+TRq9dc`Zz(3nV5#+Rt%!sL-G1U?i5DmWs_rLsj?ZZnr1BlF1Z(02S2*Xq>4xr zw&;9NswAf!mp3ebJ5t37L*v5XN#Ts9@d^`(suEs5w59;W&y^t%r&A}_pDfp3EElQl zo~Jd`L#yWe`9z8xpybYew-bw{AR4v+g1Ek4^t?ex?_hBUZ+pNcnQ z_Xx%avp3U#wWlW6iPGu5l_y*5TEoj;?o{RE2Ep5*qPl@#D&@tMxtf*HD3d;{;F) ziju#*?_AF_qhLx7^nweov)L0HxHJV`5QAMpoNdt&ySE*w3h zS?xw0pmDSkRm~ZwY)&ft3vAX66~z-ffWo<|z0dhguvkF4YE@_|+UHmBsyXeJx!Kl+ z`7)<^oe4f8f&XNIV05+oZ>8FWFJDBXcz8QBi{G`AV@|~im~_vkcDfJnb{<(6l(G?d z9L#vxth#LRE5I~{QHmjG89U6T4~n&C*3}_*5f2NQbDiwc5?P)YsjY3{)W>2G?f4^Q zK3LfqOrq8USxq*H1gg~jlGMX-7UW*#AoqXAz)SI_RZH{=IFM1xkXyC0f;|^a>2fu0 z+cg3LEU33sOn0!GaB$0AFlwgrU&{m17grkvvIOm&af}yVo$AgCCzM#VD?Cnon&NO2 zGfqH|3sjXdeew_MYtU zu=yEA72<9Zu*PgmK zWx-3My4}xwCcjbG9ku>9;Y3wdKgI*&{V$_ie9!~XzPC7ch$`AJ=GpttmVYI4o4@f! zOk1mFB-)gfg#-3JANA8Y64BxjzvK)UH8(EPBUP8D9j#)|nv@x6V=hS5ra#KhjoOSK zag93@!@=B~HO3qJ+i0!t7CLMJf#uY!pZ$k_f?={`EJ$aKsC2!LY{Dvdov3-y|-v!oYYUm1; z)<0wH27ILeWi#uK*|-DRR1hr1kC|`em^d?HlJyKYfP(CV7VTKf;^Z4A_<||rJLoD1|(xKn+Kv;ft?vf_ZM??WC*nUET!gO1%&rIk z0P#OPtpC;E`mZ~H{~y3a{~E^F{)_yzs2-t;w2b~eRZn+u1>hfAElxpVp$EvS!VgkN zb`BiDw}D(xm9Fj*IA$sxrAyZ*$a^2;4ef{pe{oLVtg{||sd`}CY_Q$u?9y7XqXGC=6 zvf$#W&VS%L@HJ+U=W4j?B@irU&>LqXMz*aM9j^Y1l098bWE#|=A{ zVaq-Nj`38EX$v9_S8xLKNn+^8rkdXZ2<;jR+Bm8Z*Y2?NOMWQnrdl9v7~B4^0oM?y zZ(33|$}KW$@*cX$VP$BIhg^^;cWQ(_>hvxbrFRrR*9eZ*Z+Zd)r9ol9p!DjeGJ1B3 z+;+i*_m8{WjrE!r&!#_s)F{tzqaxoDzB&0YWWhWK*Gqp>=ZJcdmEH~N<7SZoCrml2 z*^#U)^aH@0Fa72%$>0H}O9`$~YfV7W0_tr_gUg5hs^$0!)^Zk7LgrOXIGDvt|7rI1 z)uR6e4p`1qLBD7QFQ>`8Z>IDdi)pP9C?G$dH=H;<$fq_Z=)fjHZH%o^gLN6_oV0i; zQZiRF3}Q8!+LjzDY~)?K9-dQ-_!;g5EEph8sOczT3J)1HiC2|s&sJGmpV|snX1{nc zPZ&;PAjQ|Mj)d1VVi3NClC*ChlyB!oGP`i(L*k!hqX)NNbSf#ubCAhsLUL`^EM%2p z8YW$a-u#rBcfv%?DQzLWIuaU|zztu^p%{57ftwT>FQ`qB+qv)OCH6!L&3tA{>QGF04yqhE`HM;@myTdj&-a!hp7@y z4HGr=&UKDE*7CeV9k75bUGt@@;mC|kIWN~Y=}h{GPF=Z!b(9a;uE`bH0B z!DX#wE_u}rRUO0q{#%?dEqgIIBOr<~Etub|Gm04jV~%JqKCouLJ`|OxGt?elmFP$L zns|etlWd1f8_`O#i|i%YU*RV0@Bc}llX7G2B|7Lz>;<=-as&J!$LFo$9?-8?&aK%LEbe!4u|8Uv$#ARike3w;d% zlrzStb1bKm({kFl)7dLcO*e(TfQiGh0Y}OceJ`HN%jAxq952^R)AKlbr+X(F=DnTM z<<}`1i)0RJIC^H7rN-~t3*No-h+YzQ8><2eb0OG;Kcni%dLKgXnAv`EpwY%R)wD9( z2vB57moc!7rK-xZ-}L!b7L@XrDf?ODo55vwn-`8T>g2NiQeMCitc&9g*(*yXJp3;qd0ZT?5UHxn%&}CnHi89X=G~WN0y|w`m$S(AG096u z4?7p*rWo0h@x!5Zk~ZK(#nsq(dY*cQD7v=A_2f;Y@?w(Rl)nbQB5qS%NU4gtpKIan zm>J^*9g@Qn4U%=0`eWAd^guGn4BsgzYJhh5xV2#t&KlSE9-Exzh9^EeAB2pIX9xZy^or7A4$EgpFQT209xiuDXL*1BKvZujPSPPa257z~bBFVoy z%a~|VmozlJ5rmhL;Bfwt?`TUU$hxjT7Zx|<*9kbGMjOE5Fh=z-cPjJSR~wQr1{$Vs znfpNnASLnG`cy45hu`g!l`u#G02l9YVh%FecJ*^?(j%Mg3*{0GcZ#$udm~Svq1Sjq zBPV*z0L4hx4<0)+zJTBW@!l_)QM7fCQ}mj&)`8s5Mh_u{a5%|JH7CUTpYVfwJK^@q z5ZQrU6~jO8Y_j=t+CwsAi=fTqr!+spuk}*8VZWP)RL?hSFy7lI=C1@~K-6UnE=Xu} zX2n94`GVxJ_6dS38yOPQvkALaYEZ>kJlP>B=ng)69=Td=-o(%Osyeu~!W*4s8xiAd^6(X2dSO(JY38 z*Z<>#=|y!t`2~IyW7r4YIkHPJ($8p@tTh-#*yEG;w5?RFiqr_JD|RIgH77(2No{u`j8y`Ng^%y@#Tr)(_c4 zzJQG6y~8s;3`{l@&^XE!sCiQ>K41!XM@QW>aL^xBIG1JAigb8F`lyaB`v`aQW$FIi z)%gv0X4_^LOT)pxN|RZv8@yB17XHe-ug2kToaL;#TULcRPz8Iz#Txbmapn_m;0Wn> z!-ld0A)}f9O&`xP(UrovQzXt{CNdxKoC@1m^te6n4(8^Y^}Ia+f>shC)68K9>_z+gghcgm!6j@?Mve=Lsg~)Ys2K(M|{+~YqjEB-lYty0lc{NZALHKPhhwn|XC@e2($@GUAUBysNwHz%%BXj3 zi2^!;eSk{htXgB`NTH7`1*VH2N!ijLHtJLDi~iK{v-Ghx zEZZBwl;hfgkWf%3Q&JO*!#=v@ostoSAf&3&3YA4746vv(c}W-bd?(J1ltpTrGYj)o zc`+NWiqajya^p0OZVUP1Adzz_@5}(QZZnRty03d_3z-T_*N1WYM`>xwywNI+YsC)5 zXI!GB)zxo4`O%3(B^%LA#iDo#Im%aTo!Wz=r$tMNq0)4aFRg}-u4~*)P8;Be6TT8~ z_)7vKB9O^2v0ZYA#mYT`qd1gWJc8iXQ0RFj=&2lbXl+xFf@&)X`rt`oCj`L}1s8Yi zRi!0V7FEY{$bkmQv)R+(`B^}zqBNeV>oe5HHZ zQwMri@}|wYF_Z2R97l3v=L~qzQy$oWyeOO;?Mf$Au+zM?qBNTN%}C^+R<|$+v()&ujDC63}6HB-)3_O4ng5c`(3X;w(YE2T;$_VS&yfy{axTAD+gL ziiN(O;VY7{cDmUR0n-NP$zb~Srm$zdokGaX`h-B&xf>-ym@T=Bt|gJ26KMZNA-EFX{+X^RQAVVGZC8oOuxc@&4L~l1 zaD@JyucQ#vA*o|2TN3Qg;>v?Jcm>#$Q2J`33gul+({6qTzS9`DQ`|tQsQ6v0TBMvk zhP>Q#oG#!&F>YX7P6FGL`M@0yz-cOCb-%717FpMoV z-by*itzS$xR_iudH8k6#%Ph!7OpysAAPh2V=|13siL-$id`tM(@9XwGV!{y`QM6Le zsH`=AUYS)_?dD@+zvzQdt2l#GX4xHF-2P6FZFh>pJliZy)NCUtL5HN4pGS%(?h7&* zXG?^PyFTj16f$T|nnfHFAmf5D-wr%CSP|*e)@Hyw6Qoloy6u02&PmbsTI-L{5CZ)F z9y|pMp{|}Dsen8|tu<(1Rv1*6rjxn- zRX|D%4@L=ahp&DL`25+jZliW>(RVC6!M$sMBp~<%{35e|(kOe-q};fgWc0kBKD9&>u&8omUrnhv zmqRR==lVidJnE$y#I<#(f#HQ!31U$!SVs+`W+tk2Plu@Cb5OiA;O)~JX89vkU@jWx zjuW;pG8`Jl26NqIFWvPI@HAsn6Hd?{D}14s9r4ix`4Ju_6W~~zS2YGCzh3fSK+}rV z`4+D5s$3k0fA)lb`XaxVaNaMW_3k*$E1kGZmMGF2+sTH*1-}zaqGf-Z;s-x6GGM`! zc=hh5ot}y}G%a(34Jl$AW?ZfRpkgymo97AB?%1}WHIfu+7FfNOCi#RwVsOnUv@2n%W)uO5f<%DpwX-uetfw<*DlZVu)40e>jkI#xN5(r^2 zlrz8ze=aRPm^k#4`_2}Kys2K|e5Ft)%rc2tlv&(lJ=$o=Q-LcMKSX(MR>+95e`{|* zxcbWJO2JPz>y#vaN+8wx2$}*9glK0@Lx`r6err`sCC>VsCpE{laXk2RfBO%6pvR!z zqw}8<)c7Z4|Mw>y_kX`g{SR9NMPsLb{;EyN+W)Xb;9f|kp#p&iL>3+bO1`TD^5>I$ zl@pVqNJXN5YfhBzD7=inG&pemsYq+?%EKgP2VX95=XCM2SFI(XxXi-LIUJv-vpi?m zT}_`xu4%UcBK3uZDTk3FD{k~FA*fT$hPkC!3?ZKne~e*7JWMj|0TU>I4Q%}UTm9KV zApY=8Q*i)Uk6C{fRbO(L$Vkp3BAQ90rTJf7tOfV3g&n%h*E6Pf7nC#vCpX`@SIGUn zYfs3UWe84U#qyM0pR*oulB&={VOUc*8*8^lyM0um>dWDyvq6yx0r-gPgXwqEv#y&C zDpaRaalOw7?y9yuIx&~kFz0T`TQByaVF#93qJo_KpbS?=Auom=tFB_TzH!7u%7n?K`CZLz)`eLszH_S5>K!g?YV?PFmgKmF^6C_UuuhO#94Ll! z&5zvfuYt3{5s*iMp?Ye40^kv9kh_35kW!0a}u0E7*b$8bZ?e;duBLg9l z;IqY}SRE(oAvq|sDBOObK0(*7fFC)(U-)uxQ`nmwK;PPI{a&wjAaew^aI}P3k1d(A z&ohJmCN3HU#bg3!juha+vk3+C?(Yiz0@=!q2qw6}j;atOyjFAiJ}HUB;1EiHn~A1( zA{@0(RA=5eBBhIj$WO~>zT69|7l1Rg*+X$H9h{wD%c<1pC##}U4T?|^aliGZ>9|F( zp)Ie;SK+M!ba+bbq^5^J%+U}oxK9;vI$%tHj`6`3v~_JE0yoG$L;<&~18T#Bp&{c% z>ZcHdRmBT=Er(O#f7;_7-GwwlN3P<-$sYn%@bBy=T}4|&;s)u*ze*X``7o1$*IujsDbdy*)*d7dj2rs(U^=@vl}DUwd*$p{<f_X5?L{0uo*{7h*iG#EH+JKc#A%36;|G!i;9cArt~11+!hzf7M)L@(rcUAwW$%f6G0`=8CrfQt>7yt;rfVf_L8?@##Nk}R^|xvn zYK3Nfc4Q4o!p?ZbSbNRkR)2^M`Pm>Dkc3nPJJe^Q2Zu0|Qy2LOj@NQ|4Z0v@v9{`c ziqxY5S0``%h9~WgW2eVS)U|9%gO3! z2>@&3vF4zR#s>*uC8EKM{ln(wpk47)v#OrJx*n=Z-;&vC8)f&zvAo?VCn##MgI);_ zYFhoyA%|6asNyQkrUU^~+En#%haNtHmUglLg0Us0*GoMx%+{5DneV@GA~Cnqtd{pS zN6QEZ3g1oiO&eCB@D;QUNIbB1653xYah_TZT3e&3uO+K{-cF3pv&u&iuJ^bgcoznR zj@ZNInfMnZ1Ou`-H(!i}12uE9H<$POynJ}E?|!`n7%=cKEM-zmN(DLa)yl$8uVFYl zgYwAoL1wk$vIsED=8>fvh1Nm?(io%|HKx8ofj(JG4zVIvBLKU2BJ?tBA;w1F4Q`R7 zfwJ=bi~>-eZu~C@H8<%uFk5@rd2rl~t7Q0I;_V{c1u4S$%P|ei*I3htpmu*Q$hxqR zEKO117Rnn^bFN<@{!w+_%~8>I{v2T>|Hd-@uW=&r-#^CwleYE$@Rl~E=IMr|jQl;- zZPLIgEx87Y;`PhiG94`MZ#Rqi7>l*p8cEeAnw79!yi|hu^UwvAHJ`iEFAAifa-^bA z;V`(^5b1gA-w|e%YTIPp+qSp7yx&MOX=zy(Hu)|t&yt_rMo&D`uUU>W?9UsH*Aw3y zuUvk{FP;FZJ95ZE8zVVzAh-G(xVcNf{8+=HLS9OPBS1I%zkP9__rP%wZf^mIunfX~ zD*FL`tRX^vFN7G-TXL-Z8AAdd>>ri8$lyNUUxP&69OPSeoDVMmd@p=I;Ym9rS-W%b zpMp@4d#FLSq13eXu`-mFz7PKj%haF#EArmde^s^?b`=12hsaRM;hFu*OMUR3pql`X zjw@cFQAtXM3`nDeq$v-Dofr<9k{Wo-?f+u!En^#DkY&-COc*B2%*@O)NgQToW@ct) zW|}ZFPdIUynVFfH=4QX$mCo+fTWQa`k|kUIWm)ZZRdsbWPnu|RpOKfV+h}ZjBy}s> zOnf}6*8IGofD~+_WnG#Em?B_4H?YElMZlaMx3rRdr8Ro%z+7BY+08zLNk|bynG=i^ z6RNzDWuj?ATM$(T`#856IkuD@C_rl7)ga?rOw1{&oYkfzMZufq+Ld=d^3I4=x}1&^ zYv5H^WWR}ZcLX$7|52>q7x&RnHT=z;WmacvX+?mL#R%%8G!)di#pp<5w5A%9eV-$p z_WW|Pq_zjo=$CK8A#geAW_kJ6Vptp^*oPnuD~zgk9fWOOWlVIH8Z@c+D3cJdnV2HK z$b~MKv-4vAcNLUEo6A*y8&wdcGlz z`jF3u3su1>i??Nk^5Es@L0d`>C8brg+rQFd4|_j3vT8uR6;f^?0c#xWK67D&z)EpY zAU>@xry@$oQA^>Kxi!~OULj;I5GVgi0jW=*3wvCrlsZnfAv!fvn%c32er&c>Lz9j?9gjpZPEl(LE+I`D>UdRaE{K%B*n4qsEN>E2%SancZD@LtEy-H5SX zI@$o}EVRMaR&1+x=q3iA*g1I4s>FjlKAY$lnXG(cKh2MOnzs5@ulgo+-j)Y26PP&1ZlxoMJhqRa0D|@Q$e(MeYbI+nNW+i($=6aYdvqwB zN>E;|Rp)%f7~~QXBg2OsX!G~&1}6oy$uB%duBki}7AQIia5F(^MNxa1s~47Aki?0e zFwGV`yIZtm2EsNfGPy!kkP zH{dFc&j|gY1!A3c&eXM}d_Gal(2pR~2ml_+8vx9d&CZ>Ew9(O%G~Zv!fjbWVHWa1@ z%^Qwn%W*7wb9cCo96a8qQR~HOC)gIJNvT097xGjRAZL>}>IO%o7heiK2Vqm(c|w~~ zo{_3c@Qq&y4XoZiC6bol2(W={(WUaRiJt`~_K>y*rjV|Ek?Lb7&FpU$^3>>cxza-1 zOt|t|Bi)8@1$4h*o(Mzn@0BJM?(0GE_x^;cW)kxFeP0=fzl#dR-y=i%2Fssv1@jjF zeog%_UrqWJ49M!SA$|J}0ajs85hD@ks5p&z{)qJ9%P;294? zSuFJGWa3l`K%rf5g+ZwCQH~k#uNae&I4Epr^j5(HyUX94A}NcYzLo}XxHW#q1#8?sz3!)?0T zk}xD%WoFN-25EOqk=6@~e<M%!kn|9N*sMIA85u7`j zi)i>Izsve;9oBypiRlbCz5OxKqcR4rhfYfu+}NpZ%1esnVIztb9fLrl`pN@gbGcPd+Oc#E#< zLiLx%-D)<>YBoTYXjz(2*O|LpBlI@6zchsm90~l?2|h1CEP`UNMB{5ULDjn)0e+VR zepg)rQ7K6-b4d_-P}bU|4E-F=l5cNv`ca|H7-I0q>fU~_1GyyRW#J-A&YLIz&Qe=~2R6d8iky2bSnvz3>!XZeLA8#u1BFh;kM*?H4TH_m z)3Gwh8Q9OvCiJs?Y3Ons_u<^?OAxORtPdAFzZTaJoWVTTsScg5*lD_Ay+6N4NE4!< z3GSF#Zf{52hP)Hn;iN?F!fltyCV{o5YJl5XaUk5xdOA?V_G4?2eI6gw@o~Dl&%jPs zosK1sU~iMv9ZpIW+(fBlh)zh_f)TPI}|lNIE@ zZum%`-HkBa0?8hsS5k0@#1qX+0yJ>FR*%;eUytx5r8XW7U#{CB8BIi}B_*+hqPBz* z)9BTX*A@N|{&6gA4(OI3sSO_(#2VHyVemm}?M4C@R!RzRwoizaHoC}9mdGg6+u*m5ZD(52I#yf(Y#%Qu1U2y%`KbH#ol$c1V1I`Q;X zceHADsEGY#kO5{do+~_=B@vy4o{Qtr9Q1oby&wkN&FvaGWpDerX#3f+T^gt1swg_e zuHlWn<&S53OJ%E_l3c^~OhNWO?{nRg|4)hJ z-xW=X{~lX9IhuXy|7J!G^gop)|8{?#M8U$y<)4J?^X|MZinsPc<@(W=<}mx~=vF^@ zgzI?3y0Be+EKwRdwI^M1FWi1@(M7#C6(%G`EVy4$jEvWh7?T=hexh$XD|?wdyeWsA z#Wt_|har<+imn;ppbB9J7zqtz2hL$%7$_r)a`**%DB~C_3FzN&!N9gn4A+cAPaFI1 z4@apbMq%Tx!@G=SRd`|`V4|1JuhD?<7Z6h8YmAk&Rcf85FWM3gMtv2gBiWa_Gg?zCwn{VyJv*jauNycQ72|HjW(}Vfqw7Oev<&pq#dQc=NvlnW8P6`y3+hlW*8fPqxLj<3z z);vk~&AiYkQegk4aW$|PZ_=vS_d!&|JGPvSJHZT_oo7*~SbSnTTEtrj*LIwy$DJb` zmIq1Ukc^DZ9zDO%-o(9F=y%Xx%kbu`dkxTt%p2Gi>nYx;;Ft=aGPaW$@CsH}F;$A( z@(UkrLCWynQ``%pBp94>u~!W)*nh$+rACn$M5}H3Jzg10R`OO&6}-G_L;mtGQjD9Q z&^wYu`4anjL{Fgf`Q!WY?0E*$3lAHC8xC7w_x-SkLFkCe&CZBR_j1Z1v`<3-7HFs- zcSgM*qsub!3m|jXzz%Qr#v30JEA(?R%pb;ZKA%OiuaH9el$0Cgy#&ee+s#wo(N}qo zKNKlq_-2ER6eh6HRSCTEy=F*uO8f%mdwYFf6TJ$EW8;XXu)nfm`dOYJ=L&^Hy9l1- zESi#V4`IFPdia1(0BE}iBQ67dw#dT7`u5l%p>+B%Yw5~jZDGD8ZU2>Gk#{Gh7liIWrr%dd!s>>iVQxG?kuvDL6b4(}_ z69uyzHNH)-Y+a6O%P8{wQOg7BXebQI&6J-LFGqz|Knrhl#R$lT_NP#<@Xu#viq60B zK63foD76;(3De@gt_|&ld1Y^45!f;$03bXNzb| zZ-0qUGaf*E>F#J?ZoI$n2=EL3-MvnMopBxZh)mm`0?D1FBtr(BI7|@=tgx|xu%k(W z9q8V=8X^J8$87vP^}0b^o;JPMR6%nLB$xOP0AWq_80Swp{{iTL21`A8FQ@Y}3+gjb(v?vLi zdb~&4h>{&$lpp4r7y?(A&nP{nXl0;M!fcivoIGkEu$$bFe!@1#u>&1Hy}?(eHN>0T zzcDB6uoNP}d9r0Hpt$Jos;t*apU!jwYB5MFFQI`OB{B==&rLN*Pscxo463e#p7nbI zIzlYhbj=bM>xeBO>jknWQI-fP+9@bOj@JdPV?}}MMR=MHb8KprI&51A++Vr2U{R9Y z2*gL(Xg*A!E2nPc`;+3GJnnmv(zw68^#umxpuTZf5&b6Ai4}L~ z25smaz<}3q!6+}Eo)cx065&QlEPY)sJSvq?o{a<l`44$GNn;zG z#{rVpffTaKfl$AWa95#vSA2AzER%j!%n8jMcP8r!55IK(u{X`s_;Bi}2*SKK&44>U z+DYRm!j(aswel7XKUU31Op@w8(B!QJN9D=3Fvm>5aiMtO$&QZgc{;SwyWwaWPjg?S z9M5Wi44?0GaK2?A#-fpF(X4T$p$xb683)AwhQ>If?R8w#ooKG!CNZxuDtBPPN$QY6 z{}uplz@#rVHW8@nZhf#^RxyKWGVai5A&ZVAq(iif92H^^$TQc_=`c8O0EZnW!OiXA zKl{Xz0c_SIOq`%Tv4=K+zI`$n`0WtT1!iynGdPy!{lo3Iv{aSUc1&9Dy?V5@$)!;j z0Rj)C%@zYR$UMY0)X>jRYen7bpD5rLL6-#K7lio`PL?u$G3VG60~s7pHhNSW12pY| zfX)55%WE;1vg2w0+QgG?EHlAG))^{yS^n@*+usMjHNi`p2uDq4FjX%~)`u_=^O_!e z9J-atW$D8Qxi)N=IR+PF)EQ}z8zLy5`X6iow~FqRDtJMY%>GEcJb^nAOXX+r zGZL?ZnVRtq_WO3^Dy_nGAY8#DqSFJ?aDo0jhmhh<=vdE>UH)qIMW&&KSc#G%wPW3e zX-2p#z>O1}0tU=-+M`pEY1kCw7Ck$*)nH_bTuV|#ZPEjUu-VeUpQLEf8c;ptnxx*{ z+78u_s@|!VZ5<>iJpTS$UnS~$iBpm1c*Qma;_z^%;8?u?b?J15ssbll38bkc5{ybG zj9L?Ylyx9V_GsoD+H@vuKe@t=mboSkkCusXQPtk+G=oQtS~QnUXV5B#E#m5E_2&|^ zyNT{~Xw8cNhckIn4HQBVE2h(E>T}Yc&vJ`{`f<`tjnROv<`cwkWF@y3U!PE|flS;g z#t?V{%g;C-0W`$q$1ipm2@e+fR|q4Ij20aDev9>+69v0$6wV2>`p!T@3m}Hb*^jh9 zMyb}?A4KhqQY@k(X_`H@ZAj&Y@B;RzO+(suqw}I8tV`63 zJ7~Z0bds>ISbrlD-+-N^(C_%J1qR%Z^3bvGVm>ovCuv;Qd4l;QtT~H)as^_ty4ZcB_CruB8FTN7u=wx&MrXb>)WsQ~IqaQtUCBp0YfM9V z7I1e>h58{K4sUE|Geq1beS08YUQ;l?G|D`P!{k8I%v#5Npf&O1^3E99g4^QD-gk@} zDH=UH-T=nh^yxX8P2pnC5HTlo=OOR2xHh{0Pk8ovuJw@w>y*n~x^yRY;wSHwI|H{b zF~fqc0^Xvb_yZ0%klxh%_Q-X}f`Kf$X|8uI*f%9GLJ=^1sNWF=2fkbz;+c$3s+)SG zU(_L{WdVekCR!JaksuHY?TAh2h~Bu_4>J?8?B4tQ<>TNZ21EOiAx9EaX=Drv-!cIg z=rs0|Ia=OfRyR2Adv15b)mLuMtO^(GPp$2tHba+JTAbm)8zj6$gQwEBuQH>fuG$}g z=zEi{Vf!=z{cLB>wH(ekXoH$G>RL44msKGLbgxe!bhmMX003@+$V!1p42 z(8a-w9~-dBoai%j+LWZt#?D z_=1X7F-V%lDAtO2XDVPE1<==_H{0Z87&4_u?K$Gtc~n5^6OuQnq+M24Oq&ujR~;!A z#gTWe9C3B(>bs#rC>`HX!;TAf#+pN>t)b#s6WKP!nXDGRRv)!!t`(%HN|01 z!?v09TQV`S#b8wsfJuF}sEj-r7;FeYVf~f|VuPh*xA-lmiMyo5%3pf9zUPWD?+9@@ zv(2Do%QsT8yP$m$M`^#ZzB@%!6;;DDO4&` z3s)Fata?D^rDL47VCTiEopR-@0QFq>xF;Zi^G%sDJ=TLwAj;Xa3ksHWztqkb0NVd- z%fYD4xcFP&_FsN*^2sK{H;m6W(I-Cm-CLF8OFXn`zJ9(Pd)7SYg{F1$)Lj5iR|M~V z96;eUC4+xf0Iz@7^TjJR2Oj)5fW#{{58hd-0DdIGH6;7+DaZNDq-MlBawjIAFQDzN zcC8)t*I2!pSIhX};W`bzKJziU>Uof|U1?65QRoiKjbdH3x`H2x2j0zJnOE2LB|4Iy z4lY#e|3uvW7Y5A#o47IlgSGu5i|rc>OpAJfH-T`abJ^8S(Y2g`I<~3Y3nF1(0lcv) z8H3X@VZ8*lPaJ(`Nf=|)G5nPX<|U1ymrX)e$KjgcL>a zqDM`IO6V>$rN3KFcldx`FSAQXFfPL>7mfS+6+sP#zwxFWQ5+!0MgF>un?p`Zjq#+C z%tI<9MvZ!+kt0OJydC#0HYwO!hrbCVbXYQ`XonO)E!`s(Y}zMjlG8>(e;m=S3RyCrOt>I7wArN*Y#$*W$6Q-PuM| z=0%aa>8?H4X3S=oJ45A1nI77lT~}kUro{Z7F<`oz8_gQ5vbXZ9?E$^&eXh~xV&%_f zjuY} zX840cuzvCKNyny{%_W1SPI_7SxGaE3@>b|8bw}aXTgH9V5m!H^$q^;&FASU4)qqkc#qOfV-HMy4T>1nQQPG54DKfx?9aKmLF;B|>c^O&OCi zcEr=eV+_TrQIr#^*deA=f;?(r(JFU@GE^&UEpwjlR4(^@B0hDm*y=ee09bHARo`!fJ?io?|bw&&mD|kSy`wLh-!FA z`;2M>UL3vwbv$&V@Scgd@%tflJlnto4w^Xy0bbfUM9zmu8j&Ecg(!nM{zG8QRXaTW zmR>POBLCsjrX`3|{mW!nH!0Mg1|c-Pz9BnyZO2_wFdH39h06=8buSInIkcd3r)9}b zU1MnOam8t(uI+5xRS)*NhgB}t)mD#J123<2w#yi+)oEl6^wUi#TCh!BHs1Jg)ieR^ z+>_3G=&G|R*$t{Gcgdc(kxRKN)wCWhogxX-%-Jw*>I*a%; z!(54;W&6#Sg)HcSR?E!CvQshRiVc1Dn50wo#{!Dd%i-_orCG*wlK+R(=i0CT?u zsD?WpgUGn)$lmd}2VM<03~uFE1ha;yDyQGGMNHasV46%K@~$c3YNsQkl4x{6ynUa- z5NhT4oGyc)qyDV0fDJ29Sx*Zvk3m~0&o0cznTcpEK`qg@l#h6;YGBlH^Ns7KK&^b( zbECncTD7L>zLNBc5y8t=rVChuv{nXBl8sH3CPl#1QJMn)P~PK8g8zNn~b6SY_IvtGAWA8kX4gv`vs zgz48Fpp`kzvIm7;h(XbA@tGOdyP{__)4;pkABukvyHrW_c+h<9WYDV4aZ8zw0iM9 zZtO9=Lovpp@S~!^>GvccfYlS|1E<~_Va;+IWMybnlxk2%#+=e_5pY>hVD#z8%KR}dSl#8H;%sR9N9?Y=&1jG=bh2v za?}A1p~jKbFb7t0Yuh7noU#ogyFKKl==Eig6XSkj!nWfSXHCx@Pp!S~2}dh}7`>PQ zP0e!@wv4eFr)eG4-YrIkfJRd* zqnPms>bEfhMrw~z*7g;*Z3@^uisrZmj(y3@ncfI5vg*({x8F;6Mi>m|oGVu2_P`I_ zEf6emlBmZr7tVI>2|`z8Vq5M-IhunPP}t7;Q(KIC*Kjqr^ciBId(5@ae4!7uJQrA( zEzXDD+a@9V3!uYvR;y!PGv3vkGF4o+_?zX3M-^yDW6E?(o&Sg6(0OTeP0h zW^Z67W-tx=2WiHR%nEqw>OqZTr9VAJYoik*=4G#z4h;g|Y~ zmEH#N8XcZE_%S@^(xK>~X)rlLWL+1zHJ@NuV)`b{n4X}}hMcE4!ng==R?>G29!bTzuS{v1H@Pi9=&@f6Yx& zwk}=i4HKh3@zdTyXMD!(zqYK2+~N89-=AomcU^{d9$f=ddBXUa6nylJKP2z?1;a|Z z#!XC09lq+Ao?V(`9Ud9M(7JQJU-T+xf$gw`+`_t3D9qsl*`jWZ4~kR{cky6#xhVsZ zFH8UxBqwcZs4ge%lxY^ud;_HhQ!6G|8KE@f*L;|ppqT@X1(J$V61XzG=+jDC2fRib z<)~mbOu3ZGb!V+5f++&m|- z@qe`zC>u|PMjN>EMLykWmf>yv0Qu;#yOCkp(t+IGw9Kup0j*ap@-2}+Qk+wgwv?k= zt6am7#UoK<6;8sBDZ|21YUC(7xk`uLLNOwp_jOT3I8=h{l3(01Xhi5zmT-LO4Rnl* zQnQYh>)ohE7D_#wdBlVat72TvI4+yK8QI`P5v9rA3>-T^XMtJ&y9oE_+S?7ZS zdl(J{V1^-DTE9v=5wDejHI|`DC<^HiE3&a2+EbqDr#QROU({=TByrt9{esi%BGYvS zXLEw`XKra4hs5$bMUHRub6e5+S&zW;wI0+&S0QN515kR&bnN*>4->*149A>Q(;T(^ zQ+q4_&Qi(>SuVYn+ghWr9-Vly@UxOeXYu=p9}0}-N_RivJ#SPUy5Li%aA$V>dMg|X zc5j2Ab|K-HVqRk27=UNko8<-94DMTXpz}U``Er%#%|o-)nq-21WqIk>s9pY!v%4(R zVy)2n!#$QRy|dZ!^Vvq8brw9;-+!)@2ExPbX*HIW^a`CPMy}Ry*%V|dSj?!I2rNWd zW3XSvuh_S^#&O!;tc`=_i#W@}ez#pal^sfoD7bv*9C8wKZUBNrWEZ5c9nbM!gpy}yVKiD*Xes0YRoW>mg!2U7BV-#xieU801z*t!att738$eDn2cl#2O8ilQEO&%dx;ZuvxpLtS?2ylk z*wZjPmw$e+WdqMDmR-kKV4gotU6>P_yEThQ^yMWeK~v?lEfToMSxfEgdl8*W-ioWF z*ktEH*u2E%_jJ?A_Lq?&%#p6gpUhF~n9$w)(YC`L?~c4WuYnf( zEL?@>p1vj?vk8A`gtW?ObX_O?dg9eD#cR=BLTa%BE% zIhl`sK{{)e*)KC{^xyVB)~9V>ets?0G2%FZ+ox#jUSdU;^cYEJ+Nb>fYFAZVF5J(( zslkQL3YgXcA{LI~cKo|^I~H?BqtM+-J^N1~mPu6haa z9HY_h>fm<1}pILDL7gE(xZeS?}ghSzNRS z!;h4FoRG)iS^@`#l&B0093DSHHQ`FFO>}*EO7VKf*Mxv9IeoP>j1CjH=2A!V?_!1bTqnA6BIL-hzXFBnX+&6SY5MZk5du;T zS`^c&1+Q1&lp6>Ck&o!@148U$A8n5}Hvr1L=mf#t*1PsQl#Nb#17L8-ifI4&$xpEI z8%{dSQI)#Pl=#*qJ+?sP`12g&z}^_|Q--#Xjk}GE=Zih_CXe<|VYeK9xx~Xd-o&59 z_u;|TTg2{XTw(WoiBPq-u^4}r+J1I*?Ih-*S5v+I{j1e48@(lc=+nBp&@|QPewYM9e=XQ6n>|N_ZoEJ9-d3vkJy54)iD&u|*Ihp_Cy<+bFez^blT=c(p;YOuZ>)9U&SylowMU-YOD829U1i7-!iafE3 zxry?AC_fcNc<#pS&|EY;7AqDLefyX<`@Z3Kix3VtpCvz#*3OGgzno2^ab{;>{&{{q zW&cvqtB$A~UZWmp0$Rk~%YuTO`QsV)P_eTKZZaP)`_9W4eq&Y;&=oI{Lx zku6RS?>OV!M!K=wwk&B#x`k*zh)kr$O3}u-nE2r>iPDxfW_9+F^Wz=pNp`T_)twc`JhjMI39AoiOUU$3I zW)l$B&WIseX*P4|oZ_b+FokkhBwk#U1-{ka4zQ(*&aHIJOpd-zRI-|C9l^O!@N9U43A$$jC{i_3fl5l!i*7O4bXMDt?RWej8?ZsvT$3fB}V+{CQQrcP$73=$j2K(gnAJGDg-E z=7Bi;+S?d^Hc4C+{ZLN+K;PXDsw3cuiH76}cCA!G`h>M}YD?V1j=1T+n!CxJe^0k2 zF>y((9S9K{5R&_0`iMAZN1LNWY{(N_7vR9hUhBULS3m#zY8SJ1Ff%j~HnaXzt^QH-DiW61N+`UO&O1wKY&tWE0vT-J z`s7h!vv&zG*yL8}D2JykiQYK|CbmUO%*H&kTQ_plBz+)C0+ynrO;Jyxp#loMAhkaP z^uOtU<4(3*s{a}Ky3uEiqh2y-#CYkl$$Po+I?;AH{^;X%&+3cUelYl5$jh_`l3v)& zZY>5GW4B+7e&GE|KM$?=3YK1u`n=sv|$w8bU z(XpMFXM!?26jEQOS4JkK(x~VvP4S)KX~$eVL26VM13W7ic482M2!|@8$=;x~kd~>Y z9`+-$3>BgbLP?6181^0ayA>QAgRAg8fT@A5$b2L*NsMBkJyUd6)Id^Zam zX7hJDZu)AO>=Fz5sg*+u-TZ_QII_;fzF_iE%7zMGjh5Wjpb=o;xjDeL*t6=^z+EA) zw>@24Kq;r;;0In`@xL%i%Nr3OwUOu~13?p^Wyt9$#S(5=t2Bh;<-bi*!)4qGvHzmg z!`F_jfr$}Y3Sfism_FzSKrta9#pi&o+M+uNEzX8lh{-bS^+zDdtH#?Rlm$w-iV0w0 z(u-CQQ*Rq#AlVc6Yar1XsP$4akUHw|+mN=ZGLm#)I6KftleoAY+p;a5o z1zR;79DK+=TPHr*cAN#YK1)C2+gp$z=qQix%@kz9A-H!7!&~M+fV$`S;w?quZL!k? zoUVZer1ToPz;iE|$dgF8;u^k(KjVY6;`kB8O*}o2>^ogIjIoCo(-a z2&%zzP3+|H0%?{og=S6nfmyZDS2==d5mj!Ec1O3)k*a76U!dJ()px^ktnQXcIs}Ia z5#5+-3?5Kg_`tt{d-Stuq37}5yK(}-+YB#kNs*ePPkYEs9RQ5$pNKOGfH~mV>46P$ z`a)VItWycA(3~F-0PNPut^;c1iGpQLlNc9`XFm}IIizV zYK?Iq82p$+2_wWb`%ylv1{;GoeBEZAkzi{*oNvCjPpIfu*mOJa?zwMblgRui3;rw? zArtPgMsliWuyoAdMlCVj9_XrSP}?W?2C>g1G>!PTv0gE4pwRFeeyiv*Hnt)j;N&gL z-cer&#CnM*-^as4EJ>yNsAdL_r|0G!#N{1K=NbFRIry@iBQuEJKIn#ud!ywmIxHw( zpT8GiRGBkAMKdVWkz1x>(qKYC&0KbnXPQv2dBB4nZqzUfaQC0;*`;HZ&WoF1-?JV8 zDRKNSZT>chm_k+~(ECI$^$7oyPX7Da3*f)+=l@)L`8$ds`RA6{KXM7cp&L)_V{%*t zwHjreI(7=zR#vFQeio#tFwq*Q)vc4RmWIis9tFT-?f#llAw@*S_q^-DH{z+M?N26G zZ#^DsHgWE}9p^ML{&;(ThUuoI2}bB;g~O@}VTi`Yl3Y_9uSBrkjTUf0ZAI^MM0gBv z?Vh4$uL!qG(BnIICrz-q-U()iu>O6aRy&#i{>Woeq+I6oySLc-A^@)$Ky=TME; z5y1d6wVF)mkzoe%t$64uX6F}qG}|{=9#a(vpk;=FNnP3z&N#eLMLf`Go*2_+HA*Dv zti+#buh?QbuGgWZ<4lBN#k;Iz3Y|+6L+a-N5!`_cKf0nyPZ?mqtJ-g-qFt42X_B%~ z7(6ggf?3y_f2b~SNNbd&>uhRh$sA=Mi7ELgUd_+#&_uEi^61TF;el>$!xigcBvP-- zq{6)re8r4ztD@xqBahV@mwS#ZfRCKk>>x6f6rZG0BsJqgrymObYbtDUeYL#Yf zm5&a9`(AcasKNH*k2h?rQ>-ks*4>vC#Xat&Ie15}{AO!dxmAhHFRK_u%8#|dh>`OA z3x=FfPF7jHnELXWYVHb|ez=Z4R(c-0^-&80rt_rFVpPn7j{e3hkO@%N2t>$cUp_7xEM z>mUkR3TgpF1px&4paKv(zk=)8nhK*~z9DA`{hgTj_|R$7r?VKQ4NNw0qH95u1P6x$ zzJs+k<}PoaS14UHdS+RMq<)s{5)8R(mWZ!okPIxa#>3B&LSyDbFt3_|KbJV+1bZjS zOBg6t@3j(g<>7madSZS%nPMw%x%q7}@!;W3U`lacol(4*;@mRW6OmuxcA2G4_-Pr5 zcC0U+IW25{9rmUU_n5B9#&Q5Va!tTt)DMikmNvnDofbsHa5b9Z(u zKRleJ zOTpO;OU4Ygk*$^6$Ui%p%EdI4EIz(1!IdvG6ysbuL(nmEaPo(&7-RDn6XtX}Qy8kRqk|X>^kP%}=*d*Bd9R;w9 zQc4h@fdM8Mx5S}VTZdaiFRDrKoQ46k>TS4-l6}Lt=(|QG*|V0x8<|rnpvwsj>}w2c z3w$xcxY+Kzo6UiYxTz&S{x(;7TRBi&wDA^KoVb{5 zGB=BmSWG#tKm>`GRIHlB%S`NL9=|Uhw-p_(FaWPU?$ZivS-^e7KG`k(XF?Z)vX{u+ z3lO7zA$5Gk+DkoO)fg>k(uBhixTX_4pY+Z*l&q>TQ8JAw>S z-)~90gvWz%2Kq~x$uH3ik+rA>A$n7>N_|(YIvC|Gnj`ko?JQCTj-%Me2ZNe%W<$#& zorw!dRZOij;lCnQOG!umWUy!82Fhb1$x+g-kG#Zf3W(sz0QjKp|3K_r!BsrN78@{P zy$c9FQSB$_6XKIp7oxZR){s4J7or*)Np@75_fA?)`Otf09H0ZLrS^3A@4Y*@#4j{I zeXpag9M+zzvnn;h_-N>}MOt9e*FDOGSuk1pvAOFf!YhPVsl&*|@8ECsOTjS{MJ>_u zFRG?5aKH`u=`oQ1j~;{n#b5is=cxR>o%E|5yZlWkmTEGa^-E5!q#8n!$Y=tkut*3_ zRwr2rN|$F-BO9KAC1ciO`U)KmO|<2YowEh)T{5_P?JMA64tOUye46GT+Vx7{trU;9 ze`2uN@N(F^e82E|Tz@^7?DF|Q?N;|R7!=2;=!3@5AJ@an!%f~3^=18uN61ZOJ0)Ibp$}#kLL>w|xuVc}*ePS05&xF%AU`qi->@+&`x&`G>wvz0w1t&guPKbeqni!|O zql|3_$v~fh=C{8&OBt1&isBs5stQpoO1zcrBs?sg?zFCK3O0owafuNtp+Qwhk%T=& zyo)C<)LkHf!!ZTy0Q07;BalNy`G#|$K=suCQEibl3U*okO#IzkH2jrxUCV#?__vw= zyqG_yqa~hNoD+S>^niX(^Rvr$v-mwa8~pTOPSw^h^4ilR)KY##IMJ0@jL<1jt7>%p!j zgn0xfT$_e|RCV{P=9)uf+A_0^hYAOLl&PN)H{Php^}%-$1#2|7-Z5Zin}uh!Vz&Dm zm?N)I5Ut?bX|2cyO-5f{qcUs|I5hQ+?sW3UpV}66yaQr~ZXSEz>YNp5uG6A5fzsc# zVbS&`1`5B?gR+?jXKJ*sS_Pjx05=$zn!1M z*GB*96t}jq?;5^CT>PzrJH^ zT{roLza)*j4ztXcrI#TZ?GUX8`?c7v}rv zpLw!lL)maf1x+uKSCpG*B4KwHsd-S(uxe1xs0>@!_A;iQxE7Q? zllEE+(TrJ-QH6!DWv3{U>ri#lInpUr7WM?WvrnE}9L#~G2%^>>H5g*C$;CJh9Amkx z4*StNG8Woot(uN(6CGy!{u#lG+xJ+{9v91vQG!!AT~xnUheu-4-uF0QbT2O2g9 z{m9u#`=v+=)YC;JSHx3=sms+xixi9l)xw7-ME&KpJ+39|e85maXUVByO{~4o^Mgw4 z<-jd7@w_TD)piEPmx{#X?m0#iqdGBn6Bi3W-&^7a(wNGct&+Da?tOIeO{%NXY1T2wMv@+m?lZ6$IEo?zj0DJD>%;3nRH!pE&euXEjpX`i{1w)qi zRkwuU7>ca1NqR>NdSQwrn`oXC-ci+IE?0)5M#?*bLXXVQ*wKsMR? zjbQ5&tNwDu&n?p*1n9DUu=G0M_Nnj1GO}#wLt@|T+1mx zSfzELgs)+x_d&G<2dcn()#tIZ@9bRET@Ik;p-u?pTX z3W$%*Ow60hX5V3(7@~qL)SO9D?;WYJLGRWY^{bZ-s4v=zAH!VK3x7JUX%bk<0CZpE z)^;#+^<_GSKJ(+=oC|UlxCw`(!lZ4|%@DpCJ3{I}aw{bY&Y0No?;}6(>5{anpKz8O zmdK?dYO#j?NTXOwYB)y{ z&w^W3MEqf%xQZK*6CJffZ*i|;nS84(pqH364t8OiOwfgPLNT|@DR@Em*|%q7>V8+V z1o}7c=-|v*gq<+^ZEiHcnIN+4`neGMI4x{nloio~Dfc@uqRPtW8sVq$6B;gpW0tgW zJzlAd{QCvB>fO~Bc;34$cURDhZN_8_w39>vWB`)osVQ19F=_qq6owTK&sXx9J{ArG ztW0J&tfC(JqMl!p0bSmGDxVQ#R%k&i*l83JYD`aE85fZ;hMJ5O?=tAY^FEUN*dm9j zhV?IklMtgJ+hF4Dx~5&8ZQN@HuFgH4A{k*+LJOgOb9$G-)x6u(Juj-&pD^oT!egl#Yl(2ldJ96;)G>7NJq;ZF?4`Y#yl|Gm7z{C5miDF4@( zh&O}74hfc(c1rdKiunvE2~8+ftS?cCIwC82;A-cc*=|KO%@zD({JAo7m2^X+g1mUw#Wm(B9v}Uz_lA|4ZB$#w3_XJ15ChH z^!6k*j*IKkV#mE}O8CKEn0dpz__>TL%e4ohTr#5B%XZ4ew6OwlLnJpp9H`)4?~vRZ zmPjL_dZ%Fh`o=+BD~el=#iX#KNwWVLWw-koWry_lC_7R(RaZty=5gRzRA|ZU`#0~Q z(ivl<0jk1I-ngjwp#fU#X55Ny2U#E|gv*p|O*k1aUhLW+Tj+05cDC)L0G^dObu$Rs z+f^+VjBI3`KdIF|y^E92FI~?sJ~#J&vPUhLeS3~c!ltkpWfbC=T8b+nfZq^}VJAPz z;RIjtZ(|na`Sz~IB=1_5S1z-2`;gUlPA{yxYn%rhHICyXT{A8Gh2&41UW&5s?Q3pF zw8-p~#VW=sGu|;{h`vuGbo>y_6~((cf?1kwULi-}ORs*yOlEb3x8M#j@-I{{MW#8t z`c|l72Ngk)D@|nV4V`j(!@o77m7~ztzm_owq84HAm*HsstQ)vCLjSj_ za`4^m_?vrJ_g|{&-y4#`|KElrWM*vqX(6^YF!~pYrK+KVtb+0(Z7sN?N(?QkLATNn z1RCm+uS-Revt%15q<-wggwt!vgiMZ{Xl`Kx?{(7V)6I96yPzbu+SvNCwmF^h5y0o< z^a~Rs;>MSm2A{*^7q5qp$>szf`P=hlb=Nlzf17;M!5|DShTky%hqJGWs(Vke4jSB@ z;O-uRySuyV!8y3QyA#~q-QC?aKyY`0Lq6{9?)6RIHFHvVP03M zV+=5&3w@bKF*S^3#O)`WfR<&F9FNDMkJ#^!cb9{^lxiV92%`MBR%rMrZthK6z#Df} z3N9k3;Xg+By(16%897)9qQ9absV$HGw!vb-B6w4L8O`!Zy{#__r+H%0QHP0clGshA zy5P`i(jeGeq5LR(k(HxAlsz#{(f%9PS(-y4ks+OB)PO;71^WQBNF$s>5+eyoT9t-I zaQ5@7fE!$_SmV1}u>6#ILCyu0IcK)b(%27Ls(osEP1xWvhTU5DO2-S| z33TF;?POMZua;r8m{c?9zGrmTKzRScz@=G@ zua#Px1hiMDW}PmJu?0DLT*i)-tBiehqEIzkLHJpbdyGK@XRYSkzq|e(f6o4KaZcq{ zlxCB?`bg90`v6ep)IX0w72;vIPsKz;LJfT`i%M_5Y`;+wMUMSe#X5}c%n^?oM@DHM zHO&j%`ea3@4-uQ^D9Iiv0;MIAOxgHjBE;A+!T=kmf3x^K8XFSNMQ2DwJ3&540gMiA z!9+WRDxU}vRtB4KscTkmIdB*WkpdKX5KcRyoeelxLCt(n6Z z;|W(O9Ht9>E?h6KeQxH}9*0nb#e!Nyhh)^7;}$Fd>H`RsS__+nMvt*-e!!`n|l06M@K5ZdW>zZpC-pkPCl_L6f5J-9GFAyU6V1|9XI zfMVtrrsQam4f1LFg~Hkd14tH5EUbxv&xwHFk=c1zYuRvxee;!pwgml3b_PYC~#IbGKOQ?0bek5NkvdF`tEUeOt;V{O;QjoZS8`@fD(i&J%O42N9|epTwPf4jbDF zmTVd6H1bC?U*XYwk7?JbM01bva7}t9KLb~gcXID1T+!gnLCWzp-O1b_tK_&L1K~i3 zDj&BmMELck`N9xZCs+ys>73E1&f2%%B$TnR1vyOeL%$gVob6cXZN>&CTUxL&*@apV zf@kdV9Mkru^j&!peCE9k(ijTy^_Rg$tl-;=DaDD#4rxH7m6#u5J&)K2s-c|Cj-c-$ zuRc{i*!f}^q|{#G7a)nyKVrQQHYVV^vvw;F3-=50a_aBEg3=#qIBA$JJeMgSmQ)N_OPfJHfGggq)z%*@k)66!gG{KN`*@zHL3v9~Llc|84c}YrPzi;7+ z5j#$?U-C*Q6w(Y#~e)9s*hr3c@bJeLZ4?@YclAQ*f zxJav9Bu@sG$K;b}u-QhKx0YgB%ASaguYNea2XpZjgV9)?_RR+s)Yl;Tusc_M zX%Ld5m1Mzieqc!-VQq&UyA24PqJ!OlvcRZXZ}FqT)!4JT>o=gpPmN!>5*|0+p-t%8 zd&!%6t2@x7b)>^6vTj>p$G-8fWV@?(j7gB?>)-voOdGsDI#N=oC_=m-RhEx|x|Nz@ zT3RqPar?9A?5?A-@N!^TuM53#kdXAVCdJbn%d!q#rLyW}`^DI8P)Nvyzt7CV zm_q<1r5R&@2Kp{FzA2+W2LKK}A6t?)9{m>QW{z)3KGs`c5H(oYXv3I z1J1qwR#@J}wV9?3Zn22K5w2^xQpZ634=a>qJGYj0eaFDda7I_#vs=OjvbB58q2QyL z^}Fg|bjZfWM(p_x3+u}2rLSuZ-#T?HZ7RRRHL?dN6(F?CCjd_iZ+y&)7v7rv4H^I* zhMk8Oq527z-x~5nxhq}Z(hCpp`F;lXmj+-%E|e(ZXK+w#Wm@B}#50p^Z6di5B5jxsEh2VdTV1P@l6$Z8l^H&xr0|h1kOqost`lZTPZ9 zq7tO|G_hBi$zu>y;CY?Bhjekq9$F>8pQi-Wl_}(u!vqG})GN|S?*D0iG8ZE=f|r0U zz6(?3pDR9VeRDH<*UM{o1RjQn#v~mpBhpG%mOY@X-5r{1&Xyj+d<#8_N{Pbgh+r30 z;jI~b+Jd|fkQ>Fw=gR zEbfj>JAPdR3IdT)mF^wpqI<*qM^&`Tok}n|B&TzpLLsY z_`_lP{rzyd8?+@Hk@e1?1GUptN&=Nh+TtUr!5c_h9`#OQnX(Qrm2YFzS)|Ula1{r8 z!rfZvhHjr@*}#&*l;7^3Ss1t-+g#jxUQBIx8jx|RWlY0{`t!R?)uv||cvy;7k_q`- zBOjIHBEn`l!cPOwGUn@e{Eiw-v^FF8DZgu?LLFwnQ`wc7uL4U|^inR$YIXAu9A}xL z*3z~$E$}G&br&sQeo%7SkQuSU)l;(+DOIC#DY18)G)B%}RkSsplbEVjxaX6fM^;Sv|`(o8Kn0767({`hFnl+!9^6IamL!6=%SVgI$pL@k}Lzbc{6XEkfnO6N$ z6z*kRWi{nT&MBf?qfcguth9_T(%eroiSPtgqt~k3%gmi?6lBGKQq45JM=T+MVXl_^ zALvfBh7vgs>LQ$U7!}bbiH5FfV%RjCs@GZ3Y>AE?G4VaW66BYd{0n*pB&t(;Dt~*Z zb_j|I!!}XSNMf!lQjVv0d><7oTWJcQSj^@w+O(xmI++`!0cPj)tQwbf{s3?L`sxXp zzLM@5!@!pyHePS>9U}jj4mf(=aaD0;tg8{^+8co1yQo2&vc4XuX!d)9jBz4(eRy-j z57Q3EtjFuUESm-cV;{M-rincp;@!JS$*czi6>%mXnrM}|aN{&;!zNC04yZl(U@!DQQ%3#DUVhWJ zs2(^Lo|#MIAya>AEsM>briIayt%-Ed`LOsG24#yprU>;4cFqtWZGiaD=U(iQb*6k$ z<(Nh~$8DE2r-+BzP&VGin0EDRCbLRv3~>Bcslw#*te%A53uGa$W^!k&E&$ZCy;}+m z-XOyb*(qoe)Z2qKg)SRMh24AQo)CWI@zh{Bk6FN47%_pfxc@e&%aaXk=Y3zDXuv1Bz zW}>S@qsbLje!TEC=1}Q)tV~Gg)_b5nr!3hCCWnb*O`)u8LDCu(XY~F9t@BA_1u+FK zGjQm_IkOPn1z)V8Ae|ig{Dvt7GffyUU=L=7abwvbKQ55ZyE1}#CTno%r#Gt}@J-We^Jmom2!Y8~>GCtV z*X$*fy4B%p>IMe_psKM3rK*`SJk+irNhXy0%%fR?uV1rzjPY3pv(3C=fBY%blmrs4 z|G~Cr{u}E0E8G6hiSfIO{bu?Ii;dW zK`jS%t!Ob6b&K`6_!X}hM2@r+%9UIcZoT^U<8qdsEE&KPf0&wPMdC2I8nJ~aX82(%cUri$!1JVZH>SSIdw_KaPJuwfR>TC3A+C1^qP zc`~at>)*Cl_&mWloiM>Fi8BjYGfIFHx{;L9%^uEG_%U#q#8EwmE`N?pY)L-(chLUh zDS4{C6ABAUEO>)hrx9nUyomCZVUe=438I=XDSl*YWOSOmakM1LF8_0geImCFEhpao z)Lzo$7$3?qk<%LA%IRT@n#iMM0cA6F4bW>xXyNa7N2RAN3P&BSsa+7Se-_40q@0z5 zk64obw+!{ySYrNX(%8aVtRpZTR>6x}-*HsmN70dorDKZH@vH`Iv>E zA|X{#;1w%vg0pzLQnMC+cch*GD!c-U*MkuD^jVcW0o0v=+{P>I$s>&Z- zXu1ddwrkm=|2NF5p9jXd?%YG}cUwb3kGDP2l$?K5(v z3c`X&OB|u(lC%%c;j#+*)qqwh7gi)wp-$H@U=;nF-<2DU3l4R$N^VC)#+lUVW$Zx( z>z4o?CUsj60N8zzu|S)KH6#@8n2fJ>({}S4FsDL7PH#BEKN=Xokx*n1y?v~ap|W4y zeR;z_ki-5t%iJ<3P5moVj6_0FV5IdoshwcD#`I7T|c=W3Z zH>$C@DG-rsA^P{ois^$w1>HoqLH<N_jDCbH#2;7=O|TbP z>7(gP``c-|zmD|HEbPIN7!{?6m$^`h!wF{ z8a)YKT_(V}+3Sko@p=z&7My5y;HaE$%+<`?RX#g%)%f0flH=j5^JVuVMSi*hHbaHzSZ zQwVLNu&$)tX7=KlmjZ(YL#Q|6Mwt`wCCP5Z;B*`3&sZ(3gAIi)l}yXXl3c%@xrnrl zw?m8cB}a$Fpwc|;>N8!AMgnEBZZ{Ik&kDua+e3)Si}Z!4;=ZC}nfP0L)#Bs{ee@mX zK^|<|Di+P>o%XPd!{4i8(7Vn^6xJ%5{z`PTV6n2ptn-ZOlew);{rKKA;>et*YFgH~ zL_}~+xqU*&Nps_J#~3we1X#;_!+k7kMc0R`4=9gWBTZ}@j97(S++AMEW$Zfn4*g`@$K+=ytyKSI_kS1ci z8AXWl#048|5k^lLMcL!J>r&+dDQ6(azk;8lKs%)wwyV^5HfPYOMH1oEn|})S-9lO9 z(k>L=M+2>Iu~AK=6&kHD5r@6|(es)L#H*T=@$q}e^A^??qvW7SeY6u*u7kLwbG6gt zhGh6z#6trPU*0O+J@@7HPxDu~-A}pDACc(sx5@Kwm(>3)692VKAY^OfYyvd;ead#ejfy-yMMO-n7&;p3PmrM6P8a=0w@jaDVqER@ zLubVqZiuVgU$}d}d|c#I!huzZ+GJ>YvVRCxZT5Xr)D)i&oMAN(IobM>JY5~@&A^JMfiQVDI)LM92 zySQz!PfJhFbTD^}ri{2lCXqo*bQ6h;$dM3N+>w}uwgHGt{Lo7wZUq2Czu-PZT}Wx+<@jB{80`KDe$ zX393gh2kFmpr{=|zAHb)f_3*^*{2ENpL~5s?`DxL<%E?TAs4iu^uj^>%C8La0?i6& zOv}Tc<#sUt$nAD?#G9KRFG}y<*z&&;ihpaT{BJMnzqUyKV{=rgEF*{eF-?u&7swhE zpL{jz8@M1O1ySCY8zK`2Lr1BoN$L+I_^P^Nu^ip8St9bL#G`WJ2PWo?X6Ot;L`@_g zA8>x{dN4V0yMmeWd+L*Cj|DWUI<YK>nop69(d$S3Q=a+Z_Q9x-Gd5U_~+iTeIxgsqARmVFc8UV&;kh)84-#ae=ZGG!n zY_DX2IShWUOVajsk_2G$o&!=ljk(&)te+m;GpCUEq~4@b(L%;+X|0VB?^gX)=`#cA z#;*&{S7!3sk0p9q9+DZXbvCF+k{YV3m(uC`-`Ydhj7;~MXEM*N?ooEZiOx+cCQ)bRc zaZRecEivVV<(?af=t2J@W|a7Haoay2?CIa)f&V;a1PvVio7Va-4RxiWj2tKvQYLYo zubwN@^#usS*I-;E6m)i?JR}ABtl&n!_>E-8c2f6WdTv*rk9?SA?em56i44<6S|mEu%UyJZdUI4+el!tI~E z2f(XO`c~zwM=<2$Basg5h zifu*t2qW=C{&|eE7KsETX*@;ZE9u~3RI!1)y1h6P&iU>IOei|XH9&}&w{mg&FpgbG zc8zIA`J!%@?SuB~#TMUhkQz{~5Hy=Z`_KEd^d<_UMlhDNWoJ+HA%Kd*W9xv)OAV{K zl{q`z{;wVv7O9Ih`3AE6owODjKQMiLb#J{We%u*1pE^RItRq5<{UYRUG8X%)6}6T)$vo27+zfXm7>kHeR}pT{QiW)gaV3#2Lj)Hrk+ceA^AabC32_ z@FCBZ8c%qyHKF+&WHvb@`gYw!C-26LVspTeFORsm(`TNfnBI##n^}_ZAW-df6d1FY zE2dWmV|ZEGqkH|klQt6EVj-aD4u{zhn+8()sZNGk$=-{-3_%tN=??7_ujsMAC*)vE&B?afAsSyu5rZQXmE zk3sF1gU2=p=&m?kv~f?c1YD3o=K0bUqjJh%bBKWky=BRXWCpK00bX&t2!!9j{l0^k z5&*|I>2Lfx3U)s)K-l;&>)??)JE2|k4|CHWt@Oum;v4D>e}UmN)yNPN;IFV>0nJ<- z`#3ulc0I3@kNP^wJ%R4$I1lT2xI0q-ohdN;|!Hu?s8}#0S9lEkQ?ZAT#BcnrI%Z78-6i!=k8bh zIW{Zm*B47HZX11IvReEZ9Iz#F`q-jFa0z|xbx)2^m*g5_6!WL$ZCSXnp5Km)C-QJL zac)<1rbyY{=Q-QBoxp+8Kn97EH%4tEyPNs&_&t<|SkgH(g*M*bkl*KaE=RgN^^7t) zdYsCf0_reTDzR_u2jeY5w^|BGMeLX01vLj0rDupIM~>%gN4%xa4?Z*3RM>W{1et(+SGNyoD;}u7Sej$``JX1qr z*kaJj9)pmc0qPYnM1W^Tn>oYkQFVq_qd&4=hjx*9MK^$IB znYz^|aiF{-XaY=od%afq+JgH9cA?2BZ-c~7(t!o7y5RpdjHLgp z8GkA6ok}`VpaN)}Mh9vds^oWwcZEdm%KkNx5M-lQxy|7zY$UXp-ji}e-X2>C~$y)NvSu-@T5_-VJk@cfo|oS^;ll^+PAM_e3( zss(Qx+O{zR%2y*2gXyAF(z46*T}*--d_n3yC6(B-Y>Mq&^2p9X4Nj0jr{7}?GW0N_ zvG+WfXZl1iu*Y9bqN8LQ(uIMl@(8~oe$y&W3oi{PD=$0&<4u`i?j5u6?5h|Xj$lJ# z;AAg|Wf<@Gg%QwnEv$b4L#ZQxl(}GC;kn(cU#aeIFjxm^Rz+aFl?F_f-9ox}EF=k) zV=hAVZetC42qA8hWalG%SvlaEh)~z93>{)AR1Kzx-x1E@Q~Zgq9}H~?Bx{F2&f%C4 zKzRS;vr(z&%Pl`XZN|UhfWLzN|6H8=Ck{}tG5mwlHZlI66NK$NBN~rxn<)()t_j>% z-l41`*Pb+2fzv?n(_om~q@(y09zyn7O}S_tG6bPr#4871Oj6QEkXPa?Bz6eaKxGh= zxSf}6hpEo{Ux(EMydWz>2gLNd;W3Rk2elWwWigg;~27 zMPx)E{hnvO{mnt++f8_GTX`h#0lQ;KbwGZ#KFnAhCNZv)7;o%M9*)f<%`ZwqHTK&e zUpzXyDu)nz&1z^wSm<#4@K>2q47niOt$pVmA7EPL@>s|R8DLsf;TxZ7{GhEfbpa1-@Y?e@X){|CB%)P|9a@bIxR{n9bU{K zwWFH|&9-0Tty;DR!*#Sb`$!SBkve#Xb_v_FKAgDy7t&-;r~}!GKNdBk1M%fAZ!n)b zyK|HzCW{jkitV(|Go$M*E%EczfBPT5Jy~< z{}9{^oc>W-HZ)*el@}XzEp^RIflx@y{7?eQ_@ksu{OErCXeju-fnq5BzI1S-MA)el z1K*(;8ZF=!EiEg}MPiAIlGO{*t)YeG%T=w<#|w293(zVQXd(V#Hl@(TcYW5Dl;_z-u8@BYU%Ff{4{5;}z^G$Dw ze8fDDn|#!$jvMApdq98>(;-Y+%F7cZ1^NaJTLyiF728W#6!ZCG6N0`RbKEgF(saxy zIc2=w_3QNYoHcXx%p(e4)b6!zm-42=K9d}Nl5Q1By zGN~N_qbiMmURR@@pFQ#-8MS*OYkt>uCJVEQU|?LI-F&6`-6lb2ovmw3?sNdC7Gbyi z2;lM29ua!CeBzwWpm90x>bg7M25r;D&%9|7*rgZPA_{a4J$89~LiNn&wz;|OzMi~k zk&w4RNlXWan3uaLe)WX)S(|RYG3#&)k+zw4EgouS*{A#7ZD%9owENl^<#4*BN?)m= z&~9u!`NQqjG8Jg?HTY}D7;&z-l!g~GesohJ3w&v$2nc{bBbK!L;wyxM+5&5Z zjzWD!R#@@+PJ7_kKCFV^Anad2Wa6mj7G)x1AY;K{glkc{2d zZq6S1MGC$2-5`!W??4u97a0p#Nzk?pm_tK{!~)sSmeC>{8$>JxPotn(((T5siz)Re zEkv-3SA$t{whs)_TR zjH2kr?UOMq^MjZ)mkT7Rr4+T!t)wA7_jNN3$=^1Hn70lhh+b8^lgEw_hJ$rCZNMB7 zj0?6t7kxS@%M&G6GpWEn!KXH(J2uy{9l#Yvvp-j#_ch0uNwR_$%KNYn7V~PU3%czCV;U5la%3C8Aa>SQC)W8ppV6ZquG|gQnkqV0*e{Akd)wt zZx|Jk*tn!yIAzM28aB2AOX}JvQhj4TXUr(s?4{OX2G?m}3l{qN`X(;494(?811Wr^ zVLCVg140MAB!<^^Qr~dG;fODqr>#ug32!9`eo)M7yfLC=O&??&w>_Z8Q-RCv4x1fC zoyE?SM>F-1Boh!l?bKH(m#1ARvT+$yzXUaoWj!42$nF`EE zfWSWpLfJ0jguaUlS`?wmRCQtnG+^zl*_?&h_LDaN?Cv7Jk)-X`-kVhB1~M%+AMDs@W&w-_h_8LCz&l#il#3DFVZ6KDBw2PxWM9X){4|$z9w1Bq@q`qYUZD0 zupryUgU$GXl4YnqKalt&~Vl$2(HnO@LJ8SGQN?50Ii9sQiAc|6g+xpaC} zvUv72TrPq>rwVPw7vio-otR?==j9pDqu+IKbzoPYJM$xGQL=&-6~kIpUdA*G3q?mY z&xoflhpO~vR-XmxMgT$w2`K#Idf#mHyS0$?-qL$(GyJ!0=i{P|nQ=*$-4{k}V=^z0 zX?7ma4CROyw=~+;jxfK*$%9Js0(17pO5HXCu$t7HT00BdjqWm|#wxat>%JyKKEX|I zUn*!DfwrcR+77nvw%KO>EX@z<x5@9LB*1X*~u^2H=oZ?MXD5 zR@CE9*!&>yb3$ItNnUPCDeer`3G@;DS-4@^y+XXv`)E>nF42-o?N&Ql$P**E5Xk6s1f#(n(GAS9D! z@!8X6CUQ>p7m2ol)+0qzA;cZ>XVsaF3oqiRG;vmxs^&KwySecPpuy~`cQjAZWx0+q zGHr_FP8>7v=Z}?`-{3Zi=55w;=kZS#9%VCKu61xOm)sC}%I7mdJG2fv?>c0sXW1R! zGa{W8il<(T9a9K@# zMB5c;OiXJzy>o9-#4sFr`g+7hH7B2(sXC%?dMtcu11`~(EkAjG*M0PMrz{EUE}7>$ zmgD5>K|Jw{?Jl@YSuLNRK04&&8whbESLkUz=Hld=i214c;8#{VrH7oRx8Kjn0_DI! zF#AOLaQsS1F#p(6bC)_5bBl`OBXdY`OqZFxQ|#oP)>U=8T#E=beRRjZeR6q+7$q<; zJbnBM?+*P0?Ad|0@8@q?eoV*VtG;c1T<3iA)tx)8241+VY{g`1LJ31`Ek1ep-+=NF zhj{7jqH=bR@Xb7tz2{CLD7cJqL?EU7iZ|U{2QMCd&5KRhPbC1n8fEHjt2ueg$o>xF zX1&idd;IiZJ{zUCn=Q!m+BUU%S21KevS)_V-_xD*nax}2Q13F znme>W4@tu;k$S+zQA zI+3R(=JSR;i((1I!e;dIgtDgVNpVe{62B^jzv2*r&GB4H=V&UlztM+ND-@hsU&o_F zW=eEE-GZ*={pa-pnMzJ662NHcVn(aHs)EX!YGx(N*E^ z4ajh6)k?$~LH!!1gA99?lvXV@9dRqE?yW>d zCrzQ(C#`Y}w;PWOHAT7zt;s^iMHQ9BxqCp_qz=pj9`jK!Fc`aZ>DkvmLQ2bn(uQ?F zdQAm*J>W&0COoR5N3~>Z&c)I*pnT7OV*a#l2u!*{t757aq+-kU)*=QFj(8G5OSFFT zJA|9Gc7lw(fu^H%!9(UTlGCPh11nZ7-7R0ZPLQqs36U#|f&)kzXyzrFDsDO~86aej zOf2A8fSW`Um!x52zz{l)46m<}bz+Cr{UB;oY7tZ*z~ZOpdin8gH)YseEx&#Zj73o^ zy1yO#J$6^Ls>W|B&OvN|ZbY(3LeIrA-P~31R{kQi>EZlqCY?-BXUv+&cN|Dwbzo9+ zR~oe2zz&ZihuoHyT9s>sBScVa$ z<5V2ir=QuXS6WQNPW-(tMLo8ktyzD;M8EjDUn<&$H2k)R#tn48RJgr&Hrknh+=ua#xN1#H%AGC_irqQ+!ZleUDFWs*`FpkB&^v1P;M7*tgMeJz{AMne9zC7%Dc4(D;!(|ln@)N5;?=>UzELM zryg}V*}GGwP77~k8t4zQ68J#FZDT&L+R1wu;Dy3u)0S9HR*2qny8j1<2>G4?Sss=F zK779e!H->hte?6q4(t%QEkUl!f*kPjqnzL7L@D<~J8bcKQG5#f7 zpe5f#2g_lG@N?re=*N+SZnS01=#%ahzw>Lq(1~SUOgTXO0CC~vb}>hElSZ2m^)2{p zQ~62B{pZPnXEH@<$io7+8iNdMOEF$<3{+5Um8lhuA+gSi(CUhr%-7NHWBwq$1J{_X zX}8>B08WgIdA38xYKJz4pY!ty+v&jzA z2gCwglSQ=cq@O{*SPGhsqFn+5_x(Wbe3uHZ+j7;r@XWNJEI;_x1LON;8_PTR<-)ggavI<;$!Pu=9nBc zSGdkGlRHSY8HSd$&Apge1`cW4Yqq6cfg@8nBB?6m-O#0)f=SSB-JkC|Q7a( zM&*Jgor2<_F+rb>Ot0;kHscLR{1=6`3N^d!{9BXG9H> zb<%V*QwW!UQIsZT($w|z<<>!Xe8x5UjDSP(D`T4Ib4>BICq4SLn{pp&NhHOZDmEg9 zboo(<)0^sdi*fd(F6akid0HXD(A!cu2aE(4^~MfH59B=illZye;`WUBxMR>Nn=v~0 zmg1?qk4_e#v9J$m+nxCuJDGli(eqi|M&P9@kEMy;8Uh=>qI`>mka6;l^6 zy!JSzCHrj=1MU2Famfk2*I&2H10fY6fJqO1u{G_wLd@M<-@-ds^_zvx8)v1XW-?}^ zOaEIl1eR_faju9oi9}bVd8! zIHL9;!FyraLU94~)de^cr;jjg{(O=$BR|qz>8yudEo|~Ke@J_*=6JY*@r=+d3|HQP z4)KA%vPI7kd=vHAb)MS6LOcY=w2PnKMd0ez6V6W@&2*&qKgxm0B*)2xI~S%-rqFYqG!Tl2gcW zygKG(;*-WR{D#gJmkP*X%Q!3yf_x{a>KR)51OMGMT11=@-{eELj`Rz;%K|V>9~ao2 z`A(2a-ML$C5IWpDE`JaPgtYzfTOO%aH{LI`X8KMhSzOb_#K!FVR5^F*?dW_}c^LZI z#)jfZWA0hg#?I>UadjpdQ{-S*OehdI?vvE^$XM_8Y%i@leUbdMuSpSY}@&oi4pM0||v zx4S@}>_{%syA|k$oUpp1XbzL(a|ay{ckc!(DADtX9EczqnAVo92wY z;!m9yNhz$#^$c@2Nu^ub>Q6$1{LbHZS`KJi@KY?_gJF52Oc@`Z@T6L%iTo9}O}>|t zl~4`W;u#%Yxhp?xM9Dv_K$u-~i6qNPSDiW=GL+8;C3(C>mrWzW*DOSK`n!Nnf&)U|?*er$uiV%tP9lOoW%S=i*!8_@(d0 zB{8EeKlKZ5#RD`x>GacxvgxKH{ls7+|XzXYa)wT-!#F6KKxATc+2DNBzWNd zXBw#t*h*bd8}j^T%8A6yk&fiKkw?1c)*DL=Qy5&i!Yflz7#}eLfTB8F7AfMfB%7&* z2W8aIrP583jZ|s*P}<^=4w*^S>%IA`4n$^4B`>^VL}K53!nR)SN%tx~(>LsUR02cf zlvxR-pc|5+%1AWZms7I;b5?r#7>}wbGRH7Sx-o*Q1x>~fTJq!xu!iYammtKt?HxJAYwgIxP39y0g z6T&Kn#cWxL^-NamYJzW!Om`#~DCkFElnGblFKkMwg)3(g$8ZC=CLsworJ%7*ozn2* z&RDBC@T8eR>(jaB&mBd=lV8%!J|pfMEO|BI*rEruj9DWS4~hX!`T5IVGDsxp#UdTW zJjT4}$x1YED25hwHK7l*zaagLTLOuwV6f#xSizWBMR-;#oZtHRRY=}FL3^gc4imdJ zkLdc`aBJtEFia_M<5rPl=SRgDL-PEmoQr$*mFyAY(=8h!ll z^*GgyKh{5g>(s>}HF;90nD^oS9xVb41|ie`IW#{jt>Om79$sVk5AH$5JH+;SaeId~slygw~7bc3{jU*&$`jTfSh6e-xJCJ8Adh@4y<%qyXBsZNE6Xh#=g{Bfm{=9cWhmMJ$Kk6EdIOWZ$5lGY}=w%TqYFoHkc zG?&+75}7#cG-edGCDGQWP==87vvWB4;XOAGo zmR^NqIA}2%bCD})T|c-`!X)mZB4N|6CS-%(o>>j~BA`{YZF=r#iRSnvRw&1}5%Tvq!A@gW0w3A+bW!0o{mJ)}BW&nXize()qJVKamFgutlgxoWO;7Uy?nvZZeQT!{5$2xyG zR%4lD{k|rZ#6|+No`x`dR%1jipTBMQgXcHnA{c)a!_tE;>CQIO{@1u3yR9i^W2?sj zESH%npoTp}EbX>{!+Ru~fucdU{jT5~Jg_668=h!spQxO_`_ zcRUTzE#bCVHa_p-4F+q``a0*9XqNsbdyU-bt%(~SgZx0x1aSRgdmzoRpPvaszpx-y31JNMJI)j zS#sqa;h4qg1v;f{uM)Dv&F>M^8u`B9ap00}shA%HK98so@uj~cF*+q|J*08|>^f(# z2+{ARN6b<`aTf9sT`LZVr6Sfe`*C6IkWan%HN9EyXm)>Ri95iTR$y4&JK{f`$*+^Z zU=do+7y>Syvr)Z929_PXEEM=ShXD82;OAi?XJort&wOiWVC@w1fnN2ESOx zf;Op9rPE&-Ur%sAn6}(+5jO#bBP}a2CkvmG_eJkbE8G4QZU)U{0Rsvr+x|e<)a#mz zqo&Cbyc8i~LM+5v`|Pc|YiaH6{pIN&dia3)h;Vr1P9y=SnoxND_F$33jg6gXDR9L! z6^4NiEAT6Wm`wK^g$6$We0?iMzo(jo2%2n)a#fj|Zr@2nElgJ$iVL820^lU!&sd&k zJ;6v7W5cQ5rH0bib=lQJ>1*{-^Lt#~zpzVaNMWM6SJANaCzY{bUIIWP$$)1biOuUjVZ ztBTmd;j#D>iE`+2Fw>)&6=*?SqHrnbE=(LBCK1bIBkf%tz8L>rvEC}9lqmnLkicq# z_(u7uaKbXeq}6ezM}1l5*{B9_h{5=vIhq-p83%~IqAygOhVBf7Ks{K9ps1(1M7Zur9R!T&KCUfb-JFloMk?5LL z(N6ubPe5`69Jtd~#To~Lz8%d2wmd2@v_Lb3e6z5OtB_7#TU&*=GfBM&AWs0BL3%u% zM5HP^ClBX&CO%=9#B#9tK^B&=Bp(gW!7)B_9kYF=Iv;HMT1mC8f*=$Kr2MP!nT6P1 zU05fuHzOpKq0B&A5U52N9h3DsKB6E5@r+)7c70Y26LRV@)KiC-N{E`y+{l-MM^UyS zpd0wBu0W?;N^>emndJ@_N&QM)-DGtQscs_h*_X~kLUYT(#F|Ri*dKS2qLLC&p6S(M zvh*xbWRNZbETOqP>ny=WOt*AzG23?1^)r0`m&{3wwG|B~s4hSZ5S?;;+HGIZ;k}W} z<$542XE(&tpLG=Ad;rL=5P@@N<)->&o^}>(f!mYS`dhaK+`DzEUlwK4Uj~y;c$*V1 zXUMz89<#+UU2z((RVS;oIo6~BdK<2w%s?y`?FcRT|7g<42yW?w$va)iLd}1Swd1$GG9(QU##+&b(Iy$yxEHN{Uwk- zY@cdBYA=wFyO(_)!&pS)9Rt*40W8PsPT1RN;bu|wp@VIm8KxMXD|^fHam#V)Dckm{ zEwkgx%Nwc}G)ws=01tA{=Xv%@6dug05jH~qH+1OWWuy=GP+kN9L(jqRIQ!l(m76lO z=pZH-%zzJZ+`Zs%7#hr;zLKy+aK4_sN((d%PoAdwzy$XBiBjIVyxgX~Nquul9ay82 z%+q@|yCZ}0!?GvjPY6Xk3aVeqD0>i^r&!iuYr_e4qHI%z$zM$AM?pIx-3MB2lOyOZl>v{} zaz{VwU07kr?OfBu|5l$A4}5N{)Y{<8gv@J|U$7umi4+=mxu9;kjO8J6jR{^PCn~MZ zMMX_|P==_D)Y)-F&^FG=R5Zc2q0`KfbBjs9p-7h2<1|c(CTor2kz8s%oofQ#YOHM3 z`oN6EYvEswcf$lMMVvidfX)V_51ahN5ONnm){i7_;JtT@hy1;$TKlC7Fz)v`Xrvwb z?5^Z5f>0$b(`VJTujL)g%rT3wluf_VTqIfs%e#le#T7MJldphD4?C(k%`uvDwpDA# zMy=9h#B`@{r&m9ki!BXl1SnI@5exNs*+4$EOA%jNtAqjaypB8^(RKC6g=C751emq} zZXL=P2J@cu21Jikf_4_QHMcWi=4{Rfdr4Wd<{TyXh$F@%Z9MvVP|r@DM23sbJ;)T) zau%ck4Ffn%(2JDf>>Lg#pekVvXat5RkQu+BA1VgQKPu})s*IJ=fTH%*6WZ#{e5X&sg#>w+7kC=C1?4{kQDf`c zm{)bnhE$mzbS-MKa_KR5O>dK`9{~)ki*^s!qEo#vlShpVJRwa}{DDTLIEG1awoO`X z*8Fr0ol2;mpAer^dbv2oLf~0jUC=!J-Fx_Ci`{IcfH&)4{w8NHD}tvq!#mj=r3hv% zxB=s=enfH#aJZzoy1Vn^!gt!9QmP%KAkbO3=_}$TtIT%XFchYeGB*;DT%G8qsRi9* zLw-ZEp&lku6X6=v)j;uTC-#VSsW#)|XaMF=oi(MwJ$y#b4cXbnlS6s|9os!drp(AJ z*=eUuZL-I7)#UI{fAFpD5k%Pb&&@G%{rO2#P%3L8dh zh=g~j&AWvC9KDc^Alzbv==7MjM5t&BpsvJj?cL<1+b7)=M4Zvaj)y!%du;~Ax&<@} z@LL*l_G&~muv)1kR%1%r{w53CI7N7+^6E@QySoeKh(G_$&slyU67Z6W=F7LqRhXno zu%O~kEBjp=|LcyE4HcaA`%2I&oLD-BSGtDIaW(_6M~cZFNV;{C_o|Korir!iuXcJV zR)UWHg4a;Pbn}{Cn^;l&Qbi6}oR$pe$zV#`Mk0GglytPWi4^+Nzn>Gf<^RRVDq=g( zBO7P__e;47q1?RU$~P>JJdV}*&o{lx8^&fi$g;q%Lo4DNDejuL#})C(1NR7r{8n>N zpW)`rUB5me48EZf*Aso!p-kC#l{H|S%DvYM$!~%P#D73qK~{I{CFD@X!6&b98!Jrm z$1XuN4~L5*B8evp#Ln3XF;Y0;SeiPWgFdndmrpTOH|;<*-O8LdueT8s=a{&ccFkr= zd*f=z2278Q3H<8^kOfhb^MtN$#+U2RM<3Sdbiup7z~>L~OZ!_@2U|J>t>a{lNBy4r z6GuoN+~uU$pe(+T+yo^FARlc^e4hBjW{?uM69(TB1GOysEkXfk)5mQW;RS88gK36cYPro*}AcK z&7v^*SJA^PSo5Ry_e9{MJ@-XjX=&-#eOAsqUr`TNL*_4kN1=pm8 z9p5WJ>JRE6UGH(x*w3e%z^`_)uvi27u;LX|d=}z?M|{*>5e%Dz-M{z+t-^q6{-D~) zmi_JFEWY$LghA_8o-i&uQ*bW(ROsCJ@Q&bDEAZTbBje|Q2s+3&TzTg|)N3SvIu0Lr z`D;Z(-i&8~1$f8@1R1%j_TusX8fK1MCF`q&h#K4E%IP9nzbSL04*s-KylI{AQV&7E z$cft(M|h8r(?vP;gVt5NNs1^%S#YY-*zC@C{AjB5@JP(w)P_ug1=&qjsWCg_@GQ)s zz<_LwSO}TQ(TO1Di87S)w>XG285)ZpI~BxYd@1<3&B$cBHjd(Uip5HKUDG(XAUALR zH>yUVd78Xx`Hk^l!9|0Dr$L@B?N-Oc;{qs=GsRgW_>+|9Pbp|rNmBA8qKu+S3s?%X zy8HS>2HR<~`C$g5QUzLu$D|dnA@qYrI)C9zMP7S15k+(91C~oHhuJDswG@S9(%C6r zk^xxO_cZkJMg`odGzQP|cGASENRQ>@$ZGIKRKzI#N=;cnGgEz0Z|=7(!SS2eqZ;&h zRN@+(a;KK5wc?DY2`#DYt|31vLut8Hj-mc<#B55@MMd}l<-cAa&X=bN)+QMV&3(!# z)K5<*!c2!dNT%2V*iwJzhTuo}yJjrUKr-ivRS)M3M#sq6C5r&eA8a737c#j9h4a*F zhkDhH2vgkMRn13K#m;?iDKuQ+h2tby=HtRP656^xAt(cs&?b@?>l3C@g};kl9C%d3 z*id0dofJJ5<;F(1YAT*Ncae)LJVEaZ>e3p_E7zMOVpEpbynfs9q^NI=^R!byKs;&` z3yi5*b8_9Zel&>n3xvZG>C!8-Thn9IITvFuVqi@ch!3wha*QvHpQLe+#3Wj3urwN0 zL#vvp`J=+57D^AWT}OqO8b6bYuyBVSsV^qFo6{lRUnF3|Z1*!!>de@|8&VFjVE5~z z&{=%5ku9HN%-qC7Qg0$6R9U>xw&$m zOP|w2a-r6Uc}w(hR*sgkR8H9rUaJtHI49Xtj0^}9F@5}XEuK-fX09!P+Ce@refIa< z75moa>*tNDS)It>$j}vLJU|yKc3a#e2d=I?VSIb>SUPFc)^EsQIDp4q6L1%7v z*Bb(2<~269R2!i@#x9+7r~tAo<1*z#WkH1}65eJcjs}u`&?Y7lc?IVg+_CL%&6pJH z*vu-a4&@HQcRLaevI;vEOxAF%2b3+Ns>@`FFx&)-{HxNNnrdGUrN`+&H5!&_AHY_Y zXxWHWicdTnEE^gDRJ|viI`m5osV}EoZgB|X_Y|5FlpGgQG~*nl+M(dmT-`mha6FS; zSmn6^Q_d|-`b@EF1@l4%HrQ)W&20dw^u+2!|Le>{R9YR@tj?z8oDmZC=1N+_5f=lB zW``+BZSR3_HRK6`AfyXd+f@Z-DUeXqf7;B_ksf8-AtaD8c%{S!^F-JJV z$zGZgFcDgbSZ8@sa4`dSSq(LUZeBlA3H*Mk#LsDoR}EqE3XiYVr$}GR!O6|D!`ki( zgUN5YP4PdIDlc-*TVtmxZbC{Cq04i?If(wDs6@61-j9;|xjgW|eKKYO>(G@u{nuQ) z7=VQrm{As^ba(PpB5LQefmDtwn74}du*g>rw_8SsQO+Br7wKx+ zGd+!csB4`5`;X(Widnx!?1+$pEkSlFgqWaE`40O2)gAo>mEBX|G&G2-fh@DKRZRv~ zXP?qohSjEPdJ}SVktW8|ge|fgKFmMsvDHRGZV|5r-2-XmdUQ1i7AXO$@YeD?5Wa(S z2}EX&VJptzzqw0d^j(PY-2!Lzq9a|WbQS=|V5|2BSzXtFh1qPMHQ&SDIx?(b`qUoB zN+zO}{6_W~G9@x%A2#Ul-xw0~sMLZdC>78o$Twt-VW<#Mc^s$_FJ=bl(l=oujx@V! z&*W1v!G;9G4m5`g2tkAz0@1-5UR*2%>>fKSiVWMw0@L~vm59j-WVod=IU+>EvJK}o z!syGpR>ueT`Ve!}a)GOOdMVOYy($hhWXb#~UnJjsvC{WVasxK2a{^Pm=6#5bFjadb zItR9W>5TwaJF2b1bx0cprH%Yw_J0_mI+9jbswW1#$AVW1srx@9$Z+MHxXaSq#8&-7 zleuof9N65ScI1uO9x0yo8A?^Q0n`Q-eIB0zLd|I-Yhj%Ts)j`Fl<}_LxW!)Ry#$Fz z1o5mp>w~VqwkfN)<%Q&_s$4hKeM}Wb+t;XmQmc?y_P={b2f@j>V_{h$Q5P{12jlM=njRA6r$uK zX=zb5C^T9Fkew0oYJ)z`T}b)RB;Hx$2E5x2$tydop-@_s9j@qGN6%GwB4zQ@A;80* zNKbKk8(A&`pqO|mb~JjesNLKr`&tFSe9}rj>CZ3H3Io%j>hE@8cZvECSI2wfQp;1n zE+xlXLDF;8KvsWtYmTJWZ33!BGn$Fi8pF{uo;%Wd0Pos_c149zhT^4uC}6ane9sKT zr0efiWOlYp*S-TF&s>^s9ni;oX@0&kKr1Ss>~Kd}$a!FF?3hs0`Y#RHy_6es&wT$V zdgStjKhu5}JZg~sJvaT&qR0PQwDRu~XyX4iTuIoL`8He`>RC;>u&GvnHzxVy#~yJI z6zo)hW@|;?``O1b7*x4>X~bo;wkp+;_AH=N8O|_t{ew5@MvB1x55viQ*0$5@q?hB= z6(1iRkd-0Ppf+_A!j4X6{Tpm5uoE^ncrD@%!hj|3b6Ev57c!E~d0J$+7}Ka?;!z2? zJ8i`|2V0`V;b~%75=E;@Fmg&yV*6i4MWm3SRUpALWeGgxrtuwTHd%~!9;O87JMY&+ zvkbUmZ@Q2S6Vx|SlvgFS!)Fgh?6h*}!)}LK`pO<>TH0SH_Yq2&3Ml)6>c%F>JN7|j zYSA+y=(`k4gxtWUYW8PHG!ga=MxgV|>#7Q|9!r>5`Z$)*Tn8*|w;5WV(iVS4tCkPO zEEzpfyC;8y9Osc2ZO#`^8;`<&t>3u0(auNg0-{^=%yhtcoZCA#CmTMagI&ttKeixN zKj@-+SK=vyYQ`m;AGhvh_LNU6Q6DfOxh`L|MZBO80P8|{JMy4TzJA)DkUjY~i#%Jd z&!0D@&$gCUh*OKtATV?4{fvKS@)>R9tae~2m@TtY(@I?fLqc1pP;13zOKm`L=fKUi zcgSr%{)s(8G{#El{MI-9`hTkA{^v{O-_aQVp?@rvTbKB@7v#CA|4ut|e|>-lKDQQ- z&y`B_1zgRuTPfC$CP?ys_2J$2!Ce;)p1QoJM z^}bz@i_^HFI-}4UiOolr92hlgBNkU)G!!H)rWD#r>{&-b_TII={p3XW6c?t(upqrs zr4}S_GYDn7e?Ox2K*f>VAv?uY1{WGBm#S&2{2VBk)VUGMw7N8^{xm;gXR>X3sA9Y& zxAV%i3VGoN<6-i$u8!=Q#J6i?+;f$_RQ|A@X(Igv>q{%MbDEn;_3Ia_gH-{S<_lp@ zi~N1tpv)KFh`iAf{PRC?#+~3R-_EK(e(Zcd=Kp`3vC;qdq-bRB@QszC`}ZgP-+dfu zeLFjI8&iHGeLE*(2Vxo9|HAM6l8~#bCKGz=C5e?22$cpng2D9@6PW6!nRAmaC<_8GIHRYtUF_5WgTRd~L<#n>@US zRn~3eWg|fh*sW$b(zssUr&jrCvp0I)tC}H5IvwB1AH**cj#J;>a;>mAU{}p`2%tWT z!}MJHb)H%y?8c7Ft?7GkW0Rl&5{yEEf^op}8}U&sG>x%yvg`A9kJ*}6{W*ijzy#s$K z2?(Epz4}+;i~TxG`knj?`g4$C5N+qr51$5JjWu{|FikEduDh6R&%3S6Rk}~FFQOl3 zH&roM0`RR2L5r;vK}v~aWz7R@ABT25994gbWfgOtsMtv5S)D45WaIsWvRk}y?t zi2beVJ0w0dQI(#SR3}85J+;!Nw&p~}Hpr;HETP$wS(996xSv9VWK-oyeZ*m#gXhnBV%!$Bg~RS z11%`?^3)gS6hb&nRRjD9Mh(+0PG} zjECgEH#(;{Aui62<4I(+hkBqIco5nZ&g=5vhur4dXk^oLNLFlGn1bYRHKJa}VO4Z* z8)(dmp)G)bRTp1(x`PEesC1QE1Wz*jh~Ls#e8Wyhgzv&mH{2MNlS%29%j;0E`$8O+ z;1`US8?sjAY!2EX(?+=A$!I^Kzk3m#hZovm0)KHR` zNJb0pBvRp8LutOBljNRtr`yXsZ@*M4DW0hv4IpLCp;)Agh*9ba$CO-2`mNdY-fxgX z7J)IoMj_IcnjoM5n1W?^2&%R{|4XX;{?Ca?mIKOUhf2hWPKK&}-i}&2_ubu|M79rN zNgm++Zs`~3(L!Tbf{T-Wut8*cVzGg}*KsObu6y1@E|Ye0N*Kpt1(Pj#qAQ|9WpPaC zb$I9==OJ5&iZLhTMowu2%X)8{T46?0#p(!rCG9)ReZll^uCP`|29~wnRd!R}z=NEi z36GzkcjZbgi4Wmvv%?vrW@G=`HNhhbdM8{r*J8`e9xPIMY3mEUk8|F_!d-j6ia z>mRtx*YLQk*WkD;*XX#*H$nb5ZgahgZfm_vZgDNi!sW&qA3fsuGj(BVs4Mlo`)@^9 zc@^`{;wLs#xdPQF%M1Hc`OZ-LdR!mKqbS2cTvr_>tg#LS>lj<_-jK_qddDTbm+)l#j2a><~7(YozQL#3ZrN z_LUU4zLIO+EQ>b5$#d;l;${T<6kL1DIX|RPJQ(jjDCJ3+g|Jv6 zVsp0YRbYOG%Ff&ow&~v9TT#!XJ}~DYW%3YV&IC*HoPuhF*i5g0TJgg%?;S9xFT60C zTdWRefNAia-Zq)*Uql76w~$mdHNRnfz)?pc z)(H6mRkP7)z+2mKMp$PK0xr@-%z*J|I6p+Ka21h|J&3`KvqCqp8x;smc(-UPG;hc!ftj} zwhqQd|3QRlQk1s+M?$q;^g>^wAs|QqVuAl#VU9BlsZqc}0A2(ELON_svB|kPoN67b zI$Pl;bEmgh7@ysKPn2Lt{6$WY7XMo<)nV(hmAU!ydNE-7<4I0tuL3m0l7d=zX~qtR zjqs`@g!xu{Lt>A0Knp)E^6CYTF4+DYv;%mha6BbM0PiJHP7oQz}<<2Qhap%bFM3c2Vh%Ta z2ok2JgohI;bmp4zF?n9vV0}yn`H5Peg;VM1%qN}$hC@%16|8qa0gen>Z{$fi?#Q;>o9~GQZ_xU?1NE?I7t~a~0Bbx$N+d1;?i<{BqnJ2$k=spj z2FXeh)DyOm;_W>`z$-fnloD}2b<7e~D|deaX2!kbO!q%6dva$i*oeO&gi!w%Q0_n1 z>i_(t^{>=UP?}#@@&7E<|LPb4JR!W479XxTp1RV-N$IH4=>-vguO^7&|6)k14WWj| z|Aq9MHC3OH70Sp-tyB08Gnk1i;t&92V(& zi-32xluLh4ftE|Mck~>b9pSrrEy)E9@O6Ar<^Hk^>DE8i{O-XChL+3vN$26*2JeLQ z2TK_C_Xo3xuL%7_3*TsDN*W9vnl#GE>Yr3vQz)`$%Fe`qhN%sgs=?uA8K(t>BxBRw zz#f!iMdQ#qaM;$P4Y6ZLic~z`Q(}mU-0ge;&tYQ}k3#$gd{0ZW34(AJ$3@O=U=Ii* z#Ks&Jq-E~6vPWm`x3O<(Tu!ExPA!*ODnDAODnAkHEB=4GhM(VvMiZH zyi!D6P-BHuDe7`be>Q}#y0pqo)XA)KOAi~~;%w`@mpVr;tCQvSSicn)ZcDbvh+Vj0x*vtI#_FR@Q%^)lWhLun>w3q8=6ymuc|A=j`zv?{k%%Fs=AvliK} zuYHr_x4e8K)qc)vc7`lX0j#qop=5(ET0yPgcY9&ZuUN6X9M2Zr9WGqlL@Mh5%(|3( zXKo)LG&G0pr)NUSs!$lK#K9+kFspqXj?O@f)gEGI>jEjQpjh>z=+ADu)^?tq=;uJ7 zU)7}W*TIw;+`F}OQE^HbR=Qhzl@QFYON2!eP|Zy(Zf+)lUqA5ziu<+~PWjQ5)Rncn z^`_n(sZ3OqCu(XaZOLYU7oD0 zN#|>+$oDT%)rhW)$yJz_(_!c_(N`9>=8#tJ=fV#l;?&aYE;I2__I`QKXm5jIUg1S0 zVB%C$SL7|Uv3bdAZ*xQ?f{t=oPMxl_%niKWlfS5 zslgNfcRoTO=eJ>PQ<;tmlh+`jEHQdUn4a}bBdsklD)Gy};o!g`Z@50F^{%$^#a$53 zV0VO`Cw_q56WH1s5$O2foJ7!|h;Jnw{1V6Z_rNI#a8645?{Ur??3xF#_v(ac4C&YS z?htT$KI|LM6PpB09!pEY4e7I&n*MmbO#A%C9L>8x8mKi?0%G)N;X0pohjzI_hQ!At zoPwrob4b?3=2*en>YJC$45CKO-C6bdJ-BD?`~r{M(&8l~h?iwVRqE=CZWO9ASgb*h zF0C1n6cJfVtYsZrJ74!dW(P<1r8$&Mcysqcf{ zH&{6r!5QH6Z)fA7n}yZ9NS-1wKL~Q!6okg)7v)Ofp4EKMle<|l31)4C>=qMq;zX$L zLqD9v-0|U~gy`s~a?<}|uJKP+>YrD;vq(~XbA5hGA0}jE_*C8@>h%02Ucw_|8bPml z3>GWx>V|Aa8ie3o{kw<-ZcNsV;8-#2Tx}VtqkbIZ$`eBVsK!Be%qI2D9m_`?eEazY z<&s0+?FAFx`IWfdbM*CAM+P8KO{AN%L*`14PxUP-#&#Dvl0PqO7@p#hI%wp5JT8r& zxUBQE``&%_7e~n9hVIgdciLwGs#fO@j}b zL;4H!k~XBba0pN1PBwvjKaXe4aB+VydLyx>B9i5jCxqP9JN;0#Ba0M~4uww7;kmNtGrh z4fBw8ST6PoQ92=T#;!uc3#cL}H$n*mWa2J}yPCJ2MJR7fA2Yhyu4r9Gn9=o_hh`8x z-CFJTegGQdjzZAFmI%^IxiXOEB5HxV zKYdCwV;Qe-Ew}AO65ionkSbtKEsm|?JpL(ak}E{;%up2eL#(!vCkegiVGDD2?9+NV zw@oru|LaYJnQF(<;sH#cySArpa~^SkF&vbe#(EOBynrG{t}E8dnLWc*Q@qDKM9Eyn z^Ed|aJ=zk6e)ZT2Jj4jux|G1MYeNz?14jk38ltMid??I{cZ zcaHdEGrp-+zFx0rct&*ToK`=-Dcg~bMGo?BmimAz{+l`sjIZqT@>@lAg_A-C&OSVr zXzPnzlbEAal~d0Ikm7xmljwwj1hKuy?eQxlZmQhs%xZa1c<#FRy9D*&$`x}!nxM0Cz6Hi|lRp06Q_{A!?8hr}z zhEVyJX#e}~IILMZA8F_EMSqOf4)x+)qDI!9wrkHhfpTJ!7Hul+Tdv@BrdB3)tUg*z zpo=wman<$krQ{w4&T`uzN5m)hGG+TDuBn!#Dju;t{ZwK%I3Q8*{8Pb@@ZF>+u>Wx_QxXrw=*Go&yYTFdNG=_Ezz{;Y%rWJv+pr9X=<^#9zYH$i8or zr0WtG-lahg`(V&7V({)A?N1O}%WJrPRNewo6NY9Ts|7nknK?TW917O3Xx1BG>38^X z7W?97g#Pm{gX0O}4>cs!aA{1he)3=RWxGE@V0RrcO%N+uQT~v?`4GNqho7-{h38)! zFI@w9!RwEW7HebL44kn%htvpfH2!N=!M7WEn5XMbCmT+&V8ApWF~coF_Jd;-w>yl^%ngqXE}n5$R=n@p z{c=4hlcf{v>bv{>MV~$DrGYdZ_QrBUjW!*AgkbWXN@%n70g~w^k3Mf za^ai&31A#|QG;Rsnb9GIL4Tu<8#d&4*yuzJ3_x2fpPrCdG0(jb{+eRa^7amUezI+A zw635+zm9AqnUbXo^5Fv;s|t5CG7?#a+oxl)3nhtCRu zR3bhLxvJr2oveKT^N$7u61pA{)fSFE zmhL#_AP-M|&CJziJI0RM)S)xHlH&G~VUL$eDI_Mw$mEMKpZ>DOSm~HjQJ>UF&GtqG zA1s-L#kwq(2=gjPq35%>!K7c6I~{37OlCm#={;tig1j#pqY`Mgf7hjUo*dvg&UxM!v!6Lb!Z3uOm6qU@sn?`9S3^j_{ySC;W zF)IbjscOGyb~Lflcg^8KKXQI#{roe4<#$cR4x@Dq=9akA^5b_eUik+Z7S@q%fip0w6E&fl7n!|7%Ssw5t=9s28+cq8WC$2i%fYkbms#3^=R+JC=I4l zBSUUsTSt8A^>UGHlZ6wJZ2bjbr%sNJ6_B=Nap0eBiU zbKZm3;V0N0v!ol`AAY#9mbAo5%cC6f%ORitYL4OcK)R9LNW~u9CxpNWEm;YFGGO1B? zR>NTx4WOFU--cTPXzOt$NCklIg1bLMp5_<--Cg~@UUv}<#8rt0>uV&!nuaI|mf$jj z)B+I?e5kR)>tmY$KFElW{KklOBo{UE+n_B}5V&1?0+h|w;CqlWc=d@MtxUv9|QwPrV3r>yH=1o_*9Mo-%lI|a;N zNSyylUDq$YOVf-vSfXzK*=rtj2Nw?D3t(=A#J=`yuV>5mvl54}FT@_t$1ELStoi|` zB7mgAPo*M=ZraP41%YM=qvhW~+_HWkY)#+R)pzg+nz)W7Wn=rFH~dG<=UCB(_z;m& z+PgV*3x(T3HQoTxjS=?KLo5tY^lM(Ka0W78B3Rd)gLcX`n|Q4jiJEodWh4(fZ_XQx znKv9QTjH8GJ=PjOraFkJeiL@Aj~x>A+kMK>3*!VbDruWPNm;@W45q^Uk~i2$MS;s80iNox@6kRIYn3_9YVr zX^h^9h-*dyxtT@xTSgc1Y#f2C6c>((3tO35UQ$wHuN%bGPo!8e{-Yi~g~in}@vOsy zFIj(G%C+gkCYH=V>kZ#dR8DP;w)x^bW0sFH+0sK2qcf!jDA<*^j4)-0q?L%7vz_Eg z))mCt$)_8$`8`d5%a+?a@P{w9pxWU2ce?0ne!xmh>|u+L`E#3qN1#Os=G+Wqv}zoRTz|fv0dh zK?{O5gw%B)$tF#sq)prFo;lo$EXrlo1DdQOVRE(}xrHhihu>YiVk%Iog=n$(2Jtdy z3rKt;egg#M5+H;>T~X9ip=W`lyjWS5hHxH|zA4vGffS(~PTRp)(#jkSl=|VfCKes# zWxCd^xg%w|Mx9zbF~+93Gv}1!G(i0kf|O;Bqvu?5;wr_)_XZDbuMQW#fH>iLQQuni zrWXS_A=LLiC9&F!6T&`!kCQe+y@#Y~S<@3vb|YrZHnBKOIbLLv4aAj{KrM=@+b@&W z>w4tCULVn+pF^d%WXfp%5X7pz^4q&$%?+!`?(3DhJy6j83~ck)O_ zk!^x*a?T&5Sf&I}59N?8V+xwRKjBb<0Gyr;MY7a77A=zOEYV@AFJIEBYsm8pHnhek5g&nD;t%)g{+Y^7G zU&Bh+?SvXrFu(^-F2=^?MmRQAJH57lMu0=;C{}Ko$a41Pp^|nSw_YBp4)v%{X!A23 zPE+8J%&3pIu=myl#i2=3;r4*tAoo)_rLa3Mo zUYdqa8m>?$C53zxVZNszPrDQeS*NTNp(&iaLQ?@?G6-?gSqNhrq`tvA^^{zQcminM zRF^6KUZ7Nw|5FqJ3ZVE)g*2!xk*-$799BFgU>`F_IHeq5&{nVEmYf@gGWJoR?k-oQ z^cbOXXpA8DNxG(_9JHV{TN8s^xky+iLW5wrh+&Z3E~l0E3J5;+$gj{G6h7A_ryBLg zsSPe@X5%05h!8Z9J1FU!oROYg*N+fr?sa636uB@UlS;X(A6%!`3QfwLxtJK@pa)+n z7gv*{I>t@<+R+L)W=*22jVb65x~DAN;pR@<)9*=;KAM?ol@ad;4Pf5824m07Gupe; zZ1u}S-g`W2jU$Xz+Pe|qjx0!F-n$2B4aSOu$K9t3(4h{H4Cj_&I3d zc3Eo1IxNfr(i99M%* z9+O7lN$iT!hLDT>pbt1;QlXu|3U*vMewf(RWvEqAfCD#7vzO3@1YrZHoH#^%&jp>* zCBCo+NkSM*DZFEcx-JvCkH-$>!5YPLV#gf2m~;`8ub@EBf3h{=*AEKjc0|o0@*;(b zISF`keBbpY_oC)wjFSF*vDZoDk#)xW?Cgml8?^=tB#ip|0N_)_+LQ$s30kJZr2Y+i z$i!!6Vw3)MSjgw{culPy9sQ>UJX$R+G4-3LzwM%l>w4pv5Zk74MTP!5kua?}JCa=b z1j?zd3A;wWsA;n4)AL6UAZqaEyGoE)+ZByPE!f`kuzb=WR3#iGy|JG9Vo@O3ONx^! zD2i2ziTnDx-EL(@_WcIpf6JUuf=D1`S1`?LR&Z8N37PIu+Lk+e|IB~o#ABveEC)Rd zX@oP5lW|U-$2<>`4qD=1?iRl#JU$$A!PRd{=TgP!Vz!66st^-7!w{*b;%%t`WC3u$66CDjs7=uT35pi{8>pL;zLtHhPg zTl&^mGtnPWS$d<6g1i*EA*(cXl2Zbk(YgQO71QwB7E3v(oY$eS4hv=ZiNPyzJuci* zLD6{#dcBo$Md*5x)9T*s#GrBmWYdlc;D0&WX=d%J0V$`l>nBnKQCyNS?*%TLb9*}J_e!i>|@!N!O zZJR$g#}7wFHLI=9 z$Fct?jTr8wflUzhjG|skl%vZDAlbuEBghGkbBoD(zOxH=gQ!8KOGNSo!A0ru8y>8* zlj{Vf3)k(x0-RmPxcz^Won=rZ(UzsFaCdiicc*Z7F7EEGg%$2lxKp^hySqDF+$r4M zhWEOAqNii##k`38aU&!D-IIHteR8e!feI8n6z?vVL~I$PKk+9=a5@Tb$5;>WKIJ^I zcF}I46MfKxgms4l_qA{bAp2+q(7se8n3)hDE z#qGT-k79hPi7V<7b#eTO2*G7g$aUevUmLL`i&w!SeML!xb2vs?izrzn|EptZDi1hI zybc)|TZr5;N?p$oc4;&c6>!2sqpi&%qII-ouVSunM$Q`LI5qV=qN84vQ<~faAjt)l zxn5V<#XEIJfH5WC;1M$>(iEKFI->CAwc=ioN4HT>-G<7xFqSEnZsw%Ow#l7;1ElqN zEnL^p%Y_sy9oU5`11J6UcLY{Q9f5h(TPXeH6q^vjuC0%$eaxx)m}s=J$|yPFQb96k z@J%$MHF8q^m`QA-9?erA^UMT)XT?Nf zXKDL39I311y4VYYete9o*4*SAwT!CQUKz$sYL z$^qRXC23qVRhuW&c=yGIfplpT^>7P=a8Qg(kf?he-IbJ=GUxJM6WJV|GTZ>X7W`@X zq;pvhgQR0|x-&qNd%uX%)-HUq7VFNAaVfQ$;-+jad zS70H7QyK$|wT--b>0;7_(~#zBoeO8TPQj_CPZMoM%KZIU6D{vhZ5tj?71XrCh;_g`Xm?&Wg5e1WpGSt)@^xH45=f$mHdfdhC&1c z>f3Gh1KFnpWyDKr_^VnL!Y*ZuoIE??t!S0n+-lADlwgNY6Wy~MJEGLjGT zJM3s4)I!)-luvMs`Lo}z2s&a@R0#ccpINJl1t7h_yZdQN7-7$^`0R4J{JFj%?24Z_ z?_&M!A)LWxkQVET6)fnosoN*$h|j^hfx6s_HMwEM)$b!jO@xwr%30v%wboGOgl2I` z$bl%$fLoNl>_IA)DGORz(EO3>a!=E*VAD6*b{HXTrD7DYoNmP%fsV;pa{x@mi8)0$ zG1R2MgDTSVL*xE8ZoJwjxeyE@uZT^XIqG@eD!0kt#6E4snpGmPb zt7DPj_B9)vC8{OdZQyi2R5iqxWE%bLR%>tFoQlYxn7@9zXL>u$LV&%7$z71IzJ;in zs~I-i_P6H3)+nl=y2G~8s}3vXWC34%!nK`8mpsh!YyRWiP2OVwpcPR$@s&9AL?sE* zpx}lGjS8{%7zQX7wpn07)k2O>Gs~5K%=E!GSE65uR5bo;N8vOOa=BDy8ItxoN9-R}<$xF;~mT zHIsqUY*_<=oruP@z#I>j70@jSqsLDJ&M8#)leJ|*dt`bYX0MbX|AEc5SV{;1j)O`v z*eD@DlLEZnffJiL$Rv+Zx|iRhTBw(J5B8wWcw-cs|H7oDAjpoS{n||$F;881)Hp(Z zzM4$#iwjb;;X?a3Q@JkF>_n)l!XLVNe*)^*tZcD4rkYS>N+CDC56iwaW|L6#Dl6jf z+s#0PNrAr)LJ}lG#f+L9Ba~b^n{?~EW?zz|qkc&n>d_rG(UJT4eh!9jD-`{=LW^iq zkpPIit00^*VKCplxr<=z+&iE6<1N(eeUOv_Lu&;7O~xw`R`}z%3my2>Z?-z}RCC25 zp+ZaOhtxaov0kFZQx}j0d?sK=C1wnpqo&D((>iwqv8il-J2TFmrj>p670F;$!u%si z!WHuyPniIu+r8(An*J}PlSt7!Skb%j0=;gcz>*R?X`cGg&!aXeIP$4lrrX$B1MK7JXJjeR5dC?nU22W}cI0o)O^`5fdt(F+wy%@uW2=q@VwJ z6{l128|ASDFEJmTc^~GSF?h5tGg8q>ISTUEXSAz=>)RbqMh&;_!7i}k%!aS5ka zs&~$C#98G$6|87h zeg-lATX&bci2=Dnr}^6o8;To)GODg+n{AvZRqUS6im_o|8s!9cHCq8LZ^ z-p)w5@FN*0o=h>a1>mYci@2`F8KRyF`e`1Za{qPn4~-`B?>U75xA|s}7fo05cr}|QUT()%E@Au8y zddaJot_E~TGW2gVZcqqqY2qzq2xEHG|2tp6{HZ1_rWkq)(J z?Sb6vZRp%H;rQ)W>t7juZuiQZwznSU@&nJ>5ZN!GIetR#Gg?bJ& z#=v(k;(HLgUHP>$96Cgpq4|5yjc~+L6?gcrxu3%TFl7dqG6zgS9!)_RJ>8oku*m+R zpz~%-@u^U(G46~H0j=SZ5l4L&h6n;O1M``d-w z&xU-ln^a^@_WqLi`tzUIw0-?MHZH1f-T-o-H9F;y;NXg6{1 zjWzcRXTF|IMU#uVhJ2!YqddVUT1-t%O|)^F>U1~1;CFtU@P561ru_xNVT2_l4zJ0+ zzfglD0oQDVB_)q!xJ zfUUunnGBt9{%|U;Rhzfy`3o2>JB@GGeOG8N;A$e_%8#^WJFL8jMSu{F9zIHl<&~BV z_HoPEq#*U)TfHkySyCpbzB8A97|bfI{LWf8P~%Avt=JV^Utumeo36%-^nN%VQ}O`7 z$gMPwOwDg65?789k)cRp`6i4afrtu92Aq*Y$>R);WP3%?6uTh}nr{te(6B3tRAkr^ zqxzR7Jiiyxv|@T4}5un_^K7MVkwAn6XB5$$R3qL8moWD(toZ9!LCQOg1C znKCXlcM{c7DGNMy((d;ghc@5euPoXRs=XUg~IKStWgFN z-lbL`eR9pU2xqbZ+Y^Ilm-IEHQNI}mm#RxW{4#+en&5z%vi zGKYc`@a`}F9wgKpx`KV-mykE$EB)pF?dLQ2ci)hI0HXgZulB!t`~Jhb^&dvQ|NZ{_ zht9WC?br!b0_j6s%Tma(?_AO!?>CW&Go3nKO;9wVtSWOzUk(kZ-%xot->8)uFw0e# zfQT`kaL4?qkf!A78y^Uw$ZS3Bejuq)Z6&?!Bi_aqCoBKP>)Szs`L`*fzk-?PKYE7>L2PuInCOM7k)F7Es}UW0HZr>DL(nhSMFYM#NT(k=qFR z4<+WG9hXkky`Yw>o$@l(BfocgI|v)_Hg_%}9CW%j9sqwETJ>7DpYZ9|ZWO8tt22w> zg37Zj2_i}l6d~6aIY|`80egT*G2n%V(Q2$JYe(8jc+MD82l9*I5xciDuA{a4;RVBl zDkW4m6D`mFFEb8o>1I+f6;Y9pcu866gHtSWHc`Kw^7ZQ$D{gC!{T*r3A4RNPTIfPD zRO%BIP>UCUauCDV;m~)+m}N#=FuqA@8j5>>~3&Cto9d(OQh;)3uyG z0?UT6RiHwys0CQ7QTkU5(Cn+MC!8js-I@A%&>crRPvf9OK)IQNq;&9Cyx&Qpp3(X{ z&&w;}V6}0T;Svb3W#9yD4UuLGt7oDM$Lb$l4@zn2K}=a*BJn2-Kyhpk+O1yt0O8Jn zex8VpyVbA~wh2bRKxOe9Y3}&J+5TdA?N8$NL?0OIQWMuW?K6_k%Oduv!M~WO83I3% zB^>Dp7(|0(FV{&(xZe}DJ?AHH7MuV(55_=l(WpJm~{ z+j~1zv=zSi#2-Z)Zl>B`WghhOFsqScBv|@vIJv~c)HmO3clR3b*NEF$C*7JO{Kirx z!_uEX-;{<}JNYf3XORdwUbEKRr_!9KV*luOgL*{CK_XnNYB(bGpTL$$5F0H$pjtUR! z>G3`Uk^~Ws>#QNN1s^6d0x8lVj94gx(uJz#HBGKEOcQ`Ylxos$;sBA&E6Ie?6N<-^ zkmUWiIT+r$;Tny_OHsvBH?bO1}zI z?h-o_6dzo!mQ-#y__kb&ch@I-2u~*@`Zo05O>~!Fq^a6;Ty&~9Ziue`ML$U0RXfB| zXQ(3jo{e66X$T_liP2uZ+^WruziRcucQ333>jX3FXC^H-#C0AJNcri6+<@hCA;vcM z4$FW#?lOjerR=hg%_`aU9)%6}zIQk4J=*p|vae_j^5#IL=7w`%6HU4}>`xB~F*8y; zWsP85WG)LEMo(SM3JQh>0(bH-`Wz!-*lkP1Y0tNf9yw{F8G2#IzUDamLLaHRYlS4i zej4xILM{P$WimM|ZR{C6Qv6mq3l$BV8J7K`c;NhKg!%6SNE7C=&8ID5#CgN0?CL17 zpM7ZW%kfi;|7dZ54@w*1uNEixFI$|%zq_>mPp=A@ilw=&;eTeFDQo`&tNlUIY}>Tv zb;91nuC_t8+Sqg=qDmzdENl}bDfGeyj2TTlvs>8!y9QGF`6C9bLcWqwSL5SNH)V|_MG_9n!$3n? zPFzepjf7~ju>%)3i6XLFu!2svcGJzOuY1~B?nXA5KZBFA zg)wQvokhwkx~?w-4ys@^kYhx$GQA`qTaCj{md28?2rMb;=_vDTlk|6H_wZE7I} z*sA#L(%IZ1a56>6z;S+P#y&;cS9Pl2cFQD#yv>4s?hEc*^hnyw`S zM=Rk=-QQBSVCB?o2e4X08+LgAG@u0)4-XAOXJ0HvAWH6Vdpv4Dux}DOAntF_983O0 zprZQx)yxS44vx{Bku3v7?aWlEPF;u|GxHs1n+%?{pXpp`Q9b<%>Np>Zlv{pDWdMo1 zHFFIza#Q*U(TyoXfiXtFD<*t8jF0G@H19Rc#}mb{U9kJ;#w*NEY!|e_UAF<6$2{lz z+1JQI4)*{<-4qCSOyMQh-6FHzgLh5#yBAG4Q7kHT2s)=ct6&UEK8}F2l!h;wEvu~0 znhbk%XWh%f3+szb89D&%I=JZq9i^v1$PvK0;S4b>RYpN(xQiA4AKNkqP+M-nuQhx8 zFRk-t|L&Uo|0u`*_e$ItFY^yy;P7Wgs2rY%4Ag-fY$C)~j+OcnL0c zv(X=QZCX6GcZo&V6;$GwYxp6Kf>q}_OiCIan;>1zPvQ(Tj-|*q4@VVEAic2?if8AE zVr)QJ>>*O94#rX;5-A)5fH+w)CWJtuVF|@r4n3u^v{UO`cu*&Q{FoBBx0Cpq;FM zBInu6GtfcI*?vzFaCz(wcb;kC*(A53FAk9)_wMj|Xs8@vilX!N$}mQ{fR;s@1#8FW z*8Ci2Gd~!!x>AiG9|>Ilc3%0EHMeu&dJ}J5V}rb%37*UIz};wpi(`6xl&KmhsTIoNdG&?M#v|{_5G;k%%;v6;N%&)$| z9#m{Hh3LKPY~~Z{C1{MNS&UST@>7a20`xge_%$c`H7_7)!}r)Ww$OAuA_x0?6WSo{ zN%-wcN97ZixbDrbum-e$>F5*vcUPResf~%Llborc z$$!Q+{6~qbRI_%_mO%e_kY2jgN=6-*ltL>;EFlRkq39)R3f~*@Oyy$aMZ`IpwLTW_ z3U?`#UJjqLo~ojr55>>CXY=8nso!W zRaJ$?=_+hBBiU~5KAnB(Z9bj7IR5GT!TYW4$^%LYtLwhR$NRl{35=Vcpidb~NLmxP zZ(=-l7^X8hz6edNsmw!DXk14fRP%Mte8wbAHQw84sH&J`9fK$TBH!(be$Zkg|HOPS zEaiW-JtPO}72-}v0IU=F0SCioPXz=F*JO2y8_wO`f0j16CZ8Q{zav<8QaWGl) z@ib`0@F#_%tQn&w|4`Ya!hnAO&@y`I|1s5`;`wfGW$~=%hAYjjl4H73H+h~g=vZI3 zhQ;V$*6ToRjrM?pF7x#XyPDMy0KSBnLh~G@#8HQ8MxjlEaqL!P!G&7RQdnnq$SxF#o;za90YJL%CvF#?aw9R;3WD6m8nhPah!Ls5+m&wyp06^ zkV`gFv8q^7$FG;=Y^W6~}-HmH}~NuTag`GH~Z zf!kV#FN=2=y;(vbix2zk;bSw#JEO8JtM&BSv1-Lf(V$j8J*fFgpi|@MhCtYJuC+OSSpw% zk0f|4mt`NHlJO-a>zSubWoJ3JSLjbT_(@~;2erfA*I!qnI51yrlOuB!CR*_3b28M^ ztI%%9!m=)&ol`U3^_BNxP8wRWQmB4n+^i&rT%5u-o&8Y@5ZQ}Ua~_|MR2D5li{&QZ z?5a>5BVUm$*BrxJBP$`zF>acWEJv9*h6B7CFH#uxY0)1B2H7o>3Ff%PZ8Na552EcV0$j?Vh@qdAXs=CKM6E=qkd$;xK=wup74WEJ2V z$ya(%q5oZ;MjXUiQ|ZX7y5E(R^blDyBW2uZk-r;nUpFCT(*>3S{@FBooiU-*w(71x z_*~0*9KTfaxz_lNigfmM3VXDp(I^>Kd`Wc~2;UonyPkmyzWoAVQ?wmuretRmJROVC zhLT(F2)LB2I7qj))bPeLELdEzyMeKfjL!k17 z$d$J?;QW>Q22tmIPZN_!;m5a$XX{s{q7 zPnso1k9_p^OCnhyj$%BVwPfov@v>Zo2Jr(j1UvfUkk54wo)A?ow&}qjk16Zi70K6? zSHn(TsKZDC)80f{+3|bDTIYfWNw`2qRwa^6-fMsi&_C9Z9bL~Zhs9xqUD`2_U~ zFi(|sktyWNQ`mO_FnlbnfjoqIMYZTFZarsZdnPj!h$Menr|TPqFqsQZRL*j!6XF6A zWoC-CTn+`1E~9*)K>I!O1PRK#P4Gt$)M~Y z0A0wl-jorwAipZTW6L|8%eHKI@R*mfmxqx%E;#ds-eSYJdrH`Pcm(6y=+$6)M*qsm z0B@zj6wbbIpqprY5GBG8m`Q>f?9&Ct)f+lqj9Hrp+UQ$K3Fv6yR-DpT91jK#TS@!< zPVUdP<1cc)e-Py=QW3e777YD`g5t~ZY}`<)@}9EQ*Vm4^GbQ>2vdZRRhIBfsPSyea z4zkMc0TZc4b|;#E;~fW`JfkkV$A2_{x!7u=9T-$)LI&@@tpF_|&zS~rx%l+Vv_pEs7-C+fIb*fQSyD6k&bfSa zr&hJEGF9FP5jfVXV}H`P6&fS6V_sTbyGR%-fqxm|P}pd`_dCrLibu$(f;c7g?Pp0# zwph}sWqXruNM(|<-1F1iZ<)}5Zke9wn*d)4jGhGMKgicZ2$^#A&HD6rb>E3Ob|tV3 zKb5BN`)EgYhN*Tbxq3g)d?Q$&us@aF@$`*9UEe?$chzn52Tk8_?6)}wTBB&6Dm8+} zjj(+g)%Mt#e=QHHy(vX)!`DLkVeCCcj_g(EMR5)qpZyuo-nD$w<%{%-fPG5wAW$EG z6%LCOMokHlc#C;I%?po}{b7wkTqzgSm>OnVIPT z>5stO6||hCSJ+&?aMC==N`E~10QNQF*?|rgV+3YREU!y8|H@MB1;vstKzKOJ^@kK> z8t#pAsvsfz<@b+&CJi*SqF_@%efvg>{I3ou|Nq%B|2=R_^q=8lmiBgrHvh-&WKvDj z84ZBNp9M6>5fP?fp{omHNdpTZ2a{YO5h3~wUuOUnmL+9A$28A+clYB58$-vFT`8iL zmIelfX_B(EGQ(gwpd}eGSs}T*??#I6QCP=@{*<@KP{ac+a7WOGcg^1l(;Mm zEonOSEY|nT+vzvGUb_KL=5%y9hHtFDIszn56xEL$re}c05^d;I)Zj7*hm(1gX%At^ z^v7rFYIqlC=jW>1+=8Z5SEda*@+#X~#;GBl3jUm%8*F{Uy>DQgiw{^uo9biHr%S&% zvJWJE6a*?wCD_K1e9UL86|lv?b@@GM6Bb~!eo8A8-L~S9N*=O#S$VPO*FaI!w2i5%qM!9$5? zbvx$IkRTr`h)3^K=-$T|%PIq{ zsOwXXTySh`EXvH^oqxAGSv)3|VU0}iq@|pz3VWr>TBf8Ntn1B8o*bLIlEvZ%?|v6t zQU9}K1%O37lu^^VWEp_gXdEeQ)f^aWr0(pYmLtet36GaD@EM@O;S;WeUN&1a2A9A<3BLA%1zb0Uli@6 z8U2QLXNhBTT{AL^M(n2RC~l_jbs63;EJUpX4b5}LnbZWv>D z82lm7n}O7y+p2Ee3%7T`>C-moFl$lfN(q8hoTeBkNSf8uN7>XSpVBIy!tD~&sK~NWK(adw9aux}&%4;Rje-etv7G-kP7gt^WGbU^6&N6pGbdsnMrj}xnEkcHz;?e;- zL(TjopYXAhC&s^I~=VwrRL>$#V8M^Xt*` zr@g}kXwek~&owc^9x2|}*?FI>)bST*X9R%1(odw_YR)*V@&oL24)3s4fXEU7b&op! z#_$_tYrlx#aB98}*?Lc_NQ3v^_%Zb*!owF*7#=xI7N-?Ophp-7OYh=6s|p>8u~ zpZ*Hpapy<;>4nF{zmRY@+!2Iv2bsZtG}Z-WuwfIsl9mk+r!9hbd1l9N5FGU(Uo3)= z_qu$iB6w0A3$wnixPT=|>tE>maml~ehWS$*GO2urOqfjRWoJ4@Sd~rwklqlvBS=}N zrer?xj{a%E&W8B-XNKmy@12trbo}mhV^JHF~o*C=o;Rs_Q!PR6^EPV@r6@@!xC#%xnSYZKb@F;AJFXRoMp+v#Z z_ba5y?3n;KW8RP`f2JuT#Q_``V?ly_T?At+Qo{wJ6Y54IPbk-HryswL`mhFJ4Hrl$ z47dHV3xme+FCZw)j>&TmKEC)f1gOo8z6$Qkv(YAmgU)DNElhF?t-j;O?(ibQWXY}V zsT{~mNTqxE)Y+SOEezRgzrI>{daCxbU^nnAIoK1U zAbdLOZ$zAjZ9WaxPajF;|3NQw3{y~M*C5odrD1j!a0eKzZ|b$TI`3}!_RL3G_#q)W z`+#|?{neDcllI0}-ld30e-aDSLBW;7)z8`G@HQ6K3H_8eBE=z7)9j&womnQ4*dG`I zkfoD2(e&CoVmCG;W1+stfuROZb|XAb1<>if-adNl(M0TpvnReq%+N^h$yq~r8EJM5 zbw}KIu(gE1AeO$3mOmpc>pgtyKoHzCn6xK}YOX;RhBwtBrxT4UGrEC*?rx8E;TOk^uHcKmjG{ zgy>Cq9L8mLdzofyu zLme~96%wO6w^IFGN6)~Y zKDl8L(uFP8n5yVIFC3$kic|NriM!Tw*YLQn7{gciQtt$e#^BCR{)wNGEPg|feC<)V z8b$Ab^&3fiqg&&GQhzjX?h^WAlbfv< zzCGJCv6qP#mdUV@5fO==ECLgrld#YuBX5GoXv$cd9Q1m83^rRAo zrJBQ7MU#e&Ali+J2}D#Kx@HF@jkuXXHW%%7c59DLWFgKy&c5CH%)b5H`s6zjcziG( z{zfP-PI20x5eoy+Hw1?Z%$`;uf3ycqVeNWlB_~in=eyd+tNRxD&|7w zRn5K0?k|>x&v8ih)S^%2hHW{xX!{S%v53&~m6k?BF4Mx$glpoPKJEEYkD=@_=fTn+ zIr*$<5lf-NeQ}260`YkGaujp-`G#IknJ@dP__)!!LWZNF?}~J$VrMU#`v|lIm!n;^ z%CHJKHW*hG5#&a0kv*P`=jZc@Yss=v+NC8)VH&pmY9<5H?91>-y4p@*f29lFE++n} z(KZryu*=JPnzNw9AO@*0KW7@Zo$X+~&#};ITl`As+LN@0wuqy{^PicJGpzU^yc}3@ zocJ0AblE4fI!8772%v^p)$F;Ft?Y=?13om^kegVkK~|VEh$gWD;p}MHr#Xb!(z<+D zbRw*hh%-{N*1wK&i|m4B41XuuQ+e_=gQ+boP0I2_@(k%i`q60(6Vd9ZoU-PFoEB5F zCWJ+g!!=aCMBeU8Mev=$r?pIiV5wTI*qz0IHNt2or?T^ie_P|Yd2fn_Z}1q2STnR+ z!-*_2-E{D_;aW$Rad2IgcWPXbz0erLi6v)^QrMH#%@JcMO-v$!8ml`yP_JwpVY74{gBR`h(tu*S6;|S4$r3^n zB1_MhnD9@sSz1T|Pj#`~R*1h9N!V9`kIS(PP{pPMYo!hY7e+)ekThGlo1{Yh;SSy; z_%h218!Z$GiX~}ZY?GTRt7A@mKbC|D4Qr!1=jW|it`u9uSXM;ua|{vu9r?omV2adL zBRi7J@XCc2YIs4V>d0QXid{);DC+DBs#iMudhVY5df}c;CS_>#DU?xoPnn8QvzvGY zGdQ1@xJv;iS;Bk%j)(XCH78D2?w*~u3QR{R<-Cgt`MEDIdgRJ=_@)UD#q?YU7xkeY zzD%v?uqMj-D&pU##DK@Y8X-TW=$C6TACFrIziwf4RqhFShq}YzBO3k*dFMgcHpGwJ z&Iu9Wp>Wg~&Uab~DTzsHkueyQwURsWmF-8ykKHQ?G3Lqc!6jpw>#?mpWp&!YoxWZgZ2pY`J*q3A+B9cj@fA zGrO2=y5C1ysg$eFJx_JDi9O03YC_|ldG^40}n?s8sk{@CGGkbvbmCcG~epI}%c>L@}$B zml~7BY$>@X9k zfYnQxR}c4zo`HR=`j&Tx*B-YX9o&4%c3$!qY8NR@CyBKD#7=RUG_Ue#yA0%B!F@SL zrl+33pPOp@_T}02i@}Q;35!QQN3d>F`6M2Oh%=6bA)HkA? z=1p60;oPOR7@AjJx71th#lnwwj z)YermZ0>M^;eXc2k~sN|h9#scFBss0RfC>ClS z+dz4Oh<&HWp=y1WN29GP9k}95KEFYoArO>@MT_SY4)6N0W2g$rhJgI6gJn2oS=E`t z{Xtp+G{FFap=1^`DS?cYZGO&$>G#8>k$YriTe5wU?XU1aD{d$9--_6d2jwzGJOpd_ zLCm^lt#%f?#`Z934l*XF&R-QwbAaT)p$tYZFkZnXJ8zsiJ_&*_E5K@y8dR=9%Du^u zAkN2_)$)Uz*#e?KJJLc0dGK;7T^%j1o&yEnk|n9pKi*=#;}>=+W-4d=0lFzRxyhAZ zB42%~$MON5E;YWcshTOiZj!r;>C)_?S)+?fl66UKh(FC} zMkC^Se@9!2W-Fvv3nE0d|DwmQBu_!@r9hqLSkKl!=$_wBub7thh^(zpe7K?_J>l2G zhF9WZ3}9nOB8)4}DK+P}`q@2T+OK`q!-^ewvv(?=G^JmO?c=5$kCdw3p!NE0Jx~Qv zK?E^_pMp~(F-75h$uV}8^N<-M*q^dAVz(mo-h^!W2*u$1P}JkPFc`yeuj*Q${V?3O z(XWv{NC*b?2UR=(e4*Xp`n&Ac+8qpfy|}xs9n_nBf_Qds^GacU+|t*{#ta|l8oxeA zPEcu;0>4%2$(*i>c4Oe5!9rYf&MnESBE4Il$!wH}Vi5vP-}3$}GEgV*sFk?_78EO& z04l?HcUQLXalpT(o#_M3_?U6&p#s+`KkcDUKaH-9?-FSG#IH$hhyVdX*L3e~F#!ZzIXi$-IP@vkq z$xWf|P&~HEWl1l1?If~$7qDRS`sT!|jyHR;CQJ~ZE})twdW~J>)f1_?_b9H_k&ZeP zRY!U2l8K~sB8$kSA9O_r6NJfndRA3Db71u#b+U+?X>0Abl1<(YN?Y118sC@BfRmTH zBQ&?K-4&@}4=Zw$5%blEVT|J+j9cKxc6*T(1+;ls8reFV4z2*CCq3NOys zh(A;hT$RkfPwSq&UL(9sJOzG=bW9>JQNa$6cj#T3vmIauoP2}mH+P`r0m~6 zP~h^a=ugU4bYb&kl#DOYzUX$@>ldR8+-eOli;WsxABEtRlR-?^s_nx}d-+0Pb^X{SF`keal{O8#57Z$(7 z%H+p4R{>pVIp34hNK1UjD8npkRjsjM)n3*&i?;>zYfdTYl3I(;7mm zcO~=BC7=S&tL9M;k*A&U^jP}E*uC{CZ@X4H?J{R$#j)k-nZb7T@n4H$8hiV*3%g^p z-z>#NO=eSX+%iW?%Sn?}ne`2MX7Z-z9qDaa5EUUpvYzG=?h3{d(*Z*duJjsWwzyW(=8Tn$l_hC{h}x<|r;h^Dg=6t!FFccrj4;$ER*wO(H6* z%qfQI5@TgqhW<1W(xm#5>a<0VuLN?ukTBaCg3Dcl zOXabRJz3%8xy|WcAze*dd|Q6o=yQ18(>AXYZLQjpuG&^x{L9rkJJvM9;Oh zBZKipTU;$g5gDwf^d(o^=k3pSncS3PD>px zZ3!9U<(9dss-eA8ZJagC2DW<_H#uV@oz2#&{MJ0%!3Yepg&>z_B`RO}>2HrW7$<$z zuS)Z?>vaU^9p3WB3hKDRxm!biMq)nZjLtV*dLj%Z5GBelP|-r3Y~+OlYi zFNzNgyKpV9Mf-!B3AR?Z7;k5sP!QR|p8A5bwp?LDXRou|aN|*ImYIQd3PD+yTfa3w`=u1ccU zS~IBw2@QAYa?>Ss6Sqv(QeCb%w{fp4z?l_t^?-~hAd-yYQH-{-H&^!v$dGqYNz|}* zYA+Z=h+i0xwsvYPsFcW7My6H#fhWV>(NUWr-T_(+FK6F4iH%B5$6oDL@tYr+i%I@Z zDKE_^j#Ns!CF;pf@Z)?jHOqpwIw=Xth)TCOcIB@8`pA%i_EIG))&97Yh=r2jDWZF} zhu^YX-RkZHM-#tvoKo{bqol0uidtzPZMaLz+I1;x?MUL-<`#?#E47Vct&8IpmU4EG z5EW<-F}aqihyXYSn)+g`77tdPw5v-pwOZQhE{!dViU%D@aCLxq6*Z2yB&RvHxa2bB zw%JF6E?dw41w%l*zq4Zm-92j@0DFos>3D@~t~NP?Kuz1*R!65B&UH`QnjTz*)^#IC z&#D2~-`UYpcU(&s`L|Lsj}@!sldKEj)iPPXS}L(+O{1IQ5CuAyuR{NV?#=DBj%#Nn z&Ub3j+$KlJoqOnqR#T7y#AF_@xNXM|NqcHTA_mOUAls9 z@;K5TbvL&(QHJy(Paj@7M~Zb-#4Y5vVvNG8_prZ}y;n&jYiw^4a(t8Au{e{OVBG!qT0OJAimyEBC_ zj`_9@!bsVPMP1Ek!Vb{UvcAVLdZ{Ii?2lUMB!NSE-I``+g6C9J$c2?RPoYN$ zyFrc&#o6F^A<@%_YV>rk?dqv;{RoB{>&P3@(o9Q0+iG;SGE@$_F^UXZq-FD?FeDCk zwX9u-i)%B^A!nu1S4SZ9m+kEootU`7&tBDdT;sTQ)Zn;z=nXqsQS%IWn1c!$R(5sv z()x~NMoW7OGAFM&~6;YP{+FlnfA?9M) zkpVzsQ&UTK_lWW1$7A2t@fy0zEXaok@O!Kpi z>^wg_0FU8=Ge2Ap7y6+eF7?9=_~4uiKUeU<&R`XOu5wN1x}O`|@q(O@Sq=Vh1>kF8!7Wx9_Q!rJi!n5 z!Yw*a^uv$b^s`C$fEVFe>h*(uxE(vp%CU2>lf=0j?xdDUe%L`Yl9434l~)J=c#_Ui?a7ny=*qp5BF1*y;Pb;`b_5;em;b!Fev(Iv?%l`8@Bp$>D_kHQf!Jo%2?s?-(S<7-BY-n2p0-+Has$x2~sd zMLq3IqE!5RJj#Y7Cj2*Z_%HiBYKyT~zW)IrEDLFDCA@uw~`#2xwt2-Op z8;)OtUUTAa-YQ1g;24kn-?hNiP@YWHEU9EL{(sModVmwVtH<4$t2s^_>_vPbdfay8VT zLhgI9p`;Zc>a;zMtR)HsCB#Zr!!3%#K=0|4^Af`bq`zhzTGcNCZ`n24%rq`XGE;wp zqmZJ>BL=jt<|^DjHOlj?hWh#Q8kW{qR@cqo@MCrV4!XV1xgiz10|;dHk$QcEc@^*WfV0yZgLbQ?ObXd$22gnX3pH%l}qPT z&YM?SjiwdEVL*pBXz=w;w0jvcE%`4Z{5q=sFLUB>A$ZhmF>?Ms$MY z0LSF~y7<>E+(plIKLe+F4AKv`9T=!?^mIBX7zSsQ9fUV&7&Y*7Ak%wIVuzX|i32j%NAfAt~sQsJ6G`9+xj>;fcfo%@<(9)+ClkR%wIPsKNaFBPL?o+%9zGev@G)&6w4H2TbW`wD%0ED z`WPt6^e#8O+fDCr>+f*Woo>3zO?SKLy>5D+o9=Pby>5EHo9=Vd{W1-p>=^Ch^C8St zfQBUi{=BqA;EAB@0?m=)Vfg}z%H9Saya$gUl;qTfKf$B&^@rReASI&sm`kw(1kme} zq&&6@^t`kkVC3cO08gH!>;Ufo?Icj~`2{||L_S|Z5dID(d@cFppoKW``aX5+&@CvSBAE{MrPIB*vPuLoV}2Sx0F*t|Uuw;0j! zyC7i)B+7c`%sr5_IPV@v+zH8;#9j${Za=8Gy}Q7=BP#k3(DC^lvicrH{}E#0C&+@I zVIpH-Gcl+O^W83}Fc+T0;m4&MX2DYkaj+pBp2jW+gmLHNbb-%9<@o^E>fMmy2$EVP zLW-$mY-95gk!C6rY!!iYQyGmg)iITwkkPsmhF~VsRPqmlPL~-3JiV7+1t&x?0nFt% zm5Exkav)00QW5Nj7X~U3m8NJ-NfUF2a2JO$FM>Ov+1y&6~Sq&7%pU`u#J_$9jpR37M1WktAdwU zHGIfsz&}_GV{9giVY65&o5S*19V=vWaff*%o5$+eGB$;+V2h=>91R|vL-FuuGzcAe zjBufH$bbU~c~FXScn%>I0&EdHkMltxGl|R*gd77S$T2VoJ85pKUNXbx^g;Y~9)#i|vVX7Cr*$s%NlP>KkpVx#;}8V#bIZl&8p0`|~=Jv?BK2-qV7c22;~3)uMqdu+fS zAFw9|?8yN;6q^{DYEHeG^kkkXU*rQM;@>>{D@2Vg!4&`a_n1BppwWx}4*~RKEL(|g z@G>kr2Owb$rZ-?y)E~z>i3eg6cf%O!&Xw?!2-zZ3U>0CsJ4I-kIn6BC4ofN7Cc8Y= zEO4HV`HwSg2gos}ArN+F)L3(x^ZZq}eu2-JFi1WLZQn7YnAN!X=^Ul8`;EZ#p)AQ+7U6-Nqc{jwBc zV{9R+A!;gi6e@^9)1pve6q=rA4N0+63R0$}6sAny1rrL2Qi{X`JD5_0J}%B0Vi#M% z-7wKEwTi7$oWk~aYkVS1veLs>Y-V{pWZ{y98LWo?hV78lM4Gy6JNV-GIiacjKgC!> zt>Nf>WR(#Flw0YEa737zRa$X@%ddeXtK32`jG)`>-!CI7z0MJ%wiyYJ%`gi3rwVj&I7NJ_RmIf|Q zD!G=L>1Hk}Bz|KpFS;mEm)Z zwA>h{$rx*D@9M5xNFBE9Ch`mBniM6&|xRYlcTMP?`I?IiX6^cbp7 zgo?}}B>WoIEFycE7M8s%qE=GoVzZcJoPndBkBllT5bu72$JK zqM&}umVx#l)MOLD0Bvv68o+*)q$5}~;k#yd#BRM34 ztCwlhU|kll3j%gwU|{Mmv)*paDU5t;f0R^g!~QKwL7Ir{x|8^>MTnBp~UtAHj) zLD(v63P)UmEqw@1HY|14y8fTra9wxg({OD?`9!GDEF@uvNzqC%W0NoNnuV@leTCTW zEi1<=K>DrJ+-;F3xfD82@~ndiI15{$v~^;9VZaUs2HYg-VxQ~^8Jt~&9<>N3coWqb za39005|qPr6-5zO5pfQ0p-(7@(m*uo+?>8FR3<{@X1VmUC2qU&h~mnfnk9YZ-QhsMJRKfTkg z3R+cGRhXiR8P*J|B5X}W6~s%>o@f?_QmqO*e}L^wYciJMavhd!Cd*Ebi(@Mz(~s7S z(WX7YE|AW~jr^uafTk2qH)>dvPjyPTOeqSw9Pnv07vQ{H&c}ET1#Z6L_BAkYmcsn z8|%7Zs^fa`QpYHqa;IY0E}^n5;Im55L@_I=I9?uy%`s=GyM59>UM|_mwGrJ0k%$C@ zr51)UljMpcDO;toH8pz98i_V4zzJlq~(4Yh|`MY~~!J=7X+rQc2-V_#Hi#xTp5j*AwPq7? z?f`NqA!DhF_11W44`}Wbn>JvC20HC*h%ipApUl)ynU#+QEhj|fpb1fJR#U$p57;wA zXr?)HU=mcDGiegcLW7%S&BAWa=$jdx1l5i;=2$br(i}0al#>9X(C8$nrnoat8ceO6 z1a)Zi6ot|xsC6enWv5*mv}&zd*@3y%T#8AZNkAY@f@+)uv)xG`+16u8y;UC$+YLA! z8k~txjr68i6G?xQsrx>&4BM4sI}|eCOx*Q836k>D?Ax~s@|v(kA+XqHC9H=C#9!#mk&0 zwJLHWO{WFbJ?NM;%f_H(2aJ@b1JfhzFLOfVK?)fX4VuyT6I^ee5FOa1ltlK{1ALKqU zBFt1pdO}tjmRubql9Q;WCc9eN>f_PnT&|8)&eAs_AV-68cc+r7`qZG=?5ZV|cXk;F?&&i7zT-Zxpj?nN>}yplE~jr7)|EjyfvB zxEyFAlwzi6TVXjVM=|x?un^~Xm07(F>ZGzPhewo@qi3vvx=WCjS%pJT6-DdYAVyAy zD#xLwNVa!S*yoKc#6|vZkJ7xwH4Wp(CUnm(_6}ORa78L}k6|igM1_5+kjp_Rj-P{( z4X1_5-CN9##O~2$#-L%uL59hvLgf4F59bLv%D_+PEYX;Nn98%H3w_Rj|kk z(dm#aW0Dah-VnLlw!?DG{pE5h=)9;FORXVPj=`{%PIBg1_;1(_#xB85efqkj=5tO@ zK7Ga-OJS|k;ZOG?Nm{yPfZ*b8#+r1xl8$}wB6_KFK!xlj2BQL6_!prNe#+bF{Ww7o zvjj2m)>!NSp~Hmtk-W7ClH@WXK#`p=#Nk!!%EnewZURPN&go;s6<8(`{o{WLC3Ajz zD4Fv=hmtwJEtDJ-AC9y}-tI(EM>|ne{4p|wiX6Wi=kVbG>Eby`4LmWFBlGr(r z!On$jb{>pl=R*Oz04muyWmN-8=hhJ!U1+4yukLr%WN;a z#_oqV*gklh?T7c+1MmTR5I$xP!Kdso_<}vbD%ex3hCR*ZvS-*l_AEP^{h6&`2iR)% z9J_?Q!0u%)vb~6V2+JO4uORkS_Bwlwy~Pf)kJ#&+v4dP^Z*r5p#fPxBc`>Gy>{ULC zeZl9lFZmMo6>nyL=N;^8zMlPqpT_>lFJ<5HP3(KVh5g8{W&h?kv!D1q>}UP}2mUbU z{3$N@^IYL?a+QC;gZy(I%fIDug7bKh$P-06PZC)?S>$s|jOQt$il>S?o-SH=hUny( zqL&X9=kQ_TQl2HY@)2SO!h85g@dO_wp5r;f2tCU5&T4~}lly+XD{Ep95w((iYjeNFpH=m z_C2=$nJ-j5e39zsi`5`sqNebp)LeeFTFH-5=V5*^U#c$W%hV0LQSIZ))oU=lmN%=n z@)mU$U!lH%>3dk`V;)w&;_d2pe6_}Shvws*T0W)|d03mu7ivZPc&(Ig&}Q-zv_^iS z7Um~u7x3R{w8*I&q(9@jUoI2V;FzX$m0(g75ri2SpJBy9`nEBj~W;8$BfPVapO9ye=~p5xQ#z$ z?B-7!d-yZPpZK%Jo0z`O4;Y{E=ZtUp^B#*o=NZDE@{Hgwc}DS^jKE<|Q z@lU*Q{Bv(E|HeC(f9tjRcit-gy>~wUm-krygLe)8(Yq1hi}_F9Kk%QuR}0;{MHt?G z;ql%iyxv=d&wGdPd+!r5-iJlN`>2TZJ|W_~FNg&1J0j8h3Bq5BWbY5c@);t<=M$+u zv{c_{k>NW6;b~%+uS^X0%@J9?MPh_+smS&~3YqkX3ezwazD#dn^V>bp!# z^KBM|zB|Qq-+iLU_kbw&9S|kH4@If(Yf;@Q!q0sIc}{2aTjBH1=hJn@x*Ocym7ZGzPP6pf7}ZQ zzorD@-dBQgA1bkNUn+6&UL`g@R!N9YRTAT;U^-n1#Fs0{@pBX_ey)-dzgS6)@5c0a zB|ZKuB_sX{EW1X@jNhsZjlWhI7JsWUJpK+PEB-!ZMEu8?ey)s4P?Wrc1Z8wWhB780 zTN#@$P8pXlLz$ScP??m_s2q{dri2o@l_?3wDR#oCN zQ7RI4E0qa*lyDm4iQm6-`&D6@@ z9G#f29Gf^zS(;d;v?k6}+7j!PRf&zt>cm#1BXO0|nb@PON$geDCZ3{nCtj}fByL5x zUpX%EcBMD*Ze@MqF06CEa$4d;%IS$uD1C{4R?bX(M>#9;Z_4izzf{gm{8~BR1myzL zqg-glDi@i_$|Yuoa;cfETxRAgmz$H6E6oyRlUc27HRmYX%!SH!bE$Hzxl*~#T&rAf zZczHo)0G>{is8P`S^1Oxa_;s_Zr2RrZ@7 zDG!)GDi0>9%0o#$<>90><&mTb%Ab;ol*f`9l*f}AmAy%=%2P=_$}>s5$^m*UZw!Y6 za1nUr%lIT%1ykT9xDZUX6q+P7jV*vK`7*wMy$d5HG@V;8MwU)zZ$T@(jBTf}7oitk zk@e=mckn7gw%7`Z@EVrZiSuBrEUgviKph-J+-xx(ZiLqnnkh!Yy^?Yb{}#T4HxO4Y zID7zaB2+1|P|~*$s>W#HLU645dKPhwPrX{@+j7J!*bc8SgSzo z5#=I13(l0dB1MQB;S+3YE1I|-KBdvpN?BNr(RBSC$dUC5^yhH&|AxAe>4Q?1rz1viAqn%ij?y^BHhFd`%knl|eE51EDJ49GEOe zVTP{@g76Jlr}u7n(b2QFA8qcR#1~_ZW8hoTDMlVk(B4s}zRj>f@-6V)2`!Rdq3=F8 z+Uc9`0azgUmiR72JD`5p{!NhOSd;&EQ0er|e+;xcBj|qv(q-FX|NCIdwx#~3UAroZ z`M~Y@teEHAp3e-7M;z6w3naKbuZ?*Y_R5~m2mp>HwU`-*fs1&+I@L29crBs46essI`!^@T#2g;{?+w9)v+mv zqtcq-E;v_OXL;~L)H7LUWo#1UOM2D8Tj46l)?#P5Ey`l|xPGlN_BL4KSWfJ@aHTUZ z<0iX2D&xYghpUX6;Ci_7xKXZ$D~r1xCb`gGBQrie0rDIu?n7AU%=oxBu&tyVKQBT# zelE;#O5>|wkwYc^ZkQ&anuG**%xe;|-LagNurP{ii{egoJ!?(;9XJX^uR6Y;aVc|E z!Xu~+2YLqP!H=Z1_^s?@_&3>o{I%#YekIWgm*cG`FhLC$D3?cVQSkfu(m9V&^4NQ@j z$dZ!QF%=;dGLkx&hL8r?Nh_F+kPhRLj%Eg~6$TU}9mzZhd7v_>ig^+8!px*n=0gd5 zP?uE5{0PNBL(&u$gHR9_CrxAlgyNtzX#@)*lmIuI@32^eOt{T_lf@yAWVq8j$l?*Q z;2!f8mVi(S>@r_ui3p{_{pPdGL?{g&HXmn6*ft#=Gaq5e2n~TJ%?Fu<&`@~B+{aQ7 z!Zq96!%`6%0WX-lSsFqk;bn6NOGhXNUNi4v83^UU8|Lk72txVrws{N7L})C$XWqz$ zA~YU8Ft2CB5Sj=do7>rNgeJqM<`$NPPzb&-H?t8a)l}g0VV85cF7Oy?XClT8odcKa zLUiHK2&n^?<}?Ya1nL9W!58dA$ZL8{bsNN`=%!bm?0Q-M&z}=sHI-(iIpo6%zHLB9 z!lh}ZmtOYxMJQkfsM$zt7N9>m6!Oax+<>g(oZtrJ2`*8*KSfWYgBdTKT6x0}63RA6 zP0>s`*(^#UDtVD+A4GX{2JD~+#hG!=;c`$O=LO8T$Z=krbLJcDi=)G3E9i<79@J_i z@`$595_2#CN6a`WX25w5AE2v+u_6>NLJ0voQG}ArBou=`YbHfr2J^iEJ2_ydh)|lD zM)Yk-GRaJf$do3J7}Kp}WJ<8SKb35ySm_c<=}SXqkLFk@yJ2Fdoo1!=+8H90DMCYo zRvH}|4ilj)GYe_6Y?pRcgm#vsJ;EA62ZpCu8Pb9KFd3S8SF?z`sOWBRcI2 zGph#&Hq%OTnr8l@4wAje8g`fhY)of)X=awPEHtzq`cMYsb5cZx!w~upWJm_25f$Mu z(vOlN97cXu1nR=jzAV=N(?Ki4jx{qwSu}DZ%%rp}u+d5mw%Q|6uw?uj8Ey@u!qPC4 z=45iLoZT>kF6zxdAyMactd)aphZ2!VR&rP#)?)i`tDP^QG=#=l`PSGlbvaia< z>89WyN^w-T6N!ztN8kwd!y+pqXk|F;kqrVPt&zWCJ{I5y&&m!|kz+MH+q)@ySYbTmnp@hC9*8lGb zj!~oG&Xt-?A`4BFb{0>WyePJn%vQcAOOk_;6gh{LO_I@4og3Fg_UGHpgw2p9YbW67 z$OZ(s=l==UNLPi0vMiHQrzj_<$xf1|<|FKsfSnewGXgeFhGFI~60#L1(J*oz!&3}% zSRisHJS=i-JWLwKa1gW0aIPEN>cR_l-jQy{4sX0mI7f zwX>~kE2|gfJ3#`$M5sqAXrgyyZJ4*RJMB>-lxyY^w=&tYT%tD$dF491@?XE$0x7a~2DZy^TV!C1579ZL49o~C zr9S#;iWmZq0VqF!Q2q^mVY=Z3+q%LoUHm` zGp5@RcY_*)JJeX%ttP@lstGS(`kI;y@2eJksHVV|YAW-pDJ)h^XX$DN8>tRq<(Sr} z$*fMzVfAV*Td3x-CF*E)jGE7usbknGbu8;v$Fbwo3G8@vB0Eu?#LiSFv#Zr3*ez;^ z?Zo_Ebt?OlYO^QR0``nLjU7-6*{f;^drvK8->YRD)N-D#R`AJcC7-5N^Mz^+?@?#* zlhir9Pp#!!)H=Rfoy+&B_57gPz`s=&@SoHYp{U0SLtQHT>M{|hHi~3*xyVqPM4s9# zrl>8VQe7cx)K)P^T`7)KSBb@HSTw2aVzs(j^r{`=RJBuFpso>@scXe1wM$&Bt`}R> zWObvG zsh+1~spl)B)C-i+>V?WUb&PU^dYMwJUamB$S14y9yivVMxk%lt+^Alo+@}6fc|^Tl zc|z@1o>p&Ao>OmBUQ};ZUQusR4yv~*e^GB!K2vX3zEST`$EkOzQ`LLaGWAwK^q=-LHP7C#iqeQ`E2ZEcGAyG)zm?f9mrP zzgYcFU#fnuH>*GBC#(O~&r*NVFH(Qj`!&#?MEHQF=&x(4{+_1kA83aDrRLGU)nfG@ zwKzl5;tf+vFtQOIt(nF+Eyv34pnl4=z~4D*?39TqfIT9#^IJBPvYWmGuI^B z2H_3pcIdIIAw}ZSacenU)=OjGGgab7u-BQh>CO_T;)aHf5yp!QI7MzLM~W%1LT>VM z#A2wBo4h>H1O;+4m@ii2_JlTrW5r!iF6oVA$Mc;m2ccwkBEMU1Qc~ET_$uUbDe`@i zx3D~fGT1YGIU9|9GuZ*Yl;tBdl)cIqvN2dXO!!$A8!M%XV?)?Dl2lYVEZi7c^Nl_?20;$)*MQkE* zQ%`^g9ldDhVqYc^H?1D-l=MbwW$53iG+R%HY&i;fdI}Us33Bux%#>1%()(Sh^7M0X z1gS-?eij_XCL?Z?{yJ`KiEpm{r3;PHf5vSf)f=U}B93B5kgk-2Vi5}=l&LoJXW10e zkXFpTW>XQ$(*3yYqodkvqXaT!+YH+JMYi8Yr`*6Y3DJg=gWqV9+iwNpjbr5Y8#moX zJ+pB$twD}a%?c3GVUkhkZn}$%3GSx*4t>AeV0&S=zKcyGJ7x8H1}j7;z!vHjn~qQ{ zTcVrt04kmxqsOx%gc8^?J;;i&G*Nj%T+d1nN>ZK{+gT}Xx|Qd|HF6W5qP!@sVr676 zxT!5?70#yCcni4?15i7D^~D(N4|l?`A^IMXzP9s(Z7pbNowh;Wl6eL0QhgcQV4l2# z;FFgFe9l59LVnXvOPu^53_)LjZs7ZIdHcjEQ=PJ+L(BSn_`DSfXP934Kn)8`zjLi+ zoUAuQ*7%!bP4q+Z!iz89@>EQ3b0`LB#yI3lsr@g=KY@+0uKcP^UcU&M!HnimtQo|; zO`I8v&-j3iyHL{%su?S{!%bMS6((Y>?Lb!@J$8bOB;wrQ%CHi8B`VhpnsHVFvg?O8 zu==&|vc$%k@w9=bDxO~3l<`Qs+c*W|8mU@IGTyzaWJYstou!dF>295&w&`+=w@k@# z6~f-;jP_760?8RGo3T@*>EvZ{oUVm9(;u=BBD6&~?5Sn?@tNY1vSjKrE$52~7n|aa zVTywl$RHVq{bV`d$)nBW3DN+Pce-DF1PRQ;=yYg4mPN0eL<(dlk_X=?ku-i)Df1VV z@|{Y3$vB3m4!*(ce#&cD$^D>N$-Q<;^drL2X3$EZZBUv*_nK31#OdqBen_=a2Hjl2 zn9`GH2C>9U!y#9eZD-FTv=xpv)6mqnLqi_jxr(z=te93Sq0{+zDJ^5!Ha;PUd7CZ+ z6$z}6-s|YCNSZ==B%_#d%gi|Xh(-(3V6lH;YjxRH_IEUnSY;X7Iu1j+L*K-Wx@B4k zt#+og`*ga9<=n82m%BsU5Jhf0#z)bXiQ6VCA>8VeS_z1t&DV0Lr)1+!Pmgr6gOCm} znUmTgt(d_r;L9V_4te!6mq6FnqK22?_D>LOnN7WtYv+Ip;<3vEjd5HD$_U}MMSO3h z0m7|Lol-%~Dd-U9ZdR-Hum)`%Yt)WoE45yBoVK2A)J|ZVv=iAK z+R5wz?KJj;b~<}e>tnBLXRvp*Gua2)S?p8o_v{PpT=tE&k^P{Z$K$l~`6%sDK3@9+ zKU%wj_h?u0Q?;x3mD*;0J>qZCw(xtkt^7%C8$Y0J=dWwm@prZB`3G7*|4h4q|D@e0 z6zwh%(C!xL+72;B+bKfYE>WoM7B$+vVu5y_Sf%Y1tF`;ZI&GggP1`RvY7dA@vs{l$F}E%0}&gvQ2wV*{Qvt z9MoP?-qc=K{;Iv9{8M{VRkXL%cBdHuH@_qI2NOn z3o&l`1}3sfiTeTaSrr|r^E^0BQb`tt7|~TzWGYT$i{$H!bg_}u%7`gLT*9hl6q>0H zhcc&BErx8T6uwu&YzE?j@UzmwY7mNLsLlo7E{S|Y z=lAlPSuOR8Kgl=AgZUJGfM3e$zwJGxILOsTPb&;wzu(>jd z%2sRGkw{O2(P}xXN63KjYLR@g;e}6?)7dgI%R2;BN19o|UzT2n{ z*fke z6jI$pXp|>1;|4d#lmJ#q8E8NsR#1Z=9YrWEkt;##8^QAE61(I&#+)B*L5t~p`u=Xz zDEYDQC}d^(V-rbK`7u3sHw^lkzCr#p2K|-+&`S`O=zLW#HeuR~={8K)11Ke!UWOhm z71MnfU!LcDb?-S!eoc?cjU6IWRL%l(0qLX(#a-Zv8%R;j1*spGP=!to$%Ckhh!j(# z6s`6YE8vP2Ek)S^RC)UNXN_%j@tt;Fzcjt{Ul*VpbLn$+E6<*5E(m4G9-R}gGp)Hq?%uu-vyw^dJTr@L zfuU9&p;IisJe0Hj7Dnccs7W0O_^oQ1XVp>3j~Wv(1#50pYmU7~M!*~sQGc~-1l3N@ zqW#0B>OfN|-?i3U`7xO_H*6)-tBM8If&c~Cnbs&Pv&kN1W?cn!IFpc3R?soEEIH{m zLk!`ZSt?n`Q{M%aZ6OUDeA}`E1J?9oKh3ZHAGaXGVc2*w8eqegXzAHjCYfN%Ap84q z9d=||Crum5waTyk12|8cF*Qe+hSIz>TDL~}qKSi5);>r#^@FXm+*MDxH8F}F6EVbz zzt$otEm~1dL| z;*voUkCbzLK)|q7?#kF|Q84){DfU}=z4qjwJ${hEv#J4#Z1Q0YK5EIW_VlQ^N9(ml zE4JFj)^r-pWXBX1IKv*>jQxOjtzs%N-J)Q$;PF9PkGQDCQmfWtYcZ-eZLmlYK^9tR zuKUPyrpOqnCzk+W$J5KO>GFNkbX0~to~9f5@chH{;n(y=52n`?p;s*5rxi!(1?_y& z>reMOBm4bFad4S5z+|~cj*E`k{6V8uemK`=B}DZwfK9OC2C#Yr8z+bICR|&2C>PgO z`dyILa3Zudoga#IIL2;+<1Cc$tgsn-R;PShklhrdXBfR;3c46V#f5Pjh5ymZ0Nh+< zqa9k4TWO-Fgt50c(QB+4t5kl{SYwxBhjXn;dv-s>B8yyQ*%ov|HFhojRZ5Z0Hgh*e z4EMV?%v=&9*Q&Kgs9o4IEZo4jz7E1)A=Yg9z@|5oBmD|3)T`EJ24 z=KJOW7ik7tqdK)x{)4}q>FD1w2hFjR!4C4bx(A(zMED)bPU@~{kSom~)opU_l(wuX>Q118 zr13kUy(DR?Cg=BEq;gITj=B7bTya zmYGe$4D_D%)z~c4! z%+wdKRQ*^sL|?{w^yTb$y@{QuuVAO@t*lR9$mVd7Iuy6Er?B9AXSM>GV(2wWw`U!l5ej?A;`}k!2EN<(+=hOAGd5L}wFW1lI zbM%dTv3@>p)-T{4`h~ntzldLf_-ph_`E~jq_$~V7e6M~5e^|egAJDJj2lcD@TlzKp z1APnsO23}}L+|H5={E?kexu0LZxW;Rn?;3wt5~AnE|%+eh!y&sVwK)6*66!Mw|=kK zpx-A>()WlyeXqDkzh7+9_lfQLe$lT#ByQFp7Psk-h~4_1#Gmy?#q0Xx;(h%I@tOXV z;?*BfV)bX0VfvqyT>XGDUVlkBLVsDAs=uO?=&vfX_1BaI`Ws54{-zSv-%`5tx0Mb0 zyUMBhN6Ojy$I6BJUzIELPnB!+zbUuqpDTCkUnuwKUn~3de<%;>KPr#u|5gs@KPj&o zpuBD{9N?;1k+)KHXf4NXO5s(!;zhZ$Zq*YK&648K}##Hdw9K&>@|+F-<~i;Q@6 znUSov7?!%yNKw}rscN5*rfxJc)Ju#Z>eWW3dZRH^ecBkVzKHpQMz;F4k*~gIj8Q)@ z#;RW!mCT8S}9D>o)x>Tl2BTBI*;u3BW~|ls7+w0GjBfooqep+oSf_t&9A|iqUL)REZzLJV8>z+yW0-M* zk!PG}j5U5|OfugIl;Kj zbCz+v=NzNobBS?-XOnT8=X&FI&#lJYp1X~EJUfjYo(GKGo_CG=Jl`36yqdAsYZ?2z zBaHptkny0m-gwx1jPZ!K)!5-(Z9M8d!Fa}ds`0G1&-kza-&GO{R1IfP2AOH)QO$tizKyJz-ho24?`+nB&S&0$&enmseR=`%2krq#T0jzO}3aaZ{kg z*C8*e+feQcvrf8#3{}3BYzRJ%=Rs3T?myzoo^}YMyMR>eMhq%geqaa zZ!uekP&Mjz0Xq(%8aT=~kM$zAS#YdxE?bYd+0f{l!;VL&7MguC*#?B>LaVQuoq$k1 ztnyW`6R|}D8{)lCUbUSMoc{L(&Pkne0Ckr^zsES}q)wA3b-JmW8r_j~uGC^?nY>ji z<3oDkrEi0=A{1lBP^dA)^15gGF&MAxh8eW0_x8nL#PP0tDfpb_O@z*{?NwxBZ1S>f zpwh{Go*iSw(8WRe_WKqGF9;nRTqn*7TEVathrzo%p-C91NH2%XL3JsgEI;ulF_&0Q zS&ERqkC*IZWJQb~QzO|(EvFz-O}2@=E5WRlO7A&SuuIoP7)IZG=0-J>o#HY51M)e# z5$@03$+`!zhDvcPRV#MDfCEMmL5g^D<*hs`V8wRY@q@aIS@!}j@*5)yl7toS0 zihY9=zGmQ;kDrA}03Hp5#{j>_1Mwa&qBrT;F-?;g6Suoa`q2T1^dBM z$zwcKJjYYb%RMvr98V2D!841W=9$f}!u(cGIq&z(mG3pma2>K?xb(C!=w~OoZ#aH{ zN$g~t&#CCAj+LG^1uloH<;oI-YcWqZTH?@epCWIxB%p@Y%G)p|`pialihK)l3Opb^ zd*WVh$vg*FQsQCpa+H90q_WT8K1n4> z{+_Gr;rR{H`!Wg9X8}S&iSqq|pKq2vT!VOine^d0r1A6Q=Mo0w@{`%A@|H$EKarhA zex04b#>o2`es(4s&Q6!NG`28<^~qZr{fx;T#j~BL3(`g+dbcwocP{wtNS}TNdIx#8 zoe*C;W*_|sG+m0=18WzX%5LaV@lV+W-TT$O-o*k7m(?w%I?GH&zA&yUp!tYFtQfl$ z0uHE*y%w_eKo9Pq=qKF_BthjeQ7G93$L-HEmA(27NQ>M&u(d?!wGHR11Z5l0CB`(< zn{Rq2jK;s#ddqMy^e*2vpm*ou3j2)awADqcNl*IVKWm5)cDhFpO z+>Gpk#1y+2SLG5nZeXgPNf&24OK_?m4Tk3!obJnTx;MfIPcsyGTA;zx3O$|DI#3>0Wubu*v#Ut#P=-x~#d-`J+})6+qYfo#jXP4kM@gYD>gui@ptDLxON&c?LEAH@FMUUk!4`| zqV;j@Jc4xB;mI*`qvvkY24PH*ARM(iP1BXjCCwqm0C>5wb$(_T>7%sA=mb>m;fL!? z&%YS6vg6|4tQY`+m<*9pK?N3kp)%;-kP z^98`?6kUS54CiuhhX`;hy9Dm%)=`zBtqoMgotU~b8UrHd!rl?*ZV#%jnU*2V`rWtR z`TiPpg~HuQ!!8a4RO|V#MqMfVyQ8lDTW+4Hg_Erb0PxRn$bXD?Rn?Kh7DM4_=d!{! z>!lqaE|L+)5~_h)_DTT9SqF_!;)O+Q5SPI#Yh39mGPQAEBEA582w|6=3cdCS5wXNd zhLk1!n9iOK=6$HVdXHJ%7FbJh>ud zwGFJ&+EeKrTgK|^tq)o~gWIhPw1>43ZUs@m%^^UFT`>D|OhagX0s) zRdm)BjieQ#QNTKlxNGB7Ev!y?;-fNPhPu1q70XeLtLrpck&hFOiQF4hjbR!a%-F2a zYqGr*)2DeC97$(r>9T=)N^Rj$Ml6TrMQ54~IZjC0p~-nlLv01gT|&(;5{7K^G3%OI z(DQ4|i)SorH{#%HG@3dIqS1bH>h#lrA%5h#FnQ+N;FH)Gy(NCGwdVRzM9viOkA4eQAQ&py6MQ4fT;;rc>%_>G<+Bw4o@w&Khlv2W~ zY~`TB`P6ukzvg9$z`;6=X+{(GB?`X)@jbVY5CVb10q7m-StTQu0W|Op4tMqHc=m%o z`hjdRZYzfzhbD^cxO^LDvU$%3Ec4^%%6#+mk37Ca-T+1-^Mav4B~Zna7Ixv9x)%6f znHGO&>TY0jgPkxRPJ%XGhajedf$*6@1NoDu9RxrfBm(HE`;bP6aTi7CUqgWeWQfQS zQ<>k-61gSMrAR?dS(=o(Eh1MEaW_y3v z@f^rUw9NMD&4&!9YH#FFwFP@xrg*pptPr^N1e` z3Z7!V?>*rj)}JDj(q~eqj08XtViXE=DOf$eWnMhS7S|!Yj|zlgf*|~+13MD$K|=P8 z&xaokiU-)MbFJ2g0Cs?NjE*Um_l1|8sDXl~i0KF5Bt_QictVVr){t}U>{YzRHvo%) z=$(kByO(vUl5aY+;>Yf8Z8QL-81jg|mPOFoWSXk3;0EJ_D~iex7>pq_-4Oam%%>0o z4PbPfJ1mYxwd&kV{>OV=$H`V+ct+pkF#!+UI&mT;m5$IjK?%?_eVtdoIRNs)> zO^iwCe+qyIIj)xr@#5-Do^JJ#32?l^p0nBi6v#$h2>RXg2Zighfk({2kAQQxMV4MN z{=|!bX*B1c!(z;ehO^4MNg=)N9g0DvFtsU94QWAQhwBed#=L)+l9_tqBi5a+x#MsD zvsIre%2VfbG#HU7IxR!d1j;6rKb9<0m0B!_%0bk2r1qARDv0b^Rx(^&I?xsCsYYZ& zQ!MD#-L9DKDFm|jOnuE{+(CvOgFTpz{)mj0dKMv+_v^8=x=8hXWzfymndxo9UmZQ+ z`*G;X)_Q3-Ym7n_gr|u`-rO{?s|m;m5t$z_F^Wie%5`V=o4tPDf<|!O2ZuB3sQiQE zQeLh^#!Vf^VB8Uis166nFNhc}S>EEjXJg4a9**`m6gP#DtfU)uazfD>u-J`v>4V@R z=rc5PWul~HM{y~W*DL;|!&g22?!d^fcN`C7U+f^4{0*g0f!?#<;mzNkkqHvEHh$L=N(hJBFp#-A(U5(c8VDHFoKq+u+-Ed@K_1;F2W+NGv zL@m$}fOBVjCx7P^M%}WC{LvJmy!!(bU|M1r)JnsH_1Z^{>#{&QnCXHsR&o%|o|NFK zgA3P!0cA(tTKtPYm;pWjQ}@WjSUJaKPIFT&_72vLr=@=8LK>M-lkfW`@gh4(EnAj{ zW5Pga9(T;)5^Y^0r;NGlJ^P=1oOnz1${SE5*B8@%tLS_W+{Hw>X zEA{r`+4xrsb;jSQB6(^~0STJ~w6i zsTcVPhl(f@Mu_5-B!>C5Ba^YR>Qw9^j0Oh>(u=M^AbbCs(OLX2XLSDmk-z)5IQ0Kd5_)6YKR1KHqM>Od!B!zZ z#bOXsMk-1f-BKF!-KdKrpNwK)cekIw&I6V}_=a z_gqKIM`u@4dO+L*Z4eMkXww7E@ND*Ty3N`ZEiHSyv_edC)grw;E*KePiW2ps)5qr( z@W(5Qq5A6Q5+qq_`Qj*^++!oNrza_9AiCn^a*=RM2_*fBQ^3tmg>k%7fboZH3X-sk zh~&bYkdoqX=6#OnV8V!d^8yvjs1{6KXlL7f@vZ|=OH|T2gj%Rq71MpcN)zE`#oBv~ zI^~nOfFn_qaxy92A~Y&gjbGvqcZbt_-lay_jCl+;T!R9Sbw)51qGO zUcPN!?ur-oUts8u-W9nQMEq+a!8;3|SxH^37X%Y6lKmUz+4Qi#=BhZ$4<-UUhA&4} z*EthoHI@$wPvRwacIk_`<|z6vDcFKhSM4BRX)}}F;Tm3@Iq@dr2FXgLUY6@_psb0W zLRLLzE!o8$pKFh>v7Tg8`NScTM$K-~LxXFLOB)DVLLL%YB`}c>A?E#w=J#BOrPtuD z0pHJN6B^&xsA_8NAS2@|^Z@F~!xdOn5qs6Uz@0R4X)Tc?f7?rE=VhWhEfvaxPo zpP+^mN7|8u#+uHLuPiAD85kgDE@%i$;aAqVq8$g*?wY*OzGHA9WHA$_iE0zON~!Xz z5#BOgMoJTJQSirJ#K%DdQ)QGUt{Ki5-y)yz8ONiptt}Gp_$&ca>(=w+qj&f1(=^Rkft_~FZI08FyK9*imEo?Bcmq-wNFe%~@;)hpaaq#mk%ZHav9~&_@Wq-8Y zSW1N5O_tr!9%L8MPCF7_JOfBH)271a2hRu29*-RT)$5yk9G~1x*N^KycoLjs25h<8 zeKG0xl+x@Gj2FLpU8)Dm+!0u zJ4Z;mao2VHU8~i?ieb5fcLn?+0O}d7!huBlY)#ZCk^F(mFiO#_y0U~^k+QTqd%?)E zHbkiklo)e0x8^j2lFTPU9hnq76J}tl($vB;i6b8cNfnk7BCwTu66RsKRn2m7HS3%*OA#L5nEr{>m8JtBD{X=H5G|^ zt(_T=SP(&6Z${jh$cpOu`h%A+_28Cadd8 z!nVDhm(rLmz_t`TI*!k@-UUWcLy~Z=;HKqYIg=!zZ%)@!>FcHuO88EL6@%I*7sy7Vb_8%4>uzuXSt~^&5oxd<~wvfUb$zOcbhPQ#9ZlHBd0J6`u z;8rBCuQymtP}EbjM&v&jxt4|BD~p6#3+9dE4!SRc!55lfQs6vPcA=C%Px7oKAaX-mo#6mS6(AsBoOSYCgCq&Ph45q4Q z#;C+o$Eg#EV=%d-L#}KI znXfa40g6M1_-NkfzVF%<#hNrCL65Hrl|-mvVEHHSKa1;L;upvd;{Op1kS!L1Js`<1 zMo|Cut@fJmtcE6oV*FdWXywL9#RBJ~1<~o8c`;r2j5rZhCb|cvB368sGx1T{n@e)3 z`=0dgdJ{+|=>YO*kq#=M0h(pYcFV}fW1@kMc%$u0m)_^0-e+s}@jF?^J)LD!su#!| zH*;9^utRu#%W-;ASCt}%IfSANf`|DqH3k|8x)gP!r*8A4b3#FI9uOqLfejIcT5Kjn z7Uxtc&p#Gs=uPS9i1xG;KXFmK`wI1X7#?lCf*OoE@q(=L(1RtZ(B1Wh?`Ws!O`Q_m zg5{@UMR(NUap(&-O*0*gQTM*ml3H~mJjoXU(vrCq*D1$cqP~) z{preRlS&#bKan~jIo!~1Z>W-01cu9Uj8vv;DUa1ragJ{Odf#M;-V&rxfA#bczW%WM ze23_uUOpL?G&Xmib+9RTRk63MtZ`gfb)Wb&X)vT94gdAuP!!ALR|?C|z=4OkzywRE`!7h?9>6peIInDU!oXmHPLHSY?JIfzl|(yV4zO+nGdrEX^d|8 z9Cy$o`{^97A9c`tFCjnHnQc2^KYW=6wtO|-dLVu9Bf<7=0@;wgs*_)>nBFc~wy@&j z`z5AwU1Ku=c%O$mPPkf*c$M54wBFEjLA5pGX|M!tL-l19ckD@j7V8SrQ}mh|hSYS= zJ>Q^EzUOz8zo7<%dEe!tRImf+gY&MJDmuV0?S;Tef5I-uMDvWsB%BY=EUuLo48i(MwGT2a*dk zwqUa4p;!rHvW96a%XWAUaNmUi?Hcl4A~)|6)B*($3gRFN;2qrI(E?64nr7%eb8E7(_wuQsiro!#6vs49qzysLodeBV3F5mgH1Nz@=_2|f&#k!aUC$}xjA*@y#?6%d`zVPN@utb0c!Fx z-rtKsm$I*p>ep>KU_T9v@(gbQWJhUo_|!t`^(8y6)44{u-Jp7@41+k{Sm{RW2+$?% z5#YjmDujtS;oRrJitYD`IeTpY_KiyT=*Di~p53H*@s@4^(9f=Ao}W}1vIdkKpVxG~ zAmq^ZFtTPG*2B;21&8Z7vyi9f4#g>LanP1m*RmSGg=UnQS&ah>M`L4+330JPSA~{> z<0#f}7_P!sO&JkaEOrY2~xgnn}TRpf2q5Uu^-|K`ZrRv-ys3A!;~{w<{XHeyoCRn6k-X ztls315{52r6)<|yU{g>MKsKFT*q$DyG1R+eZo`ac*GYyP3D7$yvx(q^;#$K=0?<QlzuZ^wJ%O7=_6s)&YVMT_?p=+=S5ew~;iu#^(|3=H?11@w#XPfA0< zQn;d{NWU_XB`%sI=}4q74wpEs7RwoYW@Heg!N3#l_91>ZhxLTS6HF>>kZ@*2#y{96`obKEVw;EiY5gYVlr!bt$|we!VnPbDm}TKm>I`1!->MAFwqbr#j|Sy zXR4@jv9eXsp97A%WUDa#2!VHoe3t*EiA(onk3?6OH+8(a!Z%?`bnhWC+ycKf_y}sN z8R8?sWvFF35fyzYQ6#g7Y?L&Se3KV-^?D8MgYVu=Io$x1^{iXBCJmrtWe(pX?P#JO zbOGQ+4M+AK7k=F4VhQ-sgnvs`-f{l1*#qzWgy`cHi>?)i3EUUVc9R5ew@1dgd9#Be zJI;j6N$Tx}ZswG6zk@Sb|A($8VlraGy(WAjGCYHxq-HN(o2ZKTEpIQgo|Hy`t8CTt zv9G4QEZY*f0|K^zga(OTY)tEMb7p;WX=AmKuA`h~7X9)#JiztJ!mcx%!uL7g^M{v4 zxNWy!W!7iIx%!&t+R>pOC4T)b7Un^th45w!H5KRS{M2br;c(wAb!oVv#$r!b)Z$`N z*JRXU7f8U{19yG^|M8TW`$9lf5QfRvq9Mq#}h$CAoX5t4nverAox z22?npGIyMv{Hm=?ddw#`?xzT&ymM(TH*3yzHVL8hzVp1at1uUFd{WuF8t?`x9mzgm zWT&jEdB0pr=W!}PB6XEIU+AaBNx>kmGI9!8U2->2!eq0M#H39~9or=Gje8Dq65PF_ z9G!7tnU>a+TmcC}i9ZZjo%9V=DSwhp6iHnWKpQ-gM4zejl%qYg9yrS5{?r5+!LAf! zsXUsh)r*OHIgrMS3NT_1f;B&!993ydhEi{%VS15a@yGi9w1*g)bUSU_jxB6D_enKdQEGAxchV5*-X3rzeh=EPJ*D7-5FYB zVd3h!cWY{!hCR?wZ4QeATMQ<6m*pO}3jB9<<;?epeA443RyrORV3N4Owd>YNqfyW# zSqPm*+U_FUlz}=1nT|i%dQqs??xsT->Cb`CcS@re&x@ z((9|9se}{;I$_3Gl%|XhG^mSdsQi`U$y0kIPta`i@rFTl?%Q>^sD3H!r9i4KvRNLi zCam*PY$&Y8XUg>OU0B+`ZY1sQpDCROKgHgt0*~I> zqt{cpeDEaisc#MH?yX{gALYXV++b#f1_iQs@rrkI3+r)DOnr#e;ziF@%T2q=%@)fs z7|J2%3{QveMJz$V?r992a7667XSw;2$?h^tX7{mY?VuhqpG@wkbObM5^Xd*)uQc-Q zKcWA5#ZGUC(1jj+(-GPv$kR`Gb7kPg`vb?6R2eaW{zPYVHbhsWI^#ZK!?P-Wboizs z>PvRN8OB7p$w)!Fzvum}nb8&O=xEe|tkUFu=wihw{)7;Dh(_mLbQ2S=k-Ze^+KF-!0H#kOQ|-bR0O=kwd$oHG1Uw4{o^5?QSv;Yg}D z5XG?t#AN;(imF6tRXzC?R8pQHuodAmtj&~ZNk--zHcKFv*%_sOkIa)z)dAgNq5f^` z{(x{&$5f&&XNH4> zso@!FF|r%k{JI&M;KnP14GV3a(EH(9%?qlt^j=fV_I{8 zTpHa09%s4L&?!P3_9KZ?4kQrJaM@(LxZzXr(bTIlQG>9CHAA)RPqe&yhLg{L@A5|U zidBtNb3PFq`H~gL_smP-Lsy+?{LVYsm8-M>DeJJyNUC4B z2OOvxghCqTmt>MO)7tssrpL~81~1p(wB{#Jb)vlZ?k@_PGFA$+`qoDJV^g?6oC?oX zsQws(fj0>pZ?+8*XnHYN&s52$^CZ$h&rtkRw?WROG)O!`$f#zG?ce}2CW2u#Xj5;k zn~dK6-QmEh`Ymn}y53Dyupw_Z<8mE_a;UapvD)Tb(fd>IB0_JRxDdZcm`$bwnFL2I z6py4l&C5yjmULmrB%rx$JjpA*8S~_XaiK%!O^z~)LKh~-$-c}M>xu3!H4I9I51sWD zzov-(uhj6r?Zy7LjA3GF3tJN<69Y#h^M43q)ptc?HI&Z{?y}roW6nPtxyD=VeKlOokwiv%N#RL~hnMLY7k*r(-gC z9@pamzDMh~4p$$~Q$Mc0X%Fw=Weh#etn2M8b${sKMi4&LV)#rW4yHs2L=4Bw&HVb2 zXv-S}g$sUpk}{Bhgx=SEetAh*RWi~*NRp{+X4vwhpZb?>Qd0@!Wf}{((PC4eR*hRd zMOuV(?$wOb^T{8<=aaEFNt3pbo?{*j`}3kckB(lIm1TIb|+x`1K(>hqR# zjm>RS8Dp7Z-QvU*&PPkOdfEPX=VzwJ0wXi6ruE&b{j3pLFe|CqO@vE!q51MrQ^y1X zU-1gK6X>~dT28t^6B^J@P;m|mDY_|nac2k>>L_K*2LF12_A52S47-J;!1jqHnmFRI zsL{%@Rrudrf-*M044SCMN99)X-UDs!+wE@E#L+TxMc3*J&L~ zfrqhRb6FDK;XG_SN*$M(g1A0yg4WhO77~7Yw-hGXP?iUj*l=ce{opA`XDaA?DS1%s84;o!xU|&F zO@Q+XtS-fgD#iNBl|R*ny#+_BF~|Q!0un9HP*X7yMyT>OKo5{c!zBF>!w9&z@M92G z6d;qCb{mn*$v2Z~N$+FjGd0yF2v7>6bzWL}ZMRzd>Zh1+{xve)PSFv)Fm6xeygan7 zc0>1lc|kzOMOjLKmT=#G<%UQT*7T7CmyUT-;`9SKv#}x7<@9I&xf?Fm;%!7!@SKw~ zFxKSEEr|}`$O0|z2#5AO-AcTK7HrqSx!{RWKHXaiOJW!2PH57IPz{Tc^h_3uK~C=#rG)qOg4{P^(%_#jH?S}L)J6yo-??&gpHqvUK#M#v>X{gsX0WxDQG9PAYA19 zRCsZLB8uW_@k`&oN3huFv+0A2m0oELulKS44g^1sgs%7c zDAU~i(x-0s&|97f+4P{d$G>%8_(xO+)L`iyu;`WdEZx9?Ka;X;L2nl#lwqD9AXwg9 z0CgevxC%k;B?5J!3*tVa3z_#&MLc`k`t-ylw>%TD@$DWC!+yjgkX~B?(Y#&HLBGNB z9nBmd`1q;0-$`Y?qUP%v94}!!E^$Am1L?x+GybITgLamdI6zezKj!c|e8)5*t};&C zFTs*CowZ1dEJg)5d2-uXmbx`(G0!)YrDGa3^Z!&Okt+}CsTw?B)KHSLI--WVd5GXG z!XhfmQeLys@Yh(Vjyw)aWmER69|yO*Azw+JaRSK8#6kTsZe1-lAG%b{Q?R83HHS{X zy+DYWDp?&VS;CKMu5;60q)YD7g-Z#pGqZMb5Y;7BZz;?5gMDq2c(N}Ra4il3Gt@@fZN zpo9CeM*i%jzCZ2%IZ(qGs_>=}afo(os;95D@NEZMoK6RuV_{Yp6UZT%ZHSBDZ3ezU zJ#v79GPx~U_1s12To_V5V;S_=Hy1-LZjw)yCb+j&{H;kj5_*9txgwjU5WKK6*~*rY zq_HSxaS}r~VMeq;B{h+c`*yV8-0Td5deG2$Z%lU4!Y;v=M=>c+Q%5P0{rh!CyczfE zDtxvSHT_b-*REG6*pRYa?UY7yfF1aeCLP#)F%ovHv{+~ABip(x4QAAKLm4hp$bjX* z-M9Br3Xuv~b>`0Cs9?2Dd2;hI!f5B)(MUzn;_qhK#~crR3TZnr75Z6bSM|UkrcT?s zMh{wsa5o8;lOM`*tIq0t`3#C+ZC8Z6trru$>1uD?rpvOYdTz0ESE-iGM@*B6~4DB9mqdT5qA6y=S zUYOj8N?k0xW{0`6HndXE!2;PB-!(bY6=4MXI6REc`+u$9K{2~`L5@GMyNo=6x{RfW zc1LVE0#M-@gIMlNpfR|S%Fc*OGYXvD7K^1;?0cG`NP4n%msg4hJOdNo$yrWgTW z4(ZJY8%}Y@DgiP`zs0Y~Z3Q z^=g6C37~c;41nKYuFv)m=)}qN6PM1n#_C!+UI`8^fr|w-SN01&iB?^)k|+y)0f8~~ zD5W#$ZF_+XbmkHGvP+ONgM?q+3aY)3{LF8O{ck0gVi6!^30;-r>{;+?6P8x{q8#y7 zsyJ%4b*f)&ldbNEm^njyEK@}x?xi^~ym9>~D%#F1X`2t>QB$y}8CZ^wbG&q68I&X3 z28ebEU^%NS0SNB_7#)hBt{p&=dca4n+tzdN@z_5^`UqZtcb-bN%#kZo_*JH0RmlvM z)R`j3&X{!;yil#i?Fajye|}0$Eb2&&@P{2TGN%`%OgliJavnOeRhH%?irLSvhD2VH z+6)+>1m^wR5?xv!c8FMJsJ=DUXhjWluKjI5ah~1RW>}tG$K1GjrtOv5!LUD&Bj})O z8Yvqio6RCQD_$qs&-@1+H2fSKM#`m?!}wK32Vw9i^h|=xNHKs+BV9(j_&V1xi%x?( z{{bu6Z2ADx$sL@*Um-5@2*rs53|BTSP%CJmq0iJMEJkk1U3OkS@gUag9F5XcUWP&i z;0@?yr$*&{f>HY&RJamek|to&hb6Zcb!M#m%(9+({Tn}HnLG0S9m)dSIkbj3^5rAI z7aT6M#uv-=o{rud#)j`0m}KTX)Q(mqr8l!B2)wP{x)08ASZ3_7nVf8^$ltzPpX#TYZMYJ*f!*F}E$U{QZ>#%Aao~v4`{xpB!>d zR`Lo!DFWuO#T+<<-O|iXxJ6Zhj!JT$*Y{hjt(rYY=ev0bKatuDv3vkU0q}%8li7-T{LprC13M~4^k5gmWxThqu-e^QKJt(gR4Bk_y&8UGuvE9@) z$`Dklf&w7dqe_S+37O&DS7Osur_sKhct8dbZ>+O281OENq0$O zaBrs+8TLQwzozc%{iO-(Ix`g`zN`_Me`$@V{JWa)KbOh;vn@f!z~0`%)=a?Iz~1Sf zH8YK>8*(@*D4%ez4D=B{8^U42R152+yn%H`Uxi`Fa#6@A&;yO21`QFSKg3}iiJC<1%`4$)QIN^Xb6dN z{eBxEVKL~2V|9!L!62PT&*y=~6BY?eho>MSNUSa0?KV7FflvbRC}HX zKyntn9_=Hh^ayCabwXH~00T2Dj;=ncJZkq#8;4|&`pXtc6Rs{Wtl{2D$6qF^d$6VW zn9`$26)tvsYYxMI(3?70QL`&iesOvk7sm?p`JU)fd`UpraEDh4tfw zX0tW)w59Hr$&!`80p#Y2AT|<52QjL?n)ozY8QNSn64#i%iOS~;-ST<$W8_U5d&KvG3 zkzA4i#pzpyAqnEwT{@KDV9A^?Scp{cDBX9}Qf6tT9rss>3D6)-DGF-^_63ik`o>qZ zC)pWj6hiI%W8U1|YQ!WtjxqL?M0SUl>I6#Q^X-Ij9ai-7ZWJe1(lRu`NVBl4D*23oKWp`)o=47kU1ZG%IBVWI-5Uagt5YllC7rxx!O0OBb=XN^(ZxMQwkV&Klk6PTf&*A#=>l10l3JfKXe(O zCv>k|CsAb}=~mi-aV1%i6kK>(fzJTcx1i4aFYmFBY-Y@>jS+mg^!63q1zXAX$cz$v z&)qQQ`Prw6MTUz|!xuaM;Is}A;^CQ1Y;_7uOC2@L7f#4V$jK@h?Aa*&b+JDq zwKGcisb&(NEG)pHd_y;^XrcMMioIB|PpWIu84NDfQT;RtNkiet;zY1lvtOn}L&O&) z)>x4Tji0L%C$fROlJ{=zLS*+45sD;K`T>EO$uUIykSEVh0;LydhE@@j*C?h0^AD7E zpGgTKzudgzEi}V%!%>}B2(A#9;8J`olZ)jwGJe3<{gS6@foa6*4-(1y_r}sOYFEWOK+|TzSB$3(Nxb26=a9>N!K( zusJS)&vo>?hgPrQzPd%BJ=^+~0dqo;fk6uUuZBnjl&-&VkUz(~QSnzt2L<@QLWbP` z8X3YCrluy2Cbmu%24Brn|5>>G2TJ~d5&1Pq5C()yx0S|we>t$v93E`YyC3Hs|N_@9aCe_u;vYT@McrHbjq z44eS~3j^D)Uf%yu$Cb)ff3XtJ+|p`e5h^H{UQS6NKGiPF8gm*ez62Gdy3i9d^_+`z z``USaD8^^JkDoA-?@zulH?uYWIR2k?qnGE>hgpEjRIbOz?Cfr!3Buw%Mp71IrvUmw zq2Y$0Vatpe#K2r$xp^nmekC{nY$@vHbUSZ-(YgR7bNjS5SpATL0+LSd zevdX|E|y=-EgI-S7HsKF2Us$f3rDc+2ct#nJ6R1h`Q+s)JCNh?UgZR1KK=1Fm*SV9 zVe~v}8kg2+vMzOf2o%d}{sbCvNp4qc%>ngQeHh@9O{3VTs1moAh6CkNvx$6#31xTO z77Gy~m+e*ii@?7_lL>4eh3UOot~)UL2BbF&*}~(~Me0=C$=!*rQwa(d)m8cd;GLe3 zQOuZ|ICOzp9XErCRSNesOw)5xmb(akDMTkf88px22bYY0?`B=axNl7!YxcUX<{4>J z=^41k6;-cv86o9yj`n^|86Ps)0ag`JXv9+XPgwg$%H&MhL`2%+aD1&an$XD$I)bDq zd(7=;-7(^2@Iz4+#P|*v7|P{!iS0q?Fvq+Fa61j4I{G^NeKUL5hfszgg{pph4|)dt zC=WW9FwHzQ$K1?nV!{F7s$i?Lf7|09A~+E%cYQ=_o2}a@PpW{ja}TeueUv=F-3VcV zej_%nl)az-hO|c2)WBV5N#V^PPPx|#Se9kUZ|m^rn@=xYJn>94bw7P3z%oiL<*E5` zhu#O|eXrlhU)dcZ@Pd7L-p2w9M$VwwDvKeFYKU%?Skup3^nkcJa!#N%+qIygmK=1NrzoLCleA$G9Y`dxBdLiaETByjBrzgMnnUFjv)|h7My?r z9n1={JIG`;YUMI+Wrg$wxGU;|B9xT(C%g%F{f2*>x$rV6;EZF7`%sP$%jg6!UaR2VeH6y|=Adhe88WpLL1ZBDfgk_LG?Aw*C?hW#WSxstkZ z3vBv=qXIJLPy;5tdzJn}&vgsvwHqy(Etqq(rQaHBTXS_JeD*ZnQ&l4#I^;VRqpsSu zNNt);t#R7nY4#1(i)}-KsAQI~qjlX>7~o~I$mIrBVkI(rL-fk`xR;9&WEXq=1-6os zWp~k~^M#AER?AY_v7t_A7IF@lbv|@ZL2AXi=t4h4NH71aC5B!=J6N(OtVfEQil@{Y z^S)5E6JX;l<>sAMv|vke!v2WXFyc_QnW3@2oT^&iyL{ybcj39q80jAVt+_3}bf7%) zWPmk@glc5-lj;uFyqjSTG2fv_cD=uN>_N9B0*%yX`H`Ni* z_<|WQr1rC}JLXUa4qs03qFv>FW|U_AO_|$!KTLvIcJX$k&OE5Jxxi8HnyCiKZSF`_ zC(Ah_&PW2yNT*8r2pB|3EcBCzndksSBN~LJ+EY3&5kspV-toA^e7O8Yqp)r_FxsEr zwE09GNP@7#cMfACxPzc*8&!_+JENr`%s5Bzz;q({0XnxB%z@>x3(o5yhv@@;&$h$5 zu6Z^1Q=luF`kADw|79Eh?`E9D|9Tt$=RTrlVqs?PWMV95 z2rzMUF)^06v#@pghXb#;@dXMDo_<>`Etmvo$fsXVV(sWvA!>%w;^l~QA&4{{92-#= zF_*UWnR!pV+Sth0$aG#nGG0WHX2GIJvr=>q>2{M@x0y^_uX|I?S3s=tH2C3-+>9+* zN!S*xsr{8WwnsIz@>nIpl0UHKCq>_tkYj3rY0zeoS5=G36W$Mf^dls=9PP`G~I&n2#}dI^Ol)`Ow$#u1gy zP4mdX^yCUNGy-9GF(g8L;u%#hPOBt5l&3JnViK7sDh$B%TlHlpwY!{mXm-v47Q989 zt?f3WOZ;_ybiihA7>S-8$p4*I)&9Ht1K0N77pI#5dc5DBndB~$Va;S=bTTOIW`lBMA-LL2 z6;v&j(Jh>&dLSRbe=WYcz&9cAuf>=6FIzK}{_Vy0UquYDyn&;Ejmejs5p(_;Px2qf zSG5y>)|UmWVdeLNYL0xGyED+kfEP+iD@Sx$7q(^;HI;+Gg zu9Z^}BPWgDDg|UHDAqm*A zPxe?O%-jY0#W>LHheM~gZe;FjF)ZDbA*ED2;%I{>H2GPJlOs8M7CFxi+S=&2Hetf?;9Rf}FLd&&$yWavB@eDO96Poji}m z+ml%Qr zRI6@%idH6vi{T(Ey2wGX{~WJvjEc6~QN&Fx=14UWom@F2Lz`Y6>y_||+{2_NSPkHB zpQ_NWRmy8`Q-?AGJT_?105WEJdU)Ppd+t&*$!M0J#VV6B=OIZtQ|9Ln!77x+(E>`Q zJ40@&eX~d&JX1YjmN7$ zQPx`vYfO6NkYBY{g;nQ_Q*HkA{OFBqJJ!7guE*g5MDMTtQ5X(VuK}AA-rxgj4{Ejn zXSoTx*;TyjggFal4{!@g9~<$5_CWCmU;Ge2y`9Z3V~yH<#~*ydDL;IJsQ~4w_0xnz z2P$jf_DH(1{bMBpzA%N;L-C}F{Rnx!DndO1_A?D9Oc4@od`S{Y-vcjjPAH5bDI@?& zt#u5Iulm2z-bcqi(u;biDC%B!A|{&Io*dMsMq8fm=63{YYiX}i-iO}`IM=TS#ssfc^xLW$Kp_h-Uw4{ii)KO1%g zO+O#v#?{q3%LQSUjyEu2){gh`pTI26`I!bJ7wn&B*%M|EoTCBI4H$!D%xb4*zleY)v8QAlJ`_fXytX46;9((`WpAEl<{RCM1PJ6^^H{Si!c*M ztXw3lpIDhk>!_%^QF)hagE>1ORNaeZzLuHP0$0@n-)B3HOx@PfOs1^N-*LaU&&@{C zn8@;Rz;3utwuS?*RTmChKzt2t718Y68qMH7n_oDD1>M+t!mMgm;OY@?9)Q22!e3Po zol_<~54`K^bc$t-b?WLdcOGRXLKVq!B;qW$w}1MJhuqQsG*36n>vGM6GNDiZzZ+q)CglU($nLM~?{E^xlTc1160F30nL{!JFv zq#H1gpu>T|S6(qr>AXi~AUd|}Hr z{5r|g^3{dOdtQdz4-tCXL-Vahb1^6AQQ%hQaYe%&@!dR5?oz9Dl+&2Wo*@yz6zz0s}NIJ~%dX0>XjJL7c1<&|LVS-a|) zxuXm<2GfzGuThUo%2i1;X-)C0yHE+vyM({Cj~GLM$5AI6G)F<;CM`TeX5c2_yw46d zN;^~3ja|~*)O@BB)2B<6sgx4*$X%ET!+88xT4 zIKpG>ec!4uP!hz5nAUOJ-fVr}+#B^yDt9@BX77#*ATfc29mDDY{+){spS)U^8*n^j0{rj;vO-G&9?itah?Ri~Es{j;@dc!&zr2lx4kq)HN1r-MI%c zOA_FuOzMijT1cHFv_XO%egvIhD{RLQ+iL_EHUfx#1RU}}9Hke%N(KWE!Vn`+MZBW_ zUOcR7Z&qa>rz((34aBV$@W%1YU9JlF7qkavo(;}E6WZP_c;}q1AP`>mid*oUuCY#D z*pvrXzlsm?Y9r>VYD;m<%SbYbO}gSaDTPo;7SNJq9P?l$CFgoV?*#Hw!)`_2pTA(` zqBx?m)VHH;0P*i&<-g9!|Fe)5a``Tw{|!?T%UK&Mo154sq#28lmPS$Of;0IJ)MvPttMurBq$Xq0Z;|hb>kam*(&wVL@%rcOlj;YOI$RMR zUFCiWxS_ko&NN=T!R>&2K((%6R@%Mrr*QryKS@y?=lW<1{jj7u8VKc6mg!0Sjj8xiRK; zjn0I9(%LQi;smu*7F)2D)L|%vTRTk$6|8*|G(j6_&M>>s%g=`DQYx$mS~WGstVNfS zj+BYED;x$fECZ@^3kylMu{+sDux#BK2^Dle4=W-1;mAc~sTxt0brap1r3wCp2W%-d z^PjxXtGY-(J zZ=Y~+FFBgyGT2qo9C^QP?G9t5)o)=w2*bl+SCZ(g7N&EJNA$!|1NIh@vg2!p{~2 z$dAut-f~+5v8xu$IZIx~j>-MUB8p5PxHW{^icyJe;$=;_iX64P67?P-50K&08g>{Q zP$h7HyS54e4+`K@&H%l_+@fU;`zQ0*BGK!flpmy@=M(O_nDfyX67!4KksZRQTk{w0 zsX3c)+8N~Rp+vtH1p=>jev54XM{|^XT~OJbv(_>-0fpup6tHbV@m^S%pdjwP7@RjA z{x)cz{gE-=10tf$xZRm)_=)1X(HpOjIUMFt+GZi2oBRA2JqkMP6~Xi!E^U=c@V=FB zSzyuW&u1n>$ppt;n-^Xk)+22cu6nJ7fN!-(D{Axb%fZ*m* z+E6w~!$;*{Ha|^NaGI5#R$mC_;j%J&T+nEuZ=$iBLs4w1I5Z_NF)LcC5F|*E5rtE) zIFcU7jKrJJ>Hx8_9F{eK;@W(HYS#6dL{x?@ZCt(kyh5O2v&EgTFR`4LP0#pkN?UR= z6{TrFnu1o1!QgaKty1skby~x%0twh)y*l}9DlJQa@FyKs*X)EmQ4-qT_IMC)wJ!+N zdd%$<9R|8u794%0JLixQgGo2qb%Frpy|{52OKfx5IVLgEuRlmkl?tlL1<4>rJo;-c z@u@CR(T3KHr2Mr!-P&uDQf8~<82cB@wf3LNOBXeT6@C$I0^=M$KYt)+aN zLBPJ#t6G0%q!ENFgNZ5d;ygjya`k<_QeKz5wt*RH`r)8FL#9%Zmo<5kGe`nL&9^~o z!3b7|`(*xb7Sf`kvo?ih+c}_w>g)Ul%9JuSMo<0z2+C9zheETa29F1+tT4qnksVdz&;XZETu_KrzUJ<_T3m=(|%aS%7 zpn0EnU^eRAl7_UJV{E|?F5-C1#>;wj+W1|~wY#0qe{K(e4i|clz+3g)oBapS7SNf9 z-VYjc82u(fHX}xVaLo+|Aa~%r$Ag6*ym4cI?$~h?r-EW3J$nK1PeD5N~gtGf+v^mI7)fTWu zbfQWlJr@YK47y@Qg|dLMSS=+W*H}Pnjhcr21}rd8!=8q({ricx+=j1(-@kp5i0;?# z-qww+-5sr8=g0N?^gl+X9{kV^rpmkF$-!VIU2X$2GTIK70$UQ)xAw${-LLGA4lz}J zN^tF#RjGUZF*(kU%;HLDQ2D(kyldB&E}40&1A>oeBq1e`n{h!UyH2)>eT5ez_wo!k z7G^lqHFj7Oc=@NV3-`VJ@WQkPZROY;UH?#Nq=vJy?sk+6C~g~FK2Xc%J$zOXE(IjG65A1KDi?!!WSOyl-( zUQb|R*lquU-3v4`4ey$HyROYGJJhVa=aIR4=vt??hOV%=N9u6TN-gROP2mNnl0tyY zg37y?ulN9OAdambfUkhbZgFpJJ|?f}@e|PN4z-hfMVC2l>P ziL;g;u8z1JQH_Rc_fi|U{IUBY$G*i6ucQbG6YS?%aF)=98DIL zf=qq6eCBz$rv|NacW^(PJn!=P1@5Y6bNs5ui$}W7)=myVjaU063Gn4Mu^ewuKzymp zvpc6y?#=aX{HaAVN7wFwEznwv)XELe*Er}guct@3r;j=4AwBpZJqMt#P>4?)u{*iqJ33iiS*wFEX!Hy9Il_`TMY#yZQT2m?k*2wxRvxZljPzgyzbiF_t~s;1)bB z1)H#=kHlu3x(3T`!Io(uIH8N49kpaJpgn?ha+oomLArHoWfGK&5VZ-VR`sK-nNOlU z3^i=)qD*qZiK6Ot%UOt`CAu|iWYHI_Jk?=K5k8$+mnrAL`>Q?LirH$f300)0OH=Jt z?Tsaxq=SXcbTR{t&Wq*8XHsn(-a1(~s+YPCmrt5Kv#`9sm?xh(eR66NeZ0mrQU~8- z=RIAr41XlQ#ta~lDZD^dlFAmnKg-sDvUnEpXa=>2D#17xX33Tl~V`9n~4PEBY zj*T&yV_q*~li|Dwru4}03s4qFz;Gi5%B>ROx0J)#&Oyd46yX%HC6LyXj^!@t&J zBWQ{oyP_v@7-?T80Xzg@C!HL{duiFKF3QMagkOfv%$OE6y5RKvwRvFmVZA0;zGr+4 zx*TCPgtIR!N0M#}{qi}=r09cMOM)VbRDun)JO;JIJkpH1BGp{hR0phQ5VqwpVu>&) zk%KNIsePKDHMAXG5X-K{kJfG&v3O7^Ye=C7(j!RKilEQ)&KS2L;RJdhiB5QAB%3qb zwy0EbOgys@!FYT`e@UV;OT|5^(Tq4j?Z9J8s4^Z+T}RVYnCae$2|5y-e$!$Xu0_4A zr|}Ea#^IWrVwbkX@!4Cl>p+@C+Gufpy4R;RH=ojfp$_U$zPu0ntkk#JF-kr!f$aD) zK?o~|)~!qC)}WI?@(Fe!&ygN>wlSe8UIm{D zE};3P@f>%tX_LUT{#5e_!rgE6;D#o7M82IU&@oL&tYIC`VV$Vepy9Yq=z*@-?@x_S z+h)*5eNc}*l#P9A_nR6wktC75b4@Yuq&eg-CmHZU(_QCX_I})n6qGKE|C2o z_=Ubt9!b{Rjzk8J3P8uF*#Uu{!uHI+mv-xgURguerr!v9mUoZ+8NBptaWd34{|)f(t3>D~dj z&vaYp0{CtK2+KEmQt@zjLPQx@9Rsm0SBox?ZU)_7O5MtI&=Cw@Km20)`ron{!PCz| ztd<^qUp(?2dwG7}UtYTXP)eUH0Ak}x5F+?^Axo6fYLnhxZ8R@5E~Ji+siLHmhMcYg z-p{4ET&(D9MOwBDz}sNKP%FF6$F0irBr-yId#Q~yI=K{?Y@=4^xohUs5P4gauB3$)77+uLXJctc(kXFxL<$yx9hVnT>YyYzr)BX{wCFk0J zIeh6*p1sbcPGnl0d9&y+KWL)8pS*P$7BS&xAg<>LmJoTh6M9R`KlUSp1!FR^YNLU! zET+R19ikXxe#oMQTW3*k?#YjSm?bwIJ1%1U)a9|FgseGyrS7+%EitL07o$q?@NVO)w~Qda_TC_#FE2!5aZ1(|3S}X;aXs7^#Um zwOl>Xyzgc|Q|;Wj-@rI)=RG5ZA}Ml!rbsiZ|3I-lUMRiv1;&X^;T%3lY_G^Z&u@)M z!fZR=#n||J~2R_ut;# z{|9~Y@9LwPmKxR?#*SE9!tn6uuqq)Une6p&Vm-}4y97}3ut@KoVGsi-(&BIsy1uqW zXtXH$BJ*o&N3-kJc4mwFT$K|8^#L&zorX?T-7h|eR}Rcz;B*oreT!M2Tc6%XpPw1O ze$xH?`mrbRNfz4U&JinSudxdK3w$F`_ z&0us?HeCI2C`{$YJHU=q$6<6n!7)(W-q{tufRBJ%`Qun0u&7 zzy)%^;WWzfh@F-HFu;h0GGkC>>~QR`<;o2rQ4!HgHCmlOgZ`rI>H>pcIJ-kty`o&_ z+9SAwL6>oJ6&ZUH8Qb_RGx?}aBtg=uE4A*Y=qTwM&)BO4MUv9YHMO@OEM;b%jJ~5( za4_ttx2|o-q>87RXz8}~%Uf>E5%5sMUpSDq2juvq+T>E9jmfx)(;}IlJ0;t-Lyq1; zdn}>WEO?}CT~atHk!{GA$}AJj%~j{~^|`Fq77&=!hSn^%(}`2DU?Dx55y8tIJ35L_ z-=`hg<%W&$u3&Uj!Yc1M7kRS20!LuDe9{IWZ2?Xy`9SuK<9+Db`|GRHF87RI1puNyN#mU{~zt#INrn4R~72gXzT2U@^IORLEb5F09sb zFi2SggO&n7iRnOU5)D|rDDmgwO z)4OMbxjlEs!#jI}_glM%(_V7GSpyDj^Ns~$^|FfJ`X~$aJAY&2MQpEkN##;Be^VbK z=0*$H3dqby@$JhqO0e_OV8 zOHzN!;(Dwz-#0_Y@{s#<33$t#T)kGbQf&DvueWV`YY!F6mk8l(y%RTp6t@o(gW1C& z)P4W-4!w^bcOOj#o`#Wx&>tw?FYXa7pdX1^%Q#n=WQpu!Qyp#({-7Ff6rpye(Ja)& z-^9ukB0zde2AJu9R4_veJdT#Y5$Ql`WNFqcP)|aC5^|r|kUa#4ea0?J*H>+VAtbQK zU6R6rRGZRx9pd8otQX}P1fakSuVf@ha6APveSO7ry|w`LN~MT zVN)NtjDaW<7hEY?L5<@G%C1Q)7Nj5E2S;5b-bmA#e7k~kBWkrlu<{!8q~`prtra>-ulu)w?2I%`aZ9><=&P4^_62oUi={XO`v{ z(;K9xW?O}#%yp@rA2IpDRjvsS51KLK7#L^auhdsO8S+XQFJD*Euat((sD=kge4~Fu zsd)L6xddBc?e8rmNP3|;MWrsME)bTJ(OA7gZL(}4$b`NKCoYIw;Yx>6weSSpiVmZ- z`JF7z`!&Rg+!bhvN1MXZ><1W=WAJuIgAoCL!@^^1Ske{!D!w;);Rc$6eHAV25{Lk- z_Bd0!5w&S4y``bv0vKDyZ~qN|RC}|1yNJ3LwA1! z2D$A=Z3-i!0?QQ;(dYQai@-)Z{*_{%Amd)yR3`3P)oz(OUZJ_4Q*EsXwc+t}2ZuGe zLxRuPsLLF{pHA(|*dye+cQ{m+T&n7s@1dFXo^N7SpA^vyBurOB-Qj%Y4<#^)JG|q; z*!g6)BSq9m)ObRBfBwPk%_WPycYS+x3jS7R(EXpBlYc8S5dV99*rF=qge3y+VP`>#X(?z6~$m9q3^+T;3GG0DK zc^2DAQYA8O5)R^tnlTkhFa#LKwX}?7>DHyH%gopF?a<~2hc|Du!gLn8kS)4Ix9tJ; zF8V;0`&2&$PajX9o4qa^6zBu#HAOo8{SA1e`&>T=&@I-Rzkz&@~OuVU_aKpY`#g8-q>krUsBv zsHt}a0ddsShekko>gD;C1|U_StJL0+bJW#FK?P5I?AH5)tTft#sR1@nT;&QgPgD-% zmS>LFdpP|v5c=ik?=~Rk79`g2^r*=E9DkyA2Mrq2{$p7Z5(krG~& zp@kZ?c$b+MGyG_)j()Z%AJO2}hEq{8HVditm@|0j7n4OigyEhvhv_}n5%7shR^R)# zfs_O~EpUm)06 z+3c1j1u@&1)dlH@U4b63CFr+@3|LmLS23fb9xM?gxfB>$@ z*Tz&(lw{T>=GQV`5o#pBN^-h8B3}Ad9dUi^-&fD0hn_;zavJn|=y^X*g8cgN_W0`C zUkLcoZNz9{lX})RysleTU$0wGKh{q9tbyE-GANnz=i)@WX-eEa&&K#!KpBX`tX9JJ zbvU4_+~?vbyY*rahJTk2xS$j{_7a3Ka1bkd=N|~6NPxBu(`Pf+9GCZ2mNju_vOan& zkqbX|=Ja5$!0@>B;X^J^>?}TRw+ef%!jtSEcFu@JiEg5nGK}xFG!@RT&d|RZYMoTl zJRAhj#tEkd+dvs{a4I%SdMER?lgvOv2(2@O(rwD=f9JLdIzdl{XY50}NEqBj82Tn? zF})kcs$wRYYR=6}5IyPWDieE$_DiQ`p|*t-B~U#K=E{K57@%)sPMn7TlC5kU9$I-7 zpc&R5+q=K2y$WXY^$rzeWDKaUO?7)pI)>cT`4Hf0hBLiQj{uSZVT4|aIeRBX9aqmV zC7D1emC{>3>?7Jh%S@p36pKZ*j*B26XWC{l+HqGYMmQJS)geJUOauQ$gofKf`x25g z9$rLjYd476aX;8DoURv%D6_6gZ;e95gU(4MfV^UYY!gP^}xW?v{x0P8f9TF&=?60m5{D@6CYw$#5AR^`j&uYwioTO9-)cK z;t?=W?ZrlPVCoKyVDk20OExR|)6{uWfCRLJGYOvgk|`0+jU8pnkdmUPxMj|{{GQ&% zqBy+j0!H9o%8yRRi!E^8oZ6;(SN*K1lfgVWXP}l(x+)gp@`{DRC@0w|ARD`_;OgY% zXu`p^A+jXb$tFi+acX&rB*`mCN`(Bl5Xx{P5~0ubi!i0I z%IncZ<=_(AzPAwacb$rNN?|&d)DnFnR~tdq#*Qns_qibJ6*R1Fd`0b&%t`DHc)VK{ z2sr}_I0B0$(rUZM7{@^0-slu&C`7cS===ty`wftU^E1E)?ihm`ny=#UX8kKL&43>w zKA(|$5QX9wy05^BKN+I76O*Dd7ZiT=-btw5CMyS{;=;`G>88^NqH3wBqZ8W6wDmZjT2l7;qo0OT+}yOSsPdiV-Y zT-~)C_Pii`hXeXTHUU<4POV-f)CT-DRjpoDYzu6Wo`Ehh??0>`jqk>{#F*Yy%W*JJL4G^bnHJ-VH7YRnS;=Y^mVr9j2lDXbz8ode_Cqk#kE9s_jQ^Ekc>8;-te8j2q2|ZF$N> zC{X%r7`C)ofJ$YeY)ChX*%Ut-7ghC;Lb?Yf4L~i#Urezk9~JWao}}o6DFC5J1^p8B z0)~ugwbKms5uNS@y)%r?WTa@n5ZR=%@k<+{2*q4J3lk(pN^1gVepeDt|5}n!`AL~! z1W>o_ww)kvDXxU_-mK)}bWlw4VfZ^Pu1znrw3O4}R5DhKy)0PI`2jT4VctKWJ-~(C zc#mEYQxw{I5CO=d7#bTyATA`n2zW=j&S+dml4#GY5JS`NyJtxuRH-1eY%lll{h2d} z>s+ThGaasMW+=cQoHVdQ5&lcte*CjvW3&P^Nm$01u`!|qkHs&#l@otx{7-!7HFK{E zrhL`Ffy0Is^GlI)jS!T@T2eC}!aI&~ z@Arrl-Gk)1hwQuh*mev7Zs`MF(}zH``$Uaz!Q8xHC}o!_ER?B>sMav*>fe@lgvj^- zR%iGk3gU=MSVO~5$8~{3Og>TUYwLP$Y2L)wlief6X5LO)1C?t!VK%lw%5@ZX7elvt zw*sztRwWH92}=SUCRq9V2PNFk-oKpT==Pc|gx@vI?%y`){P)Rjc{^(lTRR&I1M7dY zRQYoj6si~>0Z+jHI^2>_xC<}0<#e)3eMk?^;hT_pfjL8fi<}VB3d;@w#5rT!I zczbb-yBoGrLX-#tq+Cr*Ubh^lxg9xqeZ5~l=wm)8oDWqIA+}}l(*%(ZDKw8(=o9*l z0o^bTwhAx62l^$UD?}8Wf@gUeX6Qc`+qf+vBb|>^2~KFHUfRiQrcBVu`;J{|F}5o$ z!#F?!vr4Rc1anvFR;GcE-#nX49jA$Q%l_L z=u2)S;*nF7plWR}+bBI6MZAV*5?ZvK)K}+uoJ3!B`ZH2Xo+8Y8G|GmCf!MKlVt6=n zbep@}F)*+493q7(vh2!@<||h_Q8~i%lK@VMYJ0!*4!eS>SSpny8ziW!HoqE<1MvTehfAQCDPcya^?jmXK!WV6_00#Vx_^tm?2#h zu>!ahJvX-i7^J3zA=t|@-IP4H_7olWcT?N)eOXPkCRrJ#`FVP;wE#|My#Y&C1B5cT zmgTQ@sC{5@^peY}EL!&Wsj47hU>^BCW*&#lnfYxIC)6J2aLP7<+ADy&pSB@C|!4ctAK5DEs&^k@gvcgaG@&gwf9U z)QI~=fH_d$V3_+h!I7b~CYB}p^^t^z0l~eWY{Ggt_^E%Q#jj>whj}}BTjvi2q&fIy z*bao2WfQ~fDU!8GolB^)@F4cdUJ>{rKRRb}t)*;Gi3)f$v`0}U<;T^8jyxh&S4=WH z$vDATx2(sT{h0u;brjoChky3Z=;L0>Pm}XV3M0FT>p!sl<8)gsLt7mC=Fvg_(}VM0 z`+1oEWiTLSXJD=DVgK*L)N+(>|8aQn#G!P?aGt!8up=Y50O@3e>xqH`FHmE|vupG7 z@k}~#FZR;vh!y&!@Dqv_?Kk-)-}l;H$oEdOcCfX*W_!)`_*}o@<@EuOA6Ni_I!YXU z_gxzq@Z_N(3GAG}++cqb-66c&x#b%+T7ote;rh)I3-gP0D*Oc@+d0-LwiP88D>% zf$MCz!2=I1h*UPLI=+t554-Jp8jilO?K5#tt-`)HvhC7dxwb?XSD`!hx=pTlgLSjw zj_(vGiz;X*bH2%gW!`91X4E!7?-Jza_%;f=lUqCptE{5HX#uE29y=5EUbW*q*rK@! zwR9irrqm^Gq7>Vyfke1L2y9B|H(s;>igBlTCR+7@gT#~`F)e@x4+%N+)899il(&{o zloH=$D*B?g5Ih^{0RFL;M6JDCN^htSCxZ^zRn|fuOAMhd)vy9l1Bsuv%F9zB zR%*A%4>*KQuuLw(bo89U4e}A*3pLCuFYHCc1%KQaj5iho>kHwtury$R?vyw02Oxy> zPK!V~u4#i#>cBL)lsg_P$`^vZ~+ZZYf-X00`WDpOcD zh=%Tk!Q>kIhJmOM&s?Zq|A$JXL5XwFYm@@C%1ocEuS`mWu+&1$O~N>}vZZTUzWO)y zjmYz@TQbiN-@nd)V!IV$i|?(x`nQsh?7zH~U2H8}4IC{DoK619id6aExBsQVd_;Li z5>Nn{*QmAX#SBDX9%x-g$i0kExsgO%@@pHfO+d`mEOkR;05^ZPJUyGv=0dBXK3K5e#m4y^b9m?hr`j!~DshJXws{I_@4d(b z&kC=P$RM6Y@nOw0Z}2E$Guh(pnNkYc+$b>s6DRIiiBLNN zbcQfTmE!n2M?3+Xilf6uwVRHcZEAmLFOF{)wVNKwR*1Bl65|xBi{#a5#vN_^g^F<_ zackVbrdOsoJBQ;}$o_;-)+{J)q)#%N6l#{O zCD4ym4+-r)uZO@Z##IObiaF_;F@;{AtR0|{6UP6>APe|}^w0zbCziHJpCV5njt`az zszwjs8Lgm@#d`Xk98h!L3&RCpr=yg5z6JF5*OD6Sq`9blcdc*y?UMfMaT@>UlKvw* z;J>V7&G#s@Y!#G0J6%~mCQTNZwvRLf=S0Cf)`O%rMq6|+KJmeb5=ryH;!x^rTXk7B ztRE#G;*jBjG!LjAFFGJ8_?(NYf|Vx1VfQ@rgqmOm#hm0!XVFaWV7>f)uUj(Uah6dN z({48%r@3CZ-|w~AozJ6dJ3p{~MD7Ct8be!c{~B3zTx+3iAgs`AareD`*A~WV{zW1B zLjFk@q$0?z0)EYaXh01RN7-l(dbGn>mNJ9i9`#6T9IGc}@{P4>(QL?vN$m?ka{Eh> ze@MqP)pCa#Tz9#!>{RvBkn$W1+x+c(HxTfb&=Z2=Z&>HUPvUQ=UmbS~ey zz&Kl5odEG%{Jlt_o8o=+M-YF7NJ| zlpe+`ESOu5n@4955t&jhu_MmF(pWKzHAN&0KPQ`)Vs1?@rzgZ>RirPl8V`rYJXLlA z0C;6}tiY3BOBP4pY>($B+{D3>N@Q%Aj22D=m~$4KfE4m@C69wwb4lfNC>u&cjAO>6 z6~`#IlJ$wN0J6SIir)ffH*|{t(%|i4@xBOZvt4@1=6nXrrg$-D3X6%sLfl9hCsNjLRiL5F5>?1LXDhB# z(_mbHy&22&w>p-0eyr)Hz1}1IV~nYm~`N>lQxC1 zDHQ<2rDP>^)R-B?&f9E`lJ3GG3XK35M04&ex`D|wS~K^EO3SSDC-aAB;e_$nawJmT z^MUGiDe&&BrzdOUw6z{G>HoS50CSiCv)C+G zJ}6wQWd{D(YSLAqN@YzXxuA17E*O{2TX(FCG-W?9H4)8#8cvajHH6R2X!4R@v&-q| z8J<=cjycp)(ypSnjuL{a7~?x2n2m9`*=ys#BFhK@#|hlthe1L$`5}h_Rn0W)g){@=UQnwm~R8&Pwo2QY}1WzHuE14yX zt+lV0l^%3jK8R3{vz9O)j8Kqz6_o0<(ro*_s`9sDRm^9mT*PnmBws6s=A+2=_V-}VM>2Kj79^h(eNA|Kw#z<- zG$)kEm#8RThe}kUFHtl@aQDF$n7d%mD{N6Y4q6P9+}%z zv9VUsLgJE2j(|_#ketSzGCj)YEkmC*YlO9s$#kkzwns9#c(KiZA4lon-h)1lA@gt_ z&JFT*_m+q<^%&N!IHK1&TBvJP%md!)cl#wOGL;<>XXOTmJYqxl+i?}&2fuxNm@f`q z4XBuFLP*S1+_IT@gp)3PsDx=+R1t7VB$hLgE74{vWg+F78WICAL&Fl;&6qvjfIXTs?U-~;n0k_u6-S z9?g#5V@i~2Qa)a=@vS0Mg_KCm$s5`Sxj`NWHHAYOCm>Ch+INTfkB!h94A+Yd*OTK6 z*z57J%ORE3WDmHXTd2X?ef@s{r1=#P`az|*UIh`=?}e`xtIYS1IQIs-%4bNDlYzCV zj!IV=chYAmPnsi`swK^8Z!pf_EbK&b4Q^X4QoiDrf|*dN%>EP`D}51b?~|y@=8u;K zU{oOzZ*XcH}?^j{B=gP${i9o-var~Gy4ieS6f z(;0Ee_BeZe@Ox+G!v$(}kF|N!-$Uq?g7FX9Em-e>e6SG(d8v!NrPq%U6o|<} zlyZ@6e`S-W(t+1~mXIgVLF94MNFMhMYhwv_%+Q`}Wfu;XMo?;%l&h-9Ru2Q_wj`mj zfwNtf$E+}g8)hdWSe?>iU<)K4Ierj%f~OK{`^4~!NI8W3h22Ct zZoNg^H@Ax<4AR%_RlWKdlc({cbDrf11dO^*Wd<3uzDtYgWwuT8 zJ?3tDcSz^TLI7pzvPXGtSO{4?JMX6quzHo0Tz+V|^0mUWd7PAcF{K2rZASY@=PWN1UWmY)NsgH^jQ5@7!aN+A zh?q5#%i(o0&GwVS>}5JG@0Je`eY6KZP#huwmLRx_U>qGb6?g&xur5zcOlO~tWEkEz=Mvb#_|vv zM^>Y5BorN0Q~NUWowLp5#{A-tr)3W_w)f0_E92+$igf@_K~^Wz#2xpp?cES)rn)J( zv{n_S5OH1BX112b!WBucVSEXd9ZE+7wQJFBC<8v?&<{`&v&>8$n>$SzqNyU*F+{9V zgJ{X#S_=GtD2T2H{^CkfAqyD}e^JJy}Z$3O?RzzQN}wUS5L^w1pRu1RCY^LSlwN}%_O zu;#N^v?DNf6$+PC08hgtI2urbZCY;iX}0&rM$%w^TXr-CzB~d>)$3#{_BkQe}cvaMph=yq87Hs z{|rAVQM0l~T0{Bz)?*?~5@Hf^MAp#}4XGmv^}$8bGt;aMFTel>s~`*#)*dz!R})s@ z7J~&BizSlaF~76-=7U=u^prA@jWEs6o;V6}nv*8tz9jwbiu@Rt@N#6gGMKM9)EXIT z$KfZV=e{G5J-ko1o#s%~_RpM=)l2 zi(lF^^dAYTrXMzT2Zh~JVEr;Y-}KYL;&j^dQyemK?{2;?u{ve>BW`AKxB=KiiwAMF zkDo-xz%hJ8pG207y~FdNw8=Hm0WyHTexEbyYwM`aBgd+aE{4k z)Fne)19y#oE?O34pWL#6@xNGm$KXt~t!p$L+fK)}t&VNmww-ir+crAtIO*87ZQJ;= z_kQ1d&hGo2Q@iTks-!CQ)bl3`bImd5m}8V1;I(fITeChCi^@;!6OGQoGFsfU;N3QH zv-qmJILJ!>k}%_<*b)I_xX0tPtvn2>NIk4uMdh3^qL;VvYD?UCnc26!nGF!4)EiYZ zW|<v@fY^e!x-_$sBG2m_UJ($x7YpXzxG}pz9NxNYIf$32W<$R zs%!HAvavRd8ayr7YmlL2%;Z5?mf>U#X(x)IR=~|`pej^?qE#E^CIUf9Q z6)(5B8QlIVD;v$cwz`fft@>7rm@qDEg15sG-+Nr!l1A!W!jzZ(9t2WvHU5o7@8@D| zrj2Q5Vf%iL7^Yo0uLUtU=vH=X;_H%`MQ~C%D;Llmc6QW*E}~?r^$cU;Wy5j{8ttI58f#LHGfk6q%5+@Hojb_HB_lA4X*q0nkjVC*FVm8l1dPO~sC#Ov?^2U?Wp+ z&nKIg_T1X|;G(x$26F+J@2nc=;W{1p8;J7MD6*=!==0`xK zDV1uiBMgs-&i%CFrF~kP>tQPk7p%-9Vq5Eg90#aV%}1|Uf|j4n!*+NIJ?xpdl%AFY z0;3zYHWw(jCyx0T$Y={rOOziVT-*$3!WO=wK5e2Y?s*Yb2eei~m{3iM-Og-7B;fYw<0tbQ7s3^jLa#;}|5uHM#5P08mO@L*YhiB;ky=o|? zlb%t$rbXOzrc3PO=zA{Zm0S2G(fKCnREI3khj@5>#}Nqp5tI%Pl(4+*+rJ|qNI)iL z#PN~aam>+MA>&G$4j0^{X+rXr9(_(O_HhP{i=pXb#?uSiWo(1R3&(tueMK0h_hUVU z+kLo$@Wd9na?&0^OTOD5WDQ_?RdnlS=ySRx$zkhyRdXwx6GX+mfC=u0hsNrlABDnN zr&kPyv4UpS6Tt0xt=_^Fpq^t9^|^r%3wTm>OG%!t%J?~MpslS;*&b8jTw5rFk`_9_ zSD1aCh%N{dR5BJ^8i|{K@A=j4Yp)ku0L#~YR4(5$*RZrVv)gS9b?$J&TL%x|i5Z|P zK$;oCN1mu{%&0A!TWIfq9fI#j+prnPHV4>?_teSghU;~E71iuzx5MB?Rk;dsMY9QexJ0`8LK6Z(Rd!&PTE3DyyvqKTA6czhd1hCRL zgan1C=$ybN$l(gK^bn}c+C_e)h?rjweH8VGCYx#CdW?2_-994gP`S+t!juPcbo3k{ zFI;mvqE*<~TpuAPMD2(}R`}!L;=^0sX`vM631f@G47kS$caHi9X;DS;VPJ+h?b{oR zd>PqX=ep~yetJyN>KofIYmMx9VqC?XqFxd!X4^qON;I4nYtiZu7S>OZPpX=i>SCP zcXgq#%@CT{JwBm8ur$N)6+_!Zrcv?Vkky44U2{HhpB(h>h{6sX0Q9Ni?25lfSD*BGqq;I%|+kXo5o31!ltj zbhN}kr73-G%bQtB;vlxRjBT;@|I;)^V%=_6k=E+r4XmAZzb&fOl*xSY1hZ4=%QPcTc` zFy>Rfuf$2VM{^dGflB{c^A6*bpqBfw#(pj*Ghj}RDpo{-zI-%fa12b&0^Us*BgxHO zn%AAKi`+a2D#BNyMI_2Hbcyahs97Udeo{ekgU=-^T*{8HRcL`x_k3L)HUajq|63% z*QdKLQii7#rC-L{#Cz)U$0Jg8z9MdVTn4%zi1-d9GzTh zHc=CT(uB|yds6FRZj94XT~g)ADn9(U+nFcyO#6@+;M;GXi+qw0UHXOOh5l&;hZT6aOQX$M3Idt4P2u{2cne`?~1oVsY973|ypHXFd4HjjcfbAxn$;&3g%dp6*+$-#9j0aVBmPk?Nq9G4vK;r}vThC9q~54p#B zvp7^0IUtn3;JK!3A#laB>cxBKzUID-6Y3<;%Bq(T)y43Ti@|}5Sp$CZf+8e}eTzW~ zw#@=3qma5G4B4i27b)~=yMQCY(TA(4dXe*q%$QH4Se|yThh(lCC>JewDW5&;pl}W! ze5gb)G6HQsVm@87TnFd_P$V1Rga@iXa>?Cc)ZaRANCoU=gY!*ik_(|ez?0k z3B#F7v_8}yp-#7O?Z|T67*Y)?t;Qnphq>>aOp9GzLk zhO{?ZQn4XG5dd~t6HrRn^#gDNBax28fLnUR6@gaFRjnHXl#WbpX7fJ@vMHX_R$pY<+2TNkbKfx?y(Ow0pbR zK|}>8;%X(S_M49Y`Mm{Wo%`dzcPcps^g1^s;FLUwUSW?wpI&oU5BGu%h7GDuX=JBRC8oY zDW?>)iNF&OUW*}^#WVWr*gW3WPllp&brBBsoF(q#?|hWy2FjYu&rPUlt>NA#qQy0}%&ZG=yj?2bnrLB|*}*gZ{XHmwIzq++VWqhZAOydQwB-ER8Bb5MV}% z?JyJ4x-K+!Z8z zDCqEZ%V9ARs&&{bKy|T?9E!ssvu{jn*ila(r>z1*YY)QN14R%CXR)-f%fm1%`Mm2h z3LI-*9#ZjHEY?yLgV(xA#e7}H8AgjvA|~~zjvs6lLYu!DZO@FYUs=ZNv) zMokiu|GG$m(P;9y5Oa;u1Sl=T@CmO9Lg> zRLb%TNM_!(?7aQH6ovRV8nG;AM?!+EIKx5RbR(oMnOPp39MMkBcY-S(E78m@4K8>0 z^$lN7Y|ivl3vyn=6>D!N2?|f|S6`)8Y#sHOx8G6vVMYqNYe*F9V!q?o_68H9pebNE zsaMpyiXag=YW?bnAida@dDug~8J$A;B-pMTqvP)$umblKO(~TYI``1H$r(|;$sDn7t3@o~^;-mwWxg|^ zcnP;)p1$m)FY_TkaTXDf$6$uG{A%!kZGd-9v#jU`XRpe;^8y0THVIk?0_$>cCR3HI zN`pbN$VbS*qcx`7l+&77K1MQ8u#cZ3Hbc)tR-};rftsFwT&}&O!Q~P0Z>DxyuZTFgCO+r#nSPK z|M2hSOh@FSC1x{;m}jW|2}Q}tpj_KH=r6C1YjS6w(k<%=^dPM-w8#q4*GMRfvuS~Z zP64OMXIK45G3@WHPSG5N=YKM49XKEpBYwiB?O)Y1?4&q+*b!FiUMOFh%xGA_xhf-= z`c-qlHbXHJs=C}q2X;X!Hw@{iVVz&D(36qzJ&URXSLEvJd<(*gNDT;2-qL{K8_KG` zOvtu^_`pQSxkO$@r=4dMpXV1Koh|6I?4E^y?Z!v=jV%Um5bbTIAnJpAhh(pA zmY0Z$t^$qo5$uoBys?nP-Y35dU=8`dy}kcj;O*aP#eX>y{R?LODKaTwYV=t^w*Mai z1tkd^tWSwa5*%KJ%(ff|np~-od?!hH1xPCae#`;q5+qXCs8HZ^bB5*`8}kX(of>j2 z-(HJ>2L4a8#B}QzywGoe^RJ-ZP?u{%Ob`JC@HI@I+^PMH3$BC50(QOwzv(x_&(+OY9~*l@xh_-YlX6iencZT6fl zjG52?d189AhwBN|lkI#4-t*E9Mm%S&9#`B`;1(^RhI}+SCR=sak0m z8dfZ)U5d<}?#eM5_eP4^&|F6yzb+{ObPQGu8JFX)bHD@Z?H_k{5Vo1Y2y54K>D}}d z1u>!sQ>5!_H4v{EV-MT`eQUuXx6;s}oT<)G-=7QupHk%cfrxo6=s&C_SLuk$=X*@h;~U!6IaY3P z2c6yyQy>g$#`dOWE2Oo-6r`r2={@a2Y{jOn@wlNdZMHi<*$!EfY7+*;Wke7m+>R=h zOmC?da+pN9#&lbX%A71qb)Q7LQwU~+^jXXz<>lAd9;pW#zt8|0GjX^}V)8XAD_69&rf@f;{3F!H@`CeJju#W(C6TXzDEo zoVT7xhoo-z3ScQaKBB1YDFYbmqh3~d(Q!OLcbp@n!cXk-f!zHHdMbyMWtP*){VoVk z8n+D8Dt2K=#gh|Y42*&*t8T^xAggt|1Yh1A@ZVbnqhq7acHl&CbuYmVZQw*6;Mass zi*IdjWoShFY+20eg_4A6}afGHh+LT$3fH< zpYwjx{J?bI-QwFlfIoQR(RluX^@MMPD|b&X{|LNrWfsE+0)aBX2dbnA3Hr^BJOW9~ z&deTRd16z@xDaU%lVq^3gwa>b9)cjN&&a-CH!0P)Thc~WW3Ggko8yXcRE&r7kTZfF z^-&xbBmSKZ6`K}BUFFjL+YcPv4BkHli`XZ{BZ)tWo+JOYf%wlIqW&#P{VP8G=_~PP zkdoCi``-v9zh?f2>k3J_)p9jGbHki+c_r^6@F{v*Tv(1)fcfO)G6*f{3Vv!_CPZsp z^CgJqR|G0Qv`^oa9l{V3l3b8dm-SBvwecr!PlwG&r*e+xLiNO*`GnFe}Wf zm0LJH_V^CO{h^~!Mz>ddqn+A}O!tvA6_YFoJMux1I@vghTjt658R&)7FjKm0PEtXE zCgPMY8IYWItJ3IYFZ%(M?AF3XQC+3Htr<2_Vfrx zqSv#A80?#=)%m2Wk`=?VB6>pvv_I2004blY+?HLc+7>!wpKyA%WtZPa&8ugkOacw} z8@&yOxjxC~3LCFzL+7O_keE?>M9JhoWzgs0B&3uL^B{%Rbxf@)T!h{i++jNh_~D*F zjA{9i9tZ_Z1)Kapd%Ao)NUSdSuh%vei*A=ubmW6@pZX9pKL&3R5G`k}1tz=Ub%B_v zJ(K#3Jn( z5FBk|Dm8$M(pBi9T&BkB@i_2H8^bIdFk~!h(w=$>?cK0H`O)&+1x#7$N)OuZ$lG4B zKJF230-Si81F^O@YTO)2ZNmNW1o~nCBW-@RN;&^#9r62|gU&yOpZ{(+_IE2XWg`Pe z8~gu=M1LwuSs;J5tg#nPjU$Egh4bYuix8}c{JI0aV-onz>9SCT6c1Y(H5wIp934R% zPSyGJ$8UCh4i6!go4}lO1>#%6&S+^VT+FGsygk3|kbWm^TIpx6V6iI?U6HCFAGN`> z=uYZhc)>mZOA}6jRV${M$fS0Z)@#aLBTHHJEYi)Gvl*sJF}Mx_v`Nn=ytnkv?TPTn z06lo~)SJBrA%+}LyfwcOvdV7U|zKIEUpzms@U*DXJw>aDRKd1bD+6wp!FIfpdG5aGa1Wa}+;O*ya~ zgSC~#;LMxMvy{{R9e0lk6y{t{nj}vW9wYktx`6(smSxWoucgGQl2_B?7W+7T(7|+Q zISG3azPwl!-ptFA^cm_KG4*y{wcrtA62%EB%}$uBxo-1zbC|`PH#Q~8evs$X&Ho%N z=TM1?@z0}G`B~lgmlW0SM@#M>AFV&?*Z+RJ{z|d2KR?i)G44GKNEh+qVcpe$HpkD z4&w#x4;uhm*kGJf58F+?sBh|lL13?;2(Ck{Y2t9?pBC`wcS`VN7*haahkkj2^pUQD zHkEXqerfr7PLy6fiB#`V8U+Jv5!#f}1Va1G z2bTA-)}DLT=6oDnY5J6)0;Py4SqIqoC}d&H%6W}D)EfOMge}>PEUx@pn9%Z07mYZF z&9mp4Z4oo82spUFLCPs8!KTojsrGkbm{HC5TT8z9?s!nHF`it7Jb<(&$fsh2hICHJ z18tzIycpN9coPZXHBun?4&yqBBjCl@HthBL5FB?RN`|dCH@v9epg2L=P%H|@8aKs#Bcjp_&1M2KcCHbK2J@#1bKK0 z5U38BnIq?6>sq2EzxOzwO@G`?k$ADHBEhTMgZ z73k0=k6i>T0 zS4{qYW0OL~wa+dP^2ge~fmq8?a9o;t?j{&fEFuNutv|nLm>|DKx;&VdZo|sTE`M#h zH46%ciJ`EpUB=ZEsncyAns!F)^c2SJ60i8{nw9C)FtmY-@df+C>djN@K^E`F^Bw+o zxi&NrTIs$?fBLaVtdtM~#Nr)r0}5CqlWn%}Htq4gQl&|Wsm}VM1DH0eO}}qt^>p0X zI%H$xn$(&pG@5PdR7%$e!!tr(@{_ruY8GL zqga4X@wu`vNyFwvW;nl|+>9{aKjPb{b0+hVk`oSYvBZSxQbsxWowJ@p(lv>*LAskx zPI+n5qUQF9xsj0jbPe+%wNt#HERI67je;&*jjDomI=a+32}4))3XVYyyI?$oXO6}& zswh&V)u~Bx)s(G%v7iY~c}bbUlU20ax_iIjwFLDiMENz@mHpFs*+6Aa@@T)T$!a3$ zAn|<3OXj3IzXcgd3_4{o+pC-ibXX{eCQD7o2;k1gFG-{yTQQxp=j-@7*VY$d7nZGr;!(8a z>c$mEWObCD9Y^v-Z36x-36i|{>ls`~&qmHFd;8Go$xLv?j4jx3+{|MQKaQJklt+H` zQU_z=wl`21o1$zJUW`JV-%nq?j>~n?FS3t*cxZ3pf!WfUxT0wb;y!nkqMv4w8V$rm z%l3ovgVWlw4l(j!PVjsmbY2r#nDF%uvw(B@KI6Vm7{rLaJH9$w^ngE|ob$`;H9z5k zbgm<~*?i+B0%eM2sV5Z-{H^#wqCSI<)fngk3@~-+s;U{NLKJv)WS8IfLxtm=x8Q;7 z=(6a;a988@E$A}Q&=4pVEaW{)O86bY9#3?jDAsTgW!PL&9VEAoD!!_LAI>Ha=R9D3 zwLCx;Xi#}wl7IJ53aBIP4Ma<8gOI);6&D_2gR>UafQu_{LG)0N2?HCN_Z6YA%a(zI z!x&naDYP&`v7*J7+hC2{p9p2A)^|~rU@lYKZ~@`h`e!*cMEPu zqtZMCQImJ~OGlr^dqV9B)d?)aBlN%}yYx2Hu3a+RvxMRm3RDLWnhux|D?~4S#1@?d zQ^^zP^sfG_%*;EU%t1*qaq=dw{{qDKeorT;5~Z&Y&yo&=Y{MB$$%JV7Br1nq36tj{ zfgK_UM_{W0aVw~@XVZV`X9rVkv??zY??wo5oHG?Aj zqU!+KC(Y$(#5C-y$B@$vbC4suDgyKiRnp>a6S@0~Nht8bx=EdY(8VmU%D* z$%gD5RheH)TTU}Oc93VhGb%=HIYC*!ni=PhYt{JN7ZXQmE>b1!00u;dJhcOyFZU}? z!yFr%(wQ&i(p1>7E@LA~*&=5#QHmeye4KGkB6FP0yXW8S{8_|g(INuz-Kye1=U#)A19@^&obfy zd(d<3YUv{V0y)XbLoBvvAd!umK6oGO-7j*~nt}l%7tZggR|kOl*avN&e45aO->JFQ zHnW+ELa&Z}W#%X2Z&IwiJDqPlXhXL$+Fbzeg=gEGrir+b)30*ownI;~r`U$ddd6D^ zrxeb;xM{)VPr97StNM2SEmERHX;*861S^`&!C#4wu# z-LQqHXO;hfQ?>O=_8GueaR5fLV}%1dz7;t(^}KMgdE#0yM}H=ACa8A0zeWYxlL?WC zK9jxEzoqWKCwzSW_%2Es={Yzm*g5Ih8#xHrSUVfp|39Y4h01F(8b;_JnGMCo2^=w% zb#w@~ed~(F14M@=i0r_N%KL#ZaOnsyz--loK!}dAYzHzyhOR(IgMZ1t zG`Q4aCW=0qGVjSxUDgaj9m@y>GDAiTS=Mfgmy2oc-CU52xMaURPgz!2-oTQ-XE}pe zIq)C>o?1sdR#wtYC3cyCos^TYaQg(3UZgo(>L$hSxx?VLHmOKSUs(E7VXpCv82=3B zD9{K-4DDnEv$3>w7y-Ny!!80Zg^`p-hGxuslE6W!`_oWzI~^gn{v@5pgOBu<5KD#S z(;074$NoHH(A0b=OPi`ZNg0zNGR$}>t&cOp62l#)t$B|teM?(0fzrG~l3P@8!lsnOtBU@_1{ zV9}QjHw~U)FsNF=6rrX*FA`=w2GxqZ7$tKbwysPrFKJGKYlJ#tl>-rkBxU7EGRPK? zG*et5McI}jKsp0f544#0)xV^c}Ean4SYie|D z=tXE@pg%z4^u0I;Zo17FF7?U2%NE07*v{OOy{?HWH+YWa4i8Bk+WDoDc35&F2E#SN>0|*&w2oh2$*SZZc zWPJm9vBL?j-rWqJJ8ph-*Ya$4^5jQKaKkQ$o{ROC7fGuk)DjWxhHO}v;@JOy=d~pb z=Gq|H!uhUaFugDpzzTjY#iM3}@7rhxf1wM1vHpea3{blD`wY!y{fx$!CZy;E012OJ zIlip52(7?k4{RwM!yP3|1~Kc>E@vv=WzI#MAKLtE>+hcOmJOr_#Wb#kb3PyIEYd4J zKz26bup`~2gg8m@UhgG~#i&=m24$>Y{UjfFRp@}C zV~g?Yz(K~CQbreAO0jmY(Rfd?E3VF#!SG0vU-lJ@cm6B33ikAdfyBK%SyrS-=Yl>`tl zG5|O@IKb~=@t@=1-zysbu{hSQa`G1*D;jDzx)v==8Mu@ zv}!4UN?&VPnnm3R1IL{mr`sVLWg}$U2IKv1Ks`w29f$EjcIU#n!X#TlZ!{`-zO(A# zePB1i{&1e{^LCB(z1Wr|f*D=zQXbu?)`vYpt_@L`y`SO=UOREjqSj4|MFjb4Wk8S} z$Pir_9YRo)0i^R_UxFn``6V4R$UwO*U{OW^ifV0Rk7kzqr7(K>WMFX z{0Bp+g_QZP0uFZ_LLsQzFqq^L4s}s9F{;$sC$bB+HXbA1+f`B)jF~fOsduU+O`_lx zE> zj3Nb8<6ipBoMxY6;1Y^USa8GnWYAH|E5u{c)Z$oeKKhXQ`?F=(SzsEGI~bwtcj&?s zf>`3P1>kn>=YxLV>V4g+lPDWwEksQlE6vvQP>JsD#kk%0ja@D3b48CvnoE6KA@Ap> zN0SazYgF@rX@peRAjYOgmm*?A(XxzG=EcP~lL+>3>zNgVjYm{PYWit7OTTeQXq~i1 zTg<4h&Q>UT;#tJ~n@R$(5Gg5c6BGm~6Mpq9&e{UHn)(C&AXiYLo5 zk6#_+;-9{d078`v3}_>W)V%d^I6NF7b;f3_ctOFEedA~JtYwU4rqnoHhRY3dMR?t0&2-+jse04^PR` zPi^fIS55IXnsj9@%IekxS*6R|uxMNHJ_lEA-I;a;9U-VRrQ5vdg%hvV`vxB3$Y<3q zGnDL2Xk48K827?_8k+TXkFZj7wQKQi`?~~9x!v}{hnm+pVI-Kf5obCP^E{B<)tSDL zQ++?y6HMb(4`3e5R?n3I023294ZI`4?6It-N+7jDWbl%S4 z>O>#o7S{Fi2f1G+Ls#y~*!PgU!)cem2X^CCgq`fwqzwR5k6;N!8YL~hwNoI#*7M0a zy)9T|xRt+xHUarr4I*!3_3v&QkRZ*U9eRFhB2z?2>&d8uNKsoPQkQ8Sl-?C1*0@mG40hkOSJyJ(D?1Pi6kl7(A-^@n%GN|>@$RDyJmCzkuxDGYk0Zx{@#o@e!BY6jaQhJ0lcB*Kb zE&yG;hXCFnX?M7ywk?Ev*he?9w5yYCF*mlUIv(1XzMbQ{7e$6Zvg|O|GwKRVgFV@1 z34ob(V>wNK7_A@TXE|uUSut^KZutXUyjEvWJ zZ%*ETI@#|HPWu;;4$Vwdb{X9fMB{F)tCYo2hmEhjSxB)#&&G!sM~X=5C=|1RVdHME z^b({&PwKpR+N(YV%sDL^fu9vr+@uM>Z2YmvT;oOJPoGN|{#oMvS7!11 zBCGu4MgBdr_>axEe+_4A*QN5m`#HU ziMpk+DR>OKFD%0mZo*tixE@Im1qfmSGnFag`RPpRC^XeM3y6O!3n6|PzndHVRPf^)9(PCjr<(dp{?-)WdWVxrmIL7 zT|1$pDY2eK@R5Gwl8m7ieYUx=$o9~MHbria;d__%r5D1u2Ui%dkn)R^Z7n}w1n%59AkRjb zzI|+jp|JoDXq6~MwOE|*sN$f)unOgQE9Z3R*gr%0qT^6|6!orfE^HTeynD3Pn?&ds zg9*##yOfqL-7?7LF5VYD$?RF2+1jwAJR)(%QN1S+j z#)|mu+Jh8i<1_b>ZauZvK)#*W+7v?N`S?S7iP&a1N5(Y*Qb$H`6k5?0x513D*TJkU z@$GYlouCt@7p`@}_75$W@`fc}VOIX&MRNl(=a{CxoBTy!nK>Uijbp#Zo$~Bu$e^){ zv7Dr^?7NjP^!ojD-n+^U-Owj5o)_sNxYsGU8mF*X#%apEIngCfpXzR%K!&r^ByT`O zL27a5CWZnd=cl?mfWy(E)LS0Cae~XQE=9M|61EM2{6af&4I&lNhr~|`N$JMxvhKr& zr~IpP_AW$xLj>K(KFFH{sccnF?}Mc${KA>7{B^= zUk5VzX3X5oKmpQQphCsg!rdQn^@ZBxQ1t?#u@2(Vbh1SkK+x}%+gn&8*ex}hGP%&h zrP3yJnN>7$vQv<;?ulIC&Kl%euYV4S8!;w;d3+XJitDI(~9JV?EVHHxbYZYk{IciY>UvOSj zwfVBot@8l(9m1WSgT5tTeOybNnlc_jubRAVXe_eb&Uq+nfV9K@dy;%Y-qJ`c-Lkf2 zj-k!?e#}s}`T^yZBzhIE-|!+yne%=?DkV}M$cbWtvm1_SVx3I!@S9@Uhd2K(?pt@prhz_Kz1u%-YQHQ?XR! z)9u;euLVhzmy*Gvhxd|ZQCqZx02Y;ycmgHn(+7ELDkxKArYNhY0GFjhaY9LBvG_n|1I}oLeHMkdqNg8t~3ywK2B*c=q}L&_zp!wQO^~1Py1&5JSG2?~;d1 zvZ`2AHL5O%3&LM8qetc~++-BUoj03X*?ldO0TEbA7Jo$-)v=${r(E;PKy!j-5 zIGUz*NTRR5aC}aDclvi+0%8lP6KnTMePkAc2@7BQVU;F6WZH}2oWlvlF=1r%UM_w$ zFD=Qimr1eX4P7`k3mvb)>GypknF(OrNyudM9uJ*F^j8I54N(XR%+Jk>$fHIQBleaP zPp4vsP<~_Tglax^lcASFBd(Y-YE~Tx3KwGoM!(P6K<{GFenKB2e}DNcR7&5BmF=_~#=1|G5?YAHn!f#V+YT zm@1K!trcW`VR@$AQuNaZuwR2>N`UL^<^uZK(dzoF(^Jo-WZ**k89#Q0dOw@f1CJ2> z$9%Q@qMAYj;m412OA$56m#+ z*wxZnS)3Y&8Qr=9t$K9LZW3K=<=M$=wxa&N@A4LxWU zJm%*2nAkoNs67zzn-`Qyxb3)=Q!KDXXop|Fzj*_zsG7DW)LM^HJ-ZlCLrdmf9%qOD zcy|PRqT>kaj^I>6&XS73!|w=bE^wTSV|r77L}vMjEkK#^Pze~ zW3tSI5lX6M{UoZ`IF4`FR%O||usbvgU1&;ePg+f+_{&cXcpm$YqWj$Yf zY_1i9hN{pN-%pkNf?<6fSMX(~c3x-&O{1Pg`GS`B5#UaHmz>GaY8bX6d;!#0P@Ve< z=>;Sw&e%>)HqQ~lA<+dWnVvS)T(!iuYSa9uPLDo{gH}h%6X@liO6KS*KXJxB&y>aA zs@=aQUqb&l&itNy{YGkNSCEqVB&TG4l2dd($tl|yv@Ahb@Dbv4L}Y?7;l+AZNpaS# z&aFg`F0W`fx98Ce&O^ei!trA`mJF#yUN`&gX3y_e*N_0k)fb&rKpwEO;0a2)O%vIl zvY75ZIrSp+-(1E^$~|?4VxCR+VZspmD0cDNqXM=hX1~Im2u(9<4$W^kL2&oexfjYx zDu1z9bBSh5ia<^_{#4r~+-(ucSvK-Dt~z`Fmcy{0C5U83`BAf;eS25uS&dppcQ9zk-G7l%tW}sw1wMC8>2IWz-*@ew>(Bq4i1P1o z;jiTRw_U7^8T*v*fFB_BK3#tHCGAQ!g^#B6llL%JtDbyel5SLRjwc>My$$?}Uqn1! zl|vB5okABtbd&xx@v(PzgaI(VNf!8q3@gv3IGJv*N6(Ul%oU~5B&?N3?Z~4O8@jak z#BUI3EVkTKX3ug6xpS@A%34s(cM#T(ZLhpQNB10p4Jxf|?8*523Ya>1TPrzvIWb!FDD`Kx_ zX!h^wq(pywLE-Z&2ByMJ)&_qhJAb|F?TQmJe=t{z)>`VTWMj=KDRRJ9_?MJpzN6DH zk=1;u46whA?C2xTOwg2Tgh84oHYD)hVbPoSTplMUTD1aShGwyV;>dE2guUd#f2V zC>*+_sG8hm>zgZo|C-k4(xio!bjFOCg{2CEGfzrwLz)2d6j#1ck!Bk>fo-wmFfv`3 z0+rReR&gb}dgZ1B$*Rd70Ob?ay^&M}eSk4Ph7|HkZn%ox6iQo3))%s4)zT931AoJD za9ZQu^1Q-MhoaqJRx{(G#2@NrPKB z7Ms5{(B}!Z#SDTS`SwMqg%8wPce)eVnnCeHgcLn4EOyVf(YVsm8cJzyR)^6cnUfX} zLp54+Nj~^%m`-e7Q48inbSBHs)RhKsQ)5Ub=4hF1b(1;We#-%eBfOVU%cqB`$wV=Q zs!U@tSeRNTK>E;m%neVE12^ zdGxbw&Dl9B3+rFIC=IX4&&2E!+NKheJ&k!6=N39TF9w|eXGfkL2YkduwX^4?<-2zYhwPJ0j|Pan0Ame6*U=3?su~Ja%)BQ^{Tyk6 z$}G|D7rGVb;c}7^Ya#Gb#2g^zr!yA-Q7IWDGmhy45X0O*%)}7R2b|Mzn7={q>u>lrxydt>&u0N1Am<%+!E^nSs^ zG;I#gVEpAvH@YQ!D?fi*>^D_mL~sdk3y>PT0O<0Xde!Ab7ZvnVCNr!wCh4{3wSrzJ zDI90)VmnI-zwdioDuv2bNmd$0lXS`Gf;iyL^E{rCgk{Bi^Tv*b#D$qVX@*^Sy}zUd>dNOF-K zC>yL2xQnG(@NJ5W7!G$JK?moH0LY$}E}8#8SvP!|Vr)JCH5p3+#{Z%0oq{usqIKQw z*tYF-Y;|ng`D5F*ZQHhO+x}zQNq2UyjXLM7sj*IclG2ih%@1P!=I01R1 zeQkjhyh}{M33W0DI~xa{`86+&)kfRrZ!2MOX|uJ3Sw4K(2EOZ>7?{XDt}dksnN=xM zL@l2nb|%(MPzxSglWW_M#@GR4_60ja8Do^OkE>8)=9HF3=o_g&rOMQmi&WNc!QHq2qx;L|K zGPmn?tQjh0_(^6&Gqb0c*eZdYn!A@3&5p7SyvDs=7kBQ(EoJkCFYQ)W!KRd!PZ@KB zjEmdB%hq+XtQhOlMe6`RO55VqX3U|}(JfJ&Y)KYml7ps%S}os=kR7++d9;Jxg}-G} z$K1o`hbc$#%Q-)HG2;t!F{IS`aoM{RR3ForJfdE^r z=k}qL*!Q`&d7)fh#`Kmw*Ny4U$e|c3Q`2#pfjtKtXPOkQ%O$+Wykw6W0J}gY|I~je)w9+dGI{ilB0X(N=FK z!ACZJi1DEArNAyV&P?%#TsVhaCrP`QHdQGzw4#=b9qFX~Tz<~P6{d83Q*%tIGdDQ~ z3K4sNX_pT=!I&>;A1k5Con`#!C2{1G$et&);dtcxuetCeSY7N^(b~r&G`39P19pep z?G5}Loq8xK)oJ3_$q-Zy$W@Iz^e8C7@H0=8x_Cim7Oz%?Zd&2c#`dE7*@c&x7Al)WJk5)>ymlOMFNNmR zG^{|!mL9t`11&kBCX=PCCh22v;QBOPv?qcWCew{CE|Wb>Ev#!*`A%b93GTi=yk(yy zw4^GD?4GG*J~+rEOwX*Ep=Di3?jDVOlYDfYT!1I>*tS6>?h1`?4ZA8h z0gFSj^9s(kU1fMAPUWJCm1;_a{)i6+f^vCfrjt8VT>6`f_qfWXy&nPO-lju@*Teu@ zsa733mSs@|JM_daJf-#Au=VW967r=CsgaMGUVeGY&`s+~ddsSU){IKEl?m!C_?97+ zXUnp|lMQe_44rqID`&eQ-ZY+xjKPnu)VBI?X$_w)@&%@Q3tp?rEEQ1g3scm&sGYcQ zo2x`_uiKSJYh|_wE_Gcd25AkxiX#m&c2yP#(XTGq7V(yJ%eqbzZn?7PA)%rb6&pjM zy#6GZHk}b6m4e3_sA`yNbuJ7Vk%vBTk8e|r6)g){`}|w9ohHN5mQ+D$*XX@+a|?@w zjPHWBU(^RFK7*3z1l8?YBU_nO>fjiPI7Ykp#k?Xoj~hk<#Qa>nl9=Z7N-?5!WVYhV zkd4riIZ}rf+H3KLQq>ilyoWFy^?S-5>oaqkl*NXf{=DT)g4`0Tvpj@Ou!~e~3)Mp-2})j%R<1)et&6tZU8B4)P_DEe+tpimpD>w5 zvu{pRGGWcLfIipaxLK}ltZXB(tsI0lrbP`sHk%A~>iLqXwbCje*{wQ98cYU`sloI$YN?f0L1~ZV3pbO98Sku zh8Mr;gc91z>w1LbSjn5tm2YIn6*SZDLt$vPb%^IU`P7aGosr%1ph4D*2saDr2}d-d zwHJO082<3qh>`oV=LY#kyB`_k4Ov`zxNXc*O6CB=_&Nv}~*&+!5RDpwFvOVS>zC9E5Vpy|-TtvlYB?D1?@v34m$*9XvYN=+L0Jq9+ikE@v;WwQe+o zR6p!T?-uaCGh*vdkaLB#Uxwwa^L-suI>V@HY3QL*AlD|~03)CFa=LzXO(0|Kb-aV$ z=Q#<%OU)8Qp8i3?;}py+u{Qy%xBDupB;?8CJ6eVZPRSeDhF|F58(PZ)9D9SS_5LQ` z8=MW03+EcPIhOdsC4CcjpvwWFjQT|UUK7R%%#7<5O{_%&@+=zG9{;AaBXXalJ*>1WbU_T^CxUwM{I0TN-D?RqJvD zA0M(er56XJSp?||W9g4EcMrBdz*~=SuoX?^1nEEwwgdbi#!^a-i=>cLoXWywPz;Wr!tUy=XfNMWonS~G z8$7YBC=99R29!8Ww$UQv+R-i}R_fkS4@qanMKW<6=Rf8u z;^Qdww7$R-6vNl@NL?!WaA21g({63|#RnV=S%WvgIAN*InYR-T7}a9w8R?go3@^WF zzbYo{|CU{I(qJGx9sddW{t#zyD81Ng-W;1z>fF`h(`rs_xg%l;`gdl)o{`%VBdQ1h zF=KDKW(itgr|jlewb!@xazMDy`e1!Ke#iK8;9T&1jDc_&8A1redrtsv~y_t|#l zO{{T2?zC5196iugR3Sq5O_n||M@dHm;<87 zPRoEqv(UOdsOLW2xAl<<%9h#8>%VO`xOEv&L%zC7=*5-Rco7`EVY}!MB1?WQSA_#z;P_5rSw#z1g{hJL9(L z$8IEiW!`Iu4o}li4$&_eb$6DBOl-j+q!a1KlQ{sU3vV#jq7|MHQK51Y@kb#i5$@$E z=rs(J^|R6Dkvz7>?(cOogOa$HBid21ya@bWE-paRE-a9NQPduZPd59&eCrskR5qn3 z&ZyQ{Af;$QQPP)2oB`+4`IoAsn|^(&9fe||#Iy4m>jk7$UJqKF9amuQCE!ENAi)lO z(x<9nQ(cg^O7Swv)3!I;turb0&RM>7%VQ%l53E6yc2(T2Q%=9kw^cm-g0sEv;J`M@ zmq3V0W}t8st* zCOKsTbl%$aM$PZ{ZAJ2q9(wPG-@zT5{8B<#GG#RpK-1e-z&Jm(XPpPp_APeHddYDn zrLHRQS)tnD9Me={X1=q!LnnkE8pFCWdLE4xP7{2wZD$#LUpOM#uyX39}SK7@| zr&_`J`YR;87n*Y3HlyIdIC|EL#g&&2Y-aYR%e%>Tz(7y1G!+WdCRlfxI zCdJf*eZ^mhb{ro@8B+f~F!8E8uIpm0mZ}6bnY;gu*Dac}n3Q%F?$>104D1;KD=89;83(()2MH#{z1nJHMDDvW2F4uizc75T+nOiQLVkJEuME; zP$>^?eUdDA$Fbyuzsre#op*CVcT2e(>vZC*U)b_++?g~m>umjeTp-DlqEckvtz7yjn26+L|J z^Su3^uKtarYm~Epy2u#(f7NLI`zq;wZZyh90BeBbf7xzE)c!X}w9#hMTVh0`;!O~p zQ5F_9P|X6D3ce#l$*lQ`Om z7IP@^PfNZ#JbE9y2!OYyr;<9>Vo3)?P|FDi_)vxHd4!jsmw0*ITdXu+8HZ0;7krS= zb@|ewSL0OuA8TY^@u}9YSX}lla^8Y=tGXNKmV?+@R1$U7jxJg>4^)!9TU;p7%|_J) z#X;f?+0YCI(9A^)_>B}+yOl?8{J}*3^BJGr!`7*uR3CF;DB6DX9y*YbU|>a% z=EmR@^=9MwsOAoSW_ip?FT-Nli-#qUD;vx|??$R%#9r$*~yVQZ?+~FLHC`W^5m~%+-0(h$r6RPfR)u`P)FpiH322i|o_vLTu$WNnF_x`{zkpYhtu2(mqq0(Yfm8~`pb-39J z!1+D4&ouHKFSfQMPLP=qeh2%7Z$4hbuNi1_E&L&GDZ`A77w&LEr_;9jiG7_ zl}FAvTI}r!BYfOahkyc4lv$Q#{lVi2`&(o6%mPEZe>k~oY|CMSmZ&0QM&Ce%be zzpL*y!s*@B#gevBk84WJmD{)u4gI5X$peQ#db629UMB2^C;1HLGRSjIx+d`W(aYsV zi(o}AHU1x7A}MHcVM#KlB)j=`y#hZ)yCsiVr*CV_XR&GEx8XLh+v#bPO{;nR{F4Wy z!`wIO-9i*-h){){bjmr2}VQ`1NE3(P7@(&rC0C#$vzThe3+cjjnfOTKdP$<8F;UwGUuyGhBO=1dK zqzwE-bi+oWJnKqJxu$Syhwv*znZFzxBL&9<@tO-DIwNBMkLz==H_ZPK9FT}GPMiL9 zj&r#Gs&oAJEe`*ubI6#un%EkeIGV`<9RI@yX8ix;!~Aa?mKU@^@=D7c*Q@W|RmQ~2 z0LKOtG%+q2*~Pd&Q2-b;L}1c*EF+mPvvCGvMtynvyh>Ep3T5D#aJ5p6OVv-h$Q>&i zpIS>OO$c=1H5s^{bO83% z*%_?{@20IV_D5KscxFBChA`srBRP2o64GC$a~=+KfSm&lLiv0Et7JtiEm+0B=SLRZfej(?q5fddqF5IsPHaKaW)G|i+OdK z>$}YrnkSks)3)==-KD$R@uJ7MwiO%tG@*j_TssxnRDjWA*+l$RAzPJoW*^l;-C-(R zzz`n4iK38ax|SzX&WTV&&A?4WKES!XHouk`{op~}xrRE=GQ5wSRjKAfxr}Q=6zLL| zor!BDUmYzXYtk8r?vT^|g{ZD}yJa<<`Mv6N~S?ZOmK zav<1B(yC;UTjg$}PPi(MeG%Q_Hd?WX$jue8^K+4BUGdOzDP%yujnFTjR@p(mB=6{| z$}+??>JjNQ5@hWF5M^4+vuT?*961MLo8%>KXN%m5k)V(YPoGD(xGdPJ4Q!agBbEBN z3OO4Ss=7<>)h}iVu&gxkAJ2+LxZ7DeMDrOtG=YVFf(VZgyDDsuV7crgdo(xPpmDIq>i6_$wt zEJD(e=68(1DIr5rB%-I!&83G|YpM!%d~8~VgdxHMLw*lmz9*hZVq_!}l*Zh3TuF{? zqVC9mD1i|-cu@y_Y(gYXXxK>sAGh&hYa481i#|+wsvVn4VzU9%lH&N_46x>U(hv!_ zN|#Vx$|M`AMz1Zdewz~R+DNkGhgsU}WD!%vel;Q-5g4*+;)V;hR*=v+wo?+*62y_6 zlx3ks<^p3FR*?sN@S2oBeN6e6G92ZG;v6Jm}cxTpF0Z_r#-mOjp;EOl`U7A>O6-aUcH+&S*@)(+hQa+*c8Z5)6Vm_ON? z?!qo^&22>=N4e*6boW3Jjmse0_TVhoj`LSRp1F~B%`sU>j+|u!>eTmoys2yr;E+`I zQBXmVeaIbgh_rfi zL$3N206Htm`KT|2h0EW$aBgtKo8umfcG4$xrfS9(gMEL8_l#89)0bE%lV*c&B=BfbaVy{TGtyLhU z*kBJW>ZMF8U8~v;t!2?q(uN5AwpLGsUp#gKbACmMqYdyJI2wYc#BEryN|lialBuRP zy8^(0*HT(IvOmjxn{Yl&WOP>LIp==1znh=J!JRrsYYd-8K`)?JB#i(=uKFl;_N>IR zu|LC-7!fmUeh`=2cDB;ocE$xb5C6iAwbJuih+MxYUBUv1ET7Keu>M%Zw^ex$`YxI)Jt<*OGZ*MCiJ0zCUE=lM4F62Z>kmLTu?_ z&4kwr{Lx6;__Ik+>zm-`pC6nAYF#LnarrN<qsL1;u+65EnE&;1nhz2DEfkZS zlrI<3-3*?v~qm@>D;Au8ee-j3ITVW&aF zGJ%MglL`rn#z#Bg;HCvAUFE5a5?h5h2fCaZA~Jq9C+Q)OfI>|JQ#W!1Aq!43#<-JP zR!yh9nzp5kjE&ENYLfI8!g2HpKMCmHQYT4o9$(r;?WZgAf5SI@w+Uxi9vcfDR(BjF zLSdpoq<3}5?F3cLb>?lNvy7ujKhcr?GO_SXQ;9B}MUN{+28Jy04n$jo2;Mfs1@<_T zlwvr8F9rTJ*#9B(5;iua(4c6Yz^9%-Ukf8kWDpH#W6L5*iiRFG7mDFqz#z5|7t;lz zICX0prpB}VOHfI|ic3FyhZ=pfKoKBN4QY`FdTc1*|C$ZOVJ_6PzqB1^Zkh=cX(!7c zcMG0KlZr->Uhj}vPpq65As-vgw6|cKp}H40F5jl&kUHx&*XeB(%hB|p2c(zi+9V7( z^4ATZSR%d+ku$4UCTpPunL=Mv)hNPKD>G|IN%R%4(4WDiB|?>u!4#Zi9d^AD!cWa4 zT650OQC>+2QQ2*w^H&4N`bzFnj<3Au*LY4tYX@*FXif(%AWRdP}epj zd^*556k=rDLO(rNtf`L7S1--EN2-rI?c+)rmN%N%5ja$dcK6$c{B7 z6hk;lx~Usnju(NUJ~@x&GEy01`Oxd&oVvo6bk;`88&bQB<^-c(F<^PTx~dD4Dc~QF zZxIa-5u_P600-|XbajYegAv?>zOkUErHh`)JdrN+mnEb-xq{%63=#ht!<0#vTIePI zdNe(Sy||h8dXhVddK zKyK=1xnCkZ-x7%>DO)s=hj_drohSR~HZt5E<7ltn^w#TN<)L?tt3WTRp7i~GB6lXp zuXIGCh95BYc*zFDGK2T_I2Z%0bOG3$$ff{lRs-zmF-P-J81oS+jnJfhkZd>`4e%UJ zaL;>Ito|hcZSK!4CNK^|EZYH#depKZTVB|g1DST*xlk_$cHY3}J2LiuWll`J;=fR{ zVfsKJchoFkT{{&1lisPD2gI*YYtNL^L#1p9#K(!JUwJ|d4~(^gT<$+-%UVR+LpRy4 zMi93BbK0>FIm0jSwXO!W>v8SI2)2c*UI8F^#eYA8pHYBcD3Ett=Dp`a1V^}Sx1>&V zTe!4CSUZj#I>(`$1Lh4%+=0zOSGzW^@T0&8&oJ^fson_Bh?RSrJM1m8-;j^efqDsM zAH~wWZ$_AY+Q^%KcJN-j^1Y&Fn6M-NOd~l!(zFz4n9|!h`wnNSa)0(#+)rGvdy~~5E{sqaX2`6nTk}!lhz|gGl+C%6FSFLQaiM(qCmYQRtpsyBb@z_o=i+b&* zmT1u>st>x*^=QaA*Oqa&D(KLp4Z^c>=#@qh4#t3?Pe~6mzcnUW=B0yhP($Y;aoMv7 z9zRec`+pOaEAdlis}$CTOc-YKg7H9226;W>w5JUIQzOkC)hz)S{Rd(dwv&zttedZ2sdP>hG?KQ4v`d#xi_f1_slP zX=a94$12|$xuF32PPWxfX;(Gr6l7zshbq_KdI3BG@bo8wcI{B+Xt*fZ1j8gn z^hvVL3|gyjP1BfjIcHG_mhdY@KTaF8mrZ1AKThdTxDR0G_O#L_c1tryIW1mMq*Z>k zU{HAXbg|WRHG)a040F-|ODQrjI@}V`Fzd)Q`;xX8H~C;dT%)c%OskusBy*%q2_W0p zeR^8SlWb6Pn0RU$2Y45sF={%=$TI296lGQOWSy=q_ENYRenNw`;?45ggmotVzWT!) zv+tdGoS8N027qllLy76r2C}gOyqUYeUt`5%Z8%Am0XsjpMo$BgQAW-)2Vg8yb z$zV{XeQrWg4cGe(RjW@?{^YMJ*fVf-qm%oP{ns&M(LYreSK?UFO&rH6_bk6=iXpSP zWyO3<*7Y4_>iov=;{gzKLusL)pZ)ogO0#zOR01St_UM5bOQ!fs`S-wHRAq6!`!^_O zR8Ht^G=F$SVM!wxmB=N7N=|&7asl;Vg9=X6LPHudQLJAWOZ#dUw@79K{92!#`3mHw zLx+Y4-ulZ!QH4KaBRlT2GrfeTgWN<&yD3kK&`t}ZV9?sk1@p}R0W-bnN`*`kH3H3$ zd9~?=AR6%IP-*SC&>5379B5fv35vC!G#qB!}FZWX?BC7_5ug5`%rOC=)n&oB=~q-4-=M=TCV7Knafz>cUji0DwPhBF|o z=C6~~B5e()9B|*0Hwar}>Jz{5JG5Y-tVIT~e)2i=xQlHQ>0xk09v(~`AhN!iIW)QJ ze}!=p+a_eLlTQuXYW{i|XBp0MEM2FaBXy5>i?l{{o3eF?+a`ILm>O0;em>CiV0cDc z+>CG6CqUCr+e1ZE$n;VmAbwLn0K9j)tNfLOn?N<}D~$rx>f|g&kDO|bIH;!);7#uK zagB5ph9?(*#mRpNTJpjX0o2k+@+KqA`P(T(-V4FfsatHp@0A$_F0~@+6%P*|3*i7| zR8_iF*vqO`WN5mlmUSR%1C&HJ`j6|!^>o2uRn8Mbcx-4OW`pFs#6ig`#WR?DMM?r% zUOm!nZ+#NlHNEo4I+hU{f{OQ7^5003%ejd6!H(Js<5|QT?&&Wg@XsFq^&@FMiD2YVQ5dCE6VZYI^_V@ z-}kx!0--_GkY$^|IxR3hF;+!E9W^L$2c`n*@F*}{K^-zqv|-Ue)NQQ*8cChI_-(K~ zmA&rWB9belJdAg@G#i1u>5wsKn0SUyAao$}c#*Ds`nC91Zm^wZi2n<1p=d~ayI|-) zvKGiB3cB1=W&F@QH8&Uh>4XgDfc+{C0{EHQzKfb-!2Xd;IZ0iuQhE`E5V2w%tFzX! z#eHtl6BECX9}013PH7V1+TV$3n+L$RpvLd~^Js;1j;93gI7hNQdG>C$?qhiJu(s4i zeoDH?gKi;w@D^xO2t+DF{t#PViLH-vWL;XSYjHw zHc3qVpGd;T+qtqbEwZj6{4?zz$EPE)^cwL>eor|zg)K2cbB8jHQ3cWvW-X&4=fY?x zCm%;4yW}g?^u{bN`q+ptLnzCDvV}=BA^rq)6&e1GPB4ZWC-e*e{3S`U6M<67BGYj?KRc1)M7}yIaCjnh7Fa z9^pLQjlq|W^|6&!1!*cfIxAqmj@L^VA>4*!Cy>l5me|w(9h39r@WnJmdV{@-AWe3N zT?{%lNf-QscMp?IsTXqG+$x3_W_!87;fuHy$pNIeXWu5-4d@!q1Nz=` zV4)E9w~Ywwd))Wgi)8z+4Ts&Og1L*6coTtlo}Xv_($%2ZaW8$^=k*+Amln_?0&UOD zZPGS|(4%K@fSlR+^^XH%9G~0B^@i$zryqZKciM>LM>=-c)d;nhh8mnqK1dHM>Tl@7 zKJwwvD3m-QrASQ~QQ_FA@!Kb=8iPseGO;XbCK*{_E;sfc~HR3lXyIi)BmsZb&) zQVzj0@n6)f_`k(ZZ|$9nH7af&@sZ;;^FLkQpFmKpKe>?^mjLDw`$*+>aF~5ays|s* zbTjb{XV21#p0m=izJ*^Y6VBe_r)1JFTB(^T-mq(K#-!J-6q zYS(~@Fjt=^%wi(J()H6SI@j#un(Jei6C=D)I57SmIHloFLY;s?@TmTlNcRZXMm452o*YRYO#4kt z{@1Ys#PV2*Q@A!T;{ha{L0y=3V9Eq-b-}YOdcglGc!n84``EKx$#pkN7W z77>M)>~sIq5fm?p`mG1gUtlr@&309Jb2m^(FZ`DWa!5{1IyJ+9kOy_@l#P4n7YO@= zpbkx6xZ*oG4Br;@lTMKOxRpa!H-cT_+9A?&*ipu)`yl*Qc-hTE+ zPrZ~cJi9_)#9iwooji|{{WQBlDszf8OzKj4`ED_KFA)46m%#3y>+ydnp{lX6mLP&iA^PtuMWZ1|NZo>s4ajMo&~Td2$lx4JG+Tz& z8RrC}t0Ce}383y&l5x1Qg6N1BUUe6)eSbmH^9hSE4`b#TXcuO0qB&+!xCt#1De^3Y z&T4il{v~BN5_dD`Gggd3@;m)Tskpu}5yz^LTg?(;KQV9Z@YcNKU3*Jl)LDi|X_{GH zVj-Q@O`-m!c`It6juxN>{`p6xgE=^3id4`9CDyU_ub&_muaRFX9!PRxpK@ zAlm{$QvlSx(GoO1crEPL&;Kaj?$ago+`r-=|MQ9d|C1d4`*@rGqbmP5Jfi=rrXw0Y z_9`pr-#b@hQ?>-S(Onb#puQ=V>p!HC3bTH&k^NLd4U`NQt3IDPN#I?-vVA2D)L##5 zZq;gOg@IW$Bv-2;fk9TjFRIaRv9z%&Ta_!5!*4m1xs>^?uqo;LbZrW*!veu~HNEY* z?e&^{&vBaLJKcW0Fq6LpRS0R*g*wmzU+YlxzufWGsN09&z-!kVSld=;OwxBVVrL(3 z!8LIzvSyz+!F{;qFmXz#}FDr5<#%uflBux`M+VJ-L}Ug$3Sr6aYU(+fm)9 z*RMv=tP|{RTxb2JUek3T95-We zXuSJ_2yis+^D$Ci8Uw;G1Q=8n%tm5a1(c*dQ7jD-o6%!n%l34pWS2#rG$zGhQbT-V zbT*}H^zt|f?$u+-Rnf)$#WIEB^0-ll6Mtn?Ff}&O>{u*N8d@;8(|ts#toC>d7iz(~}bpRcQAm@kp$IOb`56v|QZE_h-oS)MZa;J`g0pTbQ`bt8hKue#W}{eXhWI233q55fk=mr zr(PJr4Aztji)L56xsHvgos7I$BG}#Z1jkb_TLSLW*Tk3r#PO*(Y{k%#IsahmG0A+N zT(1`DZt5Z1*x#hOPlt1RZ;NmYq|-ca*zDvT0o$p8B<4ln!p5530@3LX-+clYxxL`X zQ-sBsvF!sP#g;AUjALp2Sa|8PX_Cb(`mLT#JvUCizmRF;PnKLjXjN`GnKo;SrOZP& z7h<|YF+Zt?peeFqDIKn{Vyj3*Bblj==nxh(X^JhQ60)!w`O9uQ0eU*0T)A|+Rw<(e zLTX?ju#(e-YVIHzeGX^3IDr-$9|I;siDklAtu`aILGFBQjU7P(ELYXE+Dw!LK!!QO z!ZcWee@GNv;wL=hjGPLn- zk%KKMT z6s!u9tJHug|L9n3h$WzU5BE~xjxh&4oijd>M3t+47Z{lbJO$yS+yx8MFDstbFApaz z*cU}-0GgoJ8RP}3tA3$8mS+X7seHlI(YgzdWWBM~QHg__R>xpL!>Y364K0)}&;}7V zu*P;P-lazF?YGhKAuR9Ft9>PE_)^+WK(A%F#TXrGuH{HkK1+1Qq%`GPGpg4x7dvU8 zKT*}T!eH-VM!&)lmdw6BV zQ3*zbbbp(Engajz>1Q0DlFH16%1~yGbD6@64~#fboN6YpofPD0d>c+KqeI2uU~64t zu(7_jw6VT2x5lNljQg2fiD29#xauY1J*(JZylBeWt|4Dy;#_Rk@D|UXton3T>qJzk z1y}va+g9<9wOD467>Pc0fx*V++S2AsZ&_2-*WS=mW#Zx0?jh==?yjk>?5=5~u5F}i z^=FYufZRJaeX~IT2R}m#VtO-0{B9c|JA}v-)IMK?LN8Xzc(cXx#NY*-8C09^68R+r zX&OmC5dPs1K>9CiNd`s*p(x)8s+D-1uq|~>a}OQ1T9hW$09m|bW29U>=y}H>kzB<- z6h6g5Q$Ff)yK81&`> zIHHY;>i95?S^Abnu*_gQnWVm@X21DHwly)7zGaAGZo?w3Y6OCA9D59m{5xC&j?LL8 zEir)#-blgHbWk;1P;T}mK|US^qe$BUlRH!})7$WD`5SIaFC$$*t{Yh>sj38e9{=kggfEj(eO;i+R@zzTqV7~bwll?@u0=cWwfC2Gc*2-USn|2T7+Xp?^U=K| zfY^iQ1rvDXy(F`5lwJ;_dfCT9<-_V^Wv>U;Y9%Y8t(J9jRu z>R-F=<<>~5x$&k|zg|mxnRh|Cr>? zXftWv46<5bLfngLx120d`N6O)jf+%0q)il*6pN|(;eS~R@4oICErZ+?hwY8*H)iCv zg8OdAG&vxa8quB@;1;c`d9J&DT>NQALHs?2P(4aiYw8C|FbKgLE$bfq_npeeiIR&~ zu2MJK17r@saSQHs50N|CwH_w#zO){P31$a-;QX?5SC}4>Hq6^ihjD<8Y`Pb?CW^a@ z#OJR3)aWd~PwxQwDeJDi9l96Qbr0D9e;W>YFMf~q>GPK4j_rq02jsg)*u^B=7rsaI zRxua~1OMesCm+cfV`cy`iFM9hVTG7?G)@jvUV-N^0^ZT4*TDVSDzhz0t2>LTN^vuE zzN*7Tu5L(v%6iX{4VbZ57m8N5mm6V69!awxN4#Ilht&tLdZ1!e5L`4Z9-2>Pn~Q!o7)BG#lrh#vQtmSRo!H-yv^GN(CbYOVFC+iw zl5SVxo!rsv*C>bz!#1!gFbHagRxES`pw_I*YjN0?${OLJACs!8siBI4KUk(jDG)LR zd91sssa=)05g$GA2#5H3jbFQYIUxMG?S|>&K~bXpW9cebuy@X&LwcC8RL4)Dt~#Fa zrVLdL-2wU9#~nR6tD6q+f?x?_yxj0k=L!1}Aiwc9Yxa#0V*i_&+Gq5up3n(fa_)3n zbkH=US8b3xsr27|@{2N-cL`tz#hf3{m1F`QX_acE4SbbqCLxD8m2@Z}DKV3=UlDjD zq!ZG@)e>|?ULu@(o8u8KXXO|QPK>*QKaHo9opUN!+j#;t;Sq~I1be0~sM4Umo(H-1 z{qNTOZ-{w)cl-(a;|Bu%|N9pHpNTmV|JOr|IKaipNzTO0+0OPqc}{B7tyEOj(ElQ^ zOowDd@z!~Y7PhnwEO6q$k1oWMjpDm^Fvveu+o_c z)4R}Ew|FLoX1SJ+0yF*xW$zeY+1_OfSCWct+qP}nwrwXB+qP}nwrxA9xGH>e&gp); z&$)e{e(wJ5^=a=af%PeV=`idM)0>ZbkGH zCIfM0X16PYI{+UDfbJr=Azjdu6L~oP{;|84H}+5_qI#o^9v<3$fFn}sTjqlCQ1mwU zFBjicHq}zT->=&dP#4Fo+O$S9ORf1OW}zkW`>s%*VMyhJUM3P-n?H_@;?=zRSctM# z_7DfCP_8A&pvj219oTJR#a50M{&43qTQfg?uCx)&CCYZeVm!M(<>=+Mob3#^81sk_ zkYJ!;>bPOtcS$iOG8aJg1<~$S<>;o%hQ@r+bcP13CJkzIA4Az^fMQ6F-AT$2b9QsX zQEX7)<|bC|qM}E~s+o5vS_r6eSr5y|pjO9wIFmS#P`^^*5y&{?!)a=3D_J_n6-!lo zOMvznJCb3yl7sJ~K&CxF_Uo`6UF>v_j5~HBkUx1Sd^PVq{FYSucP7!V;zg^9BYJ)C}~oSq9{w=PG#totwc|1h)oAkjdj4O9sOu&BU1r|lpHxz z)gAy9eMWU>Rf<3yn-s|_mmnHeS*za|88=UTXymTmH#)U<9jj1bX}g$6kk_0D1AD{- z!YbYS6|eT{p1$ltqAeQU)v!3uK@+wZy7&gk2BYEq#WbLZ{6v7)+Eh-gxuZ*gV5iSm zCv7jEP;*LkJMz`3h%@umTt!X7LaKcl-{r@WwDbg7XK1O)ax*2dM1p*#%hcHXSrJ}N z=y?}(b~EuBkRrrcCsp}DyGOf(f;Ue9QhaRajpdK>rd7f0>TI*~*tM|DLhrWhlEPRX zn<*ZL3x}V#4>Org{wwX3X#m_;KeN^SxW5Lb$e}PD?scE+q5+P)T-<)F^t4vB*(g@pe_mt1YPt@tV?MXAFx#3(EHz#3tknl#ZrH9%?f7$3 zue%_+O3PAvUO{^reron~inZ3|wTS8Xou3z9xXTa*;VS1@Ni1%VtAfxSBm-Q=cuJ-P zuQ^TN#xi#I#xy3qO&+Qyd&PnuAs!P>%}g?DRSDy)@ZnwJhPcJZ;n?%VGRjRXJnz#8 zSR5l+)JETL#rj@wL*4Wq%&_J##h=jJB`->>_IP2r$CuecEL0I$+@(%WVNEb3&5CRa zsx&145+Cab=-wh#+z(ofmv4jhi0UF$Xa1;h#QLbLEkkjNoqJadM3#o2ynDm9(UbIE zPG&R3J&|)8V!IniI)Q7on8C8Gh>!_a)M_C$u|NJ*m@20d8CdA-u2>1_zIx<3%%eH{V7b1o~jQW#V0Ff*=E+{1o%tqI~EZLFlyyk^3?D*9JP$TzT`qZNv zW%eCI6*c!|mH`2-Am=@R^os!Gwks2Xp99pD&Z{9Q1=d9hAPf?q4Gr%1(1UW!w@_0Z zk;9_CTPB`kMtSI7!E?BU`?7FWsM<8K-x*({3~5D|YnAUW+~=NcS+d>-o4J z_r6HzN++o#;cMqA$2G=tD&v?Z5j~=LF({1N+W~5n=rBaL&CUOO1xEt=E!_zm^x{Ij3(7pv#>XRRRAt}}hgy+9{b@@`=1aH(2Ai!kUm{QG5c z$m&b99Zxu8<9;JspUabSCZer=q_dG$#a-8L%zU(r}ExI%s;TT%3ryEESb~Td54}?Kao5h^$TO0%VpdTM>5aGhs;l zC=_%vVkTJHIUDiJN6TxYGM<*5Px4Q~O{A29%O}G`HVjsOZ{!6!coB!wX>)!xDiNuY* zbo0!e-2W%Mxl3V8LXaMb`)t=TXNhBmu+>Z$YG1*AAs=iAU`Sf^%+gG8TT&t&;zhY# z-VVR|o$R)|8Iqg^NeGagmGpTt?DY>dNXS52isgHp;;UlX+Y%5ONa znp?qkcZ1>W`C2F5uI4S>vfg}c8@g!0Qh6HH$q`Eof=@29z)6Xr;37pYs>PN-?v?x9 z5WJ(E8wf1~ps?r|W-yj&&$WHCZ#5|BB>NC?`q{A{{$qZ> zQt8A~*W3m6p~ph--_2xu=AO|{4J{!Sx>C_6W0P_jHx#G!GiOVBkdoH17Q?!| zrT8znT>WqImj4vGmHK~@kg_QE`uv;m&<7`i%rhLDPf;6SFo)eu9=xTT48iAg$i zL$%)2T|jXkOj_3r^u{xnZX;Ao&?{uHFB(VoeOyp9Z6paQmtM8}(-8ln5xy^SEq6#n z?LMf^VST*6-%7^v`HM`|OTNXj6!5x|;gSa-fB8*&$h_;|W@rminVw+x_q z^e$#x%R~Tm^Tj+O_3*}9?ymPXho0!9U78ujBb}X4gVHHZfc`{F+J>GVq2I=7xgJhR z8|7%>U_4=_ojU(DhQX3RK>L7qNTS42Rxb^KLZ^(8cvjt>!%ap8%5&Aqpf)WPn3%@PX&PUHE`69ilzu4xzyGpkdx5sL)N+hdQv&KE&h1_>4wy0@ASe z*oX2S`D{exTxXV&xNb#U*%U^29@U{+%auN4euX}Ns!e7SyhAEu6RWVF-FeN*9|ZSa z*f0zW_01l-Z3Z6KyE^KxlTH^r zPJv!Z%@*?~Q*wj!gB_$HANXNPpJJC*IrM9J^1Nv)7!vjM~La-r%OfD9$?YVh6(U@ z1+{FaU|tCHANSLy(*z@LG!5j3=$fj)msNK>Fe+KX(O+Jmet#~G-|Pb(;C!7raDNkX z{U=1g_isOhzf3s)bbkNSWmrz%{6ARE|FYt2tVE9MaN|d6Y)n$VND?Sg5buTf-YD;m zkqj{0*fHf2(TD0A((^;r+fN9wK$hf#>>zCoSxnQQU+`J$IP=EqWHRmJNK^DoJijV9?m znyMbe7VEv~WcMl(3n*>oJqaBe@D>v6*Cj7MKWe(nEa%Jg5$l@431@hG3B9!D z9H=YB`DC4F{B$+SO5|Zls6BO4LAp#z2~DbH%8P#Qv6YF#Ga3#Qen$#Emt82&jremJ zWNg=oLuDIl$OQ)q#ta4JyJD}&#*tSbC0{%&CRYmpV`6&jW^6?os4Z{97 zZ0CNsg~V+N8SG@mt*H*0og$y@`MKnu$?u7F23o{*6a#6#+sJiiBZ*!_%?G#^inzl& z9rJ`u8pkNW49c!)?MkmLxm$}thlt~rC?Px9p#YeQ3 zQuwHW4wAS`}K%{qu<| zc?lxh5Hz*G&BHa@5M(RbJnPNc7F~5MfrT?Kj2+OPG=~t!y^9q%jujxu&26-7l^H@8 zp+|{TCn=i-Nq99Y5g7Ur!|#=EqSE^1)WlfH_Lx7=G@0Nmj$P$#3uic>4utanntT3^wqhbjPZhUc4ZQa$a_ z-RFkrB(^^ZupcG&Xeh_cqok_CJ^O7Os#HkH$M9~n?oh0k&|j0o!e1e&Q@R3dD%Au>X`S{~yHf|H~;x^Dk{>)a2x< zs?bo?&fEu*327vLq;&%dBr!a$Ux#um#$zraRxLy?yEAbq-Fk&^OdvU8Z}P*88z5Ds z7R>8t`r+1|bdS04%2kyXa498M31k~Cu#m~|dR<5OJ`yVrDX z&6A?7XF?Y&vX0WN7+pfqp0(AVp>1rkv?>lvz_eryrDxboG$sTavnfK|6i`oks<_uF zgXl_BUO?@+56q*E4>51)>{*hibDRigXH?Wg2H;C5&WoWQqS4Wjs8dk#D3HlzD9x>I{rXL2@f4{2f(Ui%(6Mv{;F2 z1TuJ(7Ta9D*j}DK3LTgn+5F5M5j}YBJ~Xzjt6yj(^RyG$~2T{^dpSiXZ-?GGA<88lTON+YL>iUz83LMM`belYZlp zCGBkc;UU(H?cSFw&2AU;C*d#hz;ku*F!1(qkJRgPi6zgan&OMQmp8y(gkuV~z%&9K z)Z5}vb-y{}q9jdZHqRZpW<`Zq3cH`X`;HxFqwO7*V2M*#{Cb|DfOS91PWI=8v&=bK5Wu`% zM6b|_$~e-sOw>~<03x(Y9%LCRH(`a-_iM@|d>v1!q(rmHwV*@Fb&JdyFvqBmKK+k+ z&M!s`Iq*eR6S*k~qs<{FFO4%ZN0TLx2`kO5wRB)yOV@vb^GmfOZXN|1x<$4CPJRA7 z0bdMR?)Iw#nbqEPnx((BG#)^MaSMUZ)_ps7PraSk1BtxTI9%X)?QCJ{q3iesw9mOg zNOr5Shpl#8iZO0A^?b1U`F*sCp34}?mV3YrN4wuqicS$AfqfcD=kS%O+)vBQSb&;-L$Ta72x3R+qq@D;hP3yG2P7v`S*$mx`KAwBCC~3T>rH zWHaybMW)Lckj!#I)b7U_wkF+<$CJ-dU(`$wFNhtOYX0d!7?=k=O;rMfjBwn55EB1k zL1E|syXGY)=83Eo3u?ljiMW0r?JfnU7}3Y+%}Fhq$&_$7jMNL*s9;2j_kew!T}EIJ z$x;)k7E7qmrZSq9bBuEJ&Q&Zm?8R8G)47_=8Gs{_&5C1Y(9$&+=v&n*VOeFCHjiS% zHmxRGok#d4<0f75j3!nK4)@A}JvMCWe%3P}-D_%)Jh$ueBgZBVLu;381)`851N2T) z%*o$DOx=wdY$h|L6X4h<>a}S_6z5xutIX2UO_UihJ<;$JsgMd8-lOFY_K^*%&(WsJ zwGH|Bn_ioSinT46o|KmhX&{}L zrC2yJPUG7;t=NK#CML|&TUNne2#?pRAg%V+RHQnF7-4%L0Acf5u!fE5LqYsdjKa^j zj5Li!Xfu!{9W`O*UgC$EJGLY|#Is!lH_nDEgRf0ExgE~7=-V!c&l+Vct@3JX7>C_l z-jEYWT2`H~rCskos^scUh-BAn*xT*b6VF<^7-wK404bXFJHpvO3Y#={43x>OQ}irlB0Lqf+phOx175M{9E zb}M-;bK1ESpdUAF%2DI86Rq7SYfRIGfH;c6gNC0f_$W(33LhW+0XF9~hFDcml% z-q#0|J3*{-F#uqldr{5vCLXgeb0b##-@v1b*+^GK7hv({wV&r6DMbOG>aX-+Gxuu* zVBn?b2y&ZM4MDdJKA#w~T~}fGeO&G^i+xc&!o7mnu^i;_r_AHuJULRBT8-;Ie`(i+29=QB6TL@4vMiAz$^`Otb- zobAjmJrWvl7TzKX^m)GG^11s{j|6~v5h9_1j|>F#jqnz*p+$zkMo|RduL&ba5Gc3@ zj+(g&=%<9%x(A+`QO#wA7UAZ;zPR${vd&2>79m4yc3`9QaCPB!w)kwqe{2HfFqrZX zUd@O2k?rF+Kg8*ankr|^0_a}wa#i#^cB&^C- zWORVo|4@m{m)gUFKh&hZ2-y8M@*;(;1O>*$vuv(?`Wng7|Y{`(#<|2^maJsbbe9x(D7e|W%Txve!l z`pf$B&f)P?gGpQ|PWT6P%eE|BC2kps*8{)P_kr^E#vqus7)0Pb^#$sSIZThGr9H>2 zuzqXxZ$OJSWczXo;WwRZ>yzVD_{pHP58>=bvU27mt}Yh5e1t(ciBia@nY`?#ZJ?%Q zsR>N;8y!fq;AU>2lm@V7mL4P>Y^B`^8sGK40}6vGo6D2?;CCigTCe4pb=$|WwT4$1 ztVIHI?;(r)EcV8_G1IQV`02aw`_q!;IkHO*g=ku?DFh9!B|r+3{!D)><8bhDoT^>j zQZBUUhpemR!t^jw<|kH=e~53Ia3Nn`_8R=#TcdEiAJ!){Ih4NWHleKkP5OMHYoMObph`c* zp#3%L`lM^8I5#~ut zHvDe@glFx^I|r$4nMsJH_a;D`mN~UvegQz)IpV1eCLY5Qg?nNtOaS1vRDoRTloYzEl;D>i$ ztk%m!2{eku4sEh#n8XNWX{AvlsAD-ESLs$4v?0hFaXg{QNsDjxFsXb%tS4|9S|3l; zKQNcDGe8{aU@7Q)u)2~kMs#C;!quVIUPzl+Ya0}~c{9KJ_h_Ky(1gf zMjft=E~#33Tt3yrN5G4pLewAWrFWc`Vk^!N$C~aq>@Z2F1#Yb6b6}>f^>u7-(4lun z!&}s=PuZ1KcQFx3R@PopEvo88aY@W21A|3I5ZINYQcqPG40UFYp<*ZXr7r%K#ulL+ zFDN>4%(SIzu(mj7=(VPPyImCH=FV&VxKUqwMc!d>6&HW&RKt9sX?~rFUIVCSO;vG zQ?cGFt%VGzW>*=ARic{ycPr-Q5H>1qGKLQ0PmXOmJJ@#jf!0wd)Ykp}H0xYQryU@+ z$z#num)3g}^K@3`PUBtc&H+lzAat+?Wuh3RPlI;W%60NH5EYT`IV0W%g-X|{I-`x= zVC>1RVm0tKyCr$+mQ1Hn(B=d=R3r$7rJLWIy<8nuWX?p)Th8&SYTLU;CZ^LVTd1@qY6_^|;My_d znZ^MJf6Mq3Der-NG*FbfQ(aZORdR zM^}=jB6M&OeH6Fi3^)(N<}ENmpKG|)mYm(^OqRp6)fL!!=0e*eB^Ygwo*~M+4)Fu9 z8iCV@%~uN<^9j5ZvBw;?qjVjDgsMwHDplu)XHOtdElWe<=!Z9hA@{WRwEu(_9=h4R zl-V3AQ5qp=7HVhtAbfB%;|h2Q!_^b=8A>*`;-)O))!(>jJyeo^sKWBYxmf7p=|4ldP#cSwA8vxJ&<2v%bW>(*w7J)Fru}*pxI8qZf;h7 zLqYOaEL;vAAAb&t-^kc0vNYAly?tivM5};J#HI(#T=MB!{~HqU_Sgqw_{5^w{@v_% z!Pdl?XS4R_vPn=a?@?D=`xVm7XJ%QiV0*9V5jNIa;Q3z&=w86Eq-$lo1}AU9C8)Rb z-AB_miR2~bjrRFl5jZ>xOh&XXY?eWSuA75=1!LiJJwE~p!I?W^(3Ofzo)2OnCV-FU z@snsF(GDwv*>V)lc{psDSy95<@aYvKG|#H_KN>EAF9TrZu#+wzjo#q_x&} zGGnB*wR1AJHuw0`)|FOC-@(+_>95?EB>$g=XD(MRN1}cN{$voX)WJ(|U5lw`m@=5+ zxo1TsXAI^cPNwNsi9o){L||c{2W!0Jzg*fOZVS^UGk$kJZ$EEm{Jy=vVEtxWd(byz z2z#+=x2G&Oj0l^7?smSP7C{|czjwxm7A#OBecGio@1;iu+~ra*vFkNo;;+vWFX5F< z;vMJW<|`ycJx`D8>`uX$nGlUW4nE*hxWGR;!i5t~w=AB&L?qRUjuYr%Wkf*R8mAG2 zt=T@bd+{Muc#>T722q#QNlj{I6y;9pkv_aHXJTB=c=CbHdva(IVNYRTGe|zLeyb!8 zJePzhPVKEEk+D<%NG1s;ss-KOk(nGrk-c#L%gxUk7uoGQn$G(S6cnWEy68J2JmTZ^ z4pQ{B9}6p!JpE{PH&RUFmrp=|$itVchvq{X4I0jDwXyU<2h136*1MxxGgnE`IIFaD_Pw2 z5$;^Qb62y$2Ne}6rNNNMQk_K+?$MlOFYO;u5d1~47k?E=^?xgp{@Ld9{;Mc(b~3l3 z6|}WBFt_vU`Fi{gvpjmmYGcB@f1 zb8_q=3w(__4J6(zle($Vh{7?Sl#Sl7{L2Pj2`*O3`F*%LRy&&KPVO1@%miHC9xu?^ zfGj4XO$GTuYhZO?SLISNaCsU0g7`WDE*9iX!&Fuc+x4mGgcMKO?B)z8$g5chH?vnA z($y9~kg6+pm071>Uyl^6JQx?s>BBEWP?FVq<*_U7`p)hbUyQ)UTt@dsOBY*TDO*;> zcrKEs=kSF}O5T%AvCx>{wUEDTmr^!$!sf#>b+GWjQ{_qAMvK2{=S{3g7(T}hItTH= z4_t?>y=}gmV81Kq@}o39$6#BBk`W+Hy(j?Vn2zMycL0&cWvdyO3n)rdJM$DzBy1S# zbJ2E7STGg{vIHfBV5KRi;l3FX15KU7WfQV|naag#T;SrzRg{MmlCGBTvBARhzUt7= zbwzxpZVx+d7|C^2c|V%!M)mxPo!fDO*%xlP2^`CmvP+v5cxxwP!Bju6bM#&7mu>-- zXww7CA(n<&u977pQq3wM;`y5KUidK3&8hG~gSom`PEka;L0$s~(FZD0O zjVmMHUE@NV(zp)CO((PXQ2@fqeoPQGIkIZ?Sy+|0#7&NTf`sw#m04Bi5V$|2*a2Vo zb5;-Yti<*^$Dc^yC=l;gdI!C+l!%pxW#Li#7Nj^yA-Vy&Jaix>^#k8=6{QTH+3cEl z*~Y54%|7hIG>Yu~DgJ7eeWXtN6_^tJ~L7_7R?tFaHwklgE(N%d0>*nl;MZ)fE6^#N>f4yhSd>NqgymM#gKKw zAXEI=@TR@U1}hQ4)BTZ{Lms0)(|=F7EjRG`dcVTxA#SLnsf`f?fvR&25&~7I8~t4E zMFg@0p$eX?Ms=IR5uB&MVl1?%r$#%*(81e&@TAV$zDt%J7Z7aUk)pX{Gw)!2ouJ6Vtxo!h7fCnKN0g@J6MzRZfR?=rE29 ze*)W9g0)8K#T_anN){Zm{HsxNFG<`0(m6PA(`Yp-FdtnL%2MSZ(08|aCLr2-mIK~K zsjc!faY0mvbXQ)N_3-`Ef4{S-)s`#XA|K+pboesvl2Wzv;h}H(-ClQPP0Ss>wHvA{ zw}Cdl+6t2_m2AH(%-l%2a)6~)-vD5-%2btB7!d_M{NR%Z>h~NBJ=I5rFw}CZT5y_N zc_|Lo%O)}i*~F!v1>})iID#94Ua5w(>07aGWHnPpG){|@s8G$2I+yo!5G}e>5WY2g z^arU+bt*U}(@zlTQ=~00aSbP}2NuC(X-;U``5{`poH4Q9LQ|25G1t*JYZxrL2=`O^ zk^yv(o_tB+gULH~1Y!-{xHqQ$U3x>~T~;Hr3l5t>EkxEaiNlJ)F6P7Q*p{amWJ%sw ziUkf)52QC&`!;;GprTbv^p=BnnCszl?oH9`O5=W$eZXRaM~ufjAL5_>*Dd(h>$QUa>rIliGqw@8aZ<7svUN7FG8WT!G?Ui1`;Y8m`ya%8 zk+QZerZ5sWqkU&sgLoDa)O+X#5^6m3q6-2-i_1KViv+X`l(ll%QP7l!f~~#Fzrj|P)vexVk4TM&%HSEDf?RxSTW@5YieGiMOuC{7_ zP8RL&!xUf2ao6j96<5j z!7n5w*NWXWI6;Oa^v(4LrB%t2a(*Ay9djys3Sk?U>&;V%AuKb*Z1ohdSJs?cwOycR z7yNp>6rRjYiqEZpe6BK88nQ59k%-Em|Namc1tm< zX%^CaT{;UF^!JfuGTZ=Y&*O}Dp%Gc-S?m#J(!|W@fhBjnQak7_(|tRx7F97U5}>_O z8U4x#Q}S<|F}#*)+AymPEmH(_5oauSS#OiWAXKC)^C;+k`%Vznt}1GR55@>6ui#RI zTruxxR|6lnuZ=>iMHi$`DX}D+?TshL{4imfO|tRZ<_>1sz*IN`Gp}YXG?x15hkY=C zm1iXCK;(QA$dTvFRqdJLlE`Rfth3J8sHNe(cv5-BEoO=9z5I|8dYQKq?-{D0+q)`k z^hm#jxXCn4sKd;9=TRw3W&MfMH9OJ!#%C|n<12U)EAr@ z%Dp!^E4q%AYtF-NHwzF#gDotPn=_yvISNl?gmvJ6gnBe)7-z~6r+a;96H5-~2AsfM zi#FG=Ci~e>AdYe}YT!>r6DxeqtNwH7toB!AQp#e>M^Mo8Jx(x;ij3N`naFm>48+Vl zb^Ghv!mEJmct#!9Yc&im7Y3HK2^%k zXe}7o*xhcx4ttE6VAHn8=Z3+)Y$@0Dg2l73Qsyq$+h1$da63V%C$L-`VjhY5t`T;L z#?3^&4SUnYRt|5=0n?|EKC-_hxh zTra3^W%yT~A5w#KQ(9{Jcur$9#YyWl#RCG16U9jY#|Ic#2<(j2L$LeC4CklM5GbZ| zhz|ywm#RM6>`tZzQL=0V>dG+4D zkzw$xX?R-qta+?yTG26$#^JRC(cB_9y#aq@>(`FY<(4u0jfT+L z52^^Z=R9W;`?mWMlH1iL-L%0I;T0a5useI^1V^N~Bel5(83a$mLDK`?kDty6$U`AK zToBaOvA*;PetwB%N#tyDuO*hPe)ycNt^A6d zCsk0So~B)RQq^LgCF5p#fO1@p#GTTRQ%W~Z#QAkWeXL{L<><-#sTU-_-eFci?sy&e zN{W4@VVZbd(Xo9f)pPs^%DF+qDB+vkEwd-b;Bb;w)_~$|l*qH`(m<}Lo#*}3#!uNC zw9Vj(D<}ULX8m(xkRbW6IWN37G`M_F@~e^a|&v5LkUMsM_2Hbu`%u(PUS{c5#V^s z^o@LH?y87_EXV!`&3uQZC$ZL}H#^e?ujW*b=lNqAKRszrQ$_w(LM(L*>d?lP=J`nf zWxMD3I$-XtDQe(_e(kL$uS&2Mp;E!~{p{o9;k7AiAn8E>kRIb=pzY~Cb%Vi}LhvU0+2 zj^pRkW#t(QtR=W136axgs}yn&@U5JHjRbA9#wm&?GCQOh2?yuL9Y@QY zG0|iqX6Qw@xFB$r#X7pnw$5oOXbvG;ZB;2v=Y~&NOLSN)AkFEM>n>~)F;`3`0hCl( zB}>DP&>H((=y^GZaB>cKp=BA0=s0@zQH`1W6dtHb=s}NOx|c3;lEE6QCSGSzpcomp zsWP^_$)o9BpczHC-ct$I2Xu}WX)lOkmIrT4*AT+H>**knfHf5NBppb8of}=q!XX9X zs+YPlm?^7PaXdZ239IX{FeX}`+uE$|q$i#?$fA6{e9E2{bJA$wqAMfC4VrTRh4t~z z!r=-d<#N+v=^3oyaua9yTEl|<0Fw2rh2G$H`|8Eqq+#CBII;GjV$djp-G73A2v9Tp zR?iyS9c|>P;3iOnDj+GiiJiPwX?O z1UErJGV&M%qgP-l;3AMT()6sxr`WgZ&wDx?i@4$~w?vYcD7CuT1Hjcrt%g*fll=x0 zHvs&T9(zk{du=D3BcGlNk|IO1z*@V|BBO&1MI9qVBVY6$Xovd~tT2a!1dW-(Uvs_i zzUR#2%)BE$cdJ~NfbNLN|K9Q?fQ$WE(|-lb)k$bW24X>xq6SSgGQ>b}J{3&ghA!j0X)L zhNcJ;dwnq4gwCil&?~+RWt^una8X?s9LKpmE_n=j;Op%V3~xAIM$}o*UOt2p;L8|x z5_YR0nHSQ7^8Wa$GozJS1FXLqC$1arfm{mA&f`P07QM86P^2&z9UZUz%})Z@M@%IFfA zD=N(4C@vRDn+tcm;V5F4mr(uWq@sQakN}S%--}Pr-u^z)l8P6{>ytGFh;#n}Alt+) zSe9w~m?oyr6`}iJAWKi8jieua#OTvrq+oBSqlMQd0dH`i)=~ejNW!(&+Zd?v1&66f)iMQ*7O&wNDiHzVs!s z?ScL+&r_J}9A$Se08WJ{GbxNk8CxZE|G_%g<-CJ?$EczUl8yl#2&_J;mYo5Hiy`bQ za6Y`J`>1wkXwWZqa@J&pju3I;T;<84q78Qu&LOHx(xlMX*1=3kZi~sb#bYc-8fOaD zlkk(!k~UCTIuB)nxJAOkz;J5_#Wwfui?L9aq_p?>DU9Qs!({e$#?KDa{NZ zd0~|CTlD$mPUExNP$mi;=DBHT{qVEW&Ap|aN2jH~?TU2j6ez(Su+w=5{>40e;0*W< z0`%0v2HPVDaJNS!v-QeAactf?xdsFf1y?i%4K7dVA;Fag6%i0C5)oL5U z=U3eOCXB5zJ$p9WHI7bGtbeAEmA*M4mohD8+U%>wK0qFk{3(dK`SE$;Piuas%JgZ8 z;gd;{!v`|p%qHvPSF7JSYadM~M~cN3qh8EU^z)Et-yklKCN2^;lt~MJ-u;d_`woC> z56C^A@n6I4oBo_%%S_J%3!^S2X zkO>MeA><|i#QNYh3=IK)Y9KlHGbRTmEvjjpCf9%^AKS_~h7IKZsG{S8m6{=$6Dl_! zinLlt-Tb;38;Y_KuK+Y%g1O`MZ6Sc2h_f*BgdLc;dD5-d7fEMLm&~@2;T}5?kLL=Y z(eP;m_^5i>w#kVN;Kzl~7KRKakFr|igp!;OLT!GqaEnS_KJ4*D}?a>g5*q7oBfwDDsyk2fGo^b!}L(iAks!^d&s66WdAdU->Xj7f?#-t}7y zh}B`S=PQyYnbVk&A9S!^J_AV$1gIQP{L%=xjfs8(fKF zz8w7dt%AW!SB$q8iuP{Lr zfX6iEwp)OXGC`mqaNh0?iRJDtw`shqM}J zjL6=TM>hZuZcV2a!o6+k%6@>lZ<766n(MxWAZcle&mI#bq6&@pdY8Q?!QBay@PH=! z(bH|&mBDvA1akJN0B6R6VsAed_!r{k{0}roExon?>8`HHL^$ngLn?W#w))=2H*`6nc6kdoNHz?E4 zfQJkH??VS@l-Wi+p5ebQ%@@N7E17flw0~1oj2Ea)y!>>yr9A$Lsz%*2TK>y;lUhe# z*b@qLu)4qhI1u%*z3%UZc%W|n!CjGhP1VjNh1Jd-#->2D{Y~F2Uw2sQyitqkLdQVQj%1U59*v1ww8Ue5Hlt$)ufNy4j4GH6o? zZqi_{UZkj%uNbV-K)#+Y-t)P_x;$DXT!-Sy%Ze~seCPM1x4is1T=F2-+p?yoP>`pGD;^EDJ*>y`Fzh9MKBjCLE zSz#&)U&csE=WnrDjM#GR?={Weeyo*5FS*{m~ z1@;fQ5d-!@jHhi>RMUC$TWymMx5ByNrc$`0|N3PkY>LlG&IZ&T!{1n9x|go|rNZfS8TuVZx->O92}u6Evgo-*oN80DyCJAQCLAigyeCSm~E zM^NECDg8Ap^2XB8MT4ZBbB;XQ9K0B1eXsLiA2U+xdo5X=Wp3;4_jM37>rgCbQX7L|~6rqiK1+nV}t8rzteW$4BZTuTqWjcrZ` zabDQyItZPXx3P?QhaQY`nrBILCO1q3+@ZjizJMpg{k^UC<&J3iCit;+Xp1g@V=QBE zq(^dczn=00Vmd#Tch^f+DIEbB=Oiq#Tb|?67UGa|XP>J{{XCC>2=P3R5L88hM;TfP zfk$#9X=70xc1{M$wYJXG;pwX(Cl_#?NxhTX{9x^TROie1&eS2AwFtNlB--Oz$;W*! z7jqr0QJSp?_q?v3g@sr`f?ZQIOY#=Ab{X0=nlq@kYY{<*tJE@T_5_D$D5T|V(uZtR zG7bAwgd^tm8ptJCnTe~7N8wAv>UHki;Y|Yd28guEl}qtQ^=g(#7Yt(#nw5{?&TU4- zYL%2o7ZhW6YLykp7Z_s_jcP08%a8F%Ms+qyl^Mj8YX)2SY8iqJ&jzWHAolaHGlX`` zvVOg$6cQgNIe*|lFTe4$%i+HUw($Nt4)o9QIkx{5H~vo?h)CGY?hpJ}{|h|+4_;b9 z`;TQ2?uD4GdTl*wl{)|YMFlCnh@+|D!XX35Ef&aMc!YNVau+ z4g`&^G^9g*%!Q)0*-2iB?y3-}?u zoq2J;tV|ICfj8@0U-& zUl1v*aiItZMFpSSCwO>poHPa_{=v7;Y3$OGk{a_dWaOG^^z(LdR%J4?N9Y_dOtO%+ zceo)Ln5gXNTlk#6jTc_W1mc2hY(XWwWZoJs-|L^Y)kxf-)_q@;HR=~+_+PZ(KjFfE zsT=fvQr1$&ZsvxzrVjdcX6A-pWVW6D7lZxZIEKHxs_Q3M?8$Lil&mUBl?4z&`G6-< zK*(Gyzxn-8crZ{;HZqT&vSLZ}sABYqWRw}<#K!Kr1)AX}qsTQ_anHdorVZQHiB(zb2eT4~$1ZLZ9lRcD_awd=;+6*pqUeEjFjKu2p| z$22>+^qBG5u07$IS^Il&vx5(GIwGdfv_A!*X|K{F${Zz{uTK-DxWlFnENu()9ZjRng z1FheqM6@)vhT}a=8(CyJ_t+VN7H;2a27|(m!{(!+z322uL*XErj-yqM$qai#ugwVd zJUNfE_MfbnliBhE4`-;T+*Jjykp}8{CZ4OL%LbB>Dy5?wl{VKl(gB^tU$qB3H0J7y z^}n-XbRQvMvWf1!r*e0+N%T7r6$ct(P`l`b{PGM`Mr5ka+M?80yhq9Y`hmsW$Fgbe zZu+^r%l}o+^q6#zcz#{5N-s{k<9>kSSTt@==6c9PA#os?(u_sI!=hAKdAQg#d~GSD zif*twu~{y(nb@EJb{UM$xkN@Y{(Xkr*+vj{{=(IsSWA02foTT_+)_v0tEMZXc;wW&JltE6Fnf z68be^Qky&co*wWCIuILY7%2r&Xqfu2MtvZ9`3@#Sw$4lB-voY0ylWGkR{<#BC~3t ztJ$76I7@T3xSr68%Mds0Be^=9FqahDy{@`BQdW=rmR}UM2I?pbbdqT(bTA5ifwy&3 z73#>mGzvkqw&3!$LW#v}dB=BH9l&KCgOtI)!l+O4QI741`${wIVUOkRNt9`BQ52Jy zHSalBxW36VUIE(0$+(LKlMV-R^+}8*cjB;=dV}$l)`Dka+a3Ypm(n_7&C`U=lVG8| z+>aGfnNu?`unW<7S(tJu_D}q--Tu!1`DUC(_%?$GpUID;pQYilUIIR4RRa#k)ZXL?EY!z6Sr9;Bqq#bmitzWJ!iHre`oGdYqK2CP)v5KL z8yO;g5h_gUwXpaV#qCwCAFHfWuL8Qa&El6e4o8Po{p&fX;h8E z1fvO$X&sCU!U!&C-AriQ%_6rONDgwMJ{a*v)l=?%R14!N7EoSWyD`K#nA9-!KzzR6 zlZ@m2reR$D%kA~l)?%%bYFcubt4<+bE)&k$wjG_DW#Ku^^4BA4FYtVrL>ya-TiinI z>FXwO%he6~7!;=^t2HVw!G9BOu!}IM)Un!+4zs?%CC7MXaYNn$P1KaXLae|Am#Qq2 z+ZL(Z;L#Q{DzVQqbSWWitKSBka#wao`i42t1P-|=Q-7qCx+}J}}s~^9^J09#WYFwnY z?yyz)o;AlWj&UnZtqhf3u&nFuBrV|cccE&iMhyh}h!0V@!B}pb#j2owbjA8ekRfZ+ zN&>MzzIvF0?`dGvS{?64)ecI)0Y&uVXd{AQ78&+wWilZbc=T2_3{y^Dn)z+f@-PsY zJPg6pAVDKD6d?>U4#5ZN-%`$K_f!HIRz(^F5(|(#jb;$p?_`Bdp7sQgkd)e`*@|ra z7`AayhB(LpK@8s@alFLdK(D{^JWefCG|TM+OgQrrcm+8*%qq0#SnI?Ap&!n-BCafk z=~{=j`%yG>{=gB>M@_Z%$$qf5o@M64FyDbIu)e#`ofCik-v0_xnNj+LbYx^tZcP8lIE z==;x?UenChd;CXjf%U(hlmC^$@Xwe2zl8+0T~ndFF>)wNM(1B35sI?L%eYvA8)uV-rE@hM~wci=jP$S#P`!5zxMV(C0X}j;pnmBBgN@t`feQi)BQ&ycQ_LJdS~R@ zbyS)=E2oi``*wEn*dm#!{2naXt9+(L^;Z)Ca-JyscaCM0*n$NQZ5e^#d3jm7G^Aq2 zMn(omIBcLPGa0f4Q^qeh;e&w=Y)2%&o$dL4BSLW-tM&PgLJML!oj@Q99uwgMu1Do{ zak3UM*1$=Z94)>bmFGd9DQXbZmZqAW)vd0c`X6XSZU!hQ8!Jog&o}0_nw+$hjKmg( zub;)qonn8D`R8fa$aKwjgJu$KXcEb=vm0qCX^lL$z;0b-5>MfF%@L0-n4R9G<-O64 zDf_uNQ>=64slAYagXarA=`Z4_>ugPOorAosM}G+~;>ex_rf3^_`G|?>08dkRJt^!S zo<~63Uz@T2syyu&JS%DAEhCra-2oM3hhmq}K?3Sw0*`iH7k^|UolNShRFh86(MnL7 z9~Pj78M|_5E(z)3I~6^tb{wa4kO-i+@BOGL#(^SSwv0**+@+JW*t)k-Xa`IaF-R%EEdY>Y*i}s z%P2cSiqg`?*rv9VgiNUk5VMUq(yI#=e3M28%Op@(9TXx=pzYO33pyeoVL>egA%w4i~!zn zL45ELQGN?}ieE0o&cKe*Kr~wT-E%9Y0=W!Zmg-A?NaR&l{b?xO7!FNlftYYkD@Vx8 z6(1#xByLxx=sB!7sbdbz5u23I+q=>juxml!rahG&Bc4?~uJX{Urv{$8OQ;Tx`=+g#7k(I5Cqs*y(c$GV zd!trzfxRfbBs@vzLA?xen-D8Kmx>iW2&jOcWbCk}+l|090&{JFiJY@v)4I5-mQ*}Q zo)ufY*=!6w2O3Jps3?LB*4a|%>as=hmr(JJzQs!&Vr;csaY13$8_`6G?qB6?+W1E? zFRv$O&%1F{>XKZtUACHdR1L$*v{jY`l3`RHA#)bw^BlT-%7J(Tx20ZEHmoq6C){Rq z%B*(lYVTEjOr99^rYYT%Hi1s-?Wmwja~k7L>A@+mPMxzNL7J07ERj>r=nRWQQS5Sw zLL24Mc{`SOIZyDvOG&>MPQlLiMs%=z;+Cxz<$$rW^XM&{d78}^$4S1W3cpKsESi$Z zdsj~VPW@EggG6ucw|PF@!|=(rN)!UcLQjbU&%d)l#)-O1=O}O&Pk$wH3kGoyodSBw z7jm7^C2y~s#?rjzo_;I8`$d0A`yn=YVp-4epJ<86-x(hZe6!#-t3q|q2+_@-3$te& z)987Su4XW2&PfeBwoG=m5h5OxC1-m=B{yQQoN%*c=4pSJuP??2c`Hnlb&usM)HIyn zM@To2U}qPjtMzhZu(k?wY*2M~AfBvuIAGcmH#Qvl$86UYj!t9zdIx`OTFaPa!vNss z=yuOi&DW(=avTFiW*~_<^O@UYhq7WFK?gizb$%btqpJq3l;zi^1G;TrD^A)*A6c{H z@ti61gOmeNLE1A3BPmfc~f9Hrgl80X3$G!();NQ zqgFc{v!v&}BaH)*V+?$7-m_^fStWGE-gu; z27E{O<$A=AXkP>=?O&iZK5H~_Yb5`;+s*2o0o9*;a7fK1^o2!=qnz^+o5&T_XF-KS zj$Vrrl?b87A&W&OX`N+iETRLY5^ftH*=p#FEzB$EbXI78S=bcC3wF|hTl3~nKCFT! zB^KQrgJosI;y!rWAy67vpswWTuX|C}vJB{14YF=S-L6HoW<^Pa$1*XTUl5Sgm8?3fM$5E+Ob+#FUu9JZ^&EGzPv18DqO9hI0M zQkG)6@4?309?IN-Zty@!mH&ZopDXIW6HD+3(|-vl{z<_7L@55Pu`V@2Av59>Wye{T z9u|R}e`0N3d4jp)jIgiMiF5GMS1kX{V0I9zA8bKK!y}7lQuX+}7BIMFX1>hxl+VQM zrK52Q;vr~+p~p%l*NFBYKJ$Jo{5h1Lw{H(+w=mqrL^*5v`Uw$iNiG z79w<9PU#loZO#3tQntQ*Tn#_;$)H;4hy_ZTt#sIk7Qc`>C@0S`xgw%F150-5)ADqEEeG-0cKQ z7XHVj*HnK^9Aq!ti|gW|!O5U*AtWZ){7!gcwlY@v@o-4!jP8~pTCUQ1Qz8d-i0`eC zGAqU~{Z|-Hyq8svS!HbmES$-_`xY-6_=Fw)+Z`mf3IR{>@Lf0ih@An_F97px5g>PX zmQ$ZU_hO3?eEGax(0kwe{EFeu@c~5>|5(PMz!H_PV@M>a-r^nB;vfwtfLuE)M&N!A zd}66LP>~DD2`nW?c779gY`s%nC%=hIfP7%tiL!|UUduCv8jT#^Tv7e!Bk2R9{XXto=4J`&zx?u zgf*wgvkA}2DMt(A*EH=3DM?}zPqyvtw}OU)g&{peC@qMDQ^OfEh{r9;)5KH^0jtrV zEvnUpS0YH8G-!&e_o2=aCMd}I7wIb~2~}r#>k~wWRGcH#rSMT#X30fpeKZ#r80us2 z&|sO#YKrZ`V3F=KX-+Rq!^AefAUGt~RW3Nz?(LhRrLd`g4J*xy@PyrS6)AZsRK`e} zsVLyrmcSb+12FALntTWXn=`QZjWQvfQ(h@}-glR?j6i-SP>m@_at7qmE1z%_mk-{L zU1sejeOzvKpqgxQPKs#w2GOG(aT(719(W7bcL=;uC09XT_ZUs1fq(0FPt~JRQq%c` zyLQ4vc}AW{Vp)$aqlz=lC@v767q==FDH4$qZooe2TY(I2UWk#8#vr*dByirZDUIXW zFi-V4VN5y@&OIB;SIw zq^=^Hus_WnwtEC?xRSV_oKmKHh%M4VjGllsc!ceU z<(7FGCKUZ*YnMb&1x##Ui95FD8P~4UT1nf6#oOy4+F9ro65~+FCGzW*gxgy4u0++$ zpZ9KnrjCqGedf6N=4xC4aRPFsE zDbet8^eCk3n#RA5o9DKE&qCGui6Ikbsn#W6LDi&u1d^wm>=>(ZcH3>^)>*f+$-|tA{QtI z&;G~(@39Z~yp@$LpyQxdNM-lw7m}SbZ_bQwFD?$)7b*t4nvExZ%9rQoaVGh#*Ag`f zUEvN-cm2%Nqb1DM}rq6iBHEaYKc$ef3#n=k=MY%;Q;_P2>-RN z{_pLV|J4xq&um-R#K^+Nz?zl$U+YpzKWXES`>RH@(4wVdz4_w!-LO-ol7$-guOcOi zSv~<&Gm7eJsFmkjQdd;krCT$0Rb8L&AK%4Q2^dDb7D~dG%`C5+2kw)s%-r6dzX0|C zG68|!Sd`YK@qc9Nx)Sa*31@8UP>fN4GgIry3kTyk?ON#NGMhPtiuc-dqWum%<;**b zG-9?^Xs(~&Saz7Cud-)hBQwS9W?&4qahOOdLu}m1VeSO)A_OWp*a8je4OR=zv~c%y z?_(r#ibD#W9wItLZ*e(DYt0@p(K`CMT0ihwT^xHTQBF_^l>)8yIAMy{`U2ehn=kq4 zZRor=m}nH3JaU;$DCcOu2U!v~bZDKC2)0-|SYNzTe|3+AS)Sb-<}Y_p(inIxrL*MB z4%BfAE}d^eZ4tXwRAef=@JZ)a1=gF0fy+adsc;V$K%vGeC)L*$ z1p0(*VR9&Q4^%{;Rxu`>VDbu?cG-tK`KigiTzB}+8K#|73~Ehrww%@~@S~?}p9oYx z4iqCmOOnfl^uUcVHiUPB*LkfE-u_k%rilyvjY~5piwi=CU7|j~m?H}5xCcq#BYGJ_ z1AR9(t5uS$i6Wv(L=_RW1Dg&O5AIhdjtC9y$sL|NTrZ|nZ>4N+jgl#1h~vc#`au*m zW+EH@Z8BI3yYYxRc1O}ahKA^FLZzMqC{3)14`Yu`o&i}C4{QuvI|J?~xvbVPQzur_;4LfWVlrOSpZF;OrW*63! z5-Cl3i}N*OQu_ar1+l<@EdY)M zcR(^a=Xu{M_GoG7+K0p&UP9md98BoP&VAfNnONZFo*H24y3yEnBnvCGPYFF)UGzvp zU~=2~#pKsM&ZBnMC%-%PXo6B^L^@GLH9J3KSmV7qPo1nS($|96nI(5lx|KFg3fn1P z7ny7SzFbj~j5ANYbYSc{e)WM`g~`K^GF>tPK2yRZbSBN|72%!UN9^-`=P|QH zBNf2Nf1Z?{Tfj~8Q2^xdhbChw=r9^~a6|&9h1?0MpV*WkwH%eq@u-T|AimUMkk#2r zn?BRJQ`XL9yr?Q!N?G2T9}Iz{c%Oc;szRfIj+!00vbM^-n}z}zPPbQ=0agr`CiSWz zP@lsrt(ftoCXZaz?J!QaU@KKxGf@hiUj7nlMtn((DUl^eR$+?6JO{}sBLa3sPar(U zz%xumVOk}O3yQ5hdsATRmt(TzNlgwOsM$qP!%IDe- zFg1qgba0y|N ztcQ>z^2C-T@&w<8SWM@--3sADl<@}g`(g#cUuXbxURV{(d~H5Mr6(lN70q-9#U83$ zB|E`l$4Ov>T=s-ejnAV*Z{n{NjqtA#W_C7#yV&Oz#o64w!~sGye}EW1AuMnp#?liu z2jw0G*k>Ubyg;(=p6s>4tdm-<6pyBU7C*h3n8gDE&rmy$c1pH6_o4ERq{=FW+7T7+ z3JPl@0z|%b^f&oqD$zvLoCdv0ldp2G_}xCcvX`n7>l<@RNu+XCVCIP!Ju(InhnTi4 ziC2;d^X=*(d$dkgY(iCAomp^dLK-42&g4Yi*YAAq0oR$4#poDy^{UVxMncSY}z~K0m5lq>NiugG}Y73KN-cY7l4`88aPE_ zWf_pJZe16zGhXRZdUexQyae-{e|GPbBZ(}#k<=Hx*%CGEs!#1z-VpT@5RS|t?K^6~ z&q=otvk&OVaA~637TDx_1&8}qK<`VP*VoqlaN*Nl!6@%&pCfMO#GdP30X6Q3r^9kj zl@82MhUn7}d-q}QuuX^X+o-;@O>KamHjPdbKc{GOUvLZ_5t#tHB(xd*E^fKO(t1Vt zz!(m5+~}w5Pa=dzh_F-{Q8w55wOv|4W7_ILV;rp`5=)Ss_DL*YcR)R^*{-ogozU70 zKG{PM-5wY;$!~roVhV6QxKHG>28QBPPSxW%RH^nfj#pf_p4P0pt0zIew*8*bFZ8yV zHG}i%u;IVO|3@sbNIL;y@N;?pg8J83;@^Ap|GC5UueS34D%h*;{Pf~czHG%CjCFiT zQK5ykHdGRm6AUk6fr#SfU2P~6Lr)*6d%b&*3M=(e3hS+xAYv7xRWyDM$ zxA?}-+S#PAD6Wz?(>J|l+E2W9+E22)%)bBL)b;{O?`NVkyh@9JsVQgmCq-CH7Kwjq z!!#Pc3if41c+ixciZBElXse7_DD<(Q`n1*ThC~2LQ~pwcfqat!WkXFup<(bBVB(p9 zjHp>MXNL`Gm7Mmm{Yd^(q1LYRXyrm(C&;IdLFH7t&zXOdo{xOC&28+Hr)D3S-%IPT zqXpN3(_n)4SLXd@mW;1~L+3t7vadqRb%}D-xBA#CT5t-gG8Jknt`ii>IMHjqFdttu z$5edUJ~p%wCOpgHSPgSu#Bag?gTi5^eW}WZvk%v5fmEjBa3iJD5>$IMo)J%#1J~yh zgaP3U$Kh{mnMoQdd6Dwd;k~I=+t};`*Bb8hk<`XAPbI8toKAskvPZCfCLk!EXVu(f z2!~Wi#g@vSg;1K@`qc>isOJ(ZkL3RQ;})aP1s$w0iE!>+nvbbJt~Czv>-pCx z(h&Ht6YQmX+%ODP6t9v4Hm6wIeVDLjL$`F(43k*|%`+|~fej&CZPXO1EZ)&9uooDm z1=#>ktJ`Q{oC8Pb`|K|^rE~yLQY4vpZyqU~7$5~8(6v%KK8Vq3;074nnj9U#GpR8d z-yrcajM^So!)B+{v^D8NM;EOpYPM-2YhTXjbUj!F`1YL+sm#tTybaB6Xl*AeZAXlU zx^RT&4EP|+Zif}47sOeoW21IyhTCy+BP!jWwD4Ew2`Vd)a&`x2h&gn3&H<&pk8unE z<*$8c8f}Ynn4Z07-NNwm1q){$a*?K~Oix@>66>Yg1$R6Nl3|Iod00kkV*0d$cnK&2 zAA(|yb>aq)__OEM8%P|7fbB>y(lsDrQNGSQM2BP&4jE!mXr99jatLh0&vCyRyu`84 zpYynhv5NBmWREw5TY`Msoa3-$2NDNGvCD+G=Lzw`!-gbrYD1gw4Y{H6`5WsbG5m<` z#6syPlV3=hmRZB{FzIkEvbfJb|JF|z~LpV+$J-Tc;oXgn_k?or~=cjpF}h8kTX|P)6aINukwJ2|t(zknsn~Z^jLKm{VN; zJ*%H!cs}gE!HYSAbyY#qU5eLV4@v=o#j0#^+IbwD}G@Uy{v*7iPhwK z%7q2xt~P*_qN2UTx~ycy5qJVU%o+vMFrS*hocw%PHveikC}RsJ z7pYD8{$_iP!Fc~fGM66}BxvZsOz zP2WC-44FuBwOBEeF6hyo#f&-adRGcX=0qJc88&BGvxZ`>;g)ze7&mG?<7HKfpt>=$ z2`J8f#!yM}PVAy0IJEATyVw z;*YE*-nivTc5?e?|KSKVi}YsF5hCZhCL_&ge^6)duvlef=gmP{)Jo2u4G44sU$*U- zSuHy709>hQJ1U#Dl0@K{VQE&_DdDSs}u!xs)ZF^3PJoy}+9rIdbqEkG0xioRyhI6cT@L+4i?`U~c zvb|dt_SxZHH+G)G70Me96^;)D@56>bj*`A`tXACLeS; z9PW)<&4Uaz4A%9_MDL_t_uk6AJCS=qLUt7F`EId0;IsDQ9@%Gz{G*1SszpDaQ15Oo?yagR3yytB>qH2}SoSooy3IyC$~c~fDb0yJ20D&k~J z6;tUce6?Za<1VORL%m=);_Oju-~W(Kak(WIuW zCSru>((L*$1_P2|6Owq@Vs_dD#?3pO_$n*S__V8WhBKJ)NDT{eV=V!D<-B1=rW#|` z<23|6J87);vYaN9vESq6WUv`VEqkW8lnB%uK3r{U$~Zp-u$K1Y;kQ9y4Gva!iL?cU{k}T-ec{s2d@AU{HX?;cAY8LboX@RpWm2 z1Au1696Jo`L0ZMtbfEX#Fg!x+P=z6w<+kKx9JXbJo#@(+ewJ+jDWJ`aMc<7_OyLh+ z8^(f`)w0cTvjpAn`xw^;)#Q$F+D4wol;NUGf3&dmG<2S2!C~WDE*cIgN@Tq1A3q;1 z(sGZY61rjt0Q3CF;ntfv-i$f!-Y)SZq+u&_b?ZlG_srzr;GvYVzUCA&Jp@YH)#tn* zIYd+%>wn(|?$x2qkEss37&TNJA(cLJ2h;*tKT%_gZ$Z`=Aru>5A3QpEmI!U|nstbp zpz4lEy=5FSHPKvHF22`QHLZ=IepMe(!Oh*xh`DIX-z$lcyGxImxeMku4%R6>km@Qw zpf>4IJ;pY%B`i5;VRTdOb5p6YV;J()z;v-a>{7?U=a9=@xy}C5(=gKzasvuit$POo zmeZXB;Y<%jb<)A4h?9Mz)iaS6WJy)Wx7bs`<~TsQfNMs?WTNithrfH_ppqt*x|nxl z*8qKHqCgw;b=2AA*dpe433BmX6%r}LI_2$rI}H5{x9XtO!` zI8mOJf=Hq71ux@75FE};O5-hZD3Z2&3}j+TpC%G0t?#BA3T>*YPx}NW2LMpNw3`|=LL1~&X-!Z7*hVgQYn|IJX6pvx9jYHd*Y)f&m_82<3pO2kF-lGawof2 z>xo}uL0Qss-TsD0q#PXkEg@UJe)o*Si7eXsIcb4KbM3tej(^K|Dv4N zs+I>o{5P1*2F)W>77g7!&SEd&19a(0y^FI^Z>v3c8w$r@WmaKYFv>p7ImkPwX}#*M z81qAk?k)q?J6HNeJJjdr&CU>Nv?0@Q+sDDC)4~K+i60Yl*N}GdVG|~}!>AF`I1^-k zXfp*_x5+OHnz2EH5}5Qh;{@8Ev3SO`D(bOAEG8ZDL~LWnMi?@&3H^EHgfUvv4jD4H z(L-BI=@`OernNI3;3Z?EwBh%UH))leZ*X{>nW>-2@Y}jHzCsS4a-;`40$Gj9pE=|Q znUS4eyjJhUAfotwfS&JfTs@~8>+1VBJck?^I{P@;1id(hNtNaI%fYC9;}+HhNGL+Q zrl+}}Bp2SJP*6b)z?*RL^1wy#dT{eeVOUgqB9~fuf1i58v*`Kk$DLH2((+0gT`ol1yu)R-26Xc;!XQRu({q za?et6qlVyO32HL1e6_@>IO(;?-)md%ccERX0>VXnfAC4Ct3dM~hv8S#Ic7R9(>W$P zcl^A0KZM68GgmY5HBZ}=WIyMwbp!_3W!V=pH4s$kK%%Y6q6eag39F}9cES| z1}u%~);zZ9gP(a%F3!FpEP65)&4p3fzE-JYjw%OR$6}jnH(mTS@)T^&rSBIX)|URD zNgoT3)?#JF+3YI`Vx)r8w&qwJ)(LcZ2uD|7c!E15fHm{V5<%9ZEXQH47r7NLeeo@R znV$F3@SG`np_A_Y;lq$41eVJRAEXU|EbVCF#>8r*A#lGs*#&O(vd^|(sB?}CA!8LE zNBK6oEPkkckAO`4P3<Pgr9Q`5Du%ZtU0qP325sfplP@N-VlA|k@T@U#wKXjFkF=x@^Q&q1$7>Mq zKfDJ2zK^*6<39TTNK5{!q@kwer1VqLaGf42CY*%^p^!OLoMpC1RLs+sjBGkmqy?cs zqi)S1E4>O}4j+S5q=%nQLjMaHb>I&_O>y8qpOO#pemGiKJIy}Lu8Zj+>VwwngEaqG zlKnp0y`t;&Lne7&Zhe-(|MGd^^{;j>gt@R6gyV5!rwm2kEEA~3F1;<#e&)DKz%F$d zhDD#|beN7dVZRaX#h%FLVAvJqFq9qKDif}S?#Ke)YQjmFuY(TBq8FbMAxDypVvk3$ zcS-jYWm3Wflv86YH{(RoWUVv<9p4`g%bCQY%t6utLTxXaiytTT;N@gbTap3XusC0; zx~rHzFdbh+;z_BR2XDpoiY_u}fm{VH?L7A^zY!m5*V(oqc`9s=2jp>5#1@xVTFQ>F z2-l@G8g&t%q?=_Vvn#TmUB_X?Sed?7{z2pwH?P*=g%^v8Dvntj3p0hbia3_UhvAHo zN*7{urcexS_S;Y40loxGF!0zoM)qinGJHJqZ_VS_`34f$-NKxio-kWW=EeNze=M@6 zBuP5XNz5YgyOqYf#Prx%5oYPa+r`Dp!1jHE~|b^Avswwgd}fmuC7wlk=G3( zjnY`BVwY~&*wAP&C)2fziA*HWC%7j)VF*b~O`3$MN=eMm1weaF(k!WmCpdXYxi~Wm ztJyGqPrT&2>Z^303hFjbp1)Aee#*ne#bY+e{1ZcJ@W;)D zmFX2{syJk6(z_q%+W~s$Z+aB#c#HF(;@R9O0qEMFg!p8q)1jE2B2vc=?v@O@0d5eK zTQJGRH@8NS;f6=vqPuI4EILtQo3{v!n|2|o(kEl>Ji=cu?dcytKeJGK(#xkeO+%{= zT4PJ~#gZ=xd`T*echsG147Rmr?dp$@+!J9u!B{~65Ced~o9)2K4d6qrV})QtuKzH= zA;N5jc+T*^m6Ddk~|}&`1Q1HtgYGwObw7A>1+^LP>d9LQo6#Q#29i+85|46H8(()_AITqq0@XIO>+I#jRp-J zF;%&pVfZkr*|&MpU9yUeDPQENN_A!Va&PkGoN-mQ{|qtkm747_8r?x&$FGCtD*)xo zN9HSp?yW0}wMXi0Q19J?@f`t}fjNNZee=_>z%!+yJv^bSZIgId$g_OuaIt1 z&!drQ3(yBS>kKY#xSJMIl}I)$CpmaSJMP=JfqMs?&;LM*bW`96zVG=oL_&p60_v1F z79yz@KBH1qmxuIw#afoq?>=X4Sgg1M>fnvMF_3uv;@%+ldCNJ=rL&AP4v|+NyHqF6 zDnp}Nj9>)$jotYhoO}q%d=WMr3OfEOitW$ki~8D1UZ?n?Gh!%nIBmG5jP^yOu#3I! zbZ+No)bs?i3EG12Q2pm14<8Tc2Q@c2@D4}tc#p(a zhKi<-N0pV33N?8hmAK0X{{Em6~*~3l7KQKE5ixd zoW2fyy~9HX7&N%9D#YMWJu)}})iYCkkkf4%|I=j)?95PMzepgiuJpz<^EDL)A6xC+ zr6i61=V#Y&%Mhm9!6^6e{*F^i6y&MGg)+)W)f@W;5{SmFU!}{f(C0t(^kh|PxF$cy z-vZcwjf(y~KmN~A(SPgd{|A`w|2}43_R2@7d^^|OUX7X92?T6u)`4LV1|B4c>K@P} z*y@lVi3ss|V+~%3*5a-M*I+(fo& zuIqeUSI#A8Kc18qQ;8rK0J5En9H*X#PaiYBx0&DxVPz5gP76++pZ+N~_r!oxP0%;V z+f2}wf2eH|H$QUo~&WixDmKS8~!ysis(igd7H`LVoP?wK+6>qkllr!KUBrjWjok5gVqE1UqR z1QQ~x3tMKmF*Du7ZNk@4PV6G)7CQHCNi`IFD zCa@M8cts`sNg(w0j+X^VK{^SOZx%v8hT}!irPhCqmq{Qxgr)}Nx64vUHH>FM$pvP?ei7JIrjI{d&ng7wHYr?O(Ug80kI z5Hc=m{uglYxjH)w+(tj@58ry|Pjl**193Q@-)Zu>6hVZR*OX z)I<>XnWjQTl3bSq4t=&9uZ7?jV;r1{Q2*AgxQT$ z#!8#FDhTb1v*;TJJ{mtcO)+RsMp<}k)VR# z<}`-SK|RnCh%qCI`Q|k3eN8oMU;_oNyfu`$PBJM|lSRx~9PPO1U`FCIC`e3cJ)1h) zNY)zINv3C4bHa>E`p<)InTV$=nPE5L9~!>X@NOZ7xFyEcQLcl=lJ*6pB%vaso?`p3 z%L=k~{hPSaFNBa;_Qj~oufoY|kZQw|JhP4HV-RxwYg_SQH}&%)xHmD28hx{M+XRi7 za+%ee$1a7*Yqntx<@GIP^*_JU@>chT(~qCVW?i*h4Yrp*ljUTzaZ27@%RmEieq%-~ z-kb`4L1w7xuAr{tR)h^x&x`e8L|I7(l#Gm%wxb>X1rvmTeGHw_jS*EWM2z0~)l0x1q6FYnC)(9uwDe_eroECZX-%mEdQPE38^wrx=;!VmJbN z?v-_$waiwXr^-%QfXW6sTq#dseW;TyrCqFAz|#D&0=}_y7O8Rs>c@5jvqVxDW6y;#i}~%bpU*>7)vGRVKd$bKDpXLXYjh#dt0*&DK)$6 z5NVKTbg*2@lt?eea3zWVehxY4<`>RYanKm2hnKY{*$LO!sq(R*NMFY=Op@<6ZQ}Yn zPQU;?GT6u7H~?~e>>|p=Ib~eIYg!ZCuh&__pjQjqRY{VDqK7J&=QL;y|KtMP#B}<5 z+LH4NWGc^_s(4K~<_X7EW;FEgX4PNr%M-IJba_Y>`Qq-{eqTb`hL^-TJ!xMrKdxt~ zhUdv%W~*KpKMJ;X(W^1c;4lwHwam@J;X`fW6Cv&NG$}&hsz+v0n>^07vZZ-Zsc}p3JyuF^MN>HfVreXqq9~&FnR?^f zh-Os9buy`SEO8^M))}sPNv^)-Y|?3)NGGLkXQapt>u@iqit;pSpMj(UT*6kpJIry? z83YcG<&e=nr)dO8y*C7I0}4swFvk(w?0}CjMfpm2tjmzd7XqBW>^qSptD%3k>6`BY zfL>PDl{MFIBc`1Fz0kITnM5pC^(|gOAB|pI>O-7%$WD%udlbtF?6P?AB*nx>2(2Q8 z!0|a5L#sI9K=C6U30v@5K%KS`j_$IcGu>4~#4#JE5Tf&dUx6V!ARiVdDvQpT zSuhB_XYeaf@X+v=E^MWsY1ztAE+4UCh%t2{dZ%&;p9VH6C} zV@L`I#ju>_?e#Q$RHFQ&>VT;qcnWJgktu(NgZYRy{>Hr}IWXD{4UiS-|67XU(M=&E z)!@O)nSOfxOvqxHs;md$yLEs@Wm$pDkxO8NS4qGt_c2|z`t>HX{h@Eg^vF8QRXygl z@+d4N94Fw`)H{z8{CfoONX-QRgQ>;u8VASh)h>VgCU3R$*C$hkWUtsMpV)4%KX8w5 zgD)t_C)V&cp!mI5(syduPOi*w7vJ}~lyS_Kj7jdLUGS!{if+?K(uKH-%AGoImaIrG? zuDm%Kf10K%+NR4Vd#)rjN-+L|;nv8odE*#~HNalZ6?sIS)O@&mNsee}SQmja3rFm8 zh-4T?fYR5yty&EbC)m_{2W1u^Bghcw0A~$+^5S-}Z)dPPR$XV&qVpL{a$=zjCl=a6 zTr*KW8|)oWW3v22sl#|WvN>3y+z4U7DWqU#IqCf1{=5wl#4SSGqNjp1)^H?Cq+%3A zlSM*PdFf5T&OzyQYSRUQy~5BTZceh}g~WnDFk#YcBo$@~+d?P9dgt5cri-ePG__9{ z==KgZGL%|NW5ITFaZzOf@0oEDC57nN@h0cJF+Q3F8DJ>-e7Gt{1hU6o)k8G_G^q#o zC0{!&iOhLcx)hBCq&Sf!m^dgJ1ink^U<J<)kp+$}XljkY+cXL@% zuv@fZ_n2=WyQY6tF=ua4oX>;0L$VyfP)^@X`w(38Wt#5rPIY9fRo}aUe-GB%azc{ARv`kU@&=_lTX7 z*>_;Srm#F$Pce+N8A6kC0onEB95VSPE=zUQh=>-Xy{_c+-Zr3ma-!go`l0yMW)%>{ z*oSjFV@NJ3E}gBc0tnqnLeCbm6!#{xVXOm8iC69npTjGy0a&D!L~A$}a+;27Qu$NP z{7EvSl;aiy<>wd5%2RYmuthB`)9&I=-WSm%l3lR8LjoO~P^Q<-H@%~>L9Qjl*KK_O zJl{BWU3ECk`^~H-bf{%=`7kR~2d%v6!$vwMZTY&LdNwdLkPvdpj_u|Fn%NP5wK4c% z5^;V7l2?(+JpquJ+GK(?oMplhQX%|lTe@T9-bKG~Z#Z;ok2RHP=8pF26sa@BAzHIH ze6YI`sS{#*xQuQU!n<>;%(9zU!;JeJ##D&^0mJqZGDK$^9%&+^J;`&Vp4tXm*6)?d zF4n$J+jeP_ckYoi^J|Mn)V#$#^f(fF6vUYT2sg|1V=Q^}f$J3O;}ay`rSI z^v59mslc5SCy_6x@n7MN`(IHz{H@~P#|2u{3APJ&t&*$;c&^b$=I9;sTk~`6ry4H+ zZn*a6z^C+Tgx?YN4QgKmcSH~$#^u{EpY8b0bj}x7P591O9T}{*Ria>Yzg@ujPeQVS z9`lm3m*R%9-C?WQM2xShhK}+vg6rQl9GffxumC@eZl8! z>c60!ea64vx0BBLj3({@686asK2a*Rdj)FAsCL`UW{-*wUNPMcX+Jq5%YBG|^FvZA z243M}P26x;LA4VmbKyCCjpaWkp2q>-E*gPyoV~-(2DneY%O0MjCiupP1bJ}qGz2m| zc{Q~#JieKKA=7vD<~qJvNJRb>Y1bEZ!xwj;Wd8M9+62tOp#w$R&mB4F_s>aT*T3z; z>tFx?A~63oFZy??`+rs|{mY;MhX2Zjl6HQ8Gye}|?-V5ov}Ns9B`R%I+O}=mwr#u8 zs*JR4+qRuqY1@cO`{p^PyGM7A`~TAf3PsAHyJtC%;OXM2mdt{9acPMuoyN05wME79KD_s2wHh+uoLxD)81o4NE%x4tef zv~8gvLPBcTb@e=pVdhZQ3eQP?hxKE@o}Et7*Urk9|*ya?|qqXL8CpfbwBXu3w2t--(` zNU7EgeNH494HGJP&lhL_2>lPxfC%hT;lDrwNH|Ylpn+1~hSzf9#C=NWov~keW=)x6 zQGQz;YgU|I8%(-LUFapiJI><|6AiS`#zT%5IU8LjWHyT(xb#^{FQoX!QeBsH!m;A4 zP>j<(jM^Cz5`%g6f~0?d25jKr{skI1`km>1syN5d;1Vj5wxmwNAI+%s1sbqmH?lbW z7id6I>cIL7G_YqE*VO!N}Ag-TJ3jXJC z%yk>^TJ#CQXFKR~(BD%b0{^BM|L;aj>!UHk2R8rimi#l28Nmyj!~Pz?_dy8HWz9AQyTiziu9VA)cNo{F~7!yYd&5+6~0 zAd$GGy}mB|o@d+FSMA`fAP{U(Nt-5NP82cOEa5{_o&XMJxq-Kt5eYBOG>7!v{#t_w z1v}aqmoZ*ED1C@sPy+(OGh?)W|qn@AQYVWh6?HiH!qSzVR&o|iqXpj|N)8 z%$U!^R^HlOpJIb|Wo~T=|B94LWP+P>6aDJyx(G^d7VqN19<3Bdj*O{nltFqsInq=j z)WccH|=?cRgLwrX=u~r{Ddm@*^c2{-iwvw_vo^|$WyZL z(o?sl>8W$nYg(SW*8w{z3UMM#BWKaeq24|)=!CMB>YuCAv~;AXM8w3&b3dtv`dvXG z5HVS}#Szg;70*yj^S}P#*Lc0OR|3$3rf#B8=t_YFSsFoHi5SPD`)&o`LY9mgiD`z zB~SJ$MhtAdgg;=Z-t}M+>Qm+z1At5`l@KR2ijp&k{NDSMo?eVqf@V$E%Ab&5cLCP6 z;0FF6M4UZI(4RRJvIbt@lNrsjZGdwklaV!g1SQZ!JK)fV@8=}N+@#k0B0 zu0v{Z%@q|gn~&64{I@)dJ)b95T5bTx{9EfPqI6x9xBqwy0@farAFuT^0PANTJgB1I z#X-dRoVfwQ3mDrZ$s;M{FQvL&nYZF>lXM$@;XiWzc6F18P5INbZ=sOkUVG$Nuy3S% zmImxbKkSC!?B*=O$?7(Gu{{=gg@3w6p@p{URI=P)>9IS|QxGgo3n0UXEAZfLqJ0?! z&FhVR8YPtykIaOm4OwPmUOJn3v}k;Roxk>6EQ6}~Lx|QI`%R%55;l2X=BJcv-j1(4utD}YzdFi za=~?yw!`|MiJua-KO>=+a`V$dKyewM!Pc25=TMc)k{v7GZAjXM^bT*cvqS4}5@STk zv$ts9K~{RqKzt`%EmMaZCrVh(Op`32s6bAq3W)=lM4~GwX~%lM|Ga>IM0f~(rJ1K? zrcC)eU!19)e6RP=q?<{)S*`-R;K>mN{d?MyddWfdO)ss!X^F!kZLSJF*c4;fi`o?u zT39tD@ngl|SmJTL*d(hvV_xN2sj6(+=eG6scolt|xv<>dU)!2}f3w9^S>M0Z-`d}S zVFmL7+U*g+?Jl(AN02VBN!-%b*3$O?YdZMkbGp*d)8k6Vjs=1vhSh>*H?GD7ah0L7 zI;zPNKQ4&n?CXoExD|NBuQZ9S4bLXqbGUm5Z{eySU)`##tiG+jkEyCn&#Pf(_z<1Y zBi9n@bUAT1By?%|NuCW^pkfxaP&Vtt%fN15_0m;<5(v%ExK6e_{ZWQsh6i5GQ>yh=9>m{LURBB68hrPADd}|B; z%2jRpb3ifApG~|@HgaI*YJvdZg{y{>JO6`nLe1X0q$&qY}N}@$t<=ZM9;!V^R^s1hBGPByu(J)qtV-jewen#2_QyZ_!;$?v?xsAk3qk8 zr?20Jzkd00jw9EMoU>%BW|3386*ojG8Up3nX>L1L`%5$2ZkBZht}CiU6fbYUBAuTi zS1Hg<;k!epmTRBO>wTd0kN%1$o2`elI|FOYr0r)03ciaPwe9V)tFQ6!upz`0VLyJP zdcA-*z2z1iezVjRxTKkPswOdxI2}gTHVCg34%TdjY_LHx)3kDm>C!%;cq32lXGamn z05zl1Aw5Jw#SH?IK+{}(P;mk@H8IVY8;Rg+ehv^h2E`jENe(0%*U^p`VMh+3qi(EA zHvH|(#o6gdf`U%_BdP@Q`i7EvNlxwuPx{AVChw2D5TE!}6@QqMpUM-Sz_X+ZJdSYE zHQ15NPCWBRTfG~O^LtaLU-iM%7Rc5Cx2Sj5YM0()1qHBOo?jy1#5KlPPwkYJf?V*5 z!0|CZRe*XVjDm49G^7q3L zSmUAby;)DwGY4*k54+a4dG|pxbRUnL#QE!Iur@h|c?>*fz6YkbvrT?0?S*;*`9Mj{ zQT@v_PKKDn9TqPxIaZ=54@H+jhGheebz^vDdOIslG4qMZXLXpz0X36c^N1hz$iho? zqRw|mK|19~vm?mLCJ?lKh#0}qSjkSU&KX3IEuQA_U3Cu?WKT2<_A5>IzE$+_-l`i+ zJM)@s+i)5?)o|x77KiKbD&0h*=Jo`N2KMCsi0A(OK3O^S?<`(CIrXHF5dNMjbl-BV zKqr6;_ycPwLxZwA{C-awaM93*ZUf3!>{J?%^yGYINwTMpSX&$(6Yqt?mnT`LW|Jl& z0S`wxh}ZCoD1ho`4m38C9*dAg+zeVh2MJEmz5 z!UBbVaB*)0K0vs+mk>r0A>zaF?3Co@lBD+3%ssyM;`dbKD>074BC12m8NJaMnAJ1~ znD$H{orYtQ%4Pjl8x!>g4;hhPm=KVTZjOa!&IODGgKl{PaIjigQqn0l)TEO z={HXB9A{_cRrl+h53)2wa#pWte0^MIZ#{a-GAm%sxYQX*2b62(9&VJ&Zg}^xeVT^4 z?fN?l*W>B5@AtG#bGuUR&rmPtpdexN&_x#>feP_}rC)7Y#OY0ktxDPv_iI#l7E>!_ zx&f(6frZUKAR3!m)wN@U*TlHPrbu`AiUKRcltNay4IUxEuxAIrPT;{$3_)DN_GNUW z)H+7!N|rPaRUFw=4>NhSAavFiZ!9u!O;ziLO4Ir6Gz*PLK+MC7%qX&)+~q=L4VZ4; z1I7$yn9>H~t$8WtUl`=iM~E)pOXsRx3p0z*8;B;=fs=mjIl5D}we_{@*Tg~W2QN6J zPPQ#Usq3Mm(LtO|I;`-A#1+Sc-o$a6{KEAqf5VugF3wqIs(ThjVtGPI$>${cHcY(8 zbMg+d$h4ea$ZFqyU;BAXu~M73!OfKVoMIC;Oz}&g!ID$wNU5!EBqpuNI|+9Lf!xUb zvC0wZa${$+44W;(C7bEMUvCOSoC6S)^X@^;W;LsE(^j=Ue#6T|&Sia@T5t*!uf(a< z)R)#uoMU_fJ1Q;oqUM!;%=8_Q&{na&<}&KH7v3xJ*35}qm)~bbzqVCtPaUbeC5`G` zP)3Qn3ect>*4cEpNi_#L6oANUvX{&peb2z5#jx?+h3)&m0chPl%^Dil+#HlHcixtH315= z5CqQdOBb;fYv@Ou-ko&HYMjD5uQG|~hZmYhC(ua9z_u3T4+Uy1LlJp|?*?H{LT+a( zh8exx6Phx*nt0rA1@!EFlX=8)npa<4rjK|%*^Vo40PFA`dQSM$!g70UoslXBR8HpE zQy}}Pwa`V0f4@=Ly-QQTRAP>3eF`i~tFX?2=YL!zP+U~=uM3z4i5&`|;lAYN$TtCI z7x0DR{J;&)z=pu92gx1gl`crNM8EQ@-a%=rQ+{H}MWN|v zCf6kEVMM5JC<#=x?8xN$2`2gAos;zC$H~x;p0sE*$?5xH(Y<4O+!<5M<%lNv;YgQ4 z8+dwCR(UIgDpM&ZBU;gy8#P2eWT`!>#SbkNBbncLswSdqbGMpb?PRwVVCm<+CYH?z z-%Yawy2NtLXW%f+=p(4Y`Rp^?X8t`5qr5FsZ-VcwQv*PMAGBYbBwJKq*7`oKj#?|`4tFo~*{@TG2zHP0l?liAfH>oM33^?|5c zBggNDZlGILIH}ZiS!^9=e}F@kSaeTm(YlvfmhKi-DN|5n0LaSc50b~keh2jBE|;xU z5mGjz)LcIOvchFIdnZ45alg&kh+E%;tE4YT zS9v+1R*#wYUTIsz^lh=qRGBpKz_y`JTsh4Omo<CNLB|dpcLd|f6TZDIpY80Ef^nwi` zaX4`(Z3W8FV!!))c9lz*t6K1c+a>h~$ zmZ-51sYGoKFMG+2Y0;T3gnrtbLJ1$Mzs};%qgBe}3`McA=R0xdbt-l)2dDQB0k`?S zZrSu>6WN%!9HMVIAT*u+g6B`=={L6{1TS^g;6K{+p=%oxU)yMlB#xVZ^U&p@GVy0P zT4JU8IJk}{9GXDdQI}rW6FlBEj)peqc^2#4>)x9$UMlDRfiK}#sS@3NBZ z(prf-q+>d;LmmGK>&Yv1h&P$!NRwPpngmsuC<%7R=Q4)cJkCPI6r{*`bTb0hZGp)d zKrj0$asQ*+ChY;s!pe6{vQgO<_2LeN zF)}(tIHrG(59y9S2;H;F4vYoA$nlJFg2Tij(~W0iOKbUopo*97h-#U((>39Qu9~!W zej;r=vtl2LsZBn4am=ltlAp;7hrS0@=6)DO6l-P`e??}px`%wOFkB-l%gyfE9@%Z% zOsV!~fs4>DsgM2gtlR-FA=0=JN3H0X3b#PH_ysnfGwkxtAjH;$6+h&L!;;bT$6Tc? zY4k1xKIE$OL5sMsIr8ffyytIxMEHY-;}_x-jQoW7eZfAkC0~AmM?(Bf;~t?F{<3bu zH(J3NeO$e|ffuwl+z-8wd-Y4HQ@ryUTHGS=5}vH`_7d)G)BRR1oSh82v4g0I%3}5~ z(DG)U00oX6Gme1(Au)QHk2+H9kTbAk6^&7I1-cl+I3IM^zZ{+?&V>scT8F^{rd%|b zx)wwHJJuu_q5dk3A5ex4Y54^(mjafAUZuX6c&dztX;|{?lQMTz>$8xEEga2bz|uu(6K6u_~{O&W0A7bZryfL-lFZveh9xA?Kh1sj^Xj4 zF^%_4r%+9$Kw3s7KE?5{7>v}w;=L>v8X)^=u*S8Y!iqr`?O+y)r@I;@wI8C4zhD~kc2uC(u}iAah=dPi)a-CHkcC`<7#jGW%PPF8s#ot|{Ot2ELoPptWI`f7bNU0o+Frqf+4kh(@G7png`}iOMWx}Pim$+1hJGueq zpKXd@urp2NI%pJl6?0$jbogVq1)YJ+ogD?8wVHC%MD4U3X0E23#U5StrcXRWEz~;4 z(NP|B?J&TEo=&pqaYr^_=7?7d%06S!Z zX$UMUTlimh7qGVdVLTJ8aBV}31Cx4v9>07J~+_xVIiGR^t;y=`WgK7 zlFzXlRvOVTEE{2PJk-e4u@A$#2h20anPW#MKS#fGgQ_6L*TudhX`p4)LE`MRMnZfR zkh>iNq~7zB1=w>rt=a#QD^^F~LO3{~dvH&DcmVHMKMT4+KS4{G8Pv0o2e>NjH>?=;o!RGrPs5 zhkP`bSiQwaNN~bh3JuL0CpO-TVv+=|G&KB*uJXnm&?kkxv{g}u>t?9QG*0J_>m26E zYyRb)Z=J(-fsh$cYaYn^mVt;fMm9q$0H988!s&*B=-QGP!Biuevrc(&o>=a?<|z`C zh&_z%iaW^e)`vi@t4@xSTbsVc3rAU~Nq4E?SlXgrR)tfp%M(TpZv^=l zl^wVRyJ#5d`yg&Bnk*O+^83MqyF3To>M2RRtg>q=Q3%UORU1g0jsCe)cQ8FV5;P6R zt$LHdHx{0P%vXM$$@d;{q-ShwgNz&nu*VQc9dpFi3FIA{g3R(gM?GM{%|3t%%V3_ryhAOF~0 zwzI#5uJT;*Mp#czeh+fJ86DWTV4MN@=+Ij=2CWtC4Yl3aRUKvQo7ew`0fcG1X}#jh z0HX6h3?TpiC9_I~b|&_=3YKp6E|zxY$}V4Y2~%^=e?7!yDQnCBQ9%5VYf;ct6Bt~t zFZH;jlM+S5XTbt7vbsT5kU1D?*c7I8lOJ293;Y}%#6XEof$;yuKmODd^=c3dhCiK| zb~?%K+@1FEcK;6Xi*gcmE(*r?q;H6bZr6#wdZ!$8S#VKssxP=#K{`!hxMI99U!>;- z18k5upx`#bu1Kk*g2}D|FJDlGz6axkRf#>mxc85ek&wLIn1QgT;Jgh}pY^zl@!EN? z$Heo!f~BcRdMdX}H})w-7dgW|9#=;@mB9=-94SL9s^xv*W+nBl&XTcLXiEIAm{=d^ zOWu+!I}zG|)pzNp1&S@|JDN4Qd5JJ;%84?Eluh&&rkomVEAd{(WptmOGn5Bgqb*1c z>%#Jq>VAm?rWY6~_S8EAas_S5HXF`XF>g}K3;|j(P4R-yYSuQ&7E>tUR=xgjKX7G| zcXmUA%8>1h(p}zXU^v!cm!pc{yGrh5(F#FY5X4@v2bRm2&Y29Zi8(bAJ*c1iMXtF> zwzn}9-U<7?W!7Vi(Z)TdgD;EcEmKJU9+?%mBG}Ocr80|MIpr4Fy47}P*qc>wr>TQ% z5xPgVXlMK6Y>ioV{KMetg5T}?p5k>-e-|&MWg*9Iob9IU`P8?`Nx76;8YNAJM zikPY8J7OH6giy$JF)Wa(#1gZ}x)9k1V?EFc9mnmb%sgs=bp|**_t5 zi9&PcwvTNCQ^W6Kjq2Q~J(x2Ew9cBO^TRav5UGyNj~7p26s!8x@W*bjDi!kti=A#Jx+w%2aD)0ZEn*P6o6x4M8Nk*9_GfAiwh{U2rE0kiT zVcjjzuu?)Ll2{XxJE_+kU8@nk={ph)Uo7wREesZk;{kI`&G<9o&(XAg=7e%pRzbu(N&Va4f=hD)wQ=+=U^foM#cey?#WV`M}1?V}OURP`AHfY3(8g`5O zM!H`2ZW&OfLlV5p>O|S$DxF(m#l58DZN2$dE&85}wo7%HCEYsIe8SV>xAZv3SfssY z=oc$RYsitNW`jkGHi~*dF&s9lm$BqxsMdR(Ja0lVR=T2M==6=#qsg!_Iq+=6X&`3B z&+ro57*D~=Zn?49H=`E>ms_l1s&=4l*Bk;~Xo|Ip7LU45nfjsF_{lcrmCI@1_tY;j z-;rFzK!VDa9f=w~Hn-nG3l3~B%-QA_s+sLg+Sad4(VAyPTU?|{Dvt8sK{kv?^TJx2)6M2Qslw zm(10VFcy%UN11Jnn!W3q{+NPEZXw7?B;0_EP+6I1qI-uR=?=v*Us-Wy!3mQd6)if( zu~{Zvsa9TT0m9$L*Xq}$Snmg4?#LTDZRg)&6yo6#y(cD5+aIuul|9_82r8XS<_t~e z2i3jKR_Pe0zsop&V^8dJ))}UE#6)O2=#MPX;NXLujlfJ&Z)pVhf70s_AGjuT{yk77 zsHyv$vL;a&ldZlDfH{A_PAaU`_xr)`DFt!Dqjx%o?}YXFhJ?l}*fRLB?SHXvr8ojUPwTJaVSe-VcCL2nU`s1(S3 z%2wP)pkv5o*A!;Bz+2=n6D`6{4ZV+E32lzj_rvH6YQvchs^B+)?e_f49 z>XrtmhnRk$Hg3+aB*?N7=a|w)APS>YGv?s{PmTKY%ek-d)%1`eX@HlV(qK*OPv?-7~j(+uYlo z@7wA%-!y_Asb+uIr0ipRbmF*r1P&$8WJB*}ph50w({xYmanod*0b!$*X}Tx&ylJ{; z_8@4oO&!yRoN2Pnfx_tg(7Pi(yvl-4^f#MPG}HASl)=t~ne-zQt%&_Y&@4vfnM=2C zH)!bmhCr$)X&SwXUQ->z!e!0QzCBrVep4VbI=?v(2EE6mw1uNmzwXHu(mw1a1JSR7 zz#-S#y(chv%f+lxHe+^g-%Fb(OQu+PwYks?P-8ujCYFEcW^B_^P0B_|ae95Oq>#19 z9Gd*|53?q5*4p|)nZRnbfg!|dn$|eZA7sw1M(d%nvtwcW>in<*Xe;j+ixHN9agQvo z4GCxo)`aOIvFJZ5(|4uS1`)#cE&EWG$!7anfhvi3;C)kK;|whnr7^9bE$~VnxFGfA z%Mz!)Z3p4ms|C>v{d-$1f^b%-;O{9>-<>x`mBL3F2X$7m6U$;wF~4h{e@F-hg()Iv zs~#!!f6fUG>+ctxX>3UbDp{Q+6z}N9{-!RyRZys11FeTNvNS0bCcvgd7RH4ZYMdv2 zgDXbBpFSfaCCOV@5Ci5yE-5Kd{N+GAJ%|$OLI${?tD@fRN-)+7m~<31c7@NoG7&=2 zvM#Y1n3X0BzU;M4K&!PR3tzie$p4)e4jF&7M#UG*jM6{m@;U;$&0a99DDI5|Q+Wa3im%%Pmw ze`JZbSTUE$Ww3Ax^$b7rvee`9y13(Zt0Vy=&QJ@f5;*FJMSvT8uzM>`OBoAHU-|Ut z_oIk<9nSRWIU2-UX_M^sCaXa_DktBuN~swvGr@NYIcXCZuNwb@aJ-UkP62K@TflkR zDlY}T^5njj+eW(P#<$JT>|7~&`eeU6;o?KkVGSu}XUzId#+p8}9L`mt(PcSt?)Bx2 z4Uo(Z)c$J@Oy26B)slN=+c@&0Ksnaj%h;R>cKKjkDBiLXna=>OpIjo3H`2RSQ_(K# zzdTs6$X7D4eF(B92Jh{H+^ebX)$8gb=`vw=AE`cmt*bURoCuUe#u!qYZdUcJ6sCyc zN9of1(6}(Hiy8WkE=+S}qg zd|Bgj0;tbRTq8jov`!cOeU@t==bZRx7GW^}14PXEPvX6YMi< z*Z&n`#5jZGD4!szW7#^(D#q0qCuvvUFWlJutJ-yrC-KCSrZqg?;(jR#Qp6ZT(M#^< zmS8=45lIVyz(JCTCtTk$vS5q{89}WsN54DwNd!^27wH_NX1&_JPQEncRm>rh)9$&` zjjJ&x;nWT5nosm#i}K%l$!?O>l-Z`SAbU$ZQ@UVo++bg@4SL87T8fO?h^4gHYmN#S zuzNa5UdctM+9Ztoah`GARtVgUSIB3%KHR2Sn=7-74o#=q&5^nc9~1f?K4b=>cxZHT zI4&HFGEf``aldfgKvLJFdhxcKs$C41a3{mcmW=V5wxlEKt-5CH`%@0{+8K&*ep^PG z^b_x*6K`)?lKb#)YC`c7bUo1sfw;DnVB81rptnCUp5E+p*xsS^$7Im5tj8QS<4@S~ zCrk4`0nQN-@!+2A14QYrHm)6xze_y@;n6Z&0vf=t>a~0GA1nfrdCGNC`L7N9QnhxF zW-k3&YyyJZO4VRIg4cw!tJgwqsNwq)z}`~LTedGD7t3F3d+ZR79iw4x_u-GoDgKc2 z3STDX;r&%#WKeajgV|kx?>C2hN;EIcaxO1_uCP+ZW2Kv%;YyWPE}iiVZI=w?+N&v- zRavywh17RI?3U;?=M~;$DJgf{X1?IUID&ycib6g6`g#GA%I2qDl`Emol%Pl2uNsd~ zE-i({0Tu(=Gqzo51+1=L@hLWexf(vw-^!B%!BiOFg|Y18Ai@c9Fr>^jDiABKW2ZU* zIAFFZfqNSLgW?V`QN#hv;DFBKGl~AKP-Z|drDX`O!tEWXCtZ z6A8VfES?uKBHB<+xi1kdV~M>ExLpJ#jp=As%53W=Pr4Lc0cXs)K867tq;iI~N)*^& zkL4l1M&##eR%_x{nt=!lBX@f0@1viax7HPLes@J=xKeS#mH4J%(+k|L)%;y{AAb_W z8{QPDW^+}DDrp*>v64S({ZwA|?~I(f<9$u+LX*-xrNs2JkX^!HtL(5`UTAmWI|ui} zeTCd;ecPpWs+=H7nX|XPvTqYj;aL{Nlx^8hQMB@_(3C+a8rsi>8^9&lIkd_r?aE$H z?ik#eQ_z2)Id4whozg|`GbI*VT(C%inj6{YUs2Ma2XqB+?as-XOPS@PEGTFODVfp= zjnirrZbX`n{}6ASwtT|ms;qNISS>KGx>FNdS4wT6t)BA($kC|vRL4IAs3TIsHV+tL z$2KFtWQmurmmT*IFq$#3g)H^sZtTS~c347@MbS&8x-z*RD#|UQ<`3nL<0@<<$3WLg z%GajqGd!Fte!nM8+goG?^@663+#TJOSrVt@47p?pN#cta9!AMltZZMSh|gBARfln< z@1_x^3f9tn8g~w&DqudBgsRnp)giEf8)IeR)f?90WE{$IJr>EC?u01N2v2e`zuz`~ zDsT0>{QSqTm~S;QuKU%oA>;n{Vex-U-+BLS*Y@9}@A6J2rcNT3PNv2#UlDx&p*2>q zwV(gW|E9a7px-oLIPQIB%7T_DbEXp`gc+Sh#FQ41MCaFSht`#{meSnoaiVb)D_Ax6 zPXumA;S3I?&XGNCEZqL(Io@!7-9Jvb{)9F$;g?~76;)2}vQ1+*cbBM~L17zM zkVZo?Zs|NuL#ymRja(Plu!8i~9rSOTMfFkf4IXg^L45 z+6$a3hIEw)qIXO(9$^h%VIr+))0)O~IC=(KqzFg}q zVtw=@Mimda>YWZy+Iun?)4hw)$HfHr+_zIOh-grZA(BaAw|RkZp(7ZBN_D~FRMmTH z7HOh7Lp*ydbqR+IlPAf>C>bF#Zk2yFAHEk64X1q;_11E3nSVl~PGbj1f`rU->Cz@$ z6{tu-Wq%v0L#!W#H2$6^hsJM_K^Yk zgfvHTuwg!#DTMw#AmSIx<>IzoYoO`2TvmbW+^4F<9f*{j?K4!Rb|?`i*md$o7AbTJjPcd|A7 zkC^Z(HEjoMb<7VntxKu#Vn?HiXq+^*Jd#KgO*^GOL@fYi>K}^BP;OYOvV@wF*4{y# zPDQF#S_C1X($bb~E$}IgbTWEUmJkZE1}~$a_Bx@vN$z+rqsjyB0256)lNpat6Q73* z&dyEt1k?Lv1bl!Q2q3r);)E#B>PMWoAk7c~&18frUpV** z7ah1Eq%5dDs5ErPwZzSH9i}AOFH&$DV0yFP$yaPgdk6l zX`PRx1%JgpC$7F)F0T!DGk1P3Hm{dl0GAq_7W9M63V>Bpdr~{8!K`~Q!58H)P?O7C z%?7x|qp}I!QBJ_ASUpKTMcPnnKnim>G*quFOP7At4>Xx-k{+x3yQkD<)v@H!*1vBE z-gTRtQFk<{HD>E!xj}Ifg_qT8qQ{m{-E={=eqG9nXuBafx8QrQDPXzLcYX!|S zof-J9ZGElJM6G&Ws608%eHfXfP4GcQIlpCqB0lDFl(1ko2=e)Kw<>)o(ec zUE1h{;YOM}N9~=fwyJB0kn8~YomxQ6&nK$tpFewZ0mpDYa6v!10T{48(3ZIBa6X{h zEH|{Bx%=xs^ib*Pce%Or*lu(?^LMUj$A^0>p0YK%?ROxa@&fR8M}GJPF1vKv8GtXt zzM=9nJ0QnkJ+(PJ!RWBx{HQ+nP(G=OJfsCpcq$4U1pL63HU?cheIqS)elN9sV35LI zh*8wa@yHlawm<&eAYYd0x`GM#N%2~d{My=PL%)PRGGt(Y#q`j5>6BYKSDDJ|Zm;N4 z$zdt!h8o5n7SOZCb<)n;X_Too-PzGA8z6jAxPH^?Ip0ON&Xx_^vBt-|c#>M`G?hqN zOwj*mtHqBzW#f)py7c$FYZ-gW>^iY1cAK`w*dE-oLF5;wDYJI|o-nSK23Qd-@;O}D z#F(3x9EEM*Dk5ToJOC1$+>NDxTefg>a;!|MNXL?F*j$}_N)l=2cewd%wOJM?5UOR# z`UsG%>X7SPn*ryW>s*=9f^xoa{K;tQ5ZfbjmC&OIaucrj4P5*w`9OJh0mB=A+P91(pe#(pfpm}F|;Q)d#5)gj>L)?P4Z-D)P;?@qzVf-1_!{b~Hv&4G47cOB9&YAb8-ZHl>Qd6Nj#3DxgqKF+_NKP=L$_b-yin zq#tH>LHMNuA5jxz3Tc}?k7$W2DCs@DpFcr3vx&q(j~M{+6Z1Y2Vgd!5#!s;BTt)kp zZAfb{4Cpzw!+XM-V!e~!Fad+cKEd4~!QM;ZE| zh23B^yl^?z7=SE0q+iSLctyQC;`AHG_aVNz1cK99ITWMCVfqoqjD=5*hI^bCYB`}l z`~Q9rv1xCEe&DO;A4s>Z^$%mpPZuM7^;>e?F_OBpFKnSNjGWT8Df);VXSr?n2KWB) zlBQjE=e>=Gi1E?f&PP)4Y^~)Rw&g$I_eq;^=RWx2ZS)F?w2?T8XYpiP_mgxv(S&i$ zh;hTnQO8IgC%i8*t3UjIZyo>l!tdV;Fr-~9lud2Ey2by(t*g8`qx>V{y*@)$ zNQyf#B(f?Hx=_}ZW>LacFb@GL7&X2bUM0k~UbclKqkUDy;H?kh$xY-OGJK!oH#06i z^EfQ@)5#rq7SJAOU+d?t%(Q~!;KJ1QxZynWJk7by>Fxh{J0kjR^CyfkoEIw(QYbv@xLP!V6jv3`uZ z4YAs|Z&0YoCLs}cG3i6I;K>xnn1(3{gBFa`j}-{B$iH~5OO$F_S6^tk5uS5}TBFNB z-4&0^5!y{+wOKM}Q>RFYM5n;Ix0CC+RvEp`QpFTrrcWovF~5R=yeHeXb%4LkJve?h z&CO)ThP42smRB|k-iWIn@10u98Xf{|JZPX8hzt4SU zR!=hUxGVq2j*#v-Q7c~TrG|nS0D!}a zN4gmK4p#;VPlVe?e6qxV+((GB6dOShr5Nzwzv*y9=^TXt*MW$imI<`by)LVC;yL$4 zUpigmxa_1Y_iQ)@x-@BQ?4y>GF1Vd15Y)cYi7Mk1^cqIblDHG;x{=2J!jr90 z_+?<#%V@0*@$th84Wu&~a-^4!OGnU}Bg3cL+Z4BsNIAMn&_kwo!?hB>u(vo52fcH= z6i4hxy|qJd6rQpMSCnGX4tS-c-eAA&0Y|7b!9Av9R^YA{daj1YyGaacDJ)%5_CZ8g z%pBtU0k7C{AWu;@6nrKR#^oPUOd|j!XVG0u@=@N$Xw9|8sFOr+q00was$N5!3Q1$ofTsc=NA;}v7xzqfZi!BlRsHxyHQc z1v~Z2E-~hq-bVdP;glu%-MQ8Qi}?wX)CUAxy|gP5u-wxAFG&5ymJH)yx$%D^Z2$qu0>Ntj5J>DlYPNnmi{x>FW2K z7aZe}rlot$IP20{mL(~*Rz`dZm^Au`mA11Cf?G@JF~9JMjDx4)b4-s&yw;!J)xOH)JX0XQ)HMgK zGj|#?&z7IzI{RvNWYO=?@dmhm4tGfG`Zn+30CqszQ7^-Dau<$#^yB{Kk%POj+r&A!wPyo<>Cphi+u=bM5klR9GLwriCuY z!IDlmnp)4=OMl8Vq7j--G=y+rbfXMGr9yej3E+&|LbIDN0Cd$~;79`nkf&*9uALld zFR~Asm#@9;dS8hy7M}@RQ2CJsR|;z%HhU&=Vb+rc71meRj7F=ghmdc*o25j~O164i z4&zW{=|Ar5^&+qh2_U8f@WA07iiF28WUyI^GI>No@nq1{5{qD17ta zee^fx|F-`X8IjUZ4=oT#0wfo`GERz~$EJu;twkVa5y>UTO;z_0+)Kzo6W<+u#Uq9a zb^~>P5y|xb{VB|8Sv`nJa0~W;i156gG4gbsdRVCBE&76a0c_DI31GO6WxgKE2nUzR zM>Rj;jy+R6`KOlTOn&8W(3h4Z_-khUKR?X>d%&8ClcAln+1IRU>LhFE@UI0+m%64i z>erolRXHY;fQak{t}<(a{1Z(@!U%DIE%w*XaBQln*-4g3m$2+?$kyEO*1f>iU(i?K z`9?{Bb5t<;J~s$Ypgw=`p9=k2I+)YsxU7_t%hEeCy{|d9SGoB=ftv{5?0Vb4(2eYA z&GHDsjBvz2kS?MJWC%jLBw-D5aA-Ia_i7Jyk_U2e@ZtyjIB~*pUvQ`OaUk|RI3h^! z;x_PQV}ZtwIPn=Hhl}I~4jd8WjwBH!4l3~SBS0DCTVN$lc7l42{2n+?#J&a&J+ut1 zWpXw83u{GT#&Gkb)%Q9<1F06vM4QFh*F_=CsOmS{5#OF*dp|jYH9FfCExHwL+C_>> zwyJzHsEt`;t+qz4T(es(E^G8CpG>-PH$TgEoAZ#nVkgHEGgaPGL`aOq?*T8_yl1&* zTW6{e5;d0#&Y@N*w6eL|{%fapFy(R5?ihcR%9s}y84c%jQIXI8z-?X;MII&l1xU2C zNhcV%2;btBa>EqLoHI7C0HjbHuaSt|^yr~zo*~9mnRKU$O=JhuTni2iFf6R_s^rBd zx`G?kxd~<&j${l%@uva;3`JxGLy=NB#eNk^V@3}s_}J+z@faFQnav4e5`(yMPT`|h zfTCuK6js8h86#(&{TTNPKCFWzw+oc~Cb_mq@c=>f)bq`>3ni>)EUk?Co%lOP!S@^|a%t8M@X6 zGu*ETw*lx&?WN9PtTTyYd`Hj-9+Y)v{%Y8<0ve_IM)$K1NsB_3IMqzVECbD{gLAA` zl_s#l4eeo5oSXVf=v*xn)P?kw2ldXWb*$1&vL!lNp54FG-SpZmyb;4bt9h0V7L~TD zB4}bUwff9f6GZ6RWbe{UsVk}$O@Wqo811CU!TsnS1%Yaflp4QDf9E1~o{tr)FMXVU z;;o%AMw0XyvR@Mv#6ax*&K4z96|2;9`b#!PXc{mPvJk{ZmI%f zfN_BhPAlNF0C}ICjTPe?4w6k1zVYg6e3#dOaYsR`fjC)3H@<=3iLww?wQ3y`NcH~g zu8FV+aGTZuo5ZRAhp>0x(lqLp1k?GZZQHhORywoNwr$&}v|VZ2wr$(?)Ym;d(|u>n zy3bFDb)ML9&fYuX@BG^PmOP><1!5~ZB~PFu?PNV|E${Aok1?WC1t!L2wvUqQAgKK0><(=fqd_3N&dfwl8r*#c#7)ln?q~;yh`fw8> zL(a^SV?i=fr5Rr)db|O4a8(iQA%va~z@3OaQh!>Il>;7F##;oYFpQrpkJ;2D3Ex#^ zO;|r$L*jvwQoT17Cxf(3pk#y{VxkD=6Cd%5w(z3PaBK9#DNWcAbF9Ts5s4tx~WHCtSW zc2i-{NjBPZqN9~q1AVpHKD$CqO5xyQyP>eE;c^U#DcaQVJNd)Pi{l0B36H%=vMCyT5+ z@P7%?#qJpeRUfA(;mN=6BzeBtVpfTZDuo3+w#6)ilRMsw4jg=lj^{d%@8(o4M#9CX zQLZYJIA=Yv8a&Ak*}v%xpQ%I#PIMk74Ki_bv#^L}&@lVaSTFX8w5e7_QXQET7(69ma))tAnSrUaq1ALZAc3*&4;uk>K5vj z?LXTY8e+Rv^}AYqLTZXq)QfNnwYM}QQi-%lW;c#4_)Di2c-t(l7vJ87I@=2$E^~XP z@yhvFa0~TB;ppcAb`se|DR)%4*aEhkEiqZn+@W+pboYR(4bG;C6f}rV;b-`QX+@N8 zf8K$up9q)RNHZNDI5 z$c}$dKv7-*3#puVcp?Z9nWQ8X>LJL*lD_qo=UjcPV>2qQzX;JXIBEo@1?vOa&583j z9|-0Fl^BCq?ktS1YFO37A4czQ%B2>=!oOK7npE7fdfR}n7XrEu#n$uqeWv^2CEbYv zMq$h<%gl(M_VsW-8(F}m_q1irqr3)>RbfUIbO+Q*KI5l?IOeAu#pHFyXcLN`xGpwH z8?#gHirQa$noS}^E%Q)hVH~N$Fv+Q_LAiq+;TMqqfHW!iIM@FV0<3>B;{RVl{P*pe z|2l{&^`DR=Q-l9Cr0fz`CojSTD^??8k;ixoK3R)M1R)*_CW(b8iI*rZwRB@@TrvX=V8ZhoNgY zQ2;g;n_*nBi+7MTc;RFY#Yw~5B<1$3UfRcu0fR=DWv_ivzs;-%^*GK{P#bMAOX^a(#B)|FvI;nF#E49F0TLfVEqT9|81O`^xsIY+5bJ%U92pnj3R{k zZ7LNS3@i+$4TL5p+s{lKMK~Hl{kMdg-h@`3-Z`||*d9I0Ir%=!y}r}&E>9JL4&fWf zFZt*~z6kLN2>;kirst(=<>txz=k5u|U$fG5F6IulzLnfSxZedTgf@~=DlM6j%wRpx zXfHHG6V7zNZ;H*lI#flZR@9tPxS0Y0Y-cH6_lZQWGC|2+r=?X2^5Tx&IP%onb+`B50ByoR-Z8NWqV)lSvG-dhF|sx?3wntfvb5*1g`^n)IeDZ};AW5G-!T zMD%1`!iXG>&uLRa(kw$hWEc9eHLd>KFdglh#vgke8T4@1YgCqncphIAt<_xhUq;1b z47rt|I37?49!1ZyUzsW7*-*sYB1r;l6`T7sdW$qy6zyvEKXJ4aW7qY30>*uwo6+G7 z67BGXtg^Y`1V-^agkAP&jVfA1U#T8#nq*FRYc)ke4jx%VxP%vQ&P9^)Df}Wda4mVM z;#!Q-g>-2o0~>__ZB6EXAf{SsqkW1XrqGoLsB}jN_rx@U4Bt^d@Q7svd^TGy0DT{2N*5LvtQzuuIGrT4wQ=(B)bG?bJV6!{)TVC zpQ6q&N>`mxzXh~2GTwn(jISW*CorC}?DR3e7@YrxJWYHCW+sTOyTLceJ+0MKVoHr@ zsfyW)OjLK!jnOPMncT&NE0T1?PtX0&nP-9|ABy>R&7k_1f${&(6aPJ#O8uh+ga5Q~ zWi6bXO>F;H6jDt5lr*RiVsOPl#?osL*qr)ol*sL=rVv0BaJXGuSENTCv*6g^o)(1fgyNqiL<2b zfTJ3H|L>^}EX_YJjuu-RtqzH##n5XGHNk5jJT=}|*!&tFOa z`16C{sa@0NxlrMnTiOjigus8GyOqxiUHwM}I{yb<{MS0f{@>DtsEMh8i?#Frrx2y6 zOep>13clpz{BIMCP|D^3gWWy}#W60hB z7x_*}rO{dl~S%*UUz*GUg+|POb*EAy5qRe)um_CB5bVC4X)jtE{oF%!03U#w!okJD~ zG46V`2z{=Ag>EERPPDG!+1#ef`r#9ga^l8B)hZ>1s`2b`kE-j_&_Bpdowl4}nVC&o z6V=c>)3fK5Hdw9_4KHsZ)mWRfR&VJa1&4!Pq)z8^Th50}*u~h_MFc5>og&y!QJRUn zEjce!weJ}RCJjnaWP?)A*vCqj$d7r z!7Bl#{4Bo_X2B!}iYgPm=JVH$jM?nB_B>|maimT)_SQV~wZ;X^_U>2I7<~~>(|cgr zlXg6VfPf=OHmy8{9hqau+-FsUC{xl56Ra)YpkH4RR|nSDj%7KC?+u5OWGW-G)zaB& z*WYWvysEiFWuVc8X*zGjGwYJa+-vBWWZM%M>&#V##)b{%hj@DMcCPH9;~Tj|Nz~h! zimxMSrZ~s?>B7N)>m`s$0Vt2fmRK$=f$IWPl8C~L59*w`Nh5@pdarIP)yEl@W6&0- zpu&<&uMloQ${u4or3|`22#7#c#HxgIXTZ(0%N@`r*iS2v4#DGJX;t`wa5O8Cj1tJZl%GL%#o`jwh_Og|q!<4dA zsjVnA9Wft@nD+X1xT^N5cD$7Kbw9t=g}*#y8((3#7E9TPTnm41gb#%)uHSQ2aGrfg zh`xcLp0e2lK`Qovqw8Rm&raOZ5k?>%F zG2F`&zkYl%?#YjDd!*Y_r0}3dL{mMmGUuQ_jt=6azd-`+fRhI~QDuiJ0D}mZ#Dl2sW-CaX0(m5Zs0pTCNSEp_5_eeJz=rgZ zI9s6R*!vtJwWyq7B@D-1V0p%@xnvMUsC>5m(bK6dfGo*xWZmSBQr7SUs)jf+5>CE2 zx0L!{Tkw5APrROVwl0LPhkep%{?~um`}}WxI@9x9SYt6EaXT}@*N7S)X_z%x$tn4{ zJduW07>r4r6etnWJs1d#o8|q8Hp|T?k)cARCE0~eIzo?CAQ(k`^U^t=4 zN!iW^^VkF^z%#3+W+`rp2}GBS*))uHZUV?yor}!S0HLu?PIy>i2f4v%(^+9DX@S#W zYCuB$*STd}^L#;hj<#5RQ<3&yas6`ky%t}u)_{bgHMdD z4ZC5(h%z#vyLpFFsCtrk!X<3>(CLu0Uf~H?YMxfJk4CW(`k0!qt|al^y&~aQa3{BJ zOzqaE$WBb+Fgyik{-pdu!%kgGgPhS*Z(ZitRM8T(vOAI2JMdIU`Z&s0MqvBu@E z03*{GbPJ*(ImI`R`T7?Or15z7J+NFcsR;o4%0ATqJKjO!R^{}kM4|j9oGR_C1fCet zS5w|Rtx3x;!9jA^Y#i6q3pAb9z|L6Sc0aS%`>PMxbBm=w%=9~t*|J$H9f|=xgAX-0 zRBW_AWVY74s7FHoB?DZ@{(uD4tjLaJQ&V1XM@+F|E3%|x4HsZKyBH6(>mk|NP@MHdEN)73t|2&eBu~TYQbS9W_8vn+w~-mN z1Ayc4&`0X4eQ@8E?yqhPfMM$>p0HzmJAx!hN~VvL6$1Xoeg4}W1!!lrLu_bJ7-uVZ zMO!cvo)lVNmNVyU)!>7I3oB4(1##NqW_>e{AWE`-#bcJxO(#))gKGhb%@l!5@Ng!K zOA9<0awjG_CQbN}XUw|v`;(CHd!RLBVbK=}YsSfDbnuCd(23IuJUwb!A>M+aR@gKv z8a2IX+iS2Wt4F34s&{A@Emm;&8Uy4&I69+svxzDp0zYal&8r0@w=- z0d_mz!sHArFc(!jn1>_k#0@NwfCGxDWzWo0c;HHUCWLU^0w)9ha#ZYibAx7(&51+L zMTF5Y30iIBF+t(majVEVTU>|kZ zc1H#yC$eWeN}KH}dV6F}1KiA_)2-?0(TK(9{#QtGve0KPaORxPwsxNI^H)U()KePhHvL6zA#8r=c|;pKtRo zQI^G=zt#N-`Cz``>#<#&>Uih8rT=i#_#Cu|#0*GUh>&eK>#^{Glh#wa3VNM5Mq3=9gyamk}&3j6sCa;B$|V z^$!J$RQAj*Y&B1WU`xfwC3Xsv!(fYhqnN#rlOgK^B%1XQV+!Sb&5cqjACefQ2gFIu z){`o!X(HSA*T`z7Kh{p#Tz2?5ur1` z3>~SAQqUp|L9K8qdMAJJ1j^uQm$kk5qV*LIw?8Aa%{Ytz*7#K8wmX&0L44Oyn33*^j4`x`@XEFjQ1geQt zAA`C|gu;4)nXP^ieO0uc#m{lKCun1*;y!C zMmOvJI`Q-?W&@qWoPt!axHbn~5WNFM91?5D1~!UQgc*YY7>%yw7bsf{7iN4E!r*Q- z#WyQVD$Jcib{e7N?8L4i84tb@Sln&Bwyq4!CN^{N( zFrZ!$Z$p-g)?GLhm{J+lV#2gk$-l(I$=KcL0HQMoZ8 z2j?DYKX|#W&P+f_%$=rW7mr(#eQJrUK&-z)TRNjug{%=RwawEL7BjGX(`b>kHgQQj z{raOwN$4YX`wo+i(1KBr$)o2(XYlN3yt+OR?SS%2&g>{9j4KK@)`SeE@5HN12eIV& z5QBQjE*(^$C3L0ms52T*fvMvQ4Qm&)yC`FQk)2Njm2sPQH*ulHt6!3bJUmG5yiIVb zb-yHQWE{4S-~w674S+i$ZUY_Zzfth@|yxylEya&s}>7WNQW32&iqxt_P9agI)b||Ip;`4KXABaIeVr zS1rG#A)h^2f`EG@EE}3i=%Ds}m54@cyq~=*m|O*jJIj$@yTNK@uOspfIyjY)_5fOR zksC57bt`u%VYqFK@Kit{rZ8pJjswup6ayoYGG_5l_+lJR>$MQ#BY zjW16m#P(}7^>zJ>pxhw`tPt7@$8Iro&e;&ITAdWWfYVSudvrHys`#DFuTSO(HppTd z!YILLJiD4iTe#`s!{o@15G8j<*uCQ9FBtV-#q*rZtZX?QQTqWXm~hm5HoatGXA9b( zz{zJ@{)|*np8|Sn%YS~03>z48SoR+>RVhwKQj08<>*x-mjz8hQYEtb~w8mV+u$GK^ z8~0Ypg_y!&D4^xf6AW@vW7jZBsn>A~s;iI%FQBK(_LluV5;Z5yu(aD-_|?V}q#$AP z+zD;TA6$ndm~t*nYoLT?j7K{BOEuFcsJ8^_-(Dl(n>^UrFIRKw@_rcQu5;m#JoUnu zG#MA}B5<~w;YFxCaSz=T#`3$j5Te3+@Z6A$CPsdkCVxx?)?(X%6@{uaXbh|->^e^{ zH{?52b+1c?*bKR0p?;n0&sbaor4x^N(X_>sCon_}_#dH|9awazrKIJ~Ih9cYq3B9o zy3mh$PjwEuz%h|#b59o)|J!-O!Wc44xN1;u0BX%Xf0==9OhjDh4B>StHdKvo!Ld22 zZrU)J#HKVWcg$U?C2vNZgz3O7#a^*gV(g4?5(!ufvfNv%q;RFhdaFM<127ls(8GR7 zp2sUsC{_jr!@+m)+V=-5^8tISlts17eqzO2m|b9+N)#Q|gEn2d1Z%MP#49+xxz;rY z>l|w4s{gJ&MK_cdT3|J$E!jE!Pj3(slCj#;3(;%a4?I&Wy9~;;=((Dewg9I&T`j?Se0@p)3dRIo}*DPyexSNQXMHOB;gI)|E=9>L!1FVpyBo?Wu z`dS4&BTGJ&5JmS6RR|tK4bMeJ#sO}{#`;3UG!JiwV5?Nd*!=x*AzlCR)F}u`TwzcT zGoTrU{N5A(Vi?e$W$&{*!5#dTx?PS+%XGGMV$_@GR)ZlR-UZGkh3c2wcizHJCqe>} zkG?7N$d+zzwAAtfAnbe;X=IdJo>6%ay^9EH)i_(JMkqMD#*lW-z1oS`9q^6*f-S?> zpS2~V>V z^roy`7So)huVz(rsT&r3^zjkAI%;>p7HEvEx`?{I_rU!3+fQ@5?1IhrSUf4UE=B+G z?-Tc)i7a_6P8gFqoiEjJq)$@t>Z&&;37=7}od!0ue9?vI-5g8n2$o)CAIEqr3o%r> zL@um-R!n>xn31rf5&`hYo(b4}%4P8I;3HC`TxX@~ENV^6U8qzyCF3KumfHft^R}C@bl4+x{zgoUaTa+)EaVu*{14;Ey@}rta0d0LYpH>PJW&_{ zB20y>__H{xu4+3!81l2a$7` zTz6d^`5_+U5$>!dZy;d-yu9F1SlUP8xzIuZ-Ze5K*4!p-b%k&9aXIv8{?d7us0ALE z02bfk^2Yv1rDLv9Q(E$5%-#N>BLIhSU6_=fDu>?;#leorKZaW!a^<~_1@i67F z>0z+TRjMxCnri)~Fk%?v-pzmtR3V@})4;g!AXY{>iqds6y@k>es9q1qn6m%8bxZtF zBbDW8k@+E%w0i zX`cd1f{f&dH83`jnfGUipc`?~2DUz;V3e|gsxgjUvN_md%&VVj>Ax?$8Y)#9 zEM9ljFm#)D<%RLK8aDU7d`fyG=j?l(F@X03v!B46w2agF6!xWN31|dKK+`@FK+*$CR zjSo0Z<7Ivj`!q#dP&tkamqraVApG(MoN|Pme=PldAV+M9IXen9#+mo7%S!$4{uVA6 zd6VG|2<(YCOgh{ODYiEg2pw3-g5p7b>$gnYr4!K~$L2oSzc?4@4OUJ`9e&#NPe^@G z`>M&uex`kKg{ba!UnVbwOr$Q9+eYJNo$DDC&X(uGwn&zS7^Q7-`oPLjV47*^O?G65 zZ0paBX)ZVg-8wc4gx39W8tsNaHOuJ*iG7F=@*badd4FZ&dZF6GzUCbXfU`P5$X>nP z6q_mz5uC+X`J;0#j_Gk-&(<4bt*!_R$$WOBOG5cp98^+)z*xJpU1z`*@5=eWYO-^e z4SP_=*pd=hjRiCy1}B|i+l-^yZU>N*xzC|}vPGNb8Gq+8^4U)}2l26JD)|E3|j58p7uE@=ChNx%q(d zilqG+kelNrfhwMIePC8iqQSr}wvfx+iGy#=(hBQ2%3X?hjZYr>n&|E>d9Zzj#1s6* z5GTSMO<5g2c;6(EX+#t`qP;xZs1*wnKEfc~iIY?5%o$R;=wz+!iJjeF;$M0JqfO6i z^r%OeG~$XW#D&#t#QQrCea@%R2YhHk!JhB&Q#aHFnc-L;R=tz-@13SQ7V`lXW{u7Q zbnvQ`0_gFgZd-jTi)S|6$b6Ujf*7s62OQ7-8B)!OB{-lPV!zna4ySKs{P*P~zwl+% zi3@vRV_QW-s{t=X%oWNTvpNlnm+#9Uq;LdKyyZ6^ z(e{jlxtzhT#gSh)Jo)?vpslvA#(WV%cjYFR>mRJQhsY!!k5T#xeP;P66;AvF2>PZc zGG2g8^6vh{R>Kd=WBrm{E4`o)wVn8JjNnweV?J8hx17~mVP&0HF4UK`J=X&sv)kA_5y_4WnR7Mub-_ZanhmZdo5Fffahe5mcX^6}2IU z9A5{dfiKG%NcWI+Nc~&6xsaJv-+!T2@$XxF{mEc{{8g<(K1y{*plkgcyvYMIo)rL| zuXPHCKklIa0#2rYHxEE4oon%MYx!V;vVe}n1q`eG@rX2t0k<4|x6FiGP&3ZpsMWjw z*2;7);&xqm$)|yp4_`sRI@LVnWsxMCF=hbZjxhUtuquW_T~xEeXjT{j-EU)~q~b;k z?6+x%-B1Ck*9XH$t8D=xr@aw)mt|{&+lI&hV$HrIn(zY@UGMn7dr~I-_;hIgKEfJ@ zN_NPh+`&9P${$|Wq#$apNr$Z1B-uZ7vf_bq z-i-Ee&-UE%?%*TUN`#!oaY+#BhkL~kEo7#JD;oHJ(1X-Fm@)z1#ldDo!Wv|E%OR2r zh7O#AWn+Kr5gd$qUD!y6;Wo^OJg_$hFNuz%HO8PU#_+^VoreN3xs2b8&?0+whESyQ zC)d()L#3njRS+#HV<1h1-F!wA*_~$$@%GR%tYSutglBSah2)eu&`X5F7H&;od~ARG zZl4g*;rg4u2GMQOG%)@&^grI?K)o=UsYUXl+5E-AUa+JO zTS4*inj=M`_7>zKzC%Dw43RLa87c~MufM=x5Ops@ov{n9<)$k_b`%I*wx2}+tKf_j zPK{yULf$B!ztaxEb-DkfpD`Z(=N4FC6>#3G+K)=)jvHqoRz_e^<-OI%Ug|6d6C6!9MkVlP%koEUFmFR;F2vq`5HMRzsigUdDDC^Lj-N`YP# z^O@K{MzC*w4a}V+ZwLjXOR9pQWN(EhP~N@flV`C{F0T^NTAK=TcxI}@^*on%49ki8{r52_A z7EAi<^XAG(f~i29gATyV63yf?YNA-b;OLH@yPNs~+(R;DM^~#16N@{K(D7~~^6`h} z|9X6n23UU2qd=|`hGygNI5X9+)KMcFB?g?iMvrV82;-ti1X4&E!IK#PbCnc;uymv~ zD|ObU)v;?DtK}NP5FV$xG4u`AXBd_9s%eQOFb-kI?2)5gltc?zSj*C)*BCx*rp8mf z3^;mP%Pc{(@0bmi7+*rOEWa7`^z6aZysnj8z~}Th{fro zwQd5uZT6?1^;3DPEr8?v2I18A=kZ>63t+ptbytXG?_{&w52_#YWop?-iWJLpDoLlqAvi=PF6XhE)$S2GaWCb43*6;202FLll4w22%?*_z+8VrO5 zs}~%LC>$JRw2Jc7}hb}6|sT`w)6Amrmwm!0=7;fnNFoQ4G&4vNYA}_ zPZLSq@uGO8&R6VvBEn-P5Sg ze8`vg6N&m`Zl#YExa6a=D%T?uRPW{Iz!$-w4gDy%o)pjm_pLNgntPGu{7Ev(-_-b;X+K$8a}A zqKhOf{%$Wk@EG|Om#4OOtXL&3B! zIr7^TQ?v-1aMT)cL}Wf-2tlm;8Pv5|*W=@TPn@pS5e#22Ik9h%=HQAt$(ZL0M|uAd z#I1o26gjEe&eWZwl7>y&UJi-UeP88fSDRP=F{DlSrqN5(f3Al(Fj}X%3W@3O5@)DG zsau(Xb1Ud#l3=Xa%xuA!;ku+_fEHDj5hy|Py0JRAyYHfb{vmjSoS+a+>f7uSVZ=(j z{5!~r6}qj_GG;$F;!i{(4QXd8ew}~|X123ym^1f?my{8`hXh;4oO5FEKz4932oGY+ zOl669U>up0jF=(Yh2iecxUhy~R5cmySlMEH{0LLfN^6Fljzf=`Z3>UR7mz+l=2!`9 z?0Y?cYfLZzWsP}-ax}aU_u-7YHhZWM9JSrO#r?x!61AsRf73`u-uZ!DU5b+0UL%0O z^YMWma|AdR;7RZ8M+AONTyjGq)Fk>O2By~=%?R-ONfKtU=<|bxZM5b59uahMHhuCF zG-wh12>X$3XVdB6`Z4mwFZI-WAt0H^O6C1RP*in6!(sep`SsCisy_2&5_b*%~N4)X^5uU8kBc5Xhvgyp#lOF^Z#$N^<#ME5y`f5_o8D3u; z!VSssOsDTp{O5*Ps7ZQ$$>1-oCcP=Md?FT@9q<1ZR>lKBWlq1yu9+CN1ab>c7fh;K?J zJO~`E_D}Hra9hDqRX24ddcLtiBMn*ze7HDD317Ijnp7ibmIb9;I1TozEFly>eXhOR zuYAFA^-UvApU71qrD;e?mRe+m?R$+RNn%Y$sPZOJ@%eAKc_EXzpcgw#JRA0U*_18r za|&1l*M>2k21;we;5X?P@)Mn{fX9n>REwnf@a*-yRZ2PcPJKpER!NU42sgmuIW9Ah zuroqg5W7a!$A%_s^ks^`KSU81BH=eJK26kQ}u<53# zHpQP!(GU7&S*uSk&6@Wm-1oJpw02YwLu8ea2F^_UxNmDa!s1J+4%+4PZT=YUbPzvme-6tq1Ehs z5+IV#pOydH!ATJB+{FFK&>x_fS}I3b4KEG)RCU7xr-R|VtJneF_@}Z2_$e?zKWQDo zlk-sx@W&#_Y;P83dF_3~&J8FA@ku2CcLj!1)}ezk+iL?Cx0%&S%X)_jGA!sB-c}YN zqHpgroZ+0va9+?!DUgec@dssgFxWH7{IdfxOlBgJWpjSRza+tU-@bz$1NU3>=i+nD z060%G>#LnXJ`nj{jHSW||H($U+nQ?Zi0^?)@Zv37ljr$}Zd83P+e#zN2mEcMJE2YK z&m!p6UYywj#<8>i^Qd#@{r=d4AWw;!t~%-ysQJkgyHj~gV8HX$lcic1tM6!!N#j-J zjTK6sj?ZvcQqk6b8@@Y)szHANuZBU`tvnWG@O&0h&EF|+vV%@?|8WrT+1Z+nDzW|%y zg7hX>EPGF$-kZDXD}j5%jObS-%&dZhTu7O9?7*CY5)D>U17C0NSc{htA-KO#XqAjP ziw$0^<~`R4_u|YzojG5|C<-LXZkn>$H&)%jdaq(P%kZiH*)LAl_V>qE32_}x*Hfpu zv0`Z@eaxMz&*olHAk05h7;#*v*1!Y$146@T@2>jp1MlhDZnNOftU1s;37isw0T%KB z1NV#QsKGXlzwe4OK#cVNs1zL=iR(|I@}Ri+ub^N)Om8NSrzZmsmsIv{NZZl*-;LFc zjPRG?2=+Dn=JF#L_Vw17nSB>Ju2FuHejzBS-;>)^JlvX zZj*a4bXU={J^MkDH}V-Lcs$RBX9X6H7FE+5G!qovLl%M-&L6>7mwoLo`wCZ@6*L_ag4Vr_V1Rp8?SlW*M>h@3FsLY6!p zudOEOGW9wSl3dmt-FWM_i?3~&Z$86CPIsv&)6gdd7hDH_=}q$U1C_`%fDZuW;PgIL z)igh4F!7*1;0xfos~)hU`W!x0IL0V|njTgvo!k1bV^r?iZzc(4>06Xv{Y|x;n&J0!>JHu4|DW3+uO;{xC+UutI8h z!gs$p9UN%tV|hIZc9|LAX>6~feaa?#gVFlwx{WqHnFCk!&e4Yj&2)oSI0pf3^;hxg zZ#mHM6LN<@Ylzsjx##F{LsddyHQ_Q%2li@dlUQn%y~AtJ#Gdi``wQuJz1dc6eLUjm zXL}|madEuDYUrh3#^4)U|O$3j_MN+6-UvZm;R>_S}!(SvSP0 z?J>=yP8z2Hg;$e&9Lqlif?sn*$ErEG?#-9^ZSs(i4bADwXOl{z(+Y-LEr6w!@un1T zAUXa-fK1^AI-)rOj(@N0**izewlGFa3XMCkU0BrAz1LfJ_pNHDO3GuOc<~Im2&o4w zZ+n3;Ci|qJZ5CJ`G!KkR$gL1#ktfY|K z9$f~K^i1#d#O3+%^b~UapqHy)heYwGCiYLtb`@GaN`_G zyPr9i*H!5rBsG5@MA-m}$G#1silr+b9X09Nr8>9lRIR>S$P(vbdQ+Sg(9&p|*Ez zAU8uwtZgTmpZi~7u?s{Y^L{h6T`5=|#mo#m|JBHLdGqkU63G<&`{qD+T{jVSN2&1y-J#^;@L|LwyR~^^*MPfz2m3_T35jI( zo$j4swI6BH8w9+Xj0YLPIqQM+yrI?8%!ESv@0>iv>5E-h?#^f!aWfZO1Aj{3JAOSs z)CJt9fl^GD#oGb>gfx+~?C@3v-9L9(WwsUk^mj~DW|^; z@yz%GS@13$&J8f^1(vBT4)h$7z=?wcLI zX;D|&6~3FvO$VWmB(%>qoUyv*=(5jWV0kM})*%HOFKrBNJTk1(4#z5w*2ieeXZ#Ikl5> z4sv-3>H!#R%9bmvY??x&7vb;(M>SW3sGd*zpyPi^?U}e(lifZ{tPr_-&YM2|xYKKQ zu4A&--9H0sThARA(A49;k0k5z&9UOaVC>vv0$QCMaR7WQl*nhi53s@IIp*exwn?GV zS3Or$0Y9#m1~FDejkYsSf~#-fsWx?;94ekpx0q#-Vj@Qg5t9>ZNZW+ocNq`MB-a~+ zywr}J72o%Eh&c+>t~#US;Cm_2UWzG1L8I+d%}KHmuWu;f61B`w7bG zyNRBGuY&6rAczr*+jmRtZup|l*VvNH{6h$-vGWx$I$v}ksnf;vF{g^@{*o7VRVN&= zTOl$B*WKdJN6qe~%wtvT*Hg~QMg`Sxi%E^lIH{bapAmuHat|DJ6qkiKbD zA)ZFlbhEuA%=Lf)M_=K-5>@Q4JAu76N@S>RFyhKi+* zlIH@zI0oiT9-z(Q8w=$I#(%KLan>hrj z9m++5{W6)J&UZsj@nuS6J@_ig@N9T&sa3*VCPMpkeq{iu8Eca&8Egz1ZHr=9%Cqz`h%w+bPlrT)?)XpC4(w%X6d-krXPv_08D)^M@&62pYxiU^z9gxH_(f0w0a&74|wR^H5nFHI{#kzsP6({ZnAL7@vFhl?E5kKBKq=|L7$0vxVAg0aEZyQRB5qyi)XpwYgF%&!LJT$Z(DXvsOWq0 zIio_2NP;I!g{`@!u-gE4ghRmN*v}2`e_}dH{l@~Vg4bg~r3}y3hXI>78OGU!Vn*>F zWnPZAsYM8j4O?%0FZ3NK=O(^7PFxbp;7`qy!u1MHJc9g>i^cOWQTd8DJ#kg7ViE9% z1GZA%_A0ZWZ;>4nro$h$L7zwW8`+*dz=S=D_4>584Ak*{IeAip;!9rRw^? zZ#^;|J54ZXc|w_i)=w0Lyp(C8&C5O0QK6xPp!HLYK?Sq%W%Ko!O@#QUiQ=GWH{G%j zAx`fOzF7h}!Xj4H1tkfZD6F*f%+c|5Re}8jIV+!*J%{-T`6E^Y}54rp&z00yZRV#n`O=!@Yc4M z;Kl2#D6v5tn?h%OG&$MK+(0)3D9-aTG!bB@pGv|JiQ{#NO zU}c?(p6&GR$byp7D{Vgw`5Mae@Y1^WgxMi10|; z@9z@0vZ1snXuf>nkmZBibt$^#tGuT@xeKU!0g5~q6}8%cn=#5VzK&&%OI92N%L}`o zZ>o+Dq(zJE-2A8C>j*ZE#`8qH_#Z-B)7y@g2aA+tEI+i%6-5BBr!4vafz2eCJYUm& z)SCew;n`!*<0<8ASVWfkz6n?r)(CJFzch=JQ`&!W8z7_^ctKUAjIA$AR!_ zT=Lm(EG>B=taRMe(f7RO-1do!$J)F=cwRc%t0|j4LJzzqEGzi*?5C6$N(deONdPAqfo`P`p2kFuxOpyM5TS2Q6c`Oc{SXEYX3~n z&>I%|GhT?QT3`a5iDcMTEWLBDMa5s>w&=f~eGXJr!!nzmYO1Pn7JH|DtECde@T>Y~ z4!nJNLR%f@HDyRu2~4R2ufsAxBh0!+2~jxtwKV-wU~wML!LCOKkbv7<3_qkNjF99j z2MvbE9KQ*WCoSART}=7RVhwmW{IqT%I_n-5R_}ju0kXILT*>rxnVJhp=nu}kDJZdRDxsotw$vQ5oNBc7=q1X}1pbCsiu*E#kL;_; zHl_6u0l~GWQBx4fudzk4)v;?g%W<9sIKzW|cY2etz}Yr&TAOaOZ$WWqdS%&u$4&z2 zoEJ^95L0E&4n1*n@Q~3%wHs4AQ=kq%3a#k({~K!hVs`e}E^XY>zwoF3XZ*IzyXTXa z*|hp8&e((HTp=(VQmM=;r0!1qK#AgqdkQayjfti#0KSERZ*XFp`XsoLyf(a8&Pdlf z#WBGB8X*nT-u%2KR_eIYXOj;T#z0xL6}T}@fLZc?0ZBl%zqGo1;P&2_(zCzRnc;S# z28;~uxCytf&DLIyx+)HOMTX@~?>_DXz5Ak93u?P~&PN81U3DUW*o}fbP$O=Zey{y@fjr zgZn?MJ|+PJJ89ZG`rD?#z+s{MPsUqGFvy+Udq%#38VriVhj*#%Oag<8nRM5mk*C6) z9>>S2OdDfhuyln)aEGul7;NzE_;BvG78q6@_p`-;p zBGjeqHY}ykWBE>!^gAmD^rW1l$ZXx_3q1#74U5a@8^N%NCSWMPp&fb#PM)~r>%t2? zJ*?aVn@y*nXKAu%)UV_W7;X%by43}yff4(R!>r!6A~4cB`Ydw(!+kKaJaymgC-pBd za$aqq5FR6i-mL!T)LSbQ&|7X2SIrSD1-M@JTH~2d0pt3PTZxBl&%xbZwYiplI$baxKV)ow;h-bj{rUA%XIWD= z82=DH)EiFm1WbersH|Tn$*ZH;^4#{B(D!PrFo45D z67F#_eseQVW`}z!v|-B6F0p{AYC@NP@N;jt7cQunYG$+urs)jP%b8#2;a=|47SwsE zgK2h6!EM>zonU(No(@GkRV|n{=N;fA<(34~soxJZr{u(;pUzu)^`_Di^z-cC&n+G#yBdayFNR=#TqJ_Zq0kb{uRFM%sZag{ z=0l~&vJJyOfcc7Y7TYC>POxBH{oXmHs{|J89n_t2tCnCv!^9;)_EromO!STi-i&<% zgWh#7x=+TKfJHjz_D^+p)xaWIM^3#z!w@V=xoEs!inPFBSDN~f5yq1+_{1rCMeZdH zSWHZ=(alF#fyK-Vneq^^T(A^4YyW-cGj*_JOK=!?7VQH=%HzwQ8@QKY$m@Ac_OU!K zuuN(Va(odJ1w+}FgR-YZ@4`_176Ylio-|livL7Dx=>;&LS@$B13RV@sl9*O z8^Vr1Ry%AKMGV1;Tsx*SJSrHhBvZ5K-uU)|mABW(O%rlG7ztayd%QCC1z6<`Ke4|5 zga$^kn5a}PAF>Cll7+;Ug62#Z>HNym6xIA3MyC3sjIS0ifz=}W`#7^(mtmCR+`Z*f zJhU*%6cO8&wD=H47Pju*$Xtj4Yv;-A`d_E1VKlJ9^gtcHWG06ioOy1^55ZK9&uI{koog3C3)w zPTwD;{tC7nQk-W58qJ1*9HcyV469^O`IzbhL26CN(KijJ|>jl;tg z+klT9j}+kHm*j4fGl}oPo}KwLLq)9^jI$;gXl4FXg>jikOTAYKl3*XItVPc2XAR?t zd9>!8Cs@Ef-*-{;&<`pY_ivn7?d8aV@y^(ZzfvRLz`lPUh*Rnmf&F8H%8*lIDlq<7 zo03=WY!=vm(VS*Xvh@N7O^(<)G1&^R|2~!0u##8-kE~AB4wsa_hex5tBh4>!4B=5; z!ojW6-8bP;CA9>jOVC4j)XDwYJ^kPA@Te_nuBDD92p+wx;8hkM7KaI{lwYY`RoB3g z%}bKGpz}IBdaex+!7m<(;_p6l6Ihsi)8t-k|h;oxLo1ZSOl4Pmk= z@EG)unZV@3Lnmr9+tt8nL;p(I^FPZl`RDr$-!PIvm|}#&3>G(In37F;Ah5D&15-Pn zL^f};?E+_`Dg~pzYO*jD^lpR4sP!5+7XV!x#j+GQ+Z1Z&lg=)|)FryzU;A30fb)IF z%WV|BkubG(Z^Y?pg(OV14jxwJQ2GOp>DTTjUuwyNU2==`Dr*MUV3)a#*kAMT6nN}Q z^`L*^-AQ;H($Qbxx%N*JBbAZB8`K56_Ah6D7gtk)#}`CSDjF78z^*>=3a-U%+u-pg znZuicwoQ1v#-H%cxZ@Y>dZo|gQ?SGWE>aX7zn0%dfs0~gjz!{jNpNvyZ(_AJVg;9g z{GUOBcjv*yTWWg=D@_+X$@=p|zK?$ko`hVvGTq842rfNFeFpZp>%k% z#rmnk>dzWH`P^Rq_J|-4OiSHZrXew#g=y{9Pipz4Z7{7B_C8l(CYP3-tt9KLD2xgo%e)UL5+<_VYWxwyTKc2%(O4UyX^%WMF zDHBY)Ui_yS+$uh4(48S2fSJ+ucU0xBj^Nh5`SwBEM|+rgZ|hUd*x&&(6JJN_t1eN) ztirLIN96YTfV-^to0E3yw*s?nF2`Rp>>7jFl$R%3k4o9Wtn~%Q*5lup zz`at!YOeAo5A6OlKmwk$=8^*gd%a+uH`a4}pUxBTWM$Lk$`Mut zPc16%zbCDhU_NT0o|!R559W6tl^qXoaf5k7>jA^+SU>Qr@OP+F`dtQ|*WKy@qQ2jO z`L-8tasy(-!E@=;{ANzMJj`#iODJTCi|z$}{O{-V}IUeG<;_Wxo+DG!+lWIwbLcSKrMo%9@UI zurM8SKKAhU5LoyUb4h_>D;gGl9w=~ViPZ(K51T1}e2*5vqTp#>TSEy7SagkP$lPm7 z0^WWhM)Sdj^su;JolEqq@&Q<^b-H0yb4wT&8|VP|k?#hd@85IO&Y6;cuhDbM+|slrcxF^gdWgq)1D=^K+Du(#o`h$4`jl7t zg}LBa@-`9wp>JN`+pIumC`qpf&)R1?$}dGVf$w9%vnq#}hTz$szAc@_}|y_ii|4`h3CVX{9hVNtik_tA=}Ec`-%UUDC;E6(^(K8wAue|L*^0$h;#jL zwv;!7Wy=a}HugqpSazHp9$vh&4+0L3bCTcWzYNRA1$_)^{+2>O?hD6(WpyS9Xr9lP zxt1gk%fm4bETe9?!1B*dld*$t4=Kw|4o8B17UjI|7}Kh6a!I>+y`+B7o3ilcMT zb;;`zuo99!GSNeu4S{>bWu_CqFu+Qj_+3=-M`u(=H-?&ELbmz8?U`DDF`7~#x8reuE)UoYwhB;efNtYl;)9bEbJGD^7cpAXje}FXPdmK~iaGQBldxxL>nmL>ZA4k-hhpQAW{}s8FahNGgh( zBxFT1g7>W07(->5B!ipO_W^6lgyfEL5clFK##IbAajgN_-75TI3(b`F~ z^TEVv%f?^4yd|^9A2GSAiet7*h|@0hkIvUmpCf;42gJRKT=>YJIQ6BHD=Q+1lPBBL z51HS~h*Px9mhjr{`NZjbZk$a*@&@wfTbOR!hb|rB)GOdV^fEOJ2&7wjl|_}3;%lU!4%S2 zZjk<6Z4EaNE*rEo#*0X2=Y5+c3wHaF&TnZo_3V05q>EocB>ho)FzH%SGHIOoWew?4 zmH$zy@8w6j4oV)g68@!6x>lu@H=hoVAg&1;!o_c1$tA8=-G)qU-%paRXL?qt9Bz%I ztJutVU{#O~=^Fgy%so<;NxEk)xw9#HT!eHBE?lT|n3Y3ZdlfDo>9frzZdR@l%{ek> zNVoa?te5M3`AD~MlxwO0&m`%-F!z8|8|usv^j2I+qH*+MS4 zBbju6K6k2GC0U;IaQE0P9EjaRdR8WWIF&CRO?u>cG=5a38j>Cf%en{hchiWw#o3+F ztCnSvo}k18i>V$H;vU2~bupnqiuB~Ed(YES)*(GdNKb3!;OuWoouqfs<(8EqDpjPHa^A@{UU&tF2bW|YSw|2LC&^gV(_WgyBS9us~zWP_CjPxcud%Dh^twVaRt*wj3f8F)#e=uk(TQ8E+lBCoNYZA}A9GzVW&OyZUQT7wbOKNH86D)f&I)De32K-4v6((unkP zzV5wRa9p1B%XbeZU)YsI`n7w8M_f(Xh}W(Zg{>yG!=&F^D7jton*!-~dHlq%Owf_^ zr#$7C`zoAF`X3!kVgGRTJ?a0V_woC_x)RdgVC255dr1oM<|r4lRSI26ycal3hF;;P zi1*A>MS~V!^oh61SwmlT>jT7F|9O*NbEhI1@DKQWa_@<^#5+RVPdezPCmG1@ez2$f zQ8)26TXwqd@b?JfU3Y{_^loe<@ouIHyjxn&lYu8)*T21JI6wxb{4be)3K=DXn-=&b zS>@OepWXLQE^e1jB7^3okJf39)RRH)X|?_H(+`os$mYVzLjM)SC$Bx#QKIi987$sj z(Y5tfBJnAiw=nR}lW^kmeZ(lSZFvImDLU6^)bZ;C8CvYQJzB?EmiUUOmmAjZZXv$f z>3m01o7%~cSwvm7))|WUhRk16`|adcGIS(O>e5Nq7sU4@?cyFf*h+j0PAvbW?-M|V zijsKlTuAOGL*1>)xpQw2GBn8M`P6=(mJIXkm-Fb^B|-ew>|B%l`j;p1+r`l&z*o;h zhK*8wFFlxlp9~+A-Rkhgem)uYmtVOgYW6qcciN`zW_`gCGEC13)f{*wM~179rI;?S zyGn+CZ{P5!*T#$tkBspAO%978BRt*4OM73xBYu+s)4O=<^NIhu#CZ=C_%4tUHIsFR z8c*w!kTqZud*=I584%Yr}zguSAu}sO=NiD&PJ9642c7>3c`W zZ!+3e{6 z&kFR(*nukoDbxD4WGv}GCRaw3D+xSTVJ%Q%TSmsR?;G6BS+b4k%dJ+Kxhfm4+l zZ9DQ^$T-){1EFX0bjdhx$Boq<6|2a&aNYZPk9YEtam_z|M`v;Jksw$3RH?Qv%PU#z(TGi9V z&V)=!Zs*?};9f+gbX5EK3VueC&_n*e1bFP($dv2YdSjs{>SW4qo^VTXUj>;;>4+=%h~v<#sBQsb}1M%9mMMWUA#|6G#0JKbaphi( z9VQndk@^Y8N@v4qT-k)eR}E0+Mi{d4t|RO2TWnRtj!20FB4yTyRGh+A)fLF98%9>s zCS<*_LgK?&l=)nT#19T6ek&pI#~+FA0&LaajUA4N;#4P`Q06aAwU51>VfD=tWm@%d zGgsbNeGBfO%%WjrEmcI;iYO#j*I;vDJ|s3-AhG2-%18`hb6HjFP~im1u)ZNnT^te3 zNJMnrVDmj2kYyB#%}rk+VTotaXA_CUp-(96EQ8J6QT_V7yO0&2jYvo?${e1JtQaTk zC$0`<61O68>NK*FM^QM<3Y(`_qD7^X*?mS~Cx0Z|d6DIvhr$6m$O`Geehw!f>xdW< z@eRmI@vVV%7i$bFG^-Fgp`j z^K6me!w@hafVMNRybzJqAt)n^8Z{s~ABn9WQCR9KBHNii9l{!*)R9nIgsh$Dp9ge` zkhLcPn;RcM!b}!f2j-!$Z7U*51s2nnTz`nx%?Q3YZxMjZk<7y|3C5ak0?Sr9V%@`nWs8PRF`7&223-C zUS(se56iICmy<~R#AINoJqnR-j9){8!PsgHbAX}0%sW)9VGiaxHfwlJ5EAp5=NDMR z{Fs~!3(i79=mfSBUV<{Bm>Umo+k!GO7-fbPwUDKPv0!*7hW=rlDU{iZlOHw_Mj4Az zL=GAu;lMn*!5VhMqa60ZOn5l30$Jf0n}%c9v7h*CBu?x?*4b`so`!y7I8y;-a(*Il zGYMG*n6wW+XhWp*93oG5B2kT-Ioxmq=kxjivOe-7>uWtCzhV&SU?I^vfjtiwAu-9^ z>t~IyVNx-|HG&AwLqzz(5LwE++|C+VH5Z9>uaLC~4Q)gmO?X5Gv&s=g4ir{-jmS>a zs1aR%Y-OO0gz0J&wnQZvv28?_6TU(`;(_62#P1;X6QY8`k^eQ1WkclnFGNm1N8~)_ zHY4fD$jbh2fj9n}{2fCSet=GRq*NS*p9&%Id?B)4a3Jw|3|Svhe@4FjM%M4INOXQg zR{vWhMlslpOfxTmvqm{yG1C~GgNgm<0!$r87o$HMUEacUIJ%|-i4BC&MrvehXyKx8u8zfBeP)4m1k+8dp!p=_+@x&-I>OYRGu%(DZZ$~8F42cuC zy`#xjkhoBTV_oh?;<_LT=j}k5dzccBKEhmU^hpy6SF<6~AdSdtM{NEv9a-PrVn40( zk?7Jw)&T0y=oprhV>8$pWQ<_aHO7rHW4tv;EX97tRv9C)o_RZhH744QgoHE-%V91t zMl~TzV-5DK?SnFVs!+yc1+pxCkg&ztVa!<=3C~Dm`F}+sObMGuV-y}sz;hovc@SCW zu$CFSv=yh3m4eN0%tY25j0Iy4J|aP*`x>h#MwwbHipQF8d&k}{Lg6n7i2On~IMxx0 zMBf<7jG~hnn`U04WsP$(?_#mW=c1X9^J0=bz7!`mzA6?8;e{w8hDq1BB*wwE*A+-D4tVBDzjNLfT;KOmA6f<&?q zvMyBN5Leuh$i-+io{#Zj{DCJDv=BD0Xhfto5{Z}SGsoX|;C#MbM&h>_%5l(d_1chA- zkmWlMI}E`&Peq{`PbJ{@sHsz@Q26{P_LKSF=-1GlPUTBss|Wb4VCpeOhp9^Z`ZQIK z$36AN9+BqHDDxA`?WvANlo`PMXKEa?lxa3}!qc(Du%A=- z)p7bfeh8Y*^hKHLt57B%!{~I8KN4ja+NP`CA@L#}iFYg{z6@jY-&kBvcRM0$7~R+O z6!Xq4>n|tsZYt|9k3Ay%ScLvv-iNGpSeyS9i$+39AB7cHBB9oegmxJc2AIA7HN$Vh ze-C0>_}5tw39k_xE9eahN1|`}8=s7(p7l|HVh@cxtgw^0QB0I48QEn7Y z*n%=idr;=IAF|G+AuFvMTcx)nlEsV2H3dX&9zrDlB=%ECV?RZm$SPfitS4I7>RB)n z&u^h{{Wm0DE<)n%E+jsNqwtseNc`x=4qG?i5FIus+=G8?WyZiqL`DS=nZ&>FGIIv= zbwzn5$6KbunX{K5i--B+3(7MWrX#_R`ZIIcMkH2xB5O@C5+ZEaTvP`;+?s+c$)CuQ zlR!i<0%epNk)|Kh4u^Y1XS0G`v96LPdgZ(Jt)B{^> zoxl#Ia1YtG;~xfMQ_4a@RSJn6cG5)bW>cr1YZJgq|E>HuWbi{hY7Uy*ow28mBvD1(32N}28FLqytrP^Nn;68#-W zj9f#RNhW$Kv(IF5er0yfHYDccA~D|;Wfn2-uPU=IVZxs>`wH}I>}!r7A)<#Yv1Qm? z92J0Fx&US5(calv{|T!Lp|BmfWbI8sVxKFr%<*v9t?ceOi72#X_E=7Ab*vSIPu3zUIUk9%WMpN8Vb9t2*eZ7q5_yWqD%^m=#fuT4 zIguzILZa$7%G7;8q^TbJd0URiry?BvTRyUW;lZ*0xr{{5B@`Y^MP%&19h+wU1g$a$ zJ5vuTbIf91{Z;1RVg6T0nS(b234v^6Ex(D#>buxVxC9B&DrAYjL_``Dl0&`=2^Km} z4hbt)|1lH}MH}RZltbdEDasrR z!G2Drqi`~Y363-j{T!K?$#CQ-AaTPEiTsn;;XTxFj)#~dag+(-5cnt9lsRfpB{*K( zLDuWvIK)R(QI4+$DDyJ`hiFI7#?dnai9sb49t%R5Y4j4D?9Bh3D09xnsdCO^o`P5A z&&rLz!OiDt#Q7SEk?!*^zM&MjgnEQt|>Q|=kcP>YaI!@u&zsfpPI=kD1kY+!+i z$zANnayAMdv_ZrH!yl&`DnF;U7a{@ZMLEN^A`z8@L~JkilW2g#ryn44egz_zqLH}L ziLC4Y{fWBUm@#q|qQ~YeW^y*AU>QN<13~#cwi0eb*2dp(NN39KPNVM<|W`Hy*WX z@Ds}L(}&ENv4;p{L&`~;U@f6sGCy%UsyGqK_W*}R{!?K>g?X;HyY<})Li;HwrT;#> zj?f3H+b7xY-Xqij7v(M$!3~58exp!5!z7H*PRH)1OI1`5%1P5p@#BySp?z{!SGE}j z5z2Yh%Boz=U_#q}+8flEaf(pkt9FcITVBaO zMQ9aYqQf~+KqzgYBW+hjHxtTjVdItp#kYhGn@&71U*4C{rsZ$47pU?PDqv73x~KFm zp;teD_2I+HSA_PuFXgiP{TD)qsuXbEpO{7H@b33~_N&wg9Tc4N_(M)6p&fMu?Ma;~ zp$=XX`I1_C16EqQz};oy4xv2hD&e~q3<#y0?)YYdmj|KOi`aw~&3Qm5gR5L`IR(TC z<&)=-AC&oo(4PEve(w$vB9!-Mfj67ipM~WZd_SEM>PBes8_k1nYkm>R_%NAU@pu%b zI?v{e+=54hwiz#P3;K8fmQyz4_Dhj6V8x}MxPC~JP$8FdA8%+}53AUA`Mcvu=+Gg9 zD|+4zQ$kxB@)W5V>?gFd{AnwFE;&LQ^D8A>k(nTr$8hjCIeLQ72kVYmA5pzUXy11& zCmvkmf__p{ekRAhB1%JUTrc)%{ef+XYR?emWrJ0GHr8TU>J!R8RH`e~Y#FpVAbo7f zq2q8myb(eiIscBJJA!li9WQKDRDx)1h$YPVP-LAkJ521*sp|Zs6j?%<@B1D6xejD} z)#@rf=ly_bG_hr$KOGLcx`|5lRMRB1TcF;J^a^)qrM2btc>!%go6T@(IB{hMq4!=~ zD`Wfi1nhiaGHslEh|t;!OLgDq=Mh>r-?BLJS0b=@-ruoTyGLjP(@Y*)yXAy7^exl1 za6TS{dj*PHe&-Wft}1=UWWX6%mx+ht)^+|c!w;2DwuV@Ns^?_VJGm7J z?LBvC%F37hgbumXQp=HcmC!Eg>#{!TO~F~*u`hl}Rsym5TGehI6GFQ$rtG%7w}7?J zyM0@CyA3p7Q*iqB@h>p3@a=Url4&rF6~{`fE0z%2f9AFiE|)*TQ97PG? z$xn4zviaw&pg&WGb~;^M0Ba9esd?wbWkP$DQvph|^?;Bv%RIRm6x(C-l{=}fzk#?> zdh}Tdtiq*ba&wvx4VF^*QC5a)5)L;#>r~GDgM=)V{b1?&Wpy zgpxBnG4tl4MXi@f*;snopa{Ipt$ZV;oN-wD())rOYs&~7 z$a}hGQHB`^w@Ta)3TVu=NP<|K- z`lhpkotCdV9Nd&eD6b1`b#IeE$7}|}L$;oJ33JxCy7~3>Hc;9-hMbGaK_SC@&M3b< zFG%P;iop&B`QC(HOLKafOI`y_Se!OiZt##$do{fDefPW|)c#YVEzR3XVC&X>Fi;8~ z1f6#?>CX`Eg5{*JN)Km55L#2CK(TJgI#AK5l)il#q2O{A=S!4|gQNCzE^CXt=|yN) zbtCUSIYUCri=^%CvwjB0EfUhgxv2;on$E0FEMH?BOw_qw~TChb@dqdO!Far zhdVW31=_*&@`7N(>MSMYb-i#pzNT#XAEM`h<#tcU4GR0g#AHiU=3A{LltsqN>(eJA z;BbZY3g(9u!mgU%4cT}|o=}o!-@jVb6%7+JwOD`B2sSDp==Yl4%fVHKA4^-=Yd#6v zn|k2RjGrkmgyjz@qv~il-1sQlx(V=^9`$Dy-PZ%J<({9Rm)`+S&+Xph@AfMxBxxhty%GKaW0|s^5UyJUqZqV)WVZ@rVozW zHcCm>*g*ue<$eEpJ#IJxi{2F13%;pfJ3Yl~3dX?VTrZ7mQ&P7Fl}PqK=X_}%IP*Pv zA*cS%frHy~Z;NkN0-@OE>W|3gc@WA`w=BMm1#vn2p+Sn*>xD4Y`wc?{I_SnL$eN?O5o?+o5B@C>W8))B&rwpZ^x< zY3m=v?Ffe=HurIYk3Xn!+{tCvwtj`PnCA5gxspRDGvQaU0a0L9-e10_cWOa&2scZy z*wuXzRv~HHzhOK0Og9hZuIQF*Lb6WnOh_*uXhhUgX<)NZgpv z$|ah-vAMROs{=nB=h?$%ZXCMQb;b;gT4H3*iR1J?v(mP5*enVOgYBDvz?>B@4UehN z@~Ijba7{(kDZ5LCVe%I(wtY*7WYXVvt!&V>^RQ%j?`Yi=B|=%9;L@L|braId0|KI- zD#68hd|%laQoI;cYvWjq(q7O*yL#b+Tvt93$~M|^SSJZWwslgZuBA>QBtF)n<9+jMh%Cg|bn!L)`_&`kT$dX-dv$m0Auw}cHxfLjjV zyOkAqUm6^2={May8$-_$tsY5qE!Yl6^0~V$ z3*fj-xq5h|AoEGfdv*c8B-dQXg2C*PmCN0ubMKSq08N(ociaGfDk*`6pOGP>O_! zuE;jf`My7uhrdDeEs%R%b`=9nF*oLB`G zR~)hGr?e{^%0u2QPHQj19=_OlvN_cU^jX=tUVJ?vv_nOdVx{=Ky$3PPqq zH;h~Y-@f!c4Rdz(FJ7=6V(zXP;ZJzDzrp^@;cv9s0Gc3E*Vn(=34HG!y_l5rTv)PE z-s7Y$bI5`APd4&U&T-=AdwpZ*JZeu*y$8PBv13F!^_LwH?94ye=dbOmr0OXl^zvBeY zt$^SXcImQG3+q0lD-YVoE_6U@|GV$Rc~ z;piLSkwzD8H*$p-7w*uP^7)o5bofBWeA}%~LT_LBQ~#DOcqAW(J&)bAq4xB!*Xqv5 zfDQLJaMo7eDF`NCD&rff4m%e7bgvavz6*lyBHrhuG7N^8trs%qJQ%ERn5^UFKJX;r zukROUd;!yQUSrn0dV~k`*+O^w!FRA67e3JzF>4Kwx#o0}e-w1yUu6Cs(;QHMfYBmPE}SxwGlk~rIfVb|tX?refr~x|-H@BM~nhuF;Xzitvhpv$S zxc%l*bTx#q6~LJ;x^p%JO`p^!C)IC>Lj2mTdD%7;GJIF7Pqxu&onWv-Z&&TO2uVd4 zSAO>F3)nQcy_=kXKK4Sw}H}nwOZ7_l!Qt%TzJirwO3sLDf}VXnFxW*>t$+= zyESy^`8MZ8@4;d4W2$>9Go&CV3GJ5gykBMn$=kNo27z|q-hC>qs%>6FbrYy?%t$BY zDbygjrKcl|R>S_pr#_w#IRJLLKFi{2urPQVzAJvAzr{d!RBO?K7q`JbU#ndE!sjVy z=8T6!?ysO;wtN07s_!UNz5#8|4(XdLA(Uz3D(=x+aNOSA*9vBgY$lZA+yyt^&xdNu zW3So`J(2xHsa1a5P$(O$$RxlNvGSl0*k^glKld|uey^)SY#sXw;Bbq> zm-vW7w(J%5Y*pVkSh7c%%D3z9rC?B(tQDU^pe!|@H)y{(19_BRflO?H_P-obkw^B_ zFGyf~4kjuFM?)dz;V>+6eZ33};UB!rZv?`zw~2Sv(S;Cv1Kqyo^0QrqK&H5VZL3%* zOkS?xc%Q&yuy?WgMwik`aPP{dGe0gn0^1wz$+0xw3zFmj=MSUZ|AKh)?mV&c5F%C8 za)x;A!DD-f-qcqKhYfemk?&}*{{T~6*==Yb2-f7LQUC3N?0krf&Oz}7C%~)>XIgzY zx)Ex|z2%luk1s=6;pElwS#~iffVJFxE@MikGp4U`^>yi$unC38k}8QtamS zUQoYZNeN9C&0&9@znW*U0_@#qRncj4yESl3`l@Z5gV}@@f4fv`|0t-jkL2L$eNy24 zLL$a2FLy#F6R;!f+NGah?^e&~-j_KWp!q^EXETFSFrU0_&-dSh8qMqMx$if=g9Gtf zn)u{pT?R}{OY7YBb7_QL9JBq;wMwv^KtG>%w(Ve6dq=k3Y&U^CAt*mdefABAJO1LE zUFGINapd8*X9s)ZLm=*6{kWkAEX6%KOK(JaM$xoZ0BHIj;VpOWjrlm zfq~1CdOiPTu<84>wz$G6+bkJ1vbO_E(U`mb$ue^}IGsXe$0On(_EYhvC3OsjFWA zp9f(+J}K{6mir+bD>W}Fngd4de~fZfm4f*0;pob)eHhYa)&AAHif4k7xV8LNGAB?k z`yE(!tE3uOeh*aC^Y~7|{&1dYv*H6yP&(7!lqC#i<--bT489Cym(wY|WqsQq76eYW zXD%KiV1sK7|_Az1Uz;+e+}yyE_K=Eap1{ zh5VwF@>QF}q34|@*B*32I5y2NC|4ZLgI4_FG1rIv|K%hdGhWC+fL_Z!>-^|BsGvh) z+}FRd1xFWF9Q5nH-tq4fQ~w5?;1!VnY?ba?sL1!vx;I4%DgS^>*sEP4<#5$Pu%`MYO+Pn) zt2{(!xxOoe%t8O=!D9mw5IBN0`mflpgo4i7vD@(W@_smO%|ANvo-bjgJEL;V93Xr5 z$#HaKX+T)FKSPHvGd2VNBl}x4`zIuU276D+cN##FV`G-}h0KL&-S8`0xB0;cNbpGi znaLrj?94J+w^>`4fK^7cl$l>U`>(XWq_kxRG`Dn)Tqf6P0>Q;kG3Hei#3t{6S)T(4 z_!du+dT--7h?QPk5iQ3SKy$xM5i2(hZGp+3T|2vf8Jw3+bVYl;5~z)rg7%KP*Vll~ zs|aj7Di22F;~T#$+^U=?b!6up-s&-f(B@Lf-#2|R{^t+xHZ|UboGq|2d$+{8EKq*s zbH1(ZP$1NsS9ETLFdDv)z9Hi+ z4e|Z4tS^5TWYl)A_xKCxQ7~3NMRUc2KKt&!WBY3RF%TA0+NKo&o?p4Q+7^hxeOW?3w#mi8YtY1Qa|bxP3N-1x6hk{{l(x@7zo zC!vovrhVUdA9DWVwwFY+;?)S1XuNh#t}BGUgbeo3XNzFN9?05-|*_GY^+b=BGfTGNr~kFkc$S* zN_&241E^nc$fFh4eW4VJ5-F*S%>gTjh(FB3Hw=d6ob#u{DR%{-Slx)Bpv9;Pu4bxKmi(D3US-EeS4GIP_K!9)6*&w4lB z5A%u1c)KJ(7_zU!fg%nH+V=>xvL~ObtRC#tYqei&{uWSmA8ReiWt#k;0MmQo?kGbv z5865KdVK(RlDGhLK#RYYwN)#6AjkGdRZmvD?FP!W@R9!m*-1hlxm>!MPdNehkm5LA z-vvo~u(-+MhUXB(oixs{@4pX4M10sa;nh#aK@$e+zRY_ECulR}8qxb|J=leg=BzUt zz&}UI`Pmqs0Befj2`UWFm=6o&(AjmN9=wG1ywo4d-JoPxQK_}m%(V;@prQSFPA3%3 z3A4DfTJAwU=6~STg3qnigj&z*Cn|0U`fMs!a@VyJLUy#vp&q#}PyWT+9SdUYVa~@c zH|h=S1$U9?{$X^ZCj^&>M-D5@WG{nH2x*p+n6npL<(Th_y|0ghAG`nerRn(;2%}AL z%|C1*zQ-Fp-}UD@#LAed@kj6Z;B=1OnmRtZPL0sfe-9LGU6llrm*2CpH5+!!EzIab zZ5CA7hkgE@v$1j}bmWZMf_Dv|8^ ze$c}^yE!U5Mj+L%7+PW80NWBP)P5jL41#a;jBBc2*FqqRpPJq%NnHTf^g7YhYca$@ z*9oWFe6~;}#l?s(dNU3Cqa#+G+_tI>!o;2{)=Hbelf;bg;92n&6v<$6ExUL=1TshM zZOZbO*kD_BaQ-%KtbifLCww?7p{z*C5_fSEsVCHd_~j43sX;a9vswSZfWE_hZE-1Hk3 z_}%-=;Vwwkj?PmWn`;PGVDWkDi`soqhy^EA9a6sX8NBFReV^hl7a)yK-mLv~4{S?f z5B)U1E)y0=OBUT8mHd}pZtBoty8@f=PKf5*`vF+<5{|Cos{>+E^r-7gM^lMDVGO2YYZKRDbZcBR-^#V}Q2&Ej^CHb?^ZHE;2WJOs;$tyfC9Gt(N5 zyQp~1t{NyJVh*4F9 ztBr@8*5ymCgX1+wlI^(d->g3Y3FndH;;+`{{QHdgb;n5V893$m)bsn}BS6{quK8GZ zssoxEE%|$1YVrh}h3j0gCjNXd^L&f-X=Q8S1ee80y2Nb)mm=C*E5rvSOcZ;FpyFAK%Zkbn|mL-3gwb{Vkn0sB?{KP?8oH1rC`f5GPC)P ztb?;iJnxfP(#ru$UVmEosyz%Et?8&g+X8kqW|vF1p+3}uQR~ika_~)(-h?`s zA;m9mI|doiW)X7w0EAj=r{fQ+T$A7^mArLtXTWB9u0F@RO}mkl_J%r#^Q{L3u(Q~< zscFyz2HkexLL>`%c6)#Gl7}C-!T6gCXT)TIlSyLx{$oZfB%JZX62HRhVS7ERW4iw8 ze}m<8FkO0;GJ_kHe!9N@1$utNQ1Qy59mX zdbqpLY5_!$819eHi(W%IXaDd;d)xq+IY0Lt;{`Wh>kP6zUstTqfd!5muXSRBk~7Kj z#8;VTnb2Xu>htnC5CRf8w}=X}K{DW$d8Nmp00wneH*!pE1t$}6@8XM#Y%EX!gERes z#jhbt>HqaH?l;(%^SgPX{HvOvQn+HzXOT4*bnMlgR$c-LdC)BOPnkVeVXEt^PMlc* zg>$&;VzaF$JYl7cc?xj~;6+WP_%Cb3K|+4CLo4Kuyb~y`57jGgP7GBB=3%R2|z@ zIKjj7Z^-`Ug$&JP=LUI0%lojLR~EW@zHrJ(_S(WhA>iV?j3xYX&F4Zt?hEU7L_+h( zoo&7;E%PAi&HQw2;g|D}L)Mf>-P-_aocLDr^3&%!aFlZtb@*Qufd6^A?PJzz2gsHO zSKb=13j(9|jIs{D3gxZgyS0xJlLDZh3ppNIY~T})uaUL%Is*xH zgt2-)7nU4>tUK;~!ebdL$hzb8GYmxLnLz{*7kzp-_n%R>ZVP`L4-<2XzhRj)3gu*+ ze&&J%1&GUzi!)b0n;0jw*qRjX!vhfz);TWUzOw_IUaad-ZSqZUJFaH->dm&Gt8syC z!l{j*3CFLN8ygFPqmDZE?eaScawOa9hxSc{Spc%dW>wEDs6CIV>F%OKfru$P7NGm% zIiaK<3Z%bl0X2@z5?75ZfryrPF@7+#1SS?I*Raw12ZYGQ(cY#hA+S-=&B^Ml)sO(k z&Qu)t***n!`o7^)LUu4r?0%F%yc|q5D8Qy#W&|?x=&?iG#h=+hZGyO6Zh9%euDX8I z8!FI;sfrJ|s{V!8WVg`gbB`|AMXdkUq`-S{UPpX3UL9Qyu}LN4`FO#yYS0${RV?{@ zQAmWc3_qSZ2WAyeN-}~2pdZ6vwWXqyA+SHK#v8&yAj^$+|6|j63i6-hyEI-M3xnb@ zvLe~oJrL@zn3B|$g~uRgJGz$hQCMUH1Wmt{FWv7zni0>Xoz;9V5uEwkaQnmCAhAE@ zeqKjE1$HCJ>ce;c)^^C^R=NqN9NG%XziaD>+sl^VpEeLXPgr`BGyeaJpwef)yL;6p z#0kr4l#M~&8ulzbYT`v$_9Gns|FKYMq2zb5M~lh`%e{9FBh$5ekach53}JZ>#4|E~ z=coB)=YJ$D|8C~D-=%{hO)e%u=7bg8%KU}#(w@N|ZrlYCgcbgcxr13c*puSVUY$%> zhdY?Rmrb+%c33ulY7JpUwK8|NDW3IL-;c7J5?0Ljk^lFs^wq9EGSu3Eu#Pq}cL%8X zhv)cxUe8BZac`O5kkf42RlRq+Y#^+J7tHM;nmwVakZOz}tmD<%|L=#I%`3O)nxYS3 zC6zHhAS|8c8kIXxu0vQSnl%`iC3$s6Gm|C>>*Tx9|0DDw>qSfDqoxS!)GOu&4ZT3? zniAjEEW$e7z`RAE^ha9sYG5{ue&+clX3qV}{&$!9zay-(75kYvFD!Z$d%AQzVI|Yd zZyl+bSKKqd>fI!)bH&Vi1xkO7E1a^@8wo4r?kZ+oe8zfxKeCGn>-^1DrWOD4XNz>% zJP0c_$BUWs$~NiiZ;S2|R$4mqD?xgRzMBJw=mo;MkiuNXq~^>#A#$U=nXoRNWG+L| zd^esdu8{goSeN3N-#^pK2i6)42G%FJp0dkK;q4qeuQKNMZM3$9_DazG1~jv zYoF!<322oQ&OD|>uY4Q*A_@W-D`%W}B!OC6bw9Es>K0*L^)bbsQ+IHACkp}6&0J}x zH%ZXZVr#Vs>zczg23a}EYa`DGI(F>`qb;=Pv!B+Broq0hn==n3Q7cYXy&Z1^8@&FO z(ZkYSwoaMxN=w4Z)%(LBRdc<{^@WrHdG5vZvnBDH*OU33gmpue`GGgRqJDW~(66_E zlrTSWES-99wPTsa48po8&Ahxs37uLcR+kE+-@NV3tYYT1kvC&Aw-VMZ5$35YivRxN zthH6KfMo1s5P_<7*+~a`3G4P!F0_>0Wuo4)ih!JCej`n7Tr_I6Z}b>p<;`KP_9$iA zKPhHXC zLmlm09N@>pPGNWcVw}F9AVuh%pGT1G^aymh0QiVRG8am zl#F0geF3uTnto%>xw(z$>PFu#AM7U;8AB%TH9F5J@0 zSkqA2iAi;1(8EGUW?j@~zx#Comox#%W`2iH^9NFY%dHmy@@*mR{EmCI>GXcWx+lo> zf0@!A#Zlf*^FYV$8TB%ARv66FcJKx}y?3IPL1u)nERER#nsBd{`H3|p(WTLIawAyf zePY7ws!VmB;_lUp0a0PDXHtS=f66?bssa+s{Fs~;T@yCz(=IDO?lbR!&|(>~zZVHZ z&-Z(oX91}7HE++!K9?e_2cnF(p%y&6(pmQxJmdqr$4o0lQ?|r&)L1 zwG08|qaTAvM0ZIBKME(TqD3^e;$l57n$!kl_bBdj+lEaNpWsZ3;+T7Ol!V^xP2-Q) z0C}pxATrz1gobVw0y2dwmG=J9c|s6;X0a@DO@@*-wfy|l8$3y|Cv$6_QcODdjk1G& zif^bgGD{*F?z-Py0LU*PW^~!H=Xr1U!{`rJGC%&OWO>0E01cb$07^f80tZFiN z{{@f$<~l7crN?VIQX&sX0mZbEbZGZ!t;qqT;~F!%+#-A1qq`tdm#k+Ve<=O-Yz3Fy z53ueMOXlqeYRiMfBceAUyC^xw{OX?C)c2D0rHKQOM&=e$Y4Zfv%~K^{-KDcfaP+$m zKBfO{1w@Sx_u1vHg{7JwAR%iRWSLhzn~Vn7a_K$hj)u}`=qdjgr(r<4nV&{e8*hC4 z`FI)hOp9=9ucMm+8Dul* z6|mH}Ls*ah^J91Z`LP;U>0?#qeKuOr;uY@$iEn@eGdCPd2ddZb&2IwRd0aRbSMhf@ z=dc;%NRK;DqK0d3iobCMPN$5Qxk*Y%eHyb2yaoA2*%s!FDT;sW&pys8>j2T}z!`?7 zj-Rlr1H_)6X{B0Y>b7Y~4Ioi+%zTtN-@UcI{uq#S<{c_(ck9xp)D`d>WsjKW4rtvX zBlGvxu!m*un4itlOM{O~)v7}rEE|Yp5T)dcS4`W^64sOXiOlE=H`d1`1)cyz^f>wi z^A6v8oh(3hGPf70)fea7xg5I$kb}&NH}u;3V?}}bl7NJxH`biYSukBF3`iPtTZh)$ zwxxnsdm$hXHZeP}1#GVd%=Y7g~){Cx`jlv{K$h;+c4D=~U7=kh@2 zbseQ4#~w9N2{^&>vj)uQTO&lhUbKN{E6-;xbkK4a9tyqV0!t~cW9~uIQi}vF`%c~l zq>ag=s98K*m#%k!9zJD%hco;c{&M<^4IrzS%e*wlZ^sL1$*`+W<(b#UXz7J5){++B zC7v2Hx57)mbU4>KF9lEX)RTG7f!6!(kx(Jw1jup5vr)SitIaxdw-S(RjJD9K4d(H) z7Z?Fj!8{2??H+M=Qws*Id-|1m4S=SEy>B`-Tn1!<@pZJ8(>rOQnnQ$Dv6y+sqqHwS zmQ79tbiQKSM`jf>^dnVD1R;y7&}FV-(P~nW-&4fkEGitB=OwB2b1SBN=0QGI5yjk> zp|;moJv?&(R$6gsl0i09jFoImfo!?rA;x97T0?2=yZwN?ab~n-XG$kq*&N7ZDtc2H z8JS0y()!1z3G3NhW)+mY!IArCYh(ZsW^S6$I+ohi7J~m|RGH^ZXkq?#uXDT*3!Ygp zl>(){cC%ZJ+bci<#F({j?|PMWa1VHiXQvr!qIRVS#k|re0pvDwFPoC`)g0m-oejwU zA0_?gCG2W`zWr?i$WH~-F|#*6vQy##`76%s50(Gk#C-|mNR`W&YmD@6tA%_Ey&zkz zlxAK9q<0#bT+@34vAa@_d61J5*B(utybQ6R(y5*qo$svEk>S6~0g1_BkX_vqQASx% zl~iUhZ%|OmBe_kJYjy(iXeYC-9Rib2WXvJ~dAoqwAI;yJTfA<-3@iVOu+slU*s8hA zlN!{{%v@iIU^u}lVdjDo#oF1HAk+tWU6nF(bCZ@1KXKpXJlJWK8FOKZl0NylIXj^O z5I-HJm1@#zkzMRN06D>2&!m(pDi8G-Tms|<^U55x;7GORS3%grs>)T&Zm6U@U!ME{ zw594Bb2E|JAztqNBI+(66U;u-tJmZ`_@fE-Rn1?-p!ySWG|U{ zRzggv)?#kr&{6{y$8*2x0%FH_b$X}VfV@a5vp)+3c|Y_o*aAqy3*6Ovn>RNatp=oh16o|Ht8%VMI$=F$XI>?xHCiVW zW1QvzvVwVR?`2*&pmYX}3;k3eo<4Uu&mhVq z=d!dtjQ;!x^CSYT8x}6JUKi@7=b20vN9{<7Idwgb8<0mbxT}#IA-Nl%@_qis3fFaU z>lLYK(7NY6%w1qg)h|`@B_H^on%T^)I$C#$y`R0eJ|JtEYp|5wk9!A~%0k{!qr_ZN zresC9>BcnBpPGGNQJ+5*ND8KcE!TK5Z*|xbWHXn+ z>CI;ARrb1W2IMjGk_N3(+*KHKArFub=zsJgz3Hsw;E`$uo})(14F7fKLOEg8@-R